From ce207837cf563678eda64ee822af0372581b3ffd Mon Sep 17 00:00:00 2001 From: Silvan Date: Tue, 2 Sep 2025 09:53:52 +0200 Subject: [PATCH 001/812] rc.sensors: add iis2mdc mag to list of probed for sensors Signed-off-by: Silvan --- ROMFS/px4fmu_common/init.d/rc.sensors | 1 + 1 file changed, 1 insertion(+) diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index b88a0d334e..759acb3b51 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -237,6 +237,7 @@ then qmc5883p -X -q start rm3100 -X -q start bmm350 -X -q start + iis2mdc -X -q start # start last (wait for possible icm20948 passthrough mode) ak09916 -X -q start From 9015001b420267f71dd3914a90f984947366c165 Mon Sep 17 00:00:00 2001 From: Alexander Lerach Date: Tue, 2 Sep 2025 20:02:15 +0200 Subject: [PATCH 002/812] uavcan: fix driver init after stop/start (#25511) --- .../uavcan_drivers/stm32h7/driver/src/uc_stm32h7_can.cpp | 4 ++-- src/drivers/uavcannode/UavcanNode.cpp | 6 ++++++ 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/src/drivers/uavcan/uavcan_drivers/stm32h7/driver/src/uc_stm32h7_can.cpp b/src/drivers/uavcan/uavcan_drivers/stm32h7/driver/src/uc_stm32h7_can.cpp index baddaa5997..2a8ff73fc9 100644 --- a/src/drivers/uavcan/uavcan_drivers/stm32h7/driver/src/uc_stm32h7_can.cpp +++ b/src/drivers/uavcan/uavcan_drivers/stm32h7/driver/src/uc_stm32h7_can.cpp @@ -644,7 +644,7 @@ uavcan::int16_t CanIface::configureFilters(const uavcan::CanFilterConfig *filter bool CanIface::waitCCCRBitStateChange(uint32_t mask, bool target_state) { -#if UAVCAN_STM32_NUTTX +#if UAVCAN_STM32H7_NUTTX const unsigned Timeout = 1000; #else const unsigned Timeout = 2000000; @@ -657,7 +657,7 @@ bool CanIface::waitCCCRBitStateChange(uint32_t mask, bool target_state) return true; } -#if UAVCAN_STM32_NUTTX +#if UAVCAN_STM32H7_NUTTX ::usleep(1000); #endif } diff --git a/src/drivers/uavcannode/UavcanNode.cpp b/src/drivers/uavcannode/UavcanNode.cpp index a79485dbf6..505bf4272c 100644 --- a/src/drivers/uavcannode/UavcanNode.cpp +++ b/src/drivers/uavcannode/UavcanNode.cpp @@ -505,12 +505,16 @@ void UavcanNode::Run() if (can_init_res < 0) { PX4_ERR("CAN driver init failed %i", can_init_res); + ScheduleClear(); + return; } int rv = _node.start(); if (rv < 0) { PX4_ERR("Failed to start the node"); + ScheduleClear(); + return; } // If the node_id was not supplied by the bootloader do Dynamic Node ID allocation @@ -528,6 +532,8 @@ void UavcanNode::Run() if (client_start_res < 0) { PX4_ERR("Failed to start the dynamic node ID client"); + ScheduleClear(); + return; } } } From 271cb4959714145bf59acb4e3404097045d55067 Mon Sep 17 00:00:00 2001 From: Pedro Roque Date: Tue, 2 Sep 2025 16:27:26 -0700 Subject: [PATCH 003/812] feat: airframe documentation for spacecraft (#25294) --- .../init.d-posix/airframes/70000_gz_atmos | 17 +- .../init.d/airframes/70000_atmos | 10 + Tools/px4airframes/srcparser.py | 3 +- docs/assets/airframes/types/FreeFlyer.svg | 197 ++++++++++++++++++ 4 files changed, 223 insertions(+), 4 deletions(-) create mode 100644 docs/assets/airframes/types/FreeFlyer.svg diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/70000_gz_atmos b/ROMFS/px4fmu_common/init.d-posix/airframes/70000_gz_atmos index c17a92a305..c539586ae5 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/70000_gz_atmos +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/70000_gz_atmos @@ -1,10 +1,21 @@ #!/bin/sh # -# @name 3DoF Spacecraft Model +# @name KTH-ATMOS # -# @type 2D Freeflyer with 8 thrusters - Planar motion +# @type Free-Flyer +# @class Spacecraft # -# @maintainer Pedro Roque +# @output Motor1 back left thruster, +x thrust +# @output Motor2 front left thruster, -x thrust +# @output Motor3 back right thruster, +x thrust +# @output Motor4 front right thruster, -x thrust +# @output Motor5 front left thruster, +y thrust +# @output Motor6 front right thruster, -y thrust +# @output Motor7 back left thruster, +y thrust +# @output Motor8 back right thruster, -y thrust +# +# @maintainer discower-io +# @url https://atmos.discower.io # . ${R}etc/init.d/rc.sc_defaults diff --git a/ROMFS/px4fmu_common/init.d/airframes/70000_atmos b/ROMFS/px4fmu_common/init.d/airframes/70000_atmos index 0a7e809ad1..37b676cef1 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/70000_atmos +++ b/ROMFS/px4fmu_common/init.d/airframes/70000_atmos @@ -5,7 +5,17 @@ # @type Free-Flyer # @class Spacecraft # +# @output Motor1 back left thruster, +x thrust +# @output Motor2 front left thruster, -x thrust +# @output Motor3 back right thruster, +x thrust +# @output Motor4 front right thruster, -x thrust +# @output Motor5 front left thruster, +y thrust +# @output Motor6 front right thruster, -y thrust +# @output Motor7 back left thruster, +y thrust +# @output Motor8 back right thruster, -y thrust +# # @maintainer DISCOWER +# @url https://atmos.discower.io # . ${R}etc/init.d/rc.sc_defaults diff --git a/Tools/px4airframes/srcparser.py b/Tools/px4airframes/srcparser.py index 56c3ce52be..dc60cfa7fe 100644 --- a/Tools/px4airframes/srcparser.py +++ b/Tools/px4airframes/srcparser.py @@ -14,7 +14,6 @@ class AirframeGroup(object): self.af_class = af_class self.airframes = [] - def AddAirframe(self, airframe): """ Add airframe to the airframe group @@ -107,6 +106,8 @@ class AirframeGroup(object): return "Balloon" elif (self.type == "Vectored 6 DOF UUV"): return "Vectored6DofUUV" + elif self.type == "Free-Flyer": + return "FreeFlyer" return "AirframeUnknown" def GetAirframes(self): diff --git a/docs/assets/airframes/types/FreeFlyer.svg b/docs/assets/airframes/types/FreeFlyer.svg new file mode 100644 index 0000000000..aba991c424 --- /dev/null +++ b/docs/assets/airframes/types/FreeFlyer.svg @@ -0,0 +1,197 @@ + + + +image/svg+xmlQuadRotorXQuadRotorX + 12345678 From 944b3e763ae2a22f5449280ed4767b049c029239 Mon Sep 17 00:00:00 2001 From: Pedro Roque Date: Tue, 2 Sep 2025 17:07:55 -0700 Subject: [PATCH 004/812] doc: Change email for Pedro Roque (#25514) --- MAINTAINERS.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/MAINTAINERS.md b/MAINTAINERS.md index 5359184ffd..e1fcc89b5f 100644 --- a/MAINTAINERS.md +++ b/MAINTAINERS.md @@ -19,7 +19,7 @@ See [the documentation on Maintainers](https://docs.px4.io/main/en/contribute/ma | Matthias Grob | Multirotor | [@MaEtUgR](https://github.com/MaEtUgR) | maetugr | | Silvan Fuhrer | Fixed-Wing / VTOL | [@sfuhrer](https://github.com/sfuhrer) | sfuhrer | | Christian Friedrich | Rover | [@chfriedrich98](https://github.com/chfriedrich98) | christian982564 | -| Pedro Roque | Spacecraft | [@Pedro-Roque](https://github.com/Pedro-Roque) | .pedroroque | +| Pedro Roque | Spacecraft | [@Pedro-Roque](https://github.com/Pedro-Roque) | .pedroroque | | Jacob Dahl | Simulation | [@dakejahl](https://github.com/dakejahl) | dakejahl | From e6f60ef4037955f055d256538ee8e7ba505dad1f Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Thu, 4 Sep 2025 19:28:37 +0200 Subject: [PATCH 005/812] Sensors: remove some distance sensors from COMMON_DISTANCE_SENSOR again (#25522) * distance sensors common: remove DISTANCE_SENSOR_TERARANGER Signed-off-by: Silvan Fuhrer * distance sensors common: remove DISTANCE_SENSOR_CM8JL65 Signed-off-by: Silvan Fuhrer --------- Signed-off-by: Silvan Fuhrer --- src/drivers/distance_sensor/Kconfig | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/drivers/distance_sensor/Kconfig b/src/drivers/distance_sensor/Kconfig index 25adedcd89..65af4614df 100644 --- a/src/drivers/distance_sensor/Kconfig +++ b/src/drivers/distance_sensor/Kconfig @@ -2,11 +2,9 @@ menu "Distance sensors" menuconfig COMMON_DISTANCE_SENSOR bool "Common distance sensor's" default n - select DRIVERS_DISTANCE_SENSOR_CM8JL65 select DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_I2C select DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_SERIAL select DRIVERS_DISTANCE_SENSOR_LL40LS - select DRIVERS_DISTANCE_SENSOR_TERARANGER select DRIVERS_DISTANCE_SENSOR_TF02PRO select DRIVERS_DISTANCE_SENSOR_TFMINI select DRIVERS_DISTANCE_SENSOR_ULANDING_RADAR From fc8e2021e7eda3ab990ad35689b3799408c82932 Mon Sep 17 00:00:00 2001 From: fbaklanov <143315024+fbaklanov@users.noreply.github.com> Date: Thu, 4 Sep 2025 19:31:36 +0200 Subject: [PATCH 006/812] A driver for EULER-NAV Baro-Inertial AHRS (#24534) * Create a dummy BAHRS driver * Resolve compilation * Switch back to cpp, fix compilation * Create module.yaml * Implement required module APIs and open serial port * Revise info and error messages * Poll serial port * Push received bytes into the ring buffer * Process data buffer (1) * Process data buffer (2) * Process data buffer (3) * Process data buffer (4) * Process data buffer (5) * Process data buffer (6) * Implement and use initialize() and deinitialize() methods * Implement print_usage() and print_status() * Collect all config constants in a class * Put info about next found message into a class * Print CRC failure count * Remove unneeded print * Add comments * Disable EKF2, advertise vehicle attitude * Decode and publish BAHRS signals (1) * Run the driver as an additional source of sensor signals * Add tiny noise to baro-inertial pressure signal * Fix the sensor ID * Add copyrights * Fix formatting * Remove redundant newline character * Fix long parameter name * Fix findings (1) * Fix finding (2) * Fix formatting * Fix the timeout value * Remove aliases * Fix copyright * Fix indent * Comply with naming convention * Rework comparison to false * Reduce nesting (1) * Reduce nesting (2) * Reduce nesting (3) * Fix BAHRS sensor ID --- src/drivers/drv_sensor.h | 1 + src/drivers/ins/Kconfig | 1 + src/drivers/ins/eulernav_bahrs/CMakeLists.txt | 44 ++ src/drivers/ins/eulernav_bahrs/Kconfig | 5 + .../eulernav_bahrs/bahrs/CSerialProtocol.h | 371 +++++++++++++ .../eulernav_bahrs/eulernav_bahrs_main.cpp | 48 ++ .../ins/eulernav_bahrs/eulernav_driver.cpp | 514 ++++++++++++++++++ .../ins/eulernav_bahrs/eulernav_driver.h | 174 ++++++ src/drivers/ins/eulernav_bahrs/module.yaml | 7 + 9 files changed, 1165 insertions(+) create mode 100644 src/drivers/ins/eulernav_bahrs/CMakeLists.txt create mode 100644 src/drivers/ins/eulernav_bahrs/Kconfig create mode 100644 src/drivers/ins/eulernav_bahrs/bahrs/CSerialProtocol.h create mode 100644 src/drivers/ins/eulernav_bahrs/eulernav_bahrs_main.cpp create mode 100644 src/drivers/ins/eulernav_bahrs/eulernav_driver.cpp create mode 100644 src/drivers/ins/eulernav_bahrs/eulernav_driver.h create mode 100644 src/drivers/ins/eulernav_bahrs/module.yaml diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h index 2d943397ea..32eadbb067 100644 --- a/src/drivers/drv_sensor.h +++ b/src/drivers/drv_sensor.h @@ -254,6 +254,7 @@ #define DRV_INS_DEVTYPE_ILABS 0xE9 #define DRV_INS_DEVTYPE_MICROSTRAIN 0xEA +#define DRV_INS_DEVTYPE_BAHRS 0xEB #define DRV_DEVTYPE_UNUSED 0xff diff --git a/src/drivers/ins/Kconfig b/src/drivers/ins/Kconfig index e5f5f6324a..70db3d9fcb 100644 --- a/src/drivers/ins/Kconfig +++ b/src/drivers/ins/Kconfig @@ -5,6 +5,7 @@ menu "Inertial Navigation Systems (INS)" select DRIVERS_INS_VECTORNAV select DRIVERS_INS_ILABS select DRIVERS_INS_MICROSTRAIN + select DRIVERS_INS_EULERNAV_BAHRS ---help--- Enable default set of INS sensors rsource "*/Kconfig" diff --git a/src/drivers/ins/eulernav_bahrs/CMakeLists.txt b/src/drivers/ins/eulernav_bahrs/CMakeLists.txt new file mode 100644 index 0000000000..8d40252de1 --- /dev/null +++ b/src/drivers/ins/eulernav_bahrs/CMakeLists.txt @@ -0,0 +1,44 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +px4_add_module( + MODULE drivers__ins__eulerav_bahrs + MAIN eulernav_bahrs + INCLUDES + bahrs + SRCS + eulernav_bahrs_main.cpp + eulernav_driver.cpp + eulernav_driver.h + DEPENDS + ringbuffer + ) diff --git a/src/drivers/ins/eulernav_bahrs/Kconfig b/src/drivers/ins/eulernav_bahrs/Kconfig new file mode 100644 index 0000000000..80c32787dd --- /dev/null +++ b/src/drivers/ins/eulernav_bahrs/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_INS_EULERNAV_BAHRS + bool "eulernav_bahrs" + default n + ---help--- + Enable support for EULER-NAV Baro-Inertial AHRS diff --git a/src/drivers/ins/eulernav_bahrs/bahrs/CSerialProtocol.h b/src/drivers/ins/eulernav_bahrs/bahrs/CSerialProtocol.h new file mode 100644 index 0000000000..8814f2a5fc --- /dev/null +++ b/src/drivers/ins/eulernav_bahrs/bahrs/CSerialProtocol.h @@ -0,0 +1,371 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * The header is a modified version of a header from this repo: + * https://github.com/euler-nav/bahrs-oss + * + * Copyright 2023 AMS Advanced Air Mobility Sensors UG + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, this + * list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS “AS IS” AND + * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED.IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#pragma once + +#include + +#define PROTOCOL_WORD_LEN (4) +#define PADDING_SIZE(SPayloadType) (PROTOCOL_WORD_LEN - ((sizeof(SMessageHeader) + sizeof(SPayloadType)) % PROTOCOL_WORD_LEN)) + +#define BIT_VALID_HEIGHT (0x01) +#define BIT_VALID_VELOCITY_DOWN (0x02) +#define BIT_VALID_ROLL (0x04) +#define BIT_VALID_PITCH (0x08) +#define BIT_VALID_MAGNETIC_HEADING (0x10) +#define BIT_VALID_SPECIFIC_FORCE_X (0x01) +#define BIT_VALID_SPECIFIC_FORCE_Y (0x02) +#define BIT_VALID_SPECIFIC_FORCE_Z (0x04) +#define BIT_VALID_ANGULAR_RATE_X (0x08) +#define BIT_VALID_ANGULAR_RATE_Y (0x10) +#define BIT_VALID_ANGULAR_RATE_Z (0x20) + +/** + * @brief The class that describes and implements the BAHRS serial protocol. +*/ +class CSerialProtocol +{ +public: + static constexpr uint8_t uMarker1_ { 0x4E }; ///< Sync byte 1, symbol 'N' + static constexpr uint8_t uMarker2_ { 0x45 }; ///< Sync char 2, symbol 'E' + static constexpr uint16_t uVersion_ { 2U }; ///< Protocol version + + static constexpr float skfSpecificForceScale_ { 1.495384e-3F }; ///< Integer to float, +-5g range + static constexpr float skfAngularRateScale_ { 1.597921e-4F }; ///< Integer to float, +-300 deg/s range + static constexpr float skfHeightScale_ { 0.16784924F }; ///< Integer to float, -1000 to 10000 m range + static constexpr float skfHeighOffset_ { 1000.0F }; ///< An offset to convert unsigned integer to float + static constexpr float skfVelocityDownScale_ { 9.155413e-3F }; ///< Integer to float, -300 to 300 m/s range + static constexpr float skfAngleScale_ { 9.587526e-5F }; ///< Integer to float, -pi to pi or 0 to 2 pi range + + // Signal ranges + static constexpr float skfMaxHeight_ { 10000.0F }; + static constexpr float skfMinHeight_ { -1000.0F }; + static constexpr float skfMaxVelocityDown_ { 300.0F }; + static constexpr float skfMinVelocityDown_ { -300.0F }; + + enum class EMessageIds : uint8_t { + eInvalid = 0x00, ///< Invalid + eInertialData = 0x01, ///< Inertial data message + eNavigationData = 0x02, ///< Navigation data message + eAccuracy = 0x03, ///< Attitude accuracy information + eTimeOfNavigationData = 0x04, ///< "Time of navigation data" message + eTimeOfInertialData = 0x05, ///< "Time of inertial data" message + eTimeOfSyncPulse = 0x06, ///< "Time of the latest sync pulse" message + eSoftwareVersion = 0x0F, ///< "Software version" message + + eDebugEventWriteToPort = 0xC0, ///< Debug information: SWC port data + eDebugEventRunnableCall = 0xC1, ///< Debug information: SWC API call + + eTypeOpenDiagnostic = 0xF0, ///< Request to enter diagnostics mode + eTypeCloseDiagnostic = 0xF1, ///< Request to exit diagnostics mode + eTypeReadNVMPage = 0xF2, ///< Request to read NVM page + eTypeNVMPageData = 0xF3, ///< A message with NVM page data + eTypeAccept = 0xFF ///< Acknowledgment of diagnostics message reception + }; + + typedef uint32_t CrcType_t; + +#pragma pack(push, 1) + + /** + * @brief Message header struct. + */ + struct SMessageHeader { + uint8_t uMarker1_ { 0x4E }; + uint8_t uMarker2_ { 0x45 }; + uint16_t uVersion_ { CSerialProtocol::uVersion_ }; + uint8_t uMsgType_ { 0U }; + }; + + /** + * @brief Inertial data message payload. + */ + struct SInertialData { + uint8_t uSequenceCounter_ { 0U }; + int16_t iSpecificForceX_ { 0 }; + int16_t iSpecificForceY_ { 0 }; + int16_t iSpecificForceZ_ { 0 }; + int16_t iAngularRateX_ { 0 }; + int16_t iAngularRateY_ { 0 }; + int16_t iAngularRateZ_ { 0 }; + uint8_t uValidity_ { 0U }; + }; + + /** + * @brief Payload of the time of inertial data message. + */ + struct STimeOfInertialData { + uint8_t uSequenceCounter_ { 0U }; + uint8_t uInertialDataSequenceCounter_ { 0U }; + uint64_t uTimestampUs_ { 0U }; + }; + + /** + * @brief Navigation data message payload. + */ + struct SNavigationData { + uint8_t uSequenceCounter_ { 0U }; + uint16_t uPressureHeight_ { 0 }; + int16_t iVelocityDown_ { 0 }; + int16_t iRoll_ { 0 }; + int16_t iPitch_ { 0 }; + uint16_t uMagneticHeading_ { 0U }; + uint8_t uValidity_ { 0 }; + }; + + /** + * @brief Payload of the "time of navigation data" message. + */ + struct STimeOfNavigationData { + uint8_t uSequenceCounter_ { 0U }; + uint8_t uNavigationDataSequenceCounter_ { 0U }; + uint64_t uTimestampUs_ { 0U }; + }; + + /** + * @brief Accuracy message payload. + */ + struct SAccuracyData { + uint8_t uSequenceCounter_ { 0U }; + uint16_t uAttitudeStdN_ { 0U }; + uint16_t uAttitudeStdE_ { 0U }; + uint16_t uMagneticHeadingStd_ { 0U }; + uint64_t uTimestampUs_ { 0U }; + }; + + /** + * @brief Payload of the "time of the latest pulse" message. + */ + struct STimeOfLatestSyncPulse { + uint8_t uSequenceCounter_ { 0U }; + uint64_t uTimestampUs_ { 0U }; + }; + + /** + * @brief Payload of the "software version" message. + */ + struct SSoftwareVersionData { + char acProjectCode_[3] { '\0', '\0', '\0' }; + uint16_t uMajor_ { 0U }; + uint16_t uMinor_ { 0U }; + }; + + /** + * @brief Partial data of the "write to port event". + * The struct does not include a variable size array of data written to a port. + */ + struct SWriteToPortEventPartialData { + uint8_t uPortId_ { 0U }; + uint64_t uTimestampUs_ { 0U }; + uint16_t uDataLen_ { 0U }; + }; + + /** + * @brief Debug information on runnable call. + */ + struct SRunnableCallEventData { + uint8_t uRunnableId_ { 0U }; + uint64_t uTimestampUs_ { 0U }; + }; + + /** + * @brief Inertial data message. + */ + struct SInertialDataMessage { + SMessageHeader oHeader_ { CSerialProtocol::uMarker1_, + CSerialProtocol::uMarker2_, + CSerialProtocol::uVersion_, + static_cast(EMessageIds::eInertialData) }; + + SInertialData oInertialData_; + uint8_t auPadding_[PADDING_SIZE(SInertialData)]; + CrcType_t uCrc_ { 0U }; + }; + + /** + * @brief Time of inertial data message. + */ + struct STimeOfInertialDataMessage { + SMessageHeader oHeader_ { CSerialProtocol::uMarker1_, + CSerialProtocol::uMarker2_, + CSerialProtocol::uVersion_, + static_cast(EMessageIds::eTimeOfInertialData) }; + + STimeOfInertialData oTimeOfInertialData_; + uint8_t auPadding_[PADDING_SIZE(STimeOfInertialData)]; + CrcType_t uCrc_ { 0U }; + }; + + /** + * @brief Navigation data message. + */ + struct SNavigationDataMessage { + SMessageHeader oHeader_ { CSerialProtocol::uMarker1_, + CSerialProtocol::uMarker2_, + CSerialProtocol::uVersion_, + static_cast(EMessageIds::eNavigationData) }; + + SNavigationData oNavigationData_; + uint8_t auPadding_[PADDING_SIZE(SNavigationData)]; + CrcType_t uCrc_ { 0U }; + }; + + /** + * @brief Navigation data accuracy message. + */ + struct SAccuracyDataMessage { + SMessageHeader oHeader_ { CSerialProtocol::uMarker1_, + CSerialProtocol::uMarker2_, + CSerialProtocol::uVersion_, + static_cast(EMessageIds::eAccuracy) }; + + SAccuracyData oAccuracy_; + uint8_t auPadding_[PADDING_SIZE(SAccuracyData)]; + CrcType_t uCrc_ { 0U }; + }; + + /** + * @brief Time of navigation data message. + */ + struct STimeOfNavigationDataMessage { + SMessageHeader oHeader_ { CSerialProtocol::uMarker1_, + CSerialProtocol::uMarker2_, + CSerialProtocol::uVersion_, + static_cast(EMessageIds::eTimeOfNavigationData) }; + + STimeOfNavigationData oTimeOfNavigationData_; + uint8_t auPadding_[PADDING_SIZE(STimeOfNavigationData)]; + CrcType_t uCrc_ { 0U }; + }; + + /** + * @brief Time of the latest sync pulse message. + */ + struct STimeOfLatestSyncPulseMessage { + SMessageHeader oHeader_ { CSerialProtocol::uMarker1_, + CSerialProtocol::uMarker2_, + CSerialProtocol::uVersion_, + static_cast(EMessageIds::eTimeOfSyncPulse) }; + + STimeOfLatestSyncPulse oTimeOfLatestSyncPulse_; + uint8_t auPadding_[PADDING_SIZE(STimeOfLatestSyncPulse)]; + CrcType_t uCrc_ { 0U }; + }; + + /** + * @brief Software version message. + */ + struct SSoftwareVersionMessage { + SMessageHeader oHeader_ { CSerialProtocol::uMarker1_, + CSerialProtocol::uMarker2_, + CSerialProtocol::uVersion_, + static_cast(EMessageIds::eSoftwareVersion) }; + + SSoftwareVersionData oSoftwareVersion_; + uint8_t auPadding_[PADDING_SIZE(SSoftwareVersionData)]; + CrcType_t uCrc_ { 0U }; + }; + + /** + * @brief A debug message with runnable call data. + */ + struct SRunnableCallEventDebugMessage { + SMessageHeader oHeader_{ CSerialProtocol::uMarker1_, + CSerialProtocol::uMarker2_, + CSerialProtocol::uVersion_, + static_cast(EMessageIds::eDebugEventRunnableCall) }; + + SRunnableCallEventData oRunnableCallData_; + uint8_t auPadding_[PADDING_SIZE(oRunnableCallData_)]; + CrcType_t uCrc_{ 0U }; + }; + + /** + * @brief Diagnostic Mode Messages + ****************************************************************************/ + + /** + * @brief Diagnostic message: Page request from NVM. + */ + struct SPacketReadNVMPage { + SMessageHeader oHeader_; + uint8_t uPageNumber { 0U }; + CrcType_t uCrc32 { 0U }; + }; + + /** + * @brief Diagnostic message: confirmation of request processing by the device. + */ + struct SPacketReceiveConfirmation { + SMessageHeader oHeader_ { CSerialProtocol::uMarker1_, + CSerialProtocol::uMarker2_, + CSerialProtocol::uVersion_, + static_cast(EMessageIds::eTypeAccept) }; + EMessageIds eMessageType; // message type to confirm. + uint8_t uStatus { 0U }; // 0 - OK, other values - error codes + CrcType_t uCrc32 { 0U }; + }; + +#pragma pack(pop) + +}; diff --git a/src/drivers/ins/eulernav_bahrs/eulernav_bahrs_main.cpp b/src/drivers/ins/eulernav_bahrs/eulernav_bahrs_main.cpp new file mode 100644 index 0000000000..674db6dbf1 --- /dev/null +++ b/src/drivers/ins/eulernav_bahrs/eulernav_bahrs_main.cpp @@ -0,0 +1,48 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file eulernav_bahrs_main.cpp + * A driver module for EULER-NAV Baro-Inertial AHRS. + * + * @author Fedor Baklanov + */ + +#include +#include "eulernav_driver.h" + +extern "C" __EXPORT int eulernav_bahrs_main(int argc, char *argv[]) +{ + EulerNavDriver::main(argc, argv); + return OK; +} diff --git a/src/drivers/ins/eulernav_bahrs/eulernav_driver.cpp b/src/drivers/ins/eulernav_bahrs/eulernav_driver.cpp new file mode 100644 index 0000000000..1592308d76 --- /dev/null +++ b/src/drivers/ins/eulernav_bahrs/eulernav_driver.cpp @@ -0,0 +1,514 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "eulernav_driver.h" +#include +#include +#include +#include +#include + +EulerNavDriver::EulerNavDriver(const char *device_name) + : ModuleParams{nullptr} + , _serial_port{device_name, 115200, ByteSize::EightBits, Parity::None, StopBits::One, FlowControl::Disabled} + , _data_buffer{} + , _px4_accel{DRV_INS_DEVTYPE_BAHRS} + , _px4_gyro{DRV_INS_DEVTYPE_BAHRS} +{ +} + +EulerNavDriver::~EulerNavDriver() +{ + deinitialize(); +} + +int EulerNavDriver::task_spawn(int argc, char *argv[]) +{ + int task_id = px4_task_spawn_cmd("bahrs", SCHED_DEFAULT, SCHED_PRIORITY_FAST_DRIVER, + Config::TASK_STACK_SIZE, (px4_main_t)&run_trampoline, argv); + + if (task_id < 0) { + _task_id = -1; + PX4_ERR("Failed to spawn task."); + + } else { + _task_id = task_id; + } + + return (_task_id < 0) ? 1 : 0; +} + +EulerNavDriver *EulerNavDriver::instantiate(int argc, char *argv[]) +{ + int option_index = 1; + const char *option_arg{nullptr}; + const char *device_name{nullptr}; + + while (true) { + int option{px4_getopt(argc, argv, "d:", &option_index, &option_arg)}; + + if (EOF == option) { + break; + } + + switch (option) { + case 'd': + device_name = option_arg; + break; + + default: + break; + } + } + + auto *instance = new EulerNavDriver(device_name); + + if (nullptr != instance) { + instance->initialize(); + + } else { + PX4_ERR("Failed to initialize EULER-NAV driver."); + } + + return instance; +} + +int EulerNavDriver::custom_command(int argc, char *argv[]) +{ + return print_usage("unrecognized command"); +} + +int EulerNavDriver::print_usage(const char *reason) +{ + if (reason) { + PX4_WARN("%s\n", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description + +Serial bus driver for the EULER-NAV Baro-Inertial AHRS. + +### Examples + +Attempt to start driver on a specified serial device. +$ eulernav_bahrs start -d /dev/ttyS1 +Stop driver +$ eulernav_bahrs stop +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("eulernav_bahrs", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("ins"); + PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start driver"); + PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, nullptr, "Serial device", false); + PRINT_MODULE_USAGE_COMMAND_DESCR("status", "Print driver status"); + PRINT_MODULE_USAGE_COMMAND_DESCR("stop", "Stop driver"); + + return PX4_OK; +} + +int EulerNavDriver::print_status() +{ + if (_is_initialized) + { + PX4_INFO("Elapsed time: %llu [us].\n", hrt_elapsed_time(&_statistics.start_time)); + PX4_INFO("Total bytes received: %lu.\n", _statistics.total_bytes_received); + PX4_INFO("Inertial messages received: %lu. Navigation messages received: %lu.\n", + _statistics.inertial_message_counter, _statistics.navigation_message_counter); + PX4_INFO("Failed CRC count: %lu.\n", _statistics.crc_failures); + + } + else + { + PX4_INFO("Initialization failed. The driver is not running.\n"); + } + + return PX4_OK; +} + +void EulerNavDriver::run() +{ + _statistics.start_time = hrt_absolute_time(); + + while(!should_exit()) + { + if (_is_initialized) + { + const auto bytes_read{_serial_port.readAtLeast(_serial_read_buffer, sizeof(_serial_read_buffer), + Config::MIN_BYTES_TO_READ, Config::SERIAL_READ_TIMEOUT_MS)}; + + _statistics.total_bytes_received += bytes_read; + + if (bytes_read > 0) + { + if (!_data_buffer.push_back(_serial_read_buffer, bytes_read)) + { + PX4_ERR("No space in data buffer"); + } + } + + processDataBuffer(); + } + else + { + // The driver failed to initialize in the instantiate() method, so we exit the loop. + request_stop(); + } + } +} + +void EulerNavDriver::initialize() +{ + if (!_is_initialized) + { + if (_serial_port.open()) + { + PX4_INFO("Serial port opened successfully."); + _is_initialized = true; + } + else + { + PX4_ERR("Failed to open serial port"); + } + + if (_is_initialized) + { + if (!_data_buffer.allocate(Config::DATA_BUFFER_SIZE)) + { + PX4_ERR("Failed to allocate data buffer"); + _is_initialized = false; + } + } + + if (_is_initialized) + { + _attitude_pub.advertise(); + _barometer_pub.advertise(); + } + } +} + +void EulerNavDriver::deinitialize() +{ + if (_serial_port.isOpen()) + { + _serial_port.close(); + } + + _data_buffer.deallocate(); + _attitude_pub.unadvertise(); + _barometer_pub.unadvertise(); + _is_initialized = false; +} + +void EulerNavDriver::processDataBuffer() +{ + static_assert(Config::MIN_MESSAGE_LENGTH >= (sizeof(CSerialProtocol::SMessageHeader) + sizeof(CSerialProtocol::CrcType_t))); + using EMessageIds = CSerialProtocol::EMessageIds; + + while (_data_buffer.space_used() >= Config::MIN_MESSAGE_LENGTH) + { + if (!_next_message_info.is_detected) + { + _next_message_info.is_detected = findNextMessageHeader(_data_buffer); + + if (!_next_message_info.is_detected) + { + // No message header found, wait for more bytes to arrive. + break; + } + + if (!retrieveProtocolVersionAndMessageType(_data_buffer, _next_message_info.protocol_version, _next_message_info.message_code)) + { + _next_message_info.is_detected = false; + } + } + + if (_next_message_info.is_detected) + { + static_assert(sizeof(CSerialProtocol::SMessageHeader) < Config::MIN_MESSAGE_LENGTH); + + const EMessageIds message_id{static_cast(_next_message_info.message_code)}; + const int32_t message_length{getMessageLength(message_id)}; + + if ((message_length < 0) || (message_length < Config::MIN_MESSAGE_LENGTH) || + (message_length > static_cast(sizeof(_message_storage))) || ((message_length % sizeof(uint32_t)) != 0U)) + { + // The message is unknown, not supported, or does not fit into the temporary storage. + _next_message_info.is_detected = false; + continue; + } + + const int32_t bytes_to_retrieve{message_length - static_cast(sizeof(CSerialProtocol::SMessageHeader))}; + + if (static_cast(_data_buffer.space_used()) < bytes_to_retrieve) + { + // Do nothing and wait for more bytes to arrive. + break; + } + + // Get message from the data buffer + uint8_t* bytes{reinterpret_cast(_message_storage)}; + + bytes[0] = CSerialProtocol::uMarker1_; + bytes[1] = CSerialProtocol::uMarker2_; + bytes[2] = reinterpret_cast(&_next_message_info.protocol_version)[0]; + bytes[3] = reinterpret_cast(&_next_message_info.protocol_version)[1]; + bytes[4] = _next_message_info.message_code; + + if (static_cast(bytes_to_retrieve) == _data_buffer.pop_front(bytes + sizeof(CSerialProtocol::SMessageHeader), bytes_to_retrieve)) + { + const uint32_t message_length_in_words{message_length / sizeof(uint32_t)}; + const uint32_t actual_crc{crc32(_message_storage, message_length_in_words - 1)}; + const uint32_t expected_crc = _message_storage[message_length_in_words - 1]; + + if (expected_crc != actual_crc) + { + ++_statistics.crc_failures; + } + else + { + decodeMessageAndPublishData(bytes, message_id); + } + } + + _next_message_info.is_detected = false; + } + } +} + +bool EulerNavDriver::findNextMessageHeader(Ringbuffer& buffer) +{ + bool result{false}; + + while (buffer.space_used() >= sizeof(CSerialProtocol::SMessageHeader)) + { + uint8_t sync_byte{0U}; + + if ((1 == buffer.pop_front(&sync_byte, 1)) && (CSerialProtocol::uMarker1_ == sync_byte)) + { + sync_byte = 0U; + + if ((1 == buffer.pop_front(&sync_byte, 1)) && (CSerialProtocol::uMarker2_ == sync_byte)) + { + result = true; + break; + } + } + } + + return result; +} + +bool EulerNavDriver::retrieveProtocolVersionAndMessageType(Ringbuffer& buffer, uint16_t& protocol_ver, uint8_t& message_code) +{ + bool status{true}; + auto bytes_to_pop{sizeof(protocol_ver)}; + + // Note: BAHRS uses little endian + if (bytes_to_pop != buffer.pop_front(reinterpret_cast(&protocol_ver), bytes_to_pop)) + { + status = false; + } + + if (status) + { + bytes_to_pop = 1; + + if (bytes_to_pop != buffer.pop_front(&message_code, bytes_to_pop)) + { + status = false; + } + } + + return status; +} + +void EulerNavDriver::decodeMessageAndPublishData(const uint8_t* data, CSerialProtocol::EMessageIds messsage_id) +{ + switch (messsage_id) + { + case CSerialProtocol::EMessageIds::eInertialData: + handleInertialDataMessage(data); + break; + case CSerialProtocol::EMessageIds::eNavigationData: + handleNavigationDataMessage(data); + break; + default: + break; + } +} + +void EulerNavDriver::handleInertialDataMessage(const uint8_t* data) +{ + const CSerialProtocol::SInertialDataMessage* imu_msg{reinterpret_cast(data)}; + + if (nullptr != imu_msg) + { + const auto& imu_data{imu_msg->oInertialData_}; + const bool accel_valid{((imu_data.uValidity_ & BIT_VALID_SPECIFIC_FORCE_X) > 0) && + ((imu_data.uValidity_ & BIT_VALID_SPECIFIC_FORCE_Y) > 0) && + ((imu_data.uValidity_ & BIT_VALID_SPECIFIC_FORCE_Z) > 0)}; + + const bool gyro_valid{((imu_data.uValidity_ & BIT_VALID_ANGULAR_RATE_X) > 0) && + ((imu_data.uValidity_ & BIT_VALID_ANGULAR_RATE_Y) > 0) && + ((imu_data.uValidity_ & BIT_VALID_ANGULAR_RATE_Z) > 0)}; + + const auto time = hrt_absolute_time(); + + if (accel_valid) + { + const float accel_x{CSerialProtocol::skfSpecificForceScale_ * static_cast(imu_data.iSpecificForceX_)}; + const float accel_y{CSerialProtocol::skfSpecificForceScale_ * static_cast(imu_data.iSpecificForceY_)}; + const float accel_z{CSerialProtocol::skfSpecificForceScale_ * static_cast(imu_data.iSpecificForceZ_)}; + + _px4_accel.update(time, accel_x, accel_y, accel_z); + } + + if (gyro_valid) + { + const float gyro_x{CSerialProtocol::skfAngularRateScale_ * static_cast(imu_data.iAngularRateX_)}; + const float gyro_y{CSerialProtocol::skfAngularRateScale_ * static_cast(imu_data.iAngularRateY_)}; + const float gyro_z{CSerialProtocol::skfAngularRateScale_ * static_cast(imu_data.iAngularRateZ_)}; + + _px4_gyro.update(time, gyro_x, gyro_y, gyro_z); + } + + ++_statistics.inertial_message_counter; + } +} + +void EulerNavDriver::handleNavigationDataMessage(const uint8_t* data) +{ + const CSerialProtocol::SNavigationDataMessage* nav_msg{reinterpret_cast(data)}; + + if (nullptr != nav_msg) + { + const auto& nav_data{nav_msg->oNavigationData_}; + const bool roll_valid{(nav_data.uValidity_ & BIT_VALID_ROLL) > 0}; + const bool pitch_valid{(nav_data.uValidity_ & BIT_VALID_PITCH) > 0}; + const bool yaw_valid{(nav_data.uValidity_ & BIT_VALID_MAGNETIC_HEADING) > 0}; + const auto time{hrt_absolute_time()}; + + if (roll_valid && pitch_valid && yaw_valid) + { + const float roll{CSerialProtocol::skfAngleScale_ * static_cast(nav_data.iRoll_)}; + const float pitch{CSerialProtocol::skfAngleScale_ * static_cast(nav_data.iPitch_)}; + const float yaw{CSerialProtocol::skfAngleScale_ * static_cast(nav_data.uMagneticHeading_)}; + + const matrix::Quaternionf quat{matrix::Eulerf{roll, pitch, yaw}}; + px4::msg::VehicleAttitude attitude{}; + + attitude.q[0] = quat(0); + attitude.q[1] = quat(1); + attitude.q[2] = quat(2); + attitude.q[3] = quat(3); + + attitude.timestamp = time; + attitude.timestamp_sample = time; + + _attitude_pub.publish(attitude); + } + + const bool height_valid{(nav_data.uValidity_ & BIT_VALID_HEIGHT) > 0}; + + if (height_valid) + { + const float height{(CSerialProtocol::skfHeightScale_ * static_cast(nav_data.uPressureHeight_)) - CSerialProtocol::skfHeighOffset_}; + px4::msg::SensorBaro pressure{}; + + pressure.pressure = atmosphere::getPressureFromAltitude(height); + + // EULER-NAV Baro-Inertial AHRS provides height estimate from a Kalman filter. It has got low noise and resolution + // of about 17 cm. It causes PX4 autopilot to mistakenly report that pressure signal is stale. In order to prevent + // the false alarms we add a small noise to the received height data. + if (_statistics.navigation_message_counter % 2U == 0) + { + pressure.pressure += 0.01F; + } + + pressure.timestamp = time; + pressure.timestamp_sample = time; + pressure.device_id = DRV_INS_DEVTYPE_BAHRS; + pressure.temperature = NAN; + + _barometer_pub.publish(pressure); + } + + ++_statistics.navigation_message_counter; + } +} + +int32_t EulerNavDriver::getMessageLength(CSerialProtocol::EMessageIds messsage_id) +{ + int message_length{-1}; + + switch (messsage_id) + { + case CSerialProtocol::EMessageIds::eInertialData: + message_length = sizeof(CSerialProtocol::SInertialDataMessage); + break; + case CSerialProtocol::EMessageIds::eNavigationData: + message_length = sizeof(CSerialProtocol::SNavigationDataMessage); + break; + default: + break; + } + + return message_length; +} + +uint32_t EulerNavDriver::crc32(const uint32_t* buffer, size_t length) +{ + uint32_t crc = 0xFFFFFFFF; + + for (size_t i = 0; i < length; ++i) + { + crc = crc ^ buffer[i]; + + for (uint8_t j = 0; j < 32; j++) + { + if (crc & 0x80000000) + { + crc = (crc << 1) ^ 0x04C11DB7; + } + else + { + crc = (crc << 1); + } + } + } + + return crc; +} diff --git a/src/drivers/ins/eulernav_bahrs/eulernav_driver.h b/src/drivers/ins/eulernav_bahrs/eulernav_driver.h new file mode 100644 index 0000000000..851b8d63b1 --- /dev/null +++ b/src/drivers/ins/eulernav_bahrs/eulernav_driver.h @@ -0,0 +1,174 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "CSerialProtocol.h" + +class EulerNavDriver : public ModuleBase, public ModuleParams +{ +public: + /// @brief Class constructor + /// @param device_name Serial port to open + EulerNavDriver(const char *device_name); + + ~EulerNavDriver(); + + /// @brief Required by ModuleBase + static int task_spawn(int argc, char *argv[]); + + /// @brief Required by ModuleBase + static EulerNavDriver *instantiate(int argc, char *argv[]); + + /// @brief Required by ModuleBase + static int custom_command(int argc, char *argv[]); + + /// @brief Required by ModuleBase + static int print_usage(const char *reason = nullptr); + + /// @brief Overload of the method from the ModuleBase + int print_status() final; + + /// @brief The main loop of the task. + void run() final; + +private: + /// @brief Driver performance indicators + class Statistics + { + public: + uint32_t total_bytes_received{0U}; ///< Total number of received bytes + uint32_t inertial_message_counter{0U}; ///< Total number of received inertial data messages + uint32_t navigation_message_counter{0U}; ///< Total number of received navigation messages + uint32_t crc_failures{0U}; ///< CRC failure counter + hrt_abstime start_time{0U}; ///< Driver start time, [us] + }; + + /// @brief Configuration constants + class Config + { + public: + static constexpr uint32_t TASK_STACK_SIZE{2048}; ///< Driver task stack size + static constexpr uint32_t SERIAL_READ_BUFFER_SIZE{128}; ///< Buffer size for serial port read operations + static constexpr uint32_t MIN_BYTES_TO_READ{16}; ///< Minimum number of bytes to wait for when reading from a serial port + static constexpr uint32_t SERIAL_READ_TIMEOUT_MS{5}; ///< A timeout for serial port read operation + static constexpr uint32_t DATA_BUFFER_SIZE{512}; ///< Size of a ring buffer for storing RX data stream + static constexpr int32_t MIN_MESSAGE_LENGTH{12}; ///< Min length of a valid message. 5 bytes header + 4 bytes CRC + padding to 12 (multiple of 32 bit words) + }; + + /// @brief An object for grouping message-related attributes + class NextMessageInfo + { + public: + bool is_detected{false}; ///< A flag to indicate that the next message header was detected + uint16_t protocol_version{0U}; ///< Protocol version retrieved from the next message header + uint8_t message_code{0U}; ///< Message code retrieved from the next message header + }; + + /// @brief Perform initialization + /// If the driver is not initialized, the function does the following: + /// 1. Opens serial port + /// 2. Allocates a ring buffer for RX data stream + /// 3. Cleans up if any of the previous operations fails + /// 4. Sets the "is initialized" flag to true on success + void initialize(); + + /// @brief De-initialize + /// The function does the following: + /// 1. Close the serial port, if it is opened + /// 2. Deallocates the ring buffer + /// 3. Resets the "is initialized" flag to false + void deinitialize(); + + /// @brief Process data in the ring buffer. + /// Extracts and parses protocol messages. + void processDataBuffer(); + + /// @brief Searches the ring buffer for sync bytes. + /// @param buffer Ring buffer to search + /// @return True if sync bytes found, false if the number of bytes remaining in the buffer is less then message header length. + static bool findNextMessageHeader(Ringbuffer &buffer); + + /// @brief Get protocol version and message code from the ring buffer. + /// @param buffer The buffer to process + /// @param protocol_ver Output protocol version + /// @param message_code Output message code + /// @return True on success, false on failure + static bool retrieveProtocolVersionAndMessageType(Ringbuffer &buffer, uint16_t &protocol_ver, uint8_t &message_code); + + /// @brief Decode a message from BAHRS and publish its content. + /// @param data An array of message bytes + /// @param messsage_id Message ID + void decodeMessageAndPublishData(const uint8_t *data, CSerialProtocol::EMessageIds messsage_id); + + /// @brief Decode and publish IMU data. + /// @param data Inertial message data bytes + void handleInertialDataMessage(const uint8_t *data); + + /// @brief Decode and publish vehicle attitude and pressure height. + /// @param data Navigation message data bytes + void handleNavigationDataMessage(const uint8_t *data); + + /// @brief Get message length by message ID + /// @param messsage_id Query message ID + /// @return Message length, or -1 if the message ID is unknown or not supported. + static int32_t getMessageLength(CSerialProtocol::EMessageIds messsage_id); + + /// @brief Perform CRC + /// @param buf Data buffer pointer + /// @param len Number of words to include in the CRC. + /// @return CRC value + static uint32_t crc32(const uint32_t *buf, size_t len); + + device::Serial _serial_port; ///< Serial port object to read data from + Ringbuffer _data_buffer; ///< A buffer for RX data stream + uint8_t _serial_read_buffer[Config::SERIAL_READ_BUFFER_SIZE]; ///< A buffer for serial port read operation + uint32_t _message_storage[8]; ///< A temporary storage for BAHRS messages being extracted + NextMessageInfo _next_message_info{}; ///< Attributes of the next message detected in the data buffer + Statistics _statistics{}; ///< Driver performance indicators + bool _is_initialized{false}; ///< Initialization flag + PX4Accelerometer _px4_accel; ///< Accelerometer sensor object for publishing acceleration data + PX4Gyroscope _px4_gyro; ///< Gyroscope sensor object for publishing angular rate data + uORB::PublicationMulti _attitude_pub{ORB_ID(vehicle_attitude)}; ///< Vehicle attitude publisher + uORB::PublicationMulti _barometer_pub{ORB_ID(sensor_baro)}; ///< Pressure data publisher +}; diff --git a/src/drivers/ins/eulernav_bahrs/module.yaml b/src/drivers/ins/eulernav_bahrs/module.yaml new file mode 100644 index 0000000000..38ff4a5f1b --- /dev/null +++ b/src/drivers/ins/eulernav_bahrs/module.yaml @@ -0,0 +1,7 @@ +module_name: EULER-NAV BAHRS + +serial_config: + - command: eulernav_bahrs start -d ${SERIAL_DEV} + port_config_param: + name: SENS_BAHRS_CFG + group: Sensors From af6bf931c141d1f5df43a1176302d1f9810fe380 Mon Sep 17 00:00:00 2001 From: Alex Klimaj Date: Thu, 4 Sep 2025 14:20:03 -0600 Subject: [PATCH 007/812] uavcan bootloader watchdog_pet during long flashes (#25523) --- platforms/nuttx/src/canbootloader/uavcan/main.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/platforms/nuttx/src/canbootloader/uavcan/main.c b/platforms/nuttx/src/canbootloader/uavcan/main.c index db1f6691f9..015943f0e9 100644 --- a/platforms/nuttx/src/canbootloader/uavcan/main.c +++ b/platforms/nuttx/src/canbootloader/uavcan/main.c @@ -847,6 +847,8 @@ static flash_error_t file_read_and_program(const uavcan_Path_t *fw_path, uint8_t request.offset += length; bootloader.percentage_done = (request.offset / a_percent); + watchdog_pet(); + } while (request.offset < fw_image_size && length == sizeof(response.data) && flash_status == FLASH_OK); From 89c6d249460faf912e85ec7e6deeb572000c39c5 Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Wed, 3 Sep 2025 16:37:54 -0600 Subject: [PATCH 008/812] Update GPS submodule --- src/drivers/gps/devices | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/gps/devices b/src/drivers/gps/devices index ce0afaeca2..8fdef3bc0c 160000 --- a/src/drivers/gps/devices +++ b/src/drivers/gps/devices @@ -1 +1 @@ -Subproject commit ce0afaeca23a3b88efcf52d47c82277839980f9d +Subproject commit 8fdef3bc0cb7820119abdb7320ad3992af2e440f From 1840c0db48f4cc260a3769a8ed5fa7420f6e9818 Mon Sep 17 00:00:00 2001 From: Claudio Chies <61051109+Claudio-Chies@users.noreply.github.com> Date: Fri, 5 Sep 2025 10:57:13 +0200 Subject: [PATCH 009/812] UAVCAN:BAT: improve remaining time calculation (#25500) * UAVCAN:BAT: improve remaining time calculation * UAVCAN:BAT: fix time_remaining calculation, bugfixes, improved filter convergence time * UAVCAN:BAT: remove BatteryInfo Publishing if no valid info * UAVCAN + Battery library: suggestions while reviewing --------- Co-authored-by: Matthias Grob --- src/drivers/uavcan/sensors/battery.cpp | 113 ++++++++----------------- src/drivers/uavcan/sensors/battery.hpp | 2 - src/lib/battery/battery.cpp | 57 +++++++------ src/lib/battery/battery.h | 31 +++++-- 4 files changed, 95 insertions(+), 108 deletions(-) diff --git a/src/drivers/uavcan/sensors/battery.cpp b/src/drivers/uavcan/sensors/battery.cpp index cb1619e0cf..643e699ad0 100644 --- a/src/drivers/uavcan/sensors/battery.cpp +++ b/src/drivers/uavcan/sensors/battery.cpp @@ -112,28 +112,22 @@ UavcanBatteryBridge::battery_sub_cb(const uavcan::ReceivedDataStructureupdateDt(_battery_status[instance].timestamp); _battery_status[instance].voltage_v = msg.voltage; _battery_status[instance].current_a = msg.current; - _battery_status[instance].current_average_a = msg.current; if (_batt_update_mod[instance] == BatteryDataType::Raw) { - sumDischarged(_battery_status[instance].timestamp, _battery_status[instance].current_a); - _battery_status[instance].discharged_mah = _discharged_mah; + _battery_status[instance].discharged_mah = _battery[instance]->sumDischarged(fabsf(msg.current)); _battery_status[instance].time_remaining_s = NAN; } _battery_status[instance].remaining = msg.state_of_charge_pct / 100.0f; // between 0 and 1 _battery_status[instance].scale = -1.f; _battery_status[instance].temperature = msg.temperature + atmosphere::kAbsoluteNullCelsius; // Kelvin to Celsius - // _battery_status[instance].cell_count = msg.; _battery_status[instance].connected = true; _battery_status[instance].source = msg.status_flags & uavcan::equipment::power::BatteryInfo::STATUS_FLAG_IN_USE; - // _battery_status[instance].priority = msg.; - _battery_status[instance].capacity = msg.full_charge_capacity_wh; _battery_status[instance].full_charge_capacity_wh = msg.full_charge_capacity_wh; _battery_status[instance].remaining_capacity_wh = msg.remaining_capacity_wh; - // _battery_status[instance].cycle_count = msg.; - // _battery_status[instance].average_time_to_empty = msg.; _battery_status[instance].id = msg.getSrcNodeID().get(); if (_batt_update_mod[instance] == BatteryDataType::Raw) { @@ -144,21 +138,18 @@ UavcanBatteryBridge::battery_sub_cb(const uavcan::ReceivedDataStructuredetermineWarning(_battery_status[instance].remaining); if (_batt_update_mod[instance] == BatteryDataType::Raw) { publish(msg.getSrcNodeID().get(), &_battery_status[instance]); - _battery_info_pub[instance].publish(_battery_info[instance]); + + if (msg.model_instance_id > 0) { + _battery_info[instance].timestamp = _battery_status[instance].timestamp; + _battery_info[instance].id = _battery_status[instance].id; + snprintf(_battery_info[instance].serial_number, sizeof(_battery_info[instance].serial_number), + "%" PRIu32, msg.model_instance_id); + _battery_info_pub[instance].publish(_battery_info[instance]); + } } } @@ -182,18 +173,24 @@ UavcanBatteryBridge::battery_aux_sub_cb(const uavcan::ReceivedDataStructure FLT_EPSILON) { + _battery_status[instance].capacity = + _battery_status[instance].full_charge_capacity_wh * 1000.f / msg.nominal_voltage; + } + + _battery[instance]->setCapacityMah(_battery_status[instance].capacity); + _battery[instance]->setStateOfCharge(_battery_status[instance].remaining); + // Absolute value of current as sign not clearly defined and vendors are inconsistent + _battery_status[instance].time_remaining_s = + _battery[instance]->computeRemainingTime(fabsf(_battery_status[instance].current_a)); + _battery_status[instance].current_average_a = _battery[instance]->getCurrentAverage(); + for (uint8_t i = 0; i < _battery_status[instance].cell_count; i++) { _battery_status[instance].voltage_cell_v[i] = msg.voltage_cell[i]; } @@ -234,7 +231,7 @@ void UavcanBatteryBridge::cbat_sub_cb(const uavcan::ReceivedDataStructure Wh _battery_status[instance].remaining_capacity_wh = msg.remaining_capacity * msg.nominal_voltage / 1000.f; // mAh -> Wh _battery_status[instance].nominal_voltage = msg.nominal_voltage; - _battery_status[instance].capacity = msg.design_capacity; // mAh + _battery_status[instance].capacity = msg.full_charge_capacity; // mAh _battery_status[instance].cycle_count = msg.cycle_count; _battery_status[instance].average_time_to_empty = msg.average_time_to_empty; _battery_status[instance].manufacture_date = msg.manufacture_date; @@ -247,19 +244,18 @@ void UavcanBatteryBridge::cbat_sub_cb(const uavcan::ReceivedDataStructure Ah - const float current_a = math::isZero(_battery_status[instance].current_average_a) ? - _battery_status[instance].current_a : _battery_status[instance].current_average_a; + // use Battery class for time_remaining calculation + _battery[instance]->updateDt(_battery_status[instance].timestamp); + _battery[instance]->setStateOfCharge(_battery_status[instance].remaining); + _battery[instance]->setCapacityMah(_battery_status[instance].capacity); _battery_status[instance].time_remaining_s = - math::isZero(current_a) ? NAN : (remaining_ah / current_a * 3600.f); // Ah / A = h * 3600 = s + _battery[instance]->computeRemainingTime(_battery_status[instance].current_a); for (uint8_t i = 0; i < _battery_status[instance].cell_count; i++) { _battery_status[instance].voltage_cell_v[i] = msg.voltage_cell[i]; } - determineWarning(_battery_status[instance].remaining); - _battery_status[instance].warning = _warning; + _battery_status[instance].warning = _battery[instance]->determineWarning(_battery_status[instance].remaining); uint16_t faults = 0; @@ -290,43 +286,6 @@ void UavcanBatteryBridge::cbat_sub_cb(const uavcan::ReceivedDataStructure &msg, uint8_t instance) @@ -343,9 +302,11 @@ UavcanBatteryBridge::filterData(const uavcan::ReceivedDataStructure 0) { + _battery_info[instance].timestamp = _battery_status[instance].timestamp; + _battery_info[instance].id = _battery_status[instance].id; + snprintf(_battery_info[instance].serial_number, sizeof(_battery_info[instance].serial_number), + "%" PRIu32, msg.model_instance_id); + _battery_info_pub[instance].publish(_battery_info[instance]); + } } diff --git a/src/drivers/uavcan/sensors/battery.hpp b/src/drivers/uavcan/sensors/battery.hpp index ed61cd0817..0c0ab3c949 100644 --- a/src/drivers/uavcan/sensors/battery.hpp +++ b/src/drivers/uavcan/sensors/battery.hpp @@ -73,8 +73,6 @@ private: void battery_sub_cb(const uavcan::ReceivedDataStructure &msg); void battery_aux_sub_cb(const uavcan::ReceivedDataStructure &msg); void cbat_sub_cb(const uavcan::ReceivedDataStructure &msg); - void sumDischarged(hrt_abstime timestamp, float current_a); - void determineWarning(float remaining); void filterData(const uavcan::ReceivedDataStructure &msg, uint8_t instance); typedef uavcan::MethodBinder < UavcanBatteryBridge *, diff --git a/src/lib/battery/battery.cpp b/src/lib/battery/battery.cpp index 10dbb93a68..844f24de74 100644 --- a/src/lib/battery/battery.cpp +++ b/src/lib/battery/battery.cpp @@ -113,6 +113,8 @@ void Battery::updateTemperature(const float temperature_c) void Battery::updateBatteryStatus(const hrt_abstime ×tamp) { + updateDt(timestamp); + // Require minimum voltage otherwise override connected status if (_voltage_v < LITHIUM_BATTERY_RECOGNITION_VOLTAGE) { _connected = false; @@ -129,7 +131,7 @@ void Battery::updateBatteryStatus(const hrt_abstime ×tamp) resetInternalResistanceEstimation(_voltage_v, _current_a); } - sumDischarged(timestamp, _current_a); + sumDischarged(_current_a); _state_of_charge_volt_based = calculateStateOfChargeVoltageBased(_voltage_v, _current_a); @@ -159,7 +161,7 @@ battery_status_s Battery::getBatteryStatus() battery_status.connected = _connected; battery_status.source = _source; battery_status.priority = _priority; - battery_status.capacity = _params.capacity > 0.f ? static_cast(_params.capacity) : 0; + battery_status.capacity = static_cast(_capacity_mah); battery_status.id = static_cast(_index); battery_status.warning = _warning; battery_status.timestamp = hrt_absolute_time(); @@ -188,28 +190,26 @@ void Battery::updateAndPublishBatteryStatus(const hrt_abstime ×tamp) updateBatteryStatus(timestamp); publishBatteryStatus(getBatteryStatus()); } - -void Battery::sumDischarged(const hrt_abstime ×tamp, float current_a) +void Battery::updateDt(const hrt_abstime ×tamp) { - // Not a valid measurement - if (current_a < 0.f) { - // Because the measurement was invalid we need to stop integration - // and re-initialize with the next valid measurement - _last_timestamp = 0; - return; - } - - // Ignore first update because we don't know dt. if (_last_timestamp != 0) { - const float dt = (timestamp - _last_timestamp) / 1e6; - // mAh since last loop: (current[A] * 1000 = [mA]) * (dt[s] / 3600 = [h]) - _discharged_mah_loop = (current_a * 1e3f) * (dt / 3600.f); - _discharged_mah += _discharged_mah_loop; + _dt = math::min((timestamp - _last_timestamp) / 1e6f, 2.f); // guard to a maximum 2 seconds dt } _last_timestamp = timestamp; } +float Battery::sumDischarged(float current_a) +{ + if (_dt > FLT_EPSILON) { + // mAh since last loop: (current[A] * 1000 = [mA]) * (dt[s] / 3600 = [h]) + _discharged_mah_loop = (current_a * 1e3f) * (_dt / 3600.f); + _discharged_mah += _discharged_mah_loop; + } + + return _discharged_mah; +} + float Battery::calculateStateOfChargeVoltageBased(const float voltage_v, const float current_a) { if (_params.n_cells == 0) { @@ -287,16 +287,16 @@ void Battery::resetInternalResistanceEstimation(const float voltage_v, const flo void Battery::estimateStateOfCharge() { // choose which quantity we're using for final reporting - if ((_params.capacity > 0.f) && _battery_initialized) { + if ((_capacity_mah > 0.f) && _battery_initialized) { // if battery capacity is known, fuse voltage measurement with used capacity // The lower the voltage the more adjust the estimate with it to avoid deep discharge const float weight_v = 3e-2f * (1 - _state_of_charge_volt_based); _state_of_charge = (1 - weight_v) * _state_of_charge + weight_v * _state_of_charge_volt_based; // directly apply current capacity slope calculated using current - _state_of_charge -= _discharged_mah_loop / _params.capacity; + _state_of_charge -= _discharged_mah_loop / _capacity_mah; _state_of_charge = math::max(_state_of_charge, 0.f); - const float state_of_charge_current_based = math::max(1.f - _discharged_mah / _params.capacity, 0.f); + const float state_of_charge_current_based = math::max(1.f - _discharged_mah / _capacity_mah, 0.f); _state_of_charge = math::min(state_of_charge_current_based, _state_of_charge); } else { @@ -376,14 +376,18 @@ float Battery::computeRemainingTime(float current_a) // For FW only update when we are in level flight if (!_vehicle_status_is_fw || ((hrt_absolute_time() - _flight_phase_estimation_sub.get().timestamp) < 2_s && _flight_phase_estimation_sub.get().flight_phase == flight_phase_estimation_s::FLIGHT_PHASE_LEVEL)) { - // only update with positive numbers - _current_average_filter_a.update(fmaxf(current_a, 0.f)); + if (_dt > FLT_EPSILON) { + _current_average_filter_a.update(fmaxf(current_a, 0.f), _dt); + + } else { + _current_average_filter_a.update(fmaxf(current_a, 0.f)); + } } } // Remaining time estimation only possible with capacity - if (_params.capacity > 0.f) { - const float remaining_capacity_mah = _state_of_charge * _params.capacity; + if (_capacity_mah > 0.f) { + const float remaining_capacity_mah = _state_of_charge * _capacity_mah; const float current_ma = fmaxf(_current_average_filter_a.getState() * 1e3f, FLT_EPSILON); time_remaining_s = remaining_capacity_mah / current_ma * 3600.f; } @@ -397,7 +401,6 @@ void Battery::updateParams() param_get(_param_handles.v_empty, &_params.v_empty); param_get(_param_handles.v_charged, &_params.v_charged); param_get(_param_handles.n_cells, &_params.n_cells); - param_get(_param_handles.capacity, &_params.capacity); param_get(_param_handles.r_internal, &_params.r_internal); param_get(_param_handles.source, &_params.source); param_get(_param_handles.low_thr, &_params.low_thr); @@ -405,6 +408,10 @@ void Battery::updateParams() param_get(_param_handles.emergen_thr, &_params.emergen_thr); param_get(_param_handles.bat_avrg_current, &_params.bat_avrg_current); + float capacity{0.f}; + param_get(_param_handles.capacity, &capacity); + setCapacityMah(capacity); + if (n_cells != _params.n_cells) { _internal_resistance_initialized = false; } diff --git a/src/lib/battery/battery.h b/src/lib/battery/battery.h index baf6e5ecd6..66dd73bf27 100644 --- a/src/lib/battery/battery.h +++ b/src/lib/battery/battery.h @@ -88,7 +88,8 @@ public: void setPriority(const uint8_t priority) { _priority = priority; } void setConnected(const bool connected) { _connected = connected; } - void setStateOfCharge(const float soc) { _state_of_charge = soc; _external_state_of_charge = true; } + void setStateOfCharge(const float soc) { _state_of_charge = math::constrain(soc, 0.f, 1.f); _external_state_of_charge = true; } + void setCapacityMah(const float capacity) { _capacity_mah = math::max(capacity, 0.f); } void updateVoltage(const float voltage_v); void updateCurrent(const float current_a); void updateTemperature(const float temperature_c); @@ -101,6 +102,7 @@ public: void updateBatteryStatus(const hrt_abstime ×tamp); battery_status_s getBatteryStatus(); + float getCurrentAverage() const { return PX4_ISFINITE(_current_average_filter_a.getState()) ? _current_average_filter_a.getState() : -1.f; } void publishBatteryStatus(const battery_status_s &battery_status); /** @@ -110,6 +112,27 @@ public: */ void updateAndPublishBatteryStatus(const hrt_abstime ×tamp); + /** + * Calculates how much time is left before the battery is depleted, + * given the heavily low-pass filtered current consumption. + * Requires the capacity and state of charge e.g. externally set through setCapacity() and setStateOfCharge(). + * + * @param current_a The current draw from the battery in amperes. + * @return Estimated remaining time in seconds. + */ + float computeRemainingTime(float current_a); + + /** + * Updates coulomb counting + * Requires a dt, seeupdateDt() + * + * @param current_a Positive current draw in A + * @return Accumulated used capacity in mAh + */ + float sumDischarged(float current_a); + uint8_t determineWarning(float state_of_charge); + void updateDt(const hrt_abstime ×tamp); + protected: static constexpr float LITHIUM_BATTERY_RECOGNITION_VOLTAGE = 2.1f; @@ -130,7 +153,6 @@ protected: float v_empty; float v_charged; int32_t n_cells; - float capacity; float r_internal; float low_thr; float crit_thr; @@ -145,13 +167,10 @@ protected: void updateParams() override; private: - void sumDischarged(const hrt_abstime ×tamp, float current_a); float calculateStateOfChargeVoltageBased(const float voltage_v, const float current_a); void estimateStateOfCharge(); - uint8_t determineWarning(float state_of_charge); uint16_t determineFaults(); void computeScale(); - float computeRemainingTime(float current_a); uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; uORB::SubscriptionData _flight_phase_estimation_sub{ORB_ID(flight_phase_estimation)}; @@ -176,6 +195,8 @@ private: float _state_of_charge{-1.f}; // [0,1] float _scale{1.f}; uint8_t _warning{battery_status_s::WARNING_NONE}; + float _dt{0.f}; + float _capacity_mah{0.f}; hrt_abstime _last_timestamp{0}; bool _armed{false}; bool _vehicle_status_is_fw{false}; From 5f5a1aa4ab9343a8895f5b2d984dfc0045c128ff Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 5 Sep 2025 16:28:09 +0200 Subject: [PATCH 010/812] Mavlink stream low bandwidth: add some important missing ones, update rates (#25524) * mavlink stream low bandwidth: add GLOBAL_POSITION Signed-off-by: Silvan * mavlink stream low bandwidth: add FIGURE_EIGHT_EXECUTION_STATUS Signed-off-by: Silvan * mavlink stream low bandwidth: increase sending rate for all positioning messages to 2Hz Signed-off-by: Silvan * mavlink stream low bandwidth: reduce sending rate for a couple of status messages Signed-off-by: Silvan * mavlink stream low bandwidth: add ATTITUDE_QUATERNION Signed-off-by: Silvan * mavlink stream low bandwidth: use ATTITUDE_QUATERNION instead of ATTITUDE as its preferred by GCS * mavlink stream low bandwidth: add RAW_RPM for vehicles with ICE * mavlink stream low bandwidth: increase VFR_HUD rate * mavlink stream low bandwidth: decrease FIGURE_EIGHT_EXECUTION_STATUS rate --------- Signed-off-by: Silvan Co-authored-by: Alexander Lerach --- src/modules/mavlink/mavlink_main.cpp | 31 ++++++++++++++++------------ 1 file changed, 18 insertions(+), 13 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index ab321edbe1..f0a693b085 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1816,18 +1816,18 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("TIMESYNC", 10.0f); configure_stream_local("CAMERA_TRIGGER", 2.0f); configure_stream_local("LOCAL_POSITION_NED", 1.0f); - configure_stream_local("ATTITUDE", 1.0f); + configure_stream_local("ATTITUDE_QUATERNION", 2.0f); configure_stream_local("ALTITUDE", 1.0f); - configure_stream_local("DISTANCE_SENSOR", 2.0f); + configure_stream_local("DISTANCE_SENSOR", 1.0f); configure_stream_local("MOUNT_ORIENTATION", 2.0f); configure_stream_local("OBSTACLE_DISTANCE", 2.0f); configure_stream_local("GIMBAL_DEVICE_ATTITUDE_STATUS", 1.0f); configure_stream_local("GIMBAL_MANAGER_STATUS", 0.5f); configure_stream_local("GIMBAL_DEVICE_SET_ATTITUDE", 2.0f); - configure_stream_local("ESC_INFO", 1.0f); - configure_stream_local("ESC_STATUS", 2.0f); + configure_stream_local("ESC_INFO", 0.2f); + configure_stream_local("ESC_STATUS", 0.5f); - configure_stream_local("ADSB_VEHICLE", 2.0f); + configure_stream_local("ADSB_VEHICLE", 1.0f); configure_stream_local("ATTITUDE_TARGET", 0.5f); configure_stream_local("AVAILABLE_MODES", 0.3f); configure_stream_local("BATTERY_STATUS", 0.5f); @@ -1835,25 +1835,30 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("CURRENT_MODE", 0.5f); configure_stream_local("ESTIMATOR_STATUS", 1.0f); configure_stream_local("EXTENDED_SYS_STATE", 0.5f); - configure_stream_local("GLOBAL_POSITION_INT", 1.0f); + configure_stream_local("GLOBAL_POSITION_INT", 2.0f); + configure_stream_local("GLOBAL_POSITION", 2.0f); configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f); configure_stream_local("GPS2_RAW", 2.0f); configure_stream_local("GPS_RAW_INT", 2.0f); configure_stream_local("HOME_POSITION", 0.5f); - configure_stream_local("NAV_CONTROLLER_OUTPUT", 1.5f); - configure_stream_local("OPTICAL_FLOW_RAD", 1.0f); - configure_stream_local("ORBIT_EXECUTION_STATUS", 2.0f); + configure_stream_local("NAV_CONTROLLER_OUTPUT", 0.1f); + configure_stream_local("OPTICAL_FLOW_RAD", 0.1f); + configure_stream_local("ORBIT_EXECUTION_STATUS", 1.0f); configure_stream_local("PING", 0.1f); - configure_stream_local("POSITION_TARGET_GLOBAL_INT", 1.0f); - configure_stream_local("POSITION_TARGET_LOCAL_NED", 1.0f); + configure_stream_local("POSITION_TARGET_GLOBAL_INT", 0.5f); + configure_stream_local("POSITION_TARGET_LOCAL_NED", 0.5f); + configure_stream_local("RAW_RPM", 1.0f); configure_stream_local("RC_CHANNELS", 5.0f); - configure_stream_local("SERVO_OUTPUT_RAW_0", 1.0f); + configure_stream_local("SERVO_OUTPUT_RAW_0", 0.1f); configure_stream_local("SYS_STATUS", 0.5f); configure_stream_local("SYSTEM_TIME", 2.0f); configure_stream_local("TIME_ESTIMATE_TO_TARGET", 0.5f); - configure_stream_local("VFR_HUD", 1.0f); + configure_stream_local("VFR_HUD", 1.5f); configure_stream_local("VIBRATION", 0.1f); configure_stream_local("WIND_COV", 0.1f); +#if defined(MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS) + configure_stream_local("FIGURE_EIGHT_EXECUTION_STATUS", 0.5f); +#endif // MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS break; case MAVLINK_MODE_UAVIONIX: From fd2b7cbea42239e329ba19c6b0558625b91c6e3a Mon Sep 17 00:00:00 2001 From: Alexander Lerach Date: Fri, 5 Sep 2025 17:46:32 +0200 Subject: [PATCH 011/812] gps: update submodule (#25529) --- src/drivers/gps/devices | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/gps/devices b/src/drivers/gps/devices index 8fdef3bc0c..0b9695881b 160000 --- a/src/drivers/gps/devices +++ b/src/drivers/gps/devices @@ -1 +1 @@ -Subproject commit 8fdef3bc0cb7820119abdb7320ad3992af2e440f +Subproject commit 0b9695881bd1e8f830ab4538ab3acc0050019eba From 63e257782ac5a3578f9f5c380ff57e8f2dc9d9f9 Mon Sep 17 00:00:00 2001 From: renjieDLUT <41196373+renjieDLUT@users.noreply.github.com> Date: Mon, 8 Sep 2025 09:58:12 +0800 Subject: [PATCH 012/812] Update accelerometer.md (#25532) --- docs/en/sensor/accelerometer.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/en/sensor/accelerometer.md b/docs/en/sensor/accelerometer.md index da249b1934..6de3d5bd21 100644 --- a/docs/en/sensor/accelerometer.md +++ b/docs/en/sensor/accelerometer.md @@ -5,7 +5,7 @@ PX4 uses accelerometer data for velocity estimation. You should not need to attach an accelometer as a stand-alone external device: - Most flight controllers, such as those in the [Pixhawk Series](../flight_controller/pixhawk_series.md), include an accelerometer as part of the flight controller's [Inertial Motion Unit (IMU)](https://en.wikipedia.org/wiki/Inertial_measurement_unit). -- Gyroscopes are present as part of an [external INS, ARHS or INS-enhanced GNSS system](../sensor/inertial_navigation_systems.md). +- Gyroscopes are present as part of an [external INS, AHRS or INS-enhanced GNSS system](../sensor/inertial_navigation_systems.md). The accelerometer must be calibrated before first use of the vehicle: From 3962419669cacbbde9f4d6343d75e5fe625f32ab Mon Sep 17 00:00:00 2001 From: renjieDLUT <41196373+renjieDLUT@users.noreply.github.com> Date: Mon, 8 Sep 2025 09:58:33 +0800 Subject: [PATCH 013/812] Update _assembly.md (#25527) --- docs/en/assembly/_assembly.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/en/assembly/_assembly.md b/docs/en/assembly/_assembly.md index ef641c6a70..a704ce788a 100644 --- a/docs/en/assembly/_assembly.md +++ b/docs/en/assembly/_assembly.md @@ -290,7 +290,7 @@ If you're using [DroneCAN ESC](../peripherals/esc_motors.md#dronecan) the contro ### Flight Controller Power Pixhawk FCs require a regulated power supply that can supply at around 5V/3A continuous (check your specific FC)! -This is sufficient to power the controller itself and a few low-power peripherals, such as a GNSS module, RC transmitter, and low power telemetry radio, but not for motors, actuators, and other peripherals. +This is sufficient to power the controller itself and a few low-power peripherals, such as a GNSS module, RC receiver, and low power telemetry radio, but not for motors, actuators, and other peripherals. [Power modules](../power_module/index.md) are commonly used to "split off" this regulated power supply for the FC and also to provide measurements of the battery voltage and total current to the whole system — which PX4 can use to estimate power levels. The power module is connected to the FC power port, which is normally labeled `POWER` (or `POWER 1` or `POWER 2` for FCs that have redundant power supply). From e0cdcdb43619ea545e982375b5e2d9c6aca21b10 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 24 Jun 2025 17:48:04 +0200 Subject: [PATCH 014/812] Remove COM_POSCTL_NAVL In an effort to reduce configuration space. I've not seen use for this option. If a pilot flies manually in position mode he has some visual reference of the vehicle and can do better than an autonomous mode without position reference. Also by now we have nudging in Descend mode so the pilot can still give input and the only difference is it automatically goes down instead of the pilot having to descend by stick to land. --- .../airframes/60002_gz_uuv_bluerov2_heavy | 1 - .../init.d-posix/airframes/70000_gz_atmos | 1 - .../init.d/airframes/60002_uuv_bluerov2_heavy | 1 - .../init.d/airframes/70000_atmos | 1 - .../amovlabf410_drone_v1.15.4.params | 5 +- docs/en/config/safety.md | 12 ----- src/modules/commander/Commander.hpp | 2 +- src/modules/commander/UserModeIntention.cpp | 6 +-- src/modules/commander/UserModeIntention.hpp | 9 +--- src/modules/commander/commander_params.c | 12 ----- src/modules/commander/failsafe/failsafe.cpp | 50 +++++-------------- src/modules/commander/failsafe/failsafe.h | 6 --- 12 files changed, 20 insertions(+), 86 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/60002_gz_uuv_bluerov2_heavy b/ROMFS/px4fmu_common/init.d-posix/airframes/60002_gz_uuv_bluerov2_heavy index 287589a052..b80bf079b7 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/60002_gz_uuv_bluerov2_heavy +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/60002_gz_uuv_bluerov2_heavy @@ -34,7 +34,6 @@ param set-default COM_LOW_BAT_ACT 0 param set-default NAV_DLL_ACT 0 param set-default GF_ACTION 1 param set-default NAV_RCL_ACT 1 -param set-default COM_POSCTL_NAVL 2 # disable attitude failure detection param set-default FD_FAIL_P 0 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/70000_gz_atmos b/ROMFS/px4fmu_common/init.d-posix/airframes/70000_gz_atmos index c539586ae5..49ef971307 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/70000_gz_atmos +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/70000_gz_atmos @@ -45,7 +45,6 @@ param set-default COM_LOW_BAT_ACT 0 param set-default NAV_DLL_ACT 0 param set-default GF_ACTION 1 param set-default NAV_RCL_ACT 1 -param set-default COM_POSCTL_NAVL 2 # disable attitude failure detection param set-default FD_FAIL_P 0 diff --git a/ROMFS/px4fmu_common/init.d/airframes/60002_uuv_bluerov2_heavy b/ROMFS/px4fmu_common/init.d/airframes/60002_uuv_bluerov2_heavy index d397e5deae..7ad928367d 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/60002_uuv_bluerov2_heavy +++ b/ROMFS/px4fmu_common/init.d/airframes/60002_uuv_bluerov2_heavy @@ -45,7 +45,6 @@ param set-default COM_LOW_BAT_ACT 0 param set-default NAV_DLL_ACT 0 param set-default GF_ACTION 1 param set-default NAV_RCL_ACT 1 -param set-default COM_POSCTL_NAVL 2 # disable attitude failure detection param set-default FD_FAIL_P 0 diff --git a/ROMFS/px4fmu_common/init.d/airframes/70000_atmos b/ROMFS/px4fmu_common/init.d/airframes/70000_atmos index 37b676cef1..3ad05a85e0 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/70000_atmos +++ b/ROMFS/px4fmu_common/init.d/airframes/70000_atmos @@ -35,7 +35,6 @@ param set-default COM_LOW_BAT_ACT 0 param set-default NAV_DLL_ACT 0 param set-default GF_ACTION 1 param set-default NAV_RCL_ACT 1 -param set-default COM_POSCTL_NAVL 2 # Set Mocap Vision frame param set EKF2_EV_CTRL 15 diff --git a/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params b/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params index f80c1b5a3a..0d16ea9f01 100644 --- a/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params +++ b/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params @@ -1,8 +1,8 @@ # Onboard parameters for Vehicle 1 # # Stack: PX4 Pro -# Vehicle: -# Version: 1.15.4 +# Vehicle: Multi-Rotor +# Version: 1.15.4 # Git Revision: 99c40407ff000000 # # Vehicle-Id Component-Id Name Value Type @@ -318,7 +318,6 @@ 1 1 COM_OBS_AVOID 0 6 1 1 COM_OF_LOSS_T 1.000000000000000000 9 1 1 COM_PARACHUTE 0 6 -1 1 COM_POSCTL_NAVL 0 6 1 1 COM_POS_FS_DELAY 1 6 1 1 COM_POS_FS_EPH 5.000000000000000000 9 1 1 COM_POS_LOW_EPH -1.000000000000000000 9 diff --git a/docs/en/config/safety.md b/docs/en/config/safety.md index 92a302ad3e..a741030744 100644 --- a/docs/en/config/safety.md +++ b/docs/en/config/safety.md @@ -206,23 +206,11 @@ The relevant parameters shown below. ### Position Loss Failsafe Action -The failure action is controlled by [COM_POSCTL_NAVL](../advanced_config/parameter_reference.md#COM_POSCTL_NAVL), based on whether RC control is assumed to be available (and altitude information): - -- `0`: Remote control available. - Switch to _Altitude mode_ if a height estimate is available, otherwise _Stabilized mode_. -- `1`: Remote control _not_ available. - Switch to _Descend mode_ if a height estimate is available, otherwise enter flight termination. - _Descend mode_ is a landing mode that does not require a position estimate. - Fixed-wing planes, and VTOLs not configured to land in hover ([NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT)), have a parameter ([FW_GPSF_LT](../advanced_config/parameter_reference.md#FW_GPSF_LT)) that defines how long they will loiter (circle with a constant roll angle ([FW_GPSF_R](../advanced_config/parameter_reference.md#FW_GPSF_R)) at the current altitude) after losing position before attempting to land. If VTOLs have are configured to switch to hover for landing ([NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT)) then they will first transition and then descend. The relevant parameters for all vehicles shown below. -| Parameter | Description | -| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------- | -| [COM_POSCTL_NAVL](../advanced_config/parameter_reference.md#COM_POSCTL_NAVL) | Position control navigation loss response during mission. Values: `0` - assume use of RC, `1` - Assume no RC. | - Parameters that only affect Fixed-wing vehicles: | Parameter | Description | diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp index 1d7841cdc8..e079d13ee8 100644 --- a/src/modules/commander/Commander.hpp +++ b/src/modules/commander/Commander.hpp @@ -230,7 +230,7 @@ private: _health_and_arming_checks.externalChecks() #endif }; - UserModeIntention _user_mode_intention {this, _vehicle_status, _health_and_arming_checks, &_mode_management}; + UserModeIntention _user_mode_intention {_vehicle_status, _health_and_arming_checks, &_mode_management}; const failsafe_flags_s &_failsafe_flags{_health_and_arming_checks.failsafeFlags()}; HomePosition _home_position{_failsafe_flags}; diff --git a/src/modules/commander/UserModeIntention.cpp b/src/modules/commander/UserModeIntention.cpp index 086f9501b3..556bddbd18 100644 --- a/src/modules/commander/UserModeIntention.cpp +++ b/src/modules/commander/UserModeIntention.cpp @@ -34,9 +34,9 @@ #include "UserModeIntention.hpp" -UserModeIntention::UserModeIntention(ModuleParams *parent, const vehicle_status_s &vehicle_status, +UserModeIntention::UserModeIntention(const vehicle_status_s &vehicle_status, const HealthAndArmingChecks &health_and_arming_checks, ModeChangeHandler *handler) - : ModuleParams(parent), _vehicle_status(vehicle_status), _health_and_arming_checks(health_and_arming_checks), + : _vehicle_status(vehicle_status), _health_and_arming_checks(health_and_arming_checks), _handler(handler) { } @@ -59,7 +59,7 @@ bool UserModeIntention::change(uint8_t user_intended_nav_state, ModeChangeSource allow_change = _health_and_arming_checks.canRun(user_intended_nav_state); // Check fallback - if (!allow_change && allow_fallback && _param_com_posctl_navl.get() == 0) { + if (!allow_change && allow_fallback) { if (user_intended_nav_state == vehicle_status_s::NAVIGATION_STATE_POSCTL) { allow_change = _health_and_arming_checks.canRun(vehicle_status_s::NAVIGATION_STATE_ALTCTL); // We still use the original user intended mode. The failsafe state machine will then set the diff --git a/src/modules/commander/UserModeIntention.hpp b/src/modules/commander/UserModeIntention.hpp index b8b6827e06..cfb4e3998b 100644 --- a/src/modules/commander/UserModeIntention.hpp +++ b/src/modules/commander/UserModeIntention.hpp @@ -35,7 +35,6 @@ #include #include "HealthAndArmingChecks/HealthAndArmingChecks.hpp" -#include enum class ModeChangeSource { User, ///< RC or MAVLink @@ -58,10 +57,10 @@ public: }; -class UserModeIntention : ModuleParams +class UserModeIntention { public: - UserModeIntention(ModuleParams *parent, const vehicle_status_s &vehicle_status, + UserModeIntention(const vehicle_status_s &vehicle_status, const HealthAndArmingChecks &health_and_arming_checks, ModeChangeHandler *handler); ~UserModeIntention() = default; @@ -102,8 +101,4 @@ private: bool _ever_had_mode_change{false}; ///< true if there was ever a mode change call (also if the same mode as already set) bool _had_mode_change{false}; ///< true if there was a mode change call since the last getHadModeChangeAndClear() - - DEFINE_PARAMETERS( - (ParamInt) _param_com_posctl_navl - ); }; diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index 565c6406be..1e194ac5df 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -461,18 +461,6 @@ PARAM_DEFINE_FLOAT(COM_RC_STICK_OV, 30.0f); */ PARAM_DEFINE_INT32(COM_ARM_MIS_REQ, 0); -/** - * Position mode navigation loss response - * - * This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control in manual Position mode. - * - * @value 0 Altitude mode - * @value 1 Land mode (descend) - * - * @group Commander - */ -PARAM_DEFINE_INT32(COM_POSCTL_NAVL, 0); - /** * Require arm authorization to arm * diff --git a/src/modules/commander/failsafe/failsafe.cpp b/src/modules/commander/failsafe/failsafe.cpp index 5c3578fb89..cdc770190c 100644 --- a/src/modules/commander/failsafe/failsafe.cpp +++ b/src/modules/commander/failsafe/failsafe.cpp @@ -668,46 +668,20 @@ FailsafeBase::Action Failsafe::checkModeFallback(const failsafe_flags_s &status_ } } - // posctrl - switch (position_control_navigation_loss_response(_param_com_posctl_navl.get())) { - case position_control_navigation_loss_response::Altitude_Manual: // AltCtrl/Manual - - // PosCtrl/PositionSlow -> AltCtrl - if ((user_intended_mode == vehicle_status_s::NAVIGATION_STATE_POSCTL || - user_intended_mode == vehicle_status_s::NAVIGATION_STATE_POSITION_SLOW) - && !modeCanRun(status_flags, user_intended_mode)) { - action = Action::FallbackAltCtrl; - user_intended_mode = vehicle_status_s::NAVIGATION_STATE_ALTCTL; - } - - // AltCtrl -> Stabilized - if (user_intended_mode == vehicle_status_s::NAVIGATION_STATE_ALTCTL - && !modeCanRun(status_flags, user_intended_mode)) { - action = Action::FallbackStab; - user_intended_mode = vehicle_status_s::NAVIGATION_STATE_STAB; - } - - break; - - case position_control_navigation_loss_response::Land_Descend: // Land/Terminate - - // PosCtrl/PositionSlow -> Land - if ((user_intended_mode == vehicle_status_s::NAVIGATION_STATE_POSCTL || - user_intended_mode == vehicle_status_s::NAVIGATION_STATE_POSITION_SLOW) - && !modeCanRun(status_flags, user_intended_mode)) { - action = Action::Land; - user_intended_mode = vehicle_status_s::NAVIGATION_STATE_AUTO_LAND; - - // Land -> Descend - if (!modeCanRun(status_flags, user_intended_mode)) { - action = Action::Descend; - user_intended_mode = vehicle_status_s::NAVIGATION_STATE_DESCEND; - } - } - - break; + // PosCtrl/PositionSlow -> AltCtrl + if ((user_intended_mode == vehicle_status_s::NAVIGATION_STATE_POSCTL || + user_intended_mode == vehicle_status_s::NAVIGATION_STATE_POSITION_SLOW) + && !modeCanRun(status_flags, user_intended_mode)) { + action = Action::FallbackAltCtrl; + user_intended_mode = vehicle_status_s::NAVIGATION_STATE_ALTCTL; } + // AltCtrl -> Stabilized + if (user_intended_mode == vehicle_status_s::NAVIGATION_STATE_ALTCTL + && !modeCanRun(status_flags, user_intended_mode)) { + action = Action::FallbackStab; + user_intended_mode = vehicle_status_s::NAVIGATION_STATE_STAB; + } // Last, check can_run for intended mode if (!modeCanRun(status_flags, user_intended_mode)) { diff --git a/src/modules/commander/failsafe/failsafe.h b/src/modules/commander/failsafe/failsafe.h index d7ac7c75c2..f9382e0428 100644 --- a/src/modules/commander/failsafe/failsafe.h +++ b/src/modules/commander/failsafe/failsafe.h @@ -85,11 +85,6 @@ private: Disarm = 7, }; - enum class position_control_navigation_loss_response : int32_t { - Altitude_Manual = 0, - Land_Descend = 1, - }; - enum class actuator_failure_failsafe_mode : int32_t { Warning_only = 0, Hold_mode = 1, @@ -202,7 +197,6 @@ private: (ParamInt) _param_com_rcl_except, (ParamInt) _param_com_dll_except, (ParamInt) _param_com_rc_in_mode, - (ParamInt) _param_com_posctl_navl, (ParamInt) _param_gf_action, (ParamFloat) _param_com_spoolup_time, (ParamInt) _param_com_imb_prop_act, From 63ec2f0406a437253da6b3467db1636f93236f1c Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Mon, 18 Aug 2025 18:26:29 +0200 Subject: [PATCH 015/812] docs/safety: clarification for position loss in manual position controlled flight Co-authored-by: Hamish Willee --- docs/en/config/safety.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/docs/en/config/safety.md b/docs/en/config/safety.md index a741030744..a01a6c6bb7 100644 --- a/docs/en/config/safety.md +++ b/docs/en/config/safety.md @@ -206,6 +206,8 @@ The relevant parameters shown below. ### Position Loss Failsafe Action +Multicopters will switch to [Altitude mode](../flight_modes_mc/altitude.md) if a height estimate is available, otherwise [Stabilized mode](../flight_modes_mc/manual_stabilized.md). + Fixed-wing planes, and VTOLs not configured to land in hover ([NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT)), have a parameter ([FW_GPSF_LT](../advanced_config/parameter_reference.md#FW_GPSF_LT)) that defines how long they will loiter (circle with a constant roll angle ([FW_GPSF_R](../advanced_config/parameter_reference.md#FW_GPSF_R)) at the current altitude) after losing position before attempting to land. If VTOLs have are configured to switch to hover for landing ([NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT)) then they will first transition and then descend. From b4395d59603cb177bd4d9745dbbfaf40d0a77c5c Mon Sep 17 00:00:00 2001 From: Pernilla Date: Wed, 10 Sep 2025 10:18:09 +0200 Subject: [PATCH 016/812] FlightTaskManualAcceleration: fix velocity constraint overwriting + altitude limit slow down - The velocity constraint gets set from multiple places e.g. Position slow knob and altitude related slow down. Depending on the execution order it was overwritten with a higher value again not obeying a stricter limit. - The slowdown used valocities as inputs instead of the ratio of available altitude. --- .../FlightTaskManualAcceleration.cpp | 7 +++--- .../tasks/Utility/StickAccelerationXY.cpp | 25 ++++++++++--------- .../tasks/Utility/StickAccelerationXY.hpp | 10 +++++--- 3 files changed, 22 insertions(+), 20 deletions(-) diff --git a/src/modules/flight_mode_manager/tasks/ManualAcceleration/FlightTaskManualAcceleration.cpp b/src/modules/flight_mode_manager/tasks/ManualAcceleration/FlightTaskManualAcceleration.cpp index 788b7cf989..f73fbe4023 100644 --- a/src/modules/flight_mode_manager/tasks/ManualAcceleration/FlightTaskManualAcceleration.cpp +++ b/src/modules/flight_mode_manager/tasks/ManualAcceleration/FlightTaskManualAcceleration.cpp @@ -74,12 +74,11 @@ bool FlightTaskManualAcceleration::update() static constexpr float min_vel = 2.f; // minimum max-velocity near max_hagl if (max_hagl_ratio > factor_threshold) { - max_hagl_ratio = math::min(max_hagl_ratio, 1.f); const float vxy_max = math::min(vehicle_local_pos.vxy_max, _param_mpc_vel_manual.get()); - _stick_acceleration_xy.setVelocityConstraint(interpolate(vxy_max, factor_threshold, min_vel, vxy_max, min_vel)); + _stick_acceleration_xy.setVelocityConstraint(interpolate(max_hagl_ratio, factor_threshold, 1.f, vxy_max, min_vel)); - } else { - _stick_acceleration_xy.setVelocityConstraint(math::min(_param_mpc_vel_manual.get(), vehicle_local_pos.vxy_max)); + } else if (PX4_ISFINITE(vehicle_local_pos.vxy_max)) { + _stick_acceleration_xy.setVelocityConstraint(vehicle_local_pos.vxy_max); } _stick_acceleration_xy.generateSetpoints(_sticks.getPitchRollExpo(), _yaw, _yaw_setpoint, _position, diff --git a/src/modules/flight_mode_manager/tasks/Utility/StickAccelerationXY.cpp b/src/modules/flight_mode_manager/tasks/Utility/StickAccelerationXY.cpp index 052378244b..686db33a88 100644 --- a/src/modules/flight_mode_manager/tasks/Utility/StickAccelerationXY.cpp +++ b/src/modules/flight_mode_manager/tasks/Utility/StickAccelerationXY.cpp @@ -43,6 +43,8 @@ StickAccelerationXY::StickAccelerationXY(ModuleParams *parent) : { _brake_boost_filter.reset(1.f); resetPosition(); + _velocity_slew_rate_xy.setSlewRate(_param_mpc_acc_hor.get()); + _velocity_slew_rate_xy.setForcedValue(_param_mpc_vel_manual.get()); } void StickAccelerationXY::resetPosition() @@ -75,23 +77,22 @@ void StickAccelerationXY::resetAcceleration(const matrix::Vector2f &acceleration } } +void StickAccelerationXY::setVelocityConstraint(float vel) +{ + if ((vel < _velocity_constraint) && (vel >= FLT_EPSILON)) { + _velocity_constraint = vel; + } +}; + void StickAccelerationXY::generateSetpoints(Vector2f stick_xy, const float yaw, const float yaw_sp, const Vector3f &pos, const matrix::Vector2f &vel_sp_feedback, const float dt) { - // gradually adjust velocity constraint because good tracking is required for the drag estimation - if (fabsf(_targeted_velocity_constraint - _current_velocity_constraint) > 0.1f) { - if (!PX4_ISFINITE(_current_velocity_constraint) || !PX4_ISFINITE(_targeted_velocity_constraint)) { - _current_velocity_constraint = _targeted_velocity_constraint; - - } else { - _current_velocity_constraint = math::constrain(_targeted_velocity_constraint, - _current_velocity_constraint - dt * _param_mpc_acc_hor.get(), - _current_velocity_constraint + dt * _param_mpc_acc_hor.get()); - } - } + // avoid setpoint steps from limit changes to improve velocity tracking and hence drag estimation + const float velocity_constraint = _velocity_slew_rate_xy.update(_velocity_constraint, dt); + _velocity_constraint = _param_mpc_vel_manual.get(); // reset, reduced to strictest limit in next loop // maximum commanded velocity can be constrained dynamically - const float velocity_sc = fminf(_param_mpc_vel_manual.get(), _current_velocity_constraint); + const float velocity_sc = fminf(_param_mpc_vel_manual.get(), velocity_constraint); Vector2f velocity_scale(velocity_sc, velocity_sc); // maximum commanded acceleration is scaled down with velocity const float acceleration_sc = _param_mpc_acc_hor.get() * (velocity_sc / _param_mpc_vel_manual.get()); diff --git a/src/modules/flight_mode_manager/tasks/Utility/StickAccelerationXY.hpp b/src/modules/flight_mode_manager/tasks/Utility/StickAccelerationXY.hpp index ad6f4afec1..feb4070643 100644 --- a/src/modules/flight_mode_manager/tasks/Utility/StickAccelerationXY.hpp +++ b/src/modules/flight_mode_manager/tasks/Utility/StickAccelerationXY.hpp @@ -64,8 +64,10 @@ public: void getSetpoints(matrix::Vector3f &pos_sp, matrix::Vector3f &vel_sp, matrix::Vector3f &acc_sp); float getMaxAcceleration() { return _param_mpc_acc_hor.get(); }; float getMaxJerk() { return _param_mpc_jerk_max.get(); }; - void setVelocityConstraint(float vel) { _targeted_velocity_constraint = fmaxf(vel, FLT_EPSILON); }; - float getVelocityConstraint() { return _current_velocity_constraint; }; + + // Assuming the velocity constraint resets in every loop and update constraint if new value is lower + void setVelocityConstraint(float vel); + float getVelocityConstraint() { return _velocity_slew_rate_xy.getState(); }; private: CollisionPrevention _collision_prevention{this}; @@ -80,6 +82,7 @@ private: SlewRate _acceleration_slew_rate_x; SlewRate _acceleration_slew_rate_y; + SlewRate _velocity_slew_rate_xy; AlphaFilter _brake_boost_filter; matrix::Vector2f _position_setpoint; @@ -87,8 +90,7 @@ private: matrix::Vector2f _acceleration_setpoint; matrix::Vector2f _acceleration_setpoint_prev; - float _targeted_velocity_constraint{INFINITY}; - float _current_velocity_constraint{INFINITY}; + float _velocity_constraint{INFINITY}; DEFINE_PARAMETERS( (ParamFloat) _param_mpc_vel_manual, From 472e0657b54d7baf88fe180f75357be1fceefbab Mon Sep 17 00:00:00 2001 From: rmahoney-skai <108757420+rmahoney-skai@users.noreply.github.com> Date: Wed, 10 Sep 2025 15:09:22 -0400 Subject: [PATCH 017/812] Corrected max number of submodules displayed in VSCode (#25539) Co-authored-by: rmahoney_skai --- .vscode/settings.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.vscode/settings.json b/.vscode/settings.json index 1e799721ce..135a643316 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -43,7 +43,7 @@ "files.watcherExclude": { "**/build/**": true }, - "git.detectSubmodulesLimit": 20, + "git.detectSubmodulesLimit": 25, "git.ignoreLimitWarning": true, "githubPullRequests.defaultMergeMethod": "squash", "githubPullRequests.telemetry.enabled": false, From 2e84e55d930c691adf453b23a174810b79cc61b5 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Thu, 11 Sep 2025 08:29:25 +1000 Subject: [PATCH 018/812] New Crowdin translations - zh-CN (#25483) Co-authored-by: Crowdin Bot --- docs/zh/SUMMARY.md | 2 + docs/zh/advanced/gimbal_control.md | 2 +- docs/zh/advanced/system_tunes.md | 2 +- ..._flight_controller_orientation_leveling.md | 2 +- docs/zh/advanced_config/bootloader_update.md | 112 ++++----- .../compass_power_compensation.md | 2 +- docs/zh/advanced_config/esc_calibration.md | 28 +-- docs/zh/advanced_config/ethernet_setup.md | 122 ++++----- docs/zh/advanced_config/prearm_arm_disarm.md | 50 ++-- .../sensor_thermal_calibration.md | 8 +- docs/zh/advanced_config/tuning_the_ecl_ekf.md | 42 ++-- docs/zh/advanced_features/precland.md | 8 +- docs/zh/advanced_features/satcom_roadblock.md | 126 +++++----- docs/zh/camera/fc_connected_camera.md | 12 +- docs/zh/camera/mavlink_v1_camera.md | 2 +- docs/zh/camera/mavlink_v2_camera.md | 2 +- .../holybro_pixhawk_jetson_baseboard.md | 134 +++++----- .../holybro_pixhawk_rpi_cm4_baseboard.md | 62 ++--- docs/zh/companion_computer/pixhawk_rpi.md | 158 ++++++------ .../video_streaming_wfb_ng_wifi.md | 14 +- .../complete_vehicles_mc/amov_F410_drone.md | 2 +- docs/zh/complete_vehicles_mc/crazyflie2.md | 56 ++--- docs/zh/complete_vehicles_mc/crazyflie21.md | 80 +++--- .../complete_vehicles_mc/modalai_starling.md | 12 +- .../zh/complete_vehicles_mc/px4_vision_kit.md | 158 ++++++------ docs/zh/complete_vehicles_rover/aion_r1.md | 24 +- .../computer_vision/collision_prevention.md | 114 ++++----- .../visual_inertial_odometry.md | 12 +- docs/zh/concept/flight_tasks.md | 80 +++--- docs/zh/concept/system_startup.md | 31 ++- docs/zh/config/_autotune.md | 36 +-- docs/zh/config/actuators.md | 92 +++---- docs/zh/config/airspeed.md | 10 +- docs/zh/config/compass.md | 30 +-- docs/zh/config/firmware.md | 4 +- docs/zh/config/flight_mode.md | 20 +- docs/zh/config/safety_simulation.md | 2 +- docs/zh/config_fw/trimming_guide_fixedwing.md | 6 +- docs/zh/config_heli/index.md | 16 +- docs/zh/config_mc/filter_tuning.md | 12 +- .../pid_tuning_guide_multicopter_basic.md | 70 +++--- docs/zh/config_rover/basic_setup.md | 65 ++++- docs/zh/config_rover/index.md | 16 +- docs/zh/config_rover/velocity_tuning.md | 2 +- .../zh/config_vtol/vtol_quad_configuration.md | 2 +- docs/zh/contribute/docs.md | 202 +++++++-------- docs/zh/contribute/git_examples.md | 56 ++--- docs/zh/debug/eclipse_jlink.md | 34 +-- docs/zh/debug/failure_injection.md | 12 +- docs/zh/dev_airframes/adding_a_new_frame.md | 56 ++--- docs/zh/dev_log/log_encryption.md | 34 +-- docs/zh/dev_log/logging.md | 13 +- docs/zh/dev_setup/dev_env_linux_ubuntu.md | 22 +- docs/zh/dev_setup/dev_env_mac.md | 78 +++--- .../dev_env_windows_cygwin_packager_setup.md | 14 +- docs/zh/dev_setup/dev_env_windows_vm.md | 20 +- docs/zh/dev_setup/dev_env_windows_wsl.md | 192 +++++++------- docs/zh/dev_setup/vscode.md | 20 +- docs/zh/dronecan/holybro_h_rtk_zed_f9p_gps.md | 20 +- docs/zh/dronecan/pomegranate_systems_pm.md | 10 +- docs/zh/dronecan/raccoonlab_power.md | 4 +- docs/zh/flight_modes_fw/mission.md | 26 +- docs/zh/flight_modes_fw/takeoff.md | 2 +- docs/zh/flight_modes_mc/follow_me.md | 12 +- docs/zh/flight_modes_mc/mission.md | 26 +- docs/zh/flight_modes_mc/throw_launch.md | 28 +-- docs/zh/flying/geofence.md | 2 +- docs/zh/flying/package_delivery_mission.md | 4 +- .../frames_multicopter/dji_f450_cuav_5nano.md | 32 +-- .../frames_multicopter/dji_f450_cuav_5plus.md | 32 +-- .../holybro_qav250_pixhawk4_mini.md | 68 ++--- .../holybro_s500_v2_pixhawk4.md | 128 +++++----- .../holybro_x500V2_pixhawk5x.md | 86 +++---- .../holybro_x500_pixhawk4.md | 108 ++++---- .../holybro_x500v2_pixhawk6c.md | 42 ++-- ...dplane_falcon_vertigo_hybrid_rtf_dropix.md | 60 ++--- .../vtol_quadplane_foxtech_loong_2160.md | 66 ++--- .../vtol_tiltrotor_omp_hobby_zmo_fpv.md | 90 +++---- docs/zh/gps_compass/index.md | 10 +- docs/zh/gps_compass/rtk_gps.md | 28 +-- docs/zh/hardware/board_support_guide.md | 4 +- docs/zh/hardware/porting_guide_nuttx.md | 28 +-- docs/zh/middleware/uxrce_dds.md | 82 +++--- docs/zh/modules/hello_sky.md | 238 +++++++++--------- docs/zh/modules/module_template.md | 30 +-- docs/zh/payloads/generic_actuator_control.md | 2 +- docs/zh/peripherals/gripper.md | 12 +- docs/zh/peripherals/remote_id.md | 8 +- docs/zh/releases/1.14.md | 12 +- docs/zh/ros/mavros_custom_messages.md | 2 +- docs/zh/ros/mavros_installation.md | 22 +- docs/zh/ros/offboard_control.md | 4 +- docs/zh/ros2/px4_ros2_control_interface.md | 132 +++++----- docs/zh/ros2/px4_ros2_msg_translation_node.md | 180 ++++++------- docs/zh/ros2/px4_ros2_navigation_interface.md | 102 ++++---- docs/zh/ros2/user_guide.md | 212 ++++++++-------- docs/zh/sensor/inertial_navigation_systems.md | 23 +- docs/zh/sensor/inertiallabs.md | 8 +- docs/zh/sensor/rangefinders.md | 6 +- docs/zh/sensor/vectornav.md | 16 +- docs/zh/sim_flightgear/index.md | 32 +-- docs/zh/sim_gazebo_classic/index.md | 32 +-- .../multi_vehicle_simulation.md | 104 ++++---- docs/zh/sim_gazebo_gz/gazebo_models.md | 12 +- docs/zh/sim_gazebo_gz/index.md | 66 ++--- docs/zh/sim_gazebo_gz/plugins.md | 4 +- docs/zh/sim_gazebo_gz/tools_avl_automation.md | 40 +-- docs/zh/sim_jmavsim/index.md | 22 +- docs/zh/sim_sih/index.md | 148 +++++++---- docs/zh/simulation/index.md | 18 +- docs/zh/smart_batteries/rotoye_batmon.md | 5 - docs/zh/telemetry/crsf_telemetry.md | 42 ++-- docs/zh/telemetry/jfi_telemetry.md | 6 +- docs/zh/test_and_ci/fuzz_tests.md | 6 +- docs/zh/test_and_ci/index.md | 6 +- .../integration_testing_ros1_mavros.md | 128 +++++----- docs/zh/test_and_ci/test_flights.md | 2 + docs/zh/test_and_ci/unit_tests.md | 40 +-- docs/zh/test_cards/mc_04_failsafe_testing.md | 8 +- docs/zh/test_cards/mc_06_optical_flow.md | 12 +- docs/zh/test_cards/mc_07_vio.md | 52 ++++ docs/zh/test_cards/mc_08_dshot.md | 46 ++++ .../uart/user_configurable_serial_driver.md | 46 ++-- 123 files changed, 2858 insertions(+), 2621 deletions(-) create mode 100644 docs/zh/test_cards/mc_07_vio.md create mode 100644 docs/zh/test_cards/mc_08_dshot.md diff --git a/docs/zh/SUMMARY.md b/docs/zh/SUMMARY.md index 13288443e8..88cb6dc8d8 100644 --- a/docs/zh/SUMMARY.md +++ b/docs/zh/SUMMARY.md @@ -843,6 +843,8 @@ - [测试 MC_04 -故障安全测试](test_cards/mc_04_failsafe_testing.md) - [Test MC_05 - Manual Modes (Inside)](test_cards/mc_05_indoor_flight_manual_modes.md) - [Test MC_06 - Optical Flow (Inside)](test_cards/mc_06_optical_flow.md) + - [Test MC_07 - VIO (Inside)](test_cards/mc_07_vio.md) + - [Test MC_08 - DSHOT ESC](test_cards/mc_08_dshot.md) - [单元测试](test_and_ci/unit_tests.md) - [Fuzz Tests](test_and_ci/fuzz_tests.md) - [持续集成](test_and_ci/continous_integration.md) diff --git a/docs/zh/advanced/gimbal_control.md b/docs/zh/advanced/gimbal_control.md index 5965f81264..aa7fe7ad8c 100644 --- a/docs/zh/advanced/gimbal_control.md +++ b/docs/zh/advanced/gimbal_control.md @@ -131,7 +131,7 @@ The on-screen gimbal control can be used to move/test a connected MAVLink camera 2. Open QGroundControl and enable the on-screen camera control (Application settings). - ![Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../../assets/qgc/fly/gimbal_control_x500gz.png) + ![Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../../assets/qgc/fly/gimbal_control_x500gz.png) 3. Make sure the vehicle is armed and flying, e.g. by entering with `commander takeoff`. diff --git a/docs/zh/advanced/system_tunes.md b/docs/zh/advanced/system_tunes.md index 3feb974a11..70548c0b22 100644 --- a/docs/zh/advanced/system_tunes.md +++ b/docs/zh/advanced/system_tunes.md @@ -52,7 +52,7 @@ On Windows, one option is to use _Melody Master_ within _Dosbox_. 7. 当您准备好时保存音乐: - Press **F2** to give the tune a name and save it in the _/Music_ sub folder of your Melody Master installation. - Press **F7**, the scroll down the list of output formats on the right to get to ANSI. - The file will be exported to the _root_ of the Melody Master directory (with the same name and a file-type specific extension). + The file will be exported to the _root_ of the Melody Master directory (with the same name and a file-type specific extension). 8. 打开文件。 输出可能看起来像这样: diff --git a/docs/zh/advanced_config/advanced_flight_controller_orientation_leveling.md b/docs/zh/advanced_config/advanced_flight_controller_orientation_leveling.md index 4deace6e1d..763c210c77 100644 --- a/docs/zh/advanced_config/advanced_flight_controller_orientation_leveling.md +++ b/docs/zh/advanced_config/advanced_flight_controller_orientation_leveling.md @@ -23,7 +23,7 @@ You can locate the parameters in QGroundControl as shown below: 1. Open QGroundControl menu: **Settings > Parameters > Sensor Calibration**. 2. The parameters as located in the section as shown below (or you can search for them): - ![FC Orientation QGC v2](../../assets/qgc/setup/sensor/fc_orientation_qgc_v2.png) + ![FC Orientation QGC v2](../../assets/qgc/setup/sensor/fc_orientation_qgc_v2.png) ## Parameter Summary diff --git a/docs/zh/advanced_config/bootloader_update.md b/docs/zh/advanced_config/bootloader_update.md index 0820bdcb0c..70cb5689af 100644 --- a/docs/zh/advanced_config/bootloader_update.md +++ b/docs/zh/advanced_config/bootloader_update.md @@ -37,8 +37,8 @@ You can enable this key in your own custom firmware if needed. 2. [Update the Firmware](../config/firmware.md#custom) with an image containing the new/desired bootloader. - ::: info - The updated bootloader might be included the default firmware for your board or supplied in custom firmware. + ::: info + The updated bootloader might be included the default firmware for your board or supplied in custom firmware. ::: @@ -47,7 +47,7 @@ You can enable this key in your own custom firmware if needed. 4. [Find and enable](../advanced_config/parameters.md) the parameter [SYS_BL_UPDATE](../advanced_config/parameter_reference.md#SYS_BL_UPDATE). 5. 重新启动(断开/重新连接飞控板)。 - Bootloader 更新只需要几秒钟即可完成。 + Bootloader 更新只需要几秒钟即可完成。 Generally at this point you may then want to [update the firmware](../config/firmware.md) again using the correct/newly installed bootloader. @@ -89,80 +89,80 @@ The following steps explain how you can "manually" update the bootloader using a 1. Get a binary containing the bootloader (either from dev team or [build it yourself](#building-the-px4-bootloader)). 2. Get a [Debug Probe](../debug/swd_debug.md#debug-probes-for-px4-hardware). - Connect the probe your PC via USB and setup the `gdbserver`. + Connect the probe your PC via USB and setup the `gdbserver`. 3. Go into the directory containing the binary and run the command for your target bootloader in the terminal: - - FMUv6X + - FMUv6X - ```sh - arm-none-eabi-gdb px4_fmu-v6x_bootloader.elf - ``` + ```sh + arm-none-eabi-gdb px4_fmu-v6x_bootloader.elf + ``` - - FMUv6X-RT + - FMUv6X-RT - ```sh - arm-none-eabi-gdb px4_fmu-v6xrt_bootloader.elf - ``` + ```sh + arm-none-eabi-gdb px4_fmu-v6xrt_bootloader.elf + ``` - - FMUv5 + - FMUv5 - ```sh - ``` + ```sh + ``` - ::: info - H7 Bootloaders from [PX4/PX4-Autopilot](https://github.com/PX4/PX4-Autopilot) are named with pattern `*._bootloader.elf`. - Bootloaders from [PX4/PX4-Bootloader](https://github.com/PX4/PX4-Bootloader) are named with the pattern `*_bl.elf`. + ::: info + H7 Bootloaders from [PX4/PX4-Autopilot](https://github.com/PX4/PX4-Autopilot) are named with pattern `*._bootloader.elf`. + Bootloaders from [PX4/PX4-Bootloader](https://github.com/PX4/PX4-Bootloader) are named with the pattern `*_bl.elf`. ::: 4. The _gdb terminal_ appears and it should display (something like) the following output: - ```sh - GNU gdb (GNU Tools for Arm Embedded Processors 7-2017-q4-major) 8.0.50.20171128-git - Copyright (C) 2017 Free Software Foundation, Inc. - License GPLv3+: GNU GPL version 3 or later - This is free software: you are free to change and redistribute it. - There is NO WARRANTY, to the extent permitted by law. - Type "show copying" and "show warranty" for details. - This GDB was configured as "--host=x86_64-linux-gnu --target=arm-none-eabi". - Type "show configuration" for configuration details. - For bug reporting instructions, please see: - . - Find the GDB manual and other documentation resources online at: - . - For help, type "help". - Type "apropos word" to search for commands related to "word"... - Reading symbols from px4fmuv5_bl.elf...done. - ``` + ```sh + GNU gdb (GNU Tools for Arm Embedded Processors 7-2017-q4-major) 8.0.50.20171128-git + Copyright (C) 2017 Free Software Foundation, Inc. + License GPLv3+: GNU GPL version 3 or later + This is free software: you are free to change and redistribute it. + There is NO WARRANTY, to the extent permitted by law. + Type "show copying" and "show warranty" for details. + This GDB was configured as "--host=x86_64-linux-gnu --target=arm-none-eabi". + Type "show configuration" for configuration details. + For bug reporting instructions, please see: + . + Find the GDB manual and other documentation resources online at: + . + For help, type "help". + Type "apropos word" to search for commands related to "word"... + Reading symbols from px4fmuv5_bl.elf...done. + ``` 5. Find your `` by running an `ls` command in the **/dev/serial/by-id** directory. 6. Now connect to the debug probe with the following command: - ```sh - tar ext /dev/serial/by-id/ - ``` + ```sh + tar ext /dev/serial/by-id/ + ``` 7. Power on the Pixhawk with another USB cable and connect the probe to the `FMU-DEBUG` port. - ::: info - If using a Zubax BugFace BF1 you may need to remove the case in order to connect to the `FMU-DEBUG` port (e.g. on Pixhawk 4 you would do this using a T6 Torx screwdriver). + ::: info + If using a Zubax BugFace BF1 you may need to remove the case in order to connect to the `FMU-DEBUG` port (e.g. on Pixhawk 4 you would do this using a T6 Torx screwdriver). ::: 8. Use the following command to scan for the Pixhawk\`s SWD and connect to it: - ```sh - (gdb) mon swdp_scan - (gdb) attach 1 - ``` + ```sh + (gdb) mon swdp_scan + (gdb) attach 1 + ``` 9. 将二进制文件加载到 Pixhawk 中 : - ```sh - (gdb) load - ``` + ```sh + (gdb) load + ``` After the bootloader has updated you can [Load PX4 Firmware](../config/firmware.md) using _QGroundControl_. @@ -181,25 +181,25 @@ Early FMUv2 [Pixhawk-series](../flight_controller/pixhawk_series.md#fmu_versions 1. 插入 SD 卡(使能引导日志记录,便于调试任何可能的问题)。 2. [Update the Firmware](../config/firmware.md) to PX4 _master_ version (when updating the firmware, check **Advanced settings** and then select **Developer Build (master)** from the dropdown list). - _QGroundControl_ will automatically detect that the hardware supports FMUv2 and install the appropriate Firmware. + _QGroundControl_ will automatically detect that the hardware supports FMUv2 and install the appropriate Firmware. - ![FMUv2 update](../../assets/qgc/setup/firmware/bootloader_update.jpg) + ![FMUv2 update](../../assets/qgc/setup/firmware/bootloader_update.jpg) - 等待飞控重启。 + 等待飞控重启。 3. [Find and enable](../advanced_config/parameters.md) the parameter [SYS_BL_UPDATE](../advanced_config/parameter_reference.md#SYS_BL_UPDATE). 4. 重新启动(断开/重新连接飞控板)。 - Bootloader 更新只需要几秒钟即可完成。 + Bootloader 更新只需要几秒钟即可完成。 5. Then [Update the Firmware](../config/firmware.md) again. - This time _QGroundControl_ should autodetect the hardware as FMUv3 and update the Firmware appropriately. + This time _QGroundControl_ should autodetect the hardware as FMUv3 and update the Firmware appropriately. - ![FMUv3 update](../../assets/qgc/setup/firmware/bootloader_fmu_v3_update.jpg) + ![FMUv3 update](../../assets/qgc/setup/firmware/bootloader_fmu_v3_update.jpg) - ::: info - If the hardware has the [Silicon Errata](../flight_controller/silicon_errata.md#fmuv2-pixhawk-silicon-errata) it will still be detected as FMUv2 and you will see that FMUv2 was re-installed (in console). - 在这种情况下,您将无法安装 FMUv3 硬件。 + ::: info + If the hardware has the [Silicon Errata](../flight_controller/silicon_errata.md#fmuv2-pixhawk-silicon-errata) it will still be detected as FMUv2 and you will see that FMUv2 was re-installed (in console). + 在这种情况下,您将无法安装 FMUv3 硬件。 ::: diff --git a/docs/zh/advanced_config/compass_power_compensation.md b/docs/zh/advanced_config/compass_power_compensation.md index 35b987cde5..e5dcdbdaa0 100644 --- a/docs/zh/advanced_config/compass_power_compensation.md +++ b/docs/zh/advanced_config/compass_power_compensation.md @@ -44,7 +44,7 @@ The process is demonstrated for a multicopter, but is equally valid for other ve - 解锁无人机,然后缓缓将油门推到最大。 - 慢慢将油门降到0 - 给无人机加锁 - > Note 谨慎地进行测试,并密切注意振动情况。 + > Note 谨慎地进行测试,并密切注意振动情况。 ::: info Perform the test carefully and closely monitor the vibrations. diff --git a/docs/zh/advanced_config/esc_calibration.md b/docs/zh/advanced_config/esc_calibration.md index 36d417a5d9..27bda2805d 100644 --- a/docs/zh/advanced_config/esc_calibration.md +++ b/docs/zh/advanced_config/esc_calibration.md @@ -94,29 +94,29 @@ Flight control systems that can't power the autopilot via USB will need a [diffe - The minimum value for a motor (default: `1100us`) should make the motor spin slowly but reliably, and also spin up reliably after it was stopped. - You can confirm that a motor spins at minimum (still without propellers) in [Actuator Testing](../config/actuators.md#actuator-testing), by enabling the sliders, and then moving the test output slider for the motor to the first snap position from the bottom. - 当你将滑块从解锁到最小值时,正确的值应该使电机立即和可靠地旋转。 + You can confirm that a motor spins at minimum (still without propellers) in [Actuator Testing](../config/actuators.md#actuator-testing), by enabling the sliders, and then moving the test output slider for the motor to the first snap position from the bottom. + 当你将滑块从解锁到最小值时,正确的值应该使电机立即和可靠地旋转。 - 要找到“最佳”最小值,请将滑块移动到底部(禁用)。 - Then increase the PWM output's `disarmed` setting in small increments (e.g. 1025us, 1050us, etc), until the motor starts to spin reliably (it is better to be a little too high than a little too low). - Enter this value into the `minimum` setting for all the motor PWM outputs, and restore the `disarmed` output to `1100us`. + 要找到“最佳”最小值,请将滑块移动到底部(禁用)。 + Then increase the PWM output's `disarmed` setting in small increments (e.g. 1025us, 1050us, etc), until the motor starts to spin reliably (it is better to be a little too high than a little too low). + Enter this value into the `minimum` setting for all the motor PWM outputs, and restore the `disarmed` output to `1100us`. - The maximum value for a motor (default: `1900us`) should be chosen such that increasing the value doesn't make the motor spin any faster. - You can confirm that the motor spins quickly at the maximum setting in [Actuator Testing](../config/actuators.md#actuator-testing), by moving the associated test output slider to the top position. + You can confirm that the motor spins quickly at the maximum setting in [Actuator Testing](../config/actuators.md#actuator-testing), by moving the associated test output slider to the top position. - To find the "optimal" maximum value, first move the slider to the bottom (disarmed). - Then increase the PWM output's `disarmed` setting to near the default maximum (`1900`) - the motors should spin up. - Listen to the tone of the motor as you increase the PWM maximum value for the output in increments (e.g. 1925us, 1950us, etc). - The optimal value is found at the point when the sound of the motors does not change as you increase the value of the output. - Enter this value into the `maximum` setting for all the motor PWM outputs, and restore the `disarmed` output to `1100us`. + To find the "optimal" maximum value, first move the slider to the bottom (disarmed). + Then increase the PWM output's `disarmed` setting to near the default maximum (`1900`) - the motors should spin up. + Listen to the tone of the motor as you increase the PWM maximum value for the output in increments (e.g. 1925us, 1950us, etc). + The optimal value is found at the point when the sound of the motors does not change as you increase the value of the output. + Enter this value into the `maximum` setting for all the motor PWM outputs, and restore the `disarmed` output to `1100us`. - The disarmed value for a motor (default: `1000us`) should make the motor stop and stay stopped. - You can confirm this in [Actuator Testing](../config/actuators.md#actuator-testing) by moving the test output slider to the snap position at the bottom of the slider and observing that the motor does not spin. + You can confirm this in [Actuator Testing](../config/actuators.md#actuator-testing) by moving the test output slider to the snap position at the bottom of the slider and observing that the motor does not spin. - If the ESC spins with the default value of 1000us then the ESC is not properly calibrated. - If using an ESC that can't be calibrated, you should reduce the PWM output value for the output to below where the motor does not spin anymore (such as 950us or 900us). + If the ESC spins with the default value of 1000us then the ESC is not properly calibrated. + If using an ESC that can't be calibrated, you should reduce the PWM output value for the output to below where the motor does not spin anymore (such as 950us or 900us). ::: info VTOL and fixed-wing motors do not need any special PWM configuration. diff --git a/docs/zh/advanced_config/ethernet_setup.md b/docs/zh/advanced_config/ethernet_setup.md index 077421a3db..ac1fca8e67 100644 --- a/docs/zh/advanced_config/ethernet_setup.md +++ b/docs/zh/advanced_config/ethernet_setup.md @@ -87,14 +87,14 @@ To set the above "example" configuration using the _QGroundControl_: 3. Enter commands "like" the ones below into the _MAVLink Console_ (to write the values to the configuration file): - ```sh - echo DEVICE=eth0 > /fs/microsd/net.cfg - echo BOOTPROTO=fallback >> /fs/microsd/net.cfg - echo IPADDR=10.41.10.2 >> /fs/microsd/net.cfg - echo NETMASK=255.255.255.0 >>/fs/microsd/net.cfg - echo ROUTER=10.41.10.254 >>/fs/microsd/net.cfg - echo DNS=10.41.10.254 >>/fs/microsd/net.cfg - ``` + ```sh + echo DEVICE=eth0 > /fs/microsd/net.cfg + echo BOOTPROTO=fallback >> /fs/microsd/net.cfg + echo IPADDR=10.41.10.2 >> /fs/microsd/net.cfg + echo NETMASK=255.255.255.0 >>/fs/microsd/net.cfg + echo ROUTER=10.41.10.254 >>/fs/microsd/net.cfg + echo DNS=10.41.10.254 >>/fs/microsd/net.cfg + ``` 4. 一旦设置了网络配置,您可以断开 USB 电缆。 @@ -113,36 +113,36 @@ Note that there are many more [examples](https://github.com/canonical/netplan/tr 设置Ubuntu计算机: 1. In a terminal, create and open a `netplan` configuration file: `/etc/netplan/01-network-manager-all.yaml` - Below we do this using the _nano_ text editor. + Below we do this using the _nano_ text editor. - ``` - sudo nano /etc/netplan/01-network-manager-all.yaml - ``` + ``` + sudo nano /etc/netplan/01-network-manager-all.yaml + ``` 2. 将以下配置信息复制并粘贴到文件中(注意:缩进很重要!): - ``` - network: - version: 2 - renderer: NetworkManager - ethernets: - enp2s0: - addresses: - - 10.41.10.1/24 - nameservers: - addresses: [10.41.10.1] - routes: - - to: 10.41.10.1 - via: 10.41.10.1 - ``` + ``` + network: + version: 2 + renderer: NetworkManager + ethernets: + enp2s0: + addresses: + - 10.41.10.1/24 + nameservers: + addresses: [10.41.10.1] + routes: + - to: 10.41.10.1 + via: 10.41.10.1 + ``` - 保存并退出编辑器。 + 保存并退出编辑器。 3. Apply the _netplan_ configuration by entering the following command into the Ubuntu terminal. - ``` - sudo netplan apply - ``` + ``` + sudo netplan apply + ``` ### 机载计算机以太网网络设置 @@ -189,9 +189,9 @@ Assuming you have already [Set up the Ethernet Network](#setting-up-the-ethernet 3. Start QGroundControl and [define a comm link](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/settings_view/settings_view.html) (**Application Settings > Comm Links**) specifying the _server address_ and port as the IP address and port assigned in PX4, respectively. - 假设值已按本主题其余部分所述设置,设置将如下所示: + 假设值已按本主题其余部分所述设置,设置将如下所示: - ![QGC comm link for ethernet setup](../../assets/qgc/settings/comm_link/px4_ethernet_link_config.png) + ![QGC comm link for ethernet setup](../../assets/qgc/settings/comm_link/px4_ethernet_link_config.png) 4. 如果你选择这个链接,QGroundControl 应该会连接。 @@ -205,14 +205,14 @@ Assuming you have already [Set up the Ethernet Network](#setting-up-the-ethernet 1. [Set up the Ethernet Network](#setting-up-the-ethernet-network) so your companion computer and PX4 run on the same network. 2. Modify the [PX4 Ethernet Port Configuration](#px4-ethernet-network-setup) to connect to a companion computer. - You might change the parameters [MAV_2_REMOTE_PRT](../advanced_config/parameter_reference.md#MAV_2_REMOTE_PRT) and [MAV_2_UDP_PRT](../advanced_config/parameter_reference.md#MAV_2_UDP_PRT) to `14540`, and [MAV_2_MODE](../advanced_config/parameter_reference.md#MAV_2_MODE) to `2` (Onboard). + You might change the parameters [MAV_2_REMOTE_PRT](../advanced_config/parameter_reference.md#MAV_2_REMOTE_PRT) and [MAV_2_UDP_PRT](../advanced_config/parameter_reference.md#MAV_2_UDP_PRT) to `14540`, and [MAV_2_MODE](../advanced_config/parameter_reference.md#MAV_2_MODE) to `2` (Onboard). 3. Follow the instructions in [MAVSDK-python](https://github.com/mavlink/MAVSDK-Python) to install and use MAVSDK. - 例如,您的代码将使用以下方式连接到PX4: + 例如,您的代码将使用以下方式连接到PX4: - ```python - await drone.connect(system_address="udp://10.41.10.2:14540") - ``` + ```python + await drone.connect(system_address="udp://10.41.10.2:14540") + ``` :::info MAVSDK can connect to the PX4 on port `14550` if you don't modify the PX4 Ethernet port configuration. @@ -235,38 +235,38 @@ MAVSDK can connect to the PX4 on port `14550` if you don't modify the PX4 Ethern 1. 通过以太网连接您的飞行控制器和机载计算机。 2. [Start the uXRCE-DDS client on PX4](../middleware/uxrce_dds.md#starting-the-client), either manually or by customizing the system startup script. - Note that you must use the IP address of the companion computer and the UDP port on which the agent is listening (the example configuration above sets the companion IP address to `10.41.10.1`, and the agent UDP port is set to `8888` in the next step). + Note that you must use the IP address of the companion computer and the UDP port on which the agent is listening (the example configuration above sets the companion IP address to `10.41.10.1`, and the agent UDP port is set to `8888` in the next step). 3. [Start the micro XRCE-DDS agent on the companion computer](../middleware/uxrce_dds.md#starting-the-agent). - For example, enter the following command in a terminal to start the agent listening on UDP port `8888`. + For example, enter the following command in a terminal to start the agent listening on UDP port `8888`. - ```sh - MicroXRCEAgent udp4 -p 8888 - ``` + ```sh + MicroXRCEAgent udp4 -p 8888 + ``` 4. Run a [listener node](../ros2/user_guide.md#running-the-example) in a new terminal to confirm the connection is established: - ```sh - source ~/ws_sensor_combined/install/setup.bash - ros2 launch px4_ros_com sensor_combined_listener.launch.py - ``` + ```sh + source ~/ws_sensor_combined/install/setup.bash + ros2 launch px4_ros_com sensor_combined_listener.launch.py + ``` - 如果所有设置都正确,终端应显示如下输出: + 如果所有设置都正确,终端应显示如下输出: - ```sh - RECEIVED SENSOR COMBINED DATA - ============================= - ts: 855801598 - gyro_rad[0]: -0.00339938 - gyro_rad[1]: 0.00440091 - gyro_rad[2]: 0.00513893 - gyro_integral_dt: 4997 - accelerometer_timestamp_relative: 0 - accelerometer_m_s2[0]: -0.0324082 - accelerometer_m_s2[1]: 0.0392213 - accelerometer_m_s2[2]: -9.77914 - accelerometer_integral_dt: 4997 - ``` + ```sh + RECEIVED SENSOR COMBINED DATA + ============================= + ts: 855801598 + gyro_rad[0]: -0.00339938 + gyro_rad[1]: 0.00440091 + gyro_rad[2]: 0.00513893 + gyro_integral_dt: 4997 + accelerometer_timestamp_relative: 0 + accelerometer_m_s2[0]: -0.0324082 + accelerometer_m_s2[1]: 0.0392213 + accelerometer_m_s2[2]: -9.77914 + accelerometer_integral_dt: 4997 + ``` ## See Also diff --git a/docs/zh/advanced_config/prearm_arm_disarm.md b/docs/zh/advanced_config/prearm_arm_disarm.md index 71ac176329..f4070e7130 100644 --- a/docs/zh/advanced_config/prearm_arm_disarm.md +++ b/docs/zh/advanced_config/prearm_arm_disarm.md @@ -153,14 +153,14 @@ It corresponds to: [COM_PREARM_MODE=1](#COM_PREARM_MODE) (safety switch) and [CB The default startup sequence is: 1. Power-up. - - All actuators locked into disarmed position - - Not possible to arm. + - All actuators locked into disarmed position + - Not possible to arm. 2. Safety switch is pressed. - - System now prearmed: non-throttling actuators can move (e.g. ailerons). - - System safety is off: Arming possible. + - System now prearmed: non-throttling actuators can move (e.g. ailerons). + - System safety is off: Arming possible. 3. Arm command is issued. - - The system is armed. - - All motors and actuators can move. + - The system is armed. + - All motors and actuators can move. ### COM_PREARM_MODE=Disabled and Safety Switch @@ -170,14 +170,14 @@ This corresponds to [COM_PREARM_MODE=0](#COM_PREARM_MODE) (Disabled) and [CBRK_I The startup sequence is: 1. Power-up. - - All actuators locked into disarmed position - - Not possible to arm. + - All actuators locked into disarmed position + - Not possible to arm. 2. Safety switch is pressed. - - _All actuators stay locked into disarmed position (same as disarmed)._ - - System safety is off: Arming possible. + - _All actuators stay locked into disarmed position (same as disarmed)._ + - System safety is off: Arming possible. 3. Arm command is issued. - - The system is armed. - - All motors and actuators can move. + - The system is armed. + - All motors and actuators can move. ### COM_PREARM_MODE=Always and Safety Switch @@ -188,13 +188,13 @@ This corresponds to [COM_PREARM_MODE=2](#COM_PREARM_MODE) (Always) and [CBRK_IO_ The startup sequence is: 1. Power-up. - - System now prearmed: non-throttling actuators can move (e.g. ailerons). - - Not possible to arm. + - System now prearmed: non-throttling actuators can move (e.g. ailerons). + - Not possible to arm. 2. Safety switch is pressed. - - System safety is off: Arming possible. + - System safety is off: Arming possible. 3. Arm command is issued. - - The system is armed. - - All motors and actuators can move. + - The system is armed. + - All motors and actuators can move. ### COM_PREARM_MODE=Safety or Disabled and No Safety Switch @@ -204,11 +204,11 @@ This corresponds to [COM_PREARM_MODE=0 or 1](#COM_PREARM_MODE) (Disabled/Safety The startup sequence is: 1. Power-up. - - All actuators locked into disarmed position - - System safety is off: Arming possible. + - All actuators locked into disarmed position + - System safety is off: Arming possible. 2. Arm command is issued. - - The system is armed. - - All motors and actuators can move. + - The system is armed. + - All motors and actuators can move. ### COM_PREARM_MODE=Always and No Safety Switch @@ -218,11 +218,11 @@ This corresponds to [COM_PREARM_MODE=2](#COM_PREARM_MODE) (Always) and [CBRK_IO_ The startup sequence is: 1. Power-up. - - System now prearmed: non-throttling actuators can move (e.g. ailerons). - - System safety is off: Arming possible. + - System now prearmed: non-throttling actuators can move (e.g. ailerons). + - System safety is off: Arming possible. 2. Arm command is issued. - - The system is armed. - - All motors and actuators can move. + - The system is armed. + - All motors and actuators can move. ### 参数 diff --git a/docs/zh/advanced_config/sensor_thermal_calibration.md b/docs/zh/advanced_config/sensor_thermal_calibration.md index 3a43b02555..f5f4be91a1 100644 --- a/docs/zh/advanced_config/sensor_thermal_calibration.md +++ b/docs/zh/advanced_config/sensor_thermal_calibration.md @@ -94,11 +94,11 @@ To perform an offboard calibration: 9. Open a terminal window in the **Firmware/Tools** directory and run the python calibration script: - ```sh - python process_sensor_caldata.py - ``` + ```sh + python process_sensor_caldata.py + ``` - This will generate a **.pdf** file showing the measured data and curve fits for each sensor, and a **.params** file containing the calibration parameters. + This will generate a **.pdf** file showing the measured data and curve fits for each sensor, and a **.params** file containing the calibration parameters. 10. Power the board, connect _QGroundControl_ and load the parameter from the generated **.params** file onto the board using _QGroundControl_. 由于参数的数量,加载它们可能需要一些时间。 diff --git a/docs/zh/advanced_config/tuning_the_ecl_ekf.md b/docs/zh/advanced_config/tuning_the_ecl_ekf.md index ba875b161b..4f91ebfd61 100644 --- a/docs/zh/advanced_config/tuning_the_ecl_ekf.md +++ b/docs/zh/advanced_config/tuning_the_ecl_ekf.md @@ -157,29 +157,29 @@ Three axis body fixed magnetometer data at a minimum rate of 5Hz is required to Magnetometer data fusion can be configured using [EKF2_MAG_TYPE](../advanced_config/parameter_reference.md#EKF2_MAG_TYPE): 0. Automatic: - - The magnetometer readings only affect the heading estimate before arming, and the whole attitude after arming. - - Heading and tilt errors are compensated when using this method. - - Incorrect magnetic field measurements can degrade the tilt estimate. - - The magnetometer biases are estimated whenever observable. + - The magnetometer readings only affect the heading estimate before arming, and the whole attitude after arming. + - Heading and tilt errors are compensated when using this method. + - Incorrect magnetic field measurements can degrade the tilt estimate. + - The magnetometer biases are estimated whenever observable. 1. Magnetic heading: - - Only the heading is corrected. - The tilt estimate is never affected by incorrect magnetic field measurements. - - Tilt errors that could arise when flying without velocity/position aiding are not corrected when using this method. - - The magnetometer biases are estimated whenever observable. + - Only the heading is corrected. + The tilt estimate is never affected by incorrect magnetic field measurements. + - Tilt errors that could arise when flying without velocity/position aiding are not corrected when using this method. + - The magnetometer biases are estimated whenever observable. 2. Deprecated 3. Deprecated 4. Deprecated 5. None: - - Magnetometer data is never used. - This is useful when the data can never be trusted (e.g.: high current close to the sensor, external anomalies). - - The estimator will use other sources of heading: [GPS heading](#yaw-measurements) or external vision. - - When using GPS measurements without another source of heading, the heading can only be initialized after sufficient horizontal acceleration. - See [Estimate yaw from vehicle movement](#yaw-from-gps-velocity) below. + - Magnetometer data is never used. + This is useful when the data can never be trusted (e.g.: high current close to the sensor, external anomalies). + - The estimator will use other sources of heading: [GPS heading](#yaw-measurements) or external vision. + - When using GPS measurements without another source of heading, the heading can only be initialized after sufficient horizontal acceleration. + See [Estimate yaw from vehicle movement](#yaw-from-gps-velocity) below. 6. Init only: - - Magnetometer data is only used to initialize the heading estimate. - This is useful when the data can be used before arming but not afterwards (e.g.: high current after the vehicle is armed). - - After initialization, the heading is constrained using other observations. - - Unlike mag type `None`, when combined with GPS measurements, this method allows position controlled modes to run directly during takeoff. + - Magnetometer data is only used to initialize the heading estimate. + This is useful when the data can be used before arming but not afterwards (e.g.: high current after the vehicle is armed). + - After initialization, the heading is constrained using other observations. + - Unlike mag type `None`, when combined with GPS measurements, this method allows position controlled modes to run directly during takeoff. The following selection tree can be used to select the right option: @@ -241,8 +241,8 @@ EKF2模块将误差建模为与机体固连的椭球体,在将其转换为高 2. Extract the `.ulg` log file using, for example, [QGroundControl: Analyze > Log Download](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/analyze_view/log_download.html) - ::: info - The same log file can be used to tune the [multirotor wind estimator](#mc_wind_estimation_using_drag). + ::: info + The same log file can be used to tune the [multirotor wind estimator](#mc_wind_estimation_using_drag). ::: @@ -457,8 +457,8 @@ The amount of specific force observation noise is set by the [EKF2_DRAG_NOISE](. 1. Fly once in [Position mode](../flight_modes_mc/position.md) repeatedly forwards/backwards/left/right/up/down between rest and maximum speed (best results are obtained when this testing is conducted in still conditions). 2. Extract the **.ulg** log file using, for example, [QGroundControl: Analyze > Log Download](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/analyze_view/log_download.html) - ::: info - The same **.ulg** log file can also be used to tune the [static pressure position error coefficients](#correction-for-static-pressure-position-error). + ::: info + The same **.ulg** log file can also be used to tune the [static pressure position error coefficients](#correction-for-static-pressure-position-error). ::: 3. Use the log with the [mc_wind_estimator_tuning.py](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/ekf2/EKF/python/tuning_tools/mc_wind_estimator) Python script to obtain the optimal set of parameters. diff --git a/docs/zh/advanced_features/precland.md b/docs/zh/advanced_features/precland.md index 821d15a25c..cce0c92e20 100644 --- a/docs/zh/advanced_features/precland.md +++ b/docs/zh/advanced_features/precland.md @@ -38,14 +38,14 @@ If it is not visible the vehicle immediately performs a _normal_ landing at the A precision landing has three phases: 1. **Horizontal approach:** The vehicle approaches the target horizontally while keeping its current altitude. - Once the position of the target relative to the vehicle is below a threshold ([PLD_HACC_RAD](../advanced_config/parameter_reference.md#PLD_HACC_RAD)), the next phase is entered. - If the target is lost during this phase (not visible for longer than [PLD_BTOUT](../advanced_config/parameter_reference.md#PLD_BTOUT)), a search procedure is initiated (during a required precision landing) or the vehicle does a normal landing (during an opportunistic precision landing). + Once the position of the target relative to the vehicle is below a threshold ([PLD_HACC_RAD](../advanced_config/parameter_reference.md#PLD_HACC_RAD)), the next phase is entered. + If the target is lost during this phase (not visible for longer than [PLD_BTOUT](../advanced_config/parameter_reference.md#PLD_BTOUT)), a search procedure is initiated (during a required precision landing) or the vehicle does a normal landing (during an opportunistic precision landing). 2. **Descent over target:** The vehicle descends, while remaining centered over the target. - If the target is lost during this phase (not visible for longer than `PLD_BTOUT`), a search procedure is initiated (during a required precision landing) or the vehicle does a normal landing (during an opportunistic precision landing). + If the target is lost during this phase (not visible for longer than `PLD_BTOUT`), a search procedure is initiated (during a required precision landing) or the vehicle does a normal landing (during an opportunistic precision landing). 3. **Final approach:** When the vehicle is close to the ground (closer than [PLD_FAPPR_ALT](../advanced_config/parameter_reference.md#PLD_FAPPR_ALT)), it descends while remaining centered over the target. - If the target is lost during this phase, the descent is continued independent of the kind of precision landing. + If the target is lost during this phase, the descent is continued independent of the kind of precision landing. Search procedures are initiated in the first and second steps, and will run at most [PLD_MAX_SRCH](../advanced_config/parameter_reference.md#PLD_MAX_SRCH) times. Landing Phases Flow Diagram diff --git a/docs/zh/advanced_features/satcom_roadblock.md b/docs/zh/advanced_features/satcom_roadblock.md index fcb45ba7cf..47afa7adcf 100644 --- a/docs/zh/advanced_features/satcom_roadblock.md +++ b/docs/zh/advanced_features/satcom_roadblock.md @@ -54,19 +54,19 @@ If an external antenna is used always make sure that the antenna is connected to The default baud rate of the module is 19200. However, the PX4 _iridiumsbd_ driver requires a baud rate of 115200 so it needs to be changed using the [AT commands](https://www.groundcontrol.com/wp-content/uploads/2022/02/IRDM_ISU_ATCommandReferenceMAN0009_Rev2.0_ATCOMM_Oct2012.pdf). 1. Connect to the module with using a 19200/8-N-1 setting and check if the communication is working using the command: `AT`. - The response should be: `OK`. + The response should be: `OK`. 2. Change the baud rate: - ``` - AT+IPR=9 - ``` + ``` + AT+IPR=9 + ``` 3. Reconnect to the model now with a 115200/8-N-1 setting and save the configuration using: - ``` - AT&W0 - ``` + ``` + AT&W0 + ``` The module is now ready to be used with PX4. @@ -101,55 +101,55 @@ Set up a delivery group for the message relay server and add the module to that The relay server should be run on either Ubuntu 16.04 or 14.04 OS. 1. The server working as a message relay should have a static IP address and two publicly accessible, open, TCP ports: - - `5672` for the _RabbitMQ_ message broker (can be changed in the _rabbitmq_ settings) - - `45679` for the HTTP POST interface (can be changed in the **relay.cfg** file) + - `5672` for the _RabbitMQ_ message broker (can be changed in the _rabbitmq_ settings) + - `45679` for the HTTP POST interface (can be changed in the **relay.cfg** file) 2. Install the required python modules: - ```sh - sudo pip install pika tornado future - ``` + ```sh + sudo pip install pika tornado future + ``` 3. Install the `rabbitmq` message broker: - ```sh - sudo apt install rabbitmq-server - ``` + ```sh + sudo apt install rabbitmq-server + ``` 4. Configure the broker's credentials (change PWD to your preferred password): - ```sh - sudo rabbitmqctl add_user iridiumsbd PWD - sudo rabbitmqctl set_permissions iridiumsbd ".*" ".*" ".*" - ``` + ```sh + sudo rabbitmqctl add_user iridiumsbd PWD + sudo rabbitmqctl set_permissions iridiumsbd ".*" ".*" ".*" + ``` 5. Clone the [SatComInfrastructure](https://github.com/acfloria/SatComInfrastructure) repository: - ```sh - git clone https://github.com/acfloria/SatComInfrastructure.git - ``` + ```sh + git clone https://github.com/acfloria/SatComInfrastructure.git + ``` 6. Go to the location of the _SatComInfrastructure_ repo and configure the broker's queues: - ```sh - ./setup_rabbit.py localhost iridiumsbd PWD - ``` + ```sh + ./setup_rabbit.py localhost iridiumsbd PWD + ``` 7. Verify the setup: - ```sh - sudo rabbitmqctl list_queues - ``` + ```sh + sudo rabbitmqctl list_queues + ``` - This should give you a list of 4 queues: `MO`, `MO_LOG`, `MT`, `MT_LOG` + This should give you a list of 4 queues: `MO`, `MO_LOG`, `MT`, `MT_LOG` 8. Edit the `relay.cfg` configuration file to reflect your settings. 9. Start the relay script in the detached mode: - ```sh - screen -dm bash -c 'cd SatcomInfrastructure/; ./relay.py - ``` + ```sh + screen -dm bash -c 'cd SatcomInfrastructure/; ./relay.py + ``` Other instructions include: @@ -177,15 +177,15 @@ To setup the ground station: 1. Install the required python modules: - ```sh - sudo pip install pika tornado future - ``` + ```sh + sudo pip install pika tornado future + ``` 2. Clone the SatComInfrastructure repository: - ```sh - git clone https://github.com/acfloria/SatComInfrastructure.git - ``` + ```sh + git clone https://github.com/acfloria/SatComInfrastructure.git + ``` 3. Edit the **udp2rabbit.cfg** configuration file to reflect your settings. @@ -193,20 +193,20 @@ To setup the ground station: 5. Add a UDP connection in QGC with the parameters: - - Listening port: 10000 - - Target hosts: 127.0.0.1:10001 - - High Latency: checked + - Listening port: 10000 + - Target hosts: 127.0.0.1:10001 + - High Latency: checked - ![High Latency Link Settings](../../assets/satcom/linksettings.png) + ![High Latency Link Settings](../../assets/satcom/linksettings.png) ### 验证 1. Open a terminal on the ground station computer and change to the location of the _SatComInfrastructure_ repository. - Then start the **udp2rabbit.py** script: + Then start the **udp2rabbit.py** script: - ```sh - ./udp2rabbit.py - ``` + ```sh + ./udp2rabbit.py + ``` 2. Send a test message from [RockBlock Account](https://rockblock.rock7.com/Operations) to the created delivery group in the `Test Delivery Groups` tab. @@ -217,36 +217,36 @@ If in the terminal where the `udp2rabbit.py` script is running within a couple o ## Running the System 1. Start _QGroundControl_. - Manually connect the high latency link first, then the regular telemetry link: + Manually connect the high latency link first, then the regular telemetry link: - ![Connect the High Latency link](../../assets/satcom/linkconnect.png) + ![Connect the High Latency link](../../assets/satcom/linkconnect.png) 2. Open a terminal on the ground station computer and change to the location of the _SatComInfrastructure_ repository. - Then start the **udp2rabbit.py** script: + Then start the **udp2rabbit.py** script: - ```sh - ./udp2rabbit.py - ``` + ```sh + ./udp2rabbit.py + ``` 3. Power up the vehicle. 4. Wait until the first `HIGH_LATENCY2` message is received on QGC. - This can be checked either using the _MAVLink Inspector_ widget or on the toolbar with the _LinkIndicator_. - If more than one link is connected to the active vehicle the _LinkIndicator_ shows all of them by clicking on the name of the shown link: + This can be checked either using the _MAVLink Inspector_ widget or on the toolbar with the _LinkIndicator_. + If more than one link is connected to the active vehicle the _LinkIndicator_ shows all of them by clicking on the name of the shown link: - ![Link Toolbar](../../assets/satcom/linkindicator.jpg) + ![Link Toolbar](../../assets/satcom/linkindicator.jpg) - The link indicator always shows the name of the priority link. + The link indicator always shows the name of the priority link. 5. The satellite communication system is now ready to use. - The priority link, which is the link over which commands are send, is determined the following ways: - - If no link is commanded by the user a regular radio telemetry link is preferred over the high latency link. - - The autopilot and QGC will fall back from the regular radio telemetry to the high latency link if the vehicle is armed and the radio telemetry link is lost (no MAVLink messages received for a certain time). - As soon as the radio telemetry link is regained QGC and the autopilot will switch back to it. - - The user can select a priority link over the `LinkIndicator` on the toolbar. - This link is kept as the priority link as long as this link is active or the user selects another priority link: + The priority link, which is the link over which commands are send, is determined the following ways: + - If no link is commanded by the user a regular radio telemetry link is preferred over the high latency link. + - The autopilot and QGC will fall back from the regular radio telemetry to the high latency link if the vehicle is armed and the radio telemetry link is lost (no MAVLink messages received for a certain time). + As soon as the radio telemetry link is regained QGC and the autopilot will switch back to it. + - The user can select a priority link over the `LinkIndicator` on the toolbar. + This link is kept as the priority link as long as this link is active or the user selects another priority link: - ![Prioritylink Selection](../../assets/satcom/linkselection.png) + ![Prioritylink Selection](../../assets/satcom/linkselection.png) ## 故障处理 diff --git a/docs/zh/camera/fc_connected_camera.md b/docs/zh/camera/fc_connected_camera.md index 8645b80e94..f6254eb86b 100644 --- a/docs/zh/camera/fc_connected_camera.md +++ b/docs/zh/camera/fc_connected_camera.md @@ -188,16 +188,16 @@ The following sections are out of date and need retesting. 1. On the PX4 console: - ```shell - camera_trigger test - ``` + ```shell + camera_trigger test + ``` 2. From _QGroundControl_: - Click on **Trigger Camera** in the main instrument panel. - These shots are not logged or counted for geotagging. + Click on **Trigger Camera** in the main instrument panel. + These shots are not logged or counted for geotagging. - ![QGC Test Camera](../../assets/camera/qgc_test_camera.png) + ![QGC Test Camera](../../assets/camera/qgc_test_camera.png) ## Sony QX-1 example (Photogrammetry) diff --git a/docs/zh/camera/mavlink_v1_camera.md b/docs/zh/camera/mavlink_v1_camera.md index f7a20dcc0a..2c1289fa32 100644 --- a/docs/zh/camera/mavlink_v1_camera.md +++ b/docs/zh/camera/mavlink_v1_camera.md @@ -86,7 +86,7 @@ PX4 重新使用与自驾仪相同的系统 ID 和组件 ID [MAV_COMP_ID_ALL](ht 1. 修改一个未使用的 `MAV_n_CONFIG` 参数,例如[MAV_2_CONFIG](../advanced_config/parameter_reference.md#MAV_2_CONFIG),使其分配给相机连接的端口。 2. 将对应的 [MAV_2_MODE](../advanced_config/parameter_reference.md#MAV_2_MODE) 设置为 `2` (板载)。 - 这确保正确的 MAVLink 消息集被发出和转发。 + 这确保正确的 MAVLink 消息集被发出和转发。 3. 您可能需要设置一些其他参数,取决于您的连接 - 例如波特率。 然后按照其用户指南中的建议连接和配置相机。 diff --git a/docs/zh/camera/mavlink_v2_camera.md b/docs/zh/camera/mavlink_v2_camera.md index 5935a2d75c..abf7eb0490 100644 --- a/docs/zh/camera/mavlink_v2_camera.md +++ b/docs/zh/camera/mavlink_v2_camera.md @@ -112,7 +112,7 @@ The linked document explains how, but in summary: 1. Modify an unused `MAV_n_CONFIG` parameter, such as [MAV_2_CONFIG](../advanced_config/parameter_reference.md#MAV_2_CONFIG), so that it is assigned to port to which you connected the camera/companion computer. 2. 将对应的 [MAV_2_MODE](../advanced_config/parameter_reference.md#MAV_2_MODE) 设置为 `2` (板载)。 - This ensures that the right set of MAVLink messages are emitted for a companion computer (or camera). + This ensures that the right set of MAVLink messages are emitted for a companion computer (or camera). 3. Set [MAV_2_FORWARD](../advanced_config/parameter_reference.md#MAV_2_FORWARD) to enable forwarding of communications from the port to other ports, such as the one that is connected to the ground station. 4. You may need to set some of the other parameters, depending on your connection type and any particular requirements of the camera on the expected baud rate, and so on. diff --git a/docs/zh/companion_computer/holybro_pixhawk_jetson_baseboard.md b/docs/zh/companion_computer/holybro_pixhawk_jetson_baseboard.md index 5a49dd739d..93dd15e4e2 100644 --- a/docs/zh/companion_computer/holybro_pixhawk_jetson_baseboard.md +++ b/docs/zh/companion_computer/holybro_pixhawk_jetson_baseboard.md @@ -892,95 +892,95 @@ These instructions approximately mirror the [PX4 Ethernet setup](../advanced_con Next we modify the Jetson IP address to be on the same network as the Pixhawk: 1. Make sure `netplan` is installed. - You can check by running the following command: + You can check by running the following command: - ```sh - netplan -h - ``` + ```sh + netplan -h + ``` - If not, install it using the commands: + If not, install it using the commands: - ```sh - sudo apt update - sudo apt install netplan.io - ``` + ```sh + sudo apt update + sudo apt install netplan.io + ``` 2. Check `system_networkd` is running: - ```sh - sudo systemctl status systemd-networkd - ``` + ```sh + sudo systemctl status systemd-networkd + ``` - You should see output like below if it is active: + You should see output like below if it is active: - ```sh - ● systemd-networkd.service - Network Configuration - Loaded: loaded (/lib/systemd/system/systemd-networkd.service; enabled; vendor preset: enabled) - Active: active (running) since Wed 2024-09-11 23:32:44 EDT; 23min ago - TriggeredBy: ● systemd-networkd.socket - Docs: man:systemd-networkd.service(8) - Main PID: 2452 (systemd-network) - Status: "Processing requests..." - Tasks: 1 (limit: 18457) - Memory: 2.7M - CPU: 157ms - CGroup: /system.slice/systemd-networkd.service - └─2452 /lib/systemd/systemd-networkd + ```sh + ● systemd-networkd.service - Network Configuration + Loaded: loaded (/lib/systemd/system/systemd-networkd.service; enabled; vendor preset: enabled) + Active: active (running) since Wed 2024-09-11 23:32:44 EDT; 23min ago + TriggeredBy: ● systemd-networkd.socket + Docs: man:systemd-networkd.service(8) + Main PID: 2452 (systemd-network) + Status: "Processing requests..." + Tasks: 1 (limit: 18457) + Memory: 2.7M + CPU: 157ms + CGroup: /system.slice/systemd-networkd.service + └─2452 /lib/systemd/systemd-networkd - Sep 11 23:32:44 ubuntu systemd-networkd[2452]: lo: Gained carrier - Sep 11 23:32:44 ubuntu systemd-networkd[2452]: wlan0: Gained IPv6LL - Sep 11 23:32:44 ubuntu systemd-networkd[2452]: eth0: Gained IPv6LL - Sep 11 23:32:44 ubuntu systemd-networkd[2452]: Enumeration completed - Sep 11 23:32:44 ubuntu systemd[1]: Started Network Configuration. - Sep 11 23:32:44 ubuntu systemd-networkd[2452]: wlan0: Connected WiFi access point: Verizon_7YLWWD (78:67:0e:ea:a6:0> - Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: Re-configuring with /run/systemd/network/10-netplan-eth0.netwo> - Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: DHCPv6 lease lost - Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: Re-configuring with /run/systemd/network/10-netplan-eth0.netwo> - Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: DHCPv6 lease lost - ``` + Sep 11 23:32:44 ubuntu systemd-networkd[2452]: lo: Gained carrier + Sep 11 23:32:44 ubuntu systemd-networkd[2452]: wlan0: Gained IPv6LL + Sep 11 23:32:44 ubuntu systemd-networkd[2452]: eth0: Gained IPv6LL + Sep 11 23:32:44 ubuntu systemd-networkd[2452]: Enumeration completed + Sep 11 23:32:44 ubuntu systemd[1]: Started Network Configuration. + Sep 11 23:32:44 ubuntu systemd-networkd[2452]: wlan0: Connected WiFi access point: Verizon_7YLWWD (78:67:0e:ea:a6:0> + Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: Re-configuring with /run/systemd/network/10-netplan-eth0.netwo> + Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: DHCPv6 lease lost + Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: Re-configuring with /run/systemd/network/10-netplan-eth0.netwo> + Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: DHCPv6 lease lost + ``` - If `system_networkd` is not running, it can be enabled using: + If `system_networkd` is not running, it can be enabled using: - ```sh - sudo systemctl start systemd-networkd - sudo systemctl enable systemd-networkd - ``` + ```sh + sudo systemctl start systemd-networkd + sudo systemctl enable systemd-networkd + ``` 3. Open the Netplan configuration file (so we can set up a static IP for the Jetson). - The Netplan configuration file is usually located in the `/etc/netplan/` directory and named something like `01-netcfg.yaml` (the name can vary). - Below we use `nano` to open the file, but you can use your preferred text editor: + The Netplan configuration file is usually located in the `/etc/netplan/` directory and named something like `01-netcfg.yaml` (the name can vary). + Below we use `nano` to open the file, but you can use your preferred text editor: - ```sh - sudo nano /etc/netplan/01-netcfg.yaml - ``` + ```sh + sudo nano /etc/netplan/01-netcfg.yaml + ``` 4. Modify the yaml configuration, by overwriting the contents with the following information and then saving: - ```sh - network: - version: 2 - renderer: networkd - ethernets: - eth0: - dhcp4: no - addresses: - - 10.41.10.1/24 - routes: - - to: 0.0.0.0/0 - via: 10.41.10.254 - nameservers: - addresses: - - 10.41.10.254 - ``` + ```sh + network: + version: 2 + renderer: networkd + ethernets: + eth0: + dhcp4: no + addresses: + - 10.41.10.1/24 + routes: + - to: 0.0.0.0/0 + via: 10.41.10.254 + nameservers: + addresses: + - 10.41.10.254 + ``` - This gives the Jetson a static IP address on the Ethernet interface of `10.41.10.1` . + This gives the Jetson a static IP address on the Ethernet interface of `10.41.10.1` . 5. Apply the changes using the following command: - ```sh - sudo netplan apply - ``` + ```sh + sudo netplan apply + ``` The Pixhawk Ethernet address is set to `10.41.10.2` by default, which is on the same subnet. We can test our changes above by pinging the Pixhawk from within the Jetson terminal: diff --git a/docs/zh/companion_computer/holybro_pixhawk_rpi_cm4_baseboard.md b/docs/zh/companion_computer/holybro_pixhawk_rpi_cm4_baseboard.md index 5c331fd9bb..edece004af 100644 --- a/docs/zh/companion_computer/holybro_pixhawk_rpi_cm4_baseboard.md +++ b/docs/zh/companion_computer/holybro_pixhawk_rpi_cm4_baseboard.md @@ -69,15 +69,15 @@ To install the RPi CM4 companion computer: 1. Disconnect the `FAN` wiring. - ![HB_Pixhawk_CM4_Fan](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/baseboard_fan.jpg) + ![HB_Pixhawk_CM4_Fan](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/baseboard_fan.jpg) 2. Remove these 4 screws on the back side of the baseboard. - ![Bottom of the board showing screws in corners holding the cover](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/baseboard_bottom.jpg) + ![Bottom of the board showing screws in corners holding the cover](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/baseboard_bottom.jpg) 3. Remove the baseboard case, install the CM4, and use the 4 screws to attach it (as shown): - ![HB_Pixhawk_CM4_Screws](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/baseboard_screws.jpg) + ![HB_Pixhawk_CM4_Screws](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/baseboard_screws.jpg) 4. Reattach the cover. @@ -115,29 +115,29 @@ To flash a RPi image onto EMMC. 1. Switch Dip-Switch to `RPI`. - ![](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/cm4_dip_switch.png) + ![](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/cm4_dip_switch.png) 2. Connect computer to USB-C _CM4 Slave_ port used to power & flash the RPi. - ![](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/cm4_usbc_slave_port.png) + ![](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/cm4_usbc_slave_port.png) 3. Get `usbboot`, build it and run it. - ```sh - sudo apt install libusb-1.0-0-dev - git clone --depth=1 https://github.com/raspberrypi/usbboot - cd usbboot - make - sudo ./rpiboot - ``` + ```sh + sudo apt install libusb-1.0-0-dev + git clone --depth=1 https://github.com/raspberrypi/usbboot + cd usbboot + make + sudo ./rpiboot + ``` 4. You can now install your preferred Linux distro using The `rpi-imager`. - Make sure you add WiFi and SSH settings (hidden behind the gear/advanced symbol). + Make sure you add WiFi and SSH settings (hidden behind the gear/advanced symbol). - ```sh - sudo apt install rpi-imager - rpi-imager - ``` + ```sh + sudo apt install rpi-imager + rpi-imager + ``` 5. Once done, unplugging USB-C CM4 Slave (this will unmount the volumes, and power off the CM4). @@ -146,8 +146,8 @@ To flash a RPi image onto EMMC. 7. Power on CM4 by providing power to USB-C CM4 Slave port. 8. To check if it's booting/working you can either: - - Check there is HDMI output - - Connect via SSH (if set up in rpi-imager, and WiFi is available). + - Check there is HDMI output + - Connect via SSH (if set up in rpi-imager, and WiFi is available). ## Configure PX4 to CM4 MAVLink Serial Connection @@ -167,13 +167,13 @@ To enable this MAVLink instance on the FC: 1. Connect a computer running QGroundControl via USB Type C port on the baseboard labeled `FC` - ![Image of baseboard showing FC USB-C connector](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/baseboard_fc_usb_c.jpg) + ![Image of baseboard showing FC USB-C connector](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/baseboard_fc_usb_c.jpg) 2. [Set the parameters](../advanced_config/parameters.md): - - `MAV_1_CONFIG` = `102` - - `MAV_1_MODE = 2` - - `SER_TEL2_BAUD` = `921600` + - `MAV_1_CONFIG` = `102` + - `MAV_1_MODE = 2` + - `SER_TEL2_BAUD` = `921600` 3. Reboot the FC. @@ -185,13 +185,13 @@ On the RPi side: 2. Enable the RPi serial port by running `RPi-config` - - Go to `3 Interface Options`, then `I6 Serial Port`. - Then choose: - - `login shell accessible over serial → No` - - `serial port hardware enabled` → `Yes` + - Go to `3 Interface Options`, then `I6 Serial Port`. + Then choose: + - `login shell accessible over serial → No` + - `serial port hardware enabled` → `Yes` 3. Finish, and reboot. - This will add `enable_uart=1` to `/boot/config.txt`, and remove `console=serial0,115200` from `/boot/cmdline.txt`. + This will add `enable_uart=1` to `/boot/config.txt`, and remove `console=serial0,115200` from `/boot/cmdline.txt`. 4. Now MAVLink traffic should be available on `/dev/serial0` at a baudrate of 921600. @@ -201,9 +201,9 @@ On the RPi side: 2. Install MAVSDK Python: - ```sh - python3 -m pip install mavsdk - ``` + ```sh + python3 -m pip install mavsdk + ``` 3. Copy an example from the [MAVSDK-Python examples](https://github.com/mavlink/MAVSDK-Python/tree/main/examples). diff --git a/docs/zh/companion_computer/pixhawk_rpi.md b/docs/zh/companion_computer/pixhawk_rpi.md index 26948bd350..beb8a1f7fe 100644 --- a/docs/zh/companion_computer/pixhawk_rpi.md +++ b/docs/zh/companion_computer/pixhawk_rpi.md @@ -132,50 +132,50 @@ Enter the following commands (in sequence) a terminal to configure Ubuntu for RP 1. Install `raspi-config`: - ```sh - sudo apt update - sudo apt upgrade - sudo apt-get install raspi-config - ``` + ```sh + sudo apt update + sudo apt upgrade + sudo apt-get install raspi-config + ``` 2. Open `raspi-config`: - ```sh - sudo raspi-config - ``` + ```sh + sudo raspi-config + ``` 3. Go to the **Interface Option** and then click **Serial Port**. - - Select **No** to disable serial login shell. - - Select **Yes** to enable the serial interface. - - Click **Finish** and restart the RPi. + - Select **No** to disable serial login shell. + - Select **Yes** to enable the serial interface. + - Click **Finish** and restart the RPi. 4. Open the firmware boot configuration file in the `nano` editor on RPi: - ```sh - sudo nano /boot/firmware/config.txt - ``` + ```sh + sudo nano /boot/firmware/config.txt + ``` 5. Append the following text to the end of the file (after the last line): - ```sh - enable_uart=1 - dtoverlay=disable-bt - ``` + ```sh + enable_uart=1 + dtoverlay=disable-bt + ``` 6. Then save the file and restart the RPi. - - In `nano` you can save the file using the following sequence of keyboard shortcuts: **ctrl+x**, **ctrl+y**, **Enter**. + - In `nano` you can save the file using the following sequence of keyboard shortcuts: **ctrl+x**, **ctrl+y**, **Enter**. 7. Check that the serial port is available. - In this case we use the following terminal commands to list the serial devices: + In this case we use the following terminal commands to list the serial devices: - ```sh - cd / - ls /dev/ttyAMA0 - ``` + ```sh + cd / + ls /dev/ttyAMA0 + ``` - The result of the command should include the RX/TX connection `/dev/ttyAMA0` (note that this serial port is also available as `/dev/serial0`). + The result of the command should include the RX/TX connection `/dev/ttyAMA0` (note that this serial port is also available as `/dev/serial0`). The RPi is now setup to work with RPi and communicate using the `/dev/ttyAMA0` serial port. Note that we'll install more software in the following sections to work with MAVLink and ROS 2. @@ -199,39 +199,39 @@ First check the Pixhawk `TELEM 2` configuration: 2. Open QGroundControl (the vehicle should connect). 3. [Check/change the following parameters](../advanced_config/parameters.md) in QGroundControl: - ```ini - MAV_1_CONFIG = TELEM2 - UXRCE_DDS_CFG = 0 (Disabled) - SER_TEL2_BAUD = 57600 - ``` + ```ini + MAV_1_CONFIG = TELEM2 + UXRCE_DDS_CFG = 0 (Disabled) + SER_TEL2_BAUD = 57600 + ``` - Note that the parameters may already be set appropriately. - For information about how serial ports and MAVLink configuration work see [Serial Port Configuration](../peripherals/serial_configuration.md) and [MAVLink Peripherals](../peripherals/mavlink_peripherals.md). + Note that the parameters may already be set appropriately. + For information about how serial ports and MAVLink configuration work see [Serial Port Configuration](../peripherals/serial_configuration.md) and [MAVLink Peripherals](../peripherals/mavlink_peripherals.md). Then install setup MAVProxy on the RPi using the following terminal commands: 1. Install MAVProxy: - ```sh - sudo apt install python3-pip - sudo pip3 install mavproxy - sudo apt remove modemmanager - ``` + ```sh + sudo apt install python3-pip + sudo pip3 install mavproxy + sudo apt remove modemmanager + ``` 2. Run MAVProxy, setting the port to connect to `/dev/ttyAMA0` and the baud rate to match the PX4: - ```sh - sudo mavproxy.py --master=/dev/serial0 --baudrate 57600 - ``` + ```sh + sudo mavproxy.py --master=/dev/serial0 --baudrate 57600 + ``` - ::: info - Note that above we used `/dev/serial0`, but we could equally well have used `/dev/ttyAMA0`. - If we were connecting via USB then we would instead set the port as `/dev/ttyACM0`: + ::: info + Note that above we used `/dev/serial0`, but we could equally well have used `/dev/ttyAMA0`. + If we were connecting via USB then we would instead set the port as `/dev/ttyACM0`: - ```sh - sudo chmod a+rw /dev/ttyACM0 - sudo mavproxy.py --master=/dev/ttyACM0 --baudrate 57600 - ``` + ```sh + sudo chmod a+rw /dev/ttyACM0 + sudo mavproxy.py --master=/dev/ttyACM0 --baudrate 57600 + ``` ::: @@ -259,27 +259,27 @@ The configuration steps are: 2. [Check/change the following parameters](../advanced_config/parameters.md) in QGroundControl: - ```ini - MAV_1_CONFIG = 0 (Disabled) - UXRCE_DDS_CFG = 102 (TELEM2) - SER_TEL2_BAUD = 921600 - ``` + ```ini + MAV_1_CONFIG = 0 (Disabled) + UXRCE_DDS_CFG = 102 (TELEM2) + SER_TEL2_BAUD = 921600 + ``` - [MAV_1_CONFIG=0](../advanced_config/parameter_reference.md#MAV_1_CONFIG) and [UXRCE_DDS_CFG=102](../advanced_config/parameter_reference.md#UXRCE_DDS_CFG) disable MAVLink on TELEM2 and enable the uXRCE-DDS client on TELEM2, respectively. - The `SER_TEL2_BAUD` rate sets the comms link data rate.\ - You could similarly configure a connection to `TELEM1` using either `MAV_1_CONFIG` or `MAV_0_CONFIG`. + [MAV_1_CONFIG=0](../advanced_config/parameter_reference.md#MAV_1_CONFIG) and [UXRCE_DDS_CFG=102](../advanced_config/parameter_reference.md#UXRCE_DDS_CFG) disable MAVLink on TELEM2 and enable the uXRCE-DDS client on TELEM2, respectively. + The `SER_TEL2_BAUD` rate sets the comms link data rate.\ + You could similarly configure a connection to `TELEM1` using either `MAV_1_CONFIG` or `MAV_0_CONFIG`. - ::: info - You will need to reboot the flight controller to apply any changes to these parameters. + ::: info + You will need to reboot the flight controller to apply any changes to these parameters. ::: 3. Check that the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) module is now running. - YOu can do this by running the following command in the QGroundControl [MAVLink Console](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/analyze_view/mavlink_console.html): + YOu can do this by running the following command in the QGroundControl [MAVLink Console](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/analyze_view/mavlink_console.html): - ```sh - uxrce_dds_client status - ``` + ```sh + uxrce_dds_client status + ``` :::info If the client module is not running you can start it manually in the MAVLink console: @@ -300,32 +300,32 @@ The steps to setup ROS 2 and the Micro XRCE-DDS Agent on the RPi are: 2. Install the git using the RPi terminal: - ```sh - sudo apt install git - ``` + ```sh + sudo apt install git + ``` 3. Install the uXRCE_DDS agent: - ```sh - git clone https://github.com/eProsima/Micro-XRCE-DDS-Agent.git - cd Micro-XRCE-DDS-Agent - mkdir build - cd build - cmake .. - make - sudo make install - sudo ldconfig /usr/local/lib/ - ``` + ```sh + git clone https://github.com/eProsima/Micro-XRCE-DDS-Agent.git + cd Micro-XRCE-DDS-Agent + mkdir build + cd build + cmake .. + make + sudo make install + sudo ldconfig /usr/local/lib/ + ``` - See [uXRCE-DDS > Micro XRCE-DDS Agent Installation](../middleware/uxrce_dds.md#micro-xrce-dds-agent-installation) for alternative ways of installing the agent. + See [uXRCE-DDS > Micro XRCE-DDS Agent Installation](../middleware/uxrce_dds.md#micro-xrce-dds-agent-installation) for alternative ways of installing the agent. 4. Start the agent in the RPi terminal: - ```sh - sudo MicroXRCEAgent serial --dev /dev/serial0 -b 921600 - ``` + ```sh + sudo MicroXRCEAgent serial --dev /dev/serial0 -b 921600 + ``` - Note how we use the serial port set up earlier and the same baud rate as for PX4. + Note how we use the serial port set up earlier and the same baud rate as for PX4. Now that both the agent and client are running, you should see activity on both the MAVLink console and the RPi terminal. You can view the available topics using the following command on the RPi: diff --git a/docs/zh/companion_computer/video_streaming_wfb_ng_wifi.md b/docs/zh/companion_computer/video_streaming_wfb_ng_wifi.md index 80227c2b6d..86982c4b20 100644 --- a/docs/zh/companion_computer/video_streaming_wfb_ng_wifi.md +++ b/docs/zh/companion_computer/video_streaming_wfb_ng_wifi.md @@ -80,18 +80,18 @@ If you use a special "very" high power cards from Taobao/Aliexpress then you MUS 5. Setup camera pipeline. Open `/etc/systemd/system/fpv-camera.service` and uncomment pipeline according to your camera (PI camera or Logitech camera) 6. Open `/etc/wifibroadcast.cfg` and configure WiFi channel according to your antenna setup (or use default #165 for 5.8GHz) 7. Configure PX4 to output telemetry stream at speed 1500 Kbps (other UART speeds doesn't match well to RPi frequency dividers). - Connect Pixhawk UART to Raspberry Pi UART. - In `/etc/wifibroadcast.cfg` uncomment `peer = 'serial:ttyS0:1500000'` in `[drone_mavlink]` section. + Connect Pixhawk UART to Raspberry Pi UART. + In `/etc/wifibroadcast.cfg` uncomment `peer = 'serial:ttyS0:1500000'` in `[drone_mavlink]` section. ### Using a Linux Laptop as GCS (Harder than using a RPi) 1. On **ground** Linux development computer: - ```sh - sudo apt install libpcap-dev libsodium-dev python3-all python3-twisted - git clone -b stable https://github.com/svpcom/wfb-ng.git - cd wfb-ng && make deb && sudo apt install ./deb_dist/wfb-ng*.deb - ``` + ```sh + sudo apt install libpcap-dev libsodium-dev python3-all python3-twisted + git clone -b stable https://github.com/svpcom/wfb-ng.git + cd wfb-ng && make deb && sudo apt install ./deb_dist/wfb-ng*.deb + ``` 2. Follow the [Setup HOWTO](https://github.com/svpcom/wfb-ng/wiki/Setup-HOWTO) to complete installation diff --git a/docs/zh/complete_vehicles_mc/amov_F410_drone.md b/docs/zh/complete_vehicles_mc/amov_F410_drone.md index 1a64d3a506..8c90fbf1bd 100644 --- a/docs/zh/complete_vehicles_mc/amov_F410_drone.md +++ b/docs/zh/complete_vehicles_mc/amov_F410_drone.md @@ -22,7 +22,7 @@ It is pre-installed with PX4 v1.15.4 at time of writing (a more recent version m - Compatibility with many different components, providing platform for loading other user sensors, preparing for functional model development. - Abundant power supply making it perfect for installing additional sensors and onboard computers (including 5 external output voltages, 3 channels of 5V, 2 channels of 12V). - Pc-SDK support. - This is a PC-based Python SDK Library based on MAVSDK that significantly simplifies UAV development compared to other approaches, such as using ROS or using C++. All you need is a basic understanding of Python programming and some simple coordinate system principles! + This is a PC-based Python SDK Library based on MAVSDK that significantly simplifies UAV development compared to other approaches, such as using ROS or using C++. All you need is a basic understanding of Python programming and some simple coordinate system principles! - The [documentation](https://docs.amovlab.com/f450-v6c-wiki/#/en/) shows many of the options. 7. Quasi-smart battery. The battery has a hard housing design that makes easy to install and remove. It provides accurate power estimates, but does not have some more advanced "smart battery" features. diff --git a/docs/zh/complete_vehicles_mc/crazyflie2.md b/docs/zh/complete_vehicles_mc/crazyflie2.md index 57e7af9c1d..67534784c5 100644 --- a/docs/zh/complete_vehicles_mc/crazyflie2.md +++ b/docs/zh/complete_vehicles_mc/crazyflie2.md @@ -51,54 +51,54 @@ After setting up the PX4 development environment, follow these steps to install 1. Download the source code of the PX4 Bootloader: - ```sh - git clone https://github.com/PX4/PX4-Bootloader.git - ``` + ```sh + git clone https://github.com/PX4/PX4-Bootloader.git + ``` 2. Navigate into the top directory of the source code and compile it using: - ```sh - make crazyflie_bl - ``` + ```sh + make crazyflie_bl + ``` 3. Put the Crazyflie 2.0 into DFU mode by following these steps: - - Ensure it is initially unpowered. - - Hold down the reset button (see figure below...). - ![Crazyflie2 Reset Button](../../assets/flight_controller/crazyflie/crazyflie_reset_button.jpg) - - Plug into computer's USB port. - - After a second, the blue LED should start blinking and after 5 seconds should start blinking faster. - - Release button. + - Ensure it is initially unpowered. + - Hold down the reset button (see figure below...). + ![Crazyflie2 Reset Button](../../assets/flight_controller/crazyflie/crazyflie_reset_button.jpg) + - Plug into computer's USB port. + - After a second, the blue LED should start blinking and after 5 seconds should start blinking faster. + - Release button. 4. Install _dfu-util_: - ```sh - sudo apt-get update - sudo apt-get install dfu-util - ``` + ```sh + sudo apt-get update + sudo apt-get install dfu-util + ``` 5. Flash bootloader using _dfu-util_ and unplug Crazyflie 2.0 when done: - ```sh - sudo dfu-util -d 0483:df11 -a 0 -s 0x08000000 -D ./build/crazyflie_bl/crazyflie_bl.bin - ``` + ```sh + sudo dfu-util -d 0483:df11 -a 0 -s 0x08000000 -D ./build/crazyflie_bl/crazyflie_bl.bin + ``` - When powering on the Crazyflie 2.0 the yellow LED should blink. + When powering on the Crazyflie 2.0 the yellow LED should blink. 6. Download the source code of the PX4 autopilot: - ```sh - git clone https://github.com/PX4/PX4-Autopilot.git - ``` + ```sh + git clone https://github.com/PX4/PX4-Autopilot.git + ``` 7. Navigate into the top directory of the source code and compile it using: - ```sh - make bitcraze_crazyflie_default upload - ``` + ```sh + make bitcraze_crazyflie_default upload + ``` 8. When prompted to plug in device, plug in Crazyflie 2.0. - The yellow LED should start blinking indicating bootloader mode. - Then the red LED should turn on indicating that the flashing process has started. + The yellow LED should start blinking indicating bootloader mode. + Then the red LED should turn on indicating that the flashing process has started. 9. Wait for completion. diff --git a/docs/zh/complete_vehicles_mc/crazyflie21.md b/docs/zh/complete_vehicles_mc/crazyflie21.md index 3002164a54..370c0b61d1 100644 --- a/docs/zh/complete_vehicles_mc/crazyflie21.md +++ b/docs/zh/complete_vehicles_mc/crazyflie21.md @@ -64,56 +64,56 @@ After setting up the PX4 development environment, follow these steps to install 1. Download the source code of the PX4 Bootloader: - ```sh - git clone https://github.com/PX4/PX4-Bootloader.git --recurse-submodules - ``` + ```sh + git clone https://github.com/PX4/PX4-Bootloader.git --recurse-submodules + ``` 2. Navigate into the top directory of the source code and compile it using: - ```sh - make crazyflie21_bl - ``` + ```sh + make crazyflie21_bl + ``` 3. Put the Crazyflie 2.1 into DFU mode by following these steps: - - Ensure it is initially unpowered. - - Ensure battery is disconnected. - - Hold down the reset button (see figure below...). - ![Crazyflie2 Reset Button](../../assets/flight_controller/crazyflie/crazyflie_reset_button.jpg) - - Plug into computer's USB port. - - After a second, the blue LED should start blinking and after 5 seconds should start blinking faster. - - Release button. + - Ensure it is initially unpowered. + - Ensure battery is disconnected. + - Hold down the reset button (see figure below...). + ![Crazyflie2 Reset Button](../../assets/flight_controller/crazyflie/crazyflie_reset_button.jpg) + - Plug into computer's USB port. + - After a second, the blue LED should start blinking and after 5 seconds should start blinking faster. + - Release button. 4. Install _dfu-util_: - ```sh - sudo apt-get update - sudo apt-get install dfu-util - ``` + ```sh + sudo apt-get update + sudo apt-get install dfu-util + ``` 5. Flash bootloader using _dfu-util_ and unplug Crazyflie 2.1 when done: - ```sh - sudo dfu-util -d 0483:df11 -a 0 -s 0x08000000 -D ./build/crazyflie21_bl/crazyflie21_bl.bin - ``` + ```sh + sudo dfu-util -d 0483:df11 -a 0 -s 0x08000000 -D ./build/crazyflie21_bl/crazyflie21_bl.bin + ``` - When powering on the Crazyflie 2.1 the yellow LED should blink. + When powering on the Crazyflie 2.1 the yellow LED should blink. 6. Download the source code of the PX4 autopilot: - ```sh - git clone https://github.com/PX4/PX4-Autopilot.git - ``` + ```sh + git clone https://github.com/PX4/PX4-Autopilot.git + ``` 7. Navigate into the top directory of the source code and compile it using: - ```sh - cd PX4-Autopilot/ - make bitcraze_crazyflie21_default upload - ``` + ```sh + cd PX4-Autopilot/ + make bitcraze_crazyflie21_default upload + ``` 8. When prompted to plug in device, plug in Crazyflie 2.1. - The yellow LED should start blinking indicating bootloader mode. - Then the red LED should turn on indicating that the flashing process has started. + The yellow LED should start blinking indicating bootloader mode. + Then the red LED should turn on indicating that the flashing process has started. 9. Wait for completion. @@ -124,20 +124,20 @@ After setting up the PX4 development environment, follow these steps to install 1. Download the latest [Crazyflie 2.1 bootloader](https://github.com/bitcraze/crazyflie2-stm-bootloader/releases) 2. Put the Crazyflie 2.1 into DFU mode by following these steps: - - Ensure it is initially unpowered. - - Ensure battery is disconnected. - - Hold down the reset button. - - Plug into computer's USB port. - - After a second, the blue LED should start blinking and after 5 seconds should start blinking faster. - - Release button. + - Ensure it is initially unpowered. + - Ensure battery is disconnected. + - Hold down the reset button. + - Plug into computer's USB port. + - After a second, the blue LED should start blinking and after 5 seconds should start blinking faster. + - Release button. 3. Flash bootloader using _dfu-util_ and unplug Crazyflie 2.1 when done: - ```sh - sudo dfu-util -d 0483:df11 -a 0 -s 0x08000000 -D cf2loader-1.0.bin - ``` + ```sh + sudo dfu-util -d 0483:df11 -a 0 -s 0x08000000 -D cf2loader-1.0.bin + ``` - When powering on the Crazyflie 2.1 the yellow LED should blink. + When powering on the Crazyflie 2.1 the yellow LED should blink. 4. Install the latest Bitcraze Crazyflie 2.1 Firmware using [this](https://www.bitcraze.io/documentation/tutorials/getting-started-with-crazyflie-2-x/#update-fw) tutorial. diff --git a/docs/zh/complete_vehicles_mc/modalai_starling.md b/docs/zh/complete_vehicles_mc/modalai_starling.md index 3791ce71f9..b77b081501 100644 --- a/docs/zh/complete_vehicles_mc/modalai_starling.md +++ b/docs/zh/complete_vehicles_mc/modalai_starling.md @@ -84,26 +84,26 @@ Follow this guide to bind your ELRS receiver to your transmitter. #### Setting up the Receiver 1. **Power On the Receiver**: Once your drone is powered on, you'll notice the ELRS receiver's blue LED flashing. - This is an indication that the receiver is on but has not yet established a connection with a transmitter. + This is an indication that the receiver is on but has not yet established a connection with a transmitter. - ![Starling Receiver](../../assets/hardware/complete_vehicles/modalai_starling/starling-photo.png) + ![Starling Receiver](../../assets/hardware/complete_vehicles/modalai_starling/starling-photo.png) 2. **Enter Binding Mode**: To initiate binding, open a terminal and execute the `adb shell` and `voxl-elrs -bind` commands. - You'll observe the receiver's LED switch to a flashing in a heartbeat pattern, signaling that it is now in binding mode. + You'll observe the receiver's LED switch to a flashing in a heartbeat pattern, signaling that it is now in binding mode. - ![Boot Screenshot](../../assets/hardware/complete_vehicles/modalai_starling/screenshot-boot.png) + ![Boot Screenshot](../../assets/hardware/complete_vehicles/modalai_starling/screenshot-boot.png) #### Setting up the Transmitter 1. **Access the Menu**: On your Commando 8 radio transmitter included in the kit, press the left mode button to open the menu system. - ![Press Menu on RC](../../assets/hardware/complete_vehicles/modalai_starling/radio-1.png) + ![Press Menu on RC](../../assets/hardware/complete_vehicles/modalai_starling/radio-1.png) 2. **Navigate to ExpressLRS**: Use the right button to select the first menu entry, which should be "ExpressLRS." 3. **Find the Bind Option**: With the "ExpressLRS" option selected, scroll down to the bottom of the menu to locate the "Bind" section. This can be done by pressing the right button downwards until you reach the "Bind" option. - ![Press Binding on RC](../../assets/hardware/complete_vehicles/modalai_starling/radio-2.png) + ![Press Binding on RC](../../assets/hardware/complete_vehicles/modalai_starling/radio-2.png) 4. **Initiate Binding**: Select "Bind" to put the transmitter into binding mode. You will know the process has been successful when the transmitter emits a beep, indicating a successful bind. diff --git a/docs/zh/complete_vehicles_mc/px4_vision_kit.md b/docs/zh/complete_vehicles_mc/px4_vision_kit.md index 4a1fb66457..422ed34af2 100644 --- a/docs/zh/complete_vehicles_mc/px4_vision_kit.md +++ b/docs/zh/complete_vehicles_mc/px4_vision_kit.md @@ -42,17 +42,17 @@ This kit is still highly recommended for developing and testing vision solutions ## Warnings and Notifications 1. The kit is intended for computer vision projects that use a forward-facing camera (it does not have downward or rear-facing depth cameras). - Consequently it can't be used (without modification) for testing features that require a downward-facing camera. + Consequently it can't be used (without modification) for testing features that require a downward-facing camera. 2. Obstacle avoidance in missions can only be tested when GPS is available (missions use GPS coordinates). - Collision prevention can be tested in position mode provided there is a good position lock from either GPS or optical flow. + Collision prevention can be tested in position mode provided there is a good position lock from either GPS or optical flow. 3. The port labeled `USB1` may jam the GPS if used with a _USB3_ peripheral (disable GPS-dependent functionality including missions). - This is why the boot image is supplied on a _USB2.0_ memory stick. + This is why the boot image is supplied on a _USB2.0_ memory stick. 4. PX4 Vision v1 with ECN 010 or above (carrier board RC05 and up), the _UP Core_ can be powered by either the DC plug or with battery. - ![RC Number](../../assets/hardware/px4_vision_devkit/rc.png) ![ECN Number](../../assets/hardware/px4_vision_devkit/serial_number_update.jpg) + ![RC Number](../../assets/hardware/px4_vision_devkit/rc.png) ![ECN Number](../../assets/hardware/px4_vision_devkit/serial_number_update.jpg) 5. All PX4 Vision v1.5 _UP Core_ can be powered by either the DC plug or with battery. @@ -132,37 +132,37 @@ In addition, users will need ground station hardware/software: ## First-time Setup 1. Attach a [compatible RC receiver](../getting_started/rc_transmitter_receiver.md#connecting-receivers) to the vehicle (not supplied with kit): - - Remove/unscrew the top plate (where the battery goes) using an H2.0 hex key tool. - - [Connect the receiver to the flight controller](../assembly/quick_start_pixhawk4.md#radio-control). - - Re-attach the top plate. - - Mount the RC receiver on the _UP Core_ carrier board plate at the back of the vehicle (use zipties or double-sided tape). - - Ensure the antennas are clear of any obstructions and electrically isolated from the frame (e.g. secure them under the carrier board or to the vehicle arms or legs). + - Remove/unscrew the top plate (where the battery goes) using an H2.0 hex key tool. + - [Connect the receiver to the flight controller](../assembly/quick_start_pixhawk4.md#radio-control). + - Re-attach the top plate. + - Mount the RC receiver on the _UP Core_ carrier board plate at the back of the vehicle (use zipties or double-sided tape). + - Ensure the antennas are clear of any obstructions and electrically isolated from the frame (e.g. secure them under the carrier board or to the vehicle arms or legs). 2. [Bind](../getting_started/rc_transmitter_receiver.md#binding) the RC ground and air units (if not already done). - The binding procedure depends on the specific radio system used (read the receiver manual). + The binding procedure depends on the specific radio system used (read the receiver manual). 3. Raise the GPS mast to the vertical position and screw the cover onto the holder on the base plate. (Not required for v1.5) - ![Raise GPS mast](../../assets/hardware/px4_vision_devkit/raise_gps_mast.jpg) + ![Raise GPS mast](../../assets/hardware/px4_vision_devkit/raise_gps_mast.jpg) 4. Insert the pre-imaged USB2.0 stick from the kit into the _UP Core_ port labeled `USB1` (highlighted below). - ![UP Core: USB1 Port ](../../assets/hardware/px4_vision_devkit/upcore_port_usb1.png) + ![UP Core: USB1 Port ](../../assets/hardware/px4_vision_devkit/upcore_port_usb1.png) 5. Power the vehicle with a fully charged battery. - ::: info - Ensure propellers are removed before connecting the battery. + ::: info + Ensure propellers are removed before connecting the battery. ::: 6. Connect the ground station to the vehicle WiFi network (after a few seconds) using the following default credentials: - - **SSID:** pixhawk4 - - **Password:** pixhawk4 + - **SSID:** pixhawk4 + - **Password:** pixhawk4 - :::tip - WiFi network SSID, password, and other credentials may be changed after connecting (if desired), by using a web browser to open the URL: `http://192.168.4.1`. - The baud rate must not be changed from 921600. + :::tip + WiFi network SSID, password, and other credentials may be changed after connecting (if desired), by using a web browser to open the URL: `http://192.168.4.1`. + The baud rate must not be changed from 921600. ::: @@ -170,39 +170,39 @@ In addition, users will need ground station hardware/software: 8. [Configure/calibrate](../config/index.md) the vehicle: - ::: info - The vehicle should arrive pre-calibrated (e.g. with firmware, airframe, battery, and sensors all setup). - You will however need to calibrate the radio system (that you just connected) and it is often worth re-doing the compass calibration. + ::: info + The vehicle should arrive pre-calibrated (e.g. with firmware, airframe, battery, and sensors all setup). + You will however need to calibrate the radio system (that you just connected) and it is often worth re-doing the compass calibration. ::: - - [Calibrate the Radio System](../config/radio.md) - - [Calibrate the Compass](../config/compass.md) + - [Calibrate the Radio System](../config/radio.md) + - [Calibrate the Compass](../config/compass.md) 9. (Optional) Configure a [Flight Mode selector switch](../config/flight_mode.md) on the remote controller. - ::: info - Modes can also be changed using _QGroundControl_ + ::: info + Modes can also be changed using _QGroundControl_ ::: - We recommend RC controller switches are define for: + We recommend RC controller switches are define for: - - [Position Mode](../flight_modes_mc/position.md) - a safe manual flight mode that can be used to test collision prevention. - - [Mission Mode](../flight_modes_mc/mission.md) - run missions and test obstacle avoidance. - - [Return Mode](../flight_modes_mc/return.md) - return vehicle safely to its launch point and land. + - [Position Mode](../flight_modes_mc/position.md) - a safe manual flight mode that can be used to test collision prevention. + - [Mission Mode](../flight_modes_mc/mission.md) - run missions and test obstacle avoidance. + - [Return Mode](../flight_modes_mc/return.md) - return vehicle safely to its launch point and land. 10. Attach the propellers with the rotations as shown: - ![Motor Order Diagram](../../assets/hardware/px4_vision_devkit/motor_order_diagram.png) + ![Motor Order Diagram](../../assets/hardware/px4_vision_devkit/motor_order_diagram.png) - - The propellers directions can be determined from the labels: _6045_ (normal, counter-clockwise) and _6045_**R** (reversed, clockwise). + - The propellers directions can be determined from the labels: _6045_ (normal, counter-clockwise) and _6045_**R** (reversed, clockwise). - ![Propeller identification](../../assets/hardware/px4_vision_devkit/propeller_directions.jpg) + ![Propeller identification](../../assets/hardware/px4_vision_devkit/propeller_directions.jpg) - - Screw down firmly using the provided propellor nuts: + - Screw down firmly using the provided propellor nuts: - ![Propeller nuts](../../assets/hardware/px4_vision_devkit/propeller_nuts.png) + ![Propeller nuts](../../assets/hardware/px4_vision_devkit/propeller_nuts.png) ## Fly the Drone with Avoidance @@ -212,30 +212,30 @@ When the vehicle setup described above is complete: 2. Wait until the boot sequence completes and the avoidance system has started (the vehicle will reject arming commands during boot). - :::tip - The boot/startup process takes around 1 minute from the supplied USB stick (or 30 seconds from [internal memory](#install_image_mission_computer)). + :::tip + The boot/startup process takes around 1 minute from the supplied USB stick (or 30 seconds from [internal memory](#install_image_mission_computer)). ::: 3. Check that the avoidance system has started properly: - - The _QGroundControl_ notification log displays the message: **Avoidance system connected**. + - The _QGroundControl_ notification log displays the message: **Avoidance system connected**. - ![QGC Log showing avoidance system has started](../../assets/hardware/px4_vision_devkit/qgc_console_vision_system_started.jpg) + ![QGC Log showing avoidance system has started](../../assets/hardware/px4_vision_devkit/qgc_console_vision_system_started.jpg) - - A red laser is visible on the front of the _Structure Core_ camera. + - A red laser is visible on the front of the _Structure Core_ camera. 4. Wait for the GPS LED to turn green. - This means that the vehicle has a GPS fix and is ready to fly! + This means that the vehicle has a GPS fix and is ready to fly! 5. Connect the ground station to the vehicle WiFi network. 6. Find a safe outdoor location for flying, ideally with a tree or some other convenient obstacle for testing PX4 Vision. 7. To test [collision prevention](../computer_vision/collision_prevention.md), enable [Position Mode](../flight_modes_mc/position.md) and fly manually towards an obstacle. - The vehicle should slow down and then stop within 6m of the obstacle (the distance can be [changed](../advanced_config/parameters.md) using the [CP_DIST](../advanced_config/parameter_reference.md#CP_DIST) parameter). + The vehicle should slow down and then stop within 6m of the obstacle (the distance can be [changed](../advanced_config/parameters.md) using the [CP_DIST](../advanced_config/parameter_reference.md#CP_DIST) parameter). 8. To test obstacle avoidance, create a mission where the path is blocked by an obstacle. - Then switch to [Mission Mode](../flight_modes_mc/mission.md) to run the mission, and observe the vehicle moving around the obstacle and then returning to the planned course. + Then switch to [Mission Mode](../flight_modes_mc/mission.md) to run the mission, and observe the vehicle moving around the obstacle and then returning to the planned course. ## Development using the Kit @@ -280,22 +280,22 @@ To flash the USB image to the _UP Core_: 2. [Login to the companion computer](#login_mission_computer) (as described above). 3. Open a terminal and run the following command to copy the image onto internal memory (eMMC). - The terminal will prompt for a number of responses during the flashing process. + The terminal will prompt for a number of responses during the flashing process. - ```sh - cd ~/catkin_ws/src/px4vision_ros/tools - sudo ./flash_emmc.sh - ``` + ```sh + cd ~/catkin_ws/src/px4vision_ros/tools + sudo ./flash_emmc.sh + ``` - ::: info - All information saved in the _UP Core_ computer will be removed when executing this script. + ::: info + All information saved in the _UP Core_ computer will be removed when executing this script. ::: 4. Pull out the USB stick. 5. Restart the vehicle. - The _UP Core_ computer will now boot from internal memory (eMMC). + The _UP Core_ computer will now boot from internal memory (eMMC). ### Boot the Companion Computer @@ -319,23 +319,23 @@ To login to the companion computer: 1. Connect a keyboard and mouse to the _UP Core_ via port `USB2`: - ![UP Core: USB2](../../assets/hardware/px4_vision_devkit/upcore_port_usb2.png) + ![UP Core: USB2](../../assets/hardware/px4_vision_devkit/upcore_port_usb2.png) - - Use the USB-JST cable from the kit to get a USB A connector + - Use the USB-JST cable from the kit to get a USB A connector - ![USB to JST cable](../../assets/hardware/px4_vision_devkit/usb_jst_cable.jpg) + ![USB to JST cable](../../assets/hardware/px4_vision_devkit/usb_jst_cable.jpg) - - A USB hub can be attached to the cable if the keyboard and mouse have separate connectors. + - A USB hub can be attached to the cable if the keyboard and mouse have separate connectors. 2. Connect a monitor to the _UP Core_ HDMI port. - ![UP Core: HDMI port](../../assets/hardware/px4_vision_devkit/upcore_port_hdmi.png) + ![UP Core: HDMI port](../../assets/hardware/px4_vision_devkit/upcore_port_hdmi.png) - The Ubuntu login screen should then appear on the monitor. + The Ubuntu login screen should then appear on the monitor. 3. Login to the _UP Core_ using the credentials: - - **Username:** px4vision - - **Password:** px4vision + - **Username:** px4vision + - **Password:** px4vision ### Developing/Extending PX4 Avoidance @@ -350,39 +350,39 @@ To integrate a different planner, this needs to be disabled. 1. Disable the avoidance process using the following command: - ```sh - systemctl stop avoidance.service - ``` + ```sh + systemctl stop avoidance.service + ``` - You can simply reboot the machine to restart the service. + You can simply reboot the machine to restart the service. - Other useful commands are: + Other useful commands are: - ```sh - # restart service - systemctl start avoidance.service + ```sh + # restart service + systemctl start avoidance.service - # disable service (stop service and do not restart after boot) - systemctl disable avoidance.service + # disable service (stop service and do not restart after boot) + systemctl disable avoidance.service - # enable service (start service and enable restart after boot) - systemctl enable avoidance.service - ``` + # enable service (start service and enable restart after boot) + systemctl enable avoidance.service + ``` 2. The source code of the obstacle avoidance package can be found in https://github.com/PX4/PX4-Avoidance which is located in `~/catkin_ws/src/avoidance`. 3. Make changes to the code! To get the latest code of avoidance pull the code from the avoidance repo: - ```sh - git pull origin - git checkout origin/master - ``` + ```sh + git pull origin + git checkout origin/master + ``` 4. Build the package - ```sh - catkin build local_planner - ``` + ```sh + catkin build local_planner + ``` The ROS workspace is placed in `~/catkin_ws`. For reference on developing in ROS and using the catkin workspace, see the [ROS catkin tutorials](https://wiki.ros.org/catkin/Tutorials). diff --git a/docs/zh/complete_vehicles_rover/aion_r1.md b/docs/zh/complete_vehicles_rover/aion_r1.md index 0e4f89b899..e6bc0298cb 100644 --- a/docs/zh/complete_vehicles_rover/aion_r1.md +++ b/docs/zh/complete_vehicles_rover/aion_r1.md @@ -54,15 +54,15 @@ Use _QGroundControl_ for rover configuration: First configure the serial connection: 1. Navigate to the [Parameters](../advanced_config/parameters.md) section in QGroundControl. - - Set the [RBCLW_SER_CFG](../advanced_config/parameter_reference.md#RBCLW_SER_CFG) parameter to the serial port to which the RoboClaw is connected (such as `GPS2`). - - [RBCLW_COUNTS_REV](../advanced_config/parameter_reference.md#RBCLW_COUNTS_REV) specifies the number of encoder counts required for one wheel revolution. - This value should be left at `1200` for the tested `RoboClaw 2x15A Motor Controller`. - Adjust the value based on your specific encoder and wheel setup. - - RoboClaw motor controllers must be assigned a unique address on the bus. - The default address is 128 and you should not need to change this (if you do, update the PX4 parameter [RBCLW_ADDRESS](../advanced_config/parameter_reference.md#RBCLW_ADDRESS) to match). + - Set the [RBCLW_SER_CFG](../advanced_config/parameter_reference.md#RBCLW_SER_CFG) parameter to the serial port to which the RoboClaw is connected (such as `GPS2`). + - [RBCLW_COUNTS_REV](../advanced_config/parameter_reference.md#RBCLW_COUNTS_REV) specifies the number of encoder counts required for one wheel revolution. + This value should be left at `1200` for the tested `RoboClaw 2x15A Motor Controller`. + Adjust the value based on your specific encoder and wheel setup. + - RoboClaw motor controllers must be assigned a unique address on the bus. + The default address is 128 and you should not need to change this (if you do, update the PX4 parameter [RBCLW_ADDRESS](../advanced_config/parameter_reference.md#RBCLW_ADDRESS) to match). - ::: info - PX4 does not support multiple RoboClaw motor controllers in the same vehicle — each controller needs a unique address on the bus, and there is only one parameter for setting the address in PX4 (`RBCLW_ADDRESS`). + ::: info + PX4 does not support multiple RoboClaw motor controllers in the same vehicle — each controller needs a unique address on the bus, and there is only one parameter for setting the address in PX4 (`RBCLW_ADDRESS`). ::: @@ -71,12 +71,12 @@ Then configure the actuator configuration: 1. Navigate to [Actuators Configuration & Testing](../config/actuators.md) in QGroundControl. 2. Select the RoboClaw driver from the list of _Actuator Outputs_. - For the channel assignments, disarm, minimum, and maximum values, please refer to the image below. + For the channel assignments, disarm, minimum, and maximum values, please refer to the image below. - ![RoboClaw QGC](../../assets/airframes/rover/aion_r1/roboclaw_actuator_config_qgc.png) + ![RoboClaw QGC](../../assets/airframes/rover/aion_r1/roboclaw_actuator_config_qgc.png) - For systems with more than two motors, it is possible to assign the same function to several motors. - The reason for the unusual values, can be found in the [RoboClaw User Manual](https://downloads.basicmicro.com/docs/roboclaw_user_manual.pdf) under `Compatibility Commands` for `Packet Serial`: + For systems with more than two motors, it is possible to assign the same function to several motors. + The reason for the unusual values, can be found in the [RoboClaw User Manual](https://downloads.basicmicro.com/docs/roboclaw_user_manual.pdf) under `Compatibility Commands` for `Packet Serial`: ```plain Drive motor forward. Valid data range is 0 - 127. A value of 127 = full speed forward, 64 = diff --git a/docs/zh/computer_vision/collision_prevention.md b/docs/zh/computer_vision/collision_prevention.md index f2eb057d4c..53c5572090 100644 --- a/docs/zh/computer_vision/collision_prevention.md +++ b/docs/zh/computer_vision/collision_prevention.md @@ -203,85 +203,85 @@ The Lua script works by extracting the `obstacle_distance_fused` data at each ti 2. Configure PX4 to publish obstacle distance data (so that it is available to PlotJuggler): - Add the [`obstacle_distance_fused`](../msg_docs/ObstacleDistance.md) UORB topic to your [`dds_topics.yaml`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) so that it is published by PX4: + Add the [`obstacle_distance_fused`](../msg_docs/ObstacleDistance.md) UORB topic to your [`dds_topics.yaml`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) so that it is published by PX4: - ```sh - - topic: /fmu/out/obstacle_distance_fused - type: px4_msgs::msg::ObstacleDistance - ``` + ```sh + - topic: /fmu/out/obstacle_distance_fused + type: px4_msgs::msg::ObstacleDistance + ``` - For more information see [DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml) in [uXRCE-DDS](../middleware/uxrce_dds.md) (PX4-ROS 2/DDS Bridge)\_. + For more information see [DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml) in [uXRCE-DDS](../middleware/uxrce_dds.md) (PX4-ROS 2/DDS Bridge)\_. 3. Open PlotJuggler and navigate to the **Tools > Reactive Script Editor** section. - In the **Script Editor** tab, add following scripts in the appropriate sections: + In the **Script Editor** tab, add following scripts in the appropriate sections: - - **Global code, executed once:** + - **Global code, executed once:** - ```lua - obs_dist_fused_xy = ScatterXY.new("obstacle_distance_fused_xy") - obs_dist_min = Timeseries.new("obstacle_distance_minimum") - ``` + ```lua + obs_dist_fused_xy = ScatterXY.new("obstacle_distance_fused_xy") + obs_dist_min = Timeseries.new("obstacle_distance_minimum") + ``` - - **function(tracker_time)** + - **function(tracker_time)** - ```lua - obs_dist_fused_xy:clear() + ```lua + obs_dist_fused_xy:clear() - i = 0 - angle_offset = TimeseriesView.find("/fmu/out/obstacle_distance_fused/angle_offset") - increment = TimeseriesView.find("/fmu/out/obstacle_distance_fused/increment") - min_dist = 65535 + i = 0 + angle_offset = TimeseriesView.find("/fmu/out/obstacle_distance_fused/angle_offset") + increment = TimeseriesView.find("/fmu/out/obstacle_distance_fused/increment") + min_dist = 65535 - -- Cache increment and angle_offset values at tracker_time to avoid repeated calls - local angle_offset_value = angle_offset:atTime(tracker_time) - local increment_value = increment:atTime(tracker_time) + -- Cache increment and angle_offset values at tracker_time to avoid repeated calls + local angle_offset_value = angle_offset:atTime(tracker_time) + local increment_value = increment:atTime(tracker_time) - if increment_value == nil or increment_value <= 0 then - print("Invalid increment value: " .. tostring(increment_value)) - return - end + if increment_value == nil or increment_value <= 0 then + print("Invalid increment value: " .. tostring(increment_value)) + return + end - local max_steps = math.floor(360 / increment_value) + local max_steps = math.floor(360 / increment_value) - while i < max_steps do - local str = string.format("/fmu/out/obstacle_distance_fused/distances[%d]", i) - local distance = TimeseriesView.find(str) - if distance == nil then - print("No distance data for: " .. str) - break - end + while i < max_steps do + local str = string.format("/fmu/out/obstacle_distance_fused/distances[%d]", i) + local distance = TimeseriesView.find(str) + if distance == nil then + print("No distance data for: " .. str) + break + end - local dist = distance:atTime(tracker_time) - if dist ~= nil and dist < 65535 then - -- Calculate angle and Cartesian coordinates - local angle = angle_offset_value + i * increment_value - local y = dist * math.cos(math.rad(angle)) - local x = dist * math.sin(math.rad(angle)) + local dist = distance:atTime(tracker_time) + if dist ~= nil and dist < 65535 then + -- Calculate angle and Cartesian coordinates + local angle = angle_offset_value + i * increment_value + local y = dist * math.cos(math.rad(angle)) + local x = dist * math.sin(math.rad(angle)) - obs_dist_fused_xy:push_back(x, y) + obs_dist_fused_xy:push_back(x, y) - -- Update minimum distance - if dist < min_dist then - min_dist = dist - end - end + -- Update minimum distance + if dist < min_dist then + min_dist = dist + end + end - i = i + 1 - end + i = i + 1 + end - -- Push minimum distance once after the loop - if min_dist < 65535 then - obs_dist_min:push_back(tracker_time, min_dist) - else - print("No valid minimum distance found") - end - ``` + -- Push minimum distance once after the loop + if min_dist < 65535 then + obs_dist_min:push_back(tracker_time, min_dist) + else + print("No valid minimum distance found") + end + ``` 4. Enter a name for the script on the top right, and press **Save**. - Once saved, the script should appear in the _Active Scripts_ section. + Once saved, the script should appear in the _Active Scripts_ section. 5. Start streaming the data using the approach described in [Plotting uORB Topic Data in Real Time using PlotJuggler](../debug/plotting_realtime_uorb_data.md). - You should see the `obstacle_distance_fused_xy` and `obstacle_distance_minimum` timeseries on the left. + You should see the `obstacle_distance_fused_xy` and `obstacle_distance_minimum` timeseries on the left. Note that you have to press **Save** again to re-enable the scripts after loading a new log file or otherwise clearing data. diff --git a/docs/zh/computer_vision/visual_inertial_odometry.md b/docs/zh/computer_vision/visual_inertial_odometry.md index 3e6c5f0237..0c91c383be 100644 --- a/docs/zh/computer_vision/visual_inertial_odometry.md +++ b/docs/zh/computer_vision/visual_inertial_odometry.md @@ -125,15 +125,15 @@ Perform the following checks to verify that VIO is working properly _before_ you 可以通过更改参数来进一步调整该值,以找到在动态变化中最低的EKF更新值。 1. Put the vehicle on the ground and start streaming `ODOMETRY` feedback (as above). - 油门杆推到最低并解锁。 + 油门杆推到最低并解锁。 - 此时,设置为位置控制模式。 - 如果切换成功,飞控会闪绿灯。 - 绿灯代表:你的外部位置信息已经注入到飞控中,并且位置控制模式已经切换成功。 + 此时,设置为位置控制模式。 + 如果切换成功,飞控会闪绿灯。 + 绿灯代表:你的外部位置信息已经注入到飞控中,并且位置控制模式已经切换成功。 2. 油门杆放到中间位置(死区),以便无人机保持飞行高度。 - 提高操控杆会增加参考高度,降低操控杆会降低参考高度。 - Similarly, the other stick will change the position over the ground. + 提高操控杆会增加参考高度,降低操控杆会降低参考高度。 + Similarly, the other stick will change the position over the ground. 3. Increase the value of the throttle stick and the vehicle will take off. Move it back to the middle immediately afterwards. diff --git a/docs/zh/concept/flight_tasks.md b/docs/zh/concept/flight_tasks.md index 7e25faa449..a2aeecea79 100644 --- a/docs/zh/concept/flight_tasks.md +++ b/docs/zh/concept/flight_tasks.md @@ -38,24 +38,24 @@ The instructions below might be used to create a task named _MyTask_: - Update the copyright to the current year - ```cmake - ############################################################################ - # - # Copyright (c) 2021 PX4 Development Team. All rights reserved. - # - ``` + ```cmake + ############################################################################ + # + # Copyright (c) 2021 PX4 Development Team. All rights reserved. + # + ``` - Modify the code to reflect the new task - e.g. replace `FlightTaskOrbit` with `FlightTaskMyTask`. - The code will look something like this: + The code will look something like this: - ```cmake - px4_add_library(FlightTaskMyTask - FlightTaskMyTask.cpp - ) + ```cmake + px4_add_library(FlightTaskMyTask + FlightTaskMyTask.cpp + ) - target_link_libraries(FlightTaskMyTask PUBLIC FlightTask) - target_include_directories(FlightTaskMyTask PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) - ``` + target_link_libraries(FlightTaskMyTask PUBLIC FlightTask) + target_include_directories(FlightTaskMyTask PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) + ``` 4. Update the header file (in this case **FlightTaskMyTask.hpp**): Most tasks reimplement the virtual methods `activate()` and `update()`, and in this example we also have a private variable. @@ -141,35 +141,35 @@ The instructions below might be used to create a task named _MyTask_: - Update `MPC_POS_MODE` ([multicopter_position_mode_params.c](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mc_pos_control/multicopter_position_mode_params.c)) to add an option for selecting "MyTask" if the parameter has a previously unused value like 5: - ```c - ... - * @value 0 Direct velocity - * @value 3 Smoothed velocity - * @value 4 Acceleration based - * @value 5 My task - * @group Multicopter Position Control - */ - PARAM_DEFINE_INT32(MPC_POS_MODE, 5); - ``` + ```c + ... + * @value 0 Direct velocity + * @value 3 Smoothed velocity + * @value 4 Acceleration based + * @value 5 My task + * @group Multicopter Position Control + */ + PARAM_DEFINE_INT32(MPC_POS_MODE, 5); + ``` - Add a case for your new option in the switch for the parameter [FlightModeManager.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/flight_mode_manager/FlightModeManager.cpp#L266-L285) to enable the task when `_param_mpc_pos_mode` has the right value. - ```cpp - ... - // manual position control - ... - switch (_param_mpc_pos_mode.get()) { - ... - case 3: - error = switchTask(FlightTaskIndex::ManualPositionSmoothVel); - break; - case 5: // Add case for new task: MyTask - error = switchTask(FlightTaskIndex::MyTask); - break; - case 4: - .... - ... - ``` + ```cpp + ... + // manual position control + ... + switch (_param_mpc_pos_mode.get()) { + ... + case 3: + error = switchTask(FlightTaskIndex::ManualPositionSmoothVel); + break; + case 5: // Add case for new task: MyTask + error = switchTask(FlightTaskIndex::MyTask); + break; + case 4: + .... + ... + ``` ## Test New Flight Task diff --git a/docs/zh/concept/system_startup.md b/docs/zh/concept/system_startup.md index 381ecdeeb9..e635ca3b23 100644 --- a/docs/zh/concept/system_startup.md +++ b/docs/zh/concept/system_startup.md @@ -95,6 +95,8 @@ The whole boot can be replaced by creating a file `/etc/rc.txt` on the microSD c The best way to customize the system startup is to introduce a [new frame configuration](../dev_airframes/adding_a_new_frame.md). 机架配置文件可以在固件中,也可以在SD卡上。 +#### Dynamic customization + If you only need to "tweak" the existing configuration, such as starting one more application or setting the value of a few parameters, you can specify these by creating two files in the `/etc/` directory of the SD Card: - [/etc/config.txt](#customizing-the-configuration-config-txt): modify parameter values @@ -111,7 +113,7 @@ The system boot files are UNIX FILES which require UNIX LINE ENDINGS. These files are referenced in PX4 code as `/fs/microsd/etc/config.txt` and `/fs/microsd/etc/extras.txt`, where the root folder of the microsd card is identified by the path `/fs/microsd`. ::: -#### 自定义配置(config.txt) +##### 自定义配置(config.txt) The `config.txt` file can be used to modify parameters. It is loaded after the main system has been configured and _before_ it is booted. @@ -123,7 +125,7 @@ param set-default PWM_MAIN_DIS3 1000 param set-default PWM_MAIN_MIN3 1120 ``` -#### 启动附加应用程序 (extras.txt) +##### 启动附加应用程序 (extras.txt) The `extras.txt` can be used to start additional applications after the main system boot. 通常,额外启动的将是有效载荷控制器或类似的可选自定义组件。 @@ -150,3 +152,28 @@ Calling an unknown command in system boot files may result in boot failure. mandatory_app start # Will abort boot if mandatory_app is unknown or fails ``` + +#### Additional customization + +In rare cases where the desired setup cannot be achieved through frame configuration or dynamic customization, +you can add a script that will be contained in the binary. + +**Note**: In almost all cases, you should use a frame configuration. This method should only be used for +edge-cases such as customizing `cannode` based boards. + +- Add a new init script in `boards///init` that will run during board startup. 例如: + ```sh + # File: boards///init/rc.additional + param set-default + ``` + +- Add a new board variant in `boards///.px4board` that includes the additional script. 例如: + ```sh + # File: boards///var.px4board + CONFIG_BOARD_ADDITIONAL_INIT="rc.additional" + ``` + +- Compile the firmware with your new variant by appending the variant name to the compile target. 例如: + ```sh + make _var + ``` diff --git a/docs/zh/config/_autotune.md b/docs/zh/config/_autotune.md index 6495d5ae91..8c5df070ae 100644 --- a/docs/zh/config/_autotune.md +++ b/docs/zh/config/_autotune.md @@ -43,13 +43,13 @@ To make sure the vehicle is stable enough for auto-tuning: 2. Take off and
hover at 1m above ground in [Altitude mode](../flight_modes_mc/altitude.md) or [Stabilized mode](../flight_modes_mc/manual_stabilized.md)
fly at cruise speed in [Position mode](../flight_modes_fw/position.md) or [Altitude mode](../flight_modes_fw/altitude.md)
. 3. Use the RC transmitter roll stick to perform the following maneuver, tilting the vehicle just a few degrees: _roll left > roll right > center_ (The whole maneuver should take about 3 seconds). - The vehicle should stabilise itself within 2 oscillations. + The vehicle should stabilise itself within 2 oscillations. 4. Repeat the maneuver, tilting with larger amplitudes at each attempt. - If the vehicle can stabilise itself within 2 oscillations at ~20 degrees move to the next step. + If the vehicle can stabilise itself within 2 oscillations at ~20 degrees move to the next step. 5. Repeat the same maneuvers but on the pitch axis. - As above, start with small angles and confirm that the vehicle can stabilise itself within 2 oscillations before increasing the tilt. + As above, start with small angles and confirm that the vehicle can stabilise itself within 2 oscillations before increasing the tilt. If the drone can stabilize itself within 2 oscillations it is ready for the [auto-tuning procedure](#auto-tuning-procedure). @@ -72,41 +72,41 @@ The test steps are: 1. Perform the [pre-tuning test](#pre-tuning-test). 2. Takeoff using RC control
in [Altitude mode](../flight_modes_mc/altitude.md). - Hover the vehicle at a safe distance and at a few meters above ground (between 4 and 20m).
- Once flying at cruise speed, activate [Hold mode](../flight_modes_fw/hold.md). - This will guide the plane to fly in circle at constant altitude and speed.
+ Hover the vehicle at a safe distance and at a few meters above ground (between 4 and 20m).
+ Once flying at cruise speed, activate [Hold mode](../flight_modes_fw/hold.md). + This will guide the plane to fly in circle at constant altitude and speed.
3. Enable autotune. -
-

TIP

+
+

TIP

- If an [Enable/Disable Autotune Switch](#enable-disable-autotune-switch) is configured you can just toggle the switch to the "enabled" position. + If an [Enable/Disable Autotune Switch](#enable-disable-autotune-switch) is configured you can just toggle the switch to the "enabled" position. -
+
- 1. In QGroundControl, open the menu **Vehicle setup > PID Tuning**: + 1. In QGroundControl, open the menu **Vehicle setup > PID Tuning**: - ![Tuning Setup > Autotune Enabled](../../assets/qgc/setup/autotune/autotune.png) + ![Tuning Setup > Autotune Enabled](../../assets/qgc/setup/autotune/autotune.png) - 2. Select either the _Rate Controller_ or _Attitude Controller_ tabs. + 2. Select either the _Rate Controller_ or _Attitude Controller_ tabs. - 3. Ensure that the **Autotune enabled** button is enabled (this will display the **Autotune** button and remove the manual tuning selectors). + 3. Ensure that the **Autotune enabled** button is enabled (this will display the **Autotune** button and remove the manual tuning selectors). - 4. Read the warning popup and click on **OK** to start tuning. + 4. Read the warning popup and click on **OK** to start tuning. 4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. - The progress is shown in the progress bar, next to the _Autotune_ button. + The progress is shown in the progress bar, next to the _Autotune_ button.
5. Manually land and disarm to apply the new tuning parameters. - Takeoff carefully and manually test that the vehicle is stable. + Takeoff carefully and manually test that the vehicle is stable.
5. The tuning will be immediately/automatically be applied and tested in flight (by default). - PX4 will then run a 4 second test and revert the new tuning if a problem is detected. + PX4 will then run a 4 second test and revert the new tuning if a problem is detected.
diff --git a/docs/zh/config/actuators.md b/docs/zh/config/actuators.md index 298f878b1b..9a224e8ed4 100644 --- a/docs/zh/config/actuators.md +++ b/docs/zh/config/actuators.md @@ -448,9 +448,9 @@ Instructions: 4. One motor will start spinning (click **Spin Motor Again** if it stops spinning too quickly to note.) - Select the corresponding motor in the geometry section. + Select the corresponding motor in the geometry section. - ![Screenshot showing how to identify/assign motors](../../assets/config/actuators/identify_motors_in_progress.png) + ![Screenshot showing how to identify/assign motors](../../assets/config/actuators/identify_motors_in_progress.png) 5. After assigning all motors, the tool will set the correct motor mapping for the outputs and then exit. @@ -467,15 +467,15 @@ To assign an actuator: 1. First assign functions to the outputs that you think are _likely_ to be correct in the _Actuator Outputs_ section. 2. Toggle the **Enable sliders** switch in _Actuator Testing_ section. 3. Move the slider for the actuator you want to test: - - Motors should be moved to the minimum thrust position. - - Servos should be moved near the middle position. + - Motors should be moved to the minimum thrust position. + - Servos should be moved near the middle position. 4. Check which actuator moves on the vehicle. - This should match the actuator positions for your geometry (the [airframe reference](../airframes/airframe_reference.md) shows motor positions for a number of standard airframes). - - If the correct actuator moves, then proceed to the next step. - - If a wrong actuator moves, swap the output assignment over. - - If nothing moves then increase the slider mid-way though the range, then higher if needed. - If nothing moves after that the output might not be connected, the motor might not be powered, or the output might be misconfigured. - You will need to troubleshoot (perhaps try other actuator outputs to see if "anything" moves). + This should match the actuator positions for your geometry (the [airframe reference](../airframes/airframe_reference.md) shows motor positions for a number of standard airframes). + - If the correct actuator moves, then proceed to the next step. + - If a wrong actuator moves, swap the output assignment over. + - If nothing moves then increase the slider mid-way though the range, then higher if needed. + If nothing moves after that the output might not be connected, the motor might not be powered, or the output might be misconfigured. + You will need to troubleshoot (perhaps try other actuator outputs to see if "anything" moves). 5. Return the slider to the "disarmed" position (bottom of slider for motors, centre of slider for servos). 6. Repeat for all actuators @@ -501,32 +501,32 @@ The motor configuration sets output values such that motors: For each motor: 1. Pull the motor slider down so that it snaps to the bottom. - In this position the motor is set to the outputs `disarmed` value. - - Verify that the motor doesn't spin in this position. - - If the motor spins, reduce the corresponding PWM `disarmed` value in the [Actuator Outputs](#actuator-outputs) section to below the level at which it still spins. + In this position the motor is set to the outputs `disarmed` value. + - Verify that the motor doesn't spin in this position. + - If the motor spins, reduce the corresponding PWM `disarmed` value in the [Actuator Outputs](#actuator-outputs) section to below the level at which it still spins. 2. Slowly move the slider up until it snaps to the _minimum_ position. - In this position the motor is set to the outputs `minimum` value. - - Verify that the motor is spinning very slowly in this position. - - If the motor is not spinning, or spinning too fast you will need to adjust the corresponding PWM `minimum` value in the [Actuator Outputs](#actuator-outputs) such that the motors barely spin. + In this position the motor is set to the outputs `minimum` value. + - Verify that the motor is spinning very slowly in this position. + - If the motor is not spinning, or spinning too fast you will need to adjust the corresponding PWM `minimum` value in the [Actuator Outputs](#actuator-outputs) such that the motors barely spin. - ![PWM Minimum Output](../../assets/config/actuators/pwm_minimum_output.png) - ::: info - For DShot output, this is not required. + ![PWM Minimum Output](../../assets/config/actuators/pwm_minimum_output.png) + ::: info + For DShot output, this is not required. ::: 3. Increase the slider value to a level where you can verify that the motor is spinning in the correct direction and that it would give a positive thrust in the expected direction. - - The expected thrust direction can vary by vehicle type. - For example in multicopters the thrust should always point upwards, while in a fixed-wing vehicle the thrust will push the vehicle forwards. - - For VTOL, thrust should point upwards when the Tilt Servo is at 0 degrees as defined the [Tilt Servo Convention](#tilt-servo-coordinate-system). - Testing of the [Tilt Servo](#tilt-servo-setup) is covered below as well. - - If thrust is in the wrong direction, you may need to [reverse the motors](#reversing-motors). + - The expected thrust direction can vary by vehicle type. + For example in multicopters the thrust should always point upwards, while in a fixed-wing vehicle the thrust will push the vehicle forwards. + - For VTOL, thrust should point upwards when the Tilt Servo is at 0 degrees as defined the [Tilt Servo Convention](#tilt-servo-coordinate-system). + Testing of the [Tilt Servo](#tilt-servo-setup) is covered below as well. + - If thrust is in the wrong direction, you may need to [reverse the motors](#reversing-motors). 4. Increase the slider value to the maximum value, so the motor is spinning quickly. - Reduce the value of the PWM output's `maximum` value just below the default. - Listen to the tone of the motors as you increase the value in small (25us) increments. - The "optimal" maximum value is the value at which you last hear a change in the tone. + Reduce the value of the PWM output's `maximum` value just below the default. + Listen to the tone of the motors as you increase the value in small (25us) increments. + The "optimal" maximum value is the value at which you last hear a change in the tone. ### Control Surface Setup @@ -549,33 +549,33 @@ Control surfaces that move either direction around a neutral point include: aile To set these up: 1. Set the `Disarmed` value so that the surfaces will stay at neutral position when disarmed. - This is usually around `1500` for PWM servos (near the centre of the servo range). + This is usually around `1500` for PWM servos (near the centre of the servo range). - ![Control Surface Disarmed 1500 Setting](../../assets/config/actuators/control_surface_aileron_setup.png) + ![Control Surface Disarmed 1500 Setting](../../assets/config/actuators/control_surface_aileron_setup.png) 2. Move the slider for the surface upwards (positive command) and verify that it moves in the direction defined in the [Control Surface Convention](#control-surface-deflection-convention). - - Ailerons, elevons, V-Tails, A-Tails, and other horizontal surfaces should move up. - - Rudders and other "purely vertical" surfaces should move right. + - Ailerons, elevons, V-Tails, A-Tails, and other horizontal surfaces should move up. + - Rudders and other "purely vertical" surfaces should move right. - ::: tip - It is important that the slider movement matches the control surface convention, in order to normalize control for different servo mountings (moving the slider up may actually decrease the output value sent to the servo). + ::: tip + It is important that the slider movement matches the control surface convention, in order to normalize control for different servo mountings (moving the slider up may actually decrease the output value sent to the servo). ::: - If the control surface moves in the opposite direction, click on the `Rev Range` checkbox to reverse the range. + If the control surface moves in the opposite direction, click on the `Rev Range` checkbox to reverse the range. 3. Move the slider again to the middle and check if the Control Surfaces are aligned in the neutral position of the wing. - - If it is not aligned, you can set the **Trim** value for the control surface. + - If it is not aligned, you can set the **Trim** value for the control surface. - ::: info - This is done in the `Trim` setting of the Geometry panel, usually by "trial and error". - ![Control Surface Trimming](../../assets/config/actuators/control_surface_trim.png) + ::: info + This is done in the `Trim` setting of the Geometry panel, usually by "trial and error". + ![Control Surface Trimming](../../assets/config/actuators/control_surface_trim.png) ::: - - After setting the trim for a control surface, move its slider away from the centre, release, and then back into disarmed (middle) position. - Confirm that surface is in the neutral position. + - After setting the trim for a control surface, move its slider away from the centre, release, and then back into disarmed (middle) position. + Confirm that surface is in the neutral position. :::info Another way to test without using the sliders would be to set the [`COM_PREARM_MODE`](../advanced_config/parameter_reference.md#COM_PREARM_MODE) parameter to `Always`: @@ -597,13 +597,13 @@ One approach for setting these up is: 1. Set values `Disarmed` to `1500`, `Min` to `1200`, `Max` to `1700` so that the values are around the centre of the servo range. 2. Move the corresponding slider up and check the control moves and that it is extending (moving away from the disarmed position). - If not, click on the `Rev Range` checkbox to reverse the range. + If not, click on the `Rev Range` checkbox to reverse the range. 3. Enable slider in the disarmed position, them change the value of the `Disarmed` signal until the control is retracted/flush with wing. - This may require that the `Disarmed` value is increased or decreased: - - If the value was decreased towards `Min`, then set `Min` to match `Disarmed`. - - If the value was increased towards `Max`, then set `Max` to match `Disarmed`. + This may require that the `Disarmed` value is increased or decreased: + - If the value was decreased towards `Min`, then set `Min` to match `Disarmed`. + - If the value was increased towards `Max`, then set `Max` to match `Disarmed`. 4. The value that you did _not_ set to match `Disarmed` controls the maximum amount that the control surface can extend. - Set the slider to the top of the control, then change the value (`Max` or `Min`) so that the control surface is fully extended when the slider is at top. + Set the slider to the top of the control, then change the value (`Max` or `Min`) so that the control surface is fully extended when the slider is at top. :::info Special note for flaps In some vehicle builds, flaps may be configured such that both flaps are controlled from a single output. @@ -627,7 +627,7 @@ For each of the tilt servos: 2. Position the slider for the servo in the lowest position, and verify that a positive value increase will point towards the `Angle at Min Tilt` (defined in the Geometry section). - ![Tilt Servo Geometry Setup](../../assets/config/actuators/tilt_servo_geometry_config.png) + ![Tilt Servo Geometry Setup](../../assets/config/actuators/tilt_servo_geometry_config.png) 3. Position the slider for the servo in the highest position, and verify that positive motor thrust will point towards the `Angle at Max Tilt` (as defined in the Geometry section). diff --git a/docs/zh/config/airspeed.md b/docs/zh/config/airspeed.md index 90e3006948..bde7aa8f9c 100644 --- a/docs/zh/config/airspeed.md +++ b/docs/zh/config/airspeed.md @@ -27,18 +27,18 @@ To calibrate the airspeed sensor: 4. Click the **Airspeed** sensor button. - ![Airspeed calibration](../../assets/qgc/setup/sensor/sensor_airspeed.jpg) + ![Airspeed calibration](../../assets/qgc/setup/sensor/sensor_airspeed.jpg) 5. Shield the sensor from the wind (i.e. cup it with your hand). - Take care not to block any of its holes. + Take care not to block any of its holes. 6. Click **OK** to start the calibration. 7. Once asked for, blow into the tip of the pitot tube to signal the end of calibration. - :::tip - Blowing into the tube is also a basic check that the dynamic and static ports are installed correctly. - If they are swapped then the sensor will read a large negative differential pressure when you blow into the tube, and the calibration will abort with an error. + :::tip + Blowing into the tube is also a basic check that the dynamic and static ports are installed correctly. + If they are swapped then the sensor will read a large negative differential pressure when you blow into the tube, and the calibration will abort with an error. ::: diff --git a/docs/zh/config/compass.md b/docs/zh/config/compass.md index adfeb33028..bc93879e96 100644 --- a/docs/zh/config/compass.md +++ b/docs/zh/config/compass.md @@ -23,9 +23,9 @@ If any external magnetometers are available, it then disables the internal magne Several types of compass calibration are available: 1. [Complete](#complete-calibration): This calibration is required after installing the autopilot on an airframe for the first time or when the configuration of the vehicle has changed significantly. - It compensates for hard and soft iron effects by estimating an offset and a scale factor for each axis. + It compensates for hard and soft iron effects by estimating an offset and a scale factor for each axis. 2. [Partial](#partial-quick-calibration): This calibration can be performed as a routine when preparing the vehicle for a flight, after changing the payload, or simply when the compass rose seems inaccurate. - This type of calibration only estimates the offsets to compensate for a hard iron effect. + This type of calibration only estimates the offsets to compensate for a hard iron effect. 3. [Large vehicle](#large-vehicle-calibration): This calibration can be performed when the vehicle is too large or heavy to perform a complete calibration. This type of calibration only estimates the offsets to compensate for a hard iron effect. ## 执行校准 @@ -35,13 +35,13 @@ Several types of compass calibration are available: Before starting the calibration: 1. Choose a location away from large metal objects or magnetic fields. - :::tip - Metal is not always obvious! Avoid calibrating on top of an office table (often contain metal bars) or next to a vehicle. - Calibration can even be affected if you're standing on a slab of concrete with uneven distribution of re-bar. + :::tip + Metal is not always obvious! Avoid calibrating on top of an office table (often contain metal bars) or next to a vehicle. + Calibration can even be affected if you're standing on a slab of concrete with uneven distribution of re-bar. ::: 2. Connect via telemetry radio rather than USB if at all possible. - USB can potentially cause significant magnetic interference. + USB can potentially cause significant magnetic interference. 3. If using an external compass (or a combined GPS/compass module), make sure it is [mounted](../assembly/mount_gps_compass.md) as far as possible from other electronics in order to reduce magnetic interference, and in a _supported orientation_. ### Complete Calibration @@ -54,10 +54,10 @@ The calibration steps are: 3. Click the **Compass** sensor button. - ![Select Compass calibration PX4](../../assets/qgc/setup/sensor/sensor_compass_select_px4.png) + ![Select Compass calibration PX4](../../assets/qgc/setup/sensor/sensor_compass_select_px4.png) - ::: info - You should already have set the [Autopilot Orientation](../config/flight_controller_orientation.md). If not, you can also set it here. + ::: info + You should already have set the [Autopilot Orientation](../config/flight_controller_orientation.md). If not, you can also set it here. ::: @@ -65,7 +65,7 @@ The calibration steps are: 5. 把你的飞机放置在下面显示的某一个方向,并保持静止。 随后提示(方向图像变为黄色)在指定方向旋转飞行器。 该位置标定完成后,屏幕上的相应图示将变成绿色。 - ![Compass calibration steps on PX4](../../assets/qgc/setup/sensor/sensor_compass_calibrate_px4.png) + ![Compass calibration steps on PX4](../../assets/qgc/setup/sensor/sensor_compass_calibrate_px4.png) 6. 在机体的所有方向上重复校准步骤。 @@ -76,7 +76,7 @@ Once you've calibrated the vehicle in all the positions _QGroundControl_ will di This calibration is similar to the well-known figure-8 compass calibration done on a smartphone: 1. Hold the vehicle in front of you and randomly perform partial rotations on all its axes. - 2-3 oscillations of ~30 degrees in every direction is usually sufficient. + 2-3 oscillations of ~30 degrees in every direction is usually sufficient. 2. Wait for the heading estimate to stabilize and verify that the compass rose is pointing to the correct direction (this can take a couple of seconds). 备注: @@ -94,12 +94,12 @@ This calibration process leverages external knowledge of vehicle's orientation a 1. Ensure GNSS Fix. This is required to find the expected Earth magnetic field in WMM tables. 2. Align the vehicle to face True North. - Be as accurate as possible for best results. + Be as accurate as possible for best results. 3. Open the [QGroundControl MAVLink Console](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/analyze_view/mavlink_console.html) and send the following command: - ```sh - commander calibrate mag quick - ``` + ```sh + commander calibrate mag quick + ``` 备注: diff --git a/docs/zh/config/firmware.md b/docs/zh/config/firmware.md index 55dc6039ec..0244ee351a 100644 --- a/docs/zh/config/firmware.md +++ b/docs/zh/config/firmware.md @@ -61,10 +61,10 @@ To install a different version of PX4: 2. Check **Advanced settings** and select the version from the dropdown list: - **Standard Version (stable):** The default version (i.e. no need to use advanced settings to install this!) - **Beta Testing (beta):** A beta/candidate release. - 只有当新版本准备完毕时才可用。 + 只有当新版本准备完毕时才可用。 - **Developer Build (master):** The latest build of PX4/PX4-Autopilot _main_ branch. - **Custom Firmware file...:** A custom firmware file (e.g. [that you have built locally](../dev_setup/building_px4.md)). - 如果选择 Custom firmware file ,您需要在下一步中从文件系统中选择自定义固件。 + 如果选择 Custom firmware file ,您需要在下一步中从文件系统中选择自定义固件。 Firmware update then continues as before. diff --git a/docs/zh/config/flight_mode.md b/docs/zh/config/flight_mode.md index a418f4c3b1..557577e9ad 100644 --- a/docs/zh/config/flight_mode.md +++ b/docs/zh/config/flight_mode.md @@ -40,24 +40,24 @@ To configure single-channel flight mode selection: 3. Select **"Q" icon > Vehicle Setup > Flight Modes** (sidebar) to open _Flight Modes Setup_. - ![Flight modes single-channel](../../assets/qgc/setup/flight_modes/flight_modes_single_channel.jpg) + ![Flight modes single-channel](../../assets/qgc/setup/flight_modes/flight_modes_single_channel.jpg) 4. Specify _Flight Mode Settings_: - - Select the **Mode channel** (above this shown as Channel 5, but this will depend on your transmitter configuration). - - Move the transmitter switch (or switches) that you have set up for mode selection through the available positions. - The mode slot matching your current switch position will be highlighted (above this is _Flight Mode 1_). - ::: info - While you can set flight modes in any of the 6 slots, only the channels that are mapped to switch positions will be highlighted/used. + - Select the **Mode channel** (above this shown as Channel 5, but this will depend on your transmitter configuration). + - Move the transmitter switch (or switches) that you have set up for mode selection through the available positions. + The mode slot matching your current switch position will be highlighted (above this is _Flight Mode 1_). + ::: info + While you can set flight modes in any of the 6 slots, only the channels that are mapped to switch positions will be highlighted/used. ::: - - Select the flight mode that you want triggered for each switch position. + - Select the flight mode that you want triggered for each switch position. 5. Specify _Switch Settings_: - - Select the channels that you want to map to specific actions - e.g.: _Return_ mode, _Kill switch_, _offboard_ mode, etc. (if you have spare switches and channels on your transmitter). + - Select the channels that you want to map to specific actions - e.g.: _Return_ mode, _Kill switch_, _offboard_ mode, etc. (if you have spare switches and channels on your transmitter). 6. Test that the modes are mapped to the right transmitter switches: - - Check the _Channel Monitor_ to confirm that the expected channel is changed by each switch. - - Select each mode switch on your transmitter in turn, and check that the desired flight mode is activated (the text turns yellow on _QGroundControl_ for the active mode). + - Check the _Channel Monitor_ to confirm that the expected channel is changed by each switch. + - Select each mode switch on your transmitter in turn, and check that the desired flight mode is activated (the text turns yellow on _QGroundControl_ for the active mode). All values are automatically saved as they are changed. diff --git a/docs/zh/config/safety_simulation.md b/docs/zh/config/safety_simulation.md index be2f6cb89a..bee01fc8d3 100644 --- a/docs/zh/config/safety_simulation.md +++ b/docs/zh/config/safety_simulation.md @@ -14,7 +14,7 @@ To use it: 2. Set the vehicle type 3. Set the other values in the **State** or any of the flags under **Conditions** - The **Intended Mode** corresponds to the commanded mode via RC or GCS (or external script). - The failsafe state machine can override this in case of a failsafe. + The failsafe state machine can override this in case of a failsafe. 4. Check the action under **Output** 5. Check what happens when changing mode or **Move the RC sticks** 6. Play with different settings and conditions! diff --git a/docs/zh/config_fw/trimming_guide_fixedwing.md b/docs/zh/config_fw/trimming_guide_fixedwing.md index 833f5f1cb0..e8e7f0c00b 100644 --- a/docs/zh/config_fw/trimming_guide_fixedwing.md +++ b/docs/zh/config_fw/trimming_guide_fixedwing.md @@ -29,10 +29,10 @@ The [Advanced Trimming](#advanced-trimming) section introduces parameters that c 1. Trim the servos by physically adjusting the linkages lengths if possible and fine tune by trimming the PWM channels (use `PWM_MAIN/AUX_TRIMx`) on the bench to properly set the control surfaces to their theoretical position. 2. Fly in stabilized mode at cruise speed and set the pitch setpoint offset (`FW_PSP_OFF`) to desired angle of attack. - 巡航速度飞行下的需用攻角为飞机在平飞状态下保持固定高度时的实际飞行迎角。 - If you are using an airspeed sensor, also set the correct cruise airspeed (`FW_AIRSPD_TRIM`). + 巡航速度飞行下的需用攻角为飞机在平飞状态下保持固定高度时的实际飞行迎角。 + If you are using an airspeed sensor, also set the correct cruise airspeed (`FW_AIRSPD_TRIM`). 3. Look at the actuator controls in the log file (upload it to [Flight Review](https://logs.px4.io) and check the _Actuator Controls_ plot for example) and set the pitch trim (`TRIM_PITCH`). - 将该值设置为平飞时俯仰角度的平均值。 + 将该值设置为平飞时俯仰角度的平均值。 步骤3可以在步骤2之前执行,如果你不想查看日志, 或者如果您在手动模式下感觉舒适。 You can then trim your remote (with the trim switches) and report the values to `TRIM_PITCH` (and remove the trims from your transmitter) or update `TRIM_PITCH` directly during flight via telemetry and QGC. diff --git a/docs/zh/config_heli/index.md b/docs/zh/config_heli/index.md index 1d594e1885..f2c5ac697e 100644 --- a/docs/zh/config_heli/index.md +++ b/docs/zh/config_heli/index.md @@ -53,15 +53,15 @@ To setup and configure a helicopter: For each servo set: - `Angle`: Clockwise angle in degree on the swash plate circle at which the servo arm is attached starting from `0` pointing forwards. - Example for a typical setup where three servos are controlling the swash plate equally distributed over the circle (360° / 3 =) 120° apart each which results in the angles: + Example for a typical setup where three servos are controlling the swash plate equally distributed over the circle (360° / 3 =) 120° apart each which results in the angles: - | # | Angle | - | ------- | ----- | - | Servo 1 | 60° | - | Servo 2 | 180° | - | Servo 3 | 300° | + | # | Angle | + | ------- | ----- | + | Servo 1 | 60° | + | Servo 2 | 180° | + | Servo 3 | 300° | - warning and requirement + warning and requirement - `Arm Length (relative to each other)`: Radius from the swash plate center (top view). A shorter arm means the same servo motion moves the plate more. This allows the autopilot to compensate. @@ -72,7 +72,7 @@ To setup and configure a helicopter: - `Yaw compensation scale based on collective pitch`: How much yaw is feed forward compensated based on the current collective pitch. - `Main rotor turns counter-clockwise`: `Disabled` (clockwise rotation) | `Enabled` - `Throttle spoolup time`: Set value (in seconds) greater than the achievable minimum motor spool up time. - A larger value may improve user experience. + A larger value may improve user experience. 3. Remove the rotor blades and propellers diff --git a/docs/zh/config_mc/filter_tuning.md b/docs/zh/config_mc/filter_tuning.md index d7fe6deca3..034fe29163 100644 --- a/docs/zh/config_mc/filter_tuning.md +++ b/docs/zh/config_mc/filter_tuning.md @@ -166,11 +166,11 @@ The low pass filters and the notch filter can be tuned independently (i.e. you d ## Additional Tips 1. Acceptable latency depends on vehicle size and expectations. - FPV racers typically tune for the absolute minimal latency (as a ballpark `IMU_GYRO_CUTOFF` around 120, `IMU_DGYRO_CUTOFF` of 50 to 80). - For bigger vehicles latency is less critical and `IMU_GYRO_CUTOFF` of around 80 might be acceptable. + FPV racers typically tune for the absolute minimal latency (as a ballpark `IMU_GYRO_CUTOFF` around 120, `IMU_DGYRO_CUTOFF` of 50 to 80). + For bigger vehicles latency is less critical and `IMU_GYRO_CUTOFF` of around 80 might be acceptable. 2. You can start tuning at higher `IMU_GYRO_CUTOFF` values (e.g. 100Hz), which might be desirable because the default tuning of `IMU_GYRO_CUTOFF` is set very low (30Hz). - The only caveat is that you must be aware of the risks: - - Don't fly for more than 20-30 seconds - - Check that the motors are not getting to hot - - Listen for odd sounds and symptoms of excessive noise, as discussed above. + The only caveat is that you must be aware of the risks: + - Don't fly for more than 20-30 seconds + - Check that the motors are not getting to hot + - Listen for odd sounds and symptoms of excessive noise, as discussed above. diff --git a/docs/zh/config_mc/pid_tuning_guide_multicopter_basic.md b/docs/zh/config_mc/pid_tuning_guide_multicopter_basic.md index 6f31c50c9e..2a7602bae5 100644 --- a/docs/zh/config_mc/pid_tuning_guide_multicopter_basic.md +++ b/docs/zh/config_mc/pid_tuning_guide_multicopter_basic.md @@ -72,7 +72,7 @@ The tuning procedure is: 1. Arm the vehicle, takeoff, and hover (typically in [Position mode](../flight_modes_mc/position.md)). 2. Open _QGroundControl_ **Vehicle Setup > PID Tuning** - ![QGC Rate Controller Tuning UI](../../assets/mc_pid_tuning/qgc_mc_pid_tuning_rate_controller.png) + ![QGC Rate Controller Tuning UI](../../assets/mc_pid_tuning/qgc_mc_pid_tuning_rate_controller.png) 3. Select the **Rate Controller** tab. @@ -80,60 +80,60 @@ The tuning procedure is: 5. Set the _Thrust curve_ value to: 0.3 (PWM, power-based controllers) or 1 (RPM-based ESCs) - ::: info - For PWM, power-based and (some) UAVCAN speed controllers, the control signal to thrust relationship may not be linear. - As a result, the optimal tuning at hover thrust may not be ideal when the vehicle is operating at higher thrust. + ::: info + For PWM, power-based and (some) UAVCAN speed controllers, the control signal to thrust relationship may not be linear. + As a result, the optimal tuning at hover thrust may not be ideal when the vehicle is operating at higher thrust. - The thrust curve value can be used to compensate for this non-linearity: + The thrust curve value can be used to compensate for this non-linearity: - - For PWM controllers, 0.3 is a good default (which may benefit from [further tuning](../config_mc/pid_tuning_guide_multicopter.md#thrust-curve)). - - For RPM-based controllers, use 1 (no further tuning is required as these have a quadratic thrust curve). + - For PWM controllers, 0.3 is a good default (which may benefit from [further tuning](../config_mc/pid_tuning_guide_multicopter.md#thrust-curve)). + - For RPM-based controllers, use 1 (no further tuning is required as these have a quadratic thrust curve). - For more information see the [detailed PID tuning guide](../config_mc/pid_tuning_guide_multicopter.md#thrust-curve). + For more information see the [detailed PID tuning guide](../config_mc/pid_tuning_guide_multicopter.md#thrust-curve). ::: 6. Set the _Select Tuning_ radio button to: **Roll**. 7. (Optionally) Select the **Automatic Flight Mode Switching** checkbox. - This will _automatically_ switch from [Position mode](../flight_modes_mc/position.md) to [Stabilised mode](../flight_modes_mc/manual_stabilized.md) when you press the **Start** button + This will _automatically_ switch from [Position mode](../flight_modes_mc/position.md) to [Stabilised mode](../flight_modes_mc/manual_stabilized.md) when you press the **Start** button 8. For rate controller tuning switch to _Acro mode_, _Stabilized mode_ or _Altitude mode_ (unless automatic switching is enabled). 9. Select the **Start** button in order to start tracking the setpoint and response curves. 10. Rapidly move the _roll stick_ full range and observe the step response on the plots. - :::tip - Stop tracking to enable easier inspection of the plots. - This happens automatically when you zoom/pan. - Use the **Start** button to restart the plots, and **Clear** to reset them. + :::tip + Stop tracking to enable easier inspection of the plots. + This happens automatically when you zoom/pan. + Use the **Start** button to restart the plots, and **Clear** to reset them. ::: 11. Modify the three PID values using the sliders (for roll rate-tuning these affect `MC_ROLLRATE_K`, `MC_ROLLRATE_I`, `MC_ROLLRATE_D`) and observe the step response again. - The values are saved to the vehicle as soon as the sliders are moved. - ::: info - The goal is for the _Response_ curve to match the _Setpoint_ curve as closely as possible (i.e. a fast response without overshoots). + The values are saved to the vehicle as soon as the sliders are moved. + ::: info + The goal is for the _Response_ curve to match the _Setpoint_ curve as closely as possible (i.e. a fast response without overshoots). ::: - The PID values can be adjusted as follows: - - P (proportional) or K gain: - - increase this for more responsiveness - - reduce if the response is overshooting and/or oscillating (up to a certain point increasing the D gain also helps). - - D (derivative) gain: - - this can be increased to dampen overshoots and oscillations - - increase this only as much as needed, as it amplifies noise (and can lead to hot motors) - - I (integral) gain: - - used to reduce steady-state error - - if too low, the response might never reach the setpoint (e.g. in wind) - - if too high, slow oscillations can occur + The PID values can be adjusted as follows: + - P (proportional) or K gain: + - increase this for more responsiveness + - reduce if the response is overshooting and/or oscillating (up to a certain point increasing the D gain also helps). + - D (derivative) gain: + - this can be increased to dampen overshoots and oscillations + - increase this only as much as needed, as it amplifies noise (and can lead to hot motors) + - I (integral) gain: + - used to reduce steady-state error + - if too low, the response might never reach the setpoint (e.g. in wind) + - if too high, slow oscillations can occur 12. Repeat the tuning process above for the pitch and yaw: - - Use _Select Tuning_ radio button to select the axis to tune - - Move the appropriate sticks (i.e. pitch stick for pitch, yaw stick for yaw). - - For pitch tuning, start with the same values as for roll. - :::tip - Use the **Save to Clipboard** and **Reset from Clipboard** buttons to copy the roll settings for initial pitch settings. + - Use _Select Tuning_ radio button to select the axis to tune + - Move the appropriate sticks (i.e. pitch stick for pitch, yaw stick for yaw). + - For pitch tuning, start with the same values as for roll. + :::tip + Use the **Save to Clipboard** and **Reset from Clipboard** buttons to copy the roll settings for initial pitch settings. ::: @@ -141,10 +141,10 @@ The tuning procedure is: 14. Repeat the tuning process for the velocity and positions controllers (on all the axes). - - Use Position mode when tuning these controllers - - Select the **Simple position control** option in the _Position control mode ..._ selector (this allows direct control for the generation of step inputs) + - Use Position mode when tuning these controllers + - Select the **Simple position control** option in the _Position control mode ..._ selector (this allows direct control for the generation of step inputs) - ![QGC PID tuning: Simple control selector](../../assets/mc_pid_tuning/qgc_mc_pid_tuning_simple_control.png) + ![QGC PID tuning: Simple control selector](../../assets/mc_pid_tuning/qgc_mc_pid_tuning_simple_control.png) All done! Remember to re-enable airmode before leaving the setup. diff --git a/docs/zh/config_rover/basic_setup.md b/docs/zh/config_rover/basic_setup.md index 17aa6490bb..e68cbb1ead 100644 --- a/docs/zh/config_rover/basic_setup.md +++ b/docs/zh/config_rover/basic_setup.md @@ -27,10 +27,18 @@ That is the minimum setup to use the rover in [Manual mode](../flight_modes_rover/manual.md#manual-mode). +:::info +The rest of the tuning on this page is not mandatory for [Manual mode](../flight_modes_rover/manual.md#manual-mode), but it will have an effect on the behaviour of the rover. +::: + +:::warning +Do not skip the rest of this setup if you intend to use more sophisticated modes! +All parameters will be mandatory for all subsequent modes, except those tagged as `(Optional)`. +::: + ## Geometric Parameters -Manual mode is also affected by (optional) acceleration/deceleration limits set using the geometric described below. -These limits are mandatory for all other modes. +First, we set up the geometric parameters of the rover: ![Geometric parameters](../../assets/config/rover/geometric_parameters.png) @@ -42,7 +50,7 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and 2. [RA_MAX_STR_ANG](#RA_MAX_STR_ANG) [deg]: Measure the maximum steering angle. 3. (Optional) [RA_STR_RATE_LIM](#RA_STR_RATE_LIM) [deg/s]: Maximum steering rate you want to allow for your rover. - :::tip + ::: tip This value depends on your rover and use case. For bigger rovers there might be a mechanical limit that is easy to identify by steering the rover at a standstill and increasing [RA_STR_RATE_LIM](#RA_STR_RATE_LIM) until you observe the steering rate to no longer be limited by the parameter. @@ -51,7 +59,7 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and ::: - :::warning + ::: warning A low maximum steering rate makes the rover worse at tracking steering setpoints, which can lead to a poor performance in the subsequent modes. ::: @@ -109,6 +117,39 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and ::: +## (Optional) Stick Input Mapping + +Input shaping can be used to adjust the default linear mapping from stick inputs $\in [-1, 1]$ to normalized setpoints $\in [-1, 1]$. Applying this specifically to the steering input, can provide a smoother driving experience, by enabling the user to make small adjustments when the stick is close to the center, but still send large inputs when moving them to the edges. +We provide this input shaping through the super exponential function: + +$$ +\delta = \frac{(f \cdot x^3 + x(1-f)) \cdot (1-g)}{1-g \cdot |x|} +$$ + +with: + +- $\delta \in [-1, 1]=$ Normalized steering setpoint. +- $x \in [-1, 1]=$ Normalized stick input. +- $f=$ [RO_YAW_EXPO](#RO_YAW_EXPO): `0` Purely linear input curve, `1` Purely cubic input curve. +- $g=$ [RO_YAW_SUPEXPO](#RO_YAW_SUPEXPO): `0` Pure Expo function, `0.7` reasonable shape enhancement for intuitive stick feel, `0.95` very strong bent input curve only near maxima have effect. + +In [Manual mode](../flight_modes_rover/manual.md#manual-mode) we can additionally scale $\delta$ with an additional parameter $r$: + +- Differential Rover: $r=$ [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN), which enables adjusting the slope of the input mapping. This leads to a normalized steering input $\hat{\delta} = \delta \cdot r \in$ [-[RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN), [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN)]. +- Mecanum Rover: $r=$ [RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN), which enables adjusting the slope of the input mapping. This leads to a normalized steering input $\hat{\delta} = \delta \cdot r \in$ [-[RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN), [RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN)]. + +This scaling is useful to limit the normalized steering setpoint, if it is too aggresive for your rover in manual mode. + +You can experiment with the relationships graphically using the [PX4 SuperExpo Rover calculator](https://www.desmos.com/calculator/gwm8lrlanx). + +:::info +In [Acro](../flight_modes_rover/manual.md#acro-mode), [Stabilized](../flight_modes_rover/manual.md#stabilized-mode) and [Position](../flight_modes_rover/manual.md#position-mode) Mode, $\delta$ is instead scaled by $r=$ [RO_YAW_RATE_LIM](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED) for all rovers. This leads to a yaw rate setpoint $\dot{\psi} = \delta \cdot r \in$ [-[RO_YAW_RATE_LIM](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED), [RO_YAW_RATE_LIM](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED)]. This parameter is setup during [rate tuning](rate_tuning.md). +::: + +:::info +The input shaping through [RO_YAW_EXPO](#RO_YAW_EXPO) and [RO_YAW_SUPEXPO](#RO_YAW_SUPEXPO) applies for all manual modes, while [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN)/[RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN) only affects full manual mode. +::: + You can now continue the configuration process with [rate tuning](rate_tuning.md). ## Parameter Overview @@ -118,6 +159,8 @@ You can now continue the configuration process with [rate tuning](rate_tuning.md | [RO_MAX_THR_SPEED](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED) | Speed the rover drives at maximum throttle | $m/s$ | | [RO_ACCEL_LIM](../advanced_config/parameter_reference.md#RO_ACCEL_LIM) | (Optional) Maximum allowed acceleration | $m/s^2$ | | [RO_DECEL_LIM](../advanced_config/parameter_reference.md#RO_DECEL_LIM) | (Optional) Maximum allowed deceleration | $m/s^2$ | +| [RO_YAW_EXPO](../advanced_config/parameter_reference.md#RO_YAW_EXPO) | (Optional) Yaw rate expo factor | $-$ | +| [RO_YAW_SUPEXPO](../advanced_config/parameter_reference.md#RO_YAW_SUPEXPO) | (Optional) Yaw rate super expo factor | $-$ | ### Ackermann Specific @@ -129,12 +172,14 @@ You can now continue the configuration process with [rate tuning](rate_tuning.md ### Differential Specific -| 参数 | 描述 | Unit | -| ----------------------------------------------------------------------------------------------------------------------------------------------- | ----------- | ---- | -| [RD_WHEEL_TRACK](../advanced_config/parameter_reference.md#RD_WHEEL_TRACK) | Wheel track | m | +| 参数 | 描述 | Unit | +| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------ | ---- | +| [RD_WHEEL_TRACK](../advanced_config/parameter_reference.md#RD_WHEEL_TRACK) | Wheel track | $m$ | +| [RD_YAW_STK_GAIN](../advanced_config/parameter_reference.md#RD_YAW_STK_GAIN) | (Optional) Yaw stick gain for Manual mode | $-$ | ### Mecanum Specific -| 参数 | 描述 | Unit | -| ----------------------------------------------------------------------------------------------------------------------------------------------- | ----------- | ---- | -| [RM_WHEEL_TRACK](../advanced_config/parameter_reference.md#RM_WHEEL_TRACK) | Wheel track | m | +| 参数 | 描述 | Unit | +| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------ | ---- | +| [RM_WHEEL_TRACK](../advanced_config/parameter_reference.md#RM_WHEEL_TRACK) | Wheel track | $m$ | +| [RM_YAW_STK_GAIN](../advanced_config/parameter_reference.md#RM_YAW_STK_GAIN) | (Optional) Yaw stick gain for Manual mode | $-$ | diff --git a/docs/zh/config_rover/index.md b/docs/zh/config_rover/index.md index 3dadee2f53..212839bc12 100644 --- a/docs/zh/config_rover/index.md +++ b/docs/zh/config_rover/index.md @@ -25,18 +25,18 @@ Rovers use a custom build that must be flashed onto your flight controller inste To build for rover with the `make` command, replace the `_default` suffix with `_rover`. For example, to build rover for px4_fmu-v6x boards, you would use the command: - ```sh - make px4_fmu-v6x_rover - ``` + ```sh + make px4_fmu-v6x_rover + ``` ::: info You can also enable the modules in default builds by adding these lines to your [board configuration](../hardware/porting_guide_config.md) (e.g. for fmu-v6x you might add them to [`main/boards/px4/fmu-v6x/default.px4board`](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/fmu-v6x/default.px4board)): - ```sh - CONFIG_MODULES_ROVER_ACKERMANN=y - CONFIG_MODULES_ROVER_DIFFERENTIAL=y - CONFIG_MODULES_ROVER_MECANUM=y - ``` + ```sh + CONFIG_MODULES_ROVER_ACKERMANN=y + CONFIG_MODULES_ROVER_DIFFERENTIAL=y + CONFIG_MODULES_ROVER_MECANUM=y + ``` Note that adding the rover modules may lead to flash overflow, in which case you will need to disable modules that you do not plan to use (such as those related to multicopter or fixed wing). diff --git a/docs/zh/config_rover/velocity_tuning.md b/docs/zh/config_rover/velocity_tuning.md index cc265361d5..5b4b1361d8 100644 --- a/docs/zh/config_rover/velocity_tuning.md +++ b/docs/zh/config_rover/velocity_tuning.md @@ -94,7 +94,7 @@ These steps are only necessary if you are tuning/want to unlock the manual [Posi The rover is now ready to drive in [Position mode](../flight_modes_rover/manual.md#position-mode) and the configuration can be continued with [position tuning](position_tuning.md). -## Attitude Controller Structure (Info Only) +## Velocity Controller Structure (Info Only) This section provides additional information for developers and people with experience in control system design. diff --git a/docs/zh/config_vtol/vtol_quad_configuration.md b/docs/zh/config_vtol/vtol_quad_configuration.md index aa580ddc12..ecb9ce0df1 100644 --- a/docs/zh/config_vtol/vtol_quad_configuration.md +++ b/docs/zh/config_vtol/vtol_quad_configuration.md @@ -11,7 +11,7 @@ For airframe specific documentation and build instructions see [VTOL Framebuilds 2. Flash the firmware for your current release or master (PX4 `main` branch build). 3. In the [Frame setup](../config/airframe.md) section select the appropriate VTOL airframe. - If your airframe is not listed select the [Generic Standard VTOL](../airframes/airframe_reference.md#vtol_standard_vtol_generic_standard_vtol) frame. + If your airframe is not listed select the [Generic Standard VTOL](../airframes/airframe_reference.md#vtol_standard_vtol_generic_standard_vtol) frame. ### 飞行模式/模式转换 diff --git a/docs/zh/contribute/docs.md b/docs/zh/contribute/docs.md index bbaa75151e..91805dff44 100644 --- a/docs/zh/contribute/docs.md +++ b/docs/zh/contribute/docs.md @@ -63,33 +63,33 @@ The instructions below explain how to get git and use it on your local computer. 4. Clone (copy) your forked repository to your local computer: - ```sh - cd ~/wherever/ - git clone https://github.com//PX4-Autopilot.git - ``` + ```sh + cd ~/wherever/ + git clone https://github.com//PX4-Autopilot.git + ``` - For example, to clone PX4 source fork for a user with Github account "john_citizen": + For example, to clone PX4 source fork for a user with Github account "john_citizen": - ```sh - git clone https://github.com/john_citizen/PX4-Autopilot.git - ``` + ```sh + git clone https://github.com/john_citizen/PX4-Autopilot.git + ``` 5. Navigate to your local repository: - ```sh - cd ~/wherever/PX4-Autopilot - ``` + ```sh + cd ~/wherever/PX4-Autopilot + ``` 6. Add a _remote_ called "upstream" to point to the "official" PX4 version of the library: - ```sh - git remote add upstream https://github.com/PX4/PX4-Autopilot.git - ``` + ```sh + git remote add upstream https://github.com/PX4/PX4-Autopilot.git + ``` - :::tip - A "remote" is a handle to a particular repository. - The remote named _origin_ is created by default when you clone the repository, and points to _your fork_ of the guide. - Above you create a new remote _upstream_ that points to the PX4 project version of the documents. + :::tip + A "remote" is a handle to a particular repository. + The remote named _origin_ is created by default when you clone the repository, and points to _your fork_ of the guide. + Above you create a new remote _upstream_ that points to the PX4 project version of the documents. ::: @@ -99,111 +99,111 @@ Within the repository you created above: 1. Bring your copy of the repository `main` branch up to date: - ```sh - git checkout main - git fetch upstream main - git pull upstream main - ``` + ```sh + git checkout main + git fetch upstream main + git pull upstream main + ``` 2. Create a new branch for your changes: - ```sh - git checkout -b - ``` + ```sh + git checkout -b + ``` - This creates a local branch on your computer named `your_feature_branch_name`. + This creates a local branch on your computer named `your_feature_branch_name`. 3. Make changes to the documentation as needed (general guidance on this in following sections) 4. Once you are satisfied with your changes, you can add them to your local branch using a "commit": - ```sh - git add - git commit -m "" - ``` + ```sh + git add + git commit -m "" + ``` - For a good commit message, please refer to the [Source Code Management](../contribute/code.md#commits-and-commit-messages) section. + For a good commit message, please refer to the [Source Code Management](../contribute/code.md#commits-and-commit-messages) section. 5. Push your local branch (including commits added to it) to your forked repository on Github. - ```sh - git push origin your_feature_branch_name - ``` + ```sh + git push origin your_feature_branch_name + ``` 6. Go to your forked repository on Github in a web browser, e.g.: `https://github.com//PX4-Autopilot.git`. - There you should see the message that a new branch has been pushed to your forked repository. + There you should see the message that a new branch has been pushed to your forked repository. 7. Create a pull request (PR): - - On the right hand side of the "new branch message" (see one step before), you should see a green button saying "Compare & Create Pull Request". - Press it. - - A pull request template will be created. - It will list your commits and you can (must) add a meaningful title (in case of a one commit PR, it's usually the commit message) and message (explain what you did for what reason. - Check [other pull requests](https://github.com/PX4/PX4-Autopilot/pulls) for comparison). - - Add the "Documentation" label. + - On the right hand side of the "new branch message" (see one step before), you should see a green button saying "Compare & Create Pull Request". + Press it. + - A pull request template will be created. + It will list your commits and you can (must) add a meaningful title (in case of a one commit PR, it's usually the commit message) and message (explain what you did for what reason. + Check [other pull requests](https://github.com/PX4/PX4-Autopilot/pulls) for comparison). + - Add the "Documentation" label. 8. You're done! - Maintainers for the PX4 User Guide will now have a look at your contribution and decide if they want to integrate it. - Check if they have questions on your changes every once in a while. + Maintainers for the PX4 User Guide will now have a look at your contribution and decide if they want to integrate it. + Check if they have questions on your changes every once in a while. ### Gitbook Documentation Toolchain 概述: 1. Install the [Vitepress prerequisites](https://vitepress.dev/guide/getting-started#prerequisites): - - [Nodejs 18+](https://nodejs.org/en) - - [Yarn classic](https://classic.yarnpkg.com/en/docs/install) + - [Nodejs 18+](https://nodejs.org/en) + - [Yarn classic](https://classic.yarnpkg.com/en/docs/install) 2. Navigate to your local repository and the `/docs` subdirectory: - ```sh - cd ~/wherever/PX4-Autopilot/docs - ``` + ```sh + cd ~/wherever/PX4-Autopilot/docs + ``` 3. Install dependencies (including Vitepress): - ```sh - yarn install - ``` + ```sh + yarn install + ``` 4. Preview and serve the library: - ```sh - yarn start - ``` + ```sh + yarn start + ``` - - Once the development/preview server has built the library (less than a minute for the first time) it will show you the URL you can preview the site on. - This will be something like: `http://localhost:5173/px4_user_guide/`. - - Stop serving using **CTRL+C** in the terminal prompt. + - Once the development/preview server has built the library (less than a minute for the first time) it will show you the URL you can preview the site on. + This will be something like: `http://localhost:5173/px4_user_guide/`. + - Stop serving using **CTRL+C** in the terminal prompt. 5. Open previewed pages in your local editor: - First specify a local text editor file using the `EDITOR` environment variable, before calling `yarn start` to preview the library. - For example, you can enable VSCode as your default editor by entering: + First specify a local text editor file using the `EDITOR` environment variable, before calling `yarn start` to preview the library. + For example, you can enable VSCode as your default editor by entering: - - Windows: + - Windows: - ```sh - set EDITOR=code - ``` + ```sh + set EDITOR=code + ``` - - Linux: + - Linux: - ```sh - export EDITOR=code - ``` + ```sh + export EDITOR=code + ``` - The **Open in your editor** link at the bottom of each page will then open the current page in the editor (this replaces the _Open in GitHub_ link). + The **Open in your editor** link at the bottom of each page will then open the current page in the editor (this replaces the _Open in GitHub_ link). 6. You can build the library as it would be done for deployment: - ```sh - # Ubuntu - yarn docs:build + ```sh + # Ubuntu + yarn docs:build - # Windows - yarn docs:buildwin - ``` + # Windows + yarn docs:buildwin + ``` :::tip Use `yarn start` to preview changes _as you make them_ (documents are updated and served very quickly). @@ -256,38 +256,38 @@ When you add a new page you must also add it to `en/SUMMARY.md`! ## 翻译 1. 图片 - - Put new markdown files in an appropriate sub-folder of `/en/`, such as `/en/contribute/`. - Do not further nest folders. - - Put new image files in an appropriate nested sub-folder of `/assets/`. - Deeper nesting is allowed/encouraged. - - Use descriptive names for folders and files. - In particular, image filenames should describe what they contain (don't name as "image1.png") - - Use lower case filenames and separate words using underscores (`_`). + - Put new markdown files in an appropriate sub-folder of `/en/`, such as `/en/contribute/`. + Do not further nest folders. + - Put new image files in an appropriate nested sub-folder of `/assets/`. + Deeper nesting is allowed/encouraged. + - Use descriptive names for folders and files. + In particular, image filenames should describe what they contain (don't name as "image1.png") + - Use lower case filenames and separate words using underscores (`_`). 2. 内容: - - 将新文件放入相应的子文件夹 - - New images should be created in a sub-folder of `/assets/` (so they can be shared between translations). - - SVG files are preferred for diagrams. - PNG files are preferred over JPG for screenshots. + - 将新文件放入相应的子文件夹 + - New images should be created in a sub-folder of `/assets/` (so they can be shared between translations). + - SVG files are preferred for diagrams. + PNG files are preferred over JPG for screenshots. 3. Content: - - Use "style" (**bold**, _emphasis_, etc.) consistently and sparingly (as little as possible). - - **Bold** for button presses and menu definitions. - - _Emphasis_ for tool names such as _QGroundControl_ or _prettier_. - - `code` for file paths, and code, parameter names that aren't linked, using tools in a command line, such as `prettier`. - - Headings and page titles should use "First Letter Capitalisation". - - The page title should be a first level heading (`#`). - All other headings should be h2 (`##`) or lower. - - Don't add any style to headings. - - Don't translate the text indicating the name of an `info`, `tip` or `warning` declaration (e.g. `::: tip`) as this precise text is required to render the aside properly. - - Break lines on sentences by preference. - Don't break lines based on some arbitrary line length. - - Format using _prettier_ (_VSCode_ is a has extensions can be used for this). + - Use "style" (**bold**, _emphasis_, etc.) consistently and sparingly (as little as possible). + - **Bold** for button presses and menu definitions. + - _Emphasis_ for tool names such as _QGroundControl_ or _prettier_. + - `code` for file paths, and code, parameter names that aren't linked, using tools in a command line, such as `prettier`. + - Headings and page titles should use "First Letter Capitalisation". + - The page title should be a first level heading (`#`). + All other headings should be h2 (`##`) or lower. + - Don't add any style to headings. + - Don't translate the text indicating the name of an `info`, `tip` or `warning` declaration (e.g. `::: tip`) as this precise text is required to render the aside properly. + - Break lines on sentences by preference. + Don't break lines based on some arbitrary line length. + - Format using _prettier_ (_VSCode_ is a has extensions can be used for this). 4. Videos: - - Youtube videos can be added using the format `` (supported via the [https://www.npmjs.com/package/lite-youtube-embed](https://www.npmjs.com/package/lite-youtube-embed) custom element, which has other parameters you can pass). - - Use instructional videos sparingly as they date badly, and are hard to maintain. - - Cool videos of airframes in flight are always welcome. + - Youtube videos can be added using the format `` (supported via the [https://www.npmjs.com/package/lite-youtube-embed](https://www.npmjs.com/package/lite-youtube-embed) custom element, which has other parameters you can pass). + - Use instructional videos sparingly as they date badly, and are hard to maintain. + - Cool videos of airframes in flight are always welcome. ## 许可证 diff --git a/docs/zh/contribute/git_examples.md b/docs/zh/contribute/git_examples.md index 5fd7c15f6e..328d3e11c1 100644 --- a/docs/zh/contribute/git_examples.md +++ b/docs/zh/contribute/git_examples.md @@ -109,23 +109,23 @@ To switch between branches: 1. Clean up the current branch, de-initializing submodule and removing all build artifacts: - ```sh - make clean - make distclean - ``` + ```sh + make clean + make distclean + ``` 2. Switch to a new branch or tag (here we first fetch the fictional branch "PR_test_branch" from the `upstream` remote): - ```sh - git fetch upstream PR_test_branch - git checkout PR_test_branch - ``` + ```sh + git fetch upstream PR_test_branch + git checkout PR_test_branch + ``` 3. Get the submodules for the new branch: - ```sh - make submodulesclean - ``` + ```sh + make submodulesclean + ``` @@ -138,35 +138,35 @@ To get the source code for a _specific older release_ (tag): 1. Clone the PX4-Autopilot repo and navigate into _PX4-Autopilot_ directory: - ```sh - git clone https://github.com/PX4/PX4-Autopilot.git - cd PX4-Autopilot - ``` + ```sh + git clone https://github.com/PX4/PX4-Autopilot.git + cd PX4-Autopilot + ``` - :::note + :::note - You can reuse an existing repo rather than cloning a new one. - In this case clean the build environment (see [changing source trees](#changing-source-trees)): + You can reuse an existing repo rather than cloning a new one. + In this case clean the build environment (see [changing source trees](#changing-source-trees)): - ```sh - make clean - make distclean - ``` + ```sh + make clean + make distclean + ``` ::: 2. Checkout code for particular tag (e.g. for tag v1.13.0-beta2) - ```sh - git checkout v1.13.0-beta2 - ``` + ```sh + git checkout v1.13.0-beta2 + ``` 3. Update submodules: - ```sh - make submodulesclean - ``` + ```sh + make submodulesclean + ``` ## Get a Release Branch diff --git a/docs/zh/debug/eclipse_jlink.md b/docs/zh/debug/eclipse_jlink.md index bf292df0e3..e23e23833d 100644 --- a/docs/zh/debug/eclipse_jlink.md +++ b/docs/zh/debug/eclipse_jlink.md @@ -53,17 +53,17 @@ For more information, see: [https://gnu-mcu-eclipse.github.io/debug/jlink/instal 7. Update packs: - Click the small icon on the top right called _Open Perspective_ and open the _Packs_ perspective. - ![Eclipse: Workspace](../../assets/debug/eclipse_workspace_perspective.png) + ![Eclipse: Workspace](../../assets/debug/eclipse_workspace_perspective.png) - Click the **update all** button. - :::tip - This takes a VERY LONG TIME (10 minutes). - Ignore all the errors about missing packages that pop up. + :::tip + This takes a VERY LONG TIME (10 minutes). + Ignore all the errors about missing packages that pop up. ::: - ![Eclipse: Workspace Packs Perspective](../../assets/debug/eclipse_packs_perspective.jpg) + ![Eclipse: Workspace Packs Perspective](../../assets/debug/eclipse_packs_perspective.jpg) - The STM32Fxx devices are found in the Keil folder, install by right-clicking and then selecting **install** on the according device for F4 and F7. @@ -79,24 +79,24 @@ For more information, see: [https://gnu-mcu-eclipse.github.io/debug/jlink/instal ![Eclipse: Debug config](../../assets/debug/eclipse_settings_debug_config.png) 10. Then select _GDB SEGGER J-Link Debugging_ and then the **New config** button on the top left. - ![Eclipse: GDB Segger Debug config](../../assets/debug/eclipse_settings_debug_config_gdb_segger.png) + ![Eclipse: GDB Segger Debug config](../../assets/debug/eclipse_settings_debug_config_gdb_segger.png) 11. Setup build config: - - Give it a name and set the _C/C++ Application_ to the corresponding **.elf** file. - - Choose _Disable Auto build_ + - Give it a name and set the _C/C++ Application_ to the corresponding **.elf** file. + - Choose _Disable Auto build_ ::: info Remember that you must build the target from the command line before starting a debug session. ::: - ![Eclipse: GDB Segger Debug config](../../assets/debug/eclipse_settings_debug_config_gdb_segger_build_config.png) + ![Eclipse: GDB Segger Debug config](../../assets/debug/eclipse_settings_debug_config_gdb_segger_build_config.png) 12. The _Debugger_ and _Startup_ tabs shouldn’t need any modifications (just verify your settings with the screenshots below) - ![Eclipse: GDB Segger Debug config: debugger tab](../../assets/debug/eclipse_settings_debug_config_gdb_segger_build_config_debugger_tab.png) - ![Eclipse: GDB Segger Debug config: startup tab](../../assets/debug/eclipse_settings_debug_config_gdb_segger_build_config_startup_tab.png) + ![Eclipse: GDB Segger Debug config: debugger tab](../../assets/debug/eclipse_settings_debug_config_gdb_segger_build_config_debugger_tab.png) + ![Eclipse: GDB Segger Debug config: startup tab](../../assets/debug/eclipse_settings_debug_config_gdb_segger_build_config_startup_tab.png) ## SEGGER Task-aware debugging @@ -109,16 +109,16 @@ To enable this feature for use in Eclipse: - Open a terminal in the root of your PX4-Autopilot source code - In the terminal, open `menuconfig` using the appropriate make target for the build. - This will be something like: + This will be something like: - ```sh - make px4_fmu-v5_default boardguiconfig - ``` + ```sh + make px4_fmu-v5_default boardguiconfig + ``` - (See [PX4 Menuconfig Setup](../hardware/porting_guide_config.md#px4-menuconfig-setup) for more information) on using the config tools). + (See [PX4 Menuconfig Setup](../hardware/porting_guide_config.md#px4-menuconfig-setup) for more information) on using the config tools). - Ensure that the _Enable TCBinfo struct for debug_ is selected as shown: - ![NuttX: Menuconfig: CONFIG_DEBUG_TCBINFO](../../assets/debug/nuttx_tcb_task_aware.png) + ![NuttX: Menuconfig: CONFIG_DEBUG_TCBINFO](../../assets/debug/nuttx_tcb_task_aware.png) 2. Compile the **jlink-nuttx.so** library in the terminal by running the following command in the terminal: `make jlink-nuttx` diff --git a/docs/zh/debug/failure_injection.md b/docs/zh/debug/failure_injection.md index 62db0208cc..e013753243 100644 --- a/docs/zh/debug/failure_injection.md +++ b/docs/zh/debug/failure_injection.md @@ -68,13 +68,13 @@ To simulate losing RC signal without having to turn off your RC controller: 1. Enable the parameter [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN). 2. Enter the following commands on the MAVLink console or SITL _pxh shell_: - ```sh - # Fail RC (turn publishing off) - failure rc_signal off + ```sh + # Fail RC (turn publishing off) + failure rc_signal off - # Restart RC publishing - failure rc_signal ok - ``` + # Restart RC publishing + failure rc_signal ok + ``` ## MAVSDK Failure Plugin diff --git a/docs/zh/dev_airframes/adding_a_new_frame.md b/docs/zh/dev_airframes/adding_a_new_frame.md index 6681de2605..6bc2662d6d 100644 --- a/docs/zh/dev_airframes/adding_a_new_frame.md +++ b/docs/zh/dev_airframes/adding_a_new_frame.md @@ -37,8 +37,8 @@ Alternatively you can just append the modified parameters to the startup configu To add a frame configuration to firmware: 1. Create a new config file in the [init.d/airframes](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d/airframes) folder. - - Give it a short descriptive filename and prepend the filename with an unused autostart ID (for example, `1033092_superfast_vtol`). - - Update the file with configuration parameters and apps (see section above). + - Give it a short descriptive filename and prepend the filename with an unused autostart ID (for example, `1033092_superfast_vtol`). + - Update the file with configuration parameters and apps (see section above). 2. Add the name of the new frame config file to the [CMakeLists.txt](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt) in the relevant section for the type of vehicle. 3. [Build and upload](../dev_setup/building_px4.md) the software. @@ -292,37 +292,37 @@ If the airframe is for a **new group** you additionally need to: 2. Add a mapping between the new group name and image filename in the [srcparser.py](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/px4airframes/srcparser.py) method `GetImageName()` (follow the pattern below): - ```python - def GetImageName(self): - """ - Get parameter group image base name (w/o extension) - """ - if (self.name == "Standard Plane"): - return "Plane" - elif (self.name == "Flying Wing"): - return "FlyingWing" - ... - ... - return "AirframeUnknown" - ``` + ```python + def GetImageName(self): + """ + Get parameter group image base name (w/o extension) + """ + if (self.name == "Standard Plane"): + return "Plane" + elif (self.name == "Flying Wing"): + return "FlyingWing" + ... + ... + return "AirframeUnknown" + ``` 3. Update _QGroundControl_: - - Add the svg image for the group into: [src/AutopilotPlugins/Common/images](https://github.com/mavlink/qgroundcontrol/tree/master/src/AutoPilotPlugins/Common/Images) - - Add reference to the svg image into [qgcimages.qrc](https://github.com/mavlink/qgroundcontrol/blob/master/qgcimages.qrc), following the pattern below: + - Add the svg image for the group into: [src/AutopilotPlugins/Common/images](https://github.com/mavlink/qgroundcontrol/tree/master/src/AutoPilotPlugins/Common/Images) + - Add reference to the svg image into [qgcimages.qrc](https://github.com/mavlink/qgroundcontrol/blob/master/qgcimages.qrc), following the pattern below: - ```xml - - ... - src/AutoPilotPlugins/Common/Images/AirframeSimulation.svg - src/AutoPilotPlugins/Common/Images/AirframeUnknown.svg - src/AutoPilotPlugins/Common/Images/Boat.svg - src/AutoPilotPlugins/Common/Images/FlyingWing.svg - ... - ``` + ```xml + + ... + src/AutoPilotPlugins/Common/Images/AirframeSimulation.svg + src/AutoPilotPlugins/Common/Images/AirframeUnknown.svg + src/AutoPilotPlugins/Common/Images/Boat.svg + src/AutoPilotPlugins/Common/Images/FlyingWing.svg + ... + ``` - ::: info - The remaining airframe metadata should be automatically included in the firmware (once **srcparser.py** is updated). + ::: info + The remaining airframe metadata should be automatically included in the firmware (once **srcparser.py** is updated). ::: diff --git a/docs/zh/dev_log/log_encryption.md b/docs/zh/dev_log/log_encryption.md index be7cba82e7..bc4380f471 100644 --- a/docs/zh/dev_log/log_encryption.md +++ b/docs/zh/dev_log/log_encryption.md @@ -30,7 +30,7 @@ If another algorithm is supported in future, the process is _likely_ to remain t The encryption process for each new ULog is: 1. A XChaCha20 symmetric key is generated and encrypted using an RSA2048 public key. - This wrapped (encrypted) key is stored on the SD card in the beginning of a file that has the suffix `.ulge` ("ulog encrypted"). + This wrapped (encrypted) key is stored on the SD card in the beginning of a file that has the suffix `.ulge` ("ulog encrypted"). 2. When a log is captured, the ULog data is encrypted with the unwrapped symmetric key and the resulting data is appended into the end of the `.ulge` file immediately after the wrapped key data. After the flight, the `.ulge` file containing both the wrapped symmetric key and the encrypted log data can be found on the SD card. @@ -356,26 +356,26 @@ This section explains how you might manually run the same steps as the script (s 2. Use OpenSSL to generate a RSA2048 private and public key: - ```sh - openssl genpkey -algorithm RSA -out private_key.pem -pkeyopt rsa_keygen_bits:2048 - ``` + ```sh + openssl genpkey -algorithm RSA -out private_key.pem -pkeyopt rsa_keygen_bits:2048 + ``` 3. Create a public key from this private key: - ```sh - # Convert private_key.pem to a DER file - openssl rsa -pubout -in private_key.pem -outform DER -out public_key.der - # From the DER file, generate a public key in hex format, separated by commas - xxd -p public_key.der | tr -d '\n' | sed 's/\(..\)/0x\1, /g' > public_key.pub - ``` + ```sh + # Convert private_key.pem to a DER file + openssl rsa -pubout -in private_key.pem -outform DER -out public_key.der + # From the DER file, generate a public key in hex format, separated by commas + xxd -p public_key.der | tr -d '\n' | sed 's/\(..\)/0x\1, /g' > public_key.pub + ``` 4. Copy the keys into the appropriate locations expected by the rest of the toolchain (as shown in previous section). 5. To use this key, modify your `.px4board` file to point `CONFIG_PUBLIC_KEY1` to the file location of `public_key.pub`. - ```sh - CONFIG_PUBLIC_KEY1="../../../keys/public/public_key.pub" - ``` + ```sh + CONFIG_PUBLIC_KEY1="../../../keys/public/public_key.pub" + ``` ## Flight Review & Encrypted logs @@ -397,10 +397,10 @@ This can use logs that you have downloaded and decrypted yourself, or you can in 3. Add this key location into the server config file: `flight_review/app/config_default.ini`. - The line to add should look something like this (for the file above): + The line to add should look something like this (for the file above): - ```sh - ulge_private_key = ../private_key/private_key.pem - ``` + ```sh + ulge_private_key = ../private_key/private_key.pem + ``` 4. Follow the Flight Review Instructions to start your server. diff --git a/docs/zh/dev_log/logging.md b/docs/zh/dev_log/logging.md index 44af24829b..cfc8cc19a8 100644 --- a/docs/zh/dev_log/logging.md +++ b/docs/zh/dev_log/logging.md @@ -33,16 +33,17 @@ The logging system is configured by default to collect sensible logs for [flight Logging may further be configured using the [SD Logging](../advanced_config/parameter_reference.md#sd-logging) parameters. The parameters you are most likely to change are listed below. -| 参数 | 描述 | -| --------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [SDLOG_MODE](../advanced_config/parameter_reference.md#SDLOG_MODE) | 日志模式 Defines when logging starts and stops.
- `-1`: Logging disabled.
- `0`: Log when armed until disarm (default).
- `1`: Log from boot until disarm.
- `2`: Log from boot until shutdown.
- `3`: Log based on the [AUX1 RC channel](../advanced_config/parameter_reference.md#RC_MAP_AUX1).
- `4`: Log from first armed until shutdown. | -| [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) | Logging profile. Use this to enable less common logging/analysis (e.g. for EKF2 replay, high rate logging for PID & filter tuning, thermal temperature calibration). | -| [SDLOG_MISSION](../advanced_config/parameter_reference.md#SDLOG_MISSION) | Create very small additional "Mission Log".
This log can _not_ be used with [Flight Review](../log/flight_log_analysis.md#flight-review-online-tool), but is useful when you need a small log for geotagging or regulatory compliance. | +| 参数 | 描述 | +| --------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [SDLOG_MODE](../advanced_config/parameter_reference.md#SDLOG_MODE) | 日志模式 Defines when logging starts and stops.
- `0`: Log when armed until disarm (default).
- `1`: Log from boot until disarm.
- `2`: Log from boot until shutdown.
- `3`: Log based on the [AUX1 RC channel](../advanced_config/parameter_reference.md#RC_MAP_AUX1).
- `4`: Log from first armed until shutdown. | +| [SDLOG_BACKEND](../advanced_config/parameter_reference.md#SDLOG_BACKEND) | Logging Backend (bitmask). Setting a bit enables the corresponding backend. If no backend is selected, the logger is disabled.
- bit `0`: SD card logging.
- bit `1`: Mavlink logging. | +| [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) | Logging profile. Use this to enable less common logging/analysis (e.g. for EKF2 replay, high rate logging for PID & filter tuning, thermal temperature calibration). | +| [SDLOG_MISSION](../advanced_config/parameter_reference.md#SDLOG_MISSION) | Create very small additional "Mission Log".
This log can _not_ be used with [Flight Review](../log/flight_log_analysis.md#flight-review-online-tool), but is useful when you need a small log for geotagging or regulatory compliance. | Useful settings for specific cases: - Raw sensor data for comparison: [SDLOG_MODE=1](../advanced_config/parameter_reference.md#SDLOG_MODE) and [SDLOG_PROFILE=64](../advanced_config/parameter_reference.md#SDLOG_PROFILE). -- Disabling logging altogether: [SDLOG_MODE=`-1`](../advanced_config/parameter_reference.md#SDLOG_MODE) +- Disabling logging altogether: [SDLOG_BACKEND=`0`](../advanced_config/parameter_reference.md#SDLOG_BACKEND) ### Logger module diff --git a/docs/zh/dev_setup/dev_env_linux_ubuntu.md b/docs/zh/dev_setup/dev_env_linux_ubuntu.md index 3c01f2f634..85e5d3670e 100644 --- a/docs/zh/dev_setup/dev_env_linux_ubuntu.md +++ b/docs/zh/dev_setup/dev_env_linux_ubuntu.md @@ -33,24 +33,24 @@ To install the toolchain: 1. [Download PX4 Source Code](../dev_setup/building_px4.md): - ```sh - git clone https://github.com/PX4/PX4-Autopilot.git --recursive - ``` + ```sh + git clone https://github.com/PX4/PX4-Autopilot.git --recursive + ``` - ::: info - The environment setup scripts in the source usually work for recent PX4 releases. - If working with an older version of PX4 you may need to [get the source code specific to your release](../contribute/git_examples.md#get-a-specific-release). + ::: info + The environment setup scripts in the source usually work for recent PX4 releases. + If working with an older version of PX4 you may need to [get the source code specific to your release](../contribute/git_examples.md#get-a-specific-release). ::: 2. Run the **ubuntu.sh** with no arguments (in a bash shell) to install everything: - ```sh - bash ./PX4-Autopilot/Tools/setup/ubuntu.sh - ``` + ```sh + bash ./PX4-Autopilot/Tools/setup/ubuntu.sh + ``` - - 在安装过程中确认并通过所有的提示。 - - You can use the `--no-nuttx` and `--no-sim-tools` options to omit the NuttX and/or simulation tools. + - 在安装过程中确认并通过所有的提示。 + - You can use the `--no-nuttx` and `--no-sim-tools` options to omit the NuttX and/or simulation tools. 3. If you need Gazebo Classic (Ubuntu 22.04 only) then you can manually remove Gazebo and install it by following the instructions in [Gazebo Classic > Installation](../sim_gazebo_classic/index.md#installation). diff --git a/docs/zh/dev_setup/dev_env_mac.md b/docs/zh/dev_setup/dev_env_mac.md index f379cceb75..8d1b5a0c74 100644 --- a/docs/zh/dev_setup/dev_env_mac.md +++ b/docs/zh/dev_setup/dev_env_mac.md @@ -38,21 +38,21 @@ First set up the environment 1. Enable more open files by appending the following line to the `~/.zshenv` file (creating it if necessary): - ```sh - echo ulimit -S -n 2048 >> ~/.zshenv - ``` + ```sh + echo ulimit -S -n 2048 >> ~/.zshenv + ``` - ::: info - If you don't do this, the build toolchain may report the error: `"LD: too many open files"` + ::: info + If you don't do this, the build toolchain may report the error: `"LD: too many open files"` ::: 2. Enforce Python 3 by appending the following lines to `~/.zshenv` - ```sh - # Point pip3 to MacOS system python 3 pip - alias pip3=/usr/bin/pip3 - ``` + ```sh + # Point pip3 to MacOS system python 3 pip + alias pip3=/usr/bin/pip3 + ``` ### Common Tools @@ -62,19 +62,19 @@ To setup the environment to be able to build for Pixhawk/NuttX hardware (and ins 2. Run these commands in your shell to install the common tools: - ```sh - brew tap PX4/px4 - brew install px4-dev - ``` + ```sh + brew tap PX4/px4 + brew install px4-dev + ``` 3. Install the required Python packages: - ```sh - # install required packages using pip3 - python3 -m pip install --user pyserial empty toml numpy pandas jinja2 pyyaml pyros-genmsg packaging kconfiglib future jsonschema - # if this fails with a permissions error, your Python install is in a system path - use this command instead: - sudo -H python3 -m pip install --user pyserial empty toml numpy pandas jinja2 pyyaml pyros-genmsg packaging kconfiglib future jsonschema - ``` + ```sh + # install required packages using pip3 + python3 -m pip install --user pyserial empty toml numpy pandas jinja2 pyyaml pyros-genmsg packaging kconfiglib future jsonschema + # if this fails with a permissions error, your Python install is in a system path - use this command instead: + sudo -H python3 -m pip install --user pyserial empty toml numpy pandas jinja2 pyyaml pyros-genmsg packaging kconfiglib future jsonschema + ``` ## Gazebo Classic 模拟 @@ -82,35 +82,35 @@ To setup the environment for [Gazebo Classic](../sim_gazebo_classic/index.md) si 1. Run the following commands in your shell: - ```sh - brew unlink tbb - sed -i.bak '/disable! date:/s/^/ /; /disable! date:/s/./#/3' $(brew --prefix)/Library/Taps/homebrew/homebrew-core/Formula/tbb@2020.rb - brew install tbb@2020 - brew link tbb@2020 - ``` + ```sh + brew unlink tbb + sed -i.bak '/disable! date:/s/^/ /; /disable! date:/s/./#/3' $(brew --prefix)/Library/Taps/homebrew/homebrew-core/Formula/tbb@2020.rb + brew install tbb@2020 + brew link tbb@2020 + ``` - ::: info - September 2021: The commands above are a workaround to this bug: [PX4-Autopilot#17644](https://github.com/PX4/PX4-Autopilot/issues/17644). - They can be removed once it is fixed (along with this note). + ::: info + September 2021: The commands above are a workaround to this bug: [PX4-Autopilot#17644](https://github.com/PX4/PX4-Autopilot/issues/17644). + They can be removed once it is fixed (along with this note). ::: 2. To install SITL simulation with Gazebo Classic: - ```sh - brew install --cask temurin - brew install --cask xquartz - brew install px4-sim-gazebo - ``` + ```sh + brew install --cask temurin + brew install --cask xquartz + brew install px4-sim-gazebo + ``` 3. Run the macOS setup script: `PX4-Autopilot/Tools/setup/macos.sh` - The easiest way to do this is to clone the PX4 source, and then run the script from the directory, as shown: + The easiest way to do this is to clone the PX4 source, and then run the script from the directory, as shown: - ```sh - git clone https://github.com/PX4/PX4-Autopilot.git --recursive - cd PX4-Autopilot/Tools/setup - sh macos.sh - ``` + ```sh + git clone https://github.com/PX4/PX4-Autopilot.git --recursive + cd PX4-Autopilot/Tools/setup + sh macos.sh + ``` ## Gazebo dependencies diff --git a/docs/zh/dev_setup/dev_env_windows_cygwin_packager_setup.md b/docs/zh/dev_setup/dev_env_windows_cygwin_packager_setup.md index fef641a137..1e69010fb9 100644 --- a/docs/zh/dev_setup/dev_env_windows_cygwin_packager_setup.md +++ b/docs/zh/dev_setup/dev_env_windows_cygwin_packager_setup.md @@ -135,31 +135,31 @@ The toolchain gets maintained and hence these instructions might not cover every 10. Download [**Apache Ant**](https://ant.apache.org/bindownload.cgi) as zip archive of the binaries for Windows and unpack the content to the folder `C:\PX4\toolchain\apache-ant`. - :::tip - Make sure you don't have an additional folder layer from the folder which is inside the downloaded archive. + :::tip + Make sure you don't have an additional folder layer from the folder which is inside the downloaded archive. ::: - ::: info - This is what the toolchain does in: [apache-ant/install-apache-ant.bat](https://github.com/PX4/PX4-windows-toolchain/blob/master/toolchain/apache-ant/install-apache-ant.bat). + ::: info + This is what the toolchain does in: [apache-ant/install-apache-ant.bat](https://github.com/PX4/PX4-windows-toolchain/blob/master/toolchain/apache-ant/install-apache-ant.bat). ::: 11. Download, build and add _genromfs_ to the path: - - Clone the source code to the folder **C:\PX4\toolchain\genromfs\genromfs-src** with + - Clone the source code to the folder **C:\PX4\toolchain\genromfs\genromfs-src** with ```sh cd /c/toolchain/genromfs git clone https://github.com/chexum/genromfs.git genromfs-src ``` - - Compile it with: + - Compile it with: ```sh cd genromfs-src make all ``` - - Copy the resulting binary **genromfs.exe** one folder level out to: **C:\PX4\toolchain\genromfs** + - Copy the resulting binary **genromfs.exe** one folder level out to: **C:\PX4\toolchain\genromfs** 12. Make sure all the binary folders of all the installed components are correctly listed in the `PATH` variable configured by [**setup-environment.bat**](https://github.com/PX4/PX4-windows-toolchain/blob/master/toolchain/scripts/setup-environment.bat). diff --git a/docs/zh/dev_setup/dev_env_windows_vm.md b/docs/zh/dev_setup/dev_env_windows_vm.md index c9190d5ea5..8bfc9a4148 100644 --- a/docs/zh/dev_setup/dev_env_windows_vm.md +++ b/docs/zh/dev_setup/dev_env_windows_vm.md @@ -57,12 +57,12 @@ VMWare performance is acceptable for basic usage (building Firmware) but not for Remember all settings are only for within your host operating system usage and hence you can disable any screen saver and local workstation security features which do not increase risk of a network attack. 10. Once the new VM is booted up make sure you install _VMWare tools drivers and tools extension_ inside your guest system. - This will enhance performance and usability of your VM usage: - - Significantly enhanced graphics performance - - Proper support for hardware device usage like USB port allocation (important for target upload), proper mouse wheel scrolling, sound support - - Guest display resolution adaption to the window size - - Clipboard sharing to host system - - File sharing to host system + This will enhance performance and usability of your VM usage: + - Significantly enhanced graphics performance + - Proper support for hardware device usage like USB port allocation (important for target upload), proper mouse wheel scrolling, sound support + - Guest display resolution adaption to the window size + - Clipboard sharing to host system + - File sharing to host system 11. Continue with [PX4 environment setup for Linux](../dev_setup/dev_env_linux.md) @@ -96,11 +96,11 @@ To allow this, you need to configure USB passthrough settings: 4. Add USB filters for the bootloader in VM: **VirtualBox > Settings > USB > Add new USB filter**. - Open the menu and plug in the USB cable connected to your autopilot. - Select the `...Bootloader` device when it appears in the UI. + Select the `...Bootloader` device when it appears in the UI. - ::: info - The bootloader device only appears for a few seconds after connecting USB. - If it disappears before you can select it, disconnect and then reconnect USB. + ::: info + The bootloader device only appears for a few seconds after connecting USB. + If it disappears before you can select it, disconnect and then reconnect USB. ::: diff --git a/docs/zh/dev_setup/dev_env_windows_wsl.md b/docs/zh/dev_setup/dev_env_windows_wsl.md index 6c1083f1e2..d0800244f0 100644 --- a/docs/zh/dev_setup/dev_env_windows_wsl.md +++ b/docs/zh/dev_setup/dev_env_windows_wsl.md @@ -48,38 +48,38 @@ The benefit of WSL2 is that its virtual machine is deeply integrated into Window To install WSL2 with Ubuntu on a new installation of Windows 10 or 11: 1. Make sure your computer your computer's virtualization feature is enabled in the BIOS. - It's usually referred as "Virtualization Technology", "Intel VT-x" or "AMD-V" respectively + It's usually referred as "Virtualization Technology", "Intel VT-x" or "AMD-V" respectively 2. Open _cmd.exe_ as administrator. - This can be done by pressing the start key, typing `cmd`, right-clicking on the _Command prompt_ entry and selecting **Run as administrator**. + This can be done by pressing the start key, typing `cmd`, right-clicking on the _Command prompt_ entry and selecting **Run as administrator**. 3. Execute the following commands to install WSL2 and a particular Ubuntu version: - - Default version (Ubuntu 22.04): + - Default version (Ubuntu 22.04): - ```sh - wsl --install - ``` + ```sh + wsl --install + ``` - - Ubuntu 20.04 ([Gazebo-Classic Simulation](../sim_gazebo_classic/index.md)) + - Ubuntu 20.04 ([Gazebo-Classic Simulation](../sim_gazebo_classic/index.md)) - ```sh - wsl --install -d Ubuntu-20.04 - ``` + ```sh + wsl --install -d Ubuntu-20.04 + ``` - - Ubuntu 22.04 ([Gazebo Simulation](../sim_gazebo_gz/index.md)) + - Ubuntu 22.04 ([Gazebo Simulation](../sim_gazebo_gz/index.md)) - ```sh - wsl --install -d Ubuntu-22.04 - ``` + ```sh + wsl --install -d Ubuntu-22.04 + ``` - ::: info - You can also install[Ubuntu 20.04](https://www.microsoft.com/store/productId/9MTTCL66CPXJ) and [Ubuntu 22.04](https://www.microsoft.com/store/productId/9PN20MSR04DW) from the store, which allows you to delete the application using the normal Windows Add/Remove settings: + ::: info + You can also install[Ubuntu 20.04](https://www.microsoft.com/store/productId/9MTTCL66CPXJ) and [Ubuntu 22.04](https://www.microsoft.com/store/productId/9PN20MSR04DW) from the store, which allows you to delete the application using the normal Windows Add/Remove settings: ::: 4. WSL will prompt you for a user name and password for the Ubuntu installation. - Record these credentials as you will need them later on! + Record these credentials as you will need them later on! The command prompt is now a terminal within the newly installed Ubuntu environment. @@ -94,26 +94,26 @@ If you're using [Windows Terminal](https://learn.microsoft.com/en-us/windows/ter To open a WSL shell using a command prompt: 1. Open a command prompt: - - Press the Windows **Start** key. - - Type `cmd` and press **Enter** to open the prompt. + - Press the Windows **Start** key. + - Type `cmd` and press **Enter** to open the prompt. 2. To start WSL and access the WSL shell, execute the command: - ```sh - wsl -d - ``` + ```sh + wsl -d + ``` - 例如: + 例如: - ```sh - wsl -d Ubuntu - ``` + ```sh + wsl -d Ubuntu + ``` - ```sh - wsl -d Ubuntu-20.04 - ``` + ```sh + wsl -d Ubuntu-20.04 + ``` - If you only have one version of Ubuntu, you can just use `wsl`. + If you only have one version of Ubuntu, you can just use `wsl`. Enter the following commands to first close the WSL shell, and then shut down WSL: @@ -135,57 +135,57 @@ To install the development toolchain: 2. Execute the command `cd ~` to switch to the home folder of WSL for the next steps. - :::warning - This is important! - If you work from a location outside of the WSL file system you'll run into issues such as very slow execution and access right/permission errors. + :::warning + This is important! + If you work from a location outside of the WSL file system you'll run into issues such as very slow execution and access right/permission errors. ::: 3. Download the PX4 source code using `git` (which is already installed in WSL2): - ```sh - git clone https://github.com/PX4/PX4-Autopilot.git --recursive - ``` + ```sh + git clone https://github.com/PX4/PX4-Autopilot.git --recursive + ``` - ::: info - The environment setup scripts in the source usually work for recent PX4 releases. - If working with an older version of PX4 you may need to [get the source code specific to your release](../contribute/git_examples.md#get-a-specific-release). + ::: info + The environment setup scripts in the source usually work for recent PX4 releases. + If working with an older version of PX4 you may need to [get the source code specific to your release](../contribute/git_examples.md#get-a-specific-release). ::: 4. Run the **ubuntu.sh** installer script and acknowledge any prompts as the script progresses: - ```sh - bash ./PX4-Autopilot/Tools/setup/ubuntu.sh - ``` + ```sh + bash ./PX4-Autopilot/Tools/setup/ubuntu.sh + ``` - ::: info - This installs tools to build PX4 for Pixhawk and either Gazebo or Gazebo Classic targets: + ::: info + This installs tools to build PX4 for Pixhawk and either Gazebo or Gazebo Classic targets: - - You can use the `--no-nuttx` and `--no-sim-tools` options to omit the NuttX and/or simulation tools. - - Other Linux build targets are untested (you can try these by entering the appropriate commands in [Ubuntu Development Environment](../dev_setup/dev_env_linux_ubuntu.md) into the WSL shell). + - You can use the `--no-nuttx` and `--no-sim-tools` options to omit the NuttX and/or simulation tools. + - Other Linux build targets are untested (you can try these by entering the appropriate commands in [Ubuntu Development Environment](../dev_setup/dev_env_linux_ubuntu.md) into the WSL shell). ::: 5. Restart the "WSL computer" after the script completes (exit the shell, shutdown WSL, and restart WSL): - ```sh - exit - wsl --shutdown - wsl - ``` + ```sh + exit + wsl --shutdown + wsl + ``` 6. Switch to the PX4 repository in the WSL home folder: - ```sh - cd ~/PX4-Autopilot - ``` + ```sh + cd ~/PX4-Autopilot + ``` 7. Build the PX4 SITL target and test your environment: - ```sh - make px4_sitl - ``` + ```sh + make px4_sitl + ``` For more build options see [Building PX4 Software](../dev_setup/building_px4.md). @@ -205,26 +205,26 @@ To set up the integration: 5. In the WSL shell, switch to the PX4 folder: - ```sh - cd ~/PX4-Autopilot - ``` + ```sh + cd ~/PX4-Autopilot + ``` 6. In the WSL shell, start VS Code: - ```sh - code . - ``` + ```sh + code . + ``` - This will open the IDE fully integrated with the WSL shell. + This will open the IDE fully integrated with the WSL shell. - Make sure you always open the PX4 repository in the Remote WSL mode. + Make sure you always open the PX4 repository in the Remote WSL mode. 7. Next time you want to develop WSL2 you can very easily open it again in Remote WSL mode by selecting **Open Recent** (as shown below). - This will start WSL for you. + This will start WSL for you. - ![](../../assets/toolchain/vscode/vscode_wsl.png) + ![](../../assets/toolchain/vscode/vscode_wsl.png) - Note however that the IP address of the WSL virtual machine will have changed, so you won't be able to monitor simulation from QGC for Windows (you can still monitor using QGC for Linux) + Note however that the IP address of the WSL virtual machine will have changed, so you won't be able to monitor simulation from QGC for Windows (you can still monitor using QGC for Linux) ## QGroundControl @@ -240,21 +240,21 @@ You can do this from within the WSL shell. 1. In a web browser, navigate to the QGC [Ubuntu download section](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#ubuntu) 2. Right-click on the **QGroundControl.AppImage** link, and select "Copy link address". - This will be something like _https://d176td9ibe4jno.cloudfront.net/builds/master/QGroundControl.AppImage_ + This will be something like _https://d176td9ibe4jno.cloudfront.net/builds/master/QGroundControl.AppImage_ 3. [Open a WSL shell](#opening-a-wsl-shell) and enter the following commands to download the appimage and make it executable (replace the AppImage URL where indicated): - ```sh - cd ~ - wget - chmod +x QGroundControl.AppImage - ``` + ```sh + cd ~ + wget + chmod +x QGroundControl.AppImage + ``` 4. Run QGroundControl: - ```sh - ./QGroundControl.AppImage - ``` + ```sh + ./QGroundControl.AppImage + ``` QGroundControl will launch and automatically connect to a running simulation and allow you to monitor and control your vehicle(s). @@ -270,15 +270,15 @@ These steps describe how you can connect to the simulation running in the WSL: 2. Check the IP address of the WSL virtual machine by running the command `ip addr | grep eth0`: - ```sh - $ ip addr | grep eth0 + ```sh + $ ip addr | grep eth0 - 6: eth0: mtu 1500 qdisc mq state UP group default qlen 1000 - inet 172.18.46.131/20 brd 172.18.47.255 scope global eth0 - ``` + 6: eth0: mtu 1500 qdisc mq state UP group default qlen 1000 + inet 172.18.46.131/20 brd 172.18.47.255 scope global eth0 + ``` - Copy the first part of the `eth0` interface `inet` address to the clipboard. - In this case: `172.18.46.131`. + Copy the first part of the `eth0` interface `inet` address to the clipboard. + In this case: `172.18.46.131`. 3. In QGC go to **Q > Application Settings > Comm Links** @@ -304,14 +304,14 @@ Do the following steps to flash your custom binary built in WSL: 1. If you haven't already built the binary in WSL e.g. with a [WSL shell](dev_env_windows_wsl.md#opening-a-wsl-shell) and by running: - ```sh - cd ~/PX4-Autopilot - make px4_fmu-v5 - ``` + ```sh + cd ~/PX4-Autopilot + make px4_fmu-v5 + ``` - ::: tip - Use the correct `make` target for your board. - `px4_fmu-v5` can be used for a Pixhawk 4 board. + ::: tip + Use the correct `make` target for your board. + `px4_fmu-v5` can be used for a Pixhawk 4 board. ::: @@ -325,12 +325,12 @@ Do the following steps to flash your custom binary built in WSL: 6. Continue and select the firmware binary you just built in WSL. - In the open dialog look for the "Linux" location with the penguin icon in the left pane. - It's usually all the way at the bottom. - Choose the file in the path: `Ubuntu\home\{your WSL user name}\PX4-Autopilot\build\{your build target}\{your build target}.px4` + In the open dialog look for the "Linux" location with the penguin icon in the left pane. + It's usually all the way at the bottom. + Choose the file in the path: `Ubuntu\home\{your WSL user name}\PX4-Autopilot\build\{your build target}\{your build target}.px4` - ::: info - You can add the folder to the favourites to access it quickly next time. + ::: info + You can add the folder to the favourites to access it quickly next time. ::: diff --git a/docs/zh/dev_setup/vscode.md b/docs/zh/dev_setup/vscode.md index 634709f834..4b699c246b 100644 --- a/docs/zh/dev_setup/vscode.md +++ b/docs/zh/dev_setup/vscode.md @@ -27,10 +27,10 @@ You must already have installed the command line [PX4 developer environment](../ - Select _Open folder ..._ option on the welcome page (or using the menu: **File > Open Folder**): - ![Open Folder](../../assets/toolchain/vscode/welcome_open_folder.jpg) + ![Open Folder](../../assets/toolchain/vscode/welcome_open_folder.jpg) - A file selection dialog will appear. - Select the **PX4-Autopilot** directory and then press **OK**. + Select the **PX4-Autopilot** directory and then press **OK**. The project files and configuration will then load into _VSCode_. @@ -49,9 +49,9 @@ You must already have installed the command line [PX4 developer environment](../ ::: - If prompted to install a new version of _cmake_: - - Say **No** (the right version is installed with the [PX4 developer environment](../dev_setup/dev_env.md)). + - Say **No** (the right version is installed with the [PX4 developer environment](../dev_setup/dev_env.md)). - If prompted to sign into _github.com_ and add your credentials: - - This is up to you! It provides a deep integration between Github and the IDE, which may simplify your workflow. + - This is up to you! It provides a deep integration between Github and the IDE, which may simplify your workflow. - Other prompts are optional, and may be installed if they seem useful. @@ -63,21 +63,21 @@ To build: 1. Select your build target ("cmake build config"): - The current _cmake build target_ is shown on the blue _config_ bar at the bottom (if this is already your desired target, skip to next step). - ![Select Cmake build target](../../assets/toolchain/vscode/cmake_build_config.jpg) + ![Select Cmake build target](../../assets/toolchain/vscode/cmake_build_config.jpg) - ::: info - The cmake target you select affects the targets offered for when [building/debugging](#debugging) (i.e. for hardware debugging you must select a hardware target like `px4_fmu-v6`). + ::: info + The cmake target you select affects the targets offered for when [building/debugging](#debugging) (i.e. for hardware debugging you must select a hardware target like `px4_fmu-v6`). ::: - Click the target on the config bar to display other options, and select the one you want (this will replace any selected target). - _Cmake_ will then configure your project (see notification in bottom right). - ![Cmake config project](../../assets/toolchain/vscode/cmake_configuring_project.jpg) + ![Cmake config project](../../assets/toolchain/vscode/cmake_configuring_project.jpg) - Wait until configuration completes. - When this is done the notification will disappear and you'll be shown the build location: - ![Cmake config project](../../assets/toolchain/vscode/cmake_configuring_project_done.jpg). + When this is done the notification will disappear and you'll be shown the build location: + ![Cmake config project](../../assets/toolchain/vscode/cmake_configuring_project_done.jpg). 2. You can then kick off a build from the config bar (select either **Build** or **Debug**). ![Run debug or build](../../assets/toolchain/vscode/run_debug_build.jpg) diff --git a/docs/zh/dronecan/holybro_h_rtk_zed_f9p_gps.md b/docs/zh/dronecan/holybro_h_rtk_zed_f9p_gps.md index 12c43945c6..9418fab0b8 100644 --- a/docs/zh/dronecan/holybro_h_rtk_zed_f9p_gps.md +++ b/docs/zh/dronecan/holybro_h_rtk_zed_f9p_gps.md @@ -64,10 +64,10 @@ To update the "AP Periph" firmware to the latest version: 1. [Download the latest binary](https://firmware.ardupilot.org/AP_Periph/latest/HolybroG4_GPS/). 2. Update the firmware using either of the following approaches: - - Using ArduPilot: - 1. Install _Ardupilot_ firmware on your flight controller and the Mission Planner GCS on your computer. - 2. Update the binary by following the instructions in the [DroneCAN FW Upgrade](https://docs.holybro.com/gps-and-rtk-system/zed-f9p-h-rtk-series/dronecan-fw-upgrade) guide. - - Use a serial-to-can converter (such as the [Zubax Babel](https://github.com/Zubax/canface_cf1?tab=readme-ov-file)) and the [DroneCAN GUI Tool](https://dronecan.github.io/Implementations/Libuavcan/Tutorials/11._Firmware_update/). + - Using ArduPilot: + 1. Install _Ardupilot_ firmware on your flight controller and the Mission Planner GCS on your computer. + 2. Update the binary by following the instructions in the [DroneCAN FW Upgrade](https://docs.holybro.com/gps-and-rtk-system/zed-f9p-h-rtk-series/dronecan-fw-upgrade) guide. + - Use a serial-to-can converter (such as the [Zubax Babel](https://github.com/Zubax/canface_cf1?tab=readme-ov-file)) and the [DroneCAN GUI Tool](https://dronecan.github.io/Implementations/Libuavcan/Tutorials/11._Firmware_update/). Remember to change the firmware on the flight controller back to PX4 afterwards. @@ -98,14 +98,14 @@ In order to use dual ZED-F9P GPS heading in PX4, follow these steps: 1. Open the QGroundControl parameters page. 2. On the left side next to the parameters list, double-click on the _System_ section (this hides the section). 3. Components should be visible on the left panel. - Click on the first `_Component_` that maps to the ZED-F9P DroneCAN node (below shown as _Component 124_). + Click on the first `_Component_` that maps to the ZED-F9P DroneCAN node (below shown as _Component 124_). 4. Click on the _GPS_ subsection and configure the parameters listed below: - - `GPS_TYPE`: Either set to `17` for moving baseline _base_, or set to `18` to be the moving baseline _rover_. - One F9P MUST be _rover_, and the other MUST be _base_. - - `GPS_AUTO_CONFIG`: set to 1 for both the rover and base - - `GPS_POS_X`, `GPS_POS_Y`, `GPS_POS_Z`: This is the antenna placement, which for the F9P is internal to the module. - This is the local offset (FRD) with respect to the autopilot. + - `GPS_TYPE`: Either set to `17` for moving baseline _base_, or set to `18` to be the moving baseline _rover_. + One F9P MUST be _rover_, and the other MUST be _base_. + - `GPS_AUTO_CONFIG`: set to 1 for both the rover and base + - `GPS_POS_X`, `GPS_POS_Y`, `GPS_POS_Z`: This is the antenna placement, which for the F9P is internal to the module. + This is the local offset (FRD) with respect to the autopilot. ![QGC Setup](../../assets/hardware/gps/holybro_h_rtk_zed_f9p_rover/holybro_f9p_gps_qgc_setup.png) diff --git a/docs/zh/dronecan/pomegranate_systems_pm.md b/docs/zh/dronecan/pomegranate_systems_pm.md index d63d011d6c..3550f395b3 100644 --- a/docs/zh/dronecan/pomegranate_systems_pm.md +++ b/docs/zh/dronecan/pomegranate_systems_pm.md @@ -45,11 +45,11 @@ Source code and build instructions can be found on [the bitbucket](https://bitbu 1. Enable DroneCAN by setting the [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) parameter to `2` (Sensors Automatic Config) or `3`. 2. Enable DroneCAN battery monitoring by setting [UAVCAN_SUB_BAT](../advanced_config/parameter_reference.md#UAVCAN_SUB_BAT) to `1` or `2` ( depending on your battery). 3. Set the following module parameters using the [MAVLink console](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/analyze_view/mavlink_console.html): - - Battery capacity in mAh: `battery_capacity_mAh` - - Battery voltage when _full_: `battery_full_V`, - - Battery voltage when _empty_: `battery_empty_V` - - Turn on current integration: `enable_current_track` - - (optional) Turn Off CANbus termination resistor :`enable_can_term` + - Battery capacity in mAh: `battery_capacity_mAh` + - Battery voltage when _full_: `battery_full_V`, + - Battery voltage when _empty_: `battery_empty_V` + - Turn on current integration: `enable_current_track` + - (optional) Turn Off CANbus termination resistor :`enable_can_term` **Example:** A Power Module with UAVCAN node id `125` connected to a `3S` LiPo with capacity of `5000mAh` can be configured with the following commands: diff --git a/docs/zh/dronecan/raccoonlab_power.md b/docs/zh/dronecan/raccoonlab_power.md index 6fb21706eb..e40ded7c3d 100644 --- a/docs/zh/dronecan/raccoonlab_power.md +++ b/docs/zh/dronecan/raccoonlab_power.md @@ -7,9 +7,9 @@ CAN power connectors are designed for light unmanned aerial (UAV) and other vehi There are two types of devices: 1. `CAN-MUX` devices provide power from XT30 connector to CAN. - There are 2 variation of this type of the device with different number of connectors. + There are 2 variation of this type of the device with different number of connectors. 2. `Power connector node` is designed to pass current (up to 60A) to power load and CAN, measure voltage and current on load. - It behaves as Cyphal/DroneCAN node. + It behaves as Cyphal/DroneCAN node. Please refer to the RaccoonLab docs [CAN Power Connectors](https://docs.raccoonlab.co/guide/pmu/power/) page. diff --git a/docs/zh/flight_modes_fw/mission.md b/docs/zh/flight_modes_fw/mission.md index 991a4bb846..63425174ba 100644 --- a/docs/zh/flight_modes_fw/mission.md +++ b/docs/zh/flight_modes_fw/mission.md @@ -29,32 +29,32 @@ At high level all vehicle types behave in the same way when MISSION mode is enga 1. If no mission is stored, or if PX4 has finished executing all mission commands, or if the [mission is not feasible](#mission-feasibility-checks): - - If flying the vehicle will loiter. - - If landed the vehicle will "wait". + - If flying the vehicle will loiter. + - If landed the vehicle will "wait". 2. If a mission is stored and PX4 is flying it will execute the [mission/flight plan](../flying/missions.md) from the current step. - - A takeoff mission item will be treated as a normal waypoint. + - A takeoff mission item will be treated as a normal waypoint. 3. If a mission is stored and the vehicle is landed it will only takeoff if the active waypoint is a `Takeoff`. - If configured for catapult launch, the vehicle must also be launched (see [FW Takeoff/Landing in Mission](#mission-takeoff)). + If configured for catapult launch, the vehicle must also be launched (see [FW Takeoff/Landing in Mission](#mission-takeoff)). 4. If no mission is stored, or if PX4 has finished executing all mission commands: - - If flying the vehicle will loiter. - - If landed the vehicle will "wait". + - If flying the vehicle will loiter. + - If landed the vehicle will "wait". 5. You can manually change the current mission command by selecting it in _QGroundControl_. - ::: info - If you have a _Jump to item_ command in the mission, moving to another item will **not** reset the loop counter. - One implication is that if you change the current mission command to 1 this will not "fully restart" the mission. + ::: info + If you have a _Jump to item_ command in the mission, moving to another item will **not** reset the loop counter. + One implication is that if you change the current mission command to 1 this will not "fully restart" the mission. ::: 6. The mission will only reset when the vehicle is disarmed or when a new mission is uploaded. - :::tip - To automatically disarm the vehicle after it lands, in _QGroundControl_ go to [Vehicle Setup > Safety](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/safety.html), navigate to _Land Mode Settings_ and check the box labeled _Disarm after_. - Enter the time to wait after landing before disarming the vehicle. + :::tip + To automatically disarm the vehicle after it lands, in _QGroundControl_ go to [Vehicle Setup > Safety](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/safety.html), navigate to _Land Mode Settings_ and check the box labeled _Disarm after_. + Enter the time to wait after landing before disarming the vehicle. ::: @@ -261,7 +261,7 @@ This pattern results in the following landing sequence: 1. **Fly to landing location**: The aircraft flies at its current altitude towards the loiter waypoint. 2. **Descending orbit to approach altitude**: On reaching the loiter radius of the waypoint, the vehicle performs a descending orbit until it reaches the "approach altitude" (the altitude of the loiter waypoint). - The vehicle continues to orbit at this altitude until it has a tanjential path towards the land waypoint, at which point the landing approach is initiated. + The vehicle continues to orbit at this altitude until it has a tanjential path towards the land waypoint, at which point the landing approach is initiated. 3. **Landing approach**: The aircraft follows the landing approach slope towards the land waypoint until the flare altitude is reached. 4. **Flare**: The vehicle flares until it touches down. diff --git a/docs/zh/flight_modes_fw/takeoff.md b/docs/zh/flight_modes_fw/takeoff.md index 010e4793ff..593c1f61e0 100644 --- a/docs/zh/flight_modes_fw/takeoff.md +++ b/docs/zh/flight_modes_fw/takeoff.md @@ -93,7 +93,7 @@ To launch in this mode: 1. Arm the vehicle 2. Put the vehicle into _Takeoff mode_ 3. Launch/throw the vehicle (firmly) directly into the wind. - You can also shake the vehicle first, wait till the motor spins up and then throw it + You can also shake the vehicle first, wait till the motor spins up and then throw it ### Parameters (Launch Detector) diff --git a/docs/zh/flight_modes_mc/follow_me.md b/docs/zh/flight_modes_mc/follow_me.md index 3e8b4ecab5..a356ffd919 100644 --- a/docs/zh/flight_modes_mc/follow_me.md +++ b/docs/zh/flight_modes_mc/follow_me.md @@ -151,19 +151,19 @@ The follow-me behavior can be configured using the following parameters: 1. Set the [follow distance](#FLW_TGT_DST) to more than 12 meters (8 meters is a "recommended minimum"). - There is an inherent position bias (3 ~ 5 meters) between the target and the drone's GPS sensor, which makes the drone follow a 'ghost target' somewhere near the actual target. This is more obvious when the follow distance is very small. We recommend that the follow distance is set to be large enough such that the GPS bias is not significant. - This is more obvious when the follow distance is very small. - We recommend that the follow distance is set to be large enough such that the GPS bias is not significant. + There is an inherent position bias (3 ~ 5 meters) between the target and the drone's GPS sensor, which makes the drone follow a 'ghost target' somewhere near the actual target. This is more obvious when the follow distance is very small. We recommend that the follow distance is set to be large enough such that the GPS bias is not significant. + This is more obvious when the follow distance is very small. + We recommend that the follow distance is set to be large enough such that the GPS bias is not significant. 2. The speed at which you can change the follow angle depends on the [maximum tangential velocity](#FLW_TGT_MAX_VEL) setting. - Experimentation shows that values between `5 m/s` are `10 m/s` are usually suitable. + Experimentation shows that values between `5 m/s` are `10 m/s` are usually suitable. 3. Using the RC Adjustment for height, distance and angle, you can get some creative camera shots. - + - This video demonstrates a Google-Earth view perspective, by adjusting the height to around 50 meters (high), distance to 1 meter (close). Which allows a perspective as shot from a satellite. + This video demonstrates a Google-Earth view perspective, by adjusting the height to around 50 meters (high), distance to 1 meter (close). Which allows a perspective as shot from a satellite. ## 已知的问题 diff --git a/docs/zh/flight_modes_mc/mission.md b/docs/zh/flight_modes_mc/mission.md index 5f6088aded..77cd340405 100644 --- a/docs/zh/flight_modes_mc/mission.md +++ b/docs/zh/flight_modes_mc/mission.md @@ -31,33 +31,33 @@ At high level all vehicle types behave in the same way when MISSION mode is enga 1. If no mission is stored, or if PX4 has finished executing all mission commands, or if the [mission is not feasible](#mission-feasibility-checks): - - If flying the vehicle will hold. - - If landed the vehicle will "wait". + - If flying the vehicle will hold. + - If landed the vehicle will "wait". 2. If a mission is stored and PX4 is flying it will execute the [mission/flight plan](../flying/missions.md) from the current step. - - A `TAKEOFF` item is treated as a normal waypoint. + - A `TAKEOFF` item is treated as a normal waypoint. 3. If a mission is stored and PX4 is landed: - - PX4 will execute the [mission/flight plan](../flying/missions.md). - - If the mission does not have a `TAKEOFF` item then PX4 will fly the vehicle to the minimum altitude before executing the remainder of the flight plan from the current step. + - PX4 will execute the [mission/flight plan](../flying/missions.md). + - If the mission does not have a `TAKEOFF` item then PX4 will fly the vehicle to the minimum altitude before executing the remainder of the flight plan from the current step. 4. If no mission is stored, or if PX4 has finished executing all mission commands: - - If flying the vehicle will hold. - - If landed the vehicle will "wait". + - If flying the vehicle will hold. + - If landed the vehicle will "wait". 5. You can manually change the current mission command by selecting it in _QGroundControl_. - ::: info - If you have a _Jump to item_ command in the mission, moving to another item will **not** reset the loop counter. - One implication is that if you change the current mission command to 1 this will not "fully restart" the mission. + ::: info + If you have a _Jump to item_ command in the mission, moving to another item will **not** reset the loop counter. + One implication is that if you change the current mission command to 1 this will not "fully restart" the mission. ::: 6. The mission will only reset when the vehicle is disarmed or when a new mission is uploaded. - :::tip - To automatically disarm the vehicle after it lands, in _QGroundControl_ go to [Vehicle Setup > Safety](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/safety.html), navigate to _Land Mode Settings_ and check the box labeled _Disarm after_. - Enter the time to wait after landing before disarming the vehicle. + :::tip + To automatically disarm the vehicle after it lands, in _QGroundControl_ go to [Vehicle Setup > Safety](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/safety.html), navigate to _Land Mode Settings_ and check the box labeled _Disarm after_. + Enter the time to wait after landing before disarming the vehicle. ::: diff --git a/docs/zh/flight_modes_mc/throw_launch.md b/docs/zh/flight_modes_mc/throw_launch.md index 68454dc735..8bfa6c55f3 100644 --- a/docs/zh/flight_modes_mc/throw_launch.md +++ b/docs/zh/flight_modes_mc/throw_launch.md @@ -43,16 +43,16 @@ Also ensure that the propellers do not spin on arming after enabling the feature In addition: 1. Wear safety equipment. - Eye protection and work gloves are recommended. + Eye protection and work gloves are recommended. 2. Have an easily accessible and tested [kill switch](../config/safety.md#kill-switch). - Remind the operator to be attentive and use the kill switch if needed. - Pilots tend to forget that vehicles are replaceable, but they are not! + Remind the operator to be attentive and use the kill switch if needed. + Pilots tend to forget that vehicles are replaceable, but they are not! 3. Test as much as possible without propellers. - Keep the tools for removing propellers nearby/readily accessible. + Keep the tools for removing propellers nearby/readily accessible. 4. Test this feature with at least two people — one handling the aircraft, the other one the remote control. 5. Keep in mind that after the throw, the exact behavior of the aircraft might be hard to predict as it depends heavily on the way it is thrown. - Sometimes it will stay perfectly in place, but sometimes (e.g., due to extensive roll), it might drift to one side while stabilizing. - Keep a safe distance! + Sometimes it will stay perfectly in place, but sometimes (e.g., due to extensive roll), it might drift to one side while stabilizing. + Keep a safe distance! On first flight of a new vehicle we recommend performing a [Throw Launch test without propellers](#throw-launch-pretest) (see below). @@ -65,13 +65,13 @@ The steps for this test are: 1. Dismount the propellers. 2. Set [COM_THROW_EN](../advanced_config/parameter_reference.md#COM_THROW_EN) to `Enabled`. 3. Arm the aircraft. - The engines should not spin, but the vehicle should be armed and keep playing the arming tune. + The engines should not spin, but the vehicle should be armed and keep playing the arming tune. 4. Throw the aircraft about 2m into the air. - If the aircraft is not thrown high enough, the motors will not turn on. + If the aircraft is not thrown high enough, the motors will not turn on. 5. The engines should start just after crossing the apex. 6. Engage the kill switch (ideally a second person operating the RC should do this). 7. Catch the drone. - Remember to use safety gloves! + Remember to use safety gloves! ## Throw Launch @@ -79,12 +79,12 @@ The steps for a throw launch are: 1. Set [COM_THROW_EN](../advanced_config/parameter_reference.md#COM_THROW_EN) to `Enabled`. 2. Arm the aircraft. - The propellers should not spin, but the vehicle should be armed and keep playing the arming tune. + The propellers should not spin, but the vehicle should be armed and keep playing the arming tune. 3. Throw the aircraft away from you, forward and up (about 2m away and 2m up is recommended). - - The vehicle must reach the speed of [COM_THROW_SPEED](../advanced_config/parameter_reference.md#COM_THROW_SPEED) to detect launch, which by default is set to 5 m/s. - If this speed is not achieved, the motors will not start and the aircraft will fall to the ground. - - Try to avoid excessive rotation during the throw, as this might cause the drone to fail or behave unpredictably. - The exact meaning of "excessive rotation" depends on the platform: for instance, [PX4Vision](../complete_vehicles_mc/px4_vision_kit.md) used for the testing, still managed to recover after 2-3 full rotations. + - The vehicle must reach the speed of [COM_THROW_SPEED](../advanced_config/parameter_reference.md#COM_THROW_SPEED) to detect launch, which by default is set to 5 m/s. + If this speed is not achieved, the motors will not start and the aircraft will fall to the ground. + - Try to avoid excessive rotation during the throw, as this might cause the drone to fail or behave unpredictably. + The exact meaning of "excessive rotation" depends on the platform: for instance, [PX4Vision](../complete_vehicles_mc/px4_vision_kit.md) used for the testing, still managed to recover after 2-3 full rotations. 4. After a downward velocity is detected (the vehicle reaches its apex and starts falling down), the motors should turn on and the vehicle will start flying in the current mode. ## 参数 diff --git a/docs/zh/flying/geofence.md b/docs/zh/flying/geofence.md index 14f87a4a75..28f29608ce 100644 --- a/docs/zh/flying/geofence.md +++ b/docs/zh/flying/geofence.md @@ -43,7 +43,7 @@ Geofence planning is fully documented in [Plan View > GeoFence](https://docs.qgr - 围栏中心的圆点可以用来调整围栏的位置。 - 边界上的圆点可以用来调整半径。 - 角(顶点)上的圆点可以用来改变多边形的形状。 - 点击线段中间可以在两个顶点中添加新的顶点。 + 点击线段中间可以在两个顶点中添加新的顶点。 5. Use the _Geofence Editor_ to set a fence as an inclusion or exclusion, and to select a fence to edit (**Edit** radio button) or Delete (**Del** button). 6. 可添加任意数量的围栏 7. Once finished, click on the **Upload** button (top right) to send the fence (along with rally points and mission) to the vehicle. diff --git a/docs/zh/flying/package_delivery_mission.md b/docs/zh/flying/package_delivery_mission.md index 7579495f9e..a04437f19f 100644 --- a/docs/zh/flying/package_delivery_mission.md +++ b/docs/zh/flying/package_delivery_mission.md @@ -37,9 +37,9 @@ To create a package delivery mission (with a Gripper): - To drop the package while flying set an appropriate altitude for the waypoint (and ensure the waypoint is at a safe location to drop the package). - If you'd like to land the vehicle to make the delivery you will need to change the `Waypoint` to a `Land` mission item. - Do this by selecting the mission item heading, then selecting `Land` in the popup dialog. + Do this by selecting the mission item heading, then selecting `Land` in the popup dialog. - ![Waypoint to Land mission item](../../assets/flying/package_delivery_land_waypoint.png) + ![Waypoint to Land mission item](../../assets/flying/package_delivery_land_waypoint.png) 3. Add a waypoint on the map (anywhere) for the gripper release. To change this to a `Gripper Mechanism` select the "Waypoint" heading, and in the popup changing the group to "Advanced", then selecting `Gripper Mechanism`. diff --git a/docs/zh/frames_multicopter/dji_f450_cuav_5nano.md b/docs/zh/frames_multicopter/dji_f450_cuav_5nano.md index 43f4d0e036..d0310b1cb2 100644 --- a/docs/zh/frames_multicopter/dji_f450_cuav_5nano.md +++ b/docs/zh/frames_multicopter/dji_f450_cuav_5nano.md @@ -106,52 +106,52 @@ Estimated time to assemble is approximately 90 minutes (about 45 minutes for the 1. Attach the 4 arms to the bottom plate using the provided screws. - ![Arms to bottom plate](../../assets/airframes/multicopter/dji_f450_cuav_5nano/1_attach_arms_bottom_plate.jpg) + ![Arms to bottom plate](../../assets/airframes/multicopter/dji_f450_cuav_5nano/1_attach_arms_bottom_plate.jpg) 2. Solder ESC (Electronic Speed Controller) to the board, positive (red) and negative (black). - ![Solder ESCs](../../assets/airframes/multicopter/dji_f450_cuav_5nano/2_solder_esc.jpg) + ![Solder ESCs](../../assets/airframes/multicopter/dji_f450_cuav_5nano/2_solder_esc.jpg) 3. Solder the Power Module, positive (red) and negative (black). - ![Solder power module](../../assets/airframes/multicopter/dji_f450_cuav_5nano/3_solder_power_module.jpg) + ![Solder power module](../../assets/airframes/multicopter/dji_f450_cuav_5nano/3_solder_power_module.jpg) 4. Plug in the motors to the ESCs according to their positions. - ![Plug in motors](../../assets/airframes/multicopter/dji_f450_cuav_5nano/4_plug_in_motors.jpg) + ![Plug in motors](../../assets/airframes/multicopter/dji_f450_cuav_5nano/4_plug_in_motors.jpg) 5. Attach the motors to the corresponding arms. - ![Attach motors to arms (white)](../../assets/airframes/multicopter/dji_f450_cuav_5nano/5a_attach_motors_to_arms.jpg) - ![Attach motors to arms (red)](../../assets/airframes/multicopter/dji_f450_cuav_5nano/5b_attach_motors_to_arms.jpg) + ![Attach motors to arms (white)](../../assets/airframes/multicopter/dji_f450_cuav_5nano/5a_attach_motors_to_arms.jpg) + ![Attach motors to arms (red)](../../assets/airframes/multicopter/dji_f450_cuav_5nano/5b_attach_motors_to_arms.jpg) 6. Add the top board (screw into the top of the legs). - ![Add top board](../../assets/airframes/multicopter/dji_f450_cuav_5nano/6_add_top_board.jpg) + ![Add top board](../../assets/airframes/multicopter/dji_f450_cuav_5nano/6_add_top_board.jpg) 7. Add damping foam to the _CUAV V5 nano_ flight controller. - ![Damping foam](../../assets/airframes/multicopter/dji_f450_cuav_5nano/7a_attach_cuav5nano.jpg) - ![Damping foam](../../assets/airframes/multicopter/dji_f450_cuav_5nano/7b_attach_cuav5nano.jpg) + ![Damping foam](../../assets/airframes/multicopter/dji_f450_cuav_5nano/7a_attach_cuav5nano.jpg) + ![Damping foam](../../assets/airframes/multicopter/dji_f450_cuav_5nano/7b_attach_cuav5nano.jpg) 8. Attach the FrSky receiver to the bottom board with double-sided tape. - ![Attach FrSky receiver with double-sided tape](../../assets/airframes/multicopter/dji_f450_cuav_5nano/8_attach_frsky.jpg) + ![Attach FrSky receiver with double-sided tape](../../assets/airframes/multicopter/dji_f450_cuav_5nano/8_attach_frsky.jpg) 9. Attach the telemetry module to the vehicle’s bottom board using double-sided tape. - ![Attach telemetry radio](../../assets/airframes/multicopter/dji_f450_cuav_5nano/9a_telemtry_radio.jpg) - ![Attach telemetry radio](../../assets/airframes/multicopter/dji_f450_cuav_5nano/9b_telemtry_radio.jpg) + ![Attach telemetry radio](../../assets/airframes/multicopter/dji_f450_cuav_5nano/9a_telemtry_radio.jpg) + ![Attach telemetry radio](../../assets/airframes/multicopter/dji_f450_cuav_5nano/9b_telemtry_radio.jpg) 10. Put the aluminium standoffs on the button plate and attach GPS. - ![Aluminium standoffs](../../assets/airframes/multicopter/dji_f450_cuav_5nano/10_aluminium_standoffs.jpg) + ![Aluminium standoffs](../../assets/airframes/multicopter/dji_f450_cuav_5nano/10_aluminium_standoffs.jpg) 11. Plug in Telemetry (`TELEM1`), GPS module (`GPS/SAFETY`), RC receiver (`RC`), all 4 ESC’s (`M1-M4`), and the power module (`Power1`) into the flight controller. - ![Attach peripherals to flight controller](../../assets/airframes/multicopter/dji_f450_cuav_5nano/12_fc_attach_periperhals.jpg) + ![Attach peripherals to flight controller](../../assets/airframes/multicopter/dji_f450_cuav_5nano/12_fc_attach_periperhals.jpg) - ::: info - The motor order is defined in the [Airframe Reference > Quadrotor x](../airframes/airframe_reference.md#quadrotor-x) + ::: info + The motor order is defined in the [Airframe Reference > Quadrotor x](../airframes/airframe_reference.md#quadrotor-x) ::: diff --git a/docs/zh/frames_multicopter/dji_f450_cuav_5plus.md b/docs/zh/frames_multicopter/dji_f450_cuav_5plus.md index 4c42eaa365..8fbd134973 100644 --- a/docs/zh/frames_multicopter/dji_f450_cuav_5plus.md +++ b/docs/zh/frames_multicopter/dji_f450_cuav_5plus.md @@ -108,53 +108,53 @@ Estimated time to assemble is approximately 90 minutes (about 45 minutes for the 1. Attach the 4 arms to the bottom plate using the provided screws. - ![Arms to bottom plate](../../assets/airframes/multicopter/dji_f450_cuav_5plus/1_attach_arms_bottom_plate.jpg) + ![Arms to bottom plate](../../assets/airframes/multicopter/dji_f450_cuav_5plus/1_attach_arms_bottom_plate.jpg) 2. Solder ESC (Electronic Speed Controller) to the board, positive (red) and negative (black). - ![Solder ESCs](../../assets/airframes/multicopter/dji_f450_cuav_5plus/2_solder_esc.jpg) + ![Solder ESCs](../../assets/airframes/multicopter/dji_f450_cuav_5plus/2_solder_esc.jpg) 3. Solder the Power Module, positive (red) and negative (black). - ![Solder power module](../../assets/airframes/multicopter/dji_f450_cuav_5plus/3_solder_power_module.jpg) + ![Solder power module](../../assets/airframes/multicopter/dji_f450_cuav_5plus/3_solder_power_module.jpg) 4. Plug in the motors to the ESCs according to their positions. - ![Plug in motors](../../assets/airframes/multicopter/dji_f450_cuav_5plus/4_plug_in_motors.jpg) + ![Plug in motors](../../assets/airframes/multicopter/dji_f450_cuav_5plus/4_plug_in_motors.jpg) 5. Attach the motors to the corresponding arms. - ![Attach motors to arms (white)](../../assets/airframes/multicopter/dji_f450_cuav_5plus/5a_attach_motors_to_arms.jpg) - ![Attach motors to arms (red)](../../assets/airframes/multicopter/dji_f450_cuav_5plus/5b_attach_motors_to_arms.jpg) + ![Attach motors to arms (white)](../../assets/airframes/multicopter/dji_f450_cuav_5plus/5a_attach_motors_to_arms.jpg) + ![Attach motors to arms (red)](../../assets/airframes/multicopter/dji_f450_cuav_5plus/5b_attach_motors_to_arms.jpg) 6. Add the top board (screw into the top of the legs). - ![Add top board](../../assets/airframes/multicopter/dji_f450_cuav_5plus/6_add_top_board.jpg) + ![Add top board](../../assets/airframes/multicopter/dji_f450_cuav_5plus/6_add_top_board.jpg) 7. Add double-sided tape (3M) to the CUAV V5+ flight controller (it has internal vibration damping, so no need to use foam). - ![Tape CUAV v5+](../../assets/airframes/multicopter/dji_f450_cuav_5plus/7_attach_cuav5plus.jpg) + ![Tape CUAV v5+](../../assets/airframes/multicopter/dji_f450_cuav_5plus/7_attach_cuav5plus.jpg) 8. Attach the FrSky receiver to the bottom board with double-sided tape. - ![Attach FrSky receiver with double-sided tape](../../assets/airframes/multicopter/dji_f450_cuav_5plus/8_attach_frsky.jpg) + ![Attach FrSky receiver with double-sided tape](../../assets/airframes/multicopter/dji_f450_cuav_5plus/8_attach_frsky.jpg) 9. Attach the telemetry module to the vehicle’s bottom board using double-sided tape. - ![Attach telemetry radio](../../assets/airframes/multicopter/dji_f450_cuav_5plus/9a_telemtry_radio.jpg) - ![Attach telemetry radio](../../assets/airframes/multicopter/dji_f450_cuav_5plus/9b_telemtry_radio.jpg) + ![Attach telemetry radio](../../assets/airframes/multicopter/dji_f450_cuav_5plus/9a_telemtry_radio.jpg) + ![Attach telemetry radio](../../assets/airframes/multicopter/dji_f450_cuav_5plus/9b_telemtry_radio.jpg) 10. Put the aluminium standoffs on the button plate. 11. Plug in Telemetry (`TELEM1`) and GPS module (`GPS/SAFETY`) to the flight controller. - ![Attach GPS](../../assets/airframes/multicopter/dji_f450_cuav_5plus/11a_gps.jpg) - ![Attach GPS](../../assets/airframes/multicopter/dji_f450_cuav_5plus/11b_gps.jpg) + ![Attach GPS](../../assets/airframes/multicopter/dji_f450_cuav_5plus/11a_gps.jpg) + ![Attach GPS](../../assets/airframes/multicopter/dji_f450_cuav_5plus/11b_gps.jpg) 12. Plug in the RC receiver (`RC`), all 4 ESC’s (`M1-M4`), and the power module (`Power1`) into the flight controller. - ![Attach peripherals to flight controller](../../assets/airframes/multicopter/dji_f450_cuav_5plus/12_fc_attach_periperhals.jpg) + ![Attach peripherals to flight controller](../../assets/airframes/multicopter/dji_f450_cuav_5plus/12_fc_attach_periperhals.jpg) - ::: info - The motor order is defined in the [Airframe Reference > Quadrotor x](../airframes/airframe_reference.md#quadrotor-x) + ::: info + The motor order is defined in the [Airframe Reference > Quadrotor x](../airframes/airframe_reference.md#quadrotor-x) ::: diff --git a/docs/zh/frames_multicopter/holybro_qav250_pixhawk4_mini.md b/docs/zh/frames_multicopter/holybro_qav250_pixhawk4_mini.md index d229c04192..b211ecf724 100644 --- a/docs/zh/frames_multicopter/holybro_qav250_pixhawk4_mini.md +++ b/docs/zh/frames_multicopter/holybro_qav250_pixhawk4_mini.md @@ -103,78 +103,78 @@ The following tools are used in this assembly: 1. Attach arms to the button plate with the 15mm screws as shown: - ![QAV250 Add arms to button plate](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/1_button_plate_add_arms.jpg) + ![QAV250 Add arms to button plate](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/1_button_plate_add_arms.jpg) 2. Put the short plate over the arms - ![QAV250 Add short plate over arms](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/2_short_plate_over_arms.jpg) + ![QAV250 Add short plate over arms](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/2_short_plate_over_arms.jpg) 3. Put the nuts on the 15mm screws (shown next step) 4. Insert the plastic screws into the indicated holes (note that this part of the frame faces down when the vehicle is complete). - ![QAV250 Add nuts to 15mm screws and put plastic nuts in holes](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/3_nuts_screws_holes.jpg) + ![QAV250 Add nuts to 15mm screws and put plastic nuts in holes](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/3_nuts_screws_holes.jpg) 5. Add the plastic nuts to the screws (turn over, as shown) - ![QAV250 Plastic nuts onto screws](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/4_plastic_nuts_on_screws.jpg) + ![QAV250 Plastic nuts onto screws](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/4_plastic_nuts_on_screws.jpg) 6. Lower the power module over the plastic screws and then add the plastics standoffs - ![QAV250 Add power module and standoffs](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/5_power_module_on_screws.jpg) + ![QAV250 Add power module and standoffs](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/5_power_module_on_screws.jpg) 7. Put the flight controller plate on the standoffs (over the power module) - ![QAV250 Add flight controller plate](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/6_flight_controller_plate.jpg) + ![QAV250 Add flight controller plate](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/6_flight_controller_plate.jpg) 8. Attach the motors. The motors have an arrow indicating the direction of rotation. - ![QAV250 Add motors](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/7_motors.jpg) + ![QAV250 Add motors](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/7_motors.jpg) 9. Use double sided tape from kit to attach the _Pixhawk 4 Mini_ to the flight controller plate. - ![QAV250 Add doublesided tape](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/8_double_sided_tape_controller.jpg) + ![QAV250 Add doublesided tape](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/8_double_sided_tape_controller.jpg) 10. Connect the power module's "power" cable to _Pixhawk 4 mini_. - ![QAV250 Power Pixhawk](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/9_power_module_power_pixhawk.jpg) + ![QAV250 Power Pixhawk](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/9_power_module_power_pixhawk.jpg) 11. Attach the aluminium standoffs to the button plate - ![QAV250 Aluminium standoffs](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/10_aluminium_standoffs.jpg) + ![QAV250 Aluminium standoffs](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/10_aluminium_standoffs.jpg) 12. Connect the Esc’s with the motors and hold. In this image shown the order of the motors and direction of the rotation. - ![QAV250 Connect ESCs](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/11_escs.jpg) + ![QAV250 Connect ESCs](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/11_escs.jpg) - Connect the motors on the ESC’s, make sure the motors turns to the correct side, if the motor turns of the opposite side change the cable A to the pad C and C to the pad A of the ESC. + Connect the motors on the ESC’s, make sure the motors turns to the correct side, if the motor turns of the opposite side change the cable A to the pad C and C to the pad A of the ESC. - :::warning - Test motor directions with propellers removed. + :::warning + Test motor directions with propellers removed. ::: - ![QAV250 Connect ESCs to Power](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/11b_escs.jpg) + ![QAV250 Connect ESCs to Power](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/11b_escs.jpg) 13. Connect the signal ESC cables to the PWM outputs of the Pixhawk in the correct order (see previous image) - ![QAV250 Connect ESCs to Pixhawk PWM](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/12_escs_pixhawk.jpg) + ![QAV250 Connect ESCs to Pixhawk PWM](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/12_escs_pixhawk.jpg) 14. Connect the receiver. - - If using a PPM receiver connect to the PPM port. + - If using a PPM receiver connect to the PPM port. - ![QAV250 Connect Receiver PPM](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/13_rc_receiver_ppm.jpg) + ![QAV250 Connect Receiver PPM](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/13_rc_receiver_ppm.jpg) - - If using the SBUS receiver connect to the RC IN port + - If using the SBUS receiver connect to the RC IN port - ![QAV250 Connect Receiver SBUS](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/13_rc_receiver_sbus.jpg) + ![QAV250 Connect Receiver SBUS](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/13_rc_receiver_sbus.jpg) 15. Connect the telemetry module. Paste the module with double tape and connect on the port of the telemetry. - ![QAV250 Telemetry module](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/14_telemetry.jpg) + ![QAV250 Telemetry module](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/14_telemetry.jpg) 16. Connect the GPS module - ![QAV250 Connect GPS](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/15a_connect_gps.jpg) + ![QAV250 Connect GPS](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/15a_connect_gps.jpg) - Attach the module on the top plate (using provided 3M tape, or paste). Then put the top plate on the standoffs as shown + Attach the module on the top plate (using provided 3M tape, or paste). Then put the top plate on the standoffs as shown - ![QAV250 Connect GPS](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/15b_attach_gps.jpg) + ![QAV250 Connect GPS](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/15b_attach_gps.jpg) 17. The last "mandatory" assembly step is to add the velcro to hold the battery - ![QAV250 Velcro battery strap](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/16_velcro_strap.jpg) + ![QAV250 Velcro battery strap](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/16_velcro_strap.jpg) The "basic" frame build is now complete (though if you need them, you can find more information about connecting components in the [Pixhawk 4 Wiring Quickstart](../assembly/quick_start_pixhawk4.md)). @@ -189,17 +189,17 @@ The "Complete" version of the kit additionally comes with an FPV system, which i The steps to install the kit are: 1. Install the camera bracket on the frame - ![Camera Connection](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_camera_bracket.jpg) + ![Camera Connection](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_camera_bracket.jpg) 2. Install the camera on the bracket - ![Camera on Bracket](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_camera_on_bracket.jpg) + ![Camera on Bracket](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_camera_on_bracket.jpg) 3. The power module on the complete kit comes with wiring ready to connect the Video Transmitter and Camera: - ![Connecting FPV](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_connection_board.jpg) - - Attach the camera connector - ![Camera Connection](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_camera_connection.jpg) - The wires are: blue=voltage sensor, yellow=video out, black=ground, red=+voltage. - - Connect the Video Transmitter (VTX) connector - ![Video Transmitter Connection](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_video_transmitter_connection.jpg) - The wires are: yellow=video out, black=ground, red=+voltage. + ![Connecting FPV](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_connection_board.jpg) + - Attach the camera connector + ![Camera Connection](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_camera_connection.jpg) + The wires are: blue=voltage sensor, yellow=video out, black=ground, red=+voltage. + - Connect the Video Transmitter (VTX) connector + ![Video Transmitter Connection](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_video_transmitter_connection.jpg) + The wires are: yellow=video out, black=ground, red=+voltage. 4. Secure the Video Transmitter and OSD board to the frame using tape. :::info diff --git a/docs/zh/frames_multicopter/holybro_s500_v2_pixhawk4.md b/docs/zh/frames_multicopter/holybro_s500_v2_pixhawk4.md index ab696b1c26..57b595740f 100644 --- a/docs/zh/frames_multicopter/holybro_s500_v2_pixhawk4.md +++ b/docs/zh/frames_multicopter/holybro_s500_v2_pixhawk4.md @@ -115,11 +115,11 @@ The following tools are used in this assembly: Estimate time to assemble is 90 minutes, about 45 minutes for frame assembly and 45 minutes installing and configuring the autopilot in QGroundControl. 1. Assembling the Landing Gear. - We are going to start by assembling the landing gear to the vertical pole. Unscrew the landing gear screws and insert the vertical pole as shown below. + We are going to start by assembling the landing gear to the vertical pole. Unscrew the landing gear screws and insert the vertical pole as shown below. - ![Figure 1](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig1.jpg) + ![Figure 1](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig1.jpg) - ![Figure 2](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig2.jpg) + ![Figure 2](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig2.jpg) 2. Assemble the Power Management Board to the landing gear. Screw the landing gear with a vertical pole to the Fully assembled Power Management Board. @@ -132,132 +132,132 @@ Connect with the M3X8 screws, a total of 8 pieces, 4 on each side. ![Figure 4](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig4.jpg) 1. Assemble the arms to the Power Management Board. - Attach the arm to the Power Management Board. + Attach the arm to the Power Management Board. - ![Figure 6](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig7.jpg) + ![Figure 6](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig7.jpg) - ![Figure 7](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig8.jpg) + ![Figure 7](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig8.jpg) - Use M2 5X6 screws a total of 2 in each arm. - Insert the screws from the bottom of the plate. + Use M2 5X6 screws a total of 2 in each arm. + Insert the screws from the bottom of the plate. - ![Figure 8](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig9.jpg) + ![Figure 8](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig9.jpg) - Make sure the ESC cables run through the middle of the arm. + Make sure the ESC cables run through the middle of the arm. - ![Figure 9](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig91.jpg) + ![Figure 9](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig91.jpg) 2. Assemble the 8_3 2.54mm pitch Horizontal Pin to the 10 to 10 pin cable (PWM) to the Power Management Board. - Connect the 10 to 10 pin cable (PWM) to the 8_3 2.54mm pitch Horizontal Pin. + Connect the 10 to 10 pin cable (PWM) to the 8_3 2.54mm pitch Horizontal Pin. - ![Figure 10](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig10.jpg) + ![Figure 10](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig10.jpg) - Cut a piece of 3M Tape and attach to the bottom of the Horizontal Pin: + Cut a piece of 3M Tape and attach to the bottom of the Horizontal Pin: - ![Figure 11](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig11.jpg) + ![Figure 11](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig11.jpg) - Stick the Horizontal Pin to the Power Management Board: + Stick the Horizontal Pin to the Power Management Board: - ![Figure 12](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig12.jpg) + ![Figure 12](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig12.jpg) - ![Figure 13](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig13.jpg) + ![Figure 13](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig13.jpg) 3. Assemble the motors to the arms. For this, we will need the 16 screws M3X7, 4 motors, and the 4 arms. - Mount the motors in each arm put the screw through the bottom of the arm: + Mount the motors in each arm put the screw through the bottom of the arm: - ![Figure 14](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig14.jpg) + ![Figure 14](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig14.jpg) - ![Figure 15](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig15.jpg) + ![Figure 15](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig15.jpg) - After the 4 motors are mounted on the arm grab the cables(red, blue, black) and put them through the arm thread. - The 3 cables that are color-coded go connected to the ESC. + After the 4 motors are mounted on the arm grab the cables(red, blue, black) and put them through the arm thread. + The 3 cables that are color-coded go connected to the ESC. - ![Figure 16](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig16.jpg) + ![Figure 16](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig16.jpg) - ![Figure 17](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig17.jpg) + ![Figure 17](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig17.jpg) 4. Mounting the GPS on the frame. - For this, we will need the Pixhawk 4 GPS and the mounting plate. + For this, we will need the Pixhawk 4 GPS and the mounting plate. - ![GPS Parts](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_gpskit.png) + ![GPS Parts](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_gpskit.png) - Mount the GPS mast to the back of the Board, use the 4 screws: + Mount the GPS mast to the back of the Board, use the 4 screws: - ![Figure 18](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig18.jpg) + ![Figure 18](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig18.jpg) - ![Figure 19](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig19.jpg) + ![Figure 19](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig19.jpg) - Use the tape and stick the GPS to the top of the GPS mast: + Use the tape and stick the GPS to the top of the GPS mast: - ![Figure 20](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig20.jpg) + ![Figure 20](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig20.jpg) 5. Paste the FrSky to the Board. Paste FrSky with double-sided tape (3M) to the bottom board. - Attach the FrSky to the frame: + Attach the FrSky to the frame: - ![Figure 21](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig21.jpg) + ![Figure 21](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig21.jpg) - ![Figure 22](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig22.jpg) + ![Figure 22](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig22.jpg) 6. Attach the Telemetry to the frame. - The next step is to take the Holybro telemetry radio and attach it onto the frame, use 3M tape. + The next step is to take the Holybro telemetry radio and attach it onto the frame, use 3M tape. - ![Figure 23](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig23.jpg) + ![Figure 23](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig23.jpg) - ![Figure 24](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig24.jpg) + ![Figure 24](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig24.jpg) - This assembly attached it inside the frame facing outwards to the front of the vehicle. - A picture is shown below of the radio sitting inside the bottom of the frame. + This assembly attached it inside the frame facing outwards to the front of the vehicle. + A picture is shown below of the radio sitting inside the bottom of the frame. - ![Figure 25](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig25.jpg) + ![Figure 25](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig25.jpg) 7. Mounting the Pixhawk 4 to the plate. - Use double-sided tape to attach the Pixhawk 4 to the center plate: + Use double-sided tape to attach the Pixhawk 4 to the center plate: - ![Figure 26](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig26.jpg) + ![Figure 26](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig26.jpg) - ![Figure 27](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig27.jpg) + ![Figure 27](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig27.jpg) - ![Figure 28](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig28.jpg) + ![Figure 28](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig28.jpg) - The next step is to mount the Pixhawk 4 with the plate to the frame. - For this, we will need the M2 5X6 screws. - Align the plate to the frame and insert the screws. - Before you mount the plate we recommend putting tape on the Power Module (that way it's tight). + The next step is to mount the Pixhawk 4 with the plate to the frame. + For this, we will need the M2 5X6 screws. + Align the plate to the frame and insert the screws. + Before you mount the plate we recommend putting tape on the Power Module (that way it's tight). - ![Figure 29](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig29.jpg) + ![Figure 29](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig29.jpg) - ![Figure 30](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig30.jpg) + ![Figure 30](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig30.jpg) 8. Assembling the Battery Mount to the frame. - For this we will need the M2 5X6 screws and the battery mount: + For this we will need the M2 5X6 screws and the battery mount: - ![Figure 31](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig31.jpg) + ![Figure 31](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig31.jpg) - Insert the long rods to the small rings: + Insert the long rods to the small rings: - ![Figure 32](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig32.png) + ![Figure 32](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig32.png) - ![Figure 33](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig33.png) + ![Figure 33](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig33.png) - Attach that to the frame, make sure all four sides are aligned to insert the screws: + Attach that to the frame, make sure all four sides are aligned to insert the screws: - ![Figure 34](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig34.jpg) + ![Figure 34](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig34.jpg) - Assemble the small plate to the legs and screw on all four sides. + Assemble the small plate to the legs and screw on all four sides. - ![Figure 35](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig35.jpg) + ![Figure 35](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig35.jpg) - The final step is to attach the plate: + The final step is to attach the plate: - ![Figure 36](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig36.jpg) + ![Figure 36](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig36.jpg) 9. Pixhawk 4 wiring. The Pixhawk 4, which has several different wires and connections with it. - Included below is a picture of every wire needed with the Pixhawk and how it looks when connected. + Included below is a picture of every wire needed with the Pixhawk and how it looks when connected. 10. Plugin Telemetry and GPS module to the flight controller as seen in Figure 37; plug in the RC receiver, all 4 ESCs to the flight controller as well as the power module. - ![Figure 37](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig37.png) + ![Figure 37](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig37.png) Fully assembled, the kit looks as shown below: diff --git a/docs/zh/frames_multicopter/holybro_x500V2_pixhawk5x.md b/docs/zh/frames_multicopter/holybro_x500V2_pixhawk5x.md index 42ec97bd34..723a3bb23b 100644 --- a/docs/zh/frames_multicopter/holybro_x500V2_pixhawk5x.md +++ b/docs/zh/frames_multicopter/holybro_x500V2_pixhawk5x.md @@ -93,92 +93,92 @@ Tools are included to do the assembly, however you may need: Estimate time to assemble is 55 min (25 minutes for frame, 30 minutes for autopilot installation/configuration) 1. Start by assembling the payload & battery holder. - Push the rubbers into grippers (Do not use sharp items to push them in!). - Next, pass the holders through the holder bars with the battery holder bases as Figure 3. + Push the rubbers into grippers (Do not use sharp items to push them in!). + Next, pass the holders through the holder bars with the battery holder bases as Figure 3. - ![Landing Figure 1: Components](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/payload_holder_required_stuff.png) + ![Landing Figure 1: Components](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/payload_holder_required_stuff.png) - _Figure 2_: Payload holder components + _Figure 2_: Payload holder components - ![Landing Figure 2: Assembled](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/payload_holder_assembled.png) + ![Landing Figure 2: Assembled](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/payload_holder_assembled.png) - _Figure 3_: Payload holder assembled + _Figure 3_: Payload holder assembled 2. The next is to go for attaching the bottom plate to the payload holder. - You will need the parts as shown in Figure 4. - Then mount the base for power distribution board using nylon nuts as Figure 5. - Finally using 8 hex screws you can join the bottom plate to the payload holder (Figure 7) + You will need the parts as shown in Figure 4. + Then mount the base for power distribution board using nylon nuts as Figure 5. + Finally using 8 hex screws you can join the bottom plate to the payload holder (Figure 7) - ![Materials to attach bottom plate](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/topplate_holder_stuff.png) + ![Materials to attach bottom plate](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/topplate_holder_stuff.png) - _Figure 4_: Needed Materials + _Figure 4_: Needed Materials - ![PDB mountbase](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/powerboard-mountbase.png) + ![PDB mountbase](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/powerboard-mountbase.png) - _Figure 5_: PDB mount base + _Figure 5_: PDB mount base - ![PDB attachment](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/pdb_bottom_plate.png) + ![PDB attachment](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/pdb_bottom_plate.png) - _Figure 6_: Mounted pdb with nylon nuts + _Figure 6_: Mounted pdb with nylon nuts - ![Bottom plate Final](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/bottom_plate_holder_final.png) + ![Bottom plate Final](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/bottom_plate_holder_final.png) - _Figure 7_: Mounted Plate on payload holder + _Figure 7_: Mounted Plate on payload holder 3. Let's gather the stuff needed for mounting landing gear as Figure 8. - Use the hex screws to join landing gears to the bottom plate. - You also need to open three hex screws on each of the leg stands so you can push them into carbon fiber pipes. - Do not forget to tighten them back again. + Use the hex screws to join landing gears to the bottom plate. + You also need to open three hex screws on each of the leg stands so you can push them into carbon fiber pipes. + Do not forget to tighten them back again. - ![Attach Landing Gear Stuff](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/landing_gear_materials.png) + ![Attach Landing Gear Stuff](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/landing_gear_materials.png) - _Figure 8_: Required parts for landing gear attachment + _Figure 8_: Required parts for landing gear attachment - ![Lanfing great to bottom plate](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/attached_landing_gear.png) + ![Lanfing great to bottom plate](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/attached_landing_gear.png) - _Figure 9_: Landing gear attachment to the body + _Figure 9_: Landing gear attachment to the body 4. We will gather all the arms now to mount the top plate. - Please pay attention that the motor numbers on arms are a match with the ones mentioned on the top plate. - Fortunately, motors are mounted and ESCs have been connected in advance. - Start by passing through all the screws as you have the arms fixed in their own places (They have a guide as shown in Figure 11 to ensure they are in place) and tighten all nylon nuts a bit. - Then you can connect XT30 power connectors to the power board. - Please keep in mind that the signal wires have to be passed through the top plate such that we can connect them later to Pixhawk. + Please pay attention that the motor numbers on arms are a match with the ones mentioned on the top plate. + Fortunately, motors are mounted and ESCs have been connected in advance. + Start by passing through all the screws as you have the arms fixed in their own places (They have a guide as shown in Figure 11 to ensure they are in place) and tighten all nylon nuts a bit. + Then you can connect XT30 power connectors to the power board. + Please keep in mind that the signal wires have to be passed through the top plate such that we can connect them later to Pixhawk. - + - _Figure 10_: Connecting arms needed materials. + _Figure 10_: Connecting arms needed materials. - + - _Figure 11_: Guide for the arms mount + _Figure 11_: Guide for the arms mount 5. Tighten all 16 screws and nuts by using both hex wrench and nut driver. - ![Top plae mounted](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/finalized_top_plate.png) + ![Top plae mounted](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/finalized_top_plate.png) - _Figure 12_: Mounted top plate + _Figure 12_: Mounted top plate 6. Next you can mount your pixhawk on the top plate by using the stickers. - It is recommended to have the direction of your Pixhawk's arrow the same as the one mentioned on the top plate. + It is recommended to have the direction of your Pixhawk's arrow the same as the one mentioned on the top plate. - ![Flight controller mounting stickers](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/pixhawk5x_stickertapes.png) + ![Flight controller mounting stickers](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/pixhawk5x_stickertapes.png) - _Figure 13_: Sticker tapes on Pixhawk + _Figure 13_: Sticker tapes on Pixhawk 7. If you want to mount the GPS on the companion computer plate, you can now secure the GPS mount onto it using 4 screws and nuts. - + - _Figure 14_: Secure GPS mount onto companion plate + _Figure 14_: Secure GPS mount onto companion plate 8. Use the tape and stick the GPS to the top of the GPS mast and mount the GPS mast. - Make sure the arrow on the gps is pointing forward (Figure 15). + Make sure the arrow on the gps is pointing forward (Figure 15). - + - _Figure 15_: GPS and mast + _Figure 15_: GPS and mast 9. Finally, you can connect the Pixhawk interfaces such as telemetry radio to 'TELEM1' and motors signal cables accordingly. diff --git a/docs/zh/frames_multicopter/holybro_x500_pixhawk4.md b/docs/zh/frames_multicopter/holybro_x500_pixhawk4.md index c49543f094..babc343497 100644 --- a/docs/zh/frames_multicopter/holybro_x500_pixhawk4.md +++ b/docs/zh/frames_multicopter/holybro_x500_pixhawk4.md @@ -81,125 +81,125 @@ The following tools are used in this assembly: Estimate time to assemble is 3.75 hours (180 minutes for frame, 45 minutes for autopilot installation/configuration) 1. Start by assembling the landing gear. - Unscrew the landing gear screws and insert the vertical pole (figures 1 and 2). + Unscrew the landing gear screws and insert the vertical pole (figures 1 and 2). - ![Landing Figure 1: Components](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_step_1_fig1.jpg) + ![Landing Figure 1: Components](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_step_1_fig1.jpg) - _Figure 2_: Landing gear components + _Figure 2_: Landing gear components - ![Landing Figure 2: Assembled](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_step_1_fig2.jpg) + ![Landing Figure 2: Assembled](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_step_1_fig2.jpg) - _Figure 2_: Landing gear assembled + _Figure 2_: Landing gear assembled 2. Then put the 4 arms through the 4 motor bases shown in figure 3. - Make sure the rods protrude the base slightly and are consistent throughout all 4 arms, and be sure to have the motor wires facing outward. + Make sure the rods protrude the base slightly and are consistent throughout all 4 arms, and be sure to have the motor wires facing outward. - ![Attach arms to motor bases](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_step_2_fig3.png) + ![Attach arms to motor bases](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_step_2_fig3.png) - _Figure 3_: Attach arms to motor bases + _Figure 3_: Attach arms to motor bases 3. Insert 4 nylon screws and nylon standoffs and attach the power module PM07 to the bottom plate using 4 nylon nuts as shown in Figures 4. - ![Attach power module](../../assets/airframes/multicopter/x500_holybro_pixhawk4/power_module.jpg) + ![Attach power module](../../assets/airframes/multicopter/x500_holybro_pixhawk4/power_module.jpg) - _Figure 4_: Attach power module + _Figure 4_: Attach power module 4. Feed the 4 motor ESCs through each of the arms and connect the 3-wires end to the motors shown in Figure 5. - + - _Figure 5_: Connect motors + _Figure 5_: Connect motors 5. Connect the ESCs power wires onto the power module PM07, black->black and red->red, ESC PWM signal wires goes to "FMU-PWM-Out". - Make sure you connect the motor ESC PWM wires in the correct order. - Refer to Figure 7 for airframe motor number and connect to the corresponding number on the PM07 board. + Make sure you connect the motor ESC PWM wires in the correct order. + Refer to Figure 7 for airframe motor number and connect to the corresponding number on the PM07 board. - ![ESC power module and signal wiring](../../assets/airframes/multicopter/x500_holybro_pixhawk4/pm07_pwm.jpg) - _Figure 7_: ESC power module and signal wiring + ![ESC power module and signal wiring](../../assets/airframes/multicopter/x500_holybro_pixhawk4/pm07_pwm.jpg) + _Figure 7_: ESC power module and signal wiring - The color on top of the motor indicate the spin direction (figure 7-1), black tip is clockwise, and white tip is counter-clockwise. - Make sure the follow the px4 quadrotor x airframe reference for motor direction (figure 7-2). + The color on top of the motor indicate the spin direction (figure 7-1), black tip is clockwise, and white tip is counter-clockwise. + Make sure the follow the px4 quadrotor x airframe reference for motor direction (figure 7-2). - + - _Figure 7_: Motor order/direction diagram + _Figure 7_: Motor order/direction diagram - + - _Figure 7-1_: Motor direction + _Figure 7-1_: Motor direction 6. Connect the 10 pin cables to FMU-PWM-in, the 6 pin cables to the PWR1 on the PM07 power module. - ![Flight controller/Power module PWM and Power connections](../../assets/airframes/multicopter/x500_holybro_pixhawk4/pm07_cable.jpg) + ![Flight controller/Power module PWM and Power connections](../../assets/airframes/multicopter/x500_holybro_pixhawk4/pm07_cable.jpg) - _Figure 8_: Power module PWM and power wiring + _Figure 8_: Power module PWM and power wiring 7. If you want to mount the GPS on the top plate, you can now secure the GPS mount onto the top plate using 4 screws and nuts. - + - _Figure 9_: Secure GPS mount onto top plate + _Figure 9_: Secure GPS mount onto top plate 8. Feed the PM07 cables through the top plate. - Connect the top and bottom plate by using 4 U-shaped nylon straps, screws, and nuts on each side, ensure that the motor ESC cables are inside the U-shape nylon straps like Figure 10, keep the nut loose. + Connect the top and bottom plate by using 4 U-shaped nylon straps, screws, and nuts on each side, ensure that the motor ESC cables are inside the U-shape nylon straps like Figure 10, keep the nut loose. - + - _Figure 10-1_: Feed power module cables through top plate + _Figure 10-1_: Feed power module cables through top plate - + - _Figure 10-2_: Connecting top and bottom plate + _Figure 10-2_: Connecting top and bottom plate 9. Push the arm tubes a bit into the frame and make sure the amount of protrusion (red square from Figure 11) are consistent on all 4 arms. - Ensure all the motors are pointed directly upward, then tighten all the nuts and screws. + Ensure all the motors are pointed directly upward, then tighten all the nuts and screws. - ![Arms 3](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_fig16.jpg) + ![Arms 3](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_fig16.jpg) 10. Put the hanger gaskets into the 4 hangers and mount them onto the bottom plate using 8 hex screws (Figure 11). - The screw holes are noted by the white arrow in Figure 12. - We recommend tilting the drone sideway to make the installation easier. + The screw holes are noted by the white arrow in Figure 12. + We recommend tilting the drone sideway to make the installation easier. - + - _Figure 11_: Hanger gaskets + _Figure 11_: Hanger gaskets - ![Battery Mount 4](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_fig10.jpg) + ![Battery Mount 4](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_fig10.jpg) - _Figure 12_: Screw holes + _Figure 12_: Screw holes 11. Insert the slide bars onto the hanger rings (Figure 13). - Assemble the battery mount and platform board and mount them onto the slide bars as shown in Figure 14. + Assemble the battery mount and platform board and mount them onto the slide bars as shown in Figure 14. - ![Battery Mount 2: Slide bars](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_fig8.png) + ![Battery Mount 2: Slide bars](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_fig8.png) - _Figure 13_: Slide bars + _Figure 13_: Slide bars - + - _Figure 14_: Battery mount on slide bars + _Figure 14_: Battery mount on slide bars 12. Mount the landing gear onto the bottom plate. - We recommend tilting the drone sideway to make this installation process easier. + We recommend tilting the drone sideway to make this installation process easier. - ![Landing Gear](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_fig5.jpg) + ![Landing Gear](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_fig5.jpg) - _Figure 15_: Landing Gear + _Figure 15_: Landing Gear 13. Use the tape and stick the GPS to the top of the GPS mast and mount the GPS mast. - Make sure the arrow on the gps is pointing forward (Figure 16). + Make sure the arrow on the gps is pointing forward (Figure 16). - + - _Figure 16_: GPS and mast + _Figure 16_: GPS and mast 14. Mount the telemetry radio onto the top plate. - Plug the telemetry cable into `TELEM1` port and GPS module to `GPS MODULE` port on the flight controller. - Plug the cable from PM07 `FMU-PWM-in` to `I/O-PWM-out`on the FC and PM07 `PWR1` to `POWER1` on the FC, as shown in Figure 17. + Plug the telemetry cable into `TELEM1` port and GPS module to `GPS MODULE` port on the flight controller. + Plug the cable from PM07 `FMU-PWM-in` to `I/O-PWM-out`on the FC and PM07 `PWR1` to `POWER1` on the FC, as shown in Figure 17. - ![Pixhawk 4 wiring 1](../../assets/airframes/multicopter/x500_holybro_pixhawk4/fc_connections.jpg) + ![Pixhawk 4 wiring 1](../../assets/airframes/multicopter/x500_holybro_pixhawk4/fc_connections.jpg) - _Figure 17_: Mount telemetry radio/plug in PWM and Power cables to Flight controller. + _Figure 17_: Mount telemetry radio/plug in PWM and Power cables to Flight controller. Please refer to [Pixhawk 4 Quick Start](../assembly/quick_start_pixhawk4.md) for more information. diff --git a/docs/zh/frames_multicopter/holybro_x500v2_pixhawk6c.md b/docs/zh/frames_multicopter/holybro_x500v2_pixhawk6c.md index 3b07a691d6..a7a4bec9bb 100644 --- a/docs/zh/frames_multicopter/holybro_x500v2_pixhawk6c.md +++ b/docs/zh/frames_multicopter/holybro_x500v2_pixhawk6c.md @@ -18,21 +18,21 @@ This topic provides full instructions for building the [Holybro X500 V2 ARF Kit] **Screw**- Sunk Screw M2.5\*6 12pcs 1. Insert the hanger rubber ring gasket in each of their respective hangers. - Do not use sharp objects to press the rubbers inside. + Do not use sharp objects to press the rubbers inside. - [![Assembly1](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly1.png)](https://www.youtube.com/watch?v=4Tid-FCP_aI) + [![Assembly1](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly1.png)](https://www.youtube.com/watch?v=4Tid-FCP_aI) 2. Take the battery mounting board and screw it with the slide bar clip using the Sunk Screw M2.5\*6. - [![Assembly2](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly2.png)](https://youtu.be/9E-rld6tPWQ) + [![Assembly2](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly2.png)](https://youtu.be/9E-rld6tPWQ) 3. Screw 4 hangers to the Platform Board using Sunk Screw M2.5\*6. - [![Assembly3](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly3.png)](https://youtu.be/4qIBABc9KsY)) + [![Assembly3](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly3.png)](https://youtu.be/4qIBABc9KsY)) 4. Take the slide bar and insert 4 hangers to screw to the bottom plate later. - [![Assembly4](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly4.png)](https://youtu.be/CFx6Ct7FCIc)) + [![Assembly4](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly4.png)](https://youtu.be/CFx6Ct7FCIc)) 5. Now insert the battery holder and payload holders assembled in step 2 & 3 @@ -44,11 +44,11 @@ This topic provides full instructions for building the [Holybro X500 V2 ARF Kit] 1. Take the bottom plate and insert 4 M3\*14 screws and fasten the nylon standoffs on the same. - [![Assembly6](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly6.png)](https://youtu.be/IfsMXTr3Uy4) + [![Assembly6](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly6.png)](https://youtu.be/IfsMXTr3Uy4) 2. Place the Power distribution board and use the locknuts to assemble them. The power module PM02 (for Pixhawk 6C) would power this board - [![Assembly7](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly7.png)](https://youtu.be/Qjs6pqarRIY) + [![Assembly7](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly7.png)](https://youtu.be/Qjs6pqarRIY) 3. Use Socket Cap Screws M2.5\*6 and screw the bottom plate on the 4 hangers (that we inserted in the 2 bars on the 3rd step of the payload holder assembly) @@ -56,15 +56,15 @@ This topic provides full instructions for building the [Holybro X500 V2 ARF Kit] 1. To assemble the landing gear, loosen the pre-assembled screws of the Landing Gear-Cross Bar and insert the Landing Gear-Vertical Pole and fasten the same. - [![Assembly8](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly8.png)](https://youtu.be/mU4vm4zyjcY) + [![Assembly8](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly8.png)](https://youtu.be/mU4vm4zyjcY) - [![Assembly9](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly9.png)](https://youtu.be/7REaF3YAqLg) + [![Assembly9](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly9.png)](https://youtu.be/7REaF3YAqLg) 2. Use the Socket Cap Screw M3\*8 to screw the landing gears to the bottom plate - [![Assembly11](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly11.png)](https://youtu.be/iDxzWeyCN54) + [![Assembly11](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly11.png)](https://youtu.be/iDxzWeyCN54) - [![Assembly12](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly12.png)](https://youtu.be/3fNJQraCJx0) + [![Assembly12](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly12.png)](https://youtu.be/3fNJQraCJx0) Because it’s cumbersome to insert the wires once the top plate is assembled, do the wiring beforehand. Although the design is well built such that you can do this later as well. @@ -92,28 +92,28 @@ Note that the ESC connectors are color-coded and must be inserted in the PWM out 1. Putting the arms is quite simple as the motors come pre-assembled. - - Ensure that you have the right numbered arm with its motor on the respective side. + - Ensure that you have the right numbered arm with its motor on the respective side. - [![Assembly15](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly15.png)](https://youtu.be/45KCey3WiJ4) + [![Assembly15](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly15.png)](https://youtu.be/45KCey3WiJ4) - :::tip - Use your allen keys/ any elongated item and insert it on the opposite side of the bolt that you're trying to fasten. + :::tip + Use your allen keys/ any elongated item and insert it on the opposite side of the bolt that you're trying to fasten. ::: 2. Take one arm and insert the rectangle extrusion inside the rectangular hollow on the bottom plate. - [![Assembly16](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly16.png)](https://youtu.be/GOTqmjq9_3s) + [![Assembly16](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly16.png)](https://youtu.be/GOTqmjq9_3s) 3. While inserting the top plate on top of this the 3 piece assembly (bottom plate, top plate & arms) have to screwed using Socket Cap Screw M3\*38 and Flange Locknut M3. 4. Hold one side using the mini cross wrench provided in the developer kit. - [![Assembly17](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly17.png)](https://youtu.be/2rcNVekJQd0) + [![Assembly17](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly17.png)](https://youtu.be/2rcNVekJQd0) 5. Do not fasten any screws before all 3 motors are in place as this might make it difficult while you’re assembling the 3rd and 4th motor. - [![Assembly18](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly18.png)](https://youtu.be/SlKRuNoE_AY) + [![Assembly18](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly18.png)](https://youtu.be/SlKRuNoE_AY) ### Propellers @@ -132,13 +132,13 @@ The following parts can be placed as per usual. 1. Assemble the GPS by following the video. - [![Assembly20](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly20.png)](https://youtu.be/aiFxVJFjlos) + [![Assembly20](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly20.png)](https://youtu.be/aiFxVJFjlos) - This guide uses the GPS mount location suggested in Holybro’s guide. + This guide uses the GPS mount location suggested in Holybro’s guide. 2. Screw the GPS mount’s bottom end on the payload holder side using Locknut M3 & Screw M3\*10 - [![Assembly21](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly21.png)](https://youtu.be/uG5UKy3FrIc) + [![Assembly21](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly21.png)](https://youtu.be/uG5UKy3FrIc) ### Pixhawk 6C diff --git a/docs/zh/frames_vtol/vtol_quadplane_falcon_vertigo_hybrid_rtf_dropix.md b/docs/zh/frames_vtol/vtol_quadplane_falcon_vertigo_hybrid_rtf_dropix.md index c88c3d223c..a24076acec 100644 --- a/docs/zh/frames_vtol/vtol_quadplane_falcon_vertigo_hybrid_rtf_dropix.md +++ b/docs/zh/frames_vtol/vtol_quadplane_falcon_vertigo_hybrid_rtf_dropix.md @@ -67,45 +67,45 @@ The RTF kit requires the following assembly. 1. Spread gorilla glue inside the wing brackets as shown. - ![Add glue on wing brackets](../../assets/airframes/vtol/falcon_vertigo/wing_brackets_glue.jpg) + ![Add glue on wing brackets](../../assets/airframes/vtol/falcon_vertigo/wing_brackets_glue.jpg) 2. Attach the carbon tube in the brackets. The bracket and tube must be aligned using the white mark (as shown in the picture). - ::: info - This is very important because the white mark indicates the center of gravity. + ::: info + This is very important because the white mark indicates the center of gravity. ::: - + 3. The following images show the alignment of rods from other viewpoints: - ![quad motor frame rod alignment from bottom](../../assets/airframes/vtol/falcon_vertigo/falcon_vertigo_9_bottom_view_rod_alignment.jpg) - ![quad motor frame rod alignment schematic](../../assets/airframes/vtol/falcon_vertigo/falcon_vertigo_11_rod_alignment_schamatic.jpg) + ![quad motor frame rod alignment from bottom](../../assets/airframes/vtol/falcon_vertigo/falcon_vertigo_9_bottom_view_rod_alignment.jpg) + ![quad motor frame rod alignment schematic](../../assets/airframes/vtol/falcon_vertigo/falcon_vertigo_11_rod_alignment_schamatic.jpg) ### Step 2: Attach the wings 1. Insert both carbon tubes into the fuselage. - + 2. Spread gorilla glue between the two white marks on each tube (indicated by the red arrows). The white mark in the center (blue arrow) will be placed in the center of the fuselage and the other marks on the sides. - + 3. Once the carbon tubes are inside the fuselage, spread gorilla glue on the rest of the tube and attach the wings. 4. The fuselage has two holes for the motor and servo cables. Pass the cables through the holes and then join the wings to the fuselage. - + 5. Within the fuselage connect the signal cables you just passed through from the wings to the ESC using the provided connectors. The ESC are already connected to the motors and set up to turn in the correct order (you will need to connect the ESC PDB to a power module in a later step). - + 6. As with the ESCs, the servos are already installed. Connect the signal cable from the wing (passed through the fuselage) to the flight controller. - + 7. Repeat these steps for the other wing. @@ -123,11 +123,11 @@ General information about connecting Dropix can be found in [Dropix Flight Contr 1. Connect the ESC to the power module using the XT60 connector - + 2. Pass the signals cables through to the flight controller - + #### Motor Wiring @@ -162,7 +162,7 @@ The image below shows back of the dropix flight controller, highlighting the out 3. Connect the throttle motor signal cable from the ESC to the appropriate flight controller auxiliary port. Connect the ESC to the throttle motor. - + 4. Connect the receiver (RC IN). @@ -176,7 +176,7 @@ The sensor inputs, telemetry, buzzer and safety switch are located in the front 1. Connect the telemetry, airspeed sensor, GPS, buzzer and safety switch as shown. - + #### Flight Controller: Connect power module and external USB @@ -184,7 +184,7 @@ The inputs for the USB port, power module and external USB are located on the ri 1. Connect power and USB as shown - + :::tip The external USB is optional. @@ -201,27 +201,27 @@ It is important that nothing obstructs airflow to the Pitot tube. This is critic 1. Install the Pitot tube in the front of the plane - + 2. Secure the connecting tubing and ensure that it is not bent/kinked. - + 3. Connect the tubes to the airspeed sensor. - + #### Install/connect receiver and telemetry module 1. Paste the receiver and telemetry module to the outside of the vehicle frame. - + 2. Connect the receiver to the RC IN port on the _back_ of the dropix, as shown above (also see the [flight controller instructions](#dropix_back)). 3. Connect the telemetry module to the _front_ of the flight controller as shown below (see the [flight controller instructions](#dropix_front) for more detail on the pins). - + @@ -237,7 +237,7 @@ The GPS/Compass module is already mounted on the wing, in the default orientatio 1. Set your flight controller orientation to 270 degrees. - + 2. Secure the controller in place using vibration damping foam. @@ -247,21 +247,21 @@ The final assembly step is to check the vehicle is stable and that the motors ha 1. Check that the motors turn in the correct directions (as in the QuadX diagram below). - + - ::: info - If necessary the servo direction can be reversed using the `Rev Range (for servos)` checkbox associated with each servo output in the QGroundControl [Actuator Output](../config/actuators.md#actuator-outputs) configuration (for servos only) (this sets the [PWM_AUX_REV](../advanced_config/parameter_reference.md#PWM_AUX_REV) or [PWM_AUX_MAIN](../advanced_config/parameter_reference.md#PWM_MAIN_REV) parameter). + ::: info + If necessary the servo direction can be reversed using the `Rev Range (for servos)` checkbox associated with each servo output in the QGroundControl [Actuator Output](../config/actuators.md#actuator-outputs) configuration (for servos only) (this sets the [PWM_AUX_REV](../advanced_config/parameter_reference.md#PWM_AUX_REV) or [PWM_AUX_MAIN](../advanced_config/parameter_reference.md#PWM_MAIN_REV) parameter). ::: 2. Check the vehicle is balanced around the expected centre of gravity - - Hold the vehicle with your fingers at the center of gravity and check that the vehicle remains stable. + - Hold the vehicle with your fingers at the center of gravity and check that the vehicle remains stable. - ![Level Centre of Gravity](../../assets/airframes/vtol/falcon_vertigo/falcon_vertigo_57_level_centre_of_gravity.jpg) + ![Level Centre of Gravity](../../assets/airframes/vtol/falcon_vertigo/falcon_vertigo_57_level_centre_of_gravity.jpg) - - If the vehicle leans forward or backwards, move the motors to balance it. + - If the vehicle leans forward or backwards, move the motors to balance it. - ![Level Motors](../../assets/airframes/vtol/falcon_vertigo/falcon_vertigo_55_level_motors.jpg) + ![Level Motors](../../assets/airframes/vtol/falcon_vertigo/falcon_vertigo_55_level_motors.jpg) ## 配置 @@ -271,7 +271,7 @@ Perform the normal [Basic Configuration](../config/index.md). 1. For [Airframe](../config/airframe.md) select the vehicle group/type as _Standard VTOL_ and the specific vehicle as [Generic Standard VTOL](../airframes/airframe_reference.md#vtol_standard_vtol_generic_standard_vtol) as shown below. - ![QCG - Select Generic Standard VTOL](../../assets/qgc/setup/airframe/px4_frame_generic_standard_vtol.png) + ![QCG - Select Generic Standard VTOL](../../assets/qgc/setup/airframe/px4_frame_generic_standard_vtol.png) 2. Set the [Autopilot Orientation](../config/flight_controller_orientation.md) to `ROTATION_YAW_270` as the autopilot is mounted [sideways](#flight_controller_orientation) with respect to the front of the vehicle. The compass is oriented forward, so you can leave that at the default (`ROTATION_NONE`). diff --git a/docs/zh/frames_vtol/vtol_quadplane_foxtech_loong_2160.md b/docs/zh/frames_vtol/vtol_quadplane_foxtech_loong_2160.md index cc6418299f..08e01c67ec 100644 --- a/docs/zh/frames_vtol/vtol_quadplane_foxtech_loong_2160.md +++ b/docs/zh/frames_vtol/vtol_quadplane_foxtech_loong_2160.md @@ -99,33 +99,33 @@ Use a soldering iron to press the threaded inserts into the 3D-Printed parts. 1. Insert 10x M3 threaded inserts into the baseplate as shown in the picture: - ![Baseplate with threaded inserts](../../assets/airframes/vtol/foxtech_loong_2160/03-baseplate.jpg) + ![Baseplate with threaded inserts](../../assets/airframes/vtol/foxtech_loong_2160/03-baseplate.jpg) 2. Insert 2x M3 threaded inserts into the stack fixture as shown in the picture below: - ![Stack fixture with threaded inserts](../../assets/airframes/vtol/foxtech_loong_2160/04-stack-fixture.jpg) + ![Stack fixture with threaded inserts](../../assets/airframes/vtol/foxtech_loong_2160/04-stack-fixture.jpg) 3. Insert 2x M4 threaded inserts into the fan mount and radio mount as shown in the picture below. - ![Radio-mount](../../assets/airframes/vtol/foxtech_loong_2160/05-radio-mount.jpg) + ![Radio-mount](../../assets/airframes/vtol/foxtech_loong_2160/05-radio-mount.jpg) - If you would like to add a 40mm 5V fan to the fan mount, insert 4x M3 inserts. + If you would like to add a 40mm 5V fan to the fan mount, insert 4x M3 inserts. - ![Fan-mount](../../assets/airframes/vtol/foxtech_loong_2160/06-fan-mount.jpg) + ![Fan-mount](../../assets/airframes/vtol/foxtech_loong_2160/06-fan-mount.jpg) 4. Change the cable connector to a servo connector so it can be plugged into the servo rail to be powered. - ::: info - A fan might be needed if a powerful radio is used. + ::: info + A fan might be needed if a powerful radio is used. ::: - ![Fan-mount with fan](../../assets/airframes/vtol/foxtech_loong_2160/07-fan-mount.jpg) + ![Fan-mount with fan](../../assets/airframes/vtol/foxtech_loong_2160/07-fan-mount.jpg) 5. Remove the original mounting plate from the vehicle. - Tape the cables to the outside of the fuselage. + Tape the cables to the outside of the fuselage. - ![Empty fuselage](../../assets/airframes/vtol/foxtech_loong_2160/08-preparations.jpg) + ![Empty fuselage](../../assets/airframes/vtol/foxtech_loong_2160/08-preparations.jpg) 6. Slide the baseplate into the vehicle. @@ -142,9 +142,9 @@ The 40A power module provides power for the avionics when using Skynode (and com 1. Remove the case from the 40A PM. 2. Screw the PM with 2x M2x6mm to the bottom of the baseplate. 3. Create a cable to extend the XT60 connector to an XT30 that is mounted on the baseplate. - With that, the 6S battery power can be directly plugged into the XT30 connector with the pre-configured cable that comes with the vehicle. + With that, the 6S battery power can be directly plugged into the XT30 connector with the pre-configured cable that comes with the vehicle. - ![40A Power Module installation](../../assets/airframes/vtol/foxtech_loong_2160/10-40a-power-module.jpg) + ![40A Power Module installation](../../assets/airframes/vtol/foxtech_loong_2160/10-40a-power-module.jpg) If necessary, the 10V output of the radio port on the PM can also be exposed via an XT30 that can be mounted next to the 6S battery input XT60. @@ -153,17 +153,17 @@ If necessary, the 10V output of the radio port on the PM can also be exposed via #### Pitot Tube 1. The sensor can be installed with 2x M3x16mm screws in the front right corner of the baseplate. - Take care that the connector is facing the center of the fuselage. + Take care that the connector is facing the center of the fuselage. - ![Mounted airspeed sensor](../../assets/airframes/vtol/foxtech_loong_2160/11-airspeed-sensor.jpg) + ![Mounted airspeed sensor](../../assets/airframes/vtol/foxtech_loong_2160/11-airspeed-sensor.jpg) - Only the front tube (not as shown in the picture) is used; the other tube can be removed since our experience showed that the pressure inside the fuselage is sufficient as static pressure. + Only the front tube (not as shown in the picture) is used; the other tube can be removed since our experience showed that the pressure inside the fuselage is sufficient as static pressure. 2. When the stack is mounted inside the fuselage, the tube coming from the wing and the one from the airspeed sensor need to be spliced together. - Use some spit (that's the easiest way) to push them together and afterward use a heat shrink tube to reinforce the connection. + Use some spit (that's the easiest way) to push them together and afterward use a heat shrink tube to reinforce the connection. - :::warning - Use a heat source carefully since the foam starts to melt at high temperatures. + :::warning + Use a heat source carefully since the foam starts to melt at high temperatures. ::: @@ -175,22 +175,22 @@ If no lidar is mounted you should disable using fixed-wing actuation in hover to ::: 1. Mark the location to install the lidar with some tape or a pen. - Cut a hole inside the PVC shell and the foam, so that the lidar fits in place. + Cut a hole inside the PVC shell and the foam, so that the lidar fits in place. - ![Prepared lidar hole](../../assets/airframes/vtol/foxtech_loong_2160/12-lidar-01.jpg) + ![Prepared lidar hole](../../assets/airframes/vtol/foxtech_loong_2160/12-lidar-01.jpg) 2. Secure the lidar with hot glue. - ![Installed lidar](../../assets/airframes/vtol/foxtech_loong_2160/13-lidar-02.jpg) + ![Installed lidar](../../assets/airframes/vtol/foxtech_loong_2160/13-lidar-02.jpg) #### GPS/Compass 1. Use double sided tape to mount the GPS in the rear of the vehicle underneath the rear latch. - ![Installed GPS](../../assets/airframes//vtol/foxtech_loong_2160/14-gps.jpg) + ![Installed GPS](../../assets/airframes//vtol/foxtech_loong_2160/14-gps.jpg) - The arrow on the GPS for the orientation can be ignored. - The orientation will be detected by the flight controller during the calibration. + The arrow on the GPS for the orientation can be ignored. + The orientation will be detected by the flight controller during the calibration. ### Flight Controller @@ -203,15 +203,15 @@ Install either the Pixhawk or Skynode onto the baseplate. #### Skynode 1. Use 4x M3x8 screws to mount the Skynode to the baseplate. - Make sure that the top of the "A" is facing to the front of the vehicle. + Make sure that the top of the "A" is facing to the front of the vehicle. 2. Plug the 40A Power Module into the upper one of the two power connectors. 3. Plug one (or if needed two) USB adapters into the 4-pin JST-GH connectors into the back of the Skynode and feed them to the front of the plate. - Fix the cables with zip ties in place. + Fix the cables with zip ties in place. 4. Tape a I2C splitter to the front right side of the baseplate (The splitter can be used to plug in ETH devices such as a radio link.) 5. Connect the I2C splitter with the ETH port in the back of the Skynode. 6. Plug in the two 40-pin cables into the front of the Skynode. 7. Plug in the USB-C extension cable and bend it over to the front. - The bend needs to be very tight, so that the plate will fit into the vehicle. + The bend needs to be very tight, so that the plate will fit into the vehicle. ![Installed Skynode](../../assets/airframes/vtol/foxtech_loong_2160/15-skynode.jpg) @@ -223,17 +223,17 @@ Install either the Pixhawk or Skynode onto the baseplate. 1. Tape the Skynode LTE antennas to the side of the fuselage as shown in the picture: - ![LTE-Antennas](../../assets/airframes/vtol/foxtech_loong_2160/16-lte-antennas.jpg) + ![LTE-Antennas](../../assets/airframes/vtol/foxtech_loong_2160/16-lte-antennas.jpg) 2. If you are using a radio telemetry module you can mount the antennas to the top of the fuselage. - In the front you can mount the antenna extension cable directly. + In the front you can mount the antenna extension cable directly. - ![WIFI-Antennas-Front](../../assets/airframes/vtol/foxtech_loong_2160/17-antenna-front.jpg) + ![WIFI-Antennas-Front](../../assets/airframes/vtol/foxtech_loong_2160/17-antenna-front.jpg) - In the back you can use the 3D-Printed antenna adapter. - The adapter can be glued in place with hot glue. + In the back you can use the 3D-Printed antenna adapter. + The adapter can be glued in place with hot glue. - ![WIFI-Antenna-Back](../../assets/airframes/vtol/foxtech_loong_2160/19-rear-antenna.jpg) + ![WIFI-Antenna-Back](../../assets/airframes/vtol/foxtech_loong_2160/19-rear-antenna.jpg) ### 12S Power Module diff --git a/docs/zh/frames_vtol/vtol_tiltrotor_omp_hobby_zmo_fpv.md b/docs/zh/frames_vtol/vtol_tiltrotor_omp_hobby_zmo_fpv.md index d61a2e32b8..8d45e5c91b 100644 --- a/docs/zh/frames_vtol/vtol_tiltrotor_omp_hobby_zmo_fpv.md +++ b/docs/zh/frames_vtol/vtol_tiltrotor_omp_hobby_zmo_fpv.md @@ -93,7 +93,7 @@ Flight controller and wing connectors removed from the vehicle. ### ESCs 1. Unsolder the ESC PWM-signal and ground pins and solder some servo extension wire to the pins. - The cable should be long enough to connect the wire to the FMU pins of the flight controller. + The cable should be long enough to connect the wire to the FMU pins of the flight controller. 2. Unsolder the 3 female banana plug connectors of the rear motor (might not be necessary for the Pixhawk 6 integration). @@ -103,17 +103,17 @@ Flight controller and wing connectors removed from the vehicle. 5. Solder signal and GND wires to the PWM input ot the ESC. - ![ESC 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/esc-01.jpg) + ![ESC 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/esc-01.jpg) 6. Remove the female banana plug on the ESC. - This will give you more space to install the flight controller. + This will give you more space to install the flight controller. - ![ESC 02](../../assets/airframes/vtol/omp_hobby_zmo_fpv/esc-02.jpg) + ![ESC 02](../../assets/airframes/vtol/omp_hobby_zmo_fpv/esc-02.jpg) 7. Solder the rear motor wires to the ESC. - Make sure to connect such that the motor spins in the correct direction. + Make sure to connect such that the motor spins in the correct direction. - ![ESC 03](../../assets/airframes/vtol/omp_hobby_zmo_fpv/esc-03.jpg) + ![ESC 03](../../assets/airframes/vtol/omp_hobby_zmo_fpv/esc-03.jpg) ### Wing Connector @@ -122,9 +122,9 @@ This step is not essential, but makes the handling much easier and there is one 1. Glue the wing connectors into the 3D-Printed part with hot-glue or 5 min epoxy. 2. Glue the 3D-printed part with the connector in to the fuselage. - Make sure to properly align the connector while the glue cures. + Make sure to properly align the connector while the glue cures. - The easiest way to align the connector is to mount the wing while the glue is curing, but make sure that no glue is between the fuselage and the wing, otherwise the wing might get stuck. + The easiest way to align the connector is to mount the wing while the glue is curing, but make sure that no glue is between the fuselage and the wing, otherwise the wing might get stuck. The connector glued into the 3D-Printed part @@ -137,58 +137,58 @@ The connector glued into the fuselage. Make sure to properly align the connector ### Pixhawk Adapter Boards and BEC 1. Cut the foam as shown in the pictures to create space to mount the Pixhawk adapter boards and BEC with double sided tape. - The FMU board is placed on the left side (in flight direction) of the fuselage. - Solder a servo connector and a cable for the battery voltage to the BEC. + The FMU board is placed on the left side (in flight direction) of the fuselage. + Solder a servo connector and a cable for the battery voltage to the BEC. - ![Foam cutout 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/foam-cut-01.png) - ![Pixhawk adapter board mount 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/pixhawk-adapter-01.jpg) + ![Foam cutout 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/foam-cut-01.png) + ![Pixhawk adapter board mount 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/pixhawk-adapter-01.jpg) 2. Prepare the BEC to connect to the IO board and to the battery. - The BEC can also be soldered directly to the battery pads of the ESC. + The BEC can also be soldered directly to the battery pads of the ESC. - ![BEC preparation](../../assets/airframes/vtol/omp_hobby_zmo_fpv/bec-01.jpg) + ![BEC preparation](../../assets/airframes/vtol/omp_hobby_zmo_fpv/bec-01.jpg) 3. Mount the BEC with double sided tape. - ![BEC mounting](../../assets/airframes/vtol/omp_hobby_zmo_fpv/bec-02.jpg) + ![BEC mounting](../../assets/airframes/vtol/omp_hobby_zmo_fpv/bec-02.jpg) ### Cables 1. Cut the connectors off the servos and solder the servo extension cables to the cables. - Make sure that the cables are long enough to reach the Pixhawk adapter board. - If you own a crimp tool, then you can also directly add the connectors without soldering. + Make sure that the cables are long enough to reach the Pixhawk adapter board. + If you own a crimp tool, then you can also directly add the connectors without soldering. 2. Plug the servo cables into the adapter IO board in the following order: - - 1 - Aileron left - - 2 - Aileron right - - 3 - V-Tail left - - 4 - V-Tail right - - 5 - Tilt left - - 6 - Tilt right + - 1 - Aileron left + - 2 - Aileron right + - 3 - V-Tail left + - 4 - V-Tail right + - 5 - Tilt left + - 6 - Tilt right 3. Plug in the motor signal cables into the FMU adapter board in the following order: - - 1 - Front left - - 2 - Front right - - 3 - Rear + - 1 - Front left + - 2 - Front right + - 3 - Rear ### 传感器 #### Pitot Tube 1. First check if the pitot tube fits into the 3D-Printed mount. - If this is the case, glue the pitot tube mount into place. + If this is the case, glue the pitot tube mount into place. - To align the tube feed it through the second hole from the right of the FPV front plate. - The mount will enable you to push the tube back into the fuselage to protect it during transportation and handling. - The sensor unit can be mounted on top of the 3D-Printed mount with double sided tape. + To align the tube feed it through the second hole from the right of the FPV front plate. + The mount will enable you to push the tube back into the fuselage to protect it during transportation and handling. + The sensor unit can be mounted on top of the 3D-Printed mount with double sided tape. 2. Glue the 3D-Printed mount into place. - ![Pitot tube 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/pitot-tube-01.png) + ![Pitot tube 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/pitot-tube-01.png) 3. The sensor can be mounted on top of the 3D-Printed mount. - ![Pitot tube 02](../../assets/airframes/vtol/omp_hobby_zmo_fpv/pitot-tube-02.png) + ![Pitot tube 02](../../assets/airframes/vtol/omp_hobby_zmo_fpv/pitot-tube-02.png) #### Lidar @@ -209,9 +209,9 @@ To mount the GPS: 2. Take the GPS out of the plastic case and unplug the connector. 3. Feed the cable through the carbon spar. 4. Glue the 3D-Printed part with 5 min epoxy in place. - ![Glue the GPS mount into place](../../assets/airframes/vtol/omp_hobby_zmo_fpv/gps-01.jpg) + ![Glue the GPS mount into place](../../assets/airframes/vtol/omp_hobby_zmo_fpv/gps-01.jpg) 5. After the glue has cured, screw the GPS with 4x M2.5x10 screws to the plate. - ![Screw the GPS to the mount2](../../assets/airframes/vtol/omp_hobby_zmo_fpv/gps-02.jpg) + ![Screw the GPS to the mount2](../../assets/airframes/vtol/omp_hobby_zmo_fpv/gps-02.jpg) #### USB Camera @@ -219,9 +219,9 @@ To mount the GPS: 2. Cut the USB-Adapter cable to be 25 cm and solder the two cables together. 3. To install the camera you need to cut a hole into the foam of the wall. - ![USB Camera 01: Hole to feed the USB cable through the wall.](../../assets/airframes/vtol/omp_hobby_zmo_fpv/camera-01.jpg) + ![USB Camera 01: Hole to feed the USB cable through the wall.](../../assets/airframes/vtol/omp_hobby_zmo_fpv/camera-01.jpg) - Then you can mount the camera with double sided tape to the wall. + Then you can mount the camera with double sided tape to the wall. ### Flight Controller @@ -237,7 +237,7 @@ If a Skynode is used: 1. Place it at the on top of the ESCs and mark the 2 rear mounting locations on the injection molded plastic part of the ZMO. 2. Remove the Skynode from the vehicle and drill 2 holes with a 2.8 mm drill bit into the plastic part. - ![Mounting holes for the Skynode in the back](../../assets/airframes/vtol/omp_hobby_zmo_fpv/flight-controller-01.jpg) + ![Mounting holes for the Skynode in the back](../../assets/airframes/vtol/omp_hobby_zmo_fpv/flight-controller-01.jpg) 3. Put the Skynode back into place and screw it down with 2x M3x10 screws. Another option is to add some threaded inserts into the holes. @@ -245,9 +245,9 @@ Since the injection molded part of the ZMO is very thin, they need to be glued i 1. Screw the front Skynode mount with 2x M3x10 screws at the Skynode. 2. Then add some 5 min epoxy at the bottom of the mount and put a weight on top of the Skynode until the glue is cured. - To access the 2 mounting screws at the front, poke 2 holes from the top through the foam. + To access the 2 mounting screws at the front, poke 2 holes from the top through the foam. - ![Skynode mount in the front](../../assets/airframes/vtol/omp_hobby_zmo_fpv/flight-controller-02.jpg) + ![Skynode mount in the front](../../assets/airframes/vtol/omp_hobby_zmo_fpv/flight-controller-02.jpg) ### Antennas and RC Receiver @@ -258,14 +258,14 @@ An inexpensive example would be a [SiK Telemetry Radio](../telemetry/sik_radio.m ::: 1. One LTE antenna can be installed on the bottom of the vehicle. - For that you can feed the antenna wire through the opening for the ESC heat-sink. + For that you can feed the antenna wire through the opening for the ESC heat-sink. - ![LTE antenna 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/lte-antenna-01.jpg) + ![LTE antenna 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/lte-antenna-01.jpg) 2. The second antenna can be installed on the inside of the vehicle on the left side of the battery compartment. - The RC receiver can also be placed at the left side of the battery compartment. + The RC receiver can also be placed at the left side of the battery compartment. - ![LTE antenna 2 and RC receiver](../../assets/airframes/vtol/omp_hobby_zmo_fpv/lte-antenna-02.jpg) + ![LTE antenna 2 and RC receiver](../../assets/airframes/vtol/omp_hobby_zmo_fpv/lte-antenna-02.jpg) ## 软件设置 @@ -332,9 +332,9 @@ If motors/servos were connected to different outputs than suggested, you will ne 1. Switch the vehicle into manual mode (either via the flight mode switch or type `commander mode manual` into the MAVLink shell). 2. Check if the motors point upwards. - If the motors point forwards then their associated Tilt servos need to be reversed (selecting the checkbox next to each servo). + If the motors point forwards then their associated Tilt servos need to be reversed (selecting the checkbox next to each servo). - ![Tilt Servo adjustment](../../assets/airframes/vtol/omp_hobby_zmo_fpv/tilt-limits-01.jpg) + ![Tilt Servo adjustment](../../assets/airframes/vtol/omp_hobby_zmo_fpv/tilt-limits-01.jpg) 3. Adjust the minimum (or, if revesed: maximum) value such that the rotor thrust can point backward (needed for proper yaw allocation in Multicopter mode). diff --git a/docs/zh/gps_compass/index.md b/docs/zh/gps_compass/index.md index d4d5a030bd..660cf102b3 100644 --- a/docs/zh/gps_compass/index.md +++ b/docs/zh/gps_compass/index.md @@ -145,21 +145,21 @@ To ensure the port is set up correctly perform a [Serial Port Configuration](../ The following steps show how to configure a secondary GPS on the `GPS 2` port in _QGroundControl_: 1. [Find and set](../advanced_config/parameters.md) the parameter [GPS_2_CONFIG](../advanced_config/parameter_reference.md#GPS_2_CONFIG) to **GPS 2**. - - Open _QGroundControl_ and navigate to the **Vehicle Setup > Parameters** section. - - Select the **GPS** tab, then open the [GPS_2_CONFIG](../advanced_config/parameter_reference.md#GPS_2_CONFIG) parameter and select `GPS 2` from the dropdown list. + - Open _QGroundControl_ and navigate to the **Vehicle Setup > Parameters** section. + - Select the **GPS** tab, then open the [GPS_2_CONFIG](../advanced_config/parameter_reference.md#GPS_2_CONFIG) parameter and select `GPS 2` from the dropdown list. - ![QGC Serial Example](../../assets/peripherals/qgc_serial_config_example.png) + ![QGC Serial Example](../../assets/peripherals/qgc_serial_config_example.png) 2. Reboot the vehicle in order to make the other parameters visible. 3. Select the **Serial** tab, and open the [SER_GPS2_BAUD](../advanced_config/parameter_reference.md#SER_GPS2_BAUD) parameter (`GPS 2` port baud rate): set it to _Auto_ (or 115200 for the Trimble). - ![QGC Serial Baudrate Example](../../assets/peripherals/qgc_serial_baudrate_example.png) + ![QGC Serial Baudrate Example](../../assets/peripherals/qgc_serial_baudrate_example.png) After setting up the second GPS port: 1. Configure the ECL/EKF2 estimator to blend data from both GPS systems. - For detailed instructions see: [Using the ECL EKF > Dual Receivers](../advanced_config/tuning_the_ecl_ekf.md#dual-receivers). + For detailed instructions see: [Using the ECL EKF > Dual Receivers](../advanced_config/tuning_the_ecl_ekf.md#dual-receivers). ### DroneCAN GNSS Configuration diff --git a/docs/zh/gps_compass/rtk_gps.md b/docs/zh/gps_compass/rtk_gps.md index ced9490167..8ccdbf22ec 100644 --- a/docs/zh/gps_compass/rtk_gps.md +++ b/docs/zh/gps_compass/rtk_gps.md @@ -122,35 +122,35 @@ This should be set by default, but if not, follow the [MAVLink2 configuration in The RTK GPS connection is essentially plug and play: 1. Start _QGroundControl_ and attach the base RTK GPS via USB to the ground station. - 电脑会自动识别设备。 + 电脑会自动识别设备。 2. Start the vehicle and make sure it is connected to _QGroundControl_. - :::tip - _QGroundControl_ displays an RTK GPS status icon in the top icon bar while an RTK GPS device is connected (in addition to the normal GPS status icon). - The icon is red while RTK is being set up, and then changes to white once RTK GPS is active. - You can click the icon to see the current state and RTK accuracy. + :::tip + _QGroundControl_ displays an RTK GPS status icon in the top icon bar while an RTK GPS device is connected (in addition to the normal GPS status icon). + The icon is red while RTK is being set up, and then changes to white once RTK GPS is active. + You can click the icon to see the current state and RTK accuracy. ::: 3. _QGroundControl_ then starts the RTK setup process (known as "Survey-In"). - 测量是一个获得基站准确位置的设置过程。 - The process typically takes several minutes (it ends after reaching the minimum time and accuracy specified in the [RTK settings](#rtk-gps-settings)). + 测量是一个获得基站准确位置的设置过程。 + The process typically takes several minutes (it ends after reaching the minimum time and accuracy specified in the [RTK settings](#rtk-gps-settings)). - 你也可以点击 RTK状态按钮查看。 + 你也可以点击 RTK状态按钮查看。 - ![survey-in](../../assets/qgc/setup/rtk/qgc_rtk_survey-in.png) + ![survey-in](../../assets/qgc/setup/rtk/qgc_rtk_survey-in.png) 4. 测量完成: - - The RTK GPS icon changes to white and _QGroundControl_ starts to stream position data to the vehicle: + - The RTK GPS icon changes to white and _QGroundControl_ starts to stream position data to the vehicle: - ![RTK streaming](../../assets/qgc/setup/rtk/qgc_rtk_streaming.png) + ![RTK streaming](../../assets/qgc/setup/rtk/qgc_rtk_streaming.png) - - Vehicle GPS switches to RTK mode. - The new mode is displayed in the _normal_ GPS status icon (`3D RTK GPS Lock`): + - Vehicle GPS switches to RTK mode. + The new mode is displayed in the _normal_ GPS status icon (`3D RTK GPS Lock`): - ![RTK GPS Status](../../assets/qgc/setup/rtk/qgc_rtk_gps_status.png) + ![RTK GPS Status](../../assets/qgc/setup/rtk/qgc_rtk_gps_status.png) ### Configuring GPS as Yaw/Heading Source diff --git a/docs/zh/hardware/board_support_guide.md b/docs/zh/hardware/board_support_guide.md index e9f3309f16..f54739bde3 100644 --- a/docs/zh/hardware/board_support_guide.md +++ b/docs/zh/hardware/board_support_guide.md @@ -33,8 +33,8 @@ The general requirements for all supported boards are: 6. Adequate documentation, which includes, but is not limited to: - A complete pinout made available publicly that maps PX4 pin definitions to: - 1. Microcontroller pins - 2. Physical external connectors + 1. Microcontroller pins + 2. Physical external connectors - A block diagram or full schematic of the main components (sensors, power supply, etc.) that allows to infer software requirements and boot order - A manual of the finished product detailing its use diff --git a/docs/zh/hardware/porting_guide_nuttx.md b/docs/zh/hardware/porting_guide_nuttx.md index fb1c22d0ac..dbdf5c54b6 100644 --- a/docs/zh/hardware/porting_guide_nuttx.md +++ b/docs/zh/hardware/porting_guide_nuttx.md @@ -62,30 +62,30 @@ First you will need a bootloader, which depends on the hardware target: 2. Download the source code and make sure you can build an existing target: - ```sh - git clone --recursive https://github.com/PX4/PX4-Autopilot.git - cd PX4-Autopilot - make px4_fmu-v5 - ``` + ```sh + git clone --recursive https://github.com/PX4/PX4-Autopilot.git + cd PX4-Autopilot + make px4_fmu-v5 + ``` 3. Find an existing target that uses the same (or a closely related) CPU type and copy it. - For example for STM32F7: + For example for STM32F7: - ```sh - mkdir boards/manufacturer - cp -r boards/px4/fmu-v5 boards/manufacturer/my-target-v1 - ``` + ```sh + mkdir boards/manufacturer + cp -r boards/px4/fmu-v5 boards/manufacturer/my-target-v1 + ``` - Change **manufacturer** to the manufacturer name and **my-target-v1** to your board name. + Change **manufacturer** to the manufacturer name and **my-target-v1** to your board name. Next you need to go through all files under **boards/manufacturer/my-target-v1** and update them according to your board. 1. **firmware.prototype**: update the board ID and name 2. **default.px4board**: update the **VENDOR** and **MODEL** to match the directory names (**my-target-v1**). - Configure the serial ports. + Configure the serial ports. 3. Configure NuttX (**defconfig**) via `make manufacturer_my-target-v1 menuconfig`: Adjust the CPU and chip, configure the peripherals (UART's, SPI, I2C, ADC). 4. **nuttx-config/include/board.h**: Configure the NuttX pins. - For all peripherals with multiple pin options, NuttX needs to know the pin. - They are defined in the chip-specific pinmap header file, for example [stm32f74xx75xx_pinmap.h](https://github.com/PX4/NuttX/blob/px4_firmware_nuttx-8.2/arch/arm/src/stm32f7/hardware/stm32f74xx75xx_pinmap.h). + For all peripherals with multiple pin options, NuttX needs to know the pin. + They are defined in the chip-specific pinmap header file, for example [stm32f74xx75xx_pinmap.h](https://github.com/PX4/NuttX/blob/px4_firmware_nuttx-8.2/arch/arm/src/stm32f7/hardware/stm32f74xx75xx_pinmap.h). 5. **src**: go through all files under **src** and update them as needed, in particular **board_config.h**. 6. **init/rc.board_sensors**: start the sensors that are attached to the board. diff --git a/docs/zh/middleware/uxrce_dds.md b/docs/zh/middleware/uxrce_dds.md index 365473334f..3a6ad2baf6 100644 --- a/docs/zh/middleware/uxrce_dds.md +++ b/docs/zh/middleware/uxrce_dds.md @@ -118,78 +118,78 @@ To build the agent within ROS: 1. Create a workspace directory for the agent: - ```sh - mkdir -p ~/px4_ros_uxrce_dds_ws/src - ``` + ```sh + mkdir -p ~/px4_ros_uxrce_dds_ws/src + ``` 2. Clone the source code for the eProsima [Micro-XRCE-DDS-Agent](https://github.com/eProsima/Micro-XRCE-DDS-Agent) to the `/src` directory (the `main` branch is cloned by default): - ```sh - cd ~/px4_ros_uxrce_dds_ws/src - git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git - ``` + ```sh + cd ~/px4_ros_uxrce_dds_ws/src + git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git + ``` 3. Source the ROS 2 development environment, and compile the workspace using `colcon`: - :::: tabs + :::: tabs - ::: tab humble + ::: tab humble - ```sh - source /opt/ros/humble/setup.bash - colcon build - ``` + ```sh + source /opt/ros/humble/setup.bash + colcon build + ``` ::: - ::: tab foxy + ::: tab foxy - ```sh - source /opt/ros/foxy/setup.bash - colcon build - ``` + ```sh + source /opt/ros/foxy/setup.bash + colcon build + ``` ::: - :::: + :::: - This builds all the folders under `/src` using the sourced toolchain. + This builds all the folders under `/src` using the sourced toolchain. To run the micro XRCE-DDS agent in the workspace: 1. Source the `local_setup.bash` to make the executables available in the terminal (also `setup.bash` if using a new terminal). - :::: tabs + :::: tabs - ::: tab humble + ::: tab humble - ```sh - source /opt/ros/humble/setup.bash - source install/local_setup.bash - ``` + ```sh + source /opt/ros/humble/setup.bash + source install/local_setup.bash + ``` ::: - ::: tab foxy + ::: tab foxy - ```sh - source /opt/ros/foxy/setup.bash - source install/local_setup.bash - ``` + ```sh + source /opt/ros/foxy/setup.bash + source install/local_setup.bash + ``` ::: - :::: + :::: 1) 启动代理并设置以连接运行在模拟器上的 uXRCE-DDS客户端(Client): - ```sh - MicroXRCEAgent udp4 -p 8888 - ``` + ```sh + MicroXRCEAgent udp4 -p 8888 + ``` ## Starting Agent and Client @@ -466,15 +466,15 @@ Each (`topic`,`type`) pairs defines: 1. A new `publication`, `subscription`, or `subscriptions_multi`, depending on the list to which it is added. 2. The topic _base name_, which **must** coincide with the desired uORB topic name that you want to publish/subscribe. - It is identified by the last token in `topic:` that starts with `/` and does not contains any `/` in it. - `vehicle_odometry`, `vehicle_status` and `offboard_control_mode` are examples of base names. + It is identified by the last token in `topic:` that starts with `/` and does not contains any `/` in it. + `vehicle_odometry`, `vehicle_status` and `offboard_control_mode` are examples of base names. 3. The topic [namespace](https://design.ros2.org/articles/topic_and_service_names.html#namespaces). - By default it is set to: - - `/fmu/out/` for topics that are _published_ by PX4. - - `/fmu/in/` for topics that are _subscribed_ by PX4. + By default it is set to: + - `/fmu/out/` for topics that are _published_ by PX4. + - `/fmu/in/` for topics that are _subscribed_ by PX4. 4. The message type (`VehicleOdometry`, `VehicleStatus`, `OffboardControlMode`, etc.) and the ROS 2 package (`px4_msgs`) that is expected to provide the message definition. 5. **(Optional)**: An additional `rate_limit` field (only for publication entries), which specifies the maximum rate (Hz) at which messages will be published on this topic by PX4 to ROS 2. - If left unspecified, the maximum publication rate limit is set to 100 Hz. + If left unspecified, the maximum publication rate limit is set to 100 Hz. `subscriptions` and `subscriptions_multi` allow us to choose the uORB topic instance that ROS 2 topics are routed to: either a shared instance that may also be getting updates from internal PX4 uORB publishers, or a separate instance that is reserved for ROS2 publications, respectively. Without this mechanism all ROS 2 messages would be routed to the _same_ uORB topic instance (because ROS 2 does not have the concept of [multiple topic instances](../middleware/uorb.md#multi-instance)), and it would not be possible for PX4 subscribers to differentiate between streams from ROS 2 or PX4 publishers. diff --git a/docs/zh/modules/hello_sky.md b/docs/zh/modules/hello_sky.md index 24646f3517..02e2a97e82 100644 --- a/docs/zh/modules/hello_sky.md +++ b/docs/zh/modules/hello_sky.md @@ -28,151 +28,151 @@ This consists of a single _C_ file and a _cmake_ definition (which tells the too 1. Create a new directory **PX4-Autopilot/src/examples/px4_simple_app**. 2. Create a new C file in that directory named **px4_simple_app.c**: - - Copy in the default header to the top of the page. - 该注释应出现在所有贡献的文件中! + - Copy in the default header to the top of the page. + 该注释应出现在所有贡献的文件中! - ```c - /**************************************************************************** - * - * Copyright (c) 2012-2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - ``` + ```c + /**************************************************************************** + * + * Copyright (c) 2012-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + ``` - - 将下面的代码复制到头部注释的下方, - 该注释应出现在所有贡献的文件中! + - 将下面的代码复制到头部注释的下方, + 该注释应出现在所有贡献的文件中! - ```c - /** - * @file px4_simple_app.c - * Minimal application example for PX4 autopilot - * - * @author Example User - */ + ```c + /** + * @file px4_simple_app.c + * Minimal application example for PX4 autopilot + * + * @author Example User + */ - #include + #include - __EXPORT int px4_simple_app_main(int argc, char *argv[]); + __EXPORT int px4_simple_app_main(int argc, char *argv[]); - int px4_simple_app_main(int argc, char *argv[]) - { - PX4_INFO("Hello Sky!"); - return OK; - } - ``` + int px4_simple_app_main(int argc, char *argv[]) + { + PX4_INFO("Hello Sky!"); + return OK; + } + ``` - :::tip - The main function must be named `_main` and exported from the module as shown. + :::tip + The main function must be named `_main` and exported from the module as shown. ::: - :::tip - `PX4_INFO` is the equivalent of `printf` for the PX4 shell (included from **px4_platform_common/log.h**). - There are different log levels: `PX4_INFO`, `PX4_WARN`, `PX4_ERR`, `PX4_DEBUG`. - Warnings and errors are additionally added to the [ULog](../dev_log/ulog_file_format.md) and shown on [Flight Review](https://logs.px4.io/). + :::tip + `PX4_INFO` is the equivalent of `printf` for the PX4 shell (included from **px4_platform_common/log.h**). + There are different log levels: `PX4_INFO`, `PX4_WARN`, `PX4_ERR`, `PX4_DEBUG`. + Warnings and errors are additionally added to the [ULog](../dev_log/ulog_file_format.md) and shown on [Flight Review](https://logs.px4.io/). ::: 3. Create and open a new _cmake_ definition file named **CMakeLists.txt**. - 复制下面的文本: + 复制下面的文本: - ```cmake - ############################################################################ - # - # Copyright (c) 2015 PX4 Development Team. All rights reserved. - # - # Redistribution and use in source and binary forms, with or without - # modification, are permitted provided that the following conditions - # are met: - # - # 1. Redistributions of source code must retain the above copyright - # notice, this list of conditions and the following disclaimer. - # 2. Redistributions in binary form must reproduce the above copyright - # notice, this list of conditions and the following disclaimer in - # the documentation and/or other materials provided with the - # distribution. - # 3. Neither the name PX4 nor the names of its contributors may be - # used to endorse or promote products derived from this software - # without specific prior written permission. - # - # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - # OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - # AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - # POSSIBILITY OF SUCH DAMAGE. - # - ############################################################################ - px4_add_module( - MODULE examples__px4_simple_app - MAIN px4_simple_app - STACK_MAIN 2000 - SRCS - px4_simple_app.c - DEPENDS - ) - ``` + ```cmake + ############################################################################ + # + # Copyright (c) 2015 PX4 Development Team. All rights reserved. + # + # Redistribution and use in source and binary forms, with or without + # modification, are permitted provided that the following conditions + # are met: + # + # 1. Redistributions of source code must retain the above copyright + # notice, this list of conditions and the following disclaimer. + # 2. Redistributions in binary form must reproduce the above copyright + # notice, this list of conditions and the following disclaimer in + # the documentation and/or other materials provided with the + # distribution. + # 3. Neither the name PX4 nor the names of its contributors may be + # used to endorse or promote products derived from this software + # without specific prior written permission. + # + # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + # OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + # AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + # POSSIBILITY OF SUCH DAMAGE. + # + ############################################################################ + px4_add_module( + MODULE examples__px4_simple_app + MAIN px4_simple_app + STACK_MAIN 2000 + SRCS + px4_simple_app.c + DEPENDS + ) + ``` - The `px4_add_module()` method builds a static library from a module description. + The `px4_add_module()` method builds a static library from a module description. - - The `MODULE` block is the Firmware-unique name of the module (by convention the module name is prefixed by parent directories back to `src`). - - The `MAIN` block lists the entry point of the module, which registers the command with NuttX so that it can be called from the PX4 shell or SITL console. + - The `MODULE` block is the Firmware-unique name of the module (by convention the module name is prefixed by parent directories back to `src`). + - The `MAIN` block lists the entry point of the module, which registers the command with NuttX so that it can be called from the PX4 shell or SITL console. - :::tip - The `px4_add_module()` format is documented in [PX4-Autopilot/cmake/px4_add_module.cmake](https://github.com/PX4/PX4-Autopilot/blob/main/cmake/px4_add_module.cmake). + :::tip + The `px4_add_module()` format is documented in [PX4-Autopilot/cmake/px4_add_module.cmake](https://github.com/PX4/PX4-Autopilot/blob/main/cmake/px4_add_module.cmake). ::: - ::: info - If you specify `DYNAMIC` as an option to `px4_add_module`, a _shared library_ is created instead of a static library on POSIX platforms (these can be loaded without having to recompile PX4, and shared to others as binaries rather than source code). - Your app will not become a builtin command, but ends up in a separate file called `examples__px4_simple_app.px4mod`. - You can then run your command by loading the file at runtime using the `dyn` command: `dyn ./examples__px4_simple_app.px4mod` + ::: info + If you specify `DYNAMIC` as an option to `px4_add_module`, a _shared library_ is created instead of a static library on POSIX platforms (these can be loaded without having to recompile PX4, and shared to others as binaries rather than source code). + Your app will not become a builtin command, but ends up in a separate file called `examples__px4_simple_app.px4mod`. + You can then run your command by loading the file at runtime using the `dyn` command: `dyn ./examples__px4_simple_app.px4mod` ::: 4. Create and open a new _Kconfig_ definition file named **Kconfig** and define your symbol for naming (see [Kconfig naming convention](../hardware/porting_guide_config.md#px4-kconfig-symbol-naming-convention)). - 复制下面的文本: + 复制下面的文本: - ``` - menuconfig EXAMPLES_PX4_SIMPLE_APP - bool "px4_simple_app" - default n - ---help--- - Enable support for px4_simple_app - ``` + ``` + menuconfig EXAMPLES_PX4_SIMPLE_APP + bool "px4_simple_app" + default n + ---help--- + Enable support for px4_simple_app + ``` ## 编译应用程序/固件 diff --git a/docs/zh/modules/module_template.md b/docs/zh/modules/module_template.md index 1e1cd84ed1..4e41399412 100644 --- a/docs/zh/modules/module_template.md +++ b/docs/zh/modules/module_template.md @@ -22,27 +22,27 @@ PX4-Autopilot contains a template for writing a new application (module) that ru 总结: 1. Specify the dependency on the work queue library in the cmake definition file ([CMakeLists.txt](https://github.com/PX4/PX4-Autopilot/blob/main/src/examples/work_item/CMakeLists.txt)): - ``` - ... - DEPENDS - px4_work_queue - ``` + ``` + ... + DEPENDS + px4_work_queue + ``` 2. In addition to `ModuleBase`, the task should also derive from `ScheduledWorkItem` (included from [ScheduledWorkItem.hpp](https://github.com/PX4/PX4-Autopilot/blob/main/platforms/common/include/px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp)) 3. 在构造函数初始化中指定要添加任务的队列。 - The [work_item](https://github.com/PX4/PX4-Autopilot/blob/main/src/examples/work_item/WorkItemExample.cpp#L42) example adds itself to the `wq_configurations::test1` work queue as shown below: + The [work_item](https://github.com/PX4/PX4-Autopilot/blob/main/src/examples/work_item/WorkItemExample.cpp#L42) example adds itself to the `wq_configurations::test1` work queue as shown below: - ```cpp - WorkItemExample::WorkItemExample() : - ModuleParams(nullptr), - ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::test1) - { - } - ``` + ```cpp + WorkItemExample::WorkItemExample() : + ModuleParams(nullptr), + ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::test1) + { + } + ``` - ::: info - The available work queues (`wq_configurations`) are listed in [WorkQueueManager.hpp](https://github.com/PX4/PX4-Autopilot/blob/main/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp#L49). + ::: info + The available work queues (`wq_configurations`) are listed in [WorkQueueManager.hpp](https://github.com/PX4/PX4-Autopilot/blob/main/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp#L49). ::: diff --git a/docs/zh/payloads/generic_actuator_control.md b/docs/zh/payloads/generic_actuator_control.md index 03564f35ba..127d59c99f 100644 --- a/docs/zh/payloads/generic_actuator_control.md +++ b/docs/zh/payloads/generic_actuator_control.md @@ -60,7 +60,7 @@ To use a generic actuator in a mission: - Select the header on the waypoint mission editor to open the **Select Mission Command** editor. - Select the category **Advanced**, and then the **Set actuator** item (if the item is not present, try a more recent version of _QGroundControl_ or a daily build). - This will change the mission item type to "Set actuator". + This will change the mission item type to "Set actuator". 3. Select the actuators that are connected and set their values (these are normalized between -1 and 1). diff --git a/docs/zh/peripherals/gripper.md b/docs/zh/peripherals/gripper.md index a3f0ebbc88..d655300a25 100644 --- a/docs/zh/peripherals/gripper.md +++ b/docs/zh/peripherals/gripper.md @@ -75,13 +75,13 @@ To set the actuation timeout: - Run the `payload_deliverer` test in the QGC [MAVLink Shell](../debug/mavlink_shell.md): - ```sh - > payload_deliverer gripper_test - ``` + ```sh + > payload_deliverer gripper_test + ``` - ::: info - If you get an error message like "[payload_deliverer] not running", repeat the setup procedures above. - You might also run the `payload_deliverer start` command in the Nuttx shell. + ::: info + If you get an error message like "[payload_deliverer] not running", repeat the setup procedures above. + You might also run the `payload_deliverer start` command in the Nuttx shell. ::: diff --git a/docs/zh/peripherals/remote_id.md b/docs/zh/peripherals/remote_id.md index 711a8e47e3..b3188fb10c 100644 --- a/docs/zh/peripherals/remote_id.md +++ b/docs/zh/peripherals/remote_id.md @@ -245,11 +245,11 @@ If the Remote ID CAN node is present and the messages are not being received, th 2. Navigate to the [Application settings](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/settings_view/general.html): **Application Settings > General > Miscellaneous**. 3. Select `Enable Remote ID`. - The Remote ID tab should appear. + The Remote ID tab should appear. - ::: info - If this option is not present you may be in a very recent version of QGC. - In that case, open the view at: **Application Settings > Remote ID**. + ::: info + If this option is not present you may be in a very recent version of QGC. + In that case, open the view at: **Application Settings > Remote ID**. ::: diff --git a/docs/zh/releases/1.14.md b/docs/zh/releases/1.14.md index e240b36709..bf1e8982e4 100644 --- a/docs/zh/releases/1.14.md +++ b/docs/zh/releases/1.14.md @@ -72,18 +72,18 @@ For users upgrading from previous versions, please take a moment to review the f 1. The actuator changes require you to verify vehicle geometry and motors/servos mappings match your vehicle. In QGC, find the [Actuator Configuration Dashboard](../config/actuators.md), and make sure to confirm the airframe geometry matches actuals from your vehicle, as well as update motor and ensure motors and servos are mapped to outputs as they are wired to the frame and with the correct ESC type specified. Note: take advantage of the sliders in the UI. They can be used to confirm motor wiring. - We highly recommend running an [ESC Calibration](../advanced_config/esc_calibration.md) if using PWM ESC motors and then setting appropriate disarmed minimum and maximum values for the motors (in the actuator UI). + We highly recommend running an [ESC Calibration](../advanced_config/esc_calibration.md) if using PWM ESC motors and then setting appropriate disarmed minimum and maximum values for the motors (in the actuator UI). - The calibration is critical if you are using a custom mixer file or the airframe you assigned in an earlier version is not present in PX4 v1.14. + The calibration is critical if you are using a custom mixer file or the airframe you assigned in an earlier version is not present in PX4 v1.14. - However, an ESC Calibration is still recommended **even if** you are using an airframe that precisely matches a specific vehicle in the [Airframe Reference](../airframes/airframe_reference.md) (such as the [Holybro X500 V2](../airframes/airframe_reference.md#copter_quadrotor_x_holybro_x500_v2)) as your wiring and ESCs calibration may not match the defaults. + However, an ESC Calibration is still recommended **even if** you are using an airframe that precisely matches a specific vehicle in the [Airframe Reference](../airframes/airframe_reference.md) (such as the [Holybro X500 V2](../airframes/airframe_reference.md#copter_quadrotor_x_holybro_x500_v2)) as your wiring and ESCs calibration may not match the defaults. 2. Default disarmed PWM was changed from 900us to 1000us. - Verify if you previously used the default PWM disarmed values and if the changes impact your setup. - For details, you can find related information in the [step 7 of ESC calibration](../advanced_config/esc_calibration.md#steps) document. + Verify if you previously used the default PWM disarmed values and if the changes impact your setup. + For details, you can find related information in the [step 7 of ESC calibration](../advanced_config/esc_calibration.md#steps) document. 3. Fast-RTPS users must port their code to the new uXRCE-DDS interface. - Application code should only require minor modifications. These include (minimally): + Application code should only require minor modifications. These include (minimally): Modifying topic names to match the new naming pattern, which changed from `fmu//out` to `fmu/out/`, and [Adusting the QoS settings](../ros2/user_guide.md#ros-2-subscriber-qos-settings). diff --git a/docs/zh/ros/mavros_custom_messages.md b/docs/zh/ros/mavros_custom_messages.md index ed4f017440..946ab08715 100644 --- a/docs/zh/ros/mavros_custom_messages.md +++ b/docs/zh/ros/mavros_custom_messages.md @@ -110,7 +110,7 @@ Follow _Source Installation_ instructions from [mavlink/mavros](https://github.c - `PX4-Autopilot/src/modules/mavlink/mavlink/message_definitions/v1.0` - `workspace/src/mavlink/message_definitions/v1.0` - are exactly the same. + are exactly the same. ::: diff --git a/docs/zh/ros/mavros_installation.md b/docs/zh/ros/mavros_installation.md index 26add434e3..91c41c9fc5 100644 --- a/docs/zh/ros/mavros_installation.md +++ b/docs/zh/ros/mavros_installation.md @@ -148,21 +148,21 @@ Now you are ready to do the build: 2. 安装MAVROS最新的版本: - 发行版 / 稳定版 - ```sh - rosinstall_generator --upstream mavros | tee -a /tmp/mavros.rosinstall - ``` + ```sh + rosinstall_generator --upstream mavros | tee -a /tmp/mavros.rosinstall + ``` - Latest source - ```sh - rosinstall_generator --upstream-development mavros | tee -a /tmp/mavros.rosinstall - ``` + ```sh + rosinstall_generator --upstream-development mavros | tee -a /tmp/mavros.rosinstall + ``` - ```sh - # For fetching all the dependencies into your catkin_ws, - # just add '--deps' to the above scripts, E.g.: - # rosinstall_generator --upstream mavros --deps | tee -a /tmp/mavros.rosinstall - ``` + ```sh + # For fetching all the dependencies into your catkin_ws, + # just add '--deps' to the above scripts, E.g.: + # rosinstall_generator --upstream mavros --deps | tee -a /tmp/mavros.rosinstall + ``` 3. Create workspace & deps diff --git a/docs/zh/ros/offboard_control.md b/docs/zh/ros/offboard_control.md index ddb3d1caff..48cc2bf339 100644 --- a/docs/zh/ros/offboard_control.md +++ b/docs/zh/ros/offboard_control.md @@ -38,9 +38,9 @@ Enable MAVLink on the serial port that you connect to the companion computer (se 1. 一端连接飞控的 UART 2. 一端连接地面站电脑 - 参考电台包括: + 参考电台包括: - - [Digi International XBee Pro](https://www.digi.com/products/embedded-systems/digi-xbee/rf-modules/sub-1-ghz-rf-modules) + - [Digi International XBee Pro](https://www.digi.com/products/embedded-systems/digi-xbee/rf-modules/sub-1-ghz-rf-modules) [![Mermaid graph: mavlink channel](https://mermaid.ink/img/eyJjb2RlIjoiZ3JhcGggVEQ7XG4gIGduZFtHcm91bmQgU3RhdGlvbl0gLS1NQVZMaW5rLS0-IHJhZDFbR3JvdW5kIFJhZGlvXTtcbiAgcmFkMSAtLVJhZGlvUHJvdG9jb2wtLT4gcmFkMltWZWhpY2xlIFJhZGlvXTtcbiAgcmFkMiAtLU1BVkxpbmstLT4gYVtBdXRvcGlsb3RdOyIsIm1lcm1haWQiOnsidGhlbWUiOiJkZWZhdWx0In0sInVwZGF0ZUVkaXRvciI6ZmFsc2V9)](https://mermaid-js.github.io/mermaid-live-editor/#/edit/eyJjb2RlIjoiZ3JhcGggVEQ7XG4gIGduZFtHcm91bmQgU3RhdGlvbl0gLS1NQVZMaW5rLS0-IHJhZDFbR3JvdW5kIFJhZGlvXTtcbiAgcmFkMSAtLVJhZGlvUHJvdG9jb2wtLT4gcmFkMltWZWhpY2xlIFJhZGlvXTtcbiAgcmFkMiAtLU1BVkxpbmstLT4gYVtBdXRvcGlsb3RdOyIsIm1lcm1haWQiOnsidGhlbWUiOiJkZWZhdWx0In0sInVwZGF0ZUVkaXRvciI6ZmFsc2V9) diff --git a/docs/zh/ros2/px4_ros2_control_interface.md b/docs/zh/ros2/px4_ros2_control_interface.md index a31d7d5880..2fcce99656 100644 --- a/docs/zh/ros2/px4_ros2_control_interface.md +++ b/docs/zh/ros2/px4_ros2_control_interface.md @@ -108,92 +108,92 @@ The following steps are required to get started: 2. Clone the repository into the workspace: - ```sh - cd $ros_workspace/src - git clone --recursive https://github.com/Auterion/px4-ros2-interface-lib - ``` + ```sh + cd $ros_workspace/src + git clone --recursive https://github.com/Auterion/px4-ros2-interface-lib + ``` - ::: info - To ensure compatibility, use the latest _main_ branches for PX4, _px4_msgs_ and the library. - See also [here](https://github.com/Auterion/px4-ros2-interface-lib#compatibility-with-px4). + ::: info + To ensure compatibility, use the latest _main_ branches for PX4, _px4_msgs_ and the library. + See also [here](https://github.com/Auterion/px4-ros2-interface-lib#compatibility-with-px4). ::: 3. Build the workspace: - ```sh - cd .. - colcon build - source install/setup.bash - ``` + ```sh + cd .. + colcon build + source install/setup.bash + ``` 4. In a different shell, start PX4 SITL: - ```sh - cd $px4-autopilot - make px4_sitl gazebo-classic - ``` + ```sh + cd $px4-autopilot + make px4_sitl gazebo-classic + ``` - (here we use Gazebo-Classic, but you can use any model or simulator) + (here we use Gazebo-Classic, but you can use any model or simulator) 5. Run the micro XRCE agent in a new shell (you can keep it running afterward): - ```sh - MicroXRCEAgent udp4 -p 8888 - ``` + ```sh + MicroXRCEAgent udp4 -p 8888 + ``` 6. Start QGroundControl. - ::: info - Use QGroundControl Daily, which supports dynamically updating the list of modes. + ::: info + Use QGroundControl Daily, which supports dynamically updating the list of modes. ::: 7. Back in the ROS 2 terminal, run one of the example modes: - ```sh - ros2 run example_mode_manual_cpp example_mode_manual - ``` + ```sh + ros2 run example_mode_manual_cpp example_mode_manual + ``` - You should get an output like this showing 'My Manual Mode' mode being registered: + You should get an output like this showing 'My Manual Mode' mode being registered: - ```sh - [DEBUG] [example_mode_manual]: Checking message compatibility... - [DEBUG] [example_mode_manual]: Subscriber found, continuing - [DEBUG] [example_mode_manual]: Publisher found, continuing - [DEBUG] [example_mode_manual]: Registering 'My Manual Mode' (arming check: 1, mode: 1, mode executor: 0) - [DEBUG] [example_mode_manual]: Subscriber found, continuing - [DEBUG] [example_mode_manual]: Publisher found, continuing - [DEBUG] [example_mode_manual]: Got RegisterExtComponentReply - [DEBUG] [example_mode_manual]: Arming check request (id=1, only printed once) - ``` + ```sh + [DEBUG] [example_mode_manual]: Checking message compatibility... + [DEBUG] [example_mode_manual]: Subscriber found, continuing + [DEBUG] [example_mode_manual]: Publisher found, continuing + [DEBUG] [example_mode_manual]: Registering 'My Manual Mode' (arming check: 1, mode: 1, mode executor: 0) + [DEBUG] [example_mode_manual]: Subscriber found, continuing + [DEBUG] [example_mode_manual]: Publisher found, continuing + [DEBUG] [example_mode_manual]: Got RegisterExtComponentReply + [DEBUG] [example_mode_manual]: Arming check request (id=1, only printed once) + ``` 8. On the PX4 shell, you can check that PX4 registered the new mode: - ```sh - commander status - ``` + ```sh + commander status + ``` - The output should contain: + The output should contain: - ```plain - INFO [commander] Disarmed - INFO [commander] navigation mode: Position - INFO [commander] user intended navigation mode: Position - INFO [commander] in failsafe: no - INFO [commander] External Mode 1: nav_state: 23, name: My Manual Mode - ``` + ```plain + INFO [commander] Disarmed + INFO [commander] navigation mode: Position + INFO [commander] user intended navigation mode: Position + INFO [commander] in failsafe: no + INFO [commander] External Mode 1: nav_state: 23, name: My Manual Mode + ``` 9. At this point you should be able to see the mode in QGroundControl as well: - ![QGC Modes](../../assets/middleware/ros2/px4_ros2_interface_lib/qgc_modes.png) + ![QGC Modes](../../assets/middleware/ros2/px4_ros2_interface_lib/qgc_modes.png) 10. Select the mode, make sure you have a manual control source (physical or virtual joystick), and arm the vehicle. - The mode will then activate, and it should print the following output: + The mode will then activate, and it should print the following output: - ```sh - [DEBUG] [example_mode_manual]: Mode 'My Manual Mode' activated - ``` + ```sh + [DEBUG] [example_mode_manual]: Mode 'My Manual Mode' activated + ``` 11. Now you are ready to create your own mode. @@ -419,7 +419,7 @@ This setpoint is streamed to the PX4 [_FwLateralLongitudinalControl_ module](../ To control the vehicle, at least one lateral **and** one longitudinal setpoint must be provided: 1. Of the longitudinal inputs: either `altitude` or `height_rate` must be finite to control vertical motion. - If both are set to `NAN`, the vehicle will maintain its current altitude. + If both are set to `NAN`, the vehicle will maintain its current altitude. 2. Of the lateral inputs: at least one of `course`, `airspeed_direction`, or `lateral_acceleration` must be finite. For a detailed description of the controllable parameters, please refer to message definitions ([FixedWingLateralSetpoint](../msg_docs/FixedWingLateralSetpoint.md) and [FixedWingLongitudinalSetpoint](../msg_docs/FixedWingLongitudinalSetpoint.md)). @@ -568,24 +568,24 @@ Commanding transitions externally makes the user partially responsible for ensur 3. To command a transition, you can use the `toMulticopter()` or `toFixedwing()` methods on your VTOL object to set the desired state. 4. During transition, send the following combination of setpoints: - ```cpp - // Assuming the instance of the px4_ros2::VTOL object is called vtol + ```cpp + // Assuming the instance of the px4_ros2::VTOL object is called vtol - // Send TrajectorySetpointType as follows: - Eigen::Vector3f acceleration_sp = vtol.computeAccelerationSetpointDuringTransition(); - Eigen::Vector3f velocity_sp{NAN, NAN, 0.f}; + // Send TrajectorySetpointType as follows: + Eigen::Vector3f acceleration_sp = vtol.computeAccelerationSetpointDuringTransition(); + Eigen::Vector3f velocity_sp{NAN, NAN, 0.f}; - _trajectory_setpoint->update(velocity_sp, acceleration_sp); + _trajectory_setpoint->update(velocity_sp, acceleration_sp); - // Send FwLateralLongitudinalSetpointType with lateral input to realign vehicle as desired + // Send FwLateralLongitudinalSetpointType with lateral input to realign vehicle as desired - float course_sp = 0.F; // North + float course_sp = 0.F; // North - _fw_lateral_longitudinal_setpoint->updateWithAltitude(NAN, course_sp) - ``` + _fw_lateral_longitudinal_setpoint->updateWithAltitude(NAN, course_sp) + ``` - This will ensure that the transition is handled properly within PX4. - You can optionally pass a deceleration setpoint to `computeAccelerationSetpointDuringTransition()` to be used during back-transitions. + This will ensure that the transition is handled properly within PX4. + You can optionally pass a deceleration setpoint to `computeAccelerationSetpointDuringTransition()` to be used during back-transitions. To check the current state of the vehicle, use the `getCurrentState()` method on your `px4_ros2::VTOL` object. @@ -598,7 +598,7 @@ If you want to control an independent actuator (a servo), follow these steps: 1. [Configure the output](../payloads/generic_actuator_control.md#generic-actuator-control-with-mavlink). 2. Create an instance of [px4_ros2::PeripheralActuatorControls](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1PeripheralActuatorControls.html) in the constructor of your mode. 3. Call the `set()` method to control the actuator(s). - This can be done independently of any active setpoints. + This can be done independently of any active setpoints. ### Telemetry diff --git a/docs/zh/ros2/px4_ros2_msg_translation_node.md b/docs/zh/ros2/px4_ros2_msg_translation_node.md index 2e999b28c1..253ae12527 100644 --- a/docs/zh/ros2/px4_ros2_msg_translation_node.md +++ b/docs/zh/ros2/px4_ros2_msg_translation_node.md @@ -27,36 +27,36 @@ The following steps describe how to install and run the translation node on your 1. (Optional) Create a new ROS 2 workspace in which to build the message translation node and its dependencies: - ```sh - mkdir -p /path/to/ros_ws/src - ``` + ```sh + mkdir -p /path/to/ros_ws/src + ``` 2. Run the following helper script to copy the message definitions and translation node into your ROS workspace directory. - ```sh - cd /path/to/ros_ws - /path/to/PX4-Autopilot/Tools/copy_to_ros_ws.sh . - ``` + ```sh + cd /path/to/ros_ws + /path/to/PX4-Autopilot/Tools/copy_to_ros_ws.sh . + ``` 3. Build and source the workspace. - ```sh - colcon build - source /path/to/ros_ws/install/setup.bash - ``` + ```sh + colcon build + source /path/to/ros_ws/install/setup.bash + ``` 4. Finally, run the translation node. - ```sh - ros2 run translation_node translation_node_bin - ``` + ```sh + ros2 run translation_node translation_node_bin + ``` - You should see an output similar to: + You should see an output similar to: - ```sh - [INFO] [1734525720.729530513] [translation_node]: Registered pub/sub topics and versions: - [INFO] [1734525720.729594413] [translation_node]: Registered services and versions: - ``` + ```sh + [INFO] [1734525720.729530513] [translation_node]: Registered pub/sub topics and versions: + [INFO] [1734525720.729594413] [translation_node]: Registered services and versions: + ``` With the translation node running, any simultaneously running ROS 2 application designed to communicate with PX4 can do so, as long as it uses message versions recognized by the node. The translation node will print a warning if it encounters an unknown topic version. @@ -295,111 +295,111 @@ The example describes the process of updating the `VehicleAttitude` message defi 1. **Create an Archived Definition of the Current Versioned Message** - Copy the versioned `.msg` topic message file (or `.srv` service message file) to `px4_msgs_old/msg/` (or `px4_msgs_old/srv/`), and append its message version to the file name. + Copy the versioned `.msg` topic message file (or `.srv` service message file) to `px4_msgs_old/msg/` (or `px4_msgs_old/srv/`), and append its message version to the file name. - For example:
- Copy `msg/versioned/VehicleAttitude.msg` → `msg/versioned/px4_msgs_old/msg/VehicleAttitudeV3.msg` + For example:
+ Copy `msg/versioned/VehicleAttitude.msg` → `msg/versioned/px4_msgs_old/msg/VehicleAttitudeV3.msg` 2. **Update Translation References to the Archived Definition** - Update the existing translations header files `msg/translation_node/translations/*.h` to reference the newly archived message definition. + Update the existing translations header files `msg/translation_node/translations/*.h` to reference the newly archived message definition. - For example, update references in those files:
+ For example, update references in those files:
- - Replace `px4_msgs::msg::VehicleAttitude` → `px4_msgs_old::msg::VehicleAttitudeV3` - - Replace `#include ` → `#include ` + - Replace `px4_msgs::msg::VehicleAttitude` → `px4_msgs_old::msg::VehicleAttitudeV3` + - Replace `#include ` → `#include ` 3. **Update the Versioned Definition** - Update the versioned `.msg` topic message file (or `.srv` service message file) with required changes. + Update the versioned `.msg` topic message file (or `.srv` service message file) with required changes. - First increment the `MESSAGE_VERSION` field. - Then update the message fields that prompted the version change. + First increment the `MESSAGE_VERSION` field. + Then update the message fields that prompted the version change. - For example, update `msg/versioned/VehicleAttitude.msg` from: + For example, update `msg/versioned/VehicleAttitude.msg` from: - ```txt - uint32 MESSAGE_VERSION = 3 - uint64 timestamp - ... - ``` + ```txt + uint32 MESSAGE_VERSION = 3 + uint64 timestamp + ... + ``` - to + to - ```txt - uint32 MESSAGE_VERSION = 4 # Increment - uint64 timestamp - float32 new_field # Make definition changes - ... - ``` + ```txt + uint32 MESSAGE_VERSION = 4 # Increment + uint64 timestamp + float32 new_field # Make definition changes + ... + ``` 4. **Add a New Translation Header** - Add a new version translation to bridge the archived version and the updated current version, by creating a new translation header. + Add a new version translation to bridge the archived version and the updated current version, by creating a new translation header. - For example, create a direct translation header `translation_node/translations/translation_vehicle_attitude_v4.h`: + For example, create a direct translation header `translation_node/translations/translation_vehicle_attitude_v4.h`: - ```c++ - // Translate VehicleAttitude v3 <--> v4 - #include - #include + ```c++ + // Translate VehicleAttitude v3 <--> v4 + #include + #include - class VehicleAttitudeV4Translation { - public: - using MessageOlder = px4_msgs_old::msg::VehicleAttitudeV3; - static_assert(MessageOlder::MESSAGE_VERSION == 3); + class VehicleAttitudeV4Translation { + public: + using MessageOlder = px4_msgs_old::msg::VehicleAttitudeV3; + static_assert(MessageOlder::MESSAGE_VERSION == 3); - using MessageNewer = px4_msgs::msg::VehicleAttitude; - static_assert(MessageNewer::MESSAGE_VERSION == 4); + using MessageNewer = px4_msgs::msg::VehicleAttitude; + static_assert(MessageNewer::MESSAGE_VERSION == 4); - static constexpr const char* kTopic = "fmu/out/vehicle_attitude"; + static constexpr const char* kTopic = "fmu/out/vehicle_attitude"; - static void fromOlder(const MessageOlder &msg_older, MessageNewer &msg_newer) { - msg_newer.timestamp = msg_older.timestamp; - msg_newer.timestamp_sample = msg_older.timestamp_sample; - msg_newer.q[0] = msg_older.q[0]; - msg_newer.q[1] = msg_older.q[1]; - msg_newer.q[2] = msg_older.q[2]; - msg_newer.q[3] = msg_older.q[3]; - msg_newer.delta_q_reset = msg_older.delta_q_reset; - msg_newer.quat_reset_counter = msg_older.quat_reset_counter; + static void fromOlder(const MessageOlder &msg_older, MessageNewer &msg_newer) { + msg_newer.timestamp = msg_older.timestamp; + msg_newer.timestamp_sample = msg_older.timestamp_sample; + msg_newer.q[0] = msg_older.q[0]; + msg_newer.q[1] = msg_older.q[1]; + msg_newer.q[2] = msg_older.q[2]; + msg_newer.q[3] = msg_older.q[3]; + msg_newer.delta_q_reset = msg_older.delta_q_reset; + msg_newer.quat_reset_counter = msg_older.quat_reset_counter; - // Populate `new_field` with some value - msg_newer.new_field = -1; - } + // Populate `new_field` with some value + msg_newer.new_field = -1; + } - static void toOlder(const MessageNewer &msg_newer, MessageOlder &msg_older) { - msg_older.timestamp = msg_newer.timestamp; - msg_older.timestamp_sample = msg_newer.timestamp_sample; - msg_older.q[0] = msg_newer.q[0]; - msg_older.q[1] = msg_newer.q[1]; - msg_older.q[2] = msg_newer.q[2]; - msg_older.q[3] = msg_newer.q[3]; - msg_older.delta_q_reset = msg_newer.delta_q_reset; - msg_older.quat_reset_counter = msg_newer.quat_reset_counter; + static void toOlder(const MessageNewer &msg_newer, MessageOlder &msg_older) { + msg_older.timestamp = msg_newer.timestamp; + msg_older.timestamp_sample = msg_newer.timestamp_sample; + msg_older.q[0] = msg_newer.q[0]; + msg_older.q[1] = msg_newer.q[1]; + msg_older.q[2] = msg_newer.q[2]; + msg_older.q[3] = msg_newer.q[3]; + msg_older.delta_q_reset = msg_newer.delta_q_reset; + msg_older.quat_reset_counter = msg_newer.quat_reset_counter; - // Discards `new_field` from MessageNewer - } - }; + // Discards `new_field` from MessageNewer + } + }; - REGISTER_TOPIC_TRANSLATION_DIRECT(VehicleAttitudeV4Translation); - ``` + REGISTER_TOPIC_TRANSLATION_DIRECT(VehicleAttitudeV4Translation); + ``` - Version translation templates are provided here: + Version translation templates are provided here: - - [Direct Topic Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_direct_v1.h) - - [Generic Topic Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_multi_v2.h) - - [Direct Service Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_service_v1.h) + - [Direct Topic Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_direct_v1.h) + - [Generic Topic Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_multi_v2.h) + - [Direct Service Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_service_v1.h) 5. **Include New Headers in `all_translations.h`** - Add all newly created headers to [`translations/all_translations.h`](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/all_translations.h) so that the translation node can find them. + Add all newly created headers to [`translations/all_translations.h`](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/all_translations.h) so that the translation node can find them. - For example, append the following line to `all_translation.h`: + For example, append the following line to `all_translation.h`: - ```c++ - #include "translation_vehicle_attitude_v4.h" - ``` + ```c++ + #include "translation_vehicle_attitude_v4.h" + ``` Note that in the example above and in most cases, step 4 only requires the developer to create a direct translation for the definition change. This is because the changes only involved a single message. diff --git a/docs/zh/ros2/px4_ros2_navigation_interface.md b/docs/zh/ros2/px4_ros2_navigation_interface.md index f96d2683fe..e0cab8d948 100644 --- a/docs/zh/ros2/px4_ros2_navigation_interface.md +++ b/docs/zh/ros2/px4_ros2_navigation_interface.md @@ -22,80 +22,80 @@ The following steps are required to get started: 2. Clone the repository into the workspace: - ```sh - cd $ros_workspace/src - git clone --recursive https://github.com/Auterion/px4-ros2-interface-lib - ``` + ```sh + cd $ros_workspace/src + git clone --recursive https://github.com/Auterion/px4-ros2-interface-lib + ``` - ::: info - To ensure compatibility, use the latest _main_ branches for PX4, _px4_msgs_ and the library. - See also [here](https://github.com/Auterion/px4-ros2-interface-lib#compatibility-with-px4). + ::: info + To ensure compatibility, use the latest _main_ branches for PX4, _px4_msgs_ and the library. + See also [here](https://github.com/Auterion/px4-ros2-interface-lib#compatibility-with-px4). ::: 3. Build the workspace: - ```sh - cd .. - colcon build - ``` + ```sh + cd .. + colcon build + ``` 4. In a different shell, start PX4 SITL: - ```sh - cd $px4-autopilot - make px4_sitl gazebo-classic - ``` + ```sh + cd $px4-autopilot + make px4_sitl gazebo-classic + ``` - (here we use Gazebo-Classic, but you can use any model or simulator) + (here we use Gazebo-Classic, but you can use any model or simulator) 5. In yet a different shell, run the micro XRCE agent (you can keep it running afterward): - ```sh - MicroXRCEAgent udp4 -p 8888 - ``` + ```sh + MicroXRCEAgent udp4 -p 8888 + ``` 6. Back in the ROS 2 terminal, source the workspace you just built (in step 3) and run the [global_navigation](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/navigation/global_navigation) example, which periodically sends dummy global position updates: - ```sh - source install/setup.bash - ros2 run example_global_navigation_cpp example_global_navigation - ``` + ```sh + source install/setup.bash + ros2 run example_global_navigation_cpp example_global_navigation + ``` - You should get an output like this showing that the global interface is successfully sending position updates: + You should get an output like this showing that the global interface is successfully sending position updates: - ```sh - [INFO] [1702030701.836897756] [example_global_navigation_node]: example_global_navigation_node running! - [DEBUG] [1702030702.837279784] [example_global_navigation_node]: Successfully sent position update to navigation interface. - [DEBUG] [1702030703.837223884] [example_global_navigation_node]: Successfully sent position update to navigation interface. - ``` + ```sh + [INFO] [1702030701.836897756] [example_global_navigation_node]: example_global_navigation_node running! + [DEBUG] [1702030702.837279784] [example_global_navigation_node]: Successfully sent position update to navigation interface. + [DEBUG] [1702030703.837223884] [example_global_navigation_node]: Successfully sent position update to navigation interface. + ``` 7. In the PX4 shell, you can check that PX4 receives global position updates: - ```sh - listener aux_global_position - ``` + ```sh + listener aux_global_position + ``` - The output should look like: + The output should look like: - ```sh - TOPIC: aux_global_position - aux_global_position - timestamp: 46916000 (0.528000 seconds ago) - timestamp_sample: 46916000 (0 us before timestamp) - lat: 12.343210 - lon: 23.454320 - alt: 12.40000 - alt_ellipsoid: 0.00000 - delta_alt: 0.00000 - eph: 0.31623 - epv: 0.44721 - terrain_alt: 0.00000 - lat_lon_reset_counter: 0 - alt_reset_counter: 0 - terrain_alt_valid: False - dead_reckoning: False - ``` + ```sh + TOPIC: aux_global_position + aux_global_position + timestamp: 46916000 (0.528000 seconds ago) + timestamp_sample: 46916000 (0 us before timestamp) + lat: 12.343210 + lon: 23.454320 + alt: 12.40000 + alt_ellipsoid: 0.00000 + delta_alt: 0.00000 + eph: 0.31623 + epv: 0.44721 + terrain_alt: 0.00000 + lat_lon_reset_counter: 0 + alt_reset_counter: 0 + terrain_alt_valid: False + dead_reckoning: False + ``` 8. Now you are ready to use the navigation interface to send your own position updates. diff --git a/docs/zh/ros2/user_guide.md b/docs/zh/ros2/user_guide.md index 222ea662fa..0a8bff0037 100644 --- a/docs/zh/ros2/user_guide.md +++ b/docs/zh/ros2/user_guide.md @@ -97,48 +97,48 @@ To install ROS 2 and its dependencies: 1. Install ROS 2. - :::: tabs + :::: tabs - ::: tab humble - To install ROS 2 "Humble" on Ubuntu 22.04: + ::: tab humble + To install ROS 2 "Humble" on Ubuntu 22.04: - ```sh - sudo apt update && sudo apt install locales - sudo locale-gen en_US en_US.UTF-8 - sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 - export LANG=en_US.UTF-8 - sudo apt install software-properties-common - sudo add-apt-repository universe - sudo apt update && sudo apt install curl -y - sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg - echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null - sudo apt update && sudo apt upgrade -y - sudo apt install ros-humble-desktop - sudo apt install ros-dev-tools - source /opt/ros/humble/setup.bash && echo "source /opt/ros/humble/setup.bash" >> .bashrc - ``` + ```sh + sudo apt update && sudo apt install locales + sudo locale-gen en_US en_US.UTF-8 + sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 + export LANG=en_US.UTF-8 + sudo apt install software-properties-common + sudo add-apt-repository universe + sudo apt update && sudo apt install curl -y + sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg + echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null + sudo apt update && sudo apt upgrade -y + sudo apt install ros-humble-desktop + sudo apt install ros-dev-tools + source /opt/ros/humble/setup.bash && echo "source /opt/ros/humble/setup.bash" >> .bashrc + ``` - The instructions above are reproduced from the official installation guide: [Install ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html). - You can install _either_ the desktop (`ros-humble-desktop`) _or_ bare-bones versions (`ros-humble-ros-base`), _and_ the development tools (`ros-dev-tools`). + The instructions above are reproduced from the official installation guide: [Install ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html). + You can install _either_ the desktop (`ros-humble-desktop`) _or_ bare-bones versions (`ros-humble-ros-base`), _and_ the development tools (`ros-dev-tools`). ::: - ::: tab foxy - To install ROS 2 "Foxy" on Ubuntu 20.04: + ::: tab foxy + To install ROS 2 "Foxy" on Ubuntu 20.04: - - Follow the official installation guide: [Install ROS 2 Foxy](https://docs.ros.org/en/foxy/Installation/Ubuntu-Install-Debians.html). + - Follow the official installation guide: [Install ROS 2 Foxy](https://docs.ros.org/en/foxy/Installation/Ubuntu-Install-Debians.html). - You can install _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), _and_ the development tools (`ros-dev-tools`). + You can install _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), _and_ the development tools (`ros-dev-tools`). ::: - :::: + :::: 2. Some Python dependencies must also be installed (using **`pip`** or **`apt`**): - ```sh - pip install --user -U empy==3.3.4 pyros-genmsg setuptools - ``` + ```sh + pip install --user -U empy==3.3.4 pyros-genmsg setuptools + ``` ### Setup Micro XRCE-DDS Agent & Client @@ -155,22 +155,22 @@ To setup and start the agent: 2. 输入以下命令从仓库获取源代码并构建代理(Agent): - ```sh - git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git - cd Micro-XRCE-DDS-Agent - mkdir build - cd build - cmake .. - make - sudo make install - sudo ldconfig /usr/local/lib/ - ``` + ```sh + git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git + cd Micro-XRCE-DDS-Agent + mkdir build + cd build + cmake .. + make + sudo make install + sudo ldconfig /usr/local/lib/ + ``` 3. 启动代理并设置以连接运行在模拟器上的 uXRCE-DDS客户端(Client): - ```sh - MicroXRCEAgent udp4 -p 8888 - ``` + ```sh + MicroXRCEAgent udp4 -p 8888 + ``` The agent is now running, but you won't see much until we start PX4 (in the next step). @@ -187,31 +187,31 @@ To start the simulator (and client): 1. Open a new terminal in the root of the **PX4 Autopilot** repo that was installed above. - :::: tabs + :::: tabs - ::: tab humble + ::: tab humble - - Start a PX4 [Gazebo](../sim_gazebo_gz/index.md) simulation using: + - Start a PX4 [Gazebo](../sim_gazebo_gz/index.md) simulation using: - ```sh - make px4_sitl gz_x500 - ``` + ```sh + make px4_sitl gz_x500 + ``` ::: - ::: tab foxy + ::: tab foxy - - Start a PX4 [Gazebo Classic](../sim_gazebo_classic/index.md) simulation using: + - Start a PX4 [Gazebo Classic](../sim_gazebo_classic/index.md) simulation using: - ```sh - make px4_sitl gazebo-classic - ``` + ```sh + make px4_sitl gazebo-classic + ``` ::: - :::: + :::: The agent and client are now running they should connect. @@ -261,52 +261,52 @@ To create and build the workspace: 2. Create and navigate into a new workspace directory using: - ```sh - mkdir -p ~/ws_sensor_combined/src/ - cd ~/ws_sensor_combined/src/ - ``` + ```sh + mkdir -p ~/ws_sensor_combined/src/ + cd ~/ws_sensor_combined/src/ + ``` - ::: info - A naming convention for workspace folders can make it easier to manage workspaces. + ::: info + A naming convention for workspace folders can make it easier to manage workspaces. ::: 3. Clone the example repository and [px4_msgs](https://github.com/PX4/px4_msgs) to the `/src` directory (the `main` branch is cloned by default, which corresponds to the version of PX4 we are running): - ```sh - git clone https://github.com/PX4/px4_msgs.git - git clone https://github.com/PX4/px4_ros_com.git - ``` + ```sh + git clone https://github.com/PX4/px4_msgs.git + git clone https://github.com/PX4/px4_ros_com.git + ``` 4. Source the ROS 2 development environment into the current terminal and compile the workspace using `colcon`: - :::: tabs + :::: tabs - ::: tab humble + ::: tab humble - ```sh - cd .. - source /opt/ros/humble/setup.bash - colcon build - ``` + ```sh + cd .. + source /opt/ros/humble/setup.bash + colcon build + ``` ::: - ::: tab foxy + ::: tab foxy - ```sh - cd .. - source /opt/ros/foxy/setup.bash - colcon build - ``` + ```sh + cd .. + source /opt/ros/foxy/setup.bash + colcon build + ``` ::: - :::: + :::: - This builds all the folders under `/src` using the sourced toolchain. + This builds all the folders under `/src` using the sourced toolchain. #### Running the Example @@ -322,42 +322,42 @@ In a new terminal: 1. Navigate into the top level of your workspace directory and source the ROS 2 environment (in this case "Humble"): - :::: tabs + :::: tabs - ::: tab humble + ::: tab humble - ```sh - cd ~/ws_sensor_combined/ - source /opt/ros/humble/setup.bash - ``` + ```sh + cd ~/ws_sensor_combined/ + source /opt/ros/humble/setup.bash + ``` ::: - ::: tab foxy + ::: tab foxy - ```sh - cd ~/ws_sensor_combined/ - source /opt/ros/foxy/setup.bash - ``` + ```sh + cd ~/ws_sensor_combined/ + source /opt/ros/foxy/setup.bash + ``` ::: - :::: + :::: 2. Source the `local_setup.bash`. - ```sh - source install/local_setup.bash - ``` + ```sh + source install/local_setup.bash + ``` 3. Now launch the example. - Note here that we use `ros2 launch`, which is described below. + Note here that we use `ros2 launch`, which is described below. - ```sh - ros2 launch px4_ros_com sensor_combined_listener.launch.py - ``` + ```sh + ros2 launch px4_ros_com sensor_combined_listener.launch.py + ``` If this is working you should see data being printed on the terminal/console where you launched the ROS listener: @@ -385,18 +385,18 @@ If you were to use incompatible [message versions](../middleware/uorb.md#message 1. Include the [Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) into the example workspace or a separate workspace by running the following script: - ```sh - cd /path/to/ros_ws - /path/to/PX4-Autopilot/Tools/copy_to_ros_ws.sh . - ``` + ```sh + cd /path/to/ros_ws + /path/to/PX4-Autopilot/Tools/copy_to_ros_ws.sh . + ``` 2. Build and run the translation node: - ```sh - colcon build - source install/local_setup.bash - ros2 run translation_node translation_node_bin - ``` + ```sh + colcon build + source install/local_setup.bash + ros2 run translation_node translation_node_bin + ``` ## Controlling a Vehicle diff --git a/docs/zh/sensor/inertial_navigation_systems.md b/docs/zh/sensor/inertial_navigation_systems.md index 29faaa7347..d5d5d675ea 100644 --- a/docs/zh/sensor/inertial_navigation_systems.md +++ b/docs/zh/sensor/inertial_navigation_systems.md @@ -2,13 +2,32 @@ PX4 typically runs on flight controllers that include an IMU, such as the Pixhawk series, and fuse the sensor data along with GNSS information in the EKF2 estimator to determine vehicle attitude, heading, position, and velocity. -However PX4 can also use some INS devices as either sources of raw data, or as an external estimator, replacing the EKF. +However PX4 can also use some INS devices as either sources of raw data, or as an external estimator, replacing EKF2. -Systems that can be used in this way include: +## Supported INS Systems + +INS systems that can be used as a replacement for EKF2 in PX4: - [InertialLabs](../sensor/inertiallabs.md) - [VectorNav](../sensor/vectornav.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data. +## PX4 Firmware + +The driver module for your INS system may not be included in the PX4 firmware for your flight controller by default. + +You can check by searching the [default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/fmu-v6c/default.px4board#L25) configuration file for your target board for either: + +- `CONFIG_COMMON_INS`, which includes drivers for [all INS systems](https://github.com/PX4/PX4-Autopilot/blob/main/src/drivers/ins/Kconfig). +- The key for the particular INS system you are using, such as: + - `CONFIG_DRIVERS_INS_ILABS` + - `CONFIG_DRIVERS_INS_MICROSTRAIN` + - `CONFIG_DRIVERS_INS_VECTORNAV` + +If the required key is not present you can include the module in firmware by adding the key to the `default.px4board` file, or using the [kconfig board configuration tool](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) and then select the driver you want (`Drivers -> INS`). +Note that if you're working on a flight controller where flash memory is limited, you're better off installing just the modules you need. + +You will then need to rebuild the firmware. + ## Glossary ### Inertial Measurement Unit (IMU) diff --git a/docs/zh/sensor/inertiallabs.md b/docs/zh/sensor/inertiallabs.md index 00f77141a6..68e231041b 100644 --- a/docs/zh/sensor/inertiallabs.md +++ b/docs/zh/sensor/inertiallabs.md @@ -57,11 +57,11 @@ To use the Inertial Labs driver: - For external INS, set [ILABS_MODE](../advanced_config/parameter_reference.md#ILABS_MODE) to `INS`. - For raw inertial sensors, set [ILABS_MODE](../advanced_config/parameter_reference.md#ILABS_MODE) to `Sensors Only`. - You can then prioritize inertial labs sensors using [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO), [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO), [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO), [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO), where `n` is the instance number of the IMU component (0, 1, etc.). + You can then prioritize inertial labs sensors using [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO), [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO), [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO), [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO), where `n` is the instance number of the IMU component (0, 1, etc.). - ::: tip - In most cases the external IMU is the highest-numbered. - You can get a list of the IMU components available using [`uorb top -1`](../middleware/uorb.md#uorb-top-command), you can differentiate between them using the [`listener`](../modules/modules_command.md#listener) command and looking through the data, or just the rates. + ::: tip + In most cases the external IMU is the highest-numbered. + You can get a list of the IMU components available using [`uorb top -1`](../middleware/uorb.md#uorb-top-command), you can differentiate between them using the [`listener`](../modules/modules_command.md#listener) command and looking through the data, or just the rates. ::: diff --git a/docs/zh/sensor/rangefinders.md b/docs/zh/sensor/rangefinders.md index f5d645cb40..0ecf81df77 100644 --- a/docs/zh/sensor/rangefinders.md +++ b/docs/zh/sensor/rangefinders.md @@ -146,11 +146,11 @@ To view the rangefinder output: 1. Open the menu **Q > Select Tool > Analyze Tools**: - ![Menu for QGC Analyze Tool](../../assets/qgc/analyze/menu_analyze_tool.png) + ![Menu for QGC Analyze Tool](../../assets/qgc/analyze/menu_analyze_tool.png) 2. Select the message `DISTANCE_SENSOR`, and then check the plot checkbox against `current_distance`. - The tool will then plot the result: - ![QGC Analyze DISTANCE_SENSOR value](../../assets/qgc/analyze/qgc_analyze_tool_distance_sensor.png) + The tool will then plot the result: + ![QGC Analyze DISTANCE_SENSOR value](../../assets/qgc/analyze/qgc_analyze_tool_distance_sensor.png) ### QGroundControl MAVLink Console diff --git a/docs/zh/sensor/vectornav.md b/docs/zh/sensor/vectornav.md index 1ec42b5668..84003cf023 100644 --- a/docs/zh/sensor/vectornav.md +++ b/docs/zh/sensor/vectornav.md @@ -61,18 +61,18 @@ To use the VectorNav driver: 5. Configure driver as either an external INS or to provide raw data: - If using the VectorNav as an external INS, set [VN_MODE](../advanced_config/parameter_reference.md#VN_MODE) to `INS`. - This disables EKF2. + This disables EKF2. - If using the VectorNav as external inertial sensors: - 1. Set [VN_MODE](../advanced_config/parameter_reference.md#VN_MODE) to `Sensors Only` - 2. If internal sensors are enabled, prioritize VectorNav sensors using [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO), [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO), [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO), [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO), where _n_ is the instance number of the IMU component (0, 1, etc.). + 1. Set [VN_MODE](../advanced_config/parameter_reference.md#VN_MODE) to `Sensors Only` + 2. If internal sensors are enabled, prioritize VectorNav sensors using [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO), [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO), [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO), [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO), where _n_ is the instance number of the IMU component (0, 1, etc.). - ::: tip - In most cases the external IMU (VN) is the highest-numbered. - You can get a list of the IMU components available using [`uorb top -1`](../middleware/uorb.md#uorb-top-command), you can differentiate between them using the [`listener`](../modules/modules_command.md#listener) command and looking through the data, or just the rates. + ::: tip + In most cases the external IMU (VN) is the highest-numbered. + You can get a list of the IMU components available using [`uorb top -1`](../middleware/uorb.md#uorb-top-command), you can differentiate between them using the [`listener`](../modules/modules_command.md#listener) command and looking through the data, or just the rates. - Alternatively, you can check [CAL_GYROn_ID](../advanced_config/parameter_reference.md#CAL_GYRO0_ID) to see the device id. - The priority is 0-255, where 0 is entirely disabled and 255 is highest priority. + Alternatively, you can check [CAL_GYROn_ID](../advanced_config/parameter_reference.md#CAL_GYRO0_ID) to see the device id. + The priority is 0-255, where 0 is entirely disabled and 255 is highest priority. ::: diff --git a/docs/zh/sim_flightgear/index.md b/docs/zh/sim_flightgear/index.md index 9e5e0c2179..d528471c34 100644 --- a/docs/zh/sim_flightgear/index.md +++ b/docs/zh/sim_flightgear/index.md @@ -40,33 +40,33 @@ These instructions were tested on Ubuntu 18.04 2. Install FlightGear: - ```sh - sudo add-apt-repository ppa:saiarcot895/flightgear - sudo apt update - sudo apt install flightgear - ``` + ```sh + sudo add-apt-repository ppa:saiarcot895/flightgear + sudo apt update + sudo apt install flightgear + ``` - This installs the latest stable FlightGear version from the PAA repository along with the FGdata package. + This installs the latest stable FlightGear version from the PAA repository along with the FGdata package. - :::tip - For some models (e.g. those with electric engines) the daily build with the newest features may be necessary. - Install this using the [daily build PPA](https://launchpad.net/~saiarcot895/+archive/ubuntu/flightgear-edge). + :::tip + For some models (e.g. those with electric engines) the daily build with the newest features may be necessary. + Install this using the [daily build PPA](https://launchpad.net/~saiarcot895/+archive/ubuntu/flightgear-edge). ::: 3. Check that you are able to run FlightGear: - ```sh - fgfs --launcher - ``` + ```sh + fgfs --launcher + ``` 4. Set write permissions to the **Protocols** folder in the FlightGear installation directory: - ```sh - sudo chmod a+w /usr/share/games/flightgear/Protocol - ``` + ```sh + sudo chmod a+w /usr/share/games/flightgear/Protocol + ``` - Setting the permissions is required because the PX4-FlightGear-Bridge puts the communication definition file here. + Setting the permissions is required because the PX4-FlightGear-Bridge puts the communication definition file here. Additional installation instructions can be found on [FlightGear wiki](https://wiki.flightgear.org/Howto:Install_Flightgear_from_a_PPA). diff --git a/docs/zh/sim_gazebo_classic/index.md b/docs/zh/sim_gazebo_classic/index.md index 73f6f7444f..d3245db579 100644 --- a/docs/zh/sim_gazebo_classic/index.md +++ b/docs/zh/sim_gazebo_classic/index.md @@ -249,14 +249,14 @@ It is enabled by default in many vehicle SDF files: **solo.sdf**, **iris.sdf**, To enable/disable GPS noise: 1. Build any gazebo target in order to generate SDF files (for all vehicles). - 例如: + 例如: - ```sh - make px4_sitl gazebo-classic_iris - ``` + ```sh + make px4_sitl gazebo-classic_iris + ``` - :::tip - The SDF files are not overwritten on subsequent builds. + :::tip + The SDF files are not overwritten on subsequent builds. ::: @@ -264,17 +264,17 @@ To enable/disable GPS noise: 3. Search for the `gpsNoise` element: - ```xml - - - true - - ``` + ```xml + + + true + + ``` - - If it is present, GPS is enabled. - You can disable it by deleting the line: `true` - - If it is not present, GPS is disabled. - You can enable it by adding the `gpsNoise` element to the `gps_plugin` section (as shown above). + - If it is present, GPS is enabled. + You can disable it by deleting the line: `true` + - If it is not present, GPS is disabled. + You can enable it by adding the `gpsNoise` element to the `gps_plugin` section (as shown above). The next time you build/restart Gazebo Classic it will use the new GPS noise setting. diff --git a/docs/zh/sim_gazebo_classic/multi_vehicle_simulation.md b/docs/zh/sim_gazebo_classic/multi_vehicle_simulation.md index 722bfd7a30..381773e488 100644 --- a/docs/zh/sim_gazebo_classic/multi_vehicle_simulation.md +++ b/docs/zh/sim_gazebo_classic/multi_vehicle_simulation.md @@ -68,36 +68,36 @@ To build an example setup, follow the steps below: 1. Clone the PX4/Firmware code, then build the SITL code: - ```sh - cd Firmware_clone - git submodule update --init --recursive - DONT_RUN=1 make px4_sitl gazebo-classic - ``` + ```sh + cd Firmware_clone + git submodule update --init --recursive + DONT_RUN=1 make px4_sitl gazebo-classic + ``` 2. Build the `micro xrce-dds agent` and the interface package following the [instructions here](../ros2/user_guide.md). 3. Run `Tools/simulation/gazebo-classic/sitl_multiple_run.sh`. - For example, to spawn 4 vehicles, run: + For example, to spawn 4 vehicles, run: - ```sh - ./Tools/simulation/gazebo-classic/sitl_multiple_run.sh -m iris -n 4 - ``` + ```sh + ./Tools/simulation/gazebo-classic/sitl_multiple_run.sh -m iris -n 4 + ``` - ::: info - Each vehicle instance is allocated a unique MAVLink system id (2, 3, 4, etc.). - MAVLink system id 1 is skipped. + ::: info + Each vehicle instance is allocated a unique MAVLink system id (2, 3, 4, etc.). + MAVLink system id 1 is skipped. ::: 4. Run `MicroXRCEAgent`. - It will automatically connect to all four vehicles: + It will automatically connect to all four vehicles: - ```sh - MicroXRCEAgent udp4 -p 8888 - ``` + ```sh + MicroXRCEAgent udp4 -p 8888 + ``` - ::: info - The simulator startup script automatically assigns a [unique namespace](../ros2/multi_vehicle.md) to each vehicle. + ::: info + The simulator startup script automatically assigns a [unique namespace](../ros2/multi_vehicle.md) to each vehicle. ::: @@ -117,27 +117,27 @@ To build an example setup, follow the step below: 1. Clone the PX4/PX4-Autopilot code, then build the SITL code - ```sh - cd Firmware_clone - git submodule update --init --recursive - DONT_RUN=1 make px4_sitl_default gazebo-classic - ``` + ```sh + cd Firmware_clone + git submodule update --init --recursive + DONT_RUN=1 make px4_sitl_default gazebo-classic + ``` 2. Source your environment: - ```sh - source Tools/simulation/gazebo-classic/setup_gazebo.bash $(pwd) $(pwd)/build/px4_sitl_default - export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:$(pwd):$(pwd)/Tools/simulation/gazebo-classic/sitl_gazebo - ``` + ```sh + source Tools/simulation/gazebo-classic/setup_gazebo.bash $(pwd) $(pwd)/build/px4_sitl_default + export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:$(pwd):$(pwd)/Tools/simulation/gazebo-classic/sitl_gazebo + ``` 3. Run launch file: - ```sh - roslaunch px4 multi_uav_mavros_sitl.launch - ``` + ```sh + roslaunch px4 multi_uav_mavros_sitl.launch + ``` - ::: info - You can specify `gui:=false` in the above _roslaunch_ to launch Gazebo Classic without its UI. + ::: info + You can specify `gui:=false` in the above _roslaunch_ to launch Gazebo Classic without its UI. ::: @@ -253,45 +253,45 @@ This section shows how developers can simulate multiple vehicles using vehicle m 1. Install _xmlstarlet_ from your Linux terminal: - ```sh - sudo apt install xmlstarlet - ``` + ```sh + sudo apt install xmlstarlet + ``` 2. Use _roslaunch_ with the **multi_uav_mavros_sitl_sdf.launch** launch file: - ````sh - roslaunch multi_uav_mavros_sitl_sdf.launch vehicle:= - ``` + ````sh + roslaunch multi_uav_mavros_sitl_sdf.launch vehicle:= + ``` - ::: info - Note that the vehicle model file name argument is optional (`vehicle:=`); if omitted the [plane model](https://github.com/PX4/PX4-SITL_gazebo-classic/tree/master/models/plane) will be used by default. + ::: info + Note that the vehicle model file name argument is optional (`vehicle:=`); if omitted the [plane model](https://github.com/PX4/PX4-SITL_gazebo-classic/tree/master/models/plane) will be used by default. ::: - ```` + ```` This method is similar to using the xacro except that the SITL/Gazebo Classic port number is automatically inserted by _xmstarlet_ for each spawned vehicle, and does not need to be specified in the SDF file. To add a new vehicle, you need to make sure the model can be found (in order to spawn it in Gazebo Classic), and PX4 needs to have an appropriate corresponding startup script. 1. You can choose to do either of: - - modify the **single_vehicle_spawn_sdf.launch** file to point to the location of your model by changing the line below to point to your model: + - modify the **single_vehicle_spawn_sdf.launch** file to point to the location of your model by changing the line below to point to your model: - ```sh - $(find px4)/Tools/simulation/gazebo/sitl_gazebo-classic/models/$(arg vehicle)/$(arg vehicle).sdf - ``` + ```sh + $(find px4)/Tools/simulation/gazebo/sitl_gazebo-classic/models/$(arg vehicle)/$(arg vehicle).sdf + ``` - ::: info - Ensure you set the `vehicle` argument even if you hardcode the path to your model. + ::: info + Ensure you set the `vehicle` argument even if you hardcode the path to your model. ::: - - copy your model into the folder indicated above (following the same path convention). + - copy your model into the folder indicated above (following the same path convention). 2. The `vehicle` argument is used to set the `PX4_SIM_MODEL` environment variable, which is used by the default rcS (startup script) to find the corresponding startup settings file for the model. - Within PX4 these startup files can be found in the **PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/** directory. - For example, here is the plane model's [startup script](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/1030_gazebo-classic_plane). - For this to work, the PX4 node in the launch file is passed arguments that specify the _rcS_ file (**etc/init.d/rcS**) and the location of the rootfs etc directory (`$(find px4)/build_px4_sitl_default/etc`). - For simplicity, it is suggested that the startup file for the model be placed alongside PX4's in **PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/**. + Within PX4 these startup files can be found in the **PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/** directory. + For example, here is the plane model's [startup script](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/1030_gazebo-classic_plane). + For this to work, the PX4 node in the launch file is passed arguments that specify the _rcS_ file (**etc/init.d/rcS**) and the location of the rootfs etc directory (`$(find px4)/build_px4_sitl_default/etc`). + For simplicity, it is suggested that the startup file for the model be placed alongside PX4's in **PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/**. ## Additional Resources diff --git a/docs/zh/sim_gazebo_gz/gazebo_models.md b/docs/zh/sim_gazebo_gz/gazebo_models.md index 915dd7a90d..5756fa3bda 100644 --- a/docs/zh/sim_gazebo_gz/gazebo_models.md +++ b/docs/zh/sim_gazebo_gz/gazebo_models.md @@ -101,15 +101,15 @@ This example explains how you can run standalone mode PX4 via two terminals on o 1. In one terminal run - ```sh - PX4_GZ_STANDALONE=1 PX4_SYS_AUTOSTART=4001 PX4_SIM_MODEL=gz_x500 PX4_GZ_WORLD=windy ./build/px4_sitl_default/bin/px4 - ``` + ```sh + PX4_GZ_STANDALONE=1 PX4_SYS_AUTOSTART=4001 PX4_SIM_MODEL=gz_x500 PX4_GZ_WORLD=windy ./build/px4_sitl_default/bin/px4 + ``` 2. In a second terminal window run: - ```sh - python3 /path/to/simulation-gazebo --world windy - ``` + ```sh + python3 /path/to/simulation-gazebo --world windy + ``` No additional parameters have to be passed to the simulation-gazebo script in order for this example to work, as all Gazebo nodes run on the same host. See the example below for a more involved scenario with different hosts. diff --git a/docs/zh/sim_gazebo_gz/index.md b/docs/zh/sim_gazebo_gz/index.md index 34c383c3c9..127701dc05 100644 --- a/docs/zh/sim_gazebo_gz/index.md +++ b/docs/zh/sim_gazebo_gz/index.md @@ -316,33 +316,33 @@ Here are some examples of the different scenarios covered above. 1. **Start simulator + default world + spawn vehicle at default pose** - ```sh - PX4_SYS_AUTOSTART=4001 PX4_SIM_MODEL=gz_x500 ./build/px4_sitl_default/bin/px4 - ``` + ```sh + PX4_SYS_AUTOSTART=4001 PX4_SIM_MODEL=gz_x500 ./build/px4_sitl_default/bin/px4 + ``` 2. **Start simulator + default world + spawn vehicle at custom pose (y=2m)** - ```sh - PX4_SYS_AUTOSTART=4001 PX4_GZ_MODEL_POSE="0,2" PX4_SIM_MODEL=gz_x500 ./build/px4_sitl_default/bin/px4 - ``` + ```sh + PX4_SYS_AUTOSTART=4001 PX4_GZ_MODEL_POSE="0,2" PX4_SIM_MODEL=gz_x500 ./build/px4_sitl_default/bin/px4 + ``` 3. **Start simulator + default world + link to existing vehicle** - ```sh - PX4_SYS_AUTOSTART=4001 PX4_GZ_MODEL_NAME=x500 ./build/px4_sitl_default/bin/px4 - ``` + ```sh + PX4_SYS_AUTOSTART=4001 PX4_GZ_MODEL_NAME=x500 ./build/px4_sitl_default/bin/px4 + ``` 4. **Start simulator in standalone mode + connect to Gazebo instance running default world** - ```sh - PX4_GZ_STANDALONE=1 PX4_SYS_AUTOSTART=4001 PX4_SIM_MODEL=gz_x500 ./build/px4_sitl_default/bin/px4 - ``` + ```sh + PX4_GZ_STANDALONE=1 PX4_SYS_AUTOSTART=4001 PX4_SIM_MODEL=gz_x500 ./build/px4_sitl_default/bin/px4 + ``` - In a separate terminal run: + In a separate terminal run: - ```sh - python /path/to/simulation-gazebo - ``` + ```sh + python /path/to/simulation-gazebo + ``` ## Adding New Worlds and Models @@ -358,38 +358,38 @@ To add a new model: 2. Define the default parameters for Gazebo in the airframe configuration file (this example is from [x500 quadcopter](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/4001_gz_x500)): - ```ini - PX4_SIMULATOR=${PX4_SIMULATOR:=gz} - PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} - PX4_SIM_MODEL=${PX4_SIM_MODEL:=} - ``` + ```ini + PX4_SIMULATOR=${PX4_SIMULATOR:=gz} + PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} + PX4_SIM_MODEL=${PX4_SIM_MODEL:=} + ``` - - `PX4_SIMULATOR=${PX4_SIMULATOR:=gz}` sets the default simulator (Gz) for that specific airframe. + - `PX4_SIMULATOR=${PX4_SIMULATOR:=gz}` sets the default simulator (Gz) for that specific airframe. - - `PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}` sets the [default world](https://github.com/PX4/PX4-gazebo-models/blob/main/worlds/default.sdf) for that specific airframe. + - `PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}` sets the [default world](https://github.com/PX4/PX4-gazebo-models/blob/main/worlds/default.sdf) for that specific airframe. - - Setting the default value of `PX4_SIM_MODEL` lets you start the simulation with just: + - Setting the default value of `PX4_SIM_MODEL` lets you start the simulation with just: - ```sh - PX4_SYS_AUTOSTART= ./build/px4_sitl_default/bin/px4 - ``` + ```sh + PX4_SYS_AUTOSTART= ./build/px4_sitl_default/bin/px4 + ``` 3. Add CMake Target for the [airframe](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt). - - If you plan to use "regular" mode, add your model SDF to `Tools/simulation/gz/models/`. - - If you plan to use _standalone_ mode, add your model SDF to `~/.simulation-gazebo/models/` + - If you plan to use "regular" mode, add your model SDF to `Tools/simulation/gz/models/`. + - If you plan to use _standalone_ mode, add your model SDF to `~/.simulation-gazebo/models/` - You can of course also use both. + You can of course also use both. ### Adding a World To add a new world: 1. Add your world to the list of worlds found in the [`CMakeLists.txt` here](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/gz_bridge/CMakeLists.txt). - This is required in order to allow `CMake` to generate correct targets. + This is required in order to allow `CMake` to generate correct targets. - - If you plan to use "normal" mode, add your world sdf to `Tools/simulation/gz/worlds/`. - - If you plan to use _standalone_ mode, add your world SDF to `~/.simulation-gazebo/worlds/` + - If you plan to use "normal" mode, add your world sdf to `Tools/simulation/gz/worlds/`. + - If you plan to use _standalone_ mode, add your world SDF to `~/.simulation-gazebo/worlds/` :::info As long as the world file and the model file are in the Gazebo search path (`GZ_SIM_RESOURCE_PATH`) it is not necessary to add them to the PX4 world and model directories. diff --git a/docs/zh/sim_gazebo_gz/plugins.md b/docs/zh/sim_gazebo_gz/plugins.md index 9723f44177..0f48c53db8 100644 --- a/docs/zh/sim_gazebo_gz/plugins.md +++ b/docs/zh/sim_gazebo_gz/plugins.md @@ -43,8 +43,8 @@ When developing new plugins: 1. **Follow the plugin architecture** - Implement desired interfaces. - You can start by copying the [Template plugin](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/template_plugin) which is a simple example that only implements `ISystemPreUpdate` and `ISystemPostUpdate`. - The interfaces are specified in the official [Gazebo documentation](https://gazebosim.org/api/sim/9/createsystemplugins.html). + You can start by copying the [Template plugin](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/template_plugin) which is a simple example that only implements `ISystemPreUpdate` and `ISystemPostUpdate`. + The interfaces are specified in the official [Gazebo documentation](https://gazebosim.org/api/sim/9/createsystemplugins.html). 2. **Register your plugin** - Add it to [server.config](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/gz_bridge/server.config) for discovery. diff --git a/docs/zh/sim_gazebo_gz/tools_avl_automation.md b/docs/zh/sim_gazebo_gz/tools_avl_automation.md index 049c37b623..fd57223dce 100644 --- a/docs/zh/sim_gazebo_gz/tools_avl_automation.md +++ b/docs/zh/sim_gazebo_gz/tools_avl_automation.md @@ -11,26 +11,26 @@ The results will then automatically be written into a provided plugin template t To setup the tool: 1. Download AVL 3.36 from . - The file for AVL version 3.36 can be found about halfway down the page. + The file for AVL version 3.36 can be found about halfway down the page. 2. After downloading, extract AVL and move it to the home directory using: - ```sh - sudo tar -xf avl3.36.tgz - mv ./Avl /home/ - ``` + ```sh + sudo tar -xf avl3.36.tgz + mv ./Avl /home/ + ``` 3. Follow the **index.md** found in `./Avl` to finish the setup process for AVL (this requires that you set up `plotlib` and `eispack` libraries). - We recommend using the `gfortran` compile option, which might further require that you to install `gfortran`. - On Ubuntu can be done by running: + We recommend using the `gfortran` compile option, which might further require that you to install `gfortran`. + On Ubuntu can be done by running: - ```sh - sudo apt update - sudo apt install gfortran - ``` + ```sh + sudo apt update + sudo apt install gfortran + ``` - When running the Makefile for AVL, you might encounter an `Error 1` message stating that there is a directory missing. - This does not prevent AVL from working for our purposes. + When running the Makefile for AVL, you might encounter an `Error 1` message stating that there is a directory missing. + This does not prevent AVL from working for our purposes. Once the process described in the AVL README is completed, AVL is ready to be used. No further set up is required on the side of the AVL or the tool. @@ -49,16 +49,16 @@ To run the tool for your plane: 2. Run the tool on your yml file: - ```sh - python input_avl.py .yml - ``` + ```sh + python input_avl.py .yml + ``` - Note that the `yaml` and `argparse` packages must be present in your Python environment. + Note that the `yaml` and `argparse` packages must be present in your Python environment. 3. The tool prompts for a range of vehicle specific parameters that are needed in order to specify the geometry and physical properties of the plane. - You can either: - - select a predefined model template (such as a Cessna or a VTOL), which has a known number of control surfaces, and just modify some physical properties, or - - define a completely custom model + You can either: + - select a predefined model template (such as a Cessna or a VTOL), which has a known number of control surfaces, and just modify some physical properties, or + - define a completely custom model Once the script has been executed, the generated `.avl`, `.sdf` and a plot of the proposed control surfaces can be found in `` directory. The sdf file is the generated Advanced Lift Drag Plugin that can be copied and pasted into a model.sdf file, which can then be run in Gazebo. diff --git a/docs/zh/sim_jmavsim/index.md b/docs/zh/sim_jmavsim/index.md index 8208f0b7a6..d63db8d443 100644 --- a/docs/zh/sim_jmavsim/index.md +++ b/docs/zh/sim_jmavsim/index.md @@ -30,23 +30,23 @@ Follow the instructions below to install jMAVSim on macOS. To setup the environment for [jMAVSim](../sim_jmavsim/index.md) simulation: 1. Install a recent version of Java (e.g. Java 15). - You can download [Java 15 (or later) from Oracle](https://www.oracle.com/java/technologies/downloads/?er=221886) or use [Eclipse Temurin](https://adoptium.net): + You can download [Java 15 (or later) from Oracle](https://www.oracle.com/java/technologies/downloads/?er=221886) or use [Eclipse Temurin](https://adoptium.net): - ```sh - brew install --cask temurin - ``` + ```sh + brew install --cask temurin + ``` 2. Install jMAVSim: - ```sh - brew install px4-sim-jmavsim - ``` + ```sh + brew install px4-sim-jmavsim + ``` - :::warning - PX4 v1.11 and beyond require at least JDK 15 for jMAVSim simulation. + :::warning + PX4 v1.11 and beyond require at least JDK 15 for jMAVSim simulation. - For earlier versions, macOS users might see the error `Exception in thread "main" java.lang.UnsupportedClassVersionError:`. - You can find the fix in the [jMAVSim with SITL > Troubleshooting](../sim_jmavsim/index.md#troubleshooting)). + For earlier versions, macOS users might see the error `Exception in thread "main" java.lang.UnsupportedClassVersionError:`. + You can find the fix in the [jMAVSim with SITL > Troubleshooting](../sim_jmavsim/index.md#troubleshooting)). ::: diff --git a/docs/zh/sim_sih/index.md b/docs/zh/sim_sih/index.md index 7b09b1442f..f4896ab8db 100644 --- a/docs/zh/sim_sih/index.md +++ b/docs/zh/sim_sih/index.md @@ -71,24 +71,24 @@ To check that these are present on your flight controller: 3. Enter the following commands in the console: - ```sh - pwm_out_sim status - ``` + ```sh + pwm_out_sim status + ``` - ```sh - sensor_baro_sim status - ``` + ```sh + sensor_baro_sim status + ``` - ```sh - sensor_gps_sim status - ``` + ```sh + sensor_gps_sim status + ``` - ```sh - sensor_mag_sim status - ``` + ```sh + sensor_mag_sim status + ``` - ::: tip - Note that when using SIH on real hardware you do not need to additionally enable the modules using their corresponding parameters ([SENS_EN_GPSSIM](../advanced_config/parameter_reference.md#SENS_EN_GPSSIM), [SENS_EN_BAROSIM](../advanced_config/parameter_reference.md#SENS_EN_BAROSIM), [SENS_EN_MAGSIM](../advanced_config/parameter_reference.md#SENS_EN_MAGSIM)). + ::: tip + Note that when using SIH on real hardware you do not need to additionally enable the modules using their corresponding parameters ([SENS_EN_GPSSIM](../advanced_config/parameter_reference.md#SENS_EN_GPSSIM), [SENS_EN_BAROSIM](../advanced_config/parameter_reference.md#SENS_EN_BAROSIM), [SENS_EN_MAGSIM](../advanced_config/parameter_reference.md#SENS_EN_MAGSIM)). ::: @@ -141,12 +141,12 @@ To set up/start SIH: 1. Connect the flight controller to the desktop computer with a USB cable. 2. Open QGroundControl and wait for the flight controller too boot and connect. 3. Open [Vehicle Setup > Airframe](../config/airframe.md) then select the desired frame: - - [SIH Quadcopter X](../airframes/airframe_reference.md#copter_simulation_sih_quadcopter_x) - - **SIH Hexacopter X** (currently only has an airframe for SITL to safe flash so on flight control hardware it has to be manually configured equivalently). - - [SIH plane AERT](../airframes/airframe_reference.md#plane_simulation_sih_plane_aert) - - [SIH Tailsitter Duo](../airframes/airframe_reference.md#vtol_simulation_sih_tailsitter_duo) - - [SIH Standard VTOL QuadPlane](../airframes/airframe_reference.md#vtol_simulation_sih_standard_vtol_quadplane) - - [SIH Ackermann Rover](../airframes/airframe_reference.md#rover_rover_sih_rover_ackermann) + - [SIH Quadcopter X](../airframes/airframe_reference.md#copter_simulation_sih_quadcopter_x) + - **SIH Hexacopter X** (currently only has an airframe for SITL to safe flash so on flight control hardware it has to be manually configured equivalently). + - [SIH plane AERT](../airframes/airframe_reference.md#plane_simulation_sih_plane_aert) + - [SIH Tailsitter Duo](../airframes/airframe_reference.md#vtol_simulation_sih_tailsitter_duo) + - [SIH Standard VTOL QuadPlane](../airframes/airframe_reference.md#vtol_simulation_sih_standard_vtol_quadplane) + - [SIH Ackermann Rover](../airframes/airframe_reference.md#rover_rover_sih_rover_ackermann) The autopilot will then reboot. The `sih` module is started on reboot, and the vehicle should be displayed on the ground control station map. @@ -172,19 +172,19 @@ To display the simulated vehicle: 3. Start jMAVSim by calling the script **jmavsim_run.sh** from a terminal: - ```sh - ./Tools/simulation/jmavsim/jmavsim_run.sh -q -d /dev/ttyACM0 -b 2000000 -o - ``` + ```sh + ./Tools/simulation/jmavsim/jmavsim_run.sh -q -d /dev/ttyACM0 -b 2000000 -o + ``` - where the flags are: + where the flags are: - - `-q` to allow the communication to _QGroundControl_ (optional). - - `-d` to start the serial device `/dev/ttyACM0` on Linux. - On macOS this would be `/dev/tty.usbmodem1`. - - `-b` to set the serial baud rate to `2000000`. - - `-o` to start jMAVSim in _display Only_ mode (i.e. the physical engine is turned off and jMAVSim only displays the trajectory given by the SIH in real-time). - - add a flag `-a` to display an aircraft or `-t` to display a tailsitter. - If this flag is not present a quadrotor will be displayed by default. + - `-q` to allow the communication to _QGroundControl_ (optional). + - `-d` to start the serial device `/dev/ttyACM0` on Linux. + On macOS this would be `/dev/tty.usbmodem1`. + - `-b` to set the serial baud rate to `2000000`. + - `-o` to start jMAVSim in _display Only_ mode (i.e. the physical engine is turned off and jMAVSim only displays the trajectory given by the SIH in real-time). + - add a flag `-a` to display an aircraft or `-t` to display a tailsitter. + If this flag is not present a quadrotor will be displayed by default. 4. After few seconds, _QGroundControl_ can be opened again. @@ -201,41 +201,41 @@ To run SIH as SITL: 1. Install the [PX4 Development toolchain](../dev_setup/dev_env.md). 2. Run the appropriate make command for each vehicle type (at the root of the PX4-Autopilot repository): - - Quadcopter + - Quadcopter - ```sh - make px4_sitl sihsim_quadx - ``` + ```sh + make px4_sitl sihsim_quadx + ``` - - Hexacopter + - Hexacopter - ```sh - make px4_sitl sihsim_hex - ``` + ```sh + make px4_sitl sihsim_hex + ``` - - Fixed-wing (plane) + - Fixed-wing (plane) - ```sh - make px4_sitl sihsim_airplane - ``` + ```sh + make px4_sitl sihsim_airplane + ``` - - XVert VTOL tailsitter + - XVert VTOL tailsitter - ```sh - make px4_sitl sihsim_xvert - ``` + ```sh + make px4_sitl sihsim_xvert + ``` - - 标准垂起固定翼 + - 标准垂起固定翼 - ```sh - make px4_sitl sihsim_standard_vtol - ``` + ```sh + make px4_sitl sihsim_standard_vtol + ``` - - Ackermann Rover + - Ackermann Rover - ```sh - make px4_sitl sihsim_rover_ackermann - ``` + ```sh + make px4_sitl sihsim_rover_ackermann + ``` ### Change Simulation Speed @@ -328,6 +328,44 @@ For SIH as SITL (no FC): For specific examples see the `_sihsim_` airframes in [ROMFS/px4fmu_common/init.d-posix/airframes](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/) (SIH as SITL) and [ROMFS/px4fmu_common/init.d/airframes](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d/airframes) (SIH on FC). +## Controlling Actuators in SIH + +:::warning +If you want to control throttling actuators in SIH, make sure to remove propellers for safety. +::: + +In some scenarios, it may be useful to control an actuator while running SIH. For example, you might want to verify that winches or grippers are functioning correctly by checking the servo responses. + +To enable actuator control in SIH: + +1. Configure PWM parameters in the airframe file: + +Ensure your airframe file includes the necessary parameters to map PWM outputs to the correct channels. + +For example, if a servo is connected to MAIN 3 and you want to map it to AUX1 on your RC, use the following command: + +`param set-default PWM_MAIN_FUNC3 407` + +You can find a full list of available values for `PWM_MAIN_FUNCn` [here](../advanced_config/parameter_reference.md#PWM_MAIN_FUNC1). In this case, `407` maps the MAIN 3 output to AUX1 on the RC. + +Alternatively, you can use the [`PWM_AUX_FUNCn`](../advanced_config/parameter_reference.md#PWM_AUX_FUNC1) parameters. + +You may also configure the output as desired: + +- Disarmed PWM: ([`PWM_MAIN_DISn`](../advanced_config/parameter_reference.md#PWM_MAIN_DIS1) / [`PWM_AUX_DIS1`](../advanced_config/parameter_reference.md#PWM_AUX_DIS1)) +- Minimum PWM ([`PWM_MAIN_MINn`](../advanced_config/parameter_reference.md#PWM_MAIN_MIN1) / [`PWM_AUX_MINn`](../advanced_config/parameter_reference.md#PWM_AUX_MIN1)) +- Maximum PWM ([`PWM_MAIN_MAXn`](../advanced_config/parameter_reference.md#PWM_MAIN_MAX1) / [`PWM_AUX_MAXn`](../advanced_config/parameter_reference.md#PWM_AUX_MAX1)) + +2. Manually start the PWM output driver + +For safety, the PWM driver is not started automatically in SIH. To enable it, run the following command in the MAVLink shell: + +`pwm_out start` + +And to disable it again: + +`pwm_out stop` + ## Dynamic Models The dynamic models for the various vehicles are: diff --git a/docs/zh/simulation/index.md b/docs/zh/simulation/index.md index db8211d3cd..e5d3f03025 100644 --- a/docs/zh/simulation/index.md +++ b/docs/zh/simulation/index.md @@ -217,20 +217,20 @@ The simulated camera is a gazebo classic plugin that implements the [MAVLink Cam PX4 connects/integrates with this camera in _exactly the same way_ as it would with any other MAVLink camera: 1. [TRIG_INTERFACE](../advanced_config/parameter_reference.md#TRIG_INTERFACE) must be set to `3` to configure the camera trigger driver for use with a MAVLink camera - :::tip - In this mode the driver just sends a [CAMERA_TRIGGER](https://mavlink.io/en/messages/common.html#CAMERA_TRIGGER) message whenever an image capture is requested. - For more information see [Cameras Connected to Flight Controller Outputs](../camera/fc_connected_camera.md). + :::tip + In this mode the driver just sends a [CAMERA_TRIGGER](https://mavlink.io/en/messages/common.html#CAMERA_TRIGGER) message whenever an image capture is requested. + For more information see [Cameras Connected to Flight Controller Outputs](../camera/fc_connected_camera.md). ::: 2. PX4 必须在 GCS 和(模拟器)MAVLink Camera 之间转发所有摄像机命令。 - You can do this by starting [MAVLink](../modules/modules_communication.md#mavlink) with the `-f` flag as shown, specifying the UDP ports for the new connection. + You can do this by starting [MAVLink](../modules/modules_communication.md#mavlink) with the `-f` flag as shown, specifying the UDP ports for the new connection. - ```sh - mavlink start -u 14558 -o 14530 -r 4000 -f -m camera - ``` + ```sh + mavlink start -u 14558 -o 14530 -r 4000 -f -m camera + ``` - ::: info - More than just the camera MAVLink messages will be forwarded, but the camera will ignore those that it doesn't consider relevant. + ::: info + More than just the camera MAVLink messages will be forwarded, but the camera will ignore those that it doesn't consider relevant. ::: diff --git a/docs/zh/smart_batteries/rotoye_batmon.md b/docs/zh/smart_batteries/rotoye_batmon.md index ead3d454db..e12979457b 100644 --- a/docs/zh/smart_batteries/rotoye_batmon.md +++ b/docs/zh/smart_batteries/rotoye_batmon.md @@ -3,11 +3,6 @@ [Rotoye 电池监测器](https://rotoye.com/batmon/) 是一款套件,用于为现成的锂离子和锂聚合物电池增添智能电池功能。 It can be purchased as a standalone unit or as part of a factory-assembled smart-battery. -:::info -At time of writing you can only use Batmon by [building a custom branch of PX4](#build-px4-firmware). -Support in the codeline is pending [PR approval](https://github.com/PX4/PX4-Autopilot/pull/16723). -::: - ![Rotoye 电池监控板](../../assets/hardware/smart_batteries/rotoye_batmon/smart-battery-rotoye.jpg) ![组装的罗托耶智能电池](../../assets/hardware/smart_batteries/rotoye_batmon/smart-battery-rotoye-pack.jpg) diff --git a/docs/zh/telemetry/crsf_telemetry.md b/docs/zh/telemetry/crsf_telemetry.md index 322d3ebbe9..b265e83580 100644 --- a/docs/zh/telemetry/crsf_telemetry.md +++ b/docs/zh/telemetry/crsf_telemetry.md @@ -77,36 +77,36 @@ To use this feature you must build and upload custom firmware that includes [crs 1. [Setup a development environment](../dev_setup/dev_env.md) for building PX4. - As part of this process you will have used `git` to fetch source code into the **PX4-Autopilot** directory. + As part of this process you will have used `git` to fetch source code into the **PX4-Autopilot** directory. 2. Open a terminal and `cd` into the `PX4-Autopilot` directory. - ```sh - cd PX4-Autopilot - ``` + ```sh + cd PX4-Autopilot + ``` 3. Launch the [PX4 board config tool (`menuconfig`)](../hardware/porting_guide_config.md#px4-menuconfig-setup) for your `make` target using the `boardconfig` option (here the target is the [ARK Electronics ARKV6X](../flight_controller/ark_v6x.md) flight controller): - ```sh - make ark_fmu-v6x_default boardconfig - ``` + ```sh + make ark_fmu-v6x_default boardconfig + ``` 4. In the PX4 board config tool: - - Disable the default `rc_input` module - 1. Navigate to the `drivers` submenu, then scroll down to highlight `rc_input`. - 2. Use the enter key to remove the `*` from `rc_input` checkbox. - - Enable the `crsf_rc` module - 1. Scroll to highlight the `RC` submenu, then press enter to open it. - 2. Scroll to highlight `crsf_rc` and press enter to enable it. + - Disable the default `rc_input` module + 1. Navigate to the `drivers` submenu, then scroll down to highlight `rc_input`. + 2. Use the enter key to remove the `*` from `rc_input` checkbox. + - Enable the `crsf_rc` module + 1. Scroll to highlight the `RC` submenu, then press enter to open it. + 2. Scroll to highlight `crsf_rc` and press enter to enable it. - Save and exit the PX4 board config tool. + Save and exit the PX4 board config tool. 5. [Build the PX4 source code](../dev_setup/building_px4.md) with your changes (again assuming you are using ARKV6X): - ```sh - make ark_fmu-v6x_default - ``` + ```sh + make ark_fmu-v6x_default + ``` This will build your custom firmware, which must now be uploaded to your flight controller. @@ -128,11 +128,11 @@ Alternatively you can use QGroundControl to install the firmware, as described i 1. [RC_CRSF_PRT_CFG](../advanced_config/parameter_reference.md#RC_CRSF_PRT_CFG) — Set to the port that is connected to the CRSF receiver (such as `TELEM1`). - This [configures the serial port](../peripherals/serial_configuration.md) to use the CRSF protocol. - Note that some serial ports may already have a [default serial port mapping](../peripherals/serial_configuration.md#default-serial-port-configuration) or [default MAVLink serial port mapping](../peripherals/mavlink_peripherals.md#default-mavlink-ports) that you will have to un-map before you can assign the port to CRSF. - For example, if you want to use `TELEM1` or `TELEM2` you first need to modify [MAV_0_CONFIG](../advanced_config/parameter_reference.md#MAV_0_CONFIG) or [MAV_1_CONFIG](../advanced_config/parameter_reference.md#MAV_1_CONFIG) to stop setting those ports. + This [configures the serial port](../peripherals/serial_configuration.md) to use the CRSF protocol. + Note that some serial ports may already have a [default serial port mapping](../peripherals/serial_configuration.md#default-serial-port-configuration) or [default MAVLink serial port mapping](../peripherals/mavlink_peripherals.md#default-mavlink-ports) that you will have to un-map before you can assign the port to CRSF. + For example, if you want to use `TELEM1` or `TELEM2` you first need to modify [MAV_0_CONFIG](../advanced_config/parameter_reference.md#MAV_0_CONFIG) or [MAV_1_CONFIG](../advanced_config/parameter_reference.md#MAV_1_CONFIG) to stop setting those ports. - There is no need to set the baud rate for the port, as this is configured by the driver. + There is no need to set the baud rate for the port, as this is configured by the driver. 2. [RC_CRSF_TEL_EN](../advanced_config/parameter_reference.md#RC_CRSF_TEL_EN) — Enable to activate Crossfire telemetry. diff --git a/docs/zh/telemetry/jfi_telemetry.md b/docs/zh/telemetry/jfi_telemetry.md index e7fc2526c3..b9387b536b 100644 --- a/docs/zh/telemetry/jfi_telemetry.md +++ b/docs/zh/telemetry/jfi_telemetry.md @@ -111,9 +111,9 @@ However if you change the baud rate from 57600 you will need to create and use a 1. Disable SiK Radio in QGC (**Application Settings → General → AutoConnect**). 2. Create a new link configuration: - - Go to **Application Settings → Comms Links**. - - Click **Add**. - - Set **Type** to **Serial**, configure the **Serial Port** and **Baud Rate** to match the J.Fi device. + - Go to **Application Settings → Comms Links**. + - Click **Add**. + - Set **Type** to **Serial**, configure the **Serial Port** and **Baud Rate** to match the J.Fi device. 3. Select **Connect** to connect with the new configuration. ## J.Fi Configuration diff --git a/docs/zh/test_and_ci/fuzz_tests.md b/docs/zh/test_and_ci/fuzz_tests.md index b087f5b21e..202d7e383d 100644 --- a/docs/zh/test_and_ci/fuzz_tests.md +++ b/docs/zh/test_and_ci/fuzz_tests.md @@ -15,14 +15,14 @@ To write a fuzz test: 1. Start by writing a "normal" [functional test](../test_and_ci/unit_tests.md#functional-test). 2. Make sure the file name contains `fuzz` (lower case). - For example `my_driver_fuzz_tests.cpp`. + For example `my_driver_fuzz_tests.cpp`. 3. Add one or more fuzz tests to the file. - 例如: + 例如: ```cpp #include #include - + void myDriverNeverCrashes(const std::string& s) { MyDriver driver; driver.handleInput(s); diff --git a/docs/zh/test_and_ci/index.md b/docs/zh/test_and_ci/index.md index 91ceadea53..6e7c94f8e3 100644 --- a/docs/zh/test_and_ci/index.md +++ b/docs/zh/test_and_ci/index.md @@ -9,8 +9,8 @@ Test topics include: - [Unit Tests](../test_and_ci/unit_tests.md) - [Continuous Integration (CI)](../test_and_ci/continous_integration.md) - [Integration Testing](../test_and_ci/integration_testing.md) - - [MAVSDK Integration Testing](../test_and_ci/integration_testing_mavsdk.md) - - [PX4 ROS2 Interface Library Integration Testing](../test_and_ci/integration_testing_px4_ros2_interface.md) - - [ROS 1 Integration Testing](../test_and_ci/integration_testing_ros1_mavros.md) (Deprecated) + - [MAVSDK Integration Testing](../test_and_ci/integration_testing_mavsdk.md) + - [PX4 ROS2 Interface Library Integration Testing](../test_and_ci/integration_testing_px4_ros2_interface.md) + - [ROS 1 Integration Testing](../test_and_ci/integration_testing_ros1_mavros.md) (Deprecated) - [Docker](../test_and_ci/docker.md) - [Maintenance](../test_and_ci/maintenance.md) diff --git a/docs/zh/test_and_ci/integration_testing_ros1_mavros.md b/docs/zh/test_and_ci/integration_testing_ros1_mavros.md index e2a21e6795..083deb2310 100644 --- a/docs/zh/test_and_ci/integration_testing_ros1_mavros.md +++ b/docs/zh/test_and_ci/integration_testing_ros1_mavros.md @@ -65,73 +65,73 @@ To write a new test: 1. Create a new test script by copying the empty test skeleton below: - ```python - #!/usr/bin/env python - # [... LICENSE ...] - - # - # @author Example Author - # - PKG = 'px4' - - import unittest - import rospy - import rosbag - - from sensor_msgs.msg import NavSatFix - - class MavrosNewTest(unittest.TestCase): - """ - Test description - """ - - def setUp(self): - rospy.init_node('test_node', anonymous=True) - rospy.wait_for_service('mavros/cmd/arming', 30) - - rospy.Subscriber("mavros/global_position/global", NavSatFix, self.global_position_callback) - self.rate = rospy.Rate(10) # 10hz - self.has_global_pos = False - - def tearDown(self): - pass - - # - # General callback functions used in tests - # - def global_position_callback(self, data): - self.has_global_pos = True - - def test_method(self): - """Test method description""" - - # FIXME: hack to wait for simulation to be ready - while not self.has_global_pos: - self.rate.sleep() - - # TODO: execute test - - if __name__ == '__main__': - import rostest - rostest.rosrun(PKG, 'mavros_new_test', MavrosNewTest) - ``` + ```python + #!/usr/bin/env python + # [... LICENSE ...] + + # + # @author Example Author + # + PKG = 'px4' + + import unittest + import rospy + import rosbag + + from sensor_msgs.msg import NavSatFix + + class MavrosNewTest(unittest.TestCase): + """ + Test description + """ + + def setUp(self): + rospy.init_node('test_node', anonymous=True) + rospy.wait_for_service('mavros/cmd/arming', 30) + + rospy.Subscriber("mavros/global_position/global", NavSatFix, self.global_position_callback) + self.rate = rospy.Rate(10) # 10hz + self.has_global_pos = False + + def tearDown(self): + pass + + # + # General callback functions used in tests + # + def global_position_callback(self, data): + self.has_global_pos = True + + def test_method(self): + """Test method description""" + + # FIXME: hack to wait for simulation to be ready + while not self.has_global_pos: + self.rate.sleep() + + # TODO: execute test + + if __name__ == '__main__': + import rostest + rostest.rosrun(PKG, 'mavros_new_test', MavrosNewTest) + ``` 2. Run the new test only - Start the simulator: - ```sh - cd - source Tools/simulation/gazebo/setup_gazebo.bash - roslaunch launch/mavros_posix_sitl.launch - ``` + ```sh + cd + source Tools/simulation/gazebo/setup_gazebo.bash + roslaunch launch/mavros_posix_sitl.launch + ``` - Run test (in a new shell): - ```sh - cd - source Tools/simulation/gazebo/setup_gazebo.bash - rosrun px4 mavros_new_test.py - ``` + ```sh + cd + source Tools/simulation/gazebo/setup_gazebo.bash + rosrun px4 mavros_new_test.py + ``` 3. Add new test node to a launch file - In `test/` create a new `.test` ROS launch file. @@ -145,9 +145,9 @@ To write a new test: 例如: - ```sh - tests_: rostest - @"$(SRC_DIR)"/test/rostest_px4_run.sh mavros_posix_tests_.test - ``` + ```sh + tests_: rostest + @"$(SRC_DIR)"/test/rostest_px4_run.sh mavros_posix_tests_.test + ``` Run the tests as described above. diff --git a/docs/zh/test_and_ci/test_flights.md b/docs/zh/test_and_ci/test_flights.md index abe1d95d7c..094b9cb45f 100644 --- a/docs/zh/test_and_ci/test_flights.md +++ b/docs/zh/test_and_ci/test_flights.md @@ -28,3 +28,5 @@ These are run by the test team as part of release testing, and for more signific - [MC_04 - Failsafe Testing](../test_cards/mc_04_failsafe_testing.md) - [MC_05 - Indoor Flight (Manual Modes)](../test_cards/mc_05_indoor_flight_manual_modes.md) - [MC_06 - Indoor Flight (Optical Flow)](../test_cards/mc_06_optical_flow.md) +- [MC_07 - VIO (Visual-Inertial Odometry)](../test_cards/mc_07_vio.md) +- [MC_08 - DSHOT ESC](../test_cards/mc_08_dshot.md) diff --git a/docs/zh/test_and_ci/unit_tests.md b/docs/zh/test_and_ci/unit_tests.md index f8cbf9747c..0a3039a8f9 100644 --- a/docs/zh/test_and_ci/unit_tests.md +++ b/docs/zh/test_and_ci/unit_tests.md @@ -126,34 +126,34 @@ It can be run directly in a debugger, however be careful to only run one test pe 10. Within [tests_main.h](https://github.com/PX4/PX4-Autopilot/blob/main/src/systemcmds/tests/tests_main.h) define the new test: - ```cpp - extern int test_[description](int argc, char *argv[]); - ``` + ```cpp + extern int test_[description](int argc, char *argv[]); + ``` 11. Within [tests_main.c](https://github.com/PX4/PX4-Autopilot/blob/main/src/systemcmds/tests/tests_main.c) add description name, test function and option: - ```cpp - ... - } tests[] = { - {... - {"[description]", test_[description], OPTION}, - ... - } - ``` + ```cpp + ... + } tests[] = { + {... + {"[description]", test_[description], OPTION}, + ... + } + ``` - `OPTION` can be `OPT_NOALLTEST`,`OPT_NOJIGTEST` or `0` and is considered if within px4 shell one of the two commands are called: + `OPTION` can be `OPT_NOALLTEST`,`OPT_NOJIGTEST` or `0` and is considered if within px4 shell one of the two commands are called: - ```sh - pxh> tests all - ``` + ```sh + pxh> tests all + ``` - 或 + 或 - ```sh - pxh> tests jig - ``` + ```sh + pxh> tests jig + ``` - If a test has option `OPT_NOALLTEST`, then that test will be excluded when calling `tests all`. The same is true for `OPT_NOJITEST` when command `test jig` is called. Option `0` means that the test is never excluded, which is what most developer want to use. + If a test has option `OPT_NOALLTEST`, then that test will be excluded when calling `tests all`. The same is true for `OPT_NOJITEST` when command `test jig` is called. Option `0` means that the test is never excluded, which is what most developer want to use. 12. Add the test `test_[description].cpp` to the [CMakeLists.txt](https://github.com/PX4/PX4-Autopilot/blob/main/src/systemcmds/tests/CMakeLists.txt). diff --git a/docs/zh/test_cards/mc_04_failsafe_testing.md b/docs/zh/test_cards/mc_04_failsafe_testing.md index bca8c73323..630b537e83 100644 --- a/docs/zh/test_cards/mc_04_failsafe_testing.md +++ b/docs/zh/test_cards/mc_04_failsafe_testing.md @@ -9,10 +9,10 @@ Test RC loss, data link loss, and low battery failsafes. - Verify RC Loss action is Return to Land - Verify Data Link Loss action is Return to Land and the timeout is 10 seconds - Verify Battery failsafe - - Action is Return to Land - - Battery Warn Level is 25% - - Battery Failsafe Level is 20% - - Battery Emergency Level is 15% + - Action is Return to Land + - Battery Warn Level is 25% + - Battery Failsafe Level is 20% + - Battery Emergency Level is 15% ## Flight Tests diff --git a/docs/zh/test_cards/mc_06_optical_flow.md b/docs/zh/test_cards/mc_06_optical_flow.md index 037881f4b0..c63bebba16 100644 --- a/docs/zh/test_cards/mc_06_optical_flow.md +++ b/docs/zh/test_cards/mc_06_optical_flow.md @@ -2,11 +2,19 @@ ## Objective -To test that optical flow / external vision work as expected +To test that optical flow works as expected ## Preflight Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation +([Setup Information here](../sensor/optical_flow.md)) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` Ensure that the drone can go into Altitude / Position flight mode while still on the ground @@ -39,5 +47,7 @@ Ensure that the drone can go into Altitude / Position flight mode while still on ## 预期成果 - 当油门升高时,起飞应该是平稳的 +- Drone should hold altitude in Altitude Flight mode without wandering +- Drone should hold position within 1 meter in Position Flight mode without pilot moving sticks - 在上述任何飞行模式中都不应出现振荡 - 着陆时,直升机不应在地面上反弹 diff --git a/docs/zh/test_cards/mc_07_vio.md b/docs/zh/test_cards/mc_07_vio.md new file mode 100644 index 0000000000..0972a15540 --- /dev/null +++ b/docs/zh/test_cards/mc_07_vio.md @@ -0,0 +1,52 @@ +# Test MC_07 - VIO (Visual-Inertial Odometry) + +## Objective + +To test that external vision (VIO) works as expected + +## Preflight + +Disconnect all GPS / compasses and ensure vehicle is using VIO for navigation + +Ensure that the drone can go into Altitude / Position flight mode while still on the ground + +Ensure there are no other sources of positioning besides VIO: + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `0` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `15` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` + +## Flight Tests + +❏ Altitude flight mode + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response set to climb/descent rate + +❏ Position flight mode + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## 降落 + +❏ Land in either Position or Altitude mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## 预期成果 + +- 当油门升高时,起飞应该是平稳的 +- Drone should hold altitude in Altitude Flight mode without wandering +- Drone should hold position within 1 meter in Position Flight mode without pilot moving sticks +- 在上述任何飞行模式中都不应出现振荡 +- 着陆时,直升机不应在地面上反弹 diff --git a/docs/zh/test_cards/mc_08_dshot.md b/docs/zh/test_cards/mc_08_dshot.md new file mode 100644 index 0000000000..2f0ef74bdb --- /dev/null +++ b/docs/zh/test_cards/mc_08_dshot.md @@ -0,0 +1,46 @@ +# Test MC_08 - DSHOT ESC + +## Objective + +Regression test for DSHOT working with PX4 + +## Preflight + +- Ensure vehicle is using a DSHOT ESC. +- Parameter [DSHOT_BIDIR_EN](../advanced_config/parameter_reference.md#DSHOT_BIDIR_EN) is enabled +- Parameter [DSHOT_TEL_CFG](../advanced_config/parameter_reference.md#DSHOT_TEL_CFG) is configured (if ESC supports telemetry) +- Parameter [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) has Debug (`5`) checked + +## Flight Tests + +❏ Stabilized Flight mode + +    ❏ Takeoff in stabilized flight mode to ensure correct motor spin + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response 1:1 + +❏ Position flight mode + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## 降落 + +❏ Land in either Position or Altitude mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## 预期成果 + +- Download flight logs +- Load into Data Plot Juggler +- Ensure data is logged for esc_status/esc.0x/esc_rpm + + ![Reference frames](../../assets/test_cards/dshot_log_output.png) diff --git a/docs/zh/uart/user_configurable_serial_driver.md b/docs/zh/uart/user_configurable_serial_driver.md index 08ff1d6363..948fee14c5 100644 --- a/docs/zh/uart/user_configurable_serial_driver.md +++ b/docs/zh/uart/user_configurable_serial_driver.md @@ -26,33 +26,33 @@ 1. Create a YAML module configuration file: - - Add a new file in the driver's source directory named **module.yaml** - - Insert the following text and adjust as needed: + - Add a new file in the driver's source directory named **module.yaml** + - Insert the following text and adjust as needed: - ```cmake - module_name: uLanding Radar - serial_config: - - command: ulanding_radar start -d ${SERIAL_DEV} -b p:${BAUD_PARAM} - port_config_param: - name: SENS_ULAND_CFG - group: Sensors - ``` + ```cmake + module_name: uLanding Radar + serial_config: + - command: ulanding_radar start -d ${SERIAL_DEV} -b p:${BAUD_PARAM} + port_config_param: + name: SENS_ULAND_CFG + group: Sensors + ``` - ::: info - The full documentation of the module configuration file can be found in the [validation/module_schema.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/validation/module_schema.yaml) file. - This is also used to validate all configuration files in CI. + ::: info + The full documentation of the module configuration file can be found in the [validation/module_schema.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/validation/module_schema.yaml) file. + This is also used to validate all configuration files in CI. ::: 2. Add the module configuration to the **CMakeLists.txt** file for the driver module: - ```cmake - px4_add_module( - MODULE drivers__ulanding - MAIN ulanding_radar - SRCS - ulanding.cpp - MODULE_CONFIG - module.yaml - ) - ``` + ```cmake + px4_add_module( + MODULE drivers__ulanding + MAIN ulanding_radar + SRCS + ulanding.cpp + MODULE_CONFIG + module.yaml + ) + ``` From a20afc88c8cbdfff8e34e42645feef410a5cb299 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Thu, 11 Sep 2025 08:30:05 +1000 Subject: [PATCH 019/812] New Crowdin translations - uk (#25482) Co-authored-by: Crowdin Bot --- docs/uk/SUMMARY.md | 2 + docs/uk/concept/system_startup.md | 31 +++- docs/uk/config_rover/basic_setup.md | 67 ++++++-- docs/uk/config_rover/velocity_tuning.md | 4 +- docs/uk/dev_log/logging.md | 13 +- docs/uk/sensor/inertial_navigation_systems.md | 23 ++- docs/uk/sim_sih/index.md | 148 +++++++++++------- docs/uk/smart_batteries/rotoye_batmon.md | 5 - docs/uk/test_and_ci/test_flights.md | 2 + docs/uk/test_cards/mc_06_optical_flow.md | 12 +- docs/uk/test_cards/mc_07_vio.md | 52 ++++++ docs/uk/test_cards/mc_08_dshot.md | 46 ++++++ 12 files changed, 321 insertions(+), 84 deletions(-) create mode 100644 docs/uk/test_cards/mc_07_vio.md create mode 100644 docs/uk/test_cards/mc_08_dshot.md diff --git a/docs/uk/SUMMARY.md b/docs/uk/SUMMARY.md index 80ccf0fc76..90a224480d 100644 --- a/docs/uk/SUMMARY.md +++ b/docs/uk/SUMMARY.md @@ -843,6 +843,8 @@ - [Тест MC_04 - Тестування відмовостійкості](test_cards/mc_04_failsafe_testing.md) - [Test MC_05 - Manual Modes (Inside)](test_cards/mc_05_indoor_flight_manual_modes.md) - [Test MC_06 - Optical Flow (Inside)](test_cards/mc_06_optical_flow.md) + - [Test MC_07 - VIO (Inside)](test_cards/mc_07_vio.md) + - [Test MC_08 - DSHOT ESC](test_cards/mc_08_dshot.md) - [Модульні Тести](test_and_ci/unit_tests.md) - [Fuzz Tests](test_and_ci/fuzz_tests.md) - [Безперервна інтеграція](test_and_ci/continous_integration.md) diff --git a/docs/uk/concept/system_startup.md b/docs/uk/concept/system_startup.md index b4f0ae06ec..c4d74386af 100644 --- a/docs/uk/concept/system_startup.md +++ b/docs/uk/concept/system_startup.md @@ -95,6 +95,8 @@ NuttX має інтегрований інтерпретатор оболонк Найкращий спосіб змінити запуск системи - це ввести [нову конфігурацію планера](../dev_airframes/adding_a_new_frame.md). Файл конфігурації планеру може бути включений у прошивку або на SD карту. +#### Dynamic customization + Якщо вам потрібно "підлаштувати" конфігурацію що існує, наприклад запустити один або більше застосунків або встановити значення кількох параметрів, можна вказати це створивши два файли у директорії `/etc/` на SD картці: - [/etc/config.txt](#customizing-the-configuration-config-txt): modify parameter values @@ -111,7 +113,7 @@ NuttX має інтегрований інтерпретатор оболонк Ці файли згадуються в коді PX4 як `/fs/microsd/etc/config.txt` та `/fs/microsd/etc/extras.txt`, де коренева директорія microSD карти визначається шляхом `/fs/microsd`. ::: -#### Налаштування конфігурації (config.txt) +##### Налаштування конфігурації (config.txt) Файл `config.txt` можна використовувати для зміни параметрів. Він завантажується після того, як головна система була налаштована та _перед тим_ як завантажена. @@ -123,7 +125,7 @@ param set-default PWM_MAIN_DIS3 1000 param set-default PWM_MAIN_MIN3 1120 ``` -#### Запуск додаткових застосунків (extras.txt) +##### Запуск додаткових застосунків (extras.txt) `extras.txt` можна використовувати для запуску додаткових застосунків після завантаження основної системи. Зазвичай це будуть контролери корисного навантаження або подібні необов'язкові користувацькі компоненти. @@ -150,3 +152,28 @@ param set-default PWM_MAIN_MIN3 1120 mandatory_app start # Will abort boot if mandatory_app is unknown or fails ``` + +#### Additional customization + +In rare cases where the desired setup cannot be achieved through frame configuration or dynamic customization, +you can add a script that will be contained in the binary. + +**Note**: In almost all cases, you should use a frame configuration. This method should only be used for +edge-cases such as customizing `cannode` based boards. + +- Add a new init script in `boards///init` that will run during board startup. Наприклад: + ```sh + # File: boards///init/rc.additional + param set-default + ``` + +- Add a new board variant in `boards///.px4board` that includes the additional script. Наприклад: + ```sh + # File: boards///var.px4board + CONFIG_BOARD_ADDITIONAL_INIT="rc.additional" + ``` + +- Compile the firmware with your new variant by appending the variant name to the compile target. Наприклад: + ```sh + make _var + ``` diff --git a/docs/uk/config_rover/basic_setup.md b/docs/uk/config_rover/basic_setup.md index 08bde551a8..a5fc9f1987 100644 --- a/docs/uk/config_rover/basic_setup.md +++ b/docs/uk/config_rover/basic_setup.md @@ -27,10 +27,18 @@ That is the minimum setup to use the rover in [Manual mode](../flight_modes_rover/manual.md#manual-mode). +:::info +The rest of the tuning on this page is not mandatory for [Manual mode](../flight_modes_rover/manual.md#manual-mode), but it will have an effect on the behaviour of the rover. +::: + +:::warning +Do not skip the rest of this setup if you intend to use more sophisticated modes! +All parameters will be mandatory for all subsequent modes, except those tagged as `(Optional)`. +::: + ## Geometric Parameters -Manual mode is also affected by (optional) acceleration/deceleration limits set using the geometric described below. -These limits are mandatory for all other modes. +First, we set up the geometric parameters of the rover: ![Geometric parameters](../../assets/config/rover/geometric_parameters.png) @@ -42,7 +50,7 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and 2. [RA_MAX_STR_ANG](#RA_MAX_STR_ANG) [deg]: Measure the maximum steering angle. 3. (Optional) [RA_STR_RATE_LIM](#RA_STR_RATE_LIM) [deg/s]: Maximum steering rate you want to allow for your rover. - :::tip + ::: tip This value depends on your rover and use case. For bigger rovers there might be a mechanical limit that is easy to identify by steering the rover at a standstill and increasing [RA_STR_RATE_LIM](#RA_STR_RATE_LIM) until you observe the steering rate to no longer be limited by the parameter. @@ -51,7 +59,7 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and ::: - :::warning + ::: warning A low maximum steering rate makes the rover worse at tracking steering setpoints, which can lead to a poor performance in the subsequent modes. ::: @@ -76,7 +84,7 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and 2. (Optional) [RO_ACCEL_LIM](#RO_ACCEL_LIM) [m/s^2]: Maximum acceleration you want to allow for your rover. - + :::tip Your rover has a maximum possible acceleration which is determined by the maximum torque the motor can supply. @@ -109,6 +117,39 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and ::: +## (Optional) Stick Input Mapping + +Input shaping can be used to adjust the default linear mapping from stick inputs $\in [-1, 1]$ to normalized setpoints $\in [-1, 1]$. Applying this specifically to the steering input, can provide a smoother driving experience, by enabling the user to make small adjustments when the stick is close to the center, but still send large inputs when moving them to the edges. +We provide this input shaping through the super exponential function: + +$$ +\delta = \frac{(f \cdot x^3 + x(1-f)) \cdot (1-g)}{1-g \cdot |x|} +$$ + +with: + + - $\delta \in [-1, 1]=$ Normalized steering setpoint. + - $x \in [-1, 1]=$ Normalized stick input. + - $f=$ [RO_YAW_EXPO](#RO_YAW_EXPO): `0` Purely linear input curve, `1` Purely cubic input curve. + - $g=$ [RO_YAW_SUPEXPO](#RO_YAW_SUPEXPO): `0` Pure Expo function, `0.7` reasonable shape enhancement for intuitive stick feel, `0.95` very strong bent input curve only near maxima have effect. + +In [Manual mode](../flight_modes_rover/manual.md#manual-mode) we can additionally scale $\delta$ with an additional parameter $r$: + + - Differential Rover: $r=$ [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN), which enables adjusting the slope of the input mapping. This leads to a normalized steering input $\hat{\delta} = \delta \cdot r \in$ [-[RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN), [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN)]. + - Mecanum Rover: $r=$ [RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN), which enables adjusting the slope of the input mapping. This leads to a normalized steering input $\hat{\delta} = \delta \cdot r \in$ [-[RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN), [RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN)]. + +This scaling is useful to limit the normalized steering setpoint, if it is too aggresive for your rover in manual mode. + +You can experiment with the relationships graphically using the [PX4 SuperExpo Rover calculator](https://www.desmos.com/calculator/gwm8lrlanx). + +:::info +In [Acro](../flight_modes_rover/manual.md#acro-mode), [Stabilized](../flight_modes_rover/manual.md#stabilized-mode) and [Position](../flight_modes_rover/manual.md#position-mode) Mode, $\delta$ is instead scaled by $r=$ [RO_YAW_RATE_LIM](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED) for all rovers. This leads to a yaw rate setpoint $\dot{\psi} = \delta \cdot r \in$ [-[RO_YAW_RATE_LIM](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED), [RO_YAW_RATE_LIM](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED)]. This parameter is setup during [rate tuning](rate_tuning.md). +::: + +:::info +The input shaping through [RO_YAW_EXPO](#RO_YAW_EXPO) and [RO_YAW_SUPEXPO](#RO_YAW_SUPEXPO) applies for all manual modes, while [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN)/[RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN) only affects full manual mode. +::: + You can now continue the configuration process with [rate tuning](rate_tuning.md). ## Огляд параметрів @@ -118,6 +159,8 @@ You can now continue the configuration process with [rate tuning](rate_tuning.md | [RO_MAX_THR_SPEED](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED) | Speed the rover drives at maximum throttle | $m/s$ | | [RO_ACCEL_LIM](../advanced_config/parameter_reference.md#RO_ACCEL_LIM) | (Optional) Maximum allowed acceleration | $m/s^2$ | | [RO_DECEL_LIM](../advanced_config/parameter_reference.md#RO_DECEL_LIM) | (Optional) Maximum allowed deceleration | $m/s^2$ | +| [RO_YAW_EXPO](../advanced_config/parameter_reference.md#RO_YAW_EXPO) | (Optional) Yaw rate expo factor | $-$ | +| [RO_YAW_SUPEXPO](../advanced_config/parameter_reference.md#RO_YAW_SUPEXPO) | (Optional) Yaw rate super expo factor | $-$ | ### Ackermann Specific @@ -129,12 +172,14 @@ You can now continue the configuration process with [rate tuning](rate_tuning.md ### Differential Specific -| Параметр | Опис | Unit | -| ----------------------------------------------------------------------------------------------------------------------------------------------- | ----------- | ---- | -| [RD_WHEEL_TRACK](../advanced_config/parameter_reference.md#RD_WHEEL_TRACK) | Wheel track | m | +| Параметр | Опис | Unit | +| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------ | ---- | +| [RD_WHEEL_TRACK](../advanced_config/parameter_reference.md#RD_WHEEL_TRACK) | Wheel track | $m$ | +| [RD_YAW_STK_GAIN](../advanced_config/parameter_reference.md#RD_YAW_STK_GAIN) | (Optional) Yaw stick gain for Manual mode | $-$ | ### Mecanum Specific -| Параметр | Опис | Unit | -| ----------------------------------------------------------------------------------------------------------------------------------------------- | ----------- | ---- | -| [RM_WHEEL_TRACK](../advanced_config/parameter_reference.md#RM_WHEEL_TRACK) | Wheel track | m | +| Параметр | Опис | Unit | +| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------ | ---- | +| [RM_WHEEL_TRACK](../advanced_config/parameter_reference.md#RM_WHEEL_TRACK) | Wheel track | $m$ | +| [RM_YAW_STK_GAIN](../advanced_config/parameter_reference.md#RM_YAW_STK_GAIN) | (Optional) Yaw stick gain for Manual mode | $-$ | diff --git a/docs/uk/config_rover/velocity_tuning.md b/docs/uk/config_rover/velocity_tuning.md index 6bb98876bd..e171e07c34 100644 --- a/docs/uk/config_rover/velocity_tuning.md +++ b/docs/uk/config_rover/velocity_tuning.md @@ -20,7 +20,7 @@ To tune the velocity controller configure the following [parameters](../advanced 2. [RO_MAX_THR_SPEED](#RO_MAX_THR_SPEED) [m/s]: This parameter is used to calculate the feed-forward term of the closed loop speed control which linearly maps desired speeds to normalized motor commands. As mentioned in the [Manual mode](../flight_modes_rover/manual.md#manual-mode) configuration , a good starting point is the observed ground speed when the rover drives at maximum throttle in [Manual mode](../flight_modes_rover/manual.md#manual-mode). - + ::: tip To further tune this parameter: @@ -94,7 +94,7 @@ These steps are only necessary if you are tuning/want to unlock the manual [Posi The rover is now ready to drive in [Position mode](../flight_modes_rover/manual.md#position-mode) and the configuration can be continued with [position tuning](position_tuning.md). -## Attitude Controller Structure (Info Only) +## Velocity Controller Structure (Info Only) This section provides additional information for developers and people with experience in control system design. diff --git a/docs/uk/dev_log/logging.md b/docs/uk/dev_log/logging.md index 600c0c3f1d..31a86cce4a 100644 --- a/docs/uk/dev_log/logging.md +++ b/docs/uk/dev_log/logging.md @@ -33,16 +33,17 @@ The logging system is configured by default to collect sensible logs for [flight Logging may further be configured using the [SD Logging](../advanced_config/parameter_reference.md#sd-logging) parameters. Параметри, які ви найімовірніше зміните, перераховані нижче. -| Параметр | Опис | -| --------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [SDLOG_MODE](../advanced_config/parameter_reference.md#SDLOG_MODE) | Журналювання. Defines when logging starts and stops.
- `-1`: Logging disabled.
- `0`: Log when armed until disarm (default).
- `1`: Log from boot until disarm.
- `2`: Log from boot until shutdown.
- `3`: Log based on the [AUX1 RC channel](../advanced_config/parameter_reference.md#RC_MAP_AUX1).
- `4`: Log from first armed until shutdown. | -| [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) | Профіль ведення журналу. Use this to enable less common logging/analysis (e.g. for EKF2 replay, high rate logging for PID & filter tuning, thermal temperature calibration). | -| [SDLOG_MISSION](../advanced_config/parameter_reference.md#SDLOG_MISSION) | Create very small additional "Mission Log".
This log can _not_ be used with [Flight Review](../log/flight_log_analysis.md#flight-review-online-tool), but is useful when you need a small log for geotagging or regulatory compliance. | +| Параметр | Опис | +| --------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [SDLOG_MODE](../advanced_config/parameter_reference.md#SDLOG_MODE) | Журналювання. Defines when logging starts and stops.
- `0`: Log when armed until disarm (default).
- `1`: Log from boot until disarm.
- `2`: Log from boot until shutdown.
- `3`: Log based on the [AUX1 RC channel](../advanced_config/parameter_reference.md#RC_MAP_AUX1).
- `4`: Log from first armed until shutdown. | +| [SDLOG_BACKEND](../advanced_config/parameter_reference.md#SDLOG_BACKEND) | Logging Backend (bitmask). Setting a bit enables the corresponding backend. If no backend is selected, the logger is disabled.
- bit `0`: SD card logging.
- bit `1`: Mavlink logging. | +| [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) | Профіль ведення журналу. Use this to enable less common logging/analysis (e.g. for EKF2 replay, high rate logging for PID & filter tuning, thermal temperature calibration). | +| [SDLOG_MISSION](../advanced_config/parameter_reference.md#SDLOG_MISSION) | Create very small additional "Mission Log".
This log can _not_ be used with [Flight Review](../log/flight_log_analysis.md#flight-review-online-tool), but is useful when you need a small log for geotagging or regulatory compliance. | Корисні налаштування для конкретних випадків: - Raw sensor data for comparison: [SDLOG_MODE=1](../advanced_config/parameter_reference.md#SDLOG_MODE) and [SDLOG_PROFILE=64](../advanced_config/parameter_reference.md#SDLOG_PROFILE). -- Disabling logging altogether: [SDLOG_MODE=`-1`](../advanced_config/parameter_reference.md#SDLOG_MODE) +- Disabling logging altogether: [SDLOG_BACKEND=`0`](../advanced_config/parameter_reference.md#SDLOG_BACKEND) ### Модуль реєстрації diff --git a/docs/uk/sensor/inertial_navigation_systems.md b/docs/uk/sensor/inertial_navigation_systems.md index 4703c5ab10..e0d36d29ef 100644 --- a/docs/uk/sensor/inertial_navigation_systems.md +++ b/docs/uk/sensor/inertial_navigation_systems.md @@ -2,13 +2,32 @@ PX4 зазвичай працює на контролерах польоту, які включають в себе ІВП, такі як серія Pixhawk, і об'єднує дані датчиків разом із інформацією ССН (супутникова система навігації) в оцінювачі EKF2 для визначення орієнтації, напрямку, позиції та швидкості транспортного засобу. -However PX4 can also use some INS devices as either sources of raw data, or as an external estimator, replacing the EKF. +However PX4 can also use some INS devices as either sources of raw data, or as an external estimator, replacing EKF2. -Системи, які можуть бути використані у такий спосіб, включають в себе: +## Supported INS Systems + +INS systems that can be used as a replacement for EKF2 in PX4: - [InertialLabs](../sensor/inertiallabs.md) - [VectorNav](../sensor/vectornav.md): ІВП/AHRS, ССН/INS, Dual GNSS/INS системи, котрі можуть бути використані як зовнішній INS, або джерело вхідної інформації датчиків. +## PX4 Firmware + +The driver module for your INS system may not be included in the PX4 firmware for your flight controller by default. + +You can check by searching the [default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/fmu-v6c/default.px4board#L25) configuration file for your target board for either: + +- `CONFIG_COMMON_INS`, which includes drivers for [all INS systems](https://github.com/PX4/PX4-Autopilot/blob/main/src/drivers/ins/Kconfig). +- The key for the particular INS system you are using, such as: + - `CONFIG_DRIVERS_INS_ILABS` + - `CONFIG_DRIVERS_INS_MICROSTRAIN` + - `CONFIG_DRIVERS_INS_VECTORNAV` + +If the required key is not present you can include the module in firmware by adding the key to the `default.px4board` file, or using the [kconfig board configuration tool](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) and then select the driver you want (`Drivers -> INS`). +Note that if you're working on a flight controller where flash memory is limited, you're better off installing just the modules you need. + +You will then need to rebuild the firmware. + ## Словник ### Інерційний вимірювальний пристрій (ІВП) diff --git a/docs/uk/sim_sih/index.md b/docs/uk/sim_sih/index.md index bc2d323650..6333fe0819 100644 --- a/docs/uk/sim_sih/index.md +++ b/docs/uk/sim_sih/index.md @@ -71,24 +71,24 @@ To check that these are present on your flight controller: 3. Enter the following commands in the console: - ```sh - pwm_out_sim status - ``` + ```sh + pwm_out_sim status + ``` - ```sh - sensor_baro_sim status - ``` + ```sh + sensor_baro_sim status + ``` - ```sh - sensor_gps_sim status - ``` + ```sh + sensor_gps_sim status + ``` - ```sh - sensor_mag_sim status - ``` + ```sh + sensor_mag_sim status + ``` - ::: tip - Note that when using SIH on real hardware you do not need to additionally enable the modules using their corresponding parameters ([SENS_EN_GPSSIM](../advanced_config/parameter_reference.md#SENS_EN_GPSSIM), [SENS_EN_BAROSIM](../advanced_config/parameter_reference.md#SENS_EN_BAROSIM), [SENS_EN_MAGSIM](../advanced_config/parameter_reference.md#SENS_EN_MAGSIM)). + ::: tip + Note that when using SIH on real hardware you do not need to additionally enable the modules using their corresponding parameters ([SENS_EN_GPSSIM](../advanced_config/parameter_reference.md#SENS_EN_GPSSIM), [SENS_EN_BAROSIM](../advanced_config/parameter_reference.md#SENS_EN_BAROSIM), [SENS_EN_MAGSIM](../advanced_config/parameter_reference.md#SENS_EN_MAGSIM)). ::: @@ -141,12 +141,12 @@ To set up/start SIH: 1. Connect the flight controller to the desktop computer with a USB cable. 2. Відкрийте QGroundControl і зачекайте, поки контролер польоту також завантажиться та підключиться. 3. Open [Vehicle Setup > Airframe](../config/airframe.md) then select the desired frame: - - [SIH Quadcopter X](../airframes/airframe_reference.md#copter_simulation_sih_quadcopter_x) - - **SIH Hexacopter X** (currently only has an airframe for SITL to safe flash so on flight control hardware it has to be manually configured equivalently). - - [SIH plane AERT](../airframes/airframe_reference.md#plane_simulation_sih_plane_aert) - - [SIH Tailsitter Duo](../airframes/airframe_reference.md#vtol_simulation_sih_tailsitter_duo) - - [SIH Standard VTOL QuadPlane](../airframes/airframe_reference.md#vtol_simulation_sih_standard_vtol_quadplane) - - [SIH Ackermann Rover](../airframes/airframe_reference.md#rover_rover_sih_rover_ackermann) + - [SIH Quadcopter X](../airframes/airframe_reference.md#copter_simulation_sih_quadcopter_x) + - **SIH Hexacopter X** (currently only has an airframe for SITL to safe flash so on flight control hardware it has to be manually configured equivalently). + - [SIH plane AERT](../airframes/airframe_reference.md#plane_simulation_sih_plane_aert) + - [SIH Tailsitter Duo](../airframes/airframe_reference.md#vtol_simulation_sih_tailsitter_duo) + - [SIH Standard VTOL QuadPlane](../airframes/airframe_reference.md#vtol_simulation_sih_standard_vtol_quadplane) + - [SIH Ackermann Rover](../airframes/airframe_reference.md#rover_rover_sih_rover_ackermann) Потім автопілот перезавантажиться. The `sih` module is started on reboot, and the vehicle should be displayed on the ground control station map. @@ -172,19 +172,19 @@ SIH does not _need_ a visualiser — you can connect with QGroundControl and fly 3. Start jMAVSim by calling the script **jmavsim_run.sh** from a terminal: - ```sh - ./Tools/simulation/jmavsim/jmavsim_run.sh -q -d /dev/ttyACM0 -b 2000000 -o - ``` + ```sh + ./Tools/simulation/jmavsim/jmavsim_run.sh -q -d /dev/ttyACM0 -b 2000000 -o + ``` - де прапорці такі: + де прапорці такі: - - `-q` to allow the communication to _QGroundControl_ (optional). - - `-d` to start the serial device `/dev/ttyACM0` on Linux. - On macOS this would be `/dev/tty.usbmodem1`. - - `-b` to set the serial baud rate to `2000000`. - - `-o` to start jMAVSim in _display Only_ mode (i.e. the physical engine is turned off and jMAVSim only displays the trajectory given by the SIH in real-time). - - add a flag `-a` to display an aircraft or `-t` to display a tailsitter. - Якщо цей прапорець не вказаний, за замовчуванням відображатиметься квадрокоптер. + - `-q` to allow the communication to _QGroundControl_ (optional). + - `-d` to start the serial device `/dev/ttyACM0` on Linux. + On macOS this would be `/dev/tty.usbmodem1`. + - `-b` to set the serial baud rate to `2000000`. + - `-o` to start jMAVSim in _display Only_ mode (i.e. the physical engine is turned off and jMAVSim only displays the trajectory given by the SIH in real-time). + - add a flag `-a` to display an aircraft or `-t` to display a tailsitter. + Якщо цей прапорець не вказаний, за замовчуванням відображатиметься квадрокоптер. 4. After few seconds, _QGroundControl_ can be opened again. @@ -201,41 +201,41 @@ In this case you don't need the flight controller hardware. 1. Install the [PX4 Development toolchain](../dev_setup/dev_env.md). 2. Виконайте відповідну команду make для кожного типу транспортного засобу (в корені репозиторію PX4-Autopilot): - - Quadcopter + - Quadcopter - ```sh - make px4_sitl sihsim_quadx - ``` + ```sh + make px4_sitl sihsim_quadx + ``` - - Hexacopter + - Hexacopter - ```sh - make px4_sitl sihsim_hex - ``` + ```sh + make px4_sitl sihsim_hex + ``` - - Fixed-wing (plane) + - Fixed-wing (plane) - ```sh - make px4_sitl sihsim_airplane - ``` + ```sh + make px4_sitl sihsim_airplane + ``` - - XVert VTOL tailsitter + - XVert VTOL tailsitter - ```sh - make px4_sitl sihsim_xvert - ``` + ```sh + make px4_sitl sihsim_xvert + ``` - - Standard VTOL + - Standard VTOL - ```sh - make px4_sitl sihsim_standard_vtol - ``` + ```sh + make px4_sitl sihsim_standard_vtol + ``` - - Ackermann Rover + - Ackermann Rover - ```sh - make px4_sitl sihsim_rover_ackermann - ``` + ```sh + make px4_sitl sihsim_rover_ackermann + ``` ### Зміна швидкості симуляції @@ -328,6 +328,44 @@ For SIH as SITL (no FC): For specific examples see the `_sihsim_` airframes in [ROMFS/px4fmu_common/init.d-posix/airframes](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/) (SIH as SITL) and [ROMFS/px4fmu_common/init.d/airframes](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d/airframes) (SIH on FC). +## Controlling Actuators in SIH + +:::warning +If you want to control throttling actuators in SIH, make sure to remove propellers for safety. +::: + +In some scenarios, it may be useful to control an actuator while running SIH. For example, you might want to verify that winches or grippers are functioning correctly by checking the servo responses. + +To enable actuator control in SIH: + +1. Configure PWM parameters in the airframe file: + +Ensure your airframe file includes the necessary parameters to map PWM outputs to the correct channels. + +For example, if a servo is connected to MAIN 3 and you want to map it to AUX1 on your RC, use the following command: + +`param set-default PWM_MAIN_FUNC3 407` + +You can find a full list of available values for `PWM_MAIN_FUNCn` [here](../advanced_config/parameter_reference.md#PWM_MAIN_FUNC1). In this case, `407` maps the MAIN 3 output to AUX1 on the RC. + +Alternatively, you can use the [`PWM_AUX_FUNCn`](../advanced_config/parameter_reference.md#PWM_AUX_FUNC1) parameters. + +You may also configure the output as desired: + +- Disarmed PWM: ([`PWM_MAIN_DISn`](../advanced_config/parameter_reference.md#PWM_MAIN_DIS1) / [`PWM_AUX_DIS1`](../advanced_config/parameter_reference.md#PWM_AUX_DIS1)) +- Minimum PWM ([`PWM_MAIN_MINn`](../advanced_config/parameter_reference.md#PWM_MAIN_MIN1) / [`PWM_AUX_MINn`](../advanced_config/parameter_reference.md#PWM_AUX_MIN1)) +- Maximum PWM ([`PWM_MAIN_MAXn`](../advanced_config/parameter_reference.md#PWM_MAIN_MAX1) / [`PWM_AUX_MAXn`](../advanced_config/parameter_reference.md#PWM_AUX_MAX1)) + +2. Manually start the PWM output driver + +For safety, the PWM driver is not started automatically in SIH. To enable it, run the following command in the MAVLink shell: + +`pwm_out start` + +And to disable it again: + +`pwm_out stop` + ## Dynamic Models Динамічні моделі для різних транспортних засобів: diff --git a/docs/uk/smart_batteries/rotoye_batmon.md b/docs/uk/smart_batteries/rotoye_batmon.md index 011c485a52..9050fe7efd 100644 --- a/docs/uk/smart_batteries/rotoye_batmon.md +++ b/docs/uk/smart_batteries/rotoye_batmon.md @@ -3,11 +3,6 @@ [Rotoye Batmon](https://rotoye.com/batmon/) is a kit for adding smart battery functionality to off-the-shelf Lithium-Ion and LiPo batteries. Його можна придбати як самостійний пристрій або як частину заводсько зібраної розумної батареї. -:::info -At time of writing you can only use Batmon by [building a custom branch of PX4](#build-px4-firmware). -Support in the codeline is pending [PR approval](https://github.com/PX4/PX4-Autopilot/pull/16723). -::: - ![Rotoye Batmon Board](../../assets/hardware/smart_batteries/rotoye_batmon/smart-battery-rotoye.jpg) ![Pre-assembled Rotoye smart battery](../../assets/hardware/smart_batteries/rotoye_batmon/smart-battery-rotoye-pack.jpg) diff --git a/docs/uk/test_and_ci/test_flights.md b/docs/uk/test_and_ci/test_flights.md index 3bfc25e517..6771beac6e 100644 --- a/docs/uk/test_and_ci/test_flights.md +++ b/docs/uk/test_and_ci/test_flights.md @@ -28,3 +28,5 @@ When submitting [Pull Requests](../contribute/code.md#pull-requests) for new fun - [MC_04 - Failsafe Testing](../test_cards/mc_04_failsafe_testing.md) - [MC_05 - Indoor Flight (Manual Modes)](../test_cards/mc_05_indoor_flight_manual_modes.md) - [MC_06 - Indoor Flight (Optical Flow)](../test_cards/mc_06_optical_flow.md) +- [MC_07 - VIO (Visual-Inertial Odometry)](../test_cards/mc_07_vio.md) +- [MC_08 - DSHOT ESC](../test_cards/mc_08_dshot.md) diff --git a/docs/uk/test_cards/mc_06_optical_flow.md b/docs/uk/test_cards/mc_06_optical_flow.md index 410c1a4674..6a10870404 100644 --- a/docs/uk/test_cards/mc_06_optical_flow.md +++ b/docs/uk/test_cards/mc_06_optical_flow.md @@ -2,11 +2,19 @@ ## Objective -To test that optical flow / external vision work as expected +To test that optical flow works as expected ## Preflight Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation +([Setup Information here](../sensor/optical_flow.md)) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` Ensure that the drone can go into Altitude / Position flight mode while still on the ground @@ -39,5 +47,7 @@ Ensure that the drone can go into Altitude / Position flight mode while still on ## Очікувані результати - Зліт повинен бути плавним, коли газ піднято +- Drone should hold altitude in Altitude Flight mode without wandering +- Drone should hold position within 1 meter in Position Flight mode without pilot moving sticks - Немає коливання в жодному з перерахованих режимів польоту - Після посадки, коптер не повинен підскакувати на землі diff --git a/docs/uk/test_cards/mc_07_vio.md b/docs/uk/test_cards/mc_07_vio.md new file mode 100644 index 0000000000..a6fea1b762 --- /dev/null +++ b/docs/uk/test_cards/mc_07_vio.md @@ -0,0 +1,52 @@ +# Test MC_07 - VIO (Visual-Inertial Odometry) + +## Objective + +To test that external vision (VIO) works as expected + +## Preflight + +Disconnect all GPS / compasses and ensure vehicle is using VIO for navigation + +Ensure that the drone can go into Altitude / Position flight mode while still on the ground + +Ensure there are no other sources of positioning besides VIO: + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `0` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `15` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` + +## Flight Tests + +❏ Altitude flight mode + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response set to climb/descent rate + +❏ Position flight mode + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## Посадка + +❏ Land in either Position or Altitude mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## Очікувані результати + +- Зліт повинен бути плавним, коли газ піднято +- Drone should hold altitude in Altitude Flight mode without wandering +- Drone should hold position within 1 meter in Position Flight mode without pilot moving sticks +- Немає коливання в жодному з перерахованих режимів польоту +- Після посадки, коптер не повинен підскакувати на землі diff --git a/docs/uk/test_cards/mc_08_dshot.md b/docs/uk/test_cards/mc_08_dshot.md new file mode 100644 index 0000000000..422482bbc9 --- /dev/null +++ b/docs/uk/test_cards/mc_08_dshot.md @@ -0,0 +1,46 @@ +# Test MC_08 - DSHOT ESC + +## Objective + +Regression test for DSHOT working with PX4 + +## Preflight + +- Ensure vehicle is using a DSHOT ESC. +- Parameter [DSHOT_BIDIR_EN](../advanced_config/parameter_reference.md#DSHOT_BIDIR_EN) is enabled +- Parameter [DSHOT_TEL_CFG](../advanced_config/parameter_reference.md#DSHOT_TEL_CFG) is configured (if ESC supports telemetry) +- Parameter [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) has Debug (`5`) checked + +## Flight Tests + +❏ Stabilized Flight mode + +    ❏ Takeoff in stabilized flight mode to ensure correct motor spin + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response 1:1 + +❏ Position flight mode + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## Посадка + +❏ Land in either Position or Altitude mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## Очікувані результати + +- Download flight logs +- Load into Data Plot Juggler +- Ensure data is logged for esc_status/esc.0x/esc_rpm + + ![Reference frames](../../assets/test_cards/dshot_log_output.png) From ae60c666137ca165abb5b8ab0c7c1fb83a74462c Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Thu, 11 Sep 2025 08:30:54 +1000 Subject: [PATCH 020/812] New Crowdin translations - ko (#25481) Co-authored-by: Crowdin Bot --- docs/ko/SUMMARY.md | 2 + docs/ko/concept/system_startup.md | 31 +++- docs/ko/config_rover/basic_setup.md | 67 ++++++-- docs/ko/config_rover/velocity_tuning.md | 4 +- docs/ko/dev_log/logging.md | 13 +- docs/ko/sensor/inertial_navigation_systems.md | 23 ++- docs/ko/sim_sih/index.md | 148 +++++++++++------- docs/ko/smart_batteries/rotoye_batmon.md | 5 - docs/ko/test_and_ci/test_flights.md | 2 + docs/ko/test_cards/mc_06_optical_flow.md | 12 +- docs/ko/test_cards/mc_07_vio.md | 52 ++++++ docs/ko/test_cards/mc_08_dshot.md | 46 ++++++ 12 files changed, 321 insertions(+), 84 deletions(-) create mode 100644 docs/ko/test_cards/mc_07_vio.md create mode 100644 docs/ko/test_cards/mc_08_dshot.md diff --git a/docs/ko/SUMMARY.md b/docs/ko/SUMMARY.md index 59604e5db7..8542513eec 100644 --- a/docs/ko/SUMMARY.md +++ b/docs/ko/SUMMARY.md @@ -843,6 +843,8 @@ - [시험 MC_04 - 안전 장치 시험](test_cards/mc_04_failsafe_testing.md) - [Test MC_05 - Manual Modes (Inside)](test_cards/mc_05_indoor_flight_manual_modes.md) - [Test MC_06 - Optical Flow (Inside)](test_cards/mc_06_optical_flow.md) + - [Test MC_07 - VIO (Inside)](test_cards/mc_07_vio.md) + - [Test MC_08 - DSHOT ESC](test_cards/mc_08_dshot.md) - [단위 테스트](test_and_ci/unit_tests.md) - [Fuzz Tests](test_and_ci/fuzz_tests.md) - [지속 통합](test_and_ci/continous_integration.md) diff --git a/docs/ko/concept/system_startup.md b/docs/ko/concept/system_startup.md index c1f29f7664..5dc6d5b985 100644 --- a/docs/ko/concept/system_startup.md +++ b/docs/ko/concept/system_startup.md @@ -95,6 +95,8 @@ This is documented below. The best way to customize the system startup is to introduce a [new frame configuration](../dev_airframes/adding_a_new_frame.md). The frame configuration file can be included in the firmware or on an SD Card. +#### Dynamic customization + If you only need to "tweak" the existing configuration, such as starting one more application or setting the value of a few parameters, you can specify these by creating two files in the `/etc/` directory of the SD Card: - [/etc/config.txt](#customizing-the-configuration-config-txt): modify parameter values @@ -111,7 +113,7 @@ Windows에서 편집하는 경우 적절한 편집기를 사용하여야 합니 These files are referenced in PX4 code as `/fs/microsd/etc/config.txt` and `/fs/microsd/etc/extras.txt`, where the root folder of the microsd card is identified by the path `/fs/microsd`. ::: -#### 구성 사용자 정의(config.txt) +##### 구성 사용자 정의(config.txt) The `config.txt` file can be used to modify parameters. It is loaded after the main system has been configured and _before_ it is booted. @@ -123,7 +125,7 @@ param set-default PWM_MAIN_DIS3 1000 param set-default PWM_MAIN_MIN3 1120 ``` -#### Starting Additional Applications (extras.txt) +##### Starting Additional Applications (extras.txt) The `extras.txt` can be used to start additional applications after the main system boot. 일반적으로, 페이로드 콘트롤러나 유사한 선택적 사용자 지정 구성 요소들입니다. @@ -150,3 +152,28 @@ Calling an unknown command in system boot files may result in boot failure. mandatory_app start # Will abort boot if mandatory_app is unknown or fails ``` + +#### Additional customization + +In rare cases where the desired setup cannot be achieved through frame configuration or dynamic customization, +you can add a script that will be contained in the binary. + +**Note**: In almost all cases, you should use a frame configuration. This method should only be used for +edge-cases such as customizing `cannode` based boards. + +- Add a new init script in `boards///init` that will run during board startup. 예: + ```sh + # File: boards///init/rc.additional + param set-default + ``` + +- Add a new board variant in `boards///.px4board` that includes the additional script. 예: + ```sh + # File: boards///var.px4board + CONFIG_BOARD_ADDITIONAL_INIT="rc.additional" + ``` + +- Compile the firmware with your new variant by appending the variant name to the compile target. 예: + ```sh + make _var + ``` diff --git a/docs/ko/config_rover/basic_setup.md b/docs/ko/config_rover/basic_setup.md index 78aba9a4a9..c03f6d6fe2 100644 --- a/docs/ko/config_rover/basic_setup.md +++ b/docs/ko/config_rover/basic_setup.md @@ -27,10 +27,18 @@ That is the minimum setup to use the rover in [Manual mode](../flight_modes_rover/manual.md#manual-mode). +:::info +The rest of the tuning on this page is not mandatory for [Manual mode](../flight_modes_rover/manual.md#manual-mode), but it will have an effect on the behaviour of the rover. +::: + +:::warning +Do not skip the rest of this setup if you intend to use more sophisticated modes! +All parameters will be mandatory for all subsequent modes, except those tagged as `(Optional)`. +::: + ## Geometric Parameters -Manual mode is also affected by (optional) acceleration/deceleration limits set using the geometric described below. -These limits are mandatory for all other modes. +First, we set up the geometric parameters of the rover: ![Geometric parameters](../../assets/config/rover/geometric_parameters.png) @@ -42,7 +50,7 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and 2. [RA_MAX_STR_ANG](#RA_MAX_STR_ANG) [deg]: Measure the maximum steering angle. 3. (Optional) [RA_STR_RATE_LIM](#RA_STR_RATE_LIM) [deg/s]: Maximum steering rate you want to allow for your rover. - :::tip + ::: tip This value depends on your rover and use case. For bigger rovers there might be a mechanical limit that is easy to identify by steering the rover at a standstill and increasing [RA_STR_RATE_LIM](#RA_STR_RATE_LIM) until you observe the steering rate to no longer be limited by the parameter. @@ -51,7 +59,7 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and ::: - :::warning + ::: warning A low maximum steering rate makes the rover worse at tracking steering setpoints, which can lead to a poor performance in the subsequent modes. ::: @@ -76,7 +84,7 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and 2. (Optional) [RO_ACCEL_LIM](#RO_ACCEL_LIM) [m/s^2]: Maximum acceleration you want to allow for your rover. - + :::tip Your rover has a maximum possible acceleration which is determined by the maximum torque the motor can supply. @@ -109,6 +117,39 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and ::: +## (Optional) Stick Input Mapping + +Input shaping can be used to adjust the default linear mapping from stick inputs $\in [-1, 1]$ to normalized setpoints $\in [-1, 1]$. Applying this specifically to the steering input, can provide a smoother driving experience, by enabling the user to make small adjustments when the stick is close to the center, but still send large inputs when moving them to the edges. +We provide this input shaping through the super exponential function: + +$$ +\delta = \frac{(f \cdot x^3 + x(1-f)) \cdot (1-g)}{1-g \cdot |x|} +$$ + +with: + + - $\delta \in [-1, 1]=$ Normalized steering setpoint. + - $x \in [-1, 1]=$ Normalized stick input. + - $f=$ [RO_YAW_EXPO](#RO_YAW_EXPO): `0` Purely linear input curve, `1` Purely cubic input curve. + - $g=$ [RO_YAW_SUPEXPO](#RO_YAW_SUPEXPO): `0` Pure Expo function, `0.7` reasonable shape enhancement for intuitive stick feel, `0.95` very strong bent input curve only near maxima have effect. + +In [Manual mode](../flight_modes_rover/manual.md#manual-mode) we can additionally scale $\delta$ with an additional parameter $r$: + + - Differential Rover: $r=$ [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN), which enables adjusting the slope of the input mapping. This leads to a normalized steering input $\hat{\delta} = \delta \cdot r \in$ [-[RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN), [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN)]. + - Mecanum Rover: $r=$ [RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN), which enables adjusting the slope of the input mapping. This leads to a normalized steering input $\hat{\delta} = \delta \cdot r \in$ [-[RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN), [RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN)]. + +This scaling is useful to limit the normalized steering setpoint, if it is too aggresive for your rover in manual mode. + +You can experiment with the relationships graphically using the [PX4 SuperExpo Rover calculator](https://www.desmos.com/calculator/gwm8lrlanx). + +:::info +In [Acro](../flight_modes_rover/manual.md#acro-mode), [Stabilized](../flight_modes_rover/manual.md#stabilized-mode) and [Position](../flight_modes_rover/manual.md#position-mode) Mode, $\delta$ is instead scaled by $r=$ [RO_YAW_RATE_LIM](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED) for all rovers. This leads to a yaw rate setpoint $\dot{\psi} = \delta \cdot r \in$ [-[RO_YAW_RATE_LIM](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED), [RO_YAW_RATE_LIM](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED)]. This parameter is setup during [rate tuning](rate_tuning.md). +::: + +:::info +The input shaping through [RO_YAW_EXPO](#RO_YAW_EXPO) and [RO_YAW_SUPEXPO](#RO_YAW_SUPEXPO) applies for all manual modes, while [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN)/[RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN) only affects full manual mode. +::: + You can now continue the configuration process with [rate tuning](rate_tuning.md). ## Parameter Overview @@ -118,6 +159,8 @@ You can now continue the configuration process with [rate tuning](rate_tuning.md | [RO_MAX_THR_SPEED](../advanced_config/parameter_reference.md#RO_MAX_THR_SPEED) | Speed the rover drives at maximum throttle | $m/s$ | | [RO_ACCEL_LIM](../advanced_config/parameter_reference.md#RO_ACCEL_LIM) | (Optional) Maximum allowed acceleration | $m/s^2$ | | [RO_DECEL_LIM](../advanced_config/parameter_reference.md#RO_DECEL_LIM) | (Optional) Maximum allowed deceleration | $m/s^2$ | +| [RO_YAW_EXPO](../advanced_config/parameter_reference.md#RO_YAW_EXPO) | (Optional) Yaw rate expo factor | $-$ | +| [RO_YAW_SUPEXPO](../advanced_config/parameter_reference.md#RO_YAW_SUPEXPO) | (Optional) Yaw rate super expo factor | $-$ | ### Ackermann Specific @@ -129,12 +172,14 @@ You can now continue the configuration process with [rate tuning](rate_tuning.md ### Differential Specific -| 매개변수 | 설명 | Unit | -| ----------------------------------------------------------------------------------------------------------------------------------------------- | ----------- | ---- | -| [RD_WHEEL_TRACK](../advanced_config/parameter_reference.md#RD_WHEEL_TRACK) | Wheel track | m | +| 매개변수 | 설명 | Unit | +| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------ | ---- | +| [RD_WHEEL_TRACK](../advanced_config/parameter_reference.md#RD_WHEEL_TRACK) | Wheel track | $m$ | +| [RD_YAW_STK_GAIN](../advanced_config/parameter_reference.md#RD_YAW_STK_GAIN) | (Optional) Yaw stick gain for Manual mode | $-$ | ### Mecanum Specific -| 매개변수 | 설명 | Unit | -| ----------------------------------------------------------------------------------------------------------------------------------------------- | ----------- | ---- | -| [RM_WHEEL_TRACK](../advanced_config/parameter_reference.md#RM_WHEEL_TRACK) | Wheel track | m | +| 매개변수 | 설명 | Unit | +| ----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------ | ---- | +| [RM_WHEEL_TRACK](../advanced_config/parameter_reference.md#RM_WHEEL_TRACK) | Wheel track | $m$ | +| [RM_YAW_STK_GAIN](../advanced_config/parameter_reference.md#RM_YAW_STK_GAIN) | (Optional) Yaw stick gain for Manual mode | $-$ | diff --git a/docs/ko/config_rover/velocity_tuning.md b/docs/ko/config_rover/velocity_tuning.md index 1f07e31659..f264b81dbc 100644 --- a/docs/ko/config_rover/velocity_tuning.md +++ b/docs/ko/config_rover/velocity_tuning.md @@ -20,7 +20,7 @@ To tune the velocity controller configure the following [parameters](../advanced 2. [RO_MAX_THR_SPEED](#RO_MAX_THR_SPEED) [m/s]: This parameter is used to calculate the feed-forward term of the closed loop speed control which linearly maps desired speeds to normalized motor commands. As mentioned in the [Manual mode](../flight_modes_rover/manual.md#manual-mode) configuration , a good starting point is the observed ground speed when the rover drives at maximum throttle in [Manual mode](../flight_modes_rover/manual.md#manual-mode). - + ::: tip To further tune this parameter: @@ -94,7 +94,7 @@ These steps are only necessary if you are tuning/want to unlock the manual [Posi The rover is now ready to drive in [Position mode](../flight_modes_rover/manual.md#position-mode) and the configuration can be continued with [position tuning](position_tuning.md). -## Attitude Controller Structure (Info Only) +## Velocity Controller Structure (Info Only) This section provides additional information for developers and people with experience in control system design. diff --git a/docs/ko/dev_log/logging.md b/docs/ko/dev_log/logging.md index 7892ff18a5..4373a1e946 100644 --- a/docs/ko/dev_log/logging.md +++ b/docs/ko/dev_log/logging.md @@ -33,16 +33,17 @@ The logging system is configured by default to collect sensible logs for [flight Logging may further be configured using the [SD Logging](../advanced_config/parameter_reference.md#sd-logging) parameters. 변경할 가능성이 높은 매개변수가 아래에 설명되어 있습니다. -| 매개변수 | 설명 | -| --------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [SDLOG_MODE](../advanced_config/parameter_reference.md#SDLOG_MODE) | Logging Mode. Defines when logging starts and stops.
- `-1`: Logging disabled.
- `0`: Log when armed until disarm (default).
- `1`: Log from boot until disarm.
- `2`: Log from boot until shutdown.
- `3`: Log based on the [AUX1 RC channel](../advanced_config/parameter_reference.md#RC_MAP_AUX1).
- `4`: Log from first armed until shutdown. | -| [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) | 로깅 프로파일. Use this to enable less common logging/analysis (e.g. for EKF2 replay, high rate logging for PID & filter tuning, thermal temperature calibration). | -| [SDLOG_MISSION](../advanced_config/parameter_reference.md#SDLOG_MISSION) | Create very small additional "Mission Log".
This log can _not_ be used with [Flight Review](../log/flight_log_analysis.md#flight-review-online-tool), but is useful when you need a small log for geotagging or regulatory compliance. | +| 매개변수 | 설명 | +| --------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [SDLOG_MODE](../advanced_config/parameter_reference.md#SDLOG_MODE) | Logging Mode. Defines when logging starts and stops.
- `0`: Log when armed until disarm (default).
- `1`: Log from boot until disarm.
- `2`: Log from boot until shutdown.
- `3`: Log based on the [AUX1 RC channel](../advanced_config/parameter_reference.md#RC_MAP_AUX1).
- `4`: Log from first armed until shutdown. | +| [SDLOG_BACKEND](../advanced_config/parameter_reference.md#SDLOG_BACKEND) | Logging Backend (bitmask). Setting a bit enables the corresponding backend. If no backend is selected, the logger is disabled.
- bit `0`: SD card logging.
- bit `1`: Mavlink logging. | +| [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) | 로깅 프로파일. Use this to enable less common logging/analysis (e.g. for EKF2 replay, high rate logging for PID & filter tuning, thermal temperature calibration). | +| [SDLOG_MISSION](../advanced_config/parameter_reference.md#SDLOG_MISSION) | Create very small additional "Mission Log".
This log can _not_ be used with [Flight Review](../log/flight_log_analysis.md#flight-review-online-tool), but is useful when you need a small log for geotagging or regulatory compliance. | Useful settings for specific cases: - Raw sensor data for comparison: [SDLOG_MODE=1](../advanced_config/parameter_reference.md#SDLOG_MODE) and [SDLOG_PROFILE=64](../advanced_config/parameter_reference.md#SDLOG_PROFILE). -- Disabling logging altogether: [SDLOG_MODE=`-1`](../advanced_config/parameter_reference.md#SDLOG_MODE) +- Disabling logging altogether: [SDLOG_BACKEND=`0`](../advanced_config/parameter_reference.md#SDLOG_BACKEND) ### Logger module diff --git a/docs/ko/sensor/inertial_navigation_systems.md b/docs/ko/sensor/inertial_navigation_systems.md index 4103634ea0..9c329a2b24 100644 --- a/docs/ko/sensor/inertial_navigation_systems.md +++ b/docs/ko/sensor/inertial_navigation_systems.md @@ -2,13 +2,32 @@ PX4 typically runs on flight controllers that include an IMU, such as the Pixhawk series, and fuse the sensor data along with GNSS information in the EKF2 estimator to determine vehicle attitude, heading, position, and velocity. -However PX4 can also use some INS devices as either sources of raw data, or as an external estimator, replacing the EKF. +However PX4 can also use some INS devices as either sources of raw data, or as an external estimator, replacing EKF2. -Systems that can be used in this way include: +## Supported INS Systems + +INS systems that can be used as a replacement for EKF2 in PX4: - [InertialLabs](../sensor/inertiallabs.md) - [VectorNav](../sensor/vectornav.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data. +## PX4 Firmware + +The driver module for your INS system may not be included in the PX4 firmware for your flight controller by default. + +You can check by searching the [default.px4board](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/fmu-v6c/default.px4board#L25) configuration file for your target board for either: + +- `CONFIG_COMMON_INS`, which includes drivers for [all INS systems](https://github.com/PX4/PX4-Autopilot/blob/main/src/drivers/ins/Kconfig). +- The key for the particular INS system you are using, such as: + - `CONFIG_DRIVERS_INS_ILABS` + - `CONFIG_DRIVERS_INS_MICROSTRAIN` + - `CONFIG_DRIVERS_INS_VECTORNAV` + +If the required key is not present you can include the module in firmware by adding the key to the `default.px4board` file, or using the [kconfig board configuration tool](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) and then select the driver you want (`Drivers -> INS`). +Note that if you're working on a flight controller where flash memory is limited, you're better off installing just the modules you need. + +You will then need to rebuild the firmware. + ## Glossary ### Inertial Measurement Unit (IMU) diff --git a/docs/ko/sim_sih/index.md b/docs/ko/sim_sih/index.md index 181fc9904f..492fd425ce 100644 --- a/docs/ko/sim_sih/index.md +++ b/docs/ko/sim_sih/index.md @@ -71,24 +71,24 @@ To check that these are present on your flight controller: 3. Enter the following commands in the console: - ```sh - pwm_out_sim status - ``` + ```sh + pwm_out_sim status + ``` - ```sh - sensor_baro_sim status - ``` + ```sh + sensor_baro_sim status + ``` - ```sh - sensor_gps_sim status - ``` + ```sh + sensor_gps_sim status + ``` - ```sh - sensor_mag_sim status - ``` + ```sh + sensor_mag_sim status + ``` - ::: tip - Note that when using SIH on real hardware you do not need to additionally enable the modules using their corresponding parameters ([SENS_EN_GPSSIM](../advanced_config/parameter_reference.md#SENS_EN_GPSSIM), [SENS_EN_BAROSIM](../advanced_config/parameter_reference.md#SENS_EN_BAROSIM), [SENS_EN_MAGSIM](../advanced_config/parameter_reference.md#SENS_EN_MAGSIM)). + ::: tip + Note that when using SIH on real hardware you do not need to additionally enable the modules using their corresponding parameters ([SENS_EN_GPSSIM](../advanced_config/parameter_reference.md#SENS_EN_GPSSIM), [SENS_EN_BAROSIM](../advanced_config/parameter_reference.md#SENS_EN_BAROSIM), [SENS_EN_MAGSIM](../advanced_config/parameter_reference.md#SENS_EN_MAGSIM)). ::: @@ -141,12 +141,12 @@ To set up/start SIH: 1. Connect the flight controller to the desktop computer with a USB cable. 2. Open QGroundControl and wait for the flight controller too boot and connect. 3. Open [Vehicle Setup > Airframe](../config/airframe.md) then select the desired frame: - - [SIH Quadcopter X](../airframes/airframe_reference.md#copter_simulation_sih_quadcopter_x) - - **SIH Hexacopter X** (currently only has an airframe for SITL to safe flash so on flight control hardware it has to be manually configured equivalently). - - [SIH plane AERT](../airframes/airframe_reference.md#plane_simulation_sih_plane_aert) - - [SIH Tailsitter Duo](../airframes/airframe_reference.md#vtol_simulation_sih_tailsitter_duo) - - [SIH Standard VTOL QuadPlane](../airframes/airframe_reference.md#vtol_simulation_sih_standard_vtol_quadplane) - - [SIH Ackermann Rover](../airframes/airframe_reference.md#rover_rover_sih_rover_ackermann) + - [SIH Quadcopter X](../airframes/airframe_reference.md#copter_simulation_sih_quadcopter_x) + - **SIH Hexacopter X** (currently only has an airframe for SITL to safe flash so on flight control hardware it has to be manually configured equivalently). + - [SIH plane AERT](../airframes/airframe_reference.md#plane_simulation_sih_plane_aert) + - [SIH Tailsitter Duo](../airframes/airframe_reference.md#vtol_simulation_sih_tailsitter_duo) + - [SIH Standard VTOL QuadPlane](../airframes/airframe_reference.md#vtol_simulation_sih_standard_vtol_quadplane) + - [SIH Ackermann Rover](../airframes/airframe_reference.md#rover_rover_sih_rover_ackermann) The autopilot will then reboot. The `sih` module is started on reboot, and the vehicle should be displayed on the ground control station map. @@ -172,19 +172,19 @@ To display the simulated vehicle: 3. Start jMAVSim by calling the script **jmavsim_run.sh** from a terminal: - ```sh - ./Tools/simulation/jmavsim/jmavsim_run.sh -q -d /dev/ttyACM0 -b 2000000 -o - ``` + ```sh + ./Tools/simulation/jmavsim/jmavsim_run.sh -q -d /dev/ttyACM0 -b 2000000 -o + ``` - where the flags are: + where the flags are: - - `-q` to allow the communication to _QGroundControl_ (optional). - - `-d` to start the serial device `/dev/ttyACM0` on Linux. - On macOS this would be `/dev/tty.usbmodem1`. - - `-b` to set the serial baud rate to `2000000`. - - `-o` to start jMAVSim in _display Only_ mode (i.e. the physical engine is turned off and jMAVSim only displays the trajectory given by the SIH in real-time). - - add a flag `-a` to display an aircraft or `-t` to display a tailsitter. - If this flag is not present a quadrotor will be displayed by default. + - `-q` to allow the communication to _QGroundControl_ (optional). + - `-d` to start the serial device `/dev/ttyACM0` on Linux. + On macOS this would be `/dev/tty.usbmodem1`. + - `-b` to set the serial baud rate to `2000000`. + - `-o` to start jMAVSim in _display Only_ mode (i.e. the physical engine is turned off and jMAVSim only displays the trajectory given by the SIH in real-time). + - add a flag `-a` to display an aircraft or `-t` to display a tailsitter. + If this flag is not present a quadrotor will be displayed by default. 4. After few seconds, _QGroundControl_ can be opened again. @@ -201,41 +201,41 @@ To run SIH as SITL: 1. Install the [PX4 Development toolchain](../dev_setup/dev_env.md). 2. Run the appropriate make command for each vehicle type (at the root of the PX4-Autopilot repository): - - Quadcopter + - Quadcopter - ```sh - make px4_sitl sihsim_quadx - ``` + ```sh + make px4_sitl sihsim_quadx + ``` - - Hexacopter + - Hexacopter - ```sh - make px4_sitl sihsim_hex - ``` + ```sh + make px4_sitl sihsim_hex + ``` - - Fixed-wing (plane) + - Fixed-wing (plane) - ```sh - make px4_sitl sihsim_airplane - ``` + ```sh + make px4_sitl sihsim_airplane + ``` - - XVert VTOL tailsitter + - XVert VTOL tailsitter - ```sh - make px4_sitl sihsim_xvert - ``` + ```sh + make px4_sitl sihsim_xvert + ``` - - 표준 VTOL + - 표준 VTOL - ```sh - make px4_sitl sihsim_standard_vtol - ``` + ```sh + make px4_sitl sihsim_standard_vtol + ``` - - Ackermann Rover + - Ackermann Rover - ```sh - make px4_sitl sihsim_rover_ackermann - ``` + ```sh + make px4_sitl sihsim_rover_ackermann + ``` ### Change Simulation Speed @@ -328,6 +328,44 @@ For SIH as SITL (no FC): For specific examples see the `_sihsim_` airframes in [ROMFS/px4fmu_common/init.d-posix/airframes](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/) (SIH as SITL) and [ROMFS/px4fmu_common/init.d/airframes](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d/airframes) (SIH on FC). +## Controlling Actuators in SIH + +:::warning +If you want to control throttling actuators in SIH, make sure to remove propellers for safety. +::: + +In some scenarios, it may be useful to control an actuator while running SIH. For example, you might want to verify that winches or grippers are functioning correctly by checking the servo responses. + +To enable actuator control in SIH: + +1. Configure PWM parameters in the airframe file: + +Ensure your airframe file includes the necessary parameters to map PWM outputs to the correct channels. + +For example, if a servo is connected to MAIN 3 and you want to map it to AUX1 on your RC, use the following command: + +`param set-default PWM_MAIN_FUNC3 407` + +You can find a full list of available values for `PWM_MAIN_FUNCn` [here](../advanced_config/parameter_reference.md#PWM_MAIN_FUNC1). In this case, `407` maps the MAIN 3 output to AUX1 on the RC. + +Alternatively, you can use the [`PWM_AUX_FUNCn`](../advanced_config/parameter_reference.md#PWM_AUX_FUNC1) parameters. + +You may also configure the output as desired: + +- Disarmed PWM: ([`PWM_MAIN_DISn`](../advanced_config/parameter_reference.md#PWM_MAIN_DIS1) / [`PWM_AUX_DIS1`](../advanced_config/parameter_reference.md#PWM_AUX_DIS1)) +- Minimum PWM ([`PWM_MAIN_MINn`](../advanced_config/parameter_reference.md#PWM_MAIN_MIN1) / [`PWM_AUX_MINn`](../advanced_config/parameter_reference.md#PWM_AUX_MIN1)) +- Maximum PWM ([`PWM_MAIN_MAXn`](../advanced_config/parameter_reference.md#PWM_MAIN_MAX1) / [`PWM_AUX_MAXn`](../advanced_config/parameter_reference.md#PWM_AUX_MAX1)) + +2. Manually start the PWM output driver + +For safety, the PWM driver is not started automatically in SIH. To enable it, run the following command in the MAVLink shell: + +`pwm_out start` + +And to disable it again: + +`pwm_out stop` + ## Dynamic Models The dynamic models for the various vehicles are: diff --git a/docs/ko/smart_batteries/rotoye_batmon.md b/docs/ko/smart_batteries/rotoye_batmon.md index 06f7e5cd8f..896ef46e27 100644 --- a/docs/ko/smart_batteries/rotoye_batmon.md +++ b/docs/ko/smart_batteries/rotoye_batmon.md @@ -3,11 +3,6 @@ [Rotoye Batmon](https://rotoye.com/batmon/) is a kit for adding smart battery functionality to off-the-shelf Lithium-Ion and LiPo batteries. 독립형 장치로 또는 공장에서 조립된 스마트 배터리의 일부로 구입할 수 있습니다. -:::info -At time of writing you can only use Batmon by [building a custom branch of PX4](#build-px4-firmware). -Support in the codeline is pending [PR approval](https://github.com/PX4/PX4-Autopilot/pull/16723). -::: - ![Rotoye Batmon Board](../../assets/hardware/smart_batteries/rotoye_batmon/smart-battery-rotoye.jpg) ![Pre-assembled Rotoye smart battery](../../assets/hardware/smart_batteries/rotoye_batmon/smart-battery-rotoye-pack.jpg) diff --git a/docs/ko/test_and_ci/test_flights.md b/docs/ko/test_and_ci/test_flights.md index 062e7443eb..eabc3c3176 100644 --- a/docs/ko/test_and_ci/test_flights.md +++ b/docs/ko/test_and_ci/test_flights.md @@ -28,3 +28,5 @@ These are run by the test team as part of release testing, and for more signific - [MC_04 - Failsafe Testing](../test_cards/mc_04_failsafe_testing.md) - [MC_05 - Indoor Flight (Manual Modes)](../test_cards/mc_05_indoor_flight_manual_modes.md) - [MC_06 - Indoor Flight (Optical Flow)](../test_cards/mc_06_optical_flow.md) +- [MC_07 - VIO (Visual-Inertial Odometry)](../test_cards/mc_07_vio.md) +- [MC_08 - DSHOT ESC](../test_cards/mc_08_dshot.md) diff --git a/docs/ko/test_cards/mc_06_optical_flow.md b/docs/ko/test_cards/mc_06_optical_flow.md index 3cd59ac133..901e113218 100644 --- a/docs/ko/test_cards/mc_06_optical_flow.md +++ b/docs/ko/test_cards/mc_06_optical_flow.md @@ -2,11 +2,19 @@ ## Objective -To test that optical flow / external vision work as expected +To test that optical flow works as expected ## Preflight Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation +([Setup Information here](../sensor/optical_flow.md)) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` Ensure that the drone can go into Altitude / Position flight mode while still on the ground @@ -39,5 +47,7 @@ Ensure that the drone can go into Altitude / Position flight mode while still on ## 예상 결과 - 추력을 올릴 때 서서히 이륙한다 +- Drone should hold altitude in Altitude Flight mode without wandering +- Drone should hold position within 1 meter in Position Flight mode without pilot moving sticks - 위에 언급한 어떤 비행 모드에서도 떨림이 나타나서는 안됨 - 지면에 착륙시, 콥터가 지면에서 튀면 안됨 diff --git a/docs/ko/test_cards/mc_07_vio.md b/docs/ko/test_cards/mc_07_vio.md new file mode 100644 index 0000000000..8d338f6883 --- /dev/null +++ b/docs/ko/test_cards/mc_07_vio.md @@ -0,0 +1,52 @@ +# Test MC_07 - VIO (Visual-Inertial Odometry) + +## Objective + +To test that external vision (VIO) works as expected + +## Preflight + +Disconnect all GPS / compasses and ensure vehicle is using VIO for navigation + +Ensure that the drone can go into Altitude / Position flight mode while still on the ground + +Ensure there are no other sources of positioning besides VIO: + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `0` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `15` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` + +## Flight Tests + +❏ Altitude flight mode + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response set to climb/descent rate + +❏ Position flight mode + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## 착륙 + +❏ Land in either Position or Altitude mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## 예상 결과 + +- 추력을 올릴 때 서서히 이륙한다 +- Drone should hold altitude in Altitude Flight mode without wandering +- Drone should hold position within 1 meter in Position Flight mode without pilot moving sticks +- 위에 언급한 어떤 비행 모드에서도 떨림이 나타나서는 안됨 +- 지면에 착륙시, 콥터가 지면에서 튀면 안됨 diff --git a/docs/ko/test_cards/mc_08_dshot.md b/docs/ko/test_cards/mc_08_dshot.md new file mode 100644 index 0000000000..e5b7f8f073 --- /dev/null +++ b/docs/ko/test_cards/mc_08_dshot.md @@ -0,0 +1,46 @@ +# Test MC_08 - DSHOT ESC + +## Objective + +Regression test for DSHOT working with PX4 + +## Preflight + +- Ensure vehicle is using a DSHOT ESC. +- Parameter [DSHOT_BIDIR_EN](../advanced_config/parameter_reference.md#DSHOT_BIDIR_EN) is enabled +- Parameter [DSHOT_TEL_CFG](../advanced_config/parameter_reference.md#DSHOT_TEL_CFG) is configured (if ESC supports telemetry) +- Parameter [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) has Debug (`5`) checked + +## Flight Tests + +❏ Stabilized Flight mode + +    ❏ Takeoff in stabilized flight mode to ensure correct motor spin + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response 1:1 + +❏ Position flight mode + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## 착륙 + +❏ Land in either Position or Altitude mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## 예상 결과 + +- Download flight logs +- Load into Data Plot Juggler +- Ensure data is logged for esc_status/esc.0x/esc_rpm + + ![Reference frames](../../assets/test_cards/dshot_log_output.png) From 47c0fef8c863c46d52043133c31ad4257d1000cf Mon Sep 17 00:00:00 2001 From: JM Wang <61965335+jyhminwang@users.noreply.github.com> Date: Thu, 11 Sep 2025 07:34:13 +0800 Subject: [PATCH 021/812] [DOCS] accton godwit ga1, a new manufacture board (#25411) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Add docs for Accton-Godwit-GA1 * Update Accton-Godwit_GA1 in SUMMARY.md add docs of accton’s new manufacturer board GA1 in TOC(SUMMARY.md) * Subedit * update wording in accton-godwit_ga1.md --------- Co-authored-by: Hamish Willee --- .../accton-godwit/ga1/gps.png | Bin 0 -> 21112 bytes .../accton-godwit/ga1/motor_servo.png | Bin 0 -> 30962 bytes .../accton-godwit/ga1/orientation.png | Bin 0 -> 18156 bytes .../accton-godwit/ga1/outlook.png | Bin 0 -> 26577 bytes .../accton-godwit/ga1/pin_definition.png | Bin 0 -> 37749 bytes .../accton-godwit/ga1/power.png | Bin 0 -> 19514 bytes .../accton-godwit/ga1/radio.png | Bin 0 -> 25716 bytes .../accton-godwit/ga1/sdcard.png | Bin 0 -> 18474 bytes .../accton-godwit/ga1/wiring.png | Bin 0 -> 51536 bytes docs/en/SUMMARY.md | 1 + .../en/flight_controller/accton-godwit_ga1.md | 153 ++++++++++++++++++ .../autopilot_manufacturer_supported.md | 1 + 12 files changed, 155 insertions(+) create mode 100644 docs/assets/flight_controller/accton-godwit/ga1/gps.png create mode 100644 docs/assets/flight_controller/accton-godwit/ga1/motor_servo.png create mode 100644 docs/assets/flight_controller/accton-godwit/ga1/orientation.png create mode 100644 docs/assets/flight_controller/accton-godwit/ga1/outlook.png create mode 100644 docs/assets/flight_controller/accton-godwit/ga1/pin_definition.png create mode 100644 docs/assets/flight_controller/accton-godwit/ga1/power.png create mode 100644 docs/assets/flight_controller/accton-godwit/ga1/radio.png create mode 100644 docs/assets/flight_controller/accton-godwit/ga1/sdcard.png create mode 100644 docs/assets/flight_controller/accton-godwit/ga1/wiring.png create mode 100644 docs/en/flight_controller/accton-godwit_ga1.md diff --git a/docs/assets/flight_controller/accton-godwit/ga1/gps.png b/docs/assets/flight_controller/accton-godwit/ga1/gps.png new file mode 100644 index 0000000000000000000000000000000000000000..eea6e258991b396b46446b30f739a0d899af2dc7 GIT binary patch literal 21112 zcmbTccT`kO(=R#-2ndKG2uRK#Fl3O7B*{7BfaE-+A%h?YsN|e;RA9(y4;jfIIWq{7 zhBQRU;jZU>-uJoRch0%ztb2O(UaPC?SHJ4&uIj!2*k3f%-V!{1`4|KO5hyCiYJorx z0TAdxEDi<;1oFJ$+XR6y(RMlpFauQ;5esK0u$iT^xfR&k$p!RR6O;6IF|%;6g3+2= z+1NqF=?@U?^t5)C;`I6gs@$qBGFG;B3chYu+P-Q!7QPM^!j|-s60~C8BHm6ePF658 zT5l&usJn=_IQ_qPMWF5?e@%1I)BXzra}cM0^Or+f162)L8D}>uS|KnGrv*1RH?5E` zSlGhCg5T1LgO-<@mzRs1kBf(&lZQuyS5SmUnD*a|UV>K4&C*&#OIH5h&fF}m#p!Kf zFc%RnE-x=HuooZL+0BNFM_5>xi<_5=mzUGc(wfuV2MROu=7hR4{D(o-%H6`v&IM-Y z45j^x(ahZ0113&S|DPC~T>hbjy8nBhES#OVyv!j zd$hZbkBb$TmX*7+hnt0!oTn8O#_(4(E+R5+R%S3~HyvkZ$N!v^#($Pf%gYDmqh-~% zgIYR!xwHKj11niGn3Xs^FE_6MC-+}nhet?+Us!}sn4SBz2siiNP*rD3J8Pf+8Twj; zS6GBw@V`N=U}lzPFth(7*wRA8+S$#?3?@!*=VWGM#pMFEp{M<48%1QC9i81&oh_}z z>G}S(3RP7RMW{Q>3~FJeC@W6y?c@Tsv$GW8=d}>#wlcHe6cDr$;uI9%=jVJaWG2YT z%g^)LLXbz8|FxOrf9z$QEj<1@+5gyE{{OUBceAsxgPJ-1U-SG`aDSzQh=QFv%-PN7 z-xZ;4<@)cDqaE$PvOvVl;;-x$r?>d)SgkDS|2=K@f4u{L(|XxjLI1bM{Wr|r*&60$ z=4SQA#tI7iKc*9x1g#j?Uv>C*99;ini2u_4mzw<#TuWB|ui-yekOb}jdx=>=Eyd~G z=p`ja_4$8*Kpk$dZ+!azonot@Ly*Por8!$3yz zx0s#%@BWY2*4F;__-{;gbIn?E}{2LuBB1N-k{ZgzG~OH1p2)n;es z;Nal=GxI;#;^X80SJnTZ{ad7>q9P_H&d$yuBqaRX9S8)Xq@>Kw&f(zTc>er(c6QFs zpFjWRdHM2Xc6Lr~ZXP)~IS2$IA|lGp&LJl!&(6-Fqoe!R%L0Urjs4HEK_F0VZC!SD z4%xq&h=>RX1e%zb_!|iVfts3{|7LD&Z3Tfq&CSg!NkP$>eVY68XA0j{D6P}EiG*(CZ_M-%kJ;*K_CzV8OhI|qg`Fy zTU%QT3yb~z1DBVV`}_M14UNMfzW$ycRaMm|Cns?cUk?rr+S}U$0|Td~rYkEeM@L7G zjt(UyB~49DfB*jd>({TAmR3Ve^_Z9#b#?XTW?*=Dcztb6MMkQ&wyw9gx2>%WfoRFe z$>C;Zn3C^1=)aB)634Wfsx_W14=g*%%&&|yNjSXB} zT;1J2=;`VC`1owzLuzVjOG-*BD&VrRvS>6qEiLW1eOOml7XT2`?0WtE{cUaSHwVWk z6lz}5YA>h8+S>Zh==><5TVl>Xsg@r|p6mJI2 z{kCI@UXzd)k_dq=-2N(%JeZc6HVEyq(&6a=Xj`+n;qsn7F6SxU>=b}Nv>-*H?k|MD-mB_ z`)+^EJ5QaQ#=?=kf@`Q?Abl3`rsX(U>>%60;)Za~;pZQL)oV@5DmvlWtq(Vd_7lWb zrVHgidHug?9de$qHjbRqLG9@vVgMCfxUpxXiiA>IX17_nrj$GfVYYD9+>3 zh#@}$+E-NGBHQLeey6g!<&?t7(zUzm-e@}Vw37YcCiw3==2+$7B}w&xM>zd=Peh3} z5{Y`DF|xFu?Q;A6uX8vTh~-!H;Ks;oSwt0n>Q1Ifs~L(-#ZuI-ZL`X{az?GT!M+BJ56$V*G32W z-4tRKrRvVxp0{G_P$Ux&Hr>{=s{S^1`y(k$`cU^r7UQa1o_~u2w2!-ZKUir}Tq#+) zi{}W7j;oa8r)J78c5cvd@Z*xl87eP|b9wPayXZdBwZ%P{8kE9{U;6kgrz6#B zmK9p_z^WSQ&WX2o1Quo_-NgyRlsjzhd+Pnsd`X{iy%>WFstK}kIg7!>#4>~- zWwP*DJ0vMHf@?m>U-48w;I^5oXJ-8wk1;v^V0SQBlvXE5Aovq0w?Jdy5WCK&pj~Q! zf}1jzQ@8)!I7Da(Yk1g$12?H#l=rJN#_NxpU(wJ%-4K_DBcX_u!gM^Z2MG(ok2fd$ zNi76imcFOH-0Xt5I9_!Ji+p-#Ao?J>v-Me}($3=tr0BAbHEAxPn9~OC@4-)46QD#- zb$&<&@nW#nHdS$yDqYa2J!B29t^zh6o1A0*d>A_#xmZ>M1jo=Kv1(kuXP}BFAWOO! zHQO=Qx3PtpF+O>CFxc>W6aF^;=uc!U`_W6GPapBAoBJiMKMGaDn}F)1>1o*=K^K?y+u0|3 zUon(=1*@K`Au{k=7X7Mqi>8stFK;cX35*OC8r5!A6*He|9Fy%=({jj99BWjVFzG#4 zD#2&3#`&^8)|3(5+!^~++Lbhs5=O;8=BxeDE5fM$c}$N!@hDk?S3&jkXEINWfntV< zEZcilHC$F6)T47R)55zk(dQJ5M3q4R|1ooZ*N5KN1>K2V>5usRI6ypq#sJLB&x?x) zQmGN@Xp{0mzCnvl|JWO!1*;zy&{|0vnhOmFc$4noR$Of}(i ztUk%t=5Z91KVB&5!91AtUksP_#7GqAF_nvM(hsV&8g|nX!k?MMRHSGN{18eU|W^?qHKeGHr z%VZ;vD%Sw-hdsw^NAj9_`7`a(~1prYPJ1 zD=aD`iu#zvVGijEJsVK;Yy~e7Jd%54cS(9V&5LL8L3%JNyf#}1{I1Il*M(7y6d|G? zn}}#}V#)TxvvdWqU{m%4gdx_RNe?3X&1|?1m@M&E6s}0q(srLub9%9aKUC(89wgiG z5OcO&XIFDT*Q#Iayb*g5;I~{Brgz3!-?&w$lM6}qw=H$zKb_f{AteKUEu5U1zjcoY zpCJ<=c$9S^aWNP;W?Y;7XQtE@KfKG`GvKZ)%=e6Q8z#)To%F#bv$eQ-JXf@)%_Y+* z1=S)KwzyB_#@D1>sob8YRIodY*7DQ+W?VTsTc`MiVG1$=9WW_q0_t>co%u2Xe!8Ua z*wq}+cWeIA$*K=ZewxS z;4Qw~&^z2w+r>U-H{brB0^7o+e)iKv)n&Cp^RK&y5L`vzZemLwKM$tqhI;CqY;zC0 zZ=++%4k}3e1KPa<)8}Td)!f%#%sRj*r^I`9+#X$pZ$@gDJ1gutuXVh_uHK;ZWXJYU zuLrU`;refcU5ybRIa7L3vY)UYmy=Us zmi5O|PcQtE{Lm7&N)nB8%?#xk|Y7QRM1U;FKucjB2J+Z>->i~RbrHgRB zYwVqDVh>en^;xqWqv4tizFDg&GVi-RL!9-;t8|mFmjTKP^9zV8(|vK zAl>2pVF@pr6tt;7OPoiBNF@WSgWs;_u^@C3L4b2CfVDiKZCxL~Vw+n+Oifg<;#vWb}% z+sJoW$=V8#9##l4l20~}U?;f*u88l-<`I?ts9+}F?rcnU^4(V;Y|->i>Av}n^orx< zpKzBgLIEaKtSQ@iy$HR4Eg$^^@JD>H%rT$ z0UyqSU{7(wH_zK!0(8&7pPg#}y`4v@_S!o}h;-xf%%03)4`rRkGxKi{qk9L)mz}T8 z@aBlg8LN7|KReMR`sWc-eHRfN9tStp_wyCKyZVp425d|lOgZu*Jhtxr(TjYeKQ*!g z-qMVIxrvj=Jn%X2|KqZ~dD)&Rnj+EUKJhH@d=Ke0nt6G)+y0`=-MDCFMlJ#`Q^)L( zOt>s!seel%d@-zmotZWj}?xK*h!~u-j z-R892Ed~Y_haZQ)r0y^EXO3=9*9di|j6Vk6bKUpk1YRB8Ph~ASFV0Z)DXLG=6*V=G zDA)LF?;CvP;@K1a^1RViOEd`C10kZN3NAFLW@6XCHxXQ?GmI-Xo)P263VYDaz4u3| zMJXt>fwziPnw=oN6}yu#>;c9HoM3TG++&(kyRBFtmYyk&h>8ze5JtyF9Zz$2A>Mu> z+TOi3`^jbNt~KCnw@nS^M48dRC6{p5O9Uiry~B$z6MvHb2bN>=}j8|E-x?<#xPMm+L)g%=P{T&##Zulfoed%Sjq z@}$1Ad#F#(yyv=o5##!<;rC9B?iGFb-K^V@kriinas@fqsIoO_Be<+qZ$T4Y*Pca_ z)8oEmq9u_$wUZctx>CpwiS#8H%fg`5F!Uo28b2S(`5+#&V4FPlN3KAGFr>nV?5yBs zwe$f%Rm!R2F_d?*i7Dfbx?6kl0=wGZnnioAzm@}$WVO$Q6^ERSN17YPjo8e$URV>c z=j^34@c;>~W=y}Qi0b=Z)h>kEmPkjIk z+M?dHKSDmGg0Grs6bylwEs2nC4eJ6wFtjD8l48MsC>}AZ!YF^+t!Q%5& z?og_9N@@SbBh&}B++^fzTaxjY-x}s(q5^>Hi^nJ=e4-$Pq5@E za396*d1!}-8(Hl;9;6CRTHr#s=8Pw+(&uifuy(0gBkz~L25t$JI9M_u z3>n4|WXYIFQB%fCWCEo*}|HmD~gl zbBg90E(`{{dZe2@5!kCaPbf{=-2Y}zY~ofIv5KION1d(kT!s*9k|Mub8?n9KN`Hi0 zs~@|?uQr-fbmPH21pN?*Q_bbMC;TAX&uok&R#_2=ORm&$>g=_>s!4(L zteEC(+~7womw!ahqINcgoFj;cn~2#T<1&CR6BqWrrGc+LSZqswZ2aSYxGfEwu8CY5 z^S86foJ26G2dhf6omkosAY;8moNSBh_bBbKu8rwP23DpKL70! za)8cLpDG*-Ie{J{zJ1njZ1j?J;cnJV%VUQSB_c2sz1WRr$sqMJ6^#1L=lZfxYyF_= zi!xaG{9vD~VOCq+b4W9<`H8O5JvJ3#qp_54%KeZ;o`Xces+<5&ds}{rK)qj}zwSHvm_Fz{D-}jn%T)D(Mj~Q3LEa}sb=U& zdwq^q{!#PZ06)Ygy>j)n^A$t5OPK7&gih$M*CLi)t@bs8HPby*3m=-@dyM!90!$HU zn_Q3hCBJscqR#{^z2vsy9Kx-=dpdR8FzPSbG_n@ks*|3LYDtnkxD}Z0x;)7VUUh#i zm@m5e^1=J}4~!vQR^{K0{v5x3l~ua)bX|E@P44`NAU|w|sRa#x)5Q!6Ph4d{=eO@a z;RWcieFQm$W0z*;lP1LQns3~3YTtO^P;=%mY6!(s1?7u&FvH$nA1*DfZafAePW^cT zp0ygt>kkNT9(~RElYzYc z6Ou?2_J=v)&OdECSRQ-?#)>%*6oAWRI0Fzeruu`Wlhs8NmuBWwS!DZNOOs8@#+l@Q zrbIb7b(g)F{T2E%?YC*A^f@r((Ofe!?4P4yTjzdCSYCB}qR5lDFX)(>}7Wnn#Nrc(A=29^|`$mMHr#H5Lm@*!KvpOk8?ESNO zy{uJ00i=$Zu6@17zm#RgVMqz(0>&L5GUCfhu{gEIvA+hSG>NEGz`mP}Kfn?q zJfqUy1`*Iys6)ZF2CJ-k(3e-R#bOxhcR!D`9a68rZ+-*#=H{x3c=8Ri+cjmE3Jb~S z%mCXGlL`UzHPrF<+Kv^KLIZUlKP&QI?>G4pc>nzcAkmCXw*!xWBFHQJw71MINC^`h z*jSHS5(YxGT1Y&#Tb?RA<$hnD%{S&cZ>W(Cfl~@^IuBI(S%ZSejUvET&(a^*!=ki4 zvu-?R>E#g{S0gOP_0{o(iaOQ+bKOA^H~VI|)@wvL=1eRJi}VPh3$mfqe!3gq<orCYs!l=WPeDJ!W2>O`~Z2n^4 zSYKf-@#LX}@kn;+_>)^wLT4CmVfaPITr zR@kygpd?|D2;q9F4{0Ru&KW>1&@6 z5Ykm+F9C(QRy@|aQirJ~FW>k8FiSV7{)%>mq+rT>DStMe1uAovUd&mUMF;lk8X_nA zcf!;{8jm=UmGY!hJF0xL=Ph=fLFH&J8Gi9{d9Ty%vcax0n%}NnC*juX6eX20c~Rp` z5_g@K@{RL1K=SxTlTGpo4;5zfNbOLU4ZVI8_>B8gZ-=YDiILRo*O`4va*I^Eded3m zwl4m={1Y#w8=vbbW@ar_RpB+O9O6il7hfjV=l|HY53#rPJw$*(_cg8OABRE8) z;d$>tr3zwY6c}ds+eTuY^~(*uP$fE;*MyI-7bkE0dWz!@|+0eaG3D z#lLOVLDdOqReBZ43rO#c&^EGpS_D4>O6k^d4d0Nyjn*7T#XbNgK`QzUR8H9YN$V=7 zT0AM)FOW<=_Jm6r4KC=V;J$~zk5Q_G(<4%SoLbbxuz-aS{YfAiz2EqaAqL}OuEzc6 z>o;oopMFSqE`5@E811_L`co|E(RUX%Mg_ZITch{SHT07nx9r=SUQGoc!vhurY6upI zEjRSs3KaE}4C6IqH9tKzstz2=j@WnK&*`nmVY-@QQmj>wQ50dlW$!=U^|VemvscSKxNhJsAYmQhU!V;7v^keD6W zHg$uJMTlU2-hSvJ7^!j^Ugzwa<^dUZDzIj_sIJS9SMw^_;GH8erOcn9dj0dHGbjxD ziAz;qDcTJ6wHBJR=~n=q+1EjtL^dj%=hc-lg(OlIaFT(@Xy!*oZC?YJ``|(G;${cg zmZTu38Kh71si!6^<|wXKEKsm35S&H$WWf0hD|kJXX7(kZ?;hRMnk!J(;o7fqe(@03!X9qRU%Vne8}JyFcT6s(GSwQdi9@#{i4ip)4KpOD-SI&=^*CnBcUvehzt_WX29g!^B9# z(24JxRRDfNS=+a+H77@k&q7E%5oMBJLeZ=+4?bZ1q-9Rv)xpxJi0{`dRgMpF*~O?u zPXE&SebEu=C2<7W!$Ee{+F8Q9a^ATiP=@;Y+)Ma|0UcZBVjU+Ec~pMoygAM*E}HK9 zJK&Ro1+7=2WFcaF`h6d*U^4Tb52>|)1V43fHBxcCe9@OUw_tN-eB-BF&3UoelUnU@ zEGijC&zz0*;tv+-jW+Vo2fL`v^k#qSpXCVAjravQQv9q50Q|~6x`-W8_X@HAFY!y? z66pJV-6M2IxO0*glae6Vw4T}!ibDk%o9(VEJEKz<>Y0eQ-0T*3PlwEp0jg^YO>z+Ox3aIMFlSo#59P^Astx2mIhfm;v%!oofifHdxn0hZj zNQX*pP0I>`le_(LE{^ESz*^kP-`;r~<_1%KSLZ9f_)MLg(^bF3$p6#}c$d{|kz{VA z>G7`i^^0KBSNAh1+&^UX>y&THJ#~w&e-bsb0u|4j900ZY$2fq769k8RJDu)a_a)Cv z<6e!j;BInMIy-5FNaVY^@1ny`bb;6?a0rqh32dbuo))J`)Qqx7x@^x7nwHjo^|-F@ zRhj?gTg)VQB|lOTu~9sk;W?kh_}ybjek6)3dfRIfpA`T23QfQ9a@Jf8Y*o#Z(!-8qMoNdSe1tsl{_tRC$Y} z89pWDJ6eNC1%CpLB0RC%=MQz>-UNyLpkam{hNDpFbYATDwt`s$j+~af2PL!af8gSy z_Qz$ljP}q+5QYegOYv3AjkdXy>E>pF!De6h)&uTP=xaYBS@jh6<&`*wj$I;OLmfcko~C%(b7}TyzQ><2IY@m7T{5z8U(D{Si6=I zrpl16h=@NN+n4@T4BLDP;;)6XxsehVRz`fduDC%sI~o3x8<(>rTS()@r#1&3rh~8L zT{^oL#`22-POYDxiw0=|&Em@^1^}^4;q@_77+g{G8CiiFR*U&&+XC@VuKg3w~MpbuC+zznmN9K9K&jSb(1sX?mX(5L<11?qy_xGju0? zby;UExGdx3EV3Ks9!(Jw1W@IMTl24>j`856bkC#PA`vWJh+p z5M)kqEX+8BlGJh95i=zs-Rz{p;y?caC=c)iia^417qM2Y{)|3((vf;q@1J#9>N7{O z*5v+REh+=&@TJK{7DNeY6;jq*F~KfTAkh3q5s;^uYZBjgY|M_?~W~gbP(Z%{7RFa$t0NYJ7h$Beg7Eea9N#`9B?;ZGaG%){%(Y- z^A0HP{oTW}i%S3S#0g98yh0!WJP2QUgGuh|_;e3KsqHn%UkeRtQ)JT|5nbl188i?Y zZdb-fZi70wA!F~hT&9{@&&CAqF*jzIgQ3UuX^S09`}8)DqB0*?2`UT&lJYyKT7ZAM zNhsN9F?Z(L-=lB~O2N%P`xeWr!kD1DZ_JdNQq(n{7=pI}ZuwA8FHuoZsp32jCDrF< z^}^gO*qlM?;X*Urn$@y;OzR#qgNI<)iw_*RQ=l(g7F#RZ+eJmL8t=cZ9b^J=`Mn z`X-$B>dW@r7#bM4VHL(^D_uQE=dVEe$vhtMcf_;%dT|APf0YEKFe7u|lvDOc+IFau z+vK)>!$QEv{IX#nhk*4wB)sYA*3l9NjjyAcD0hlFmCpU19DL>Y8*N`Gu1t)WY<=1y z0>(x&IfqgcuP-+m^J=TM=X>aMzD=AB5Ar*4&3n5d@8KJ1bD*UwUz!q8y7l2gFPef? zPJeRx-P1EtbrMfHyqR&Hs&uMU`0VETEH?TZ;uc=+CzFh>xy32 zf25(`%qTph=Cly%fp5n*KukzSM2nFIxNT>NNXc(aS<=wln5xB7M| zv!5P|Q->awUKKy)tdeUDskkTm6u0!-faQ~}+OV1DmTJ{KD%iSRrp>L77f=tpna|Jq z9C_ww)D~=@xL|X>MH8qE_ZuB53KeAPSW}1}1ENmU&>0-d=WwZFE>z zF>tG$izK6K*YD>Mh*`lJcF+o+xx5$LlJDi}c;ossY5xloyhWbsYAVZ+D4wPdtcj_c zd7q?T&PmkQ1*%ADBstFY+TV;#(Z+|vWnL^c(KS`&#ZH7_>pzaN|A^x+BCIt;k?7@e%W@xLkH2 zsEE@e#2xa&vfM|C;oMTbX{208xX;=P9kh^{t(vrW3%toL z4yh&v0|K%($g;29u#)p`;}y?`>rxNNDzdV$X;W}KauHSbNBhJ1J06W`s%dEET5&-b z!S$|Zen#?Db<$f4Ziub0A6r%xR;`iw0w@FPr{%zd?CSz5iRtL ziw&M4gj6~Y**qV!O#UQ{)KM8EUR(6|gWE^RRlAGQQa<}e0P`l69)F|xcYorGfCIr>@>4K zJoGx-_6mmFKZxYWLojKyr{b=5iimWL9PXg*kV|Dw2t9r$?3(%D;h~7ia2@!9RZ&C} zicuY^`gW;8U9h6T>b8XqCeqEGR*wo}9C)t7#^O>MG@FHA>uvc7xPkzognq(ReQYca*__$QPZ- zW*Wu1ChuA+rs3+9(6Mgzw_da2byw6@q|C7E!i+84bQY~9aPUSKPkmjB=SSfMDsJR7 zlS9t$_p9hn&>R?UbY!&;^{kwWDh=&By=sXSK3hOES@KKO?$?n^zUM$|FA%l0X zjor@Gcbxj7f8>op`nrc-Ntt0tiLrBmp9JP;v9OF+1>=*P^z5bLKT1OT1m=at&Erwk zaKi3dJMnQ6?26512~_a%Q#I5p*e#E5*hxG;7?=f|&TqNJGG?AbvQJ8cPwSLu|7`2( z)qwnaHV*`)rO+A@c@8pek<7x94aXE4-v&4B6%V6LHpt?kxIyt(J6-&#;8Gey+35sd z3B}lNF9zgv#p@b34s893iKrjuEjbL;5JjDlnSR~qXSX`hAKm1Al=7+IT=?%)XDtjW zm4m9}07u6#m1h^!)-*(bI?bY{uyxC>+PBKH`h9>Y4ZZwTs@zcj? zi9ey08~_IV!J6I|)fa21b~yP0$jDGslHh7v{dOP&7?g z-A(a>*?pLRI;Nxs2BiA77X4*~F5l0-;c)!+bhKMRKa~AOZkKO4q(pRSceWkYf^t>J zRxJ~wk^szdxEy1d(#LKI!uz>bIDKVj4u5m`mbbjbN6HEb;B&&dpN0`U&%`Lco_v;j zjaL#uy;w&33xd>ffX{o7a_U7RGtTNJ{-mmqQolyhM1zntqL9}>&N4W*;OU{k$+{TA3{Zh2h>j-L(#flpHHS%4F%n%o*$5ZMV9$(S#Q{Et2 zg54f-rq+j1XXn2~dhU`T)$e!2kgZ9W-Lh*~`z(4#%T6QY&9U$zLn3C_NukiFc~Kb> zN>y-u`E=dmjn9KRl^SA6fh4BGEswX+aIwztBE@*ZV%PD2#j|%Cml<9ceE7G&ibuS^ zC?su^!9l+_8#)IXsi149 z<``5^f_So8bG0)DUeaZ0lJ8+*7)E{dCKsCglM!=M3(J^EWqNbW7*k;~tJrXc1}qu- zYk8*N4$Tk~3tm48lm4bS=npP~06U=842gRQUt7}iB80IOx z8jT{7V|yS&%Od+io93kgN2Fp0$oD6AVXFxj+szM>-5IsfKdVqD{_W!L{9A9SC(AcI z!Z*!4%VCDg%)p=|MkZ;e%`C7t*Rz2$QQv;k`v+!MSr>de3Gw_4_h&g;9&bT^f@8p1 z`P{Gru2Doj!7GL>upW;9zC2MAm|bg(iFBUW*Zr`GOkTOD0R|S_Q1y$6U zV#*6ImthNy1$Z!0X4WPR>d&#g8PYK3q*C^SVt2+k|J^sU?LTRLD5E<@*JiqVG}*W= zoNx|qfs`X$bI*puk2i0KcT=bHzIq51vw>!K6Yyo;0;_UVNUKnIs;zr|*y`rs$BY%a z{EWgMFX+FlzqTU#k#vv_&Z7x&Grba+So(1^(c1J~pVHt=FM6X)cNuH{_^<~Uk=%(v z*A)NgjvK6|DA$A|VMT*H^jXd&qD92v0}kvMY$I}qk3X?L2ar^gIH&!R-_o&75iMmA z4K;n5a7qRZ_sL{3YyFenp0uXo8|H3qWecTQt#XGfsL8j@&J;?-ls=D+>C9W+_X@6* zyM#pI`q3m$`nYEH{WGk;pyQrDkSX}OYCd%WXl;-wmpp}~&@Jhk1~lQN=wy#;)lRi2 za6Zsb`%FW0`0=Uv#K{hsi6Y7zX((?ZAp=}+1=nXBC`^#B_Ze_0!+bkzCQ%P)ew$GS zWhTz5E=eaQV|1;N`vHrOkr)LQFR9#f!`>kMsY)p3EIG4&hJ8KL(;vrFdD%--WVgg4p!pfaobMD-(RQ}L$htu+ zzKG)auV|J&x808qYq8Q^V-Peh*}^E6)R;xbAXN)ZY%OJZcy;8sPAX9^X?Pa~cqH_g z_Vd~I*O$rQ`F-ghvUJtjT++e0`E=Ioug0QYPK3I=V6`$~hBZ1H`w1Ov2tI{1mS*ze ze_C*(Ln^!?V-QZ?&w&ee2XW3g?OK{#|6Vu!ISIMp2C4YcD3}Lf0RurjjeOiOxyl0P zd)yn+fJwZvhu^cM)zq1H$cc)1ne%nyzU{D>7+O#*2#1c-jg=^zst=k>lt|o21dFuxVq8=j0tGz|n2&MEDyS zq1eMqq6c0RB++)#Kcsw}2Dxds+rGCvy&fo<*{8W3> zK+HY!jd>@O5VpvNFI^rn1gCA(x}2nul%EjDuw=hiWrtLw#$z%w8uEv=l4kc_8fZB8 zq*8(q7E1ciB^@UMG8|>{M>y}Nh>&m9C95rGlgmC;$^k5<0a1$RT2h(<)UpIB8E$Zz zT6s1Ju52nkot+*F1wSEM_w@PDfDHf`<+#Wz(^oTR5YZX^)IB9PcGJ5TiuyXut+ND> zY820Co^N#h%3I=D=s@+Vxugw= zyK-}d+1Hg3`Rp&muUc6F_oqL<(NK(bL|!?YTTpj}%Da_gt|r>}$6Ex9sg`adLzD?$l!ONlu_GEI{QzaJ|b*FChc9`9>ly68QYnZBRv@ZIY`O zA?@|dR<;0yMRMddxIhwBoZngC5EY%i&Fk-Pv8>b7NcT$UqO$e(p;CnAEEhtuJG1|e z3yCIe8=BS&uC4|%vgKDg4VB_iaw?8_wa<4(0S#q_OSVyoA+ZCN)qz{!Ep}w2(EyXh-Gr<6hx)~{W4WZ9@0sIR0PVJ#V;WbA-TnVoU@xV z)G1FmkPkuK-T?lIYL{oy=4@3o&^C8V6^-t^hav8djKOwOs)VHF)zIT&3Lv5^F@?{# zbCP5bl!)b5BeTx?u?Vlc)(j7Fm5~KM_Y90m@;fxmLZ^Hf>X{q~L5gyh3XH4n?J{I* z2__#h%(Nm3oXYAr6bmPfRbhscqZj}uYOr2@q+r%F@cXIb73xcX@WrpYk*RXGfokwg zU%Z)Z!t8z~^Z`k7No7Yk*c8WxqDUMJKc?jNyc)!&bf&1F&=Uo$@ zM37!p?MA%2oYQkyCg%Q};c}=<0gISj1Y;HqR&R&!s4r{?px}ji`r7OtONLkk{qv3a zoZ??goQ*-L#&2;D%~}Q5UD(ZieZ@{h0*)QA>#HeVgZw*BQWnQ_U-g+cX?n$2c}4Xl z%j&&zzJb}vTo+}beJ(8Ky*W+pi8!(2p@M#L{6&r_Q;GXg6!}fn%jA%{mGu}%-OHmg zy`j#)BYn6aw$n?G6lHv+=&ZMsK11=Cap3Qi6#J!a<#tn9jvQjLES$Be9phGd)1lJC zoV6QN5cPeDk9pv>#x;i|wEo>7(>Or{3S}3>tgH-!C3*Vb!*9akp}t2CTeK2fWWiOY zTjQj*VYA0Cul<= zO?w!|v`?&;y(mVw4aZXw$;;=bUsT+NX^Ub2CXoPjAAaGYL(I1MhP`sAY5{o2Xq%a1 zMCx;rMRf?)xeo+}uQZT3E1;V}{0P>Xw@898^%hm_9%70D%qWmx#=b+m&ZE`UCSgs& zR3u(`D%F^WawEH^sjuNjnOJ2i?$gic?@wb2+5l#t+$Aj|lX9%6fPJ=*dhQkx&fdw` z%zD6LvEwn@r3dtwJEM*-m6%42w|NySSPs$(uGi=rZmerbAo!0)pwp7T{V7x+idEmw zOBLp`EbkTPF5?w`_R@;<2$u08_#@MpxHe4KgsgWWYrQraW&ad?ZFBBEIstI56QP(B z@U<<4b-)ctni6|86hIjhP*&6G9ibsCC@Cbwg^zlbGjireZEBy*?MzY4+;>RT=ii98 z{Q=$h?jiCIQz&@QxWdZz81M$Hc6J}Wg-m4z{*)KW*ldD%N~OG^@K^dYcze;RvM^q{ z+m1|Gc2sv@BXvR`V%P<24vRMLdVujuvC)WN&h8G}hkf{{S2R~5cE(Jue4=siU!JBu z@h=@X^+$46zEU3*ZQhMTNHqgX4@G=JMh#1bL>GqP6HE)Iv*d#mbA)ve0qJtUkiD?a&mwU%CjcETgUy@e9f` zeyFsPhnx_mC02Pr336uynlrAf&oY{GCy{D(i=LYT5Yzp(o#1y5Aq}WRxZBuH|LZU~ zPLQpbAnBvk%p(<&iWKT-@S?Y7G=U(pDYk71T3eY0wnB(a-N^5JLAHCo0Vl(a?4bj@ z4O{|m#rvf54A13a^f&7uL^fPAB>4^(zR1>*y~kl-s{}0zeJkf<{JTLp*e>w{nMEyk z9brLF7w#x3kI^)^)?_LBcUUE-3=panJvS}Z0h>+6#XUqVGcIPM;mW|RLy9~c=1X-B06`YvAAegy2m_Oi~4~p?*vkxU}i?b~b`6jgS#5j?H zudb)SN$={z6}E~tC8oJkjb*UY;6}I8<_>C{Y=Qj4~ztS~jH*6Q6yTHidfZ5BjLBEIhAw!N0y}zACYq^ zwHSI*^(Rqhjr{fDORXr+-qo<6A( z_$eG%8W}sn9alFTdHaul{GpWLbk@V7u1|R(wH6y2G)_fjZmWJsH=%2eoVWY4U5pRt z`U1D_XY<~1K{8ivvQKb4&KKNODRfbE7^Dr6;uY~qX%7c$P4d55fQ zaYs?Mv!W>L>~;2KU+xYe+i}PUXCKF9Rc6NL_5S_`-{l z@}#)LEU=9H>K0(j3_Ubq>;@RSO*21fuO|4qUmPPpG5jn(Tj2wy!J@o;&I_ADD#pli z*(obN{#607^2!9PBX%%f=}E=N_7M28AyffP&*W+n#3du+33_4#{!}!=&up={XH0Waqd$&c`)1!xcAW>Mx;94$sIUqq1#c1G@crl`xZgO|b( zz3;oMof2Oeqceku{XJv&Xzt1rrIsIODUk8Cci6}CZimQTkUr{H3r390T+V&h)OVF{ zEYGsQ*JV(RxbPDu%%QR6se8dyf`WMN{Mr-Sog)dfZXD9cZlxH;Ja|z=FfqXVr3MO> zs^`gqu$KfeBIGAbgrglB*H~wuC zhnl82*%u(yjt$c&9hs+#D6iIWpiM^D#c+G4h-M+hTfn*ynd8kb+WmC`yY^G(@Sw0F3IvD2@Ua{AL06lBs( zV8`+fs8vld7C1|DzzdQ!Q}7zUFmb&Xv>v-u9mPj6N=DH1P=o(y?Ll1x zkWzGC`1Eu;Vi(I5Y_{C7yaVZcc@|!ieGL|&Lx$71-j`<1Jnd;qjY>XgT6=M2P*=(GDM$pP(-6zz{ zwjt`~mb!Yafv!fwIKH!z3sF+`1kuP(lW2GK`NO`ftH?9t_gA+kVhsZH%unz%uq5)8n{FoGk&)TeACJ~p&`^F09q$NI{TymmJH4x+QLDGB zTMLD8x^QI;)?fWWX$g=(M<>8QV0^R3-Me=8C+bt5&@pXi3h@|D=-i(WP%<}1AD^*> z6?DZf@3Eq`Pkhn9)~5_2#+CdE0}pkkE@` zYn7As?4853tSG^IRHOi|a7U&0LUN#VX94eWT?#{iK`FEPFj0u=&pHlOTivP%V#Ld& z?)Tf+fC6Pez*Mc${m!?#X-3sDv*(TfO3tgoX4QWE-D?3Jk5r8oOqcrg;i1YTpl9sL z<#rz4Z*HBpkAJY3&kP}=&jxC<4!ETsVbxtrw1E3O;$ER1NTlgxp-!Y563gUy`&+=e zE{HtNr?^J{vL1!KnI@{wAmR8ikO2M2FtpIQ*D2$8FK)KHNc%EDjaAI9R5Br?S$OM2 zrye4jqEwtDLmWuLt@Z=1 z69GlKIEF4?%(R$%QmmO``7iySneVBnt~vbo1waaUfWy7Fz05}(>i5+8yWAS)%CDsC z^x%4JvfxROMREyu+1yv*v8zNXFO_FvR9(|)7GYLtYoF7&)q_GG01Au-%se^}>1)!k zP+q&+g;UTX;XD3LDv#Nqz`bkJOX3}NZPD-JGS2sHsld5BtI-1^@=V{}ECoLYJ`qEr{_SQ!n!-;5wxoRC;w@atp%TN zJKdKI{(*2&Qi+E#!H2q=ZJ$Amb(@b3!xMmw&0A$^sL^-(IcJB4Hn- zjyK>!+x*)bCK8|Z+~eYj`2&)o+S-F<2G}=ZM;j0$ZANIfeNK3EsBxTBoicmoD7`(x zh)TTK$v^bXAbW6dm>_3_V%H;{N>Zu!Nd=-a)}j&{1rQ%{eJibu{v$OB$XkKmu56G9 z4ptlRSX&%BsQ6WMZnwq|PkAGT zwW_-HQDL}$6PaN(WkG8&c5YZk*qFq>)f_mSkSR4g!FwhtyimX^mVm_u%mmUGbgWh> z9nk_$0DlK8e0bnfiH_(e6VBuCWg3ip^U04~pQ0g2x3XXB3$hK2J!!ex^p+1TQ9ooW z)ov?TBgV5e^fykoU?gJ6+oS-#>X$QG2bB-q%@WOqORm#tdrYc5J-WzrF<8b4@F+zhr76YbF3q z!z>)Y4)s7BRkCAj3z>npVm(r&2(HZKl*@Bq=E&^B5={TG`h!h(}_k)vOAcq13O>CWGl)dt(!eWf9WZ2TuQNYMTJ^aYT#5IPJ2i z{EG>7Oc}!f94a}Tb9s2eh%zoO-o^X%vJ)F|)3)r;Y2=*+zuz4En>y{@JKT`7-zVR{ zJD`8u+j_};o~1OA1CVwwYAWe*PXd#Ft~}KZIXPM3KG4?AbXBVI_U>OadVIOUpOAso z6Zxda@Be4Og+~Y+aYS>s&FFy#E<*Qkc(mGhIudmkc~TRH8f%BJOi<-mPXgjF&4t(1 z)G#7)dA_tfE1_u|iaI7=$g0avBJ{E@lIJGv_H=( zrArp){W!p1T)Uc##=udLy)h%R){ah4)j2I@aPF(W_qB1jf)BYRLtY7DUz9PQ>Ro3t z)-yzCw~GyQ=YgSwe-S&6Vp@91Gy*)num5V%+#}y*qTR`2S!utzTgJOz%Fhi~f)pnA z-(f~@!qY|YQx9YaQ(w=X&0o#(ahktTD*6H7X$j348CEw@k+9sluTh3HKQAZF!Bd$)a}kX zglz_J;T!N1({Jg}+!BfrW`B*>w~>jqTRjiX>$xoJm2tFZWK*<$)U1Lz zPT|r-i$j~4X#MZ4ek`R{WKzd{+W=B6LxEmU%@->3Vwj_%N}pA+1zl_n!9c5grndEg z10ZxM|Q0HmIaCXOj(=Bzy-pp-E^hQ7A=|{2tqs8_>S{hUUA#e>zIair0YXYZ&Kvl;S$4UoF;yj#z(n z;;gCr2LCn_P)mrMB7k|#zz^Vbh30KV7pex48A>pnFx}hWj6&6XE_g^tC(H8MT1Al; zdj#m-e|D3~oOP2MH~n0HI)>&uYt+t6QT1+4@3JFN*^~SNyR>!{vzqBd&@-g!Pv*nC zze<-;s5(V%_!@^+3Lw*D&=x-<@H#_#gk4}?uv^=M+bd^T&j`GB&{t)YTRNlCOG!pJ zx1ej7=>(~`DlkJsmuPWyfH)#ZK$vWMlSrqsKi?!uBh&Efx{)Xww2v9gqGh;KF2QM; zFjLB?I3*^B&K9?N-E*w|U9MYD@y8PIUmkVMfE%E_fR#CD)K^}yTt2dGCwfen!>|3h zvrraca$?_cVefF6Kkhnl@sZMfd0Nfj-ml2fu4rPT>U&#!;&RHm|d@k{ECIvwNT&=K4JK0bQdMo&>%j#2*uATLIX literal 0 HcmV?d00001 diff --git a/docs/assets/flight_controller/accton-godwit/ga1/motor_servo.png b/docs/assets/flight_controller/accton-godwit/ga1/motor_servo.png new file mode 100644 index 0000000000000000000000000000000000000000..13022124b536dd2fe8346737a33341ad7d305edc GIT binary patch literal 30962 zcmb?>cT|&Iw`XV~O%$X_2?7cz5IWKV2uPEzC`BT@6M85Q0s^9RrAZA+Q>xNy=uJxK zRScm>5lrX_b(Zh@z2DrKb?@9Yv*xVxthLYHzunH>=bV3@HwJndbksMfK_C#FmZq8! z2t)>eKxDO-$v_}bM1x%i2t@wd>Csc4r@9a2Y~XGpR<>|!I}v|3573{XpycmiW#eM! z!) zX6IwY?eFI5?k(r9$n%$7Id^ZlKWqpO_g@en7eyYGKMuK{>KbsX!oBRcWkke;ZA3*y zxn*QUWNmD0ByH`4xWz@q#UY{+5HU$%F)=xDX*n@j?tcv)D7S)_t-YL)+Jk>N^Rl&9 zZR6$S z;o}5%=l)~S${OzLqsYVaPY!M#|2FIH{jYtpfxAKctvn!NBBFnC`YTymn}6dxe7#)% za&Bt_v2(R^vvc?HhKPxX{Tu7y2={?|JHr19)BhI#FAn_OJal#c?c+a<#m(*CF1&rz z{e1q9(E8TJ8!tJmyMmepPjo8@1JZu0kt$eKhTd=K-oITvj&B{lS$H~pg!4Bf#?!d$S?`@P*g}cJNbm6vk ziaZj3MWL%Jr{(VLW94pRr=_OIH;|{n?K#H$Yb-Ttai3M|6)7+KkvZbW)Y5d?*GSf{|)no+xsA_ zyzEpQ?A(3++jfFLxfLLP&f(vAK>qg>|C0TOGy4zRNbSKN^50hwl>2{PVs`GfiacIC zO3J0+XF#h>SKp9!AAP^bI;Nc^64UdO8ImnzGNWZzkZ#Um5G;?>2E17D-$CfO>b}C-^-kwKO7XQ^=|^1mCbVX3NOp`zn5RX zR`RkkiHL~&txiEfk(2YsJ}>JZKu!)4iOi*;p%E7s|9i>9!*luaWgb?hzk`vGklgD+pc%+Ai9pI;y^FMspqO%f1@gM;I57!w1-5j9O-UjFmvRv-|lrKKe& z2Pq>XBP%UZU0q#O^=H=9)K1Fn%0CnfFfhTUWVi3@^eXO(JeYcUw99S~@Y=F+um z*UCU3+%xXxX7>va=xFt75D0WJ3K|+3K0Bi*EiL=A^TnX7EXrrkXe6nqIy<}C+S)S_ zh|0>UZ++xhtgNp+2^HiFiEz_wU~qgCKf( z`r6t$BoYaO!M=R?f<}+Le*GGQ!3=^VnwpwD;O^Yq+-hoSdwY9*-CYR@3B|?55)u;n z`uZ12N`r%glarGdAt6gkOBb!JPmGN&aQL?|(La9tsH&<)AQ1NU_R2D#%#8F4Fu0+i z@dAy$Kq7m3dM+T4i-d%Ss>*F35ac#5R6_Iu2D{ML4-XDH$6%GO(Onq5RRiW5d;D)`xxmNgL2!H z+mzcvl|w_@l|x4m#U7)-uP(lASd?i0%5zn%sq}Sj`uSj?-*fJT9q`jr{I~Rd;$zY7 zT>F*T4crnW>g?f3z{Za$njM?W)%slGa!7Y42 zU2I@KoZ}{6x91+T^yE+3XXV=eUfAbrTUyvT%y>6;O7K_&W2Qx278ifcBo2;T{C^tf zv~skoAP_f5OHJjG|J+t~yUX$nXD^w=72Ekh$T=fJo!sz+BH>v%7AyEY5I2){cVG%R%WFk+davsjv6#u)d}vR|5Ha ziX5!W+`CVa4h8}B4D((LfktdflAwDYPChHP?|tII>>xBkf5eXMkOa^3J#!}NBR>c| zcoci^d&4;*xbH-{R^YlmaWwW?)^K+U(b8d&Ms4NNg;VNAsfAbKmnD#RSHsF(j?a%} z)Qc*sKMrr~TXf#|w5L0HgX(8A-m#?4vM%sQPK- z)=5vPRPYjZqwkV$QWH?g{Me`eD3$r@rE5GV?lY4&Oiq-g`$|q%jrFE55dK&9)1A~p zD7F3X#zsf;hXV6`h`fk}`DAaAmOS4`7`rC&I~DxS#y6HLfPJiRP9ZkpKKK%;W;Wwe z{M&NC_tvAPSnr^_)oi-TQu3O#jNVt!4kK_V@Mfh%;(*DHnb0FiZK=2kJ)f;jLo|NTVGve$Ov4T1Ar{A~ zxCe=biD)FSP_niqGgi^!|y8Fy7su>%hJIL84- zmhTCbrygKn%RL!4w4+_Dk1H@1&$|g;kryR$4Tv4J_a@{IxWm$rsoc|jEDm5N4b9s~ zoBJr$w>U%{Wyi%*-&$ND_;;a>_hDibAg<_OPeZH}!feY_93_N2Tny@0Iz{YN@2UL0 zAz8~J;x343W$L3`>N~nIK3r5w*PBzKWDHG9(GPhAz*L}p2+>{L!}maQCYQ%YcyYY| zru>KQo^X|tG0g(;>-*&e3c=fScG(~8>-@8rcR61JaunXfls1H?9&GLn6CUl?g~|-T zRlU~30-6xI=~P_vC-dh~G%Ewmz_@(;YPp8(!_*tcUsG>PZEu%~C9HoHzGdH?rQG!9v3Bg>@{9FL z6fXuNJ`iG*oUm~%Cw`Tj$v$~43v_1dEc8Tf*nQ&g%)*45P02HnD{_?g zQ7wtMC>*k;Zcnv%m+5|#!O6MFbZd`CBoM@nDRF>K;Jq7*u1n3_o@^{}^$fmNqt{nQ zzZ-l}xpFtM@ev|+rPnBPo&7TL@IGo9qJzr&HA1ANIaxZ4pB`19+Eqcht=u)_cZI>H z6rq*}>MD!jKoB41Sq}FhUC2mv)V~Np`;LG)n0& z74dit$A&c1btU-8z4y6~8ti*AQQuUgGpfi%o$@2P;)bGh;2VW96BZ9?)|G)+fa3Fz zIrMHTHs_X8_tscovi|D~%98-vM}28*#CR05F3J-ioLWt)H1_V> z;)C1PTr1(ghM0UO^V;xzXdfkLB^&_lsz5>9;1#k&`dtzb5flm}(u4jM876!27ag2N zJg9o#*(2UZNi_OkF{oo*QbapJ6}?pVDKPj|oX8*NGtCbkR}Xsh4iC2#XZ3a>yUhgBItZ*iGx7`_{f#ibVR|Tf7Kk37I;No7Em+Kw<(U^3|vH zos6{LI1*|iH(2T0WGZ8on}hi&@5?`}-h3}%zQ$YbXrlPuCz4$iDAXdl|4P0|J`Jr= zA0^ShJ}vjjsm+C+T(3YRkeCo26u4v~BhRxH4kY5d>nTsT!7D+~xP#xa#l_`k1JWNh zNr~dOVC9y#+#iX^;51}ep8O0d{>WzQnDJocI6S4~YGK5JNFqda_u14X&UBW>x%sCo zf;x9Mv*PXQTLRF|zKiU?m0`Y;k`M0u>9Y9(*xPi|eZS=Ub^*cqleBkFAxgBq$cU8Fh=#&u_^O|9GIta^$XWV)wy=<)KK>NKlOyaC5T5>$xh;@ z-6V{k3A?W5Mt`LyR^Ei6hG5WER^Lv1{?6i zpx_g))u4+7H`f<>Pf+aA%f^Dk40#M@bWT=jY%BA|#257~3r~pJU5@!p;ZIp6X5N*) zN%8BeE81ldp$YK-k8|-7im1T{`XO5$+(!al!|XcuJ^9j#dWpWl}OI~Bqegg z#EIHGzYI>H3?jySZZe)9fZQF& zB^-r*7Tzj?p0eW2e;VU%BLi9X-ocd$`C&<>W*(D~fGTx!Osc*WiXh{kFYU6+X*1WL zL)2pnVWwKFhcv0Ys(bGjZ$CcFznlJW##IH{M@eMp>n)cQ-HjvNwx>v2Jh<3e(065= z<)p-?zjlnR?bh1jwBg`qoxd4zRWqqnlgfQci2FR^`lnihNB2IK&+#s#%oUfo>EAst z_-u4bKg%qdKE`Z%4iDK?JT2q{De$nE< zvci7DZk#X0Ph*rXXXuC~1rdN#a>ffQF}Dh-clSss;wd5!Y_p`u_MM?>wR7`;8KN|v z`;LNXpIIpbruBYX)TgdG%1%Ag`MIRk?mqb?^G8cM&19(MKY@fNaM|o07$xUKUH$yX zlPX&nRp@Wx3E1C*qm9HI0^U3ni>y&r6Od`->~NxMo4!HdA!YMM#g%JOq}AL>yCHIi zI<>#KikNRbY$M(hDf`+|xDnM?|_6&-{d zJxFefi7aWjSkY~M7FO{FAGa->vva&OaPsBVYyQHs-@JsUev2-*fgp;lUm%a&PY_5T(`RS_Fu?x%XkL z;BgS3`?_N0*_8F?o2FO5@20|x7@sbaLBkiD*v7!fB0znmv1lfe zByYpYqw@4wub~?Wv~y7&H@#rlO=i#&BmDbTf!4ZqL#0kvg7=$Hv?$@dXG;_6b~Fzf`oqky;lNT)TerC1A;D&L!va^ZOXNF#Zi@( zk%93W>AWYWcl6d`A|igVdXa+h8(B1rDFpTVswW;?WOx#o8=*j(9=iPXgE^}wDHuN~ zz*0edcdz@j+c@X#!1_TbJ;7P_NFLC^^R0PDBi}YmM2D>WRBwia(G#3=4ihTkX*zb; zu^xna*j4uhg;*#(A++MfS8dAA*zLv4SxFLV9pWuC@-T4A*#o3&J- z3=5ZIDL+NWZ4>X+#Nod0eYHav#k?Hg*62mwwyb!hY8kRn=d2TX5_;rHSQ}N}WP#+LX_5RQKY8)AAs;hUzD3iBhodWO;L=fMr zq>`XgyEQ^i4)wpbJ-IOOzrv5N5rsB-bm;4nz!o~?)Abn10O8mK>_!|V>UeoTse_zg zb_Ld&kS^}jK8>pLSG)hMFzC@-1(PmvtWf{1yI|46r^7zSJPbK76kic^IFKt1Ecl6; zc%qGC;o4`$atcdYuc9CD<+~nVOF2|hAFr$4n2$EMXV}w^y-~Zo%(m$A03eekSXAMB zT{@?)RgctH-r`{}k}flHVvjELovXI=9B};^CBn)8rUZsw;`mjtu7ZI3 zcBkGGjl-bS<;KQG?ud3U)dU-i8*1D4fgerlM+##+1di-qVr+M29a?={viGt}e+%j+ zZyh;DK@xAs*rOf9Nnqpj@>+F8Ovr%b4L@I(7uwtB%4B$oSMjV@F;u^~15rPF9i|l4 zB!Yt8yVrG>9|&^BOOa#fc;n?q_oRfOt485d&P4?peCt!k$%n6QyoAsKZFMd?PQvy6 z-McL`giw0IW?V(@l5}PeW#d5?3k%gPuT1H>Pt}~=Nu{~1)K}H-~s|?8YCK?)vp32%j_#B!`Hjl7G)R7Pz(wTqY;wcF$2rJ zWt>jKb;Km8u=w#K zY&6XBj9LUMn?7>(Wn!S^n~A)`nC`s!tn(VpXBmq@cUiEzC-A+&$U$mePIhs8|8lpp zH6rnpZR^Ur_v!JLyDjNo12^a;+oK8PZ;U;xz%Bg^5~^@7drY3pJDceVMR6T^)%}fo zTZ8Q~Y3+5Eq44lnDFh$zYs@R0TUbi1%Dh$tB~A40Ye-zdOD&c#fS3Jrdin&=)>d2X zS9%r(W+($E7QN-JRA%#axCJJ82fq5TGHCfh<{b*^JALcRO!^gxJPDNO&FYU^#81`z zy6Wg7qtf=PX-4R^o92OisbXV$WgyrgyegcB5&t-*BGX5L0oqhB?e1q@sv?K=`rO_N zRyYoxYUjG%W9l`~9>S}>uK5V+CQgm}c|*JzO^QZXr?@te3F)XD&jm#U#d zd~UK(n4d(%86Pd?YsWm60m71P9YvbV>J%Gzg@3p7nXc(T>MI^WsEns>4yD&+f3VD?8+cr@DY(o}l1_bM+C?fYFv~EGg z*SxcB2RVsOY~)=Ep?%2*$zA3Uz0sO!&6mRycYL;28byF@g5%t zgu%5DLA-B&g+c4~qc`t9ZLE91Ru|-Sqh9zeww)j_MGYsiXM4)GqYhzm)j?kF8PGA; zE{#*-LIRX0fsmw{GNssJP3irPS&r@N99y-7C5z2(-6!(fsoy&Fq7#f2w``>rdG~$0 zSu`U$upZh0u505gB_$QflqPTm*s~!a3ESF-W5T@mYLk|hS6W5l(YA8FrCo}8PfnA? z*3$J~oKM0wLN;LM=pSdzwQ;K?pfqy%G2Pn9nru0xEqjiaHsOl4;aWGH))PBZ4K5EH z8_k4?>{BXkI~{%TUf6a!`ZBOdhPaTuww3y6yH84jgT$-n~)S6bBI@d#eS=UeDut&CrYDo66v)+PSk?x`d z9LE4HrpN8XuIk}KjeRd z?(-8t<8{eUF0KN$<#$8{p>wm!3hbDUI0*Z?t;sDF1D9T@M}rA1Uf)k%Ub&b$nEPTh zjXl~_MLnh|%`GyNT$~gasII`Gd4D$SX3?M^>*0_sq%?!bR30WT zVnB^xwCeR`c9;!{Cj6Ap5o&UM2SB79m+dn2xUfCDy1t`dA=mCfk1NQTiP|B@O^>(vMte~6c|mh))2bY6MRNiB$UJSB zpG591E*w7c_A4-sc z(whfP7WHD?0MCu{?;}Op&v5w4Sa&d8I=p87#_23&finK+81Rq+a|$#EdWa4A4NfvQEmcOzcQ2$I?6pf-IvmGOya(q#Su zZhYi7yDLjH4U6-9o-|a#PFwmq>=frO zTm7Q9pa(%$hOHlFa9H}KQ~$KHoRi>wr4s?R{1{zM^*ZPKCucn859Uj@*}ji&tW(-P zo{ntGfWIs++3i!7U#y~9mZA+_j|3Sq{bC}_p@b+xA!KJm4Yw@@Bls=xu0`p1NkpTh z3o_3o+x1hOMKcS4nK?jToXHpf8XAcUb(Co}z+uS?;PaqY1+}=}N>!z}jXKn}BG0*! zlP&|!eR*Y&cUf^tH0yc+^JMg#JVBXu>s4E-%VjmDwM!Kw1!wmwI?ca@ zQ(O>UA*9G-;qlM(ye;N}YWK{8RyRL*UsJG`#=eDAw2%djhLn_8d8RL?&JeYDkn*UT zZ*h=!R`jUHlSsp6*4FoTZb>A3?zs5;*fJ(8g_=Gj+)ON9MECnlgc}NJHEB8(+qmEP zxwDtH1)Q(y>gkTJi%Xz4Ux%*?Dc}fKM7)XJ%KY-|8BuZg=e)=kZm-W|+ci>Dk6b=( zHoP%Ni8C?FCB*Xc28C!l)1bIiO4|I8g!L@EdT&o!+s^i_L+SPNcXcL9>3fm5J<}DM ztFYUh!c6F{>9lR1UI%;mp#_X9K+iNXc8hCQHaSc`sQpl{4|+gi`tBBYD>FF=Nzu`m~B5I~6P;18uut`SP-41?Ri2m9)7 zwBtud=15)NK5^l3CdNhk8?*eGoV4$ciCjtawsQ%&g+frU+Q4VoBqzMHrzY< zcE(`W=MpoCdVt3{%jz%iGO3*t!VlWtioPDk-uj4cRe$`t2*0HZE7^XVg7 zxSex8g3NAwTd?TW^YN-mPI$oJlcPsl=3QQ@wlU)-t_<*{L`CU-?9(v#?WW_?GNvB% zeB3o+pnFMmsCr~f?%Gw9y7$|c26acI6i`zTPsJT$M|3Mxohg9ZXAUG;^`0wQOmEB- z?n3@0GlTXr#*e`e^1W(jTLSz0-SQwR68*j8=C;f26IWLUWkTTo?J~bBixS1zt{HZ+ zgx*rWRKA%d7wP8(##!1y=Lc^xN?(h+qNTa8ghTiPfg3scjRpes8qk@ayqp9hj;|IX zMa|1qlqN^`Th>Ppfg@`w8l+fU!8-4}Z06)ui<+c?T+I|}YS`=d%cas7-WgWsfl!u7 z!J0J~axT%Tgc&+;au3SWYE4m(ZAXVeTFBAqvzWOkcw9$Rn)=dp>1H7y?c=MZ7}M-v z8ZjD-T<@&;^&z}2ti!IW%^3mgr~vfX%qkvI6^5e89C+}@E*Uc~iqMLxd(e#cSHT&R z$`(2ekL3l|N-t#)79=#lSOZ|)Q<`Jg@4{(mK*&0CZwUX)Co_RNI(Tw83k>Wz(O?)s z`&SaxtOB=*Q~aGH(_skKoxA*~V0(usE6t~M-=i-4QnR-}P{|S!x3u5UxVj6U=dW|WCS1sjby@g0`Vxl1?$3>ouFj9J{W6+q+MEb7yGueE%R` zH`?=K=>32G1!#0JF)=~hgl=+ew`sUP;K|G<0}qH4gUZEvW$)o(1SFSM*+A8G@ zt@Zi6xJ6p_gS1jWuSzj@;&k2RjZw|xF#UtCj2P3Vgba-5qJ+Ivew3|zuK=HFY59mx zgy)j#Z><}>EQF5@5A=Y5x9c(98z&Af;+0r4(oyqyoC!6E$=rq)g*ey5CP}p3N zds2LxvjYp0TkVAcR!7vva(*)ICgBUs^{c2Sb)_x(DEdR58I2c+z{s6#L=p1gkIB#k zkFZI-4|EwXMGp>7*MIeKjxci&2K&~cD@Nw`JcNLtw>u(kPRq44D20V>J6P^sJ61jb z-m*Vl7iJlbn0oMFiuuKpYp^gY?WCn9*^&NuJf}`g|2zQ3{oBBUb+5v=fO;Jy+xd3(@pOlCA-Ck*~h8q?8pTdQa1 z1@v2E2kmi3hqw1DHzBP=^B+5kRWe+G#Aja!mRGol)JvU(9l4R7y&ZMZq8;6Bly{Pr znplH!4tDTN)Vw9x@^{zb5*ovQqBTB!aD(z>O5)$5ZDo3_H(Rc`{8- z;NZ1*2%JU`M84%b30^;-Q$sEAt+u7j_gUA~I67U0Me~;1ef#xery+jZLQ^fzvBIx6 z?7fs6mJ?jtKOIFMmU99AF{|++q#M7w+?jFY!anhy@YA$3X@LT9f*nIsCzo`{}^_S4Y3| z{W-$57M4EkEJYiHi`k}Dr1U#^(4xfrrzRsXZLOX1c{|UQOjxQ%M5(|h)(G0Ew;Td@ zVq})09uxSoH9&vySC)}sM=83&32UGp18Ufl=9Xr%idm(6)f5Lk_lfF=c zn38wFWu#NMqO~YZBPk%~wl9KPF=8m`WtOuCTK-i1Sv5<0I%k0qF$z+*qTVkJAlF;Q zM*B5-5<)6~HN;TuBzL>uaV>+S-)k2vnHUU~t4}{KjP<@YAAmaC9F4O4E?2fjHhP5= zvtmmJ+$(8c%S(-6X=|1(!9qfKUpTCmUNZbWA~E|xlzfeVm6tQ*cTj2t5M6`~aCX)w z1awy3SsDO6RB@j2jRxi?X4X`9U#j`fl5t>{I4}Y8C92>+&tzF7STWQ8eOp>;@p7jr zoissCS0f_ww2-&M09~}UCyb?F`E(FH*T(1|^#$z5!;7{o&ngxDu`(`m4OYID{`v2*(6MqzEasVrF%&Q9(;eL zH+g`dd^_%TRMN-8llML98KBo42A3b~c)AC=IE2!l1ik3mAU^rt5Q&zBHZP9JJY}Vw z3dixxc$c9sVSGWiDX8er3ypnWrSE@Pq^3(gRMc+9S-3Yk3xw$(u$bw>a|DU z;2GJNBcfw}buA%~l-o#vAV8SAwOYGVbM{UxIi`2^*W|bEBz12#>~i{K?(l8HlYpg3 z@3J#oMXO`Pp@Ti)&JVRh3YH_n%&h#3B4zNV^ljmiu$+f3F%=a}F4a+UdqXPX&8406 zZ)S%1GS(hkMnY?Zzswb>Qzo7VE4eU5A}4tfn#t)f8WH7HL~wkq43H(gbG$qwO6lxtg#J1$Z;;pb!`Gq@2!tsQQzs+9!(YI*Bdz1&CNO@!^MV=`t@ynW z|Mkn!Mzz8054e9}LOfc0t2C0n==y<09@e-#V|eXkh&liYyI6o|ukERidtdd7?lMuO zeo=5%R`EO<`z6Wcpt4Rk8gA>_|Fa!kU`GvI+Twi54`n`#rqB**!KFYQ6k$WQW>N(L zS99~P3${v@`B|EZmHF`m6a+(cHk2I~!?*B?5>xkNC$<#=Yog}61{BNA&g-6t1ZR4L z>Ssxx2TR`IGJ8jnESI#}j|zjBa$*{%52+)KEB4FeGxjDQ7S>>#Jz~)e*bavor-_vF znc}D0pPqTXM5`1F= zdh{zH4R{UWe|X(1QEA%i?U5@9V}f4Y1SfqMwLf!K1^09qwaNoRTia(2^gf0lGgJNkWT9n1U(}!l}B)n;%i<=#f9)L`gKon+idDy%zKl{z-ZCcqL z{_&li%aFZlDMpmh%8al%AabMQ=&IZQ z?;ig08lJ{!*f4zP3{U>Z422S$Icc_;kFuYT2GLQ)VDR`EpFhHbkfy5gLI#SGmm8Uj!IK2nmk$N5unM5FtO zhPd#s^W|D!;~gzN6s$tiwt>*pTKRL&6T(^FSW{Tagt+%~zP#DnX4yEQAe!PKVaYn{ z8fr4c6#sQF`|;cC-_CJu4jD9FlN#MJJOyVWGP9H6M%F$+TP!+x@;R-%1a>Sd0Wtc0 z$==g9$X6$z>wAvh+DETeS-dYrATRgSngo_H{QxN0H0fLph8}*)+*&ORlQ-DoINak} zpAUK1EyKXlO}Ko`(&TPBvx5{ZGj)qdRJNAQ3{~Vc!{pA>fo>M1@xa1u-KpbPc_k-m zpj}g+JoZ@mG2rmbvZf)!BWtW&4ku;QOiB&=TgaUf>CDu)y^hlxracVt{vaV zmn0!xD_VJ#2h82oY8=U=aY;_9TUWGA7lc}lw{>fI^_O4Ff76p#{KdA#NoV3Nh41Wb zwj8)ghoOOTf_0H*5@{Jml0rdElh4)auPTD0lAP*d#jsP1h4hFLM1@ubE!u{z0#A580gsn6YZ4WrWVk|9CPPTz^JdxF~w(BGe3EKx{mu@@KC0hS1^UT@f;kxvg+UcqZj z@pM-%HCA|rcc@ZmP%y{ua$F4tt@k(X=Lb^1DWKL|Sgt`Xd)tR&@-BwgK@|q$h zp)3a{L;%9tb4Ja)p`@_tkc^zkMS876!W4V2WhClA!MDcv{q>Fh>J@5RH=wRC8_N#f zC|bUo{m_Ns_S*pT?=_%j&^2y5tD@d6TUS~V^OrNVwnYTBrg3$QE6Bttl#$UqD~^$U!1&`O5@k z3teTz7`D9kxY`>bSdwk6ZW4Y@K1o+MA$*0f(hwirn9YQ>OaCg_g;C6T$#736Vj$S= zSJR}1l6z%>N5D(m=>oH-11Y#qI5&sh*EWWXN?mKE@*C-IB7?RFtE$M3gEr{_u->`E znfu)!Ib9s;b2IgE>S!d#`SJUAk6+5(%2ad!ZUqkG-%bv^-ktKlZ)4s<+aizKse1Bt z+Q1)I1{L;;uk3dZPrx`AUA}wQKvR->oGm!!#9Fr*S$Opv`dxC z<^vu}_WDJuxvotkTCZjoUQfXres1bm3pNQ4!@YWEZqOUk5Ws}t;R<|5z^A-tP;0i1 z9^G3|P8)H9QobRUezcy1d%t0}*z7zan7iBPxzspY&j0cW#z1R(`RC81w~V4g(QD*L z!IBS`pi8!9rl=JHGoyd|EotPC$x>5zIpk4$(eb05Ta|l=N)`&3zB&0>#XJX=p?1ib zdnfXsLB|cC=h`)M5lq=uP*l@}-0*M2en3Uhe2tF%p$6bB_Mea8~QK;CX6b zuJSP`SAhB*#WR8Syy9<04t2%cGnq`h${9Dk7l;K-^>m_JzVHRu=o!U3CR@#s?sg9T zwx!(StDR|Gec|D@aaQ~!q~v`Ap=TsP9Q0aR%^Zdkkx}_RFAjBB!IZCv{kT&R3OsEU8 ziB{)8T58)wyB#ZrsviwExD;`aZ5{;g&K#v_G(v)oyx_RWy%+qW_;#-_3unz>ioM(5 z2_*w;(`n@Og)qqG!9W^z+`XfK25FntsVqw$P`7zF-p@BZiasFwc zdX@uink7T^3sq8@CVtxk`n3qP@CC%D+8-0c9vk0P!ISt=#Klz74F;62y`6gCj$pJY zj@H(7Ub~$f!^&L1JwG6q>BKvr*FIf-;uKoR10mZRS7 zQF#D(HQc0q5Ct#i2M{h%i0lm)Pd3zCSyR-QepE!one)+$Ic-?J3lOWyvzkn$zSpf#Xk{%yei_1}iG5x;TIf|9O%58hqs_{m-$tLYnTP)(_? zeHnTh)<#($zc|Z+7hGOSkXONA1yN?oW6_U?D=+F^vSKSE~SLMN+O5G2&)HU2VM(h_NRHYPpi59oG)vjg*ld8ErN7! z1jy+fRk}*wNB8ChFW#+~+XrNmbKu$7iLEY}for&Bc?4&|!OYC{`L2>2PX?dFm5?RR;n_-Jl5ND0(FQ@g z)Um`zgd7)ZC=>MAU{MaA7{(FbF9v2Occli&+Qm~q$IaHq&obumqu+rHZ5?E?U&5#U zDb_o(4+txxVYAgfeA;Nw*NEp#~==F~Dif_F@;V+K{kk&Y&zAqtX zQ{G}Fe0&c3QLMQB71YAQeAo&5>pIyGzToA{tF+WAu{ru$&C2t|R&_h={M2H#@9x*8 zQS5Kqk?01oA-4BIsh|eA>xr|YUXRAu2+q+LV@H0_$o!U(;Mu!`^~bGA<5Vz_v>dSn z2UGLRbREAJZp`?8sx)tT_Gn#_*5h@jaEt;h{f_Z0m;8l70){>=7hD&-&;H?$e#*D3wLB zujFl)U;~qv(!_3CJb+Xp+^F#%aYV}<7%3YKbv#$0RT5tH}|DX|=S>c}lAleFw8df>SC7~;;O`#|$z zy&|#tVuLG~1{^$pWIGQnzj(oL$^|9d;d!oZ&@pLQ`1(fU((F&RpP$fH1QS*1Tk5MZ ztcyt^(zp+Qso&w-hBsA;j0v)-X!RO zq14F6r(#=~JQl$ba;Sc1@4>_#N#k=yl-i3_2nmo!rbvo8#Poh}W*ypdYm1;^D*iZ9 z#cHFuxJM2!Yaf!j$zVH3vkG4I?*O~ymqa}Vi%jFGitRSuRo>4V;l&4VLQB|0JmIM~ znn^K=3DPEYqkl1n_A51I7Q<;o>Ba{X$T442u;DoT8y4)ZkNjtmFSt0v&@TAd?0F{& zu)WsX`Kj~K+7?RKO$NdJzNd_Y+jJ;489sH*IPeQC!=amK7D}>xzs<$F29G{CG`wzG zvm=xur2I9EY^PXT78Iu;TYEKY=3hTMKfU4^NT~N}|7fDKxF-&@dFi}G@Tp%)LwvkG z`z#b!u9{Qve0)#r0lL>fmK3Ab<}ibHVA{i`TxYY$aUR-;B^JkAuX&o^gpt-*++zYB zOYxd;GDDl+@q`a}(?KD&@-pRJY=!U3om)Ni_H=!TE~H3GY*kIt0x60bT*~*QqsTX) zy!|Mfaue`rq`jDqT}SzHQ)*_zsTa+SwCRMi%?QL9Mzd*$A-+g74Qgdm7EqD!K8VkALC57BFg-g}9K=$!;n!$kDnJEQj&ExIv- z=**}~i|=^$v-h$0`+ocTeq2A+RnB|e=XqWCpS6zTHb>IJrCHE9G&nG7Bys=uuYGtX zPsYc!yFfE23D7^94nqZ0)V0M~j|z znRk;y=s(m?9qqf0%#YZUb)`V;)fLNIIN9`!a|+XppJ@>R&?e7G87s+mo$o)VKwWx) z(Y1FU=4MYgfIR%CJ)eoFTRflw5qoZG+)a028Wsqbx-t1x7BmUAiL>_n+H)xQ0uPHnkQ!=T=7s|a95+E%Imf%f zQk_287ogq*H`0}y*Ht0bJ5u82f-7F&5d!Z>A;fKkCy~bsHnw~j^dNIRQi%cth)mc7 zslfG+=(_??@V>`HRx3|wov=819`2c+X-urLN+%82zI@K_Jkrp`|KJ=cc%lho{4nDF z@!9X;P#htK2y!r=X;Dv?zoQ|yi(r__@x(Lhu=%IS@5f*@wwRD;790A4Ymul-fDb?q zlX<|M`@f(<5ADw@e+R|t%)GS`lC9>nC^mzSRhSBa$wH$o<%P6kRj+;5!ql{dKWSR< zX~~qg7YBB1I)QJAs40M`;+F?geGQxz=Oe67j%tdrN0`eqA%d5Ewy#Bb;PF}U9h>K= z<51vXof@4X`FS|ULYZ;hEQ5p$!u#n_ueFJQtQOBR-fB8CINs~3H)vV;Vw)|Y2_xM!aow80t z*T)@SH_ddbe&CFxadhN*U)z*t9@4QX3|@LQ(yZ?OfyIVYutxE(;s6W;TOxq?69)pg zI}el|p#Eb$?2yE zp%Q7RY?hz|GNkLmc!!_;SP4WuZ+NwOOb&4Udi`bjv-8XDSuSC7FeU?i(|@YbeXU`G$oe6C&MZ)ICiNB`PUQhgjFPbEEFF|oOoHHO;Srj_oty|!rgyKVg`dEM@rZ309# zSDtRb1fS(PaRC{~xsm(h&IZzLEo69NEdHx+Upf(Wo^aG*q%f#$ye|%yeXcs`o}M3? z%@AvEE}@dXW@kOpuc|&hU3eE#HYVr|E`=Y0k@0b!iv3UL!VU=zFkW#;-v*TVR?BUw zf!u0InM|RZ)6_3iv@+g?pQIMpWzWS0pSB z4{EfWB~qWFC(J$iZ689DV`X)Jb#JZ^rLf2g+es?0J8;1>@i6odd34)DbXlv{zzR-7 z4a*&AN;p;~RdeQqb<+KvUmuH>;YI)Y7eFE0{Uw+itPwYo_2LV;Y)e1F@Xs`1Z#8&@?LE#>w(ZM?G?@43TIu>0LE5VP5Kc)k zGAZl&>U#cd5;~Yo;ny9QrbdXz+o<^kRkp!$`a#CyguT)FmGLoBOabxY@%M*3=ja<9 z==RD}AXp)om*0Z&BBaGF&h0Ity!5aR_pDJ|b3G9~$aP0Q9rzL;W+t9o+cA&Q3}%G* zX;Fo}F#RehpC#;$FklnUxn*uBwlLGGB$8?KQGVKR-*oaE{p|Hn*U(Sqt)#~?7 z{%B<&^_4vI0nFjj(>Pi9>dm!LpVfzEwJMI*>RxdMIQB;-uGdiKW3@_K!0fTB2$B#E z)qhQue-+XYsi6t~VJfnR6m(do7G$v-9@xG8zBDCmDGv2c`ra@9IkG6J_?hJsRuN={ zcfCG+R1Dy`edVc*_+vD4zT)Y7bSbc&s`la`PNp>H(F6(GJnkH*tGPa9IBIX$Y?)`O zrB@a{{%J)V{!J8)7nS!Vdz`*gCu5(LCixZblof7siEg)7e2oHvy~~*UWOUAvv{gWJ zeK>F+g#vf%6XgYt3X&LwY@uW&K~HF0k~WLDe~bJG?$n<}0~gtY4xihf3t1Atg;cJ7 zf`llyV3h|aCX{hN{ni!TT@&t;wz|bE_4Vk>H{K)E7~$XwCvw4~-fL?B+cb%q#G1pH zBegcX;y{=8oo-(vg(6FMb6LN9x1bvt^g6%Ssts=S#<%WggIR-=5FA^AkqqDK2{4%I zS`nNOmdo$~ZmPZVLLt+f^mWcl2B_lcTz3JfugS^tjuz@DyR^iEKGB9kO-jA8!^p;W z*J>GP@)}40;9#;9y#FZvqQlaEXI?e&xydfrQ-+)K0NE~EC??ElB!^7oW8FvEaW?U3 za+)FTUu5wvaCfG#5S<=c72)yJ#i(hGSye$FAZX2E=VOev@nfaXLkEx1>Uu#$V$n`w zIOG-EHrqQIuIt1XH;*T~XJ60_kBGX;P!iuPQ>`BN$Cd|sfQ_NP+B+1OHd$abR^>)j zVRHGHZ+&8^%I=zxJznPDJ1ZgX0-`S$GIITV! z^vkms*mpG)J~21Zt$d5P-*HZ{!!i@MNk_NG{j5-Np8Cu37$KKCww~7dv78DzQi}wV z&5W?QYi#`5@04!i%i*pX7b~28Ab%E4rMEvID+REhCDXy5iYT8TSEGBGA8XxpdaH_5 zAqpt`g$|TsI@`j%IBoxBV1D+?*!Rdjf#*mim+-Ugz;?o382Cb~yDGVu*8K}_VeVx2 zOKYJ+WX&XF|JR+}?oN4S#o>4|?os{laSgwWuFs@?JYVQ9SLW@;31QN#t90KxYx|iP zp_uQKI8Bwbq$ahbdsQi+`n=SF$2I(T zZ#4q^P9=T!voY!@ZjwwI2|)9JfM^3~#Uq#E7DvjZR6x>>3{&Li6;UMX@@{Hprv^H?(o#U~QUEcE- zDdXcQv$MmT0Y;l=#8CN@wg%5GJcn`4qYGh>{*5q`P9qr+j5k|#X;SvNT&UR<7DBAu zbo=IQDP86Z$@a2awd37gIe#Rp{w_2*7c4%_(mhRBHjic!b#a>pt~I2S72cL zS_T(Ny(Zaidc&YjQ*lf?W+Rz7tYoofVL5EHAZ*>6<hpRbp0$sFME{Y5A8_^H;xJ9V)Vq7~K={!w#DinVblUd1 zFq>>%p2p2%^OV;nHUo~pdR`#5JHLZQn>hA2+ZV9u_bpItgj>u0qg7nu3_O5oFwGX~^7}Nun)8~^d zRsgts$vEeUUTC~2XAViyy@vZjJys2HBPDW@(|rZErosefcm6Uzu#l+osnmcAjROl3 zDcI+gckgC6TuIEWY%$#wHPAQ;4usX;PeMQ1sn$Upl;51?o=RSt>BHCu8Cgb>Qv!?e zQQh~6i)o8NjXIJf4aeT|r(UaevoYXZi_+~W4{vSjwbl=yv*>7MiJJth?6Q;)usm~S zf$3$bmD-A}@Gnlx>5)`@v=Y8|l~jfsz8vLr?N#0(s{QF<8FdvDc{C{#V~EcPS5m0i z*DLL_DuEjj>^)k|sg6bAYLWEEf7_}=f2UNu_;GJT8+b2jZGP33172nuTRt%OLmT6H zWnKf42W}P4_nF%QsRVhSNJ^TdCeDYjecu2Y{M<>Kg1q^7R>Jhqr3pYmot0Ck`mlf> zhS|$W1Q&cbCr6z=Z0?)p=OIL*dCA69n07BvRdafGpd&0@wpSecqu&bJ&amJNF^&bK z1;yEJo@bgVIO)4k}A5w~0oNPjEeM9`JO|D=H`j)2Pzz_4SQ zbRcn3HV`7>D4X75e3Y~NRQLz-Za<;Sp~*0gsgK}2j8R|$KsN(lC;sD$+^1@PB3-UY zru0ihbO=xG{j7H)xb?YH6@4d9q6C{hoMqf4p%GLzY|?}zOWDjW{ff46&|fTq(oc0; zMN~j8&5TGX0R#H;BptL=5ayxMu~{0#WSFSj$es#PYg2wn_~G;d=+e^0KO=*8TC%{D zPLcC6ui@-bHd26ZWPG?AFmrBfk5Oy78v#7bLVSGET6EpoON^|nzOPHwQv9xFD5A=} z&;tm&@>~cWkG=WCw_V6?8kvGyw98Gdb}3bHxHJY z-PZa}MK*{wWVmYsKH*EBZU)@lr#hKVSuNt_m)?NfZqUPV3$l$1CL;libxD_l7C58T ziOAt5yI_<;XoxzOC|twmTSjVFhR; zYP5w!u?={#>1jBK$1z)-J@YMoxA=0FZL4{taJQbWzL!LTW$@D;pSvBuds`{p$GM+I z=Sgv2C{yn|zKtO0ePBjFeg|UC%eN}ygd2r*Mc_I2$*}(X%@8wN0*b{Z+UCZCS$~`e zW{t@?JoiJK_w!oZ4%J@cM!Rl}t9`y!7 zwtMyb)AKI-B>@1-`pldooRl_jT<_$OmD)4CWgJArVzT+d`$;UIOMLq1Vp?=QFvqr0 z%xv_W0S}0MxO9Nq7^v+{QsY+O=;=s5SGd)+!8X?X(pWmT#=@`8E+T%cdyz^D-HQ2afrkZ7ccikATgogQ zrA31KvqW$Y(>{*~y*clD$SDW+XZ4|nKBv_|QJMHq8PA4$_AfG4?GTAZ6i|iZyvw#K z<9BHBP$=`6(CY3%6J9q1E@z$+gDT69r(il5Y~FB4@|(1v@kb|LstWERSVNH|_$GW_W*pLz3CST=_+1(n2<5RYtsS7%ERUgs~$1h~BsEb2Hk;rqn zHFH0~rZcQgX40A+g8{n&5?B3RjO2WF#9@n(2yq{nNZvE#Tf!A%i8kguI zA4!8%iq_0p9YVE})AUK;{`dGKDgKYD!fBpCoN3x`xOTLr0B$`J0i_34!i{V-iL^aj zoYFd}nb-wh`E}NwuXIDDiD5O zv4TMLQCl&;bWWI>Z4x;@39N-9Vy;^Sdv|5bDqFD30{l$L=tRZG2S~<8CwFi7-~qVW z*QM-d7wIEoFKvI8cC(?5C%9m)qy3*-FXJZV$FfqNmL@3EvD*=I3o8=!k_aho+jy&n z|2dQKiYGMjHv6@)lbs&*TcS;{Oc(_3Rg1%@h7!8-_S4lqlpw2LheUHGaCq2JbU6s& zRY=B05>j7h4X@^mNE*K2trolKcn)Odj^FdOMXPAkbVlad3OIacEOpFQk1{mB0&Mee z4TgG&B}u6Z53CrVrhP`bOGD;&y-SdR*=6`$bE@jBYCB{1C#&doo!ykI!hAolq9=@B znu&DIa%7F|ijtaaZVC2gHUI85EMlJ;TE6XTpoP!!eSzL8n)2W5zQZ(v$?m$cq+3ef zL4V*ijbPk~gVBor$(u94Wg_g40nXi_?D6(jN6BWKLE+5!Y8OLmIg94AL$+_dH6FNc zbX|%p%}=D6#&VW)E~=gP+bk3i!(3_vWupu1#0)`U4NyW3CVuvFri{C2dOvqM(MF~7 zykj zuBuNRNVV}Z-1{7<7L^^3`Pq-J=2I7(wimDICuxvjuv__-XG>gWP+*><(`sokl9hqL z-((95ntL6A+`Z#xIUhVS$yiz^EV+v&(!#>Q#7^zGoe!)4^UQo2qs{*bHs zPuT~DuS0R}2oA29>r2HGS8$?yRuz`#N0X3e$twx*m0`p|ybLuDp?m0<83vwV-_J#k zuQsQw(xn>vn3i?ycv$#Lu_1cidL4X#`a`gpG~FtsCDdnHv5v7je7)4w$;qQ`2B{I2 zA?E8RmD8|p;PdEn2geuM>fyylJBPUL`t)s`d>MM9P_DQi2P$1-KcR z2_G^&%zZ5{uhK~n(@F3`GmqQ-oz+727C)e0vput4>Z{>1VkDkZph&puNqgi;YjS)+ zQT6s2W8}233A93odxif*?>(sz1M#t~CCAU!G6md{4OdKZpLX}#l#Cxs%jpIrQ|j{8 zaMCP6_DGh{!x&dz4Czvn8C#C>4GoD>(0w9s)SLnJ@zf59StXPnUJjJ-Seshv1q;R6Ly3(N;{ok!=xnbB_~8AplFHipahGTBTsi%;=hx=)o}?_B1m$J8 zf-7z4*JL)2qiE^vMZ|a8fZ)!Fv@(Mw>Lw!sgWAfApoqR zNU&_(Ir|+GC2`;fFkN(^Ki%s3YMCU6+U1s#58LF5kQyhPxL#C-z=^wB^7xtl=|**a zfa#v;BuACipLIQV3wx2_PG1FafDxIJ>tzrfYq_^%YaQ!MbZ3cq`&Dkt9SFlAZnpoR zka(CHeD>Tn`iHM>quq(cdjA-Cw-sksC}*WUkEjw~gU;_J`*O1fpJlSu%*L-dWa>25 zy+y`fc+059`<6@cZU1=9Nu9^$=!O1?v^%T%#lWL`b1KOI7uDGdXond6+H9+PAQ@1= zS83J*uA4~VMj&@{NbIXiIz{(v7n$#UT8BJd8m2OhGxgb=uu5ywNFMAo^M?gDnGBYH zG#62be4N=VDl$Vs|C|#1F&$bt1O)0C_9~pn_S2I>+H9qP&3=!9llUU6@rvg|_m=eR z3a}3U;D7E8Z=gj*@(#3Re)ntgRzLlkoI+Du?8@kuJik`0_Gm!!?2C3gPrJ2_>si7T z`DHNNeVyK8VG17}nfnqX`xI7Q89v=T3=Q4EWT(z5T`?RwV_S_aDkFyG zyj#RgM8ymK6xA{Cz~2-*ghcy*9ll$(M|ICh9{_q|FHiI=E4sAx2CSkl$k$D3T{m|+ zL}^3{FS=L+z>e*XlTKfkvruYTH7pM{F%k*dMFm9@OAj`ujOW)APuKQ0h2%}>N`;Zc zy(st_30X#C{7=~7#4EdNj~jFrO}e6fSgT&RG%Yd4yl4xI#x58!=CL}Uc$^}) zt9ugJMKy8SMg?UBBYpv$dJVqXOO%TDJ(PA%YpRqj_XIl|KC<1*;sQJ71)Z|0Rs4Z@ zC-X5#>i3FF#TmCork1HqDIu^UmV7;`*A>y=a5{XLoT|qpmJ1UY8(q-_%b`5 zc;K?+WHq*sJ}$cRfbBgY9BoIxo*X^5RZ8VXuR(RMM#ph!Ycl)E%0W8t)mCri7uyRS zlc(ET3x9pzk+!k$!RiFaUqL#`n_;M;4|1(G_9Q@IAu7>vGAclA=>>fin-nsMI zt-W{f3oe>a+DPNO|FgkgD93D}$&-@j`!y-+Nex4rX2c%~=f*S3?tn_qMup991@--z z8s;uUnZ~bOljrYLl*9I9dwO8T2#a&F-&wlcQR8!@_=YRv%=^!CQqxC%T+laxts0#L*_cO3$QtK@FQ&k&HNWVr z+@%TPoxqcu$Zy8KJye4IKQMrOLYEchNZeoYm6O%}n$Ki&Dj^Sv87N&9dV97Gm!N~H zY2F0VWp0Z#oE3h=46g0cCkG7IX}WFCx|=v9`Nd>!Z^Tr?ws}QG`aem4b6j$`-w*Ui zSSQq1U~2bZ+Pjr@bvHDyH{Kk_i>|6%8CNe~<7u5Njrpg1nKyjN1$}k=)qoL-WlZ1g z?kJUbPrh4uSlf`4D|*dbKt8}61kHYIKaJx3`s{a9uXW*yF0TOh2O$r`=Mt8bP=6xL zu71ZP<_NVF0N&~AZUU5UhTVZDvh})j%C%yyk`>=zh~?Sk&6m@_rc5ddth;BMYY~aj zq`-OVBg;8mQmeQG`6iTl)xaO6WafS#0yXz|?@D@C;;RU^-n!9I z<<$Kq=xrG-uaK4E7d~jvi%HcVn^#A|Vu?43Hiby?mxhyxlQsnom-d#`0oweRpA{ow zCG5+Tc``b-(JnOsp&+4(IH3aIo_r~$HOAMiEK?oHn(6dP!|q-eyWI^XM@zw0H{&p4 z?sx<_b+4p;%pL!U!HH{aEN{iw6W|9X!@OP-@8K#e%wISAcLZh zj+8d{iHCJ6jN6>EYii;kIwS}NSLL}m5-IF4eyBzK=U#$-Cwq5qhx>`$27R0Fhp$C! zfG~^!tHRBvkx*|BhNjC)9=Da>+}){$fW8xKr~Sk&?l38v%!F5AClrJ26|1Fyzl^me zGpX8mk14g@mqDb=QR01&&8ARm;PT)P1lt!+PeaT0LdT1x^u)AJ-;(2F^%{A@Tf$DHWGD|DDVZDVl)*i3l+Fsz>m$pG8gQ73`gmDeSgBFj{ z1|xN5eLqIfQFO1}DcE@03w|{oq$qg_)9KGrh{x2i!Xp(QQ)Kl9VP=9!EB&DFg>aN! z==9A}f1l?kc8^+{BD1s0Dhn-1J2{Vq`OUn<_cg-6j;7irh)VoP(oVd?qT{W{>}PFKQdU~B*i+p--(qfrh%RFo*UL^ST2og}a% zY*<>kXW0jm`3^O#DJX1}bP*(~);#=2%y|rF5~RkG#=;_v{_Bo_C`{&LRxaEYpyhC; zpfNF6V_CIzSB+7Nlk&E;8VwOr_IT1oK={;If*&r@x7jM=b)l&cKwB%gU;UA8%9ESt zO+3*v?>jzhUd%2}=psADFWQpOziV@%&`n6|V2U+61Aq_1-=g)%*_IGapvheHJ8Lgd z!_HAv9mn@UE;+{DVq#~S%1@Z{=ktRR&aVDiU#nu$HAy8vTjF%$b4ZI8Mk=DycSSnE50D%=IZJna3j}_sbIi#dW@B}J@I%>`^hOuV?GPfF3R$; zC+}!vSv%gDzY`;uNtTpwqI0QDGF_` zdx2e;bOZCSng{S9DVPAzLDaJ7C}rwtdy<~t?@aK~@AJ=ERkC25+j;)EPb}L$?O{*1 zUKaAK@03V0>zJ5OwjZ;BKX|kIr?y6a>&tIb;oMjS;tMMmuhBDVmvtiu z0n<|q9`7`CWnbL*UGnEGH^*Kdx`uELl_7LzZn%o%IMaqq$&w>Zt>yxk7}-?B7xmaM zFV-JbHXPU72AOTamZ!~hn^>^;*%7udjRZXU6))N3uc%;~f_dcx{OWD~I77iDCdq+c zM3+@D86|&GwzO{F-076m7{7C#p75}wWKACYaXWBT7ava-mT611V2ivuruGQ0Y62a{ zF>b2cAIGTl(02Px$BZ9Q2X4wj!L}lSKG7n;__$jfxl*v48a-7 z7iF=bvOT;xk?)MZ)(z@oA*7|B0!mvQeX6p*H5a^f`*iX9!ZE_s2t>fGIP&=M*I`Y= zgKzM%XZm@1T_7L4rk|iR-~uHyFqNHEGCTzx1IO{tJ5NCWAc#Q{|xsW8~myu5T= zOuAO^v!Bu_AA9@PIT4QG>THOZ*6~zi=pdc;y*!3~6>rK?)lvHhj)%WVesWI3a{SM< zO&NTu>LLNSUwiwDubBOOpG_TkPLUz0zE$$RaEvK%7oEnL%m0*G9lG}pFMzflu!&mW z{Rx|dopCjbD_cEQ3PAN3w+cWTqcElb4Gag!95Da!UOe);vITZ_SWu)KcGl2BY5-q0 z3J4p@D^jyh9z-n`356xnn9w18{nUjH{I5YwfETZb7_{r{InOQT@Ha9;euw*_>@NJo zKjz8XG@<1&i$a>%_@RmU&8riIH5xiIv`d2a-8DN15a8=)yw*P2-4Jt++r0ZBfEVSd zLkE+7SfJw4e+l2~0T=LLnya<%@Zlwda76-ice%9EIr@ps=9R`mT3M;V>&GR-6@Lqc z1(BHiwCbx?^Yo$N*7!ycv6a~a0bFPh#uV73H%S*aTOj2&4>-M&zIkP0$%;|$3jCJc zq{2lJn?>-~-ZvQ$JiZsieiu(49^b;+uB;qbRItRJ5#9ywiWW$GeZd)e&(4s>@R2Ni z_A7QV*86bWfIxe-N=h1#^ak5$gQw0s;b@Sq;Rgu@6@fv)7vQ}nC zRkrREKz$J(;6;x3qrR5X*7vo3wA*;i*X56?6={#?G$uAGz}SE8qUpMts&)Q)!7Ltg z)4&Xsh&a^t5+%4s^PhA>%Jpg!;%|)B5fTf>Ux&k;&b*3sVw?)Z;bl*IL?6Q+$5klF z_>axLy|SsGS`L5fH@{}TIp;YwR$?*AktlxUi{!F&)-A{1k8^a>!$dl~3)@Ask;T&KI+eM%jDAyT=?+PlW=CEvz;ciBh_c zjNNhfEf=MZel-O%K{1hsD0u=Alf@Dtm8Ng1zcq6X?gx7o04>KT8DP107BG<+#>JLQ zfpb86W{rSzO9Oau_QLQ{!`N*;B_{H)d5vzjWZS!))1unP<8;P2x!p)PBK~F1tVx~s zn%xD}j%{ z=wUQL{_an45Z`_3v^U+7;ZYRB(IdZyVbe&fs-lxZl4qUPL7_jI(^s}Eiv?53A-EA0 zw|#4Iy!ugD#`*UoKj|O9p$qYL)_~&(DfC{XI4w1xOsCR(?53yqSH!v%5YQJxoyI?=&AhGQ#4#lLw?Tt!C#`I1D{)Bj2Nt0P55EBO9X z!5j(~6A1PYpl~tR|I7aAjwJmn`oHaOHw7euw1?nta||(;;fktAvOhiBH^6k(HA-JB z%bH6wEWoT!50+cpo6mNC1O`Eee`^n=l#J7GZJiexw=G3>ym{HaR`M6b|3Lc}>c89^ zP%=maDcG0U%cMIJ)~rrSP+M~QSNs7+oF>HXBC-ebN6zQcc zkK0EuO^s4;;%a1R9{k-Ug?Lr@?XCbScsG*w8Sm1t+#&U0rqt#z`%xO|mFadI_`N+m z(`{ncRpjAUs-;Mjf$Sz!v=K9x$3O#pNPpfiD)^5|Bjs_CGNoz$^c)4x9d3+8 z@OQE{gD08FV-cj~2kRO#e^hgNG$~D75gZ_W;Y?b>0V1oYJ z&{toIqDk?Y=}O&y8vFIVdD*@UyT^0B>wt^L?|Zg4e_RR01cEPsPyfZ3pe+Ae?teW8 zf>{3#`xn&vRORJ1-}9TRb2S#E6A57t+eN?07~ws_9xBASoz*|I#4YE5FJT^`g6DD- z`yp`ebbcnXj4D_=qX#2L>_0o^-x^1d`g>vUtRhIwHu%Yzpk$E$W)W(@e{=uk`~QcW z&7KHS!Qvs((1#G&yMj%@iX-*6Uwu;rPGTC(9NV5_(UnZS!-su2V>03ApACSbxI}NC771=o8`B6K;&_kf40KA=ZFz@-H z$8^Mo4D#%ui9`8rKhg>C@fYeBP0BwXBZ%(x+R71{7{P43Id6*LpZQ=F%X>K;K}zMj zxf@Pvu#m!@B7u7gIH#@IP3C~_Bf&owh>IC4yB?h(CaA8((Z%3>)PHjR&okz~QvVMQ zU;GD^|DL>m=Ko)6{hRiG=KhQFe|6-4DEoJA_}@qE|AcO>2g`rO9A4HiyssJ4Fy@D6 zyp!zk^t){{_Vw|y#GOMoxp}qd1Eh#jX@j#3^RnR0(O%!-@qE7pqlzyp`{VJORIu2V z);Xzbv1$_z2t3^v{rmc4xvH&h=l{AP?{=5y!uwOxBieYMzhVkPfevLQ!Jsdo3RQKHu|}d4{M@Xy{nT_U{p>A8tQek4(uwkE|+(msP82+Iv>f|o^S2GU--9I26_7V*6zZ}vTsA|y3IJ;TXiEu-?ETK>+osbAO zuMn>#pO6hF9UqjBj|VEu!z;+eD=Z4-6NT~9{qtauq!V|uvJusieeq9cZdNuD3`h?T z7f~J_Z*OmIZ+>oPH(MTF5fKp{C?5|WAD5ez4VSyGlLx|w%gLSbUkb9;?v`#S7Y~%P z6Ww2m2n%OV4+#c_f5qVF@^4uu_kWI)rL!ZC55k3qmmB(5O#cYh%JSbh7f&~be>k_Y zc#aOdIW=KVL;1?lYJ?2dH)KS=-E{J%Kxadc5t{kM<*ZC@N6|LwxvL(a?N zzel_4__|p0Xj!{Ed%9U#%XwKlc`*JJjf<#^n>E72*-gjU+2LQA()d@G>G)vWP&!t9 zl#`XSw>#T^AXv*HJgg-c_@I0OTu>MnFRuo^oU%*mWz?w_QO2CSXR{)0K60t^Da|!SX zTSE~rYhivtk$>@Joh?28%Iv@RR{tOQ>TW1oloP_?|5@j+1^3sK5LH0AdpNuK{&PiW zTf6?VgcKQ}RJCo2gCH-_hu zMi?wJ5D0YNMZwS=1R{L=*M$X2&!7N-a6lR=I&$(ZDvT6lSy|bGgF{(a*^Crqe^;}z z{(1gg?d1bMxBTT5oUf7>Ivn zX6EC^=E1?i?(UwZrl#@n@y5ochK9z!tz#hm#>S?WmX`7H@uj7u(b2Km+PcQZrqFF6A9cyW6?e8Dx?;ohIuWxT}@9F8SuC5sv7$_?%&(ANYtgLEpZ?CPb zYi(_toW#`EHEjrPf2jXcO-=3T>1jfA)a>ls&!5K|8yoHI9fq3fo8P{v$Vk=KH*|J(LYW!o zXJ=xrdgTHt5jhYqxhOEi58d^nJ&t%bTP& z#0N`Ocej>;j^|<=+o~Hp{4*T5>U3I94`{<|EJtI{%ldLiT(5t7=gtkK#0RhM)k~}# zcm3M0zEr+SPr90G-83){Frd9S9w^y3PZ8&dxE4P@F*%(a@>pD1J>`ye-Lf&RIgLM@ zr>!RD1A*v3in4GWpXL2bV~3S_%0Wf>O?o+&R*hPwJqw`)uEfuNG%0NK z$tYphZC`03cb9DroOtBni}!NDiH3%;XlqKBT@UiIf)Dq{wL{sK&0Li z&io^nIK4o@6UprB;rE=D=*m8{WGPNFaR}}A7}^Cw7N$^fsXj=SBXII?wY=mz{2gME7mf{dm>)$A`VhTd*Duj&ssPk8+xJ^m(7uNEr zZq7xszefk5=cGfFnJ=lJ#XUQYt-{soUOub%p5FFNJ!^Qd3h5OoCoA1x8T=8++~E@< zq^<+bAQn*mMO#CsTV6l@y*E%L6)$O zq=UQM2jSWfZsCWRnt7y)-vy1g4y+YEv%8Ca61Yf<0}%~FJp7yv~?=IzydsBBp>Ot;TvoWc`1neIw>$^uViqAy;NV?l%?w2 zVD2wlhkl@fx#&K`R4PKKIQZM(7;2aP^fVa#2v`o3c99>+>fL+m(;q}J<%oldc>$x# zqB<0_I?5cV|222KvJ@1M1IL7bS1@b_X8JSMwZw_H>-dgK_+v-W% zQY3a&!L@oN&)Xkdw zPG1*fvEu%X2E(q_e8dc^><&aUb!Xm*lvX0+$G+-pD-Fi0ncQ0GPUmcqN)ke_iAH}s z&QCAI(!EC+J@a*`Swfke_g%W`=HMTGwKJE`CEu7VH&ZF|Yj#Ff z-popPWJ+7(cSrRKf%ojggZf|Qp%QO)Vb%+92 za~kiEa#R1>5Eph>(H5rxj$SgF((_9^=YQ_`%1ARQ{4#0YUP<@8?j;R-RGG?}w$0$t zcEo7gxzi|;WK}vTl8+g-FOLkg-s?m(G)~ucON3+I7a=3+;OSnk#&4<4*cKnwMxj+- zX3MD|3WDYDm_NWiw}+K;`@VX;y>@L;6R%cKs9Wqh&ZLm`a$~CZz!#4ezMWny0Bb&0 z{GO=l7$WnE;w~b0Y1sRz90ZNlOkS-S<7MPj{qTw)+lH^#gA8crf|MxjP6eU8wS|w< zY4wYD>Y1>$$<9sJfBT1JAk(9G6jhg4zU-p><=qDS8F?N^a;R{WDfvv4jcnd!Qh&LK zTQHW!>BFxOf?T9wphK?V?8eTATYdm6W4#&PG3*zY@vRxh@&lDGK{|1r%BS`&c#c0e zJ13tmjLtYK4~=#D_>n6zf#i|MQ5*HSBe6&ABB$Z5}XCxo-n)( zQRuNa)D9Y}jDybR!DeL>3VAD^lp$-zpk{sJ&jsEoTR{o!1mE@P2C!%@%ti~meD83q z+o_T2XowFrX5H+vLq`1wY7q)q+vMAnDzN$;9m)3ELAf8EPahFXGM2CKK}3$N5xLJw z(e!&ntb?rsZpNhX0Wm*~`Spz*GLmaU2COyatgAQo79IW8R#h(jRFGFxXQP^#0n5sG zp%Uf)DD7@mr>?MxJ}rABC7^vmiS+HKg3<)KPVVx}g0s8NW4JbVELr5T3Ca^t$7wpK zWI~Z#v};t&gYeXta>^BRwU98!E8nQ@nxH-I=kgP*x6{0e-hKfA}F#AJ^ zUZ0Rw8i@%^m=r(s&CnE3|C5spLyF}~{^s8LgN|dVg@##%Z{8b~4f#b_%tL{S2;VT? zd(i|QsW%SmN8*D~-X59|J2wJ%$XSMTmzY!-+N_{(_%@rPS%S87`Vj)@s8z=O@SdV- zDVt*E2UUe>=dwYr){8|-pZ#@907X$h*gKV_55TT6XBE6xJyL&Vczq*I)WN_9GQenJ zKgPEk;9Hn1%H$d3cVg1C8S^78Kk)=R9txu%8TN$Kq?0%smcp~!fhO013oo&(o(J+D zEgyF5?)(Cfi;#~f$jwIzq*T^ZeZL<_pPQ)c7`|7-NkcBK+%LHR#0%{PlsfNp_zlF5 zVA4JjCU$$-kYt7wqc94VQ5r8ey}!>9;JBY3;I$)C8I8{+>BjG|d3UHc0IZ2cW86d0 z61(^0RRt-9rMW-Ne;BZsjiS$-&zl#Rdr2C(U@V_t;i}d@9+Si+p8hUra_%A|muzAq zIuw@H_7-Ql9Bp^xf3q9pu8a@R?fo%x**#4?Ph@w~)3Bpt<7X-icPZ_uhZAhW0 z^nibOiy){FlWvSa*GNuAaWPlYTFm4y7ZfC_f21c;9;DAyXVfd{MF zFVz*l|8e(rR#&w`fx5+(248tkFIkQXwq%J2BKze$P$UEi+VldF|fjvwc5O>%RR{vj#O z&8PM__D&L@PVy$@DtOB5MP|roAGT04S+agl(eGBA!+O5%ZB!3m_`Z=}{_)yQ;@Kpq z49g`3Vov;S&*2;ACKP~t-NC9B(zw%@!+7S*wg>Cn&gOq$>(zrbG^7aJsU`;au~l00 zzm4wU3(pW2Zod=Zu&%Zfh#{ORp^G^2fN}>`_~&7TfK&TIxzfh$DPle$NGx^o5sOdo zuh5#niSbNBaT!{|QKeCR?t(N^A?*T_p5%W@%l0wL-kj*f+&L2GwP#DpN!5mOB|84= zIf1k=HTjF~2(=I)I}FG@HKX-v-d=d{w0ua?^-Z>nO;kYE^L#tufZw8^e4(HhAwFI< z+Z82KnAwJ|Opn$g)%)ay7dmr6qehgl3djX%;G~lAC7~Ag2S+QS=^F_SYJ#Q4wlMjV zk2m_2XuAWg+2>P84Y$;T_Zz_AJuC%$BjCi0Ap$g~aqgj73{i5bML7h$BDiAhy4`9$ z`~AhQDc;oCiiljKqFAU&Fl)rJ?@0;Tio#`zkO;CrW<(Ep{j;{V`N3SyFEhi+oa&b1 z5^*zy>3n%DKgQKX3Qji#WyqjKK5Frdtn~LSMgsFsBTn#@cszl=7 z?^VB2=O4d^vU+wRKFL@2V#=rla{3~_pE%5GSkt7RuXKPZ;J0AjKBafVes!M1O zS@t!u!6{?}&P+NBeyY|d#HmNCY%`t)xB8hwC+WHT$E?pF zU$Yoqlb`ivN8 z7NLdZ!n=(iM(Odp@7RFzKJ!GJ7dVruXuKQ~x%nuehL49_0!jo5Ui*ULSUU&|XX z!e6ku``IC_DQ|iTo%~DXM9TFlU$Lf$J36djw}o^2g|l9gLitvg3$q@v*&DRo`kF)g z*AF3TA?<3XVTQ17Y8!2KPf$JrJLvxArU^f?Dx>PLO_aP>Bg7_2@FkR723+j^4GW3>+)Q`=)ZHC8RSJ@)MjU&GIO1qT7I}1MO!C?STilrh4|RGrl3& zdjXRT{qfgMk^`rq+Kzwt87in!0wI5AS@YDu%(^N_L}i8_Z%#4ZsC=kMZ>i68;`5?L zAkjXx3#2G)=ssNd;Y02|f*+D+g`F@qg>rQuVoR@M<-i58A<47bf(HJ#8WOGT#z2yRxBZ+qQ@Yj?aTtW*B|aAEv=Rnfvb1k_f{_5BtDy}6P5+D zf5iw>EDE#oOhN@SmWt;{F5GNjn6+1Nqlg#mhUE$-u(JmD%&aV&eF)?}&g1Zg&=mw^ z0Nj&=X0;|hHLCyU^`h;n2dEbMo(Qg*`?j=p2)8A$X8qL;t#Rpo3y41RU9A`!`8j z9#xSxlFP%rd!GTztqP*R+wkBloB#*t80jc|F~>UjyVW;PvVBIq;rH$oK}E}9MlvNn zoZa%}^q1F&obC9&Sm386b?0)w2w;ApS8K+U`{oNhP?#^nazIH1d5pt#?@q-PGC<`r z$1Mxg)YtfJC7br)!KLheu3PhVRdUi6M_qm*aZBC(4he_tnv%)?piwIBkt7Ox{ZyEB zo%AK~W3vM-u6+L*KunM`!s5A>Js;x)?r64Zk6$r61oO^227( z%zZ8`SPI3fpSQC&kHGIYLI%*=(C}(6-h`j&S-T}8Ip$*bQ(_Fgu!4B) zWD%T*`UD}M!i@Igh1gx>6l2Wqp}pg@Z+7~d?5U3-MEr7GfUYQE_P6V>kp)wglgG)1 zJ6E{XxVg#fhQ3N^VsG}LG8;la0?*%4Sj>}{b-)d{I5P+=U=hhOgL#U8m$^@3ulNJ+ z)eR{j!PyEgO)X{Cps{w%vRmc$v3ZHJxfiRr zC(G`Mp-g<;l!v($s2ZN3%(N{V4H4crDEW*5b#AR{@eJ0+08QqLdTW=qt!n{=cZVGM z8^ppus<>Qssd!kNkqk+7&uc4)9V=euU?hZs#;|YYBQ79_mx=G(R+qk5%g^2d-w2|m zBAVkK&0qs&pYP=?f441Ca(?0k6o%?VV8%mq`%a7dJ>T=M@2Xl08Q$Rrv`5BJRv!>) zm9Ld1gg{W91->VYOA(BNgw$Q?a9cj3{&rAe z1EU}|UP@`yfwlJ`eImx_V%_Lsfc-h{ntB&)f?`BfYLQNMA+IYaQiWy9L{c%N>La0C zGUtVtPOOh{SC*scAT zKM~^l0Ve)uIHzY~gM7;*FhieKHpE6^o%LP?8b#07N8zufwnfuzmotXAs7#s%w$&Fj zR%7i<`xvdmTWYs-3TN(_h#Qe*B@$9M3D!V1ctIAfOnfHg%Xr(+HZ8W#CN016 zA~HryL^zqj9CO^oqjTJhI5VIzFJn<(c~7yjIbEhlE;TLtTyb;9n8--%Nw~l3Vns5A zRf(6TTPn4e14ggc))@Ejl0bmy3HYAVW_x(E1ZZfH3jM zI>h0H7>S2>xM8FmgC&l=^ON)yO~)DYK=}TlWeoUxTBhswGU^)3kmZ$UMmzxH>M!|s z87)pUDj)OHr!-hohD9}>{vs-dFZjh6fh*#O|z=od`Xg(Z7fyHPeoCpg^jfhfh51ST`}C)bpegl*eJa=qGyi>23${g$}VU_bLKHZHK>Sdwn6Y8&vgD}p`??YMOub{=|w4bF+1zkuTSKwzIA1DM6R#fL8w2~ z{MsLmZBKpOT;H-MdT&}K_aaSDuT6MC`F&eM_bFi@lQ;Rc-VQ0i;h#Z4w+*#li#3{Z zq4$aKklphtg|q2}xKlJui7sWfk5bQ02vGi@Ig?NG!_*`3C;SV=)N`X%F3;Dr{C@Wz z#<#`Re~C3JP0Nx$#H!Nc2X5^}!{HzMRXSW!LLgp)ve^zT*>BjwuLCb828!RF#(wi2 z@}A6m>t;)}?rn*XQl<;alzN1e#?2++O{@*IQX~~H;V9fI_+_~>#fkMGR7Mdim&s$i z%t32TudK{#&a}SEe7R%ETk^Sgz(nV(LzUa0cm@Z?jR##jmp8x2V(Rt4jwwH0yg5eA zIHl+{;MQTk8 zmgbja<>cmh`_vo_hgoNgXK(HGc2jUHvoM2N?uAeTG@mPd#&bbhc?m}S)JZ=in$du; zv0S(!5G%juLQ=((U1++Yi{5#DEk2`T7&_xU)?l(o-Kz@MPLrKqT$7@^2EY(<6_n3~ z#mqB`&GqzE$G-94!2}(b#k)RR7l_efGS#q+IoUxu=PTU>YXA2VT`!AyRq43M>kSpT-3s^R&-B*}m({U&_r_#XiNNC03_>{x}D=_&NWeTZbFQ zZ!+U`KkG#fyvingL-rQNnKpe~sc}7@NmMWh!;gDjjUN~~qtUT7zNRtu&b!B(dO6vC zF~cDREGw|2hr$e!tR#LrhL|N9{hEUyQz5%gs_*v;O2zqv;qt0)F?=EgLulrWtVG{{ ztxufFw}o}Qeuky$!Nveiuy2Ad>w&a5dT#ZIm7DU5vEFOV=7QRHn1cW&`6dJ0joZTK)v5~-!b zl+Yt5Lz(y4h0aGs=F-6dFGD$)Hy+!@HsCiAh4Q)Jo->6U3=lC0?8B`u!_SxOWQHTmt0|67g;vk`GsV6=gid z${IFQx}MINKp;s0UYB^)D3Hm6Lh&Wg zx6yON9DQD9Zs=K1TgwvyspKdN4@g<~c~YXygZ5Nd<=im2Ot$!h#J50Ew9Fl)r4 zG8(&A>_Qm?f81(&NXNer2zeA6ewS0@=?Tj29u&zPAN;CtmFS9PTb?!aiEgyHS+@WMlAF-xifb11mZ7DIY|z){^ZpiH(bT zy_!046uRbTRP7S6Q*;Z^NY1$zz+(gB#F_Zt_8ghtr%2N$8s-imO9@OaGdUAmUQoad zsIM&joY2ENj7@rQhx{l+Sz2Bx{2Jy!Yd7Ov{h%Xv{Z@Us5MG9G6Q7NKNq~EZilg~J zH1@+O>RsMLePr|T={*qX8s6`m-1lkZPlxd(c}{dYHm<&uPc#5pz`O8CWd1f46IqSx zfHRDQp4ixC8R`=*M)p1D$#?U)5gZ8fjTCJtxQa#9s(ul<$m2WrfU)B23w=dGH(zh#YA@}MS{g*ikH|6cdh)T*^p}v6o_AD7IurbE2 zp&TdUNas7WUEDJ@NK;Jgr-``fXd<(Oi?xnD9!QN>uPy|+cn&u!5Q34ey(h(Piw?-6 zSCxlO(@|5-_HzX6Mmsd36|JrXkx0Gb;~=!gn;+|_#9q0++#ccf3mG%3a)B|}gF*y# z5bwbhqb~{P>~GK9C#-}8cQ0fFdJ7aJLo4kH1&8O=Og3^)?NT)$%vhN3Dm!g(Z_`(Y z&pfRb($O_pEVGd9Ev5#v$Utn~G>JM>9(~rQ_x|jLnX%=FM+dXeo-xnH%hH4}bE3t< z+|h=vU=Xh?q*?Ys8vU^+<~9_4w2)DPNM8YG*16R52$qcWj%w#UF{GI6Gl1@GJ6B$^ zfi*f5qPi&&G_)(`xtuR?rJk^oo_N~P%(v72`B5HQxeM+?vf{*Z^j$UiyHdiOA5f<)C3ayZ*jP3kuc zVV-}cNC?4}%&zoch?WsxEF2bjSm;-)xn)nFsQ z(?y4!mTCnWYS7m{x2mfylM*J~=m^0drF8tG(*V3!FHH152|`br{BV}ieQF!i6pV0p znli^Y*PKut>oou`;1XN3#cM8q#7EUsajwYQP$1CLxxfAeIIwmJH3MJ@SCPo|XjeGiY!4pgxZ%^f8QP&C;yCitH#*Bv&`9bd-XX zBet<)R3XyyKXP|@@#qI0Yw|@^cJ(Mf%4h_v#2;-vg02LKCmYY@IDZYcCP77n7rb+g zLVLW~A0Fr^(cX9Rg(mH7swS-ama)({rlB`Bqgu1E2XLZgWkPk-o&pt(Kbpgy46`L( z&@6&WeQ(YYgJr&FvVO=&G_D7`x8|#}^V04Dr}7&sDbqAA@8Kx@k%}d+-q(9Vcu0{V zg&CM?RCeLYnK4IH67R;bbqDjmHOpA!$M53EeIZUW5=75m5 zsnWaxi@Mzx=fC@Y=F&&9!k%&v-6nvQ>iAQ2yCH5fgW+g8K0vV;IrM@$H@ECr^n!EA ztS`~Y+3)p>pSf7qa*0vXlZ6*Z4Su-{$1X%k^nE||kX-Y|wlH1&Mg4%jFl8)Ilx;^O zn}rM*LaqZTK+Z*r_D==hD@D;xK_A5zxoHe&4jmMg{b?V@*T=mt!hpFq z)1}-d)8*5zg4W>(g-o=^M^Ik*C;%xdH`^I&S72XU;vtdTW7wTHOv6A=KzFGrq2w8mDc-p1kc;2o;B#YczE z)aaZt)Hm<2{h0Ve+;PFM)Dm_Ye7aG5g>XImLjBY;4E@lC;3EEe^oXE0A!M3V`eJxM zQiZoYriAdmc;5P2mVBxu;kvkcnsp*M70K-_OLt3xwkncBHnTmt=K>*k#iA-ir}WSU zrpb_*2X7Mcz}A;*a}ZzY9Y`^q0b&2@7~2X+KnG|;44NJw^bbFYz$l#FcHrb9oEaz4ERk}OLiOh)3!R%C_H-%ZHG2$_s`mjMjA(&V*@5CM zIDM1fi+@J7eQ3E>S!Rh6BKZ5e2vFOm%n9-bMI2(iret1O7!)k-dB1iX-7jVSQ|2j< zbLc3a8yqdGXiAys@fKYjHg3C!yqX*UznEMfFFK|S1#`h|6S%<>)A1P{`4if^Nc`eA zJvtO==!OQ|OeR#g1pzBC8Cq;si6}sPyY~`W;eW0JnZLvXax^jEkL6q)t4hG0XU z1k)PD=4q1hs1orMm6Kc812NdsTADy>6+UtoyC0Of*(S6cQ8o{N7W=c>2+$Whv-ZZ|AekU3#0CF6j$Se8#5UGdLP(9 zYA_!uoeSXwlWNxl9mwacU+%>vxVSLcpS_js8}ME;e}g#vE)RuFj4u_!%aFFp2P#|S zQDp%kvEcbHs<|p#=w@;xw7G&Drt_OA$M7D@gmq1N zx$1eZl8|xz{d4`@q==rsOjLohLPbaS>8QSz9*-7@9Q}Zo)*_=y>_~J$F+8pBB?q;n zecWMgwR){6xqQ%IW_R%O%3Xi{3Jd<*e06e4YWc&^ qY=^D)OiE_j zB|4D_Li`|?w}WT+dU^f0R;kZkzA=cNhXY1!BuMv$tdj$1&V9DE94dX>OCViG0NBZ` zDC<}8-@**4@~v_55dIOz0TI_=pBAf9v@kVFSiBO8C^4oUU-rAwEQEWUMV=&!k8#44*i_Q4u*@C`ChrU zRNxZ0fW(I$XrQqI>hkt;5LgbxY)x3JZwm|3z;bL!u?wMSM9%6tg;cTPU4Mp`yyY+j z88H8DKoN)KlhA;w?h@b_DaTaz&WWbdoa#;Qx^3#x>7N<$Hn{6y4-5D3J=jR~0XKFxAMTlePJOonzPlpacsto)JSZESRt`NEPaI@Mh2tm6& zEhL5w^}E4WoT+EWhn*#Bc8dQ{W-y|{g7<~GpTAGdQ|jyy1KusUQt-S6B%eK8zMqLX z6o_HR`x*td^d6VnD|#FUOWgz{za5JrB5&SJ!XUrNp+vjy$e=K*8S3XI#t^N@gOdrd zIZ?V5lC;zad?zH`QR7J*n9c0?arlB_xhw7706huCX1nU)hAeJHr(tsu2UzoPp!sJ^Iu%QXjF_l7HzGuD>%!&`n{;gJBNXo1>L8Q#l@6Zp~$6&j7|g z1^QLIg8{4EXzX-JF}j!fe-=CuL7Ct#S_ptg1$1s4&rfnZsg}G?4i*RKw;;wAQ6A_# zv|p7pptCz@e53P)#7cUDDKlk;qQd@IzNy?Snx4pEA>04Hzutmp^$#A^yKWA+r zHBe-vUbrKESOtv8@Wv`aU~EF{*WoFEBv=d;Su-zVRTYE+0zK<8fgK9sL`*9foBUkx zLuN_-r_N5XA08_Ntr*>x15-tz)4v|4WruNK6V0;7Wg;mae{+R>?2(mGcpZ84ql^)7 z(=5Xw&b~=aXYL7lV@sLuoa$UZ9j~?!4o0|pdTQ59cRy=Ldk}zuei+cJBq*8Ynk;laKg8luoiJD5uwpCl%6NkfV>H`*LXRDlAGs z0~VP1Q3L2tF4d{G=?JJC8dN_JP{~A-$vkU&Bn&jH3b=)R2ZA?_r@nnfA9ofns$Qukw|mTH|Nto9xo;u7NI z<;uEh>FBoQKx}R^#UuXJg zGT%0&a6;I_PT>c6vrv%?$5d?d5uLXxhDE+iprPHrz7SRvV7WFCQUT^_bXT#t`ax-6 ziBu9Ks>Cgyiu4{k#q0&-$Sx)52kAD7CI)8EYCoop8at)JO?P~z(v%B#%?ZJ>r+Qgp z0!af~JePyQU<|}bP!cr)n?_{~0hKXDUQs+PM)*w4Rxo;?FPI$s#_?G3AknH+`zsPU z={42a#L!z^WPohO&&1Y)DDZ}r&iyzI!4V*8UD`3W+45UNrBXt^vjKB`Y4}d2e0l zuedcSEW2&*_sIf!mU%(UZz6KUG3BB_Q-@x%P47dL#vS?#&G}$jQ!?o;3W-Zif#{yj z@!B%YLTI!h+uWuc5Mlt;8<$=mr-ibbbk;xizV+=`4_ERfgo(P3={)0_M3tMW`GDrs zUbu|xN?EMd!M1-YQBy9Ki+LDawcT=#yHCaLNnze5nJi^(%O`o z*i!6i6cPx#O|J;RnStcDZgdleuy6O2m{>Tx3uvhNjAUuz@b2?Dye`CKpvrGvvXV~e z)*UMt-X?PKO9=7u4vMbebwm=ZC>bz}&Cj10$?3ypAKw##enlF9sD@`;E0(R(8?t*} z>2s^Wk9OO&u_wyQ{3f>aJpCYkbF>T72U+Nw^{)irc1KK6xab_W!(;4UMS?hv7_(l31`wP~kPIQ}YF zw7)W6dTaZZ-?U-GYk2x9aEP4{@tb$m1>WUZq@sYL{|^Q-;Qk1F=I1ac8r+kE)$!?Y zIOWmq97}b-2p=%_v5bEzs5gpuHTrJ!Hu2?6$Ly7GGaBB?GCG}2yOiuAg9};Yn_&C3CSJCioYREesK+-LAd zL`3ahqrgAjG32V<7*>9jJ7nG!q|=LL+b!2ym3TT8J8|K)RnEhqY+^M$$5qKjOk*CD zT}Ah__ua;z7bI1X()W^zTweyHGETxcHig^2y=jR!+r1nX3|+~c!BqMtJWnd{HsyMM z!JBUaA-u-}RdCbf?!1X*>TnpBg!8zy7QtddHT0eMzNH@206=NJhfv;Ahbmk?An5OvF=UstoRUjV?5Mxv z!~;suOMw+s@6t>kherJTd_YNWKcd2eBK)baqItf=Z4J3ePxtdnh6NdS1xps~9uaxF zivs!2lcSuaSWdbRDyq}Jeg(k&jy^sHi5FeYh4h6EYHHH7e0{d8f-D>YD%{JajeL16K(shLeo@uu(ZR6DhcX9l zMHOCYV^yGIhs25;ea11QnE1WCAKPbNQ9(S#w%N_uNd+OV9z^%Qd5y^t_6f^17)pt9 zemP?R||SU)^859de<4 zauDG+B**8Iup1Ha;#}yKQBjmrYI0ruusD?b%_qd<9%e-1YM9`U^U+I-72yeC$%2Lq z6D^?SrL?jZgPejUu5zB?upaIw1tMX#yu7-1v#KGpQpQZhtxoaH3L(9XE4@-QTo`4V z11?9+hVW-CFSUa3-^kKG#Sac*8j@xjRd8gw$M~^TWb<>HiPmP~?S?YLr|akqd&PLPTzxhJ)`EHg=wkLd&8^@8a4vnAG0@N++V<*2Yk2V!BJFrPG&79PNiIRrKaUZ zzxX*KF1`4^7o^(Pe`&wgT{V36o%OGro4h#_%mt$ zWN^h>pD92j)nRT5t8I|#8-6xg5pN=*KsWmN zA3CBfA4ndxw3U2mt7518eZAFV?I9BgzWHKpeNr%W4y~MM|2DVK_xdGH_~>)0K@;+P zL0UOqY$r$MhbLeMnvvCKki|XL3WHnmu(7VBA6(SSXnO4{=|@`G%DYdT+V$IJG?~F% z$ddMq_gDa7G`a28K!BDE4zQF)E6{sssh4$fa3M;aWHuPx;459^m{2(b`t2%1A}A=t zH>9ilY(^qfW(B%g(9UF)7*tI{%=3*-pBmsqaY&q~2xnop$*)A8 ziDGU|W7$cW+Bd%{>6FsNX(HPzBy(tWY9f?5sQ4U24yY$Td7uXqe85tUv$?xN_qtsK@=_q5 z0%BYw6AUGgHqJq0G(AT|g1b%o4lV8Kn;8`s$!$M~XsQ1k~*Lc%i%WVD6roxxY{u=x zxIX@1g%=zqw#9VO`6Z>W-C(sXKW$OwPVz>-$!SF7%O7<&YwK4sKLaGMxj>nD@WZM3 zf?U4#QgPuMPWKB7&;6MhB7Vb2D6M5GVMrqpERZ~i*7{6ml77d9q#!->}?^5h<|VCzhjI?D|k z=M^xIEWwSlY=!AmTfs~V5udRE(A{}voV&%f#%N*r#Tuc_HC%Sup5=^MaV}dPjndfnUQAi9S%PSG6g_g4l=vs0PlBE zgWn{-Zg2dAMzn!;@JRh=;=zdCHQvt?@YnmJmY;~f zwa1P%`t`E|ri?swh7h$r*8}P78vd`iGnkjeWDu9dLpcIpk>^iD3xc)t#HvLAnOZrd zqI>jYjB#NwL5t@tTLX$B7*nN+^VQZ?fS+^|D;I9fc8v5Pxd;>H*}@i?ri>1#Nxx6CGjs)%t(w$NN4%~82cZWtGp-7175LBKl^Zz zj9I`+X`47!w(XtbFXvc%_4ylMr7qK4P%&es#BV>J>?yH1pO$7`KC{!AZ|UqyTD-|u z3mCVX3rR&SWYnl*-f*))`<=y-gRb;ersamk*=NiKHW%4Z5xT`5%4;%zVIbcm|t*?9AM0ZPOR5-1{s? zV@bhJ-@k1)R$9)DkEnXb>g0UAXob7;^e23ZyHh{Ux_Dqi__LX-=1EQ3y2GL*tF2E! z%8!Fr@6_>|Idd{wDy8CTgFnAoq5OqI!DNnrlm)wJS!9PnY4dS$rG^UyNjj~Y4y?B1 zJzjf&lh?ga;=`#&j9nKTG8mo)_Ah?Av7n{RZn@*k{_K10o*6H=^@H*xzOPh1qbRY* zCF6y&)Rf8@bLL;+ZDCWfe_GHYoz#`la^XU|$ph1ecfJZP3*ILv^{cP#Kt}3EHd9`n zg$wPIyNVnXtNRNwIBaiKCOqflt@UUwvYmMsl0#d(bw4KO&Vm5`BrN8+M$HImAnFp2~ zJQ;pVvfymN8VdobzR7H2lI&7O?TxB#iib9|wAC$9?BbdyyYj230pA|sPc3bAiyK=7 z4u4pq^^)V8VukhNo(t1oC}01w=U3^3h1Kpp0gunl{2c3X(r$5`t>l|`^Y;4Oo_kK? zoAkc(SE_})LIsyLyVoCB@3$&0?q8+<#e&es9eX}jnP*4@FaPo=r~LaH8(rz<6JJVP z7S9XPIcj+2(yMFwPab`nvh+gF{@oXyoG+JZ8s5EUoT90;o@MSVIi@blxdMC#m8Vyk zK3m9X!BOq5p>LRec=s8P=fO!cc1>wJzN_X&^2Yr0ZV?VH#DbEdul4Jq(l0V?SalP0 ONR6kfpUXO@geCy`Kiz8p literal 0 HcmV?d00001 diff --git a/docs/assets/flight_controller/accton-godwit/ga1/outlook.png b/docs/assets/flight_controller/accton-godwit/ga1/outlook.png new file mode 100644 index 0000000000000000000000000000000000000000..32dc8f28ea6d0bb81314e457a1e8d1fa1f4d34d9 GIT binary patch literal 26577 zcmeF1WltOo*R2P4cXxLfC|2Cv-Jvj8ad$25u7kU~yW8NdMO&QWEu7qWa{k4;lKpM3 zYbE>JN_MoGiYyv3F){!EK$Dk~(f|OUfdBwh1|kdq0MN6&kOu$&NX~NlZU6uZ_J0Gl zv>W&r0DwkTQ__-_byfoWpZ-q(fa8IbCIA4abJtMO1T>mCgOezO#V|S5Y6qjr^)d^T z*gHqdvJ@sMy4!>yYiV|s?Hh*qz3xN)KK=8d(+w$BEz3;{UypWmXQl$JOPi}Lc49}C ze&h`}*16Oq-p;K%9Gso5Y!7=~7R62MB?xW)95Ww}(7p(mWz#y8%V|CC*viN)*$?Yk zJXsB?O8?b${=Gh1J|?K*_qVG*k8Tg)#U9a~k@t6+rq_Lig0?a@PxkS?e_d0Zl3xah zLpcBdN`SnSxR&?UrSZEe={jCNk6R(nNWXceG3o|9NmxABDHcg1l9btBT=`2vBZ7&B z@HecPF=eX>4-IMCpr+dDX$;%a%DQTW^f%e3J)y*W{ZsKMhm4Z~3bX8NV;Miu{)d3G zydD4qSsaO4ILRCukGUO_P&~E^!$T^|S5~VOR`LW>$@xdo9xh(AIOeHoA}P`-bA0u) zw6udBWN4ykgcA|hc;r`~Iu@HXa2ICb04N0o<_t}1RmY;U4nO_20~D_w`uUTgc`;a{ zXcz@X!CHI*YwF_^^|Dcj#IZAlkC_@%-4_EqO9Y@)8cs*Xqka~f(D6c5wldjlH>Q#& zQi?!UJwZnUD@NSu&wWIWhT5qu^CuhU&@D-d|3HjI`*!@?u)%7(;qsfaqb(seeJyeG? zjrs>KPyo93S3*o5);s{#o+Y(kA*2O;*Q83<1OF*!j<1Echm6zv&wASL704)g(`K`& z@yv+mu!=Lv$(3mtNZZDIA&Ll~05hIx$*`@9BaoAX_{bS>zGt+y+BWe~NE8dhX50 zu@3#-R-9&`TqjuD#(X`7sP-{Mt>{Z#(ou#%!sF@K<4O^s#4tGdjnQK}k2q&TS^b76 ziWtQhy**8>`@x*y1;?)Cgcjm`LPFipGr}!QB^r(Pu%m{SRIJ_8qm}*M_ zgx`WCzG&66gX723WzG?weeqm(lo1j0ak9m!{(CuodprQw%8z^Nm~TtGOrePZ#FYt_ zv0(l0h{_MK+0F}MtW4%3orgQ8=O!fM#z|fB43@|VC7Kkvz>a}m7!aE9 z;Z23Mg6b;h&C-+GGOOAcA}aGe~3D zFhT!@2vkV!Ve%i(QFo)E<_fRxeg?GZE#MDX_}iRuuG`d&6Li z{^|*YK5S=%kiyc2$(hVR!hfkr!fk|S`z~o{ExTJpjvb@!r2bvG*2MX1pUYz)4Vb(8 zqltjVEeyF0`x`7U48pb*cUXYCM!rHZlT%mLlvWbb7j*dPa=F}kIVxJCo$aVn>t$Y* z#Y86#!E_1Nepl%RC+qSrJ%^J=@41*hB>7XJev{@^wrVMHjQxVNh|dyg67R5cemXNS zT)2Qtpic@KcPrZt`VLU0s2%EO{PwWE(A%@MkN8cRcMh8?;P{PJiWLMOw=UV-EQzWo zQMy6_MGONaXmxRB-v|YqG)lNvhh5$2nU)gE&eOdLx5nh*D%(&$R+W$nJ&kP}8~DqA zuH)wP+W}6~aS>ro{8vb%AN^J$lsQGH9VU>V;7)ddeUy-&-MU%5O=PX8z2nk z{OehD?)vpv!W40*?!%kRD6zin7t+9Fa0nH|3TqRA#k{0vk3}ZSmN`;j zc#A{~Mt|WIX3tn#g3jlQhxt{vmyj8jL0@$sl`bR-vdsF}MjXt%z^=rTU6=C@l z_!4#s5=Nz5GV)-+J`1!7G;|HpA9D&a=P$1;uc8({9{lXZ@!b9~?zK3w?#K&x>JaLo zA*=LGLJX0)bfGp2G?5rXK>KZr!}E)Z>XL-t2{5d#(IzgM0P(wgh7{*` zIku4a!f!1mHPMH$E?FZr66z*Cv=tQKzh~2*`7eZTOM+i_cO}nL;UQLjlOcD{KJ&hv zCJ1xQU%%}$@#tE>`N0p^q)vTiU0=i)Op@X7480Y+%*#*46$kFTHzRCf(6*PCqw*u) zWo~i~@F$M`kPJq5(D$W7%t6Q522a$ygyaE0i`FFi%Y8Kv0PH#YEc!#q*^x7bu80VD z?cP}W48wZ5(gBRIm)#0u2W&N}%b>4yq0oX$No>hDH~|5Hln9 z*ErtRzQ4EZ0bqqsLhUL3u9~;y+|XM1!Bc&hGZrxOMAw1WGX6 z07oZ9hqcx06KnH@HHR+8aiyxB-){^0E*r5nG3H<_0)J-VO z33+l?F-^ve5?Fr=z|l=RO^t!T=i*!x6r!&jOVG1|7aaZ~x`$_Iy^KsP>{-?-Lv7!# z+((TAC6)by623mJzuMo%TTWRK{fbU;#1ON`L^PXFr|aZTEiE<#K#JjCuE#Y+Y?#orWuV- z01t+Ev?U?LJj%A(EU-Ykk4l6pn797B-M>euC^Z|DUEEO%Ux{%kXVF=BCySu)INhaF zw&?6S{|ugXM5*J?OXCZ-?QybQxW)}*0PGMU+s}<_=-625vMpOFV?s1(EX*M&@}Orw#c)=JgmEEk zX`%vqMb6Let_a-*sa)T=;$vPpbF5lp6To6Vz`_Od`5a z#6MeS2?!wBOe>BY6lmc0&3X4Vafr_wC>=o()D};>7v zA}6j&TfqD9$~nP#M+1UzF2Q{6U2T`Nx`Y&O!<&3{hdGpYiI-`;Y9L8LuvKP`@rJoF zrb2(z6%q;FmhdGf0tYO3@hgO%tOD)CYZ3&dOb=zg`iFS$?>B9xfFh$#{<`+5+>@$@ zxf`1#FNyF42MHT9o5J>g!t3T6g1{I7ui#tTuCJkF{XuC8qMA{B6yN%NNDY%x#X=*P zxqgL2dga+sBI!x}42v8{tV?lR;&amZnJ!3JUT#X0L)J^Ozdi$d=BL`&Ohd5hUM$_> z0@yh1HU zB+Oe7LZ5W^41DbF=f0EK;G#sN5}UXFDr;yN^|D&58MLq|?9kAhVE%zwK5Qn;Q`GM2 z5C9ov?5D!PhMI$43yKFpe}e;IcIb~MKt-LH>UV)@!9K1a3aHe?44`$K4E@HCX;w=-1C=l66-tiSw+=izzdhjDz zu7dlp=jTD$fg|K8k-0o==KaZwFVk-eK65I;<7VJ&qj?4d&g_!!`KNq^zH$zV_wMy* zw%mmQ$@#)(9CdfT%h2vP68W5#8yvD6}#)XGU*q6>gH+;temgwl(Q z6v(@1Jh2R;Mk^=H#9*7$K!?+p9AiEjK}S@GWVdt&UJ<*UHlbRF0^b&Aia}a2*+%d3 z(UIu)?|Xld3^W3QBGsXd=S(6?Awx^3OgYgDkvllsj<~c+zRkz=0OgSPUf1$;pbvS? zVai~NT$+NW6UO*ejvxTCd&4&Tbc<}X$913a?sh6nOo2ewi7#Cz?^C#Yx z6ar;dA$8KipJk*p1;b2>0yB9wIBl9S>gRKC1lSmD;`wVW$iw|kb{>6iw5&T^&$Eu=c;3L=g7go?17P&XP z?rAyt!B|`a`H!M#Mq6&iC*~oxlCPl3ZwkXm9x^i8y1d;oW%k&+gbpyozV$vS`RA=}9RArOFU|yFW%b)D~%-BE5r8EVKp}dR@CsX7gBC~0rX*Osd zj1Ts}i-*cxF^kZo?Z{ErEI|Qn(jws&!o^0MHG)&3ZSdJSV78-e?Ti{uTT0h?Fkvup zWBD|hYc#cqurzgi%AO7m+L0e>?n+SqD_#?J9`a}=TQESCxtj>8*fj}H9+F4}L?C@; zBR6Uc4S4Yspuei2a1Y05NNtm1*6^YgxBw{sVvcE7mYmfYsw#{A$K&g?B+g<%NUF&@ z9pUCRC@A(X1!?zItmwy*6PpzH$URRZtUZ+{BHKxfxrT6-(4RY%%$)0n5yvqnioG&S zCkOz2a{Iumnz*QPrhqit6ZYC4R#-atT9O@z@D-+lDEd7u^71!}C;7_fskp~rh)%xl ztE_cFFgiAmYWs~bIgENjook=EQA21aC;O;HJ;W${rMJ@(5IS&$8Cv)~hAhVaJD+y# zF^2qXl1PjsP7xI1V%(^^&rHLzd%KF$r-ttZERSoLCfe;POFk}SDeNVUybU-*(^-WF z%{MTNeP^D_Dp8Ve2UMWvUYo2PY%0onB00IWVpt2Az5d`BLhV$;jvUi$+ID2Uc{g-v zXqHT`uFlk6%Cm(b-g6k(2ZX^(n$^=9QXr80FR+f zb__yO4wp;K3HLP~p%!Z)DY~EDDC`LC*aFc+wAaTgu#s*LE@|OL(9NqqTQRz-gqSgM zu*MI~uXgUK^BVAAE~dL>bRtxIEIwK{mk(eJT_d6?M;X*J7LUyboRle|tAlBZnoSU1 zN)S*0Mtr2JAQAPp6uXAt)0C`8_e{&*hB>Oa!Ag)kV}xqJhDr6JKQ?MNdi00QKNDTD z?ox2!=w51?k5nXmZ}7LHe7{5!;e4;U1wsY=9!%yS%O|IO_tsF8T?Y$*ptFPi79I?x zLgwfnXq4>12k8{IET?jwDw?2ToMuhlZV>|p{OYKkRVACF$%BB#YtLjPiRSVE#KdPr zRApGGSRF##=ANB<=j9^w?-1i+@Q!jlF`7@k@^>6aB>Pm|L}u)YkrPz>>rzf%tQZtZ zw-r)#YvYFMp`LYxU8|21TY63%Yp33@X2k=V8r0exyNNGzOHyG#9puNqcXNsyX9P;x zr#5xGhwX+B<~2F4v*%v&+<~)sD4N(4B~QCTsK-n;dXdXH|oTEpU@*A_(yf-p6lv) ztS;Fq2r7LtrPLgP$yvlbm<0t|afOddgefbx=%a-1Mnq*2Lp^}xwJ_x^GR(Uu$ps@Ldz@F>XiM$IBJiNn@g-2FOC*|p-N!j;0 zN#lHnl3D-=dQ~-PS8a?U^RdqG8e%xN$Jw)RC+eAQ7KJR}Uitq7&01THGp(@8pK~9J zEC>9^S*9XZ9qV4dlaPgvrxsY9AK$F5_q>Q? z^L>Ycy}p>TqL&q&M^iERbJT4jLPeA#RG9QQ5Q{~K)#|5t#% zM-LVc38y!ti?h~Yn4QyJsV4sFHTHTrktc|F?;XDM)?4#=?yn+*7*8;>tSSxseLoKI zvzp~>!qF>Fsj_!I;pMbnQllqj>lbjLkSQwmk_C%TEfu!N;0wc5M4@~y zLmv$4(dlDWUX*7A3f$=iJ{Wt{FAEFO1-M;TB2`yVWdLy`$=H1?_*5{~X+u#ukY;Dj z3FT+^>_5hbeXquzr7VjyqmJhgmlG*BQ24+_j)DC+yc1qG1W|O{JP96T{rhi{YC^ns z$M3mTnx8p&tcrnzZ)+d-q9y5*Q$c?h?O#i2Hfvro#}XU*#R+QM z3~0qi&>(y2Xw8GM3%j_#`+P6RcL>iV39_LMx;d#6?QBJP4&w@mvr_HdLC^O{Z z%ai8Li3W^%F!?e|K!tWHV%2nN;Z=wcgR|8fc^SrJ$}iimfIL6(1+uiF+K30-eKS*p z0ReP6MRTOEZ`?B$4o?Y#QycOt2Cc6p+Yv{5d5yLb5a4r6#P%o(PEYmX&k?D8W1Tah z6duerQ@E2K!=`bM$JwqNE8=KBfnt`(`IF0o<8u$_6}tW2f$HSBp1b58;ex0F(^9BS zRB;wnOgE%Tjo0*kAbXDfG8BO05ylOR9EC2f}MW_NUHUh|j|#_|jMgsJ(^_)I?W znOD!Hqga&I`7nY{Ymme?3W&r;3RAYvM3zV44k7}}?EcKJ<`IWrk>vKB3KL{B*sOB$ zBep?~J6byQDvAz&*ns`|7t0!{(!|tb!V}@p7z^cX0N%!}W-G`25D5s#Rqa5RQI!TV*qhgHIm-x&l%g8bGTGz^gbKI$$L&{+F4rOW z+J`{`U$^#;uF-V5&l8(?r1?NK`!0@r3|`Y^bW(Uv0mhjoeJ!r2i@;OGuTl61m>xV+|FW+aPGjzH8e-U?M;IhBNcxBU7Akj=W>Rb2T9iYgz>(hsQ2pm1v9<` z!XdmXd|zynCSN=|yYT6nna^Q1js=bwO>xFW_an5kbI9z%o0EUfHZ zm|I$@z!4`?$geApW30^&oFKo9wa6;)3Km5p1xrws2ai*59ey3^eR47J?C0`PIQ~P{ zr_GyVE2lr;(T5J%v@1rsfphKd5w`&+2bS83UAuC>(g|BCS-3SfSx|v)ou|Q5F*V}9 zC7rS}>YizybH}#m%BpLghOFq&=TNR@%5qmC<1`vXTV58*K8FeVul4nKefy(C9=<52 z9vd3!Nd6pfJ}~Vy1ZC|v*-%MwXP}yS%R;O24|2kyHC8Ocp>biAylpQ$jh@WL!{`v( zo0ke&DTJsz6AhQ!+Tm5mYmcfHpw;}TNmi(XGR&n{2DZ;9H9VCpW-HZTVO5%LihGR; znb@Y`l??yPInn=8aX%6cme1X0qqfVvQ@c5|iFH!JutrY_2As`v;Tqf0vmFFuYxAD| z#aNUygr1Ry!wjCce}^&o%0MZ7WkHpjsHatQXBr%df5Rt!zGg^zCNuun^5LT0S1?MjzW0yiDQ+-M+nf39M$9N-(3=s_xoM1Il_OG zE*xv(v3v+?!r#CWvnGlebn4L|vmOdwNNoX!|G2tsz7Pt8Nft%>J8wm4Kf*^w8) z!wMwi$&q9RPf}&O#4v)hQI3*7TvdfFMOZ|Wjd6_A>Z%vbzPqcsNcnXNNlc^^H{3OC zCfhgGK`MJaWNb3dwRL0!FTE70M}xTg4=7h6ub9|!Es+2JFFC5XxJc!g~EI^$S4ZZfRVq2j6;Xh z@26vP8lIH$kfam#1z$`Icy6+FbkMmoanT)$2u5M!zhb7$Lk(DBAQub^EArf1aQhdX zBfks`G)c~|`puEo&VAIk=E@p_yG%3%=51d^Mz-p})nB@;o0th^G-OwU(CB^|j=}Vo zH06jnV#DMmBlA7LY{{?fN-s*`hH@6PwsKHt5APqCz@5-}jDru_)pPbAYy|Cp!}(h2 z6|{+&I2^SH?4r$DiHLE0dOGTHW5a!un}dnCw~^3P61UmVV-2VfhET#OEM}1+f&s+l zAK$S<+a4>Sx41|3n~`K5*nvJ&To2a#<__(h0a1`q<(CaL#BcKbDp!p+Dd0f7#PoJA zza?7oxN+{3Y3Mbo?+n1APA_I~k-C$hYtSvr;T0lK>d()VsI?=!YaX^-{Uuns{qjY7 zWBI_AH~l}XwOw*(a+y`z9Kpdb^5&)9I_3EgGuz+PQnhPR?VRy-%l|s@L3(yO*Z82l z;Z~wBdZe4qo^a)fbj_SuY~T_7YCu|P5FrW>%>KwK2%$B~{hQqAf0#p|?E$mX(<_rB z4|xgJ)BW;=!jTb+0x?b?0)qge_}iw&oR#r(E;GPAf=vcYmEQ-K(UToXg`BkBI)@Ex zS2NdJoa`nVk%7tSUTHZO$EkSax%l_-#F6Rwz2JRf?ghp3VlASzZ1d-SCqYQ$M6US$ zqi=oWm+iBLp;$M&+$tDT4)!+vm=hV>+uH9MspGkHAVO3>>&jr%IL0BakaG4%R(c2^ zz#1yq=bhtRtGXxi-&!3I^yd7*+zUS+4&FSd*gU0^TtDxc(M>q@TA1lzhfln@zZaJ0 z=TZ1OHJM{0D&I9vod2P;nVL2$B@KUMx*fvfs_Fr*lK&cu1$2?2V#;yOG3`ibj$vFg zu$QGttQ&-~&J{5XB?wiG#8Xy+qFczlqBl4{&>=K!g|&(CeH#lQCF#caenm!Gk#?ce z=nml|!NT3aKJu?UNzbAZ6neeaIYGWla}di(IU)<+9H0I=->1y7&YR-}+T)L5|Ls#D zl=Gk-E&2_O;itZP2)V@*vLbwZFzSPFHSH{V!!-s80S|`nL6*2?qHhKjIC`hI7gYR8 zSZp61{;#n6c@nNv3)`%W#JlZ7(Dy!e;h~oZZT>r_9Cg8!@O<_ze-cf(ckDLpeO}5C zIol^I0r2RODqJHbiHy8K>6rPIO2Jw&_z_$s{WbOrEYL+}Xiivn<8%AI>=K*ZEAh1@Q`$t5>NWX?b9X#Dv=F)?E&)C4w5jO)Y|f;SyQ4~Y@jbie z9|IJX|9bjh6%f!OmagK>#HB^M5T%r83(fwAOcukj!Ii;O&fBKmXx7`|6%^t#{0@N0 zDqTIIB$+(a>@6EZ;)q?}LyIT-$Vx{e#?uGy8U5L1)aFJKCLuMg3v;olZm=Q30!Cy< z%pR3w7J6ogUKP!5H~>1=hxejCAQl0;-?S)YRqo)UDK9AqZ*!XU!{w8K0w61_5VT}F zs`&hac(v?VGIJ597-^RSWUq4HEjGj{&=FM&=;*+eS>xUP_H1BpbK&-M5a~@7rD#pr zgH~wo5q^#cNcVBPY$8z`u1@XnC=e+(<2AcA5iL$*V>XK86`HzuGM_eW;|4_pfAaf* z-Y1Wx!G_9`)iq6jGKSvspm*=16d8dtTN1V?i4HFA{TgOqSH4SyIf;faWzD9G+HJjd=5_<Qvlk0q^H?} zf4S=QGNt^VdAh7fy0N=ukDUK>q z*6da#7k+y(YM*qToZd#YxdjJL6&0MBebq2wU)>tVMNiaJ!m1EQE~$!9hMgvQ)8+Bc7o3u*mj(sGhoXQP?!dQX2>U^3zZ8g=X~bYCZ^)f>y=KH z4U<&=J6?5GH46<)Uu#i9%>gMc6L0z-0=izK`x>b4ieX@>pDp)g;as5y45aU9Jz`44 znIO0}J{3xOTNz}$4CNY9VN`Iuu*zkRtguR{2M-#bXA{;lQL`du_v`^5$~%5@?ym_&A+1LB&gF%;nes*NwuO`-QjV;yDmW^ zqGg*JB#3Ed)&9gmBsYaC!TnJXybjTF^>}1m)+bKFRPODwUBNQEl4)2~k$*rHfQfe^ z<6=b5q2}!e@g?rtO!d4mg_U>vW>krnc&?i4^LHcU{!(AN#mA=HNwBZMeusPKHjk?w6uDB>1r&u?80 zfc$d@S4xqgtRWV3_<>i)A}2NN@WkNoUKiK(@gtRAAnrtS=%~>`6aR-gc=_P*%lC*7 z0VJ|--FhA?HoxG|GR8d)=nT%6b+s2XV#<)9EE8QRM}H1@b14`AlAF*LMD^g@*`bJW zW=0Ryap%0jTx>$gSx6Lg$EZXcI_h5)^}&bA3$mQNF3&8)nSD&Z(jFz?z0%1gLQl&M zhg@lqUG5(gOwNZ=&$guQQ+b&dIdf-Xe(6s`#{+pK{pzJd@*-}yp%I-=+!Nf{;Cqpo zA!?uN8&a(}kmv^KKRyXtLOklF{|wwfO5HiW8B1a`O3HVYIi)W+AN?2Boi6h(5l%1R z5z$>fh39VW1r8-;Tt9y~&1eQJnhw8E7KaIyVG3aW4c+O3fKtJdg}WWUqv!L$2?|XaJIqVLUjx z&7tw!5ZR|}Q447HuPl5d!Q z=_|m-Gg_>Ez#6ZE?xIZ+L$wQU}&!dj(jugTRRK6;O{1i*@hz8TEIe-uQT)sqKrsHwp=n@xI@L!hIshi+lpe zB|2&=!PfTRqJv_FeZw9GVqh^I;_POa%%VwCL^?bSdBfB}hBdp7(D6a2G?9M~njp(f z2bz>$=^BN+f`(#_<0eygzF)f;)ayq^ffXd`Y1URVmF%<3u<@gwt(_NvcxAs#=!a|w zlHbE)wtDna(t#|QajukHG?Dr@k(i4umwirV93a2FU7T^rLp_>IFWHj0zmS8uD_dO=50ATG?yK(45gasPbGu=F!|s%b!kN0E zFUC5@TN^(X$ag)ZCr`z_WV2vxn>g6xpJven;D0gX5He6XwKx2GOhqNOwL_Fk{7k7B z`M2ja`6W@x)yb`E^{424eA$4GYtWpV(Iy&*%Jk*<9)l_s0oB*=pRNQr(gJ z-G+quEiyR+3@V50UQ#EB2U9x9c99NG`^I-CAi4UfturbINdgNu&}BUEeM4Nc+%Aa* zn&aDekaUvo&$Uol^tg5VT8H~U-anE-W??c8XvFc!)cD`t@+S^vm5#H2muLdl{f@6| zQY~#etA@^RyNXi2iFU5cqS!Z{t%%st$0@MS@>bA#qgJaQnxNZ?{8xE52aV#d`m9%k zsDE)6WsJui1GrwbSnKN+fVA3zp#DoY)r|vN?p*%&^UoFIO}CXvBHfPe)gLl$8{{Nm zSNfKg4ya?cYbdO3!R7?m&6*|*DAHH#esn0>K3k#FE9)akap@!C39!l#TfQWfxOA|30(K2=ut>hpqJ%AUiV}6{Kf#lU&62Bz&>Uz1n&Q(Fgi{QV^P& zlH61KqY6bhI4(-KUSek5Gi?TzG}>s3#{)i#P_mip+5?*ZR>BUPnAQxXC?@mFNj zkXdg+L;F zPy7ZoTJEIYecnrg{-v`xY0_qHZeZS^m{aaepa-JHE4auH2Ai)uxPjELgFVWTW&}1= zAMoQ3ULWp5S&fD(FfBuq*Q_V3XRBC2DuTwYB@9;N05@!P>n;B6bsN`GsSP3x9N8NK zwh(m!)Jrn)IVKqV{%q1W`~B9b;7I>7w%~!M$R*nA9CtM_bIka!vta{g<@Q;1^aR=` zSvEJAOBkp(alaW1Y`sy#qi8|cx*4C|pMGMyU(J6Insij`_nb5)#xR`Oe4(j>{;`IQ zJiF)l+O!7WP1QTT+3sL?y@!zS5QY7ATz)q%kFD;DRHb+Dls`ZNKvk2Hq>23 z!$jUG@n3P+OXL24jmc@sU$cndkQ?eX^ku!W|5h)Xsf?8a^!TP(4^TmW?K24lst(>E zk#jnb9y(Phr^5^}%VfK(Rd_L`R16);BzS3@aO)$A<9Y1VHuV>+c&6eL8+8pJ*VPvJ zctWEiWTS*QS1L6wb{eQVau;f7eDpoAKcy*)ye$ATB5`cfmCnqu@QH0e0nvYLBd%r z{io`wi5K=FwdFG+hKa+pIzUHJt|cDDqD6Z{Ar(PlU+aDqy$=LQYy;x+FUB$qiB&Y* zKuZR_zO1EhAR@Wk9(L_5^xw*=D?MfI=@ACF^Ue+NTW~BfqZvy=sKkf9D5EP(DAj#Z zT|Uy36Rtrjr=fNTtOCxhj5{zQjzw|nky9~srwkhC(8*SsH#_zO%D{R=*kG67Kj~32 zi=$S${=)n4AXff~f)gc>;9S6iwIe~x_eH7Y)-D3dAwY?QKV9XWnQwee68`h z?P5yU?&h1V)oRPNwe-8-Xo^%Bh+t_|vIq5#5wbu~ob6@B0|GrqspvxAwImHGa|nU{ zI1`tA!-XC^+*AES4>dW4i7V*+T3X+s$hk0;be@r8;osTEKKLP|jarLR*Yz*8l3OLj zJm%)xC%+C^S+ENK2^U4JqMaSmcekZvk+7$fIRx7+iSHIi+fB3G?jNWlkFx?qieLrV zsY2+#|AhItlDUpZF7vFEL5@ovqmKbqdQ{H9T>jNiY5g%IyM15QwtiSl8G%cgn+Cx| zH3+UO)UO2Z0N^Z(qW@ZTW%F0hgxg^c$mv>3-X9O`{(V$eyi!ARMy=x$S3!{~kr*22 zrck(%-R-LfBJrs-GNxe3@Zf?Zl*??kg7LXgtfb&X2KfURkqDIh2g#IQknWG6SU4rN zo9&K0dgiKR>UPVYp8JQ2{GXd*Z%q34kPfWeVi2h>p-j9iInNix1D0h>yTlLg;{8Q* zR>-efV3LHL00QHO18G4sFgjM@?cY{|!|8Ky;vdOPSaIoYRGiRgoZcl{iRN=q&82X> z9rsIWTBwjMBFeBn#h-XkLT#g9jKU8X1?jwl!zCspT%wa7NaLaFoSl;Wt3$5T;_W!m ztFVfj$QYsmGTN@+8`vr5{aqh1`9=$QK0`uH4`7uIfIPe?ppI zeuVynkqUt3!A-j)uQh)$T5Eh?rMD@dM(R*kOt`>rU4DgS3;KBN^8^E;QO={P3#N@#b}q}^G?;X{Ki8P@mFMe)T*Vld8}o>NluopGCpyHddZ(r`O}XVyx11G*gH zUzwCh>G(8f@D*hV3K~!}Pp-4b)5_&I6)a*|FPz8sOu-T`^o9(5#m{{^)#ZPo;qj$tnzt2r>cv5_;ErDanSJmT?t z+pt&`G`km=6F5q79T(ptA#?HiKl!*zPH1C9#8gJ2iUc-q!`sXwsdL;hiX_Iczt!V?ikUV(rwju!2UX0q#Z&6XSUdYy+Lw6+URSL8@4 z8XAC-jDGNB*%mX=d+?!#v6(|jjb|av*l<%|tkX-?3+MILAHDXu}!d&TyNbaiV^IyOn2|Qf!DH_YBCM z^ZSvPfnO74e+{%*~nV`B|U zJX6Aeh?Hn2b1+(4VU^LCpE_CR9BxYAk5<}b@n?-o08V{7Ak0cp@fItTqw3v7@bslh zt|2zF(>_pKTnJ{>Z5fETE_8<(3%}dPClxO;OL?`nfNBB>ua?PNmlJc*z?*>$bYic zdRx&O0EV9EX}eB+=_)ld{hq$8SqoXvv|W3OWlPJ`21!$L3^rC@^bWRsjljOIy-%{e z4P%u4Srec8_)OL)-RWG1FQe}nFRs96U|cDO7J+v(x)%<+Ze-Ur+iAT%g&;Ix2%fuS z4aC4k%|T5-^-@}-Grqk@v@1sP85h-;nMKq9eiY>#IF~qf=3xPUAg}IPhnKugZGvFf z?KAr1Q;F6U#{6)O>IFQP0OY?suq?N}Qn5RtX_Tlytul9(`egCwf3EBc)(3Y4@qrvG2pl!ezX8 zpOY8016O1EkvPp>G88=f{|luhTH3ng=eekm3kdjCjSxlSn;muKjs^PNRi(Szi$qx* zl52gTu7Aw~^_Yj2bQ%?p!E!|eS`$s+lPPmJp zAkYYQWQ=N-OB6B^a^b2*n^@6=>oky4w{gg1Ne`ne0Wql|xDHl1oB53egjtbEj1q0Y zwZJv^P}lDM;rx<3i#FxeAs3P&o_k@S5$wo}xt=+R5eP4u;8itXQbps3N&7N{x&~ec z2o`Yw03ZNKL_t&rI)tj+bsv%!8L+!YHS>?!aT7HBaz45&As{p4$+DNEdRelYXq2E> z8_j5M0;munBwKa$`7cR0`OiB`J`K=@H@UIqw?NQ{c4RVN&n%jd6T34O4ume`HqQQ` zTCmiTl+_X_fk8(KD>MBlOUKt3$m@$!8x3 z^xE&lwn=LuYBRmg1F}bJ&YK_Liml0qC6yKU1i>#FG=iy3WYVz6SR^`|}6+Bw@c zm<>+8t)ghqWVoa?FuR~WkHUL#zBy3oLui@^Jo z2~fIKncGdB4roMIeuV)rT$Pt$HOKAu+KgQ-G>wfwNq`=4Xc%$sT zEk`6RM?5cXlQ7yeOb;}I9hq#`GiUR-Mt-j25{1+{P8rYe zs2aIeqFiizb{;|8p&y+Zt%6!Y$&?n~R@OD|4O?#cMp1EGCpvA=h^98tz4xMR~QKdW6x>8z)6fp_&k$#quDVeg(sD-9XkzThnxCCay5Hbfr;EuUZ z6*MQFS&#&v7Nysi`)w;(wlgSzc)J5{pxVd#oBP944%9s_tT#(mZN7LgdCZv$pnHVn4$bU_%^-zHwWD{Aem^rCPgbV zYhKAzteXi*wK*rbX>zW7u5ne8oaQj@OSWirPl&ajI%q@}O^msoIor|a2q>CBNSY}}sZH@k6Das_e6T)jOyG@> zM-tz5vfwrpge*^z=qO9-1T?AqMI>hsy5@JUJ*AfBg2sT?b)&SFy52x|Gi}GofhJe= zx1kS(`>^bulA;={x-YzF0tJUf^nn5q9_LIfOQ1YaKD^>@?tgoeDS!yLn_n_j`FWYq znDlVQGBfN!*NGOoqNO>F+4>u({b6d;X${T!b8j z?`G762H0Z#tf4A~n4nr>n>AivZLuCHfJmJHA*qd7_^stzy~>i2=6Pn_hZ6-&R!0Vz z#{8=O?(8vHqxIHo9hOQ}xMoK9EjQ226Kh0Nlm)7OmQRIL<{RYzDpLUAwY?9P5xR2Jjaoc@%a@gqqx`Snni`#=F)*3A z)n{VK#>fc}-i?FC9B!JtjuF_FEc?qIyXpD7$dd;RKiH9^ExA}g64G`3tasMHu0!+~ z*m_Kuiz=GP4Vsh#8eah6btcv3=0;A9PE<|!H9e#C`EJ*LV^|97C_b!0Zt!M>}% z7bNhLf$Hw?4j%Jl-vemoy{Z|vcm)+rqj*yxBIk-~-8ZJl1(Z5^4 z_qph~HSRiGJjz?Lo%v!v(}@G9pJtewAx(lk_#q6rSQlo2#s@o8ndl5_=}`{44m zl*!peQPC4ZidFy4{h8! zwzT`~yYIg5^FD8FGGH;Z4eG6pZpBL%*G*ja-z_cwcZ((oygIK~u-b&jAB<)J za+m)&^WMMBmyICuPa9|wm!?E}#sDVjtL&|JWiKibJJ*>L|9wwf89?Jq(8$eBp!q2w z(MN20HiMZQdLPOsiRzSk)z>0U@+m-oTCH)x`2Guoj-Av&7V^ka0U4XzZ6wt;cyRyT zU1FYY&?Kae=)T0?kpl|$y-k75xGm_!NfYTo<4#azPWtD0H}jL5m?60?j{9Es>yEnSuxM45Ql%6^y}2Q)FVa2vC;0W)6P3Mrj-(8M2PAg9JL z!ey~hME*5hjvJ6HdwHTm-pm9Vdx8+-erq>j4?1_Dnq)60nm_A%T_+`=1^^YTs(3s) zEPOk4(wS`Ba{0oXrlDGX!O6R4^6d%|pk$9vy9KRQ(*SHU%NTs>Qwf^bgN&SGy@mke zMYw7i&SWUn7}J~i)F3iTDa9XX@+TS(rD3KWkR@IP*?N z!|MplZ1rQU?~a#6!&;*!+r_~9FF++pp9XTC)U{USgUL&sV(FRWe3V0gs2!1CIwZX$ z`QHEmVj0h+6q+7rPac;VPwRN6&>BTYjf!kNG#FOUhz>Hk)b%Be>G-*cJ&vOj8b;g2 zI9i{I^!`>ADC`+Wun$i}dNBPQwiZ3d#34W+(r6rP^p*b&)g~e=WrOXQ*4JVVn!*GbKG2Aq{vd&xzH%u9fOR{JuA?z6=-;L_@nq|>lGviiG=@Ql z%@HPq(mtIg^~xM?&o!Cn+@}yTbISVey~(CD;{*gm!GK`fY*y=r3I&u-XgV8%k>r1c zFZ|U+b$s=z(;%s0fZV;0tiPMI0o|~HMigGq0?Kpjl}lCla3BS;^bfs^gD_xaP z`{w*Ry`=-xo^noY*5K$1RZ2VkF3qFndqWW1>+jkGJL%C^o@*oPg0%!&uSjUe>labi z(C3e`XM@Yq5j=N%fKY|cKtKUv!s*Rb;zuW3vPB}w1r)ZWq1prl=YvAiL~fBjA@!8G z6U%Rby(?Yw_x5#nuyUu|ijR3)EzoL)Nc6)bgXReJ+z!oUtkrk*^S`J9k zg}Y`RPtRnximR`Xw6G$*sMRE&c9~OV0-d(mm~UCT2Hy_U`%5^uMxwO|bdRte58YX| z(e$yBON>Z_x=zt zqN3UaR?Y7TO#}6h*Tk-ShDuZA5M8veSgII5wfo$#3aYh=>R0spuneR~$XnLI5M0qw z2=)|VuUHnw2QQr)m-3gny(Tc=$Xqkka#VM|$qzuf-ncEb7);h3hZShz-dxzX5M;v) zDL@2k6P%84#B*$eF-^hRN|iIX{o@)|SBn5&es|A4Vo^W6y6CT=p>|P1dKfes1jBJf zQ%7t(UDrnEnT4~T+;CTta%JNOES`TTHLW8gQHXoEN+3<3>HEJJq#md~N+bBzH`PNy z7;A=e0n)fN?4*+e7nbQw8lj@eaBYGe+@({ws)IvnVB`foDL|2`XtKOC4>kRefC{uT z@YGL7TQfeP8cq&;^brVy29hBGjVQjtR)jl7tOdFB^T^uO%uJel0&*J*RHNf+6KEyISq-n|V$abT+4Mx&hX6Oc zqn0(gGh2R~M%zOs?Q;bAe^LUV0ic~{87XO;^q`3&hRXN1mS^$b zT0L9fSm0TBQ5H==8b7d3dN~*(9Kw_*vN2<&Z%O(w<~mJ(%&;tiV&?p zHzUUq`5sOqS|{G^KT^T4UC{?2lKZsOd%RZ+fd;p1K2otmFiyxUEKM^efK(hzx5ejK zxQ>Y$8GPG|wYI0V;DeN2?%B^LfEkm`BP3_=&2LvRdk3x8Dw-s{va{6acd$XtjDDk?zWy1F|MJ&^iz);i6ICEI!#O}O z`pI8BBGxXH6I3%fwFwpL({9~nv(`H|X^qGBQgDOBc4@Uj;>O$Z=5!O11{LXM*!ps7}s*L5$YZ1`! zV`6;1ml-NlB!RbhZbJISRZEtpa?~8+Jr8Ypu^xt*O=@Km)?6sg=8dg_d#D<;Xp;DH z2F#HoQoxxJjnxS^cYFg^6!hfV>_Flx6$*kzD^+6W3gJzR%b}xeW*t9N(~_jAB$=N~ z64?r>WQ1YHPAs1t0BwZ^qVnA~!V8Mnlh0rforO`@Kt3}SQAbKJ@5AWYM7LK$`3f2k zgQjAt2@kF=l&Uy3o|sa{5B+_LM{gJ7rKti3d==v;Gsj!dF3h+%V{80s9x2=K&x;8$ zgDg&=weWINc{S7pNSGTx`G(bR%C+g|$ooK(Hw-SwoXx~$)A7@)TYO0t;-#qqs?o1D zfp$J>By74Kt!8rdj5O;f>FIIz=Sni!qzcg=eQ2z9sWKifsLP7;o+!+Z6y06x&X zkR(9UK>-xAKS=sg9 z&RukN8=C;(n5l@?NhAvTwp@ur<^v5a9US45o2)A{n~q=MdNEm=DsVK10ExNc`uReA zf+nT7I3vD*)TXk!ou3FTm(0@dtRsDd0AVi*q4##Ott3yYYa<2?Z6yd5UMQV0K$S_y zPirGBUYaU&G{+9LCc10p3>o47e$I1cYTH;+_sY1LqHT8a1?`IOAORw(j`Y?!GoeKp zYXQQb@%D)UU7K_xs9u+1q^W!#$3Kc!rii)X+7t8g+`rtji)1vU>_w9i{O7qdQ&}TE z-asUt7&!{OeOH_Xut787fd-KCdG0FUxl99|ErjNyYXqdJJi}$*@;+*$<%$FSwZe|} zXCTJyu?Y~eFSHm8S6D2^LF;fsAhB{}E%@PPeqwU(Z-%%%F;SVi4`z(`=pEcqI^!z#j zv2C+?L#G^6T-r^4BxI_=sT!+JvO=}*xB+!i-Hi|+glq1#`{WG4B^dDkv3G6FZ5vm3 z0qkP207QT{k>W+ROxl!bDUvLWtVEV<`C8kOJ$1)*V#jS=r;{{o+DzTLt{*aP(WdO z&)#MJ_!_9!Mf{0kJ5h~f(eb$n{vLP3@A~7PKJ|X^9|Inp%*?6FurXJWmMQ>HRu$w( zUW&^c6P+*s{GS8EMvEkdQwy&4%Q16Y3G24GvF8`nU4K=STGut>iSQmraE8-EZJ4$kly-(;$Et zW<>lKNQdER>^9h9I`3Z4xLR^>@b;abAq~zQcB7}Q86^q+8{ra zn5Qj=wLKygEn_*?AjR(MC}^a}xus960AeU=6P^IlM&!z3t^Ax-)1vuj3~2I|-_gQl zIii?F=d_%+vC{z(Sc-B(DYfbv z90LBX=@{Yr)wp~*rb}_IiXhX~8;e+){gh?wul@r9h>gY7bs^Gy=zAvjxe5?*olOp- zbF<`tu!*+Rqu+(-&cQ4xJYYrFSP+E+%>V(!#KsK7Mo4%)(Yg1Ia*u4E+K>onT#pXH z*Brx1{jj};@Pjv3vE3bLM+u51P(|gFCV8FB&b%Ze2TAOAmgCSEf_3N0dx)Si{Rcgu zc`!u+h+#(Xnq&EN-BTr&=K~jFpaGz}vqAy4hB0j1BATM9stD;G_`1>8kAkF0DOqRZ z*fgtbhL5@xOCHv~_l7B(R6|V6GU)-$(_6TY6J`Ph5JOTMki`2~#{pWB%#MQw+e=Kv z08pXvO*l-+eSTGoQCmkjS`w%oADC;Mc1{_)2Q)M1=UHKB=RI4S zYl?XhAQOPW)J8xwVK-pE7I4h|I_ToXTx}A7nOUBW6T0 z34niP(SB`O52x{xUD$na;jb&XDk(nDLAgMLsLcT8QAKKE3%K=F=cBf1=fLG!K99TW z;#2nZQL)MWdzAytUgFrK#F#|zr z6BswqN`1-KQx4y5YQg#&G!JS-vSOSylXojvS-Zz-TGV8K675& zAWOtdgZM%r_xQlxEQS7{nIZwikmff>ZCGiDM9?fWkhfsr(Qq3@AG_Idye~=pXmveQ4-fUE-mk1h?nc0U@n_yQ3I_hN50J0Fg zP|x`445y_8Ei| zK{I^G_^Q?X5dj3>VTs@xVM%r;!hkzZL~I=`TYyOIHS^RoBJLY zO_Kvma4e!)eC73*3m(9o#r}?-S{HgilaZNJ25GQ7&BBw!lZJn<{-&2r9WG$&P2;*M z;!hlylg~jSXoH%n+JIR#d4=EgB~HxBLb9b(UDtuQA>p-Ti!vK2sEvvmMMWP7nys5$ zGHugxPMTL$xL6qM*BG+;N1D1ObCxFQ`7-yt^|11>FaBT(BIh0|LHDrC$jp!$^5>5awt?m{VLi)$YeJrk;)T=6BDl!|Ysn z)*_)Ts%c(%SauG0OWIfw0Zj@YT^a#|Dz(okOT{WOU=yNE`W%roq)pM6mbG=kJ74VfVqT5GWU$^W)r7QhvU zm_RMOSn1RH>43X8b|e4G@H)-}5Jw&S39yW>Z2-5eVT*cVT(lIeuskd)G8|}%5V_?szLCPs^Us&ZovQ$q98U zVq>>VZ6u60H`Fz*ZT1%c+}orNjDqVa*Z>)sIiBH@TbHhcm7?GpQ}@deAF`jXl;+g; z))j}G21i!9|Fvd0XN>6>PJe8lhdphx-CFwOA+7`-;aIDnENSw%s108+Kx>*zDXd3m zj0#sA-k|TM1&#Rk-BDL12Vh`d1JJ4@w#{}>p(C$F_I5E=rYIxac9B5<00fXpL_t(D z$1noI8|%Q^Xn2u@2tBA$kUbtRXewpnG_FGZv2^a9?+6=ylH}a9T*$GvnU;DMu(fVZ^ziYE`EarDm zT212m4Kr%v_lp}lXsV6vIb3@wAt2s1Taz;Z#P@D~^HLOL&otO}4-(PF2pU|2c|4=+ z|G`78o}z7bW@djM!(R%%&MrZcCz|jQ(Z&iI6NB9ScGxz%KH+V%CyCm)YZK7UKs2Gw zjvF-2+_lbBwauOYYU8g6Uku4GUHySy4|uGgnZCB!6GUzJ@Lv#FAY%p1OlK73N*~eKa1>$Wz`n`{a+n zFA|F^P--)l>&f=X%oMlHKKaAn*=mnyVjL&U4{ipx4c|7KOjFzJiJ&%-4IL3pR7MXP z-LHAp+csOxT40iEc~X%ZJ!p_mX0o=~Cx6IEqKVOS8l%G`7;em9+S_JNz#Ww! znix4~bl6t_k;M#7ruof97O4Jnb=07d+-XJIW@j;j6G3gFq6zZvv!_N38hsbaS=;Q% zqc&0yS*Szx|LvX4PTN2fg~yYb%#VW|Dg`0}s~~72q^d#`@v~~BbP-q}V8arz1tB3e zNbN(g;dQaof?~&G&!pXS=A1`}zsxVV_gY@e;okJXy$F!*)QiJhU5 z&&2=)uFdww+PwY8>lPKQ|GXt})OCbrvZrTf2DmocM{8pgUrzGR;qIy9Nh1+}@K;TJ z3m@grRrfZj8#LWQ00P%$duDCwO$E!B1Ef-Iq_GP$-A*w8fti74s(lyxv_eja5JMIH zSr}too~D)s*JgXGnl))5!~B*gYiPdTEExk3 zXtRA%r8!M66%pz#5rl6$l&84WLI5I+_Pe5T$cGN;vA$R%tkt%LCaXcIb9)c{r`Bfv zg&RBEx{C7sHR9;V9-1m40O75*DOVMhUT={c7e?EE0}W;dUR#^e5K(XJ_49=`@dvUv zGzdWWZf#1|qn&=+@AFS*#|uM)nL!BFrg$zWv7E54W3?zW2tWjBZIqB6)_`fWTco@BO~@uKVZK>iW@DyXu_Nwd<_Y6%y~7=+V>g&=3(3(d*y2ZAL^y z1`!dF>Qj*t5fLfSkuwt!5m9^Hx$jFv#L4_G6ZebmX%P_-FWoh=(9!cUBKlv6jg9Sp zz5V|rGBUFN4}zGOn1O-e{}xhHQ!_9y(9_d1GBWb<@i8(o5)l#6(b2K6un-XuQBY9O z($ccAu`w_(P*G9Q)6)|X5m8c75)l#6($dn<&`?uTlal_kf|;3_goK2Oii(7U6@R7w;uj3dVJ4&YYw?-Tyu4V~ z)5E0Qq9W3A{NMlnKFeWtU?RKu-&19J^S#A#vA|_2*Bo0Bu04wv`H`2u>3Yk~z-IgA zqJM;`qIsSnfQAt*CNc$PKUSBs|vnDWgM=5Fo%)Jh3g{eE@4>xq$$ z)nVa8iQb#~%7gTX%i3bv3V5Vbh|8V0*_+tPss6i~!x1e{ADX||Hjb{cv$_%$Za14c zs&u;JH%PS~iTKC>^&6#dn^Av;R%(mWu6NB36@Sf(U#a<0M9f-R1*9a)YB}1bL|oU$B$l`|DK|AIRxH+|CiyS-R7>_ZfM&GRx7dyHur) z2kJL6eHupobKKC?gj#-w991Oi^hOqJvQ?l27`VCRczUAPN~O7r3Q=~Tw|qYdy|CD0 zP0uymdbUe z;7Se?H7DC2zD3Eyt**@bT$cjm4;{DtKZr@oc4vmmcBjR1U{F?*d?DI;)NY0z!L`EK zafpiF-^`x-fWci_h<*b5%z5BTg%RIRC6`#CZxS*NKzK|gLMt(gO$2(S8kNzGDvVzE zG;)+!jJhpK%F(0aV#Iz+=4$47?^1=MnVKB8V+aj+f4lX?LXx`PiK)_T>O*-#iB@4J zGn92V>&*xWEEmM$P6v4OUFoo{x?3l^Q9(zTrw1GMLZ}1N*81M+&B&+3?fo&!NbaVG zwAU0^0i%AGy!+aZ478I}Q?5(zrukQtAi_LisHUFQ@_u*VBEa8qh8JNyO~PG9ruL0I zGrzVknQO=OzCKDSv@3ipPgr?!X%&9=_a4{73b{{YP*&eV^FR5u35LzjyN$uxYv^mu zys&HeBN|WIbheF`;W9ekJ05}T6G~4XB9gbmSX(745!QFr)gQQUgY0pv*Qr^|X&lE0 zsd22-_y%9$+r8FOvr>Y$Vh~sZaL!>XLUVNpW4d}aK72G9mb94ERQ1qnpgYbg>9-zp z^ASyq7PqC2L-LIgbv{rz#lu&gO@P1f^fDC*beSqT67etNXrnLx%T#dm|CImVy307) z=_-b!%#mCBGo2@JVKu)71r&++n0z?FqFP5zjW}Fi@4={fti`aV|D32jIS|B?gIg{p z8m%4@VFCD&E8tt1%J2E?#u4EAYBm4#@?t)@1y+SGmGf^MTm`#b=|E zO{=XfQlO%_6%o2hd;R3=(XLnE+rJ@24A3SYG0=|vd4Nw`xBYP+Fh5vlg01xt$-XhA zp)Ee5m)a(g=0|3(?K%PeEx<4N!j1AU94$Pp*lH5OslbdspBiS2LL+T4v+ve^+=y;o zAJGFU_?jNauWOv`pii7XM<0fjn!WScasH>z3b+4Qg}{PxL;x9BRY*DfGSeT~HQoB> z>fVEVt;vT1fk;bFTicSuSk5SP=zF0Y;Y{b4h_KT`0Z*qjEzgVGfNx&PD9Uy$O=`4L zaDcykDs^}A{)70iSGfC=%^4L%N=qmtC>nC}ovVt{Jw^8Q+dIfK`?3?@I%3 z^M_;z{?(#Y-FpT*_Yjd&3V3qR!_IV{M(gfd)%vwX>s^GIifp(rsz$g(Yqo2{%RYO(&wa2Wwt9!s|btG(YjDgs0!| zn>>|0{WGp|I?P`d+%m3t_NRBtlizq9by`6^$x~q3YO+Pd^3tBRJTwyhc0p3|kzF7) z5MPk@QFJX6&2Uquc({7i2*kM=!u`*!P^5T;7yfgCpa!@LHoqzv&&_pytE4YF7*)1v zr)DWXK&h&x*>Oy&8~U~fpFWj@u74W$aD)m>ua!9^Ae+pt^8)dJMY@O03-tK-fE(UT z94t9pG(>V!ylh8JydZ)aOHjk*{f$+A?i~qykXTX4f3x(;Mq2>`IG&vTosA(*S~B@fp+XJOmn5=N&)rCy4&|l zK1V&<0{Wx`g-Oz{PnA>No^R6M>W2oG99OvIkC*{%iIp#d3n$ZiT!K-jmWvg}mAj9x zrll?!&Y#E;K|G-+r8=;IXM`=sLWRveCSL?0-NiEQb+Iw`>m|eDfh?uNg#p=Y-Y2jzBSr|{P&X_x8| z(TGe-lDU!Ye*`jKk`yR#E~kWjyjIl_O1gm4EhXRW}G-Zf}~#^hTr^I+*g zvh_)F_4yYn=$rb!0`0p8Td+Ze`hFd%ezC?yqQ!Xp+*I@9NZOu@GOrK19kuB0JVMq) zyk%GteGJPvc57ugr_cUyJKGHuO-CZVWJk~!E&;d#QoyDMrCW5Wzf>Y`LR7I1IpH=W zV`8MFk5>KL%#J@F{`LEbVlxqNme^kwyAss7`Y;OJeqR78ef5fiqFSY})D#5_&mA0g zyx;pq2R)jSz_Ta%FG#jfPuEL;j%jn*6FsR#p&it~i7EzFQ#I1sB{XgqB?_r=0!ttB zf9oDQrL(_H7PvwNdN2cP$Q*m)fP+|lCoSl^?vPCH(EW4AxQSBYwKckpBsZ{Dcq;Nh zVQn$s86095=()Czc#L<_@W6-r4WPC~ZHF(qafTQDg!D>jzk+~r)nNVA*T-z;Y{3_e zyPeccC7skLatTofWZ>|ZV{&kg8ASFt^2DPXlv9fKuO8~aG)>kKn-wg;0H=vp$-DL} zxoHvkIM&f=8ZimNM0XvsgWL2$*i=d5_SFv_X2XVYY6hU4-^o03$?aM|!msqVFwa{& z%6)b_KZQY2(?)df;}(g>kDyK|tlO}9H7Ag}vD6Za@Yol5v*O(uOAJ_Em6f4SiPy^L z%?z*)nSc#2$sIe+mWzgG3x-wmily7M@O1N|EtOu;y(y<^cT&Leqaz2)>$_GRv2GdN z*tUzDrHX=cucZ!Sx(9|E&@S;PITVS`-uTKr!O!|QN<|tsK%;N+Gbp0DKfoC565W_8n-g>5Jn}m(#8Y+2Ke!!R zO3>+R+050&Rj4^QTb>!;a?)}d^fmnU(kRl~P?e(3(zdk>PM@t@eG z;}7Rrqm3D=r}Ibj7;HiRNZ1nIv9v3*0w*cXQT57|1eBoh5^u1~STg?+Vhq2NXht5X zzgcsb{`oF!hC6tuV+F)SgC0MH^KWVi1PS|)}$Mkv8N@7Ipb z2*pXf(P)bJZTfeX9hn~lTB9;>{82X$3l`9Q z|NhmD-ML+&^)k;xWCR67v)0gk*=@?>)bTf=Ao!2wmaX#=Bg6ONEtsZ^E0vrF_*&Js zQqe60HodN40!l?aT)0onf;)9V4=dWdr!VRza^M_uWnysZ1$se*|MCC%KpeogSEq?zk#FDITHydR5haG&B|l+>c{z)5m;vZp`q!=Z*$?iGZ?b0n5_K0 zxQo3BSC#&Ns_|Lq|KQ-{xwsNx2!#gb6}S0Fux!jhqvL7M0hP3Cmxv@yFM^+sJ*F zvE^SLL+cNW;qm^TR$ueMW$Q$E^4=O5HMhdFJ5Mj<8(Z2r8{Ii|YL~jFiaUe&2c7n@ z7wn5}eRG3i$%yQY@@MhrC5@Dr4$c=VcX7zw`^~qb*!T!>$*h!oV*Mg10-1^PoLLps zV=&Dd@}w4Y$3n&J;iU)o9yYOL{)K`1lBmD>OhDMyS27h7+c1Has`Fj*S2_#di>)xP=U)lH^j8Itin10;g{#Kt?X^390jja0Q9{-cFpr*G*UVP0smEXCjz@> z7&3c{j~TdXqXWKdb5xt#qcWS>xcucjtahyN_OQbSETQI@`&klx@~TNBp%5)fm9453(Gl%I|Y0s*?*6Nn_R!?b9R@PMNTno;kW0V~c(rch zSK4LiS~UJvjtCGY0<$OpN|UW=>?&_EdI&s6BjtXP_yf_!^q}`J#nkF5Ej@jo>K*>A z+o?Yv?*8#O)zmQmr~cwY^Gd&+H`5L1su_tAtrsna3aVXsrLfP{qK9wXVgp6*sdl1b zZa&GDZQxr>;=58`p1E}eqA)*w{>-?iGqGGw;78a&-Kq6s_KAwZ^DJvBu7Dd-#tgNW zBWp1P5mzIRKzR55mRS)+#G(*nBE$r=;@ki;yHKMlHV-HDdHMJG0RZh)rAw-OQytg< zBaaWT&vAxf26tz34<~ju^7-FIHiYI7M5T7wLXQ{}wvT zvG+%SWZu=2)J-`T-r(kwEzTWZ=%nUs-3dq#AP@W8)rEwcg0b+Jpl8gO`H$H0J@3NC zXYl$ZU}s6FmwBlo%8R6Y;msy>TkquFr0%Az=CkS_tNcEr;yi%r@(5nH=tl~^q>cq0 z4RJt*w5&z`;Y$yBf%NGRpRvqx4Ye_)!z&R^blpXNc5ZkvK zjWs=)&H+J$;tY?liqcA#i)XMlC*|-0Y8{!S=3*V0H`Ttv z_XZljyMDeVmh>tFK4B)LlSR2kR#a5pN@4G!SNZzMc>gc~(T!379aAK+STzAHO*99v zy_8f|d1KvVnG6WYgr8eCPBACzO6yNJwlP4K7dNI{UEQ{#uUJJrHAB55uy4CnmHzA< z@6GJU%ph*yNSR3V??$2fihBtq_lgUaWnHJ7U>Z;50gL@jhJ~d1&Y;HVqLqu|?0kdq zSFiH*L_nt4%(R7p6oN=g#;Z`ru@(e{)UczrO;2e8`V!bdpEVm*m9Z@Z>X%QU*76(N zF)+===Q^>16qmIdn8aln`S#W*72kDPNNS?gnEDw!7X1BzD(+5f3tAmqF>tbBHsNY~ zA`9M^g`}o7ZIvJL&;ihsDRJLen!crYC9xQUU^pOH^#Df9U|Fb7jOk=*EanvP>7Q*W zU!t2+pFIM_XL|#9`j&3hR5V9ukWG~n*C8jK+q%A}a-UekPh+HKA`uu%1sDB^JC2~8 zUF-R3;v_qbw+(%P?zOD=g#n5WR|gKICZC47O2XFf|9W5|(ajF74iDB|d+rJ2*+q!O zCo~l4J=}n=jy9`LFV9|1gC_{=v|_rR9Matz{GzHZU?u73XyBkU2H`&SRQm4G#Br++3GAAoZoRNK@o3npn{&~v4mLot>Q3x^QQh=< z#V|RW_joOT>+7Yf%t8-XGv|jGgx24N#|2Lyb#_7=yy&cyUp&yryhQsx14&5#W{DZA zYyG@qO>w;2Cb(c2;@wpC=};*X@qWC6la~U~fd|eh2nya{kGZ4Ylx!6jpjnoHPVwx; z*4gQ*E2x9|ZLPKzRwqdVS_WdV2pP*b?=&9uhx#9&bqYjz=vjnA2B*m=x#g4IVQd^Ae_eYhDFA7;?E^O zZpWey*{6?+_r7br(^pIf*Cp^QNNR+(<~%gvhoDoLzCI>^WF0W=S9@%Kr*+BggM;V9 zW1}iEyXK5#SB~1O`}Xn4Di5A-M(Vr>xE{R81q=*2d4!aNz9oV>k5r%+JSC^y)m~^v zwXkDmAT^N+2o0yc86(?p55k3Ne$H6;IVxdI3{r7=ceW&Xy2ZC(81>BlepIjhN9|{s zak=^-bJcQxrbJbbB>kGaIxB_pV8VleLo2+$G81q>NUty{Qz`u!ZAO{(ZgMuG#2k!M zqUK5rx&8fDF=;#M=Z<7P?Nqg$U@bcry=xp?=KzWqT62vT7RhxczQ$GD(2j#yUZ9&B z5MA%-?z1QN>cp`=mCIu)ka(eJ^g%49i}NVhy3q~wk>y-{v}tsm0~odGMqy!9>(krd zK{A@Zt9aJjApZ2HfBXxy%-8KyI^%Stxjx=8T}JOjnBiZTp$#^0Z-!484=7=x(e4zr z*4yCU%}Q(ap?n9J8j>0}#*^y@^m&!_lm5S8P37>ewPGEL0(D)O<>Jl51xb}8D> z5RWYKkvXy#y9GWpA_hjo4KqYA+s%FvgHp|y<$F%>o5yBC!LcW8|6~e6AuoOs{6Pyn zMtHI0lnbCy2$h)oyrUciYlFtLfHa1QqC~tqK$tf9Au;eu&&P|~iF_e*q5ZK!amN7D ziZWq=6@yiUS3cayQ+5H#(;Z&IERksAO^+1Vl@`dI4L2OELnifE(kCt%Ua56&==`bY z=uob%kUW^hyBj4B9uzfu@<$U z^39J+-Kl$>L0=hs2?sOpGPZ~pX^WM>A%@wM1oSk_^JI7_;IX`H4z6O-d$BUea94fS zZ4}5%K+tugOks%wl4v`@?xkOZ5=9L59wyPJZwX_131Ga5-&38di~R3fJc~r3QKH0xN95_@U_|1E9J=DIL(Ftw2_Uv9aHjU7rH7@-v{q{53Kj$Kg6-dx-2b@)d zglB%T_lz2U?iglTQNDLM&q@pv7!ei+=P*Hvq3kQhPfh>YeetmughZbqdgAml*A8Ho zMz}c_p|!HKp((=U)H|AhF2ij|Sp7?DKN{@TYKwdsqR z$NZFJ1hSK!!8r_&wvUHBMG5SG;X{7n(~aT}`q@%`+Ea$BIJ&bWiDrJ(IOy_+2}n(( zJqf(SfkmM7oXx&xxC^gL>>75X7=mJh=7gYR+{VLfc@4*mtp_(iV=?IA=ZU#1%C1f| z_CvwBzs$Qi7c0a-cH3T+o@wmzqPQKh*;omP5E6t$6A*4N+?lF(Z{ZtZs-|<5-siJH zw%dW9yjon%aFBM)uDt&a2XL`KLYUx(CN+;%RFehHXSEvr6t};N_2UR}&4_#Za*i%| z=c=;U;6KbxT0Ml7yFz~%!Y-o^Ht(-xrx~7nn1A`k-k}3KpTV?221Kl#^-qZsV`wC7 z63}I2m^7M!!;>6jr zwEM&e`4(Our%omRjE(o;0T8tLRSAfjyxZOOw~L><%0KUbSJ@z2UiA2Te8aaOrWM}b zRJ|w(>JcL+zSkxs1`7k1@y7459k=NKb`rxQdV!F>cXu6s$>{n?+v=A2JMaX(6^%p7 z1;j-Y(hW!~GF6`Jh!TqsO7vTo++-2FhTWOhz>aF(bLOlDXOWHG0D_z`576W^`sg2A zYW!LuMN2MOT6gA{7IZ%Rt7*US^(AkRf2+3T<#zDR!;rUJKJG#F;eyv#$od51Zy1{i zmy~?sct01{dgImQ$;+9`w99$7O!_EIP=UjA&M*(;{7vG4h*{d#Wusxw^70ELQfpgx z4(k-Hhq#x|$u$bI%noB;3ecz`?%Z~q4QYSdU)`p z(5$=qdjxq%4S(uvB`@N3h(}*mlkcD4h7Mbh@4WDnEO>L7%B_}%OsW@kZW>zEfz@IH zHgr>}@9rDKa-|=?L5JzG90@Wy zlIMvuqWH)Em%Y__}*+B*Koaf0o_dd+`(|!H@Q|e6Tf)S+~ZbfAS@(W&b+hG6U8@T@@ z#sk&p8WZ`=FNERoHGVQKaH^^#y9rTuF^6Fd4h!(NsaHIrk!Yku6U=V7J^U^^M!jJn zhY8{t>Oi%PPc^NFhq;kJel}^Qb>^#o?B);A-*s75Mcy?G?>{Tv$H;3LcVL;oD&|Eu z_7?Okx_-c;*fCJ+XIKp`=0v6OS3n zk`{|lWdeJyPuIIobf@?PwOXmkuIHbxbISyNiou{*SJf360eco7een0z8Jp&@LFe|C zty=mHkdJfKy9EkDm5GtfG!N-N`nI%veEXX-#k;Kd-(P}bCVhcbX<9;%AbH-<<)yfHJP-% z${}fY7*V6lc9Mag51uw;eh#cL5x_lkQ-Uav6K8+J0VPY9rX!UUT7rm~^y#i_Sj26t z0s8PQNAs;KkaY^$v85{D!FX`Zg-Qx7o?Su5FQsw7ZKYI8CH!el8Rv;o0(z+nW&T@T zrX9sI?lKqS*}NAyv)WXe#;>}lnz;RE$b9B&yf~I=uuO8rbrz|h3#QyFUar+m-%ibtu;zVQTVx|NR{RQXN z@xZp zK3r>@w0Im%9IbuQ&-}i~yf-sEw?ymqEpS0xWg6#wo`=zapHm-vP1t=L22$^7#VCGx zxcJ^S*xuyLUQRrzsa<6}LiGM``tsGp4dL3ZY*yX- zOW3_l-~V$Kz%>bB`IR%JJ_Dh4mUuadQ`h0i4PTZ`D~i3;LO)R!IH~YHoTG?kB=~=V zbLQ6kKl}1?;s%DtRv-JP!HTVl&(LXI!VAhApww;Q;OFyJlP5nkaFWDS7$=Lj$CVa* zei>_jKxIx@P6y{s#nG!gCRrND#?+Y#XS}M!9{&wE0s1Vb%54Gkr z{5p4bD}FNe5aT4T4JP+Z7TpB~V1p7=9`)(iFWk$2p%kvda&+Y5SYF75&MjVAe*bH{ zJOy{{J_^c?$3Ec(k}o$R-f=b-*y9sf_SQ&zDP;>3((m=0?qZ$_dw;!fBPTQn448{W zOL0xy8~bH!RM7`~&EH)&K3`vP5~DXx;}2^(BF!n;#!iL|9zTv__399{{!yay3Au3l zk%@o`QFhzO?EtaPu|Ck!ltPNvVs++{RTSdQWhi;V_EBKP8$MH>X*vj63zO;PV4#@4 za59W9JIuojQH$;S^E&rcSrp`FaqjedR!h+xGN=d71s5erz?Y$bMX4i5{%TlD80wdzX;^M};L_V>f=~evbn|PO}A4X?!qYFRE4St|_)yHmi zqTX4FXk)z>s>xxR$SJGmmT~H}P~aWvMK}5VPMt;uh@>8n)$(UtT4<<~F>CVxRE0rm zhWw0GTI{O*GX%!iE6(C4t-^udbw4J6w>GjkvyB0gTey7}Cn?UAPMMN_qTzKn!6fop zLgQ>#2kMn0v8}<}B_J_H^8I7nyO`!Xcq&2z_k7anAV&O_8_uxlUL4g#g2jCq8<8H< zeIe`si_XHYbq#4ql;;*8VN0JDMk%?c7PP&8|xsin$^F)X?X^|td} zrpx?E$m+q~z8FgGPS|G;}rIDB9z24&*9zt0TNccbj*^Obt`6IX8wQ@92<-&0KuF-0+!jg}v_ z%Q#s|x!UDO_}xsH{~D5V#%Qq7^?T^us5$bR|IXIgx8Upr|Cg{UKlJ?M@T+(!L(50D zWP$Qbz6xVv9lKK3f;fa2a=%_%qZ|A9`t*!AJKngx--Hr}_#}UP`eg7ml551=671iCnZ=vU zS(@dbXzdHP)vqv-41z9k<8I+=yd5>SY=vvVR@lp6*93G)=$xnWQOUq>?Umq_1<;Lf z0C%k&BVTrD@_YmGt~-wQtyC4k>n`_(*Wul+Z#R;(1+_0X5rN{FSBI}xC7|Cyt?Jmg zK8v%c024KP*ak>QXbHal8n|9 z!(BlQy2*MPwxT~=s}J`ZKc2^2gsaV*9}Hj2-i!@C{wuQRrUsXD(EGQ{eXp6})6CP7 zQ^90DLK)zm7+i;LYfe8vf-47GD$s3rxB0M-aUY6CS`qByKFH80gpE?fKHOYpl9gV- z8;KD6u@y6TKglKut>^PTx#rR@Kh7!K;o-^Vrmg0a@9$d5In|S`W6*>*9n2Hu(={oDErKfPQUVAH>$Cf+grb8#bvhL7^| zYQq&w)L*}V!$qVohusj_&Cl$xb?w7s{W(^b!xGD4MtJwjK3B@6Zj=zdVL1*n> ztm{iB%~vY2LMGX6&oliU;;tD=1Q#t!O=zUC09sRm5C>NM-yRm_3-ry;)$}RUKv5^_ zz`&cPW0I>>%H!67O0310+FMP<$ZcUc(|~7a9)*;DyIBj18yEpU=`Ku?iqi%k)T+i0 zmNY+p!3a72EJJ1f)4V{$0aslSAKnV1JZ= zeoK}zcRuI@tk&tMr9{L(FB%Rw+2DcSHNO}hcuZ+zcit@zpJ;`y9&IREb`u;OyAenC=_)yp6FLOBJXWamcn!U^kVF`1m{bJyQDP2>yyf@U0$y#U zpi3QG1CP`dd$BPB6F(h}*FG?whLyTWhwFfucpZ3M7OEz&mSr7fTh5=^H)woh;J=?! z0_om#EyKx1aDNl4yYB1L?h=Xqx_Em|wxK1IpLcO%-9h%$$85aRchpnbzN#lhvbXQF zSqfbFn_b_IRkL`Xw{b?nHpp~Tv1RYL&fmz{q#K1cJ6e$Q7YLT36YjsF|7ImdXa#cJ zS6A%9PGGcJro?nKww2mGacHdrA70@7nca`n~v^`JspF)3D5 zCmC(}*sz8&52RX$(Q4n^+nU>^e-hV}XK0 zCVH!~MH=8puWCGOOoF3{YEv{)wD>nzAAB14{fLaHZ-KT%12Zwwb{o8JI5pCBJks~R=qcU%wB-wk3(FOIjawSW+IpfNVd_`h zgNDZ5qhQr2+XWvpYnMa$?`G^WDd>BBW~@;2A+#@X!~h)O>7`st+nkbS>{lH!tp8p{ z@T@95JB>#dC+OtrKiRHJSZ0I!FOxe=BN;ldLw}~w{e*Pvx;+ylLk)aRYPL3j`}vpL z%6b@i`Ho|MGvgc3R{Qtxj-n;O#8{1|AKFpRfuyG>6*7QTO7UtJD*Sj=z7sW%kK>yu z6{)ua=Mo<+!*$n>MeIIh?#a*5OLkz_W6~!k5Cu}>SHrV`RB1y?Ukkm@F=K=8KUstn zvpAkV(Jc}UnwFVCewkqc&~0~Nmc^mzFiO0FXe(NCi5BxUH)Ak>(9p!)x?oVKCVOuu z@G87Md2+2ZAk2(syF0)0^i6dE9+jpXraOb^tU@o&rJ)E13N^csr*}>Gvzwm+QtSVYR%5poR|JCGD9cHXe+M{hw(T1 zuxbRjCi=RXP+~pF%8;BDrV7d~$jl%WThZ|oGAr?8SeEg&vn0H~1!zqBy8YvEmi26V zqMu>u%&*ELX*dVH;!g!^Ep1d=Y`u#q4~@<6U}sZK-Ux0o;3S_xGJFd=^UXdDF=;|? z6OffLrWzAraZ0b2_jA=jHnZaxVwoLtix3UB+er=0sWJQsZ|0{Tax z#~R0;MXQY5-?sVJ228h$h(&kd6@XOA;(QD#9%-rU{ThDrw2HTCn&&mm4QlghI(=P0 zT-UdC)t&OBhvEEkjC4nL#Y;3Pjo96WX#*R(hn?73ypHrtEc%e(NV#Uf7?Ox6pfo5{ zVR$5vA3Mg*$dY1TjDED@J9?rM1pFPzP%1(^eDC(BtRtif#R! zBs}sZI%dL>_7`W&cguORCskY#of^T!y;qICkOTVGn~P0eVD=k^;pZ_UILRea3}+uZ z3&gXqLDYc!78cxe-{msERU*jL?=ANS@e-U*`C>1WQMHG^9pg^O9n~4YAGytc5fy`@5%^!#@?~mrp@_nNGNINh$HRB*2#I5o+`9A z@xA;lkQUs)+fhso(=>Gr;fOl1C5si(J&8y2;^50(w9|3Ue3J28;87!GBzj&w^pI|T zN8ndG^Poz8A|Yu1UN*|cXfD*X@{Z^i?n^h|W(%<4y|Qd*HA!`5@hGr*oGjVo8WGLE zJ(DDDbI{G-a@t~Vn~aw8D7#6KVr3xK<>mK?^(h6VtunOkFU-gSsIiOjTdY=Sy{chp zyYNH~9IA^!y2vBDAVBgGUF&v5e1H$w`cWxy+o`bZ)U_uubmDkDMR%z-%kH9y1}L7O zHiXy7fK=%Y;e`zn{KVk1`aP>M<$H)A@WLhz-9mtKnV*g`LsY;&CSdYWhR<0|+mL0a z$A5Mr1_zc|plJ-YQvC>deR5I=WQLw?hBZ_v-!oIb3A-M7m~!&wTbA{SahP|aLNlND zS18Ak8B#+(p_q47W=O{?%t`~!p47k`@506(&r_W(g2qx$(!&MX1{JV@@WMLwD(0L;f z^kVZ+E9LeF?y6MkT)Ym;iJCOVve6x+S`(JBpg z{1V3RZ1GvUH3uoFt~(~@5wE+bfU_F1$C5fOv}}r+M8L(b>AJA8Uzy~vHl`5ij3bCW zvcPtWrA)066eKdnp9TS^%a9y%@5m~LO0^lQnH*a%7{|ANvz(cHS9jSbo*4>xBoSQr z6+e=gySQ=CvL!vU`V4JJ=Ibtq5T377yOU+7(F|bu?P~28H(t$hQW*sie`Hh%78pWB zOc_KXKfV3if8!}jfPlm6Yn>=yke)1oXG6^@@d){0l@PJh9T~#U4D5KFxcN3|_etl5 zPM_{B(hfckh(fdKiqlwUq~pq-^05N-o%wPLk_D-LSNNY|P<%a!7oe;%$S1);|CEz1 zEpirh3K1<-X#LcH6zig5(Fb3Cp`NFEFU?{%hEdWp@^1@U_i@bI6T6LJo!slO=y6%VaIuLWqhj_@xL*QpFAjQ zY4|l7rQ#{~R){~_o!JHdto<(B$+?h(_ZR$kbmva`aZP(%*?Y%doJ&P+vj5fS!0S|i zG3LiRa?L?Yj+<7`(bo;be%#2+c=)U!PG-SvQhMf3yu(B9<$u$D4!03tGY~K&+fX{F z_ax-F1g;Ze8teF>apbpt{?!*y(h*T2sC8y4wq}w#N7KLEmsuUcA4o4Gxl=--y4OBD z!GG)ry&CEEgksPKt^%~G(-<^E;AasN8fN=*o9WU=9cy^%WS5WBZ*QR<@ zD%gotSv0KlxWNL+lsnGg4A1$hQO9$f4KGXGQ(qtHz^aYp60|ww4~1#WH`mEicAR6; z@04(lN_*vwNEkU4zj4v%lFJSo)^*i9Fw_kApAq(u4^@doEBn~qdEN|qf*N5b2Z5qT z2YEig^E&~NG>uM04qWRi?+2Hn)H{QJGXM*c>riXlKS$s+(D;Fc(rRols8I_tTIhD) zJ@E*K@Fg_ABd>(Mu`#Lw@?c&}Aw$yg6b-M+r@18VktYNux2CA;;Gb_$7AQ_(<_4P{-GIxV zPW6&D#lE(u$&j$`!}dn~RUGr9g=!ur{4<{pvZmtqzEs#3=BRF|YH_pkk=H9lU%+3? zXtR^^hez*~F_iN%J=H&z640*@xAYPeSjEzAI{XpYJ!f)s7Yh0`l&`jsgjb*f8;Tnx z&?R5K>}B1!DuxzJyk_MtJ!H@F?5pN94NdX8CFGD z;eXu>tU`^;G<)#^FbQPxYcD9xd$_zSiJ~19@q)v5tR^4jt!<~gpkSj+3=#va>%r>V zvO8$G7wy;wba1qPJlZLQKc)7rnqS_%O&(y@Cs!Uv3zIQC^c%i{-DMKddjDU42rix^6DQ#9-ERxkgGmCtkq|^e=B* z=P?vB(k=c!{gD87^SG2DRiw>?S;gyu-d9`iGvnVh?-UaQVxLOc#4=K!{qCE;_;&O+ zduc=AjDD~Bho$&Ydbs?YQ-~-YIpeCJL;|cj3|%z=Ll5E(tvJTl=2?~fdyBQ zZ1*=(y?p9y|MzGsl>KY?oB3%+j~70@!5ytTV4ciN3S70(n6`wQTl3BuE&PT+U#wU>ZgZ*@E}@H0XZtsYiZeVT~Q zad6Fq-^EtRMImq%)L{A(E@S`sAvW06{qv5KP3EJr5`n?(lmEdLJH~XyKPCa%Q7X{3 zlL(J)l5ij5HVJSLsMa(iL6#$8(;NR+Mul-_qg}RP%H@7;h=2z*NDR>9+?r3-?aMby zn<=67B{%Dme8O|uAW~E zMQ*qXA+Yvjc4Z>Mxn&dUdjH6uvSGrbVWJt9I5m$%mlAY7$cuv9mLaNh8gOUfr}|DT zaYkPH^tzFJ=I>_!WOka1oe!~WNBK7(asNzGq@~O5-(~_Rj6>*R_Ai9B25TbG56M#| zrcH+pJPw$yReU}Q22MC8iyCP_zMp$85)1<^J(;Phwh(8>DG79vf_^$-8HJ7s;SYXO z>}lNGlga*kvR*!}>;@4a)Q!d7wUNGOqah7lN;yi^ce}5CqCMT(jrzIw5t)A*^9xn^ z_nI&`s-AwC1kz1FtNjR@nA<8Pu$NTslHTG{KWu+QZ2uu#@?nyLt7!~kKB-l?C$ma4 z7R0#`9d_+6pM`thrKkO285)O}7oy6_@U+Tr>dw6OPLY80HLA)O&+~hMU=Hbb2D96- zH!8nUdwv-DfbhhH9nb(3O$ky>E#0WI;3nzhvXviUSJl3UQ7gSXXI5wE|AqRD0OsZ` zExnq8o9>dp<%wwNhkrKwj;hU0RgP|sR{(s`2&GoL&FjLnvrq9zPou47uPeExGt5vz zen7@Jotn|yEvaUO(03dN&xXp?rQVZZMgda5pMW$o3G8cI-CP{27(U_%{%TIgPrl@~ z7{?8*Cw)u#^2FuVCzkwr4LwJLkCSSAuZ4NKS_ zkBdN7alhq54s6mV=DtHVW{*z&g!~ImNYE)UN40TrLbur{lK=Hsy191h zxzi9hA2QbVLTA;rqPmE->iv(ixXw&MZ{?*feB9R5)R7se(;+;EGXwlppf7a0<2>-A z5DL~-)y?TobSi7U_-`+_qoQUx@e0;6F=#E2aB{FQUpo+lq68dWD`G{)bGzSU>A-SI z1Oz#Tr5pTF4et3MCXJA<8l)>+78*8C%Fclk9u4FQM$q7_Z3Ky+rm&mW&D6!0SkI%QiKjb`IhM!GRfg)CDyYU8Q5P{KORv*rDQe$--U@u6 zfEd%iMYnL1KE(+o2UL^A4exv+zC_`Q>d0PS?2+!p(;4!H)oW;r@twP0caeNRpoh{1 z-gv~zs)Oj&R@VX|wq7)}v;=~y)sH?2|E@lVbJewP7q+Z>a&#Ueg@Y$Zk)w?4wK&90 zr3>Ed>IVq@qzbZMT!zGZ5Y^7nKYD(@Pzx@V6bPtZL0h!MFO&X`;#xj9q6qp^H)Azm ze@8c+Ltu}2X@rsqIeR@-JyD)HgTt?F1HLr9KpBAQRaB`0*Trgn=$FD|=gh;DpWh_X zo;^c@C)AJ3i2&ui-^1hYh%(3!oPye%Finw>dQ-TJfg2xKf~bH>Lj$-WdC#& z1Y{?tT#r1np@=gk+>Cq`FKOJAdQZum^7`ES)$*cPPVP1NNjnZxn$A}z;?ui3O22yzmhZ$;jP`^>rKct}0l0eTfM)sm^6CrD}p(EqM%|x+c ztp~h^5?~ijd_ugV3i@BceMp^;d+9!Fa91e`TrE6%_+XEOxq@S+t;yn@g@B0ZAxqP` z(}2L>M$3Y+TAn-#W``PYWNrL}kf1t-3nfItdJsPaTVbkE;AQo;Hc|M_O{&hssSsBs z|4V$86~gK!_4dnRi6hn8d_mh4y}}H#;X2-kwitL)H+2CI$N$L4E%x7JB=b>mj)oYl z$QB_iP#p8RoRD`n=V;b)T^tx#9<<$ZQH=AYp0xSPQ%cYul;2@0fpY_os9uOshC0qb zXW+-gxfea=@wP7JtbhoRP=W0Z@hIWxITtGc?-}(X=WRz(yZlPVJDY58GSss4dUot! zPf=aJufeDUPE>J{J@c^vIDLBoKOvwV8&k8#1*|Lizc>;KzO2BScwKQXecsWZt>CjR z?{m8K9;b9<=zju(P96)yjD+==UMa0%*wPBn<-2;!KXV=rMuJn&*G{77a5n`*|vBv;tE~{(Sc;srY(95&Ga}8F`*xzQ5-%ZGQ zut7%AFpkR8zzF#yfXH}z1eG=yCm|QED2)iOh%=MM)W933JEp^o3^&`JcfO()w}Sg+ zSf*N$geugaad!U0+2^}HQaB5rHv0R+P`A6-Pe=rAm9XWt(LfU<1!UkQTDuVVNG<1s z&BY)uAbxcI2mzt{vyBZn*tPoN2nknk8r{UZdTHIW?&R8$XMD4m%m!od62&nyVMX~um8x&U50Ai2z>dQ2#=LjCJKNGxZEn2}&l#d=RXh$zNXegpx9HKz(HA65A>3g_?%VafbHw@B{s#n&)}Gv+0D~2`RXhcSpLqwXyTr8+1dfCY@-o zI~rU}dS}HWJDyzly~c37R(bOT=-MSOKhkscbJoU}e8GJl+9DrtdBwp+qR0)vUnA-h$!$v;(^w`DMqco+yP!(P;WMyBe-=?5xvp{_`WJ0y;kat&}YnqHpEyo*{( z1mBvg?_c*+xdb(&jVawakHvEU^haIx3obS%)=DQMm5*#CumR8(WQoMYd@a6Do*mW$ zk1U|aaXs-V9Zol7<|%g>*$-wXa#yryaKk29iKO2 zXahH&7?{Aldudz9$BgsEz}}Hh#QE{x*b8s#rnJ~ZXp6$Y8W`P&a%=W3_IUb4k0q&M4Z!3va0U9@EIVL(RO7lDhb+bC!0VMlf|F@Iu?hInNoPpmg85d?DOh7oR z$#2KKqMdN*T7B4~LZmaUcFw!qzgX3gxRJ3UT;X$0`DZfzyZiecWruZqfUWwbf91?) z=OF*lhbe9<1aHP|-kBE8Q@}~Zduc00azV$1f!x14XCnlhFBWxWRMH%yqnq#k)a>)nYj_6R(_n3*?kXk8~|bqZ2Uu42o%jse)I9^$pp z7%=!wANdyIc<)}AZXQ`XNqblsrBm&RHHm_ii*?00{;aGG(0sl6&*}OQ2Dw8xUL*I< zjoYZCdf?A5S_!Cdk$IE<8lXiPWKW`Zkn?>&Tye0nRhvcvWQaU zr}NfkP^AWxxfr4ND@CIk^Dbqh=ns($%j^%h?b;Ux?I8~ys@KaqV`1nKS<8jPq8Tt> z!7WXd-P^>NNXwl)n({w{R{5uEiV@F0&-lbL)c7GUG0OFN&X&t-d^Dfy&>s;a5e_cE zo(dJ!V6|m`2Aoc0=^K@RN?i8pQ(l*x^UfbEQC0m01Ke_KxQ}q3sDAK_zL<12m8}C& zsxC6mNh2hHe_2jwPWZ%j?K29@lJ82E_nv{chLn~#fx-SUVKIftx2yCfyup2Aq1j&r zI|mq(+$&J!G?6#W^dk)Nn)7Owg|~EM1bh{S)c&dmaV(`S-8Y@AcSMBq9b}pi8y6^# zaPXm>f}!WPi+kl!0cSs7M2S7R{$vq&7INtTv7*QdL{(tbHsVgBl9VviwCJ<62;U_} zcHPhR6Tm`uh6E0-e<9i76|A6k-cRz8;J4kYg2JxN5v5H;OXH(!wr_+w-E$0lji8>E`F5Rwq z5gf2m7_D>lh_}Chn}Ak0Tmqb)P2*ROa;O({eUYDD5>WZE0(Z%`n9+?GSU5(DV2B7n zV^Q~yz5?%O$fNY~%^9IfLwV^}_+`Cs9*u_uIdF|=>Zn4uUrGvp`iJqulf&lH2zO~o zPFVrnC?eVXi3p7VoxE8hcL7p70t6X}{Bi}~&Ba-jv)|)xNEU?ddZ5||jJVoDdk`1D zv_G9$Q>kJ6p%!nBk>y_aFmk)61>d_2bIKwlL`XvEHWr z0*-P1+O)L4*|qvVB8P#$zs_eKYI8p;m25J+K6}N!{4RtVa%V+gwk&<9Whw2jgjarop88j=!W0n}T6f z2eBQA5rq1$tLzK*jxQHfes*d$)>e`?&|1(O;X9mI7r;(UD}L>X_X~Xzt}`bHv|jQ@ zO=(J?J>wW6vXBs5^zR2pOkEYUHiDh7Z6rck6(W9H4kkkYVU}>^9O~aL3|Ifaa;YVe$(~ZQ!K#e zG_2b4`{l1MPO-LL?IsdX%pposaOPL=1dx#k+8(9SK4*6me7P;Mui$h72MrL(G@V!+|R^(4Ee+P}Rj?XHM&{!7l?*a4q{-#>DS}$-?Kb zSD#Rk1hu0AY7<%eA!Ez66-l z+YE(q44jp_%8)xbj~8fLbtSg0L@?BD1{E&HHRr81S$(04syn`dG2k6;nos&+%D7|P>aQ5k z#Gsf9lH4L)iDhV`^7C^!p&}WbEHkNS>x1OBXU~>HVFlso2B;YC&%|3xIE#Q{-ZswV zAN`MLiw16ly0E8wB$578PTvc2*?@BMB{?InT$L!hyyMV*a}n`Rutfac8gJ>X(&J&i zZheZjZUmvF>;$Fs*oD?`Uk+3Vzl1+veXaB!cOuwlsq@QLVRCT4@K9J!4${V1sC!Hx z!Tz~2NlE&Y+uGJg%N=9>xNFZ*VwH7B8vBgDPR<-QT<8t=^tG)9+c%ZLmY)y8b~P=H zlcQSjM_$Yak;m19eW zSE|X_(J-M^8!9`*ag+3Ny|m5}cWE+eCBw>`(%f>8(2=l{7ABb)-xy6z*SdphjR(g~ zs=O|vluxb|-#3lUu;U3C{>mtDxQ)7jBgB}#!|_VIqz8WVnLlvY$HWB=Dc%o$vK1Z4 zn1EBJVbCwZw$jeBHv1Hwr+p*NU%cy!Uuki^M#8Cj1&42-V-bwdblD^o>vb9{c@cAv(U!<{xsY z@Mhh1A)^<6OIgdX1^G{?4Q)3bcq+IxUQFe^J!M+a#luK8cKlUIjfjk7i0}X@Rpk_j zQ~JGgE+y1K<#eZA9BjdL^%W@9eV_)>pn2~14~`hUr+9O3>BsL#o%8a@c}~|9o@)vT zf72zBAzf5{enbM;6*!^)*M}SU*7uVH-x22;Tj8-n-~G1@rmEa*;nOyD?b^|jssCtK z`yAc?zdcOts#xqiOgmVK8Vr@c6H!NR9+0}{^S}fVGV;A{@2^hU9mjzz+h@_>8!Ei0 zT){>MmC#!`mzcr)hDs}AN=BCAeVI_YswvDN09!(%`Ars+h3w0Vj; z-hB8-m+)5nlA0C0qq~$`Q}F&$IhWDt%6HOBCoIk+sr%Ylgz{w>cM|<+QYQziT?J`` ziAdQBbt@l_6UI49w@p>qHBET{DzDX<&cB1xjeo9tiF!6jym;9A%HiWpNDnhZb=#%Aocd%7oGRL68NQ%VEEDo zUdc=o5}gTUG~Gj8(YeO!>~*cR`(&I-y`v%j8*_HT$JCF6F-itjHMe}iEggWExOk(Sp(cqfh@C`oJ1=hYpjxEP4 zW(R6V6OSgIhcT6;&*>a+0Gs7!q2#JfqV;oCPK2d-K{@nsaVTqo5L8r@u*;}m_|*@y8iX2G1QW5+Mgpa z+;+q6!^NSZaRy!Lw<#ETR911i5JMkfInO1L?X#07h-y@fF%E(G+}l!GHXFZQuy?p| zItC^oTKv0V^L~v0Vn-7-W#yh*RX1@~C|8f~t~$pjdht{DmUy((sojYX@H{%L@k>_P z@*8(JhmtJuig(ck?sJ;A10Guehig7*FDuER?`?71Kjvp5g)Vs8w=)hUX|`O zJTpm^^8f06^-d<&pKcaHpXQe&i-TrlE*5*ury15%+qNJZiglumi!SE7J$(4Ynq2aZjw{Japx9Q+yiC`-_ zfreLb_XXitgRZx{_0 zPpJh+Ge(v?*tWn32AL1w-R~3J&bm&U@!Oc*TLXP)%kPnxZ5KH%Nb-&YmS5|Z#5KY@ z`sDCyx@oKW?e4|j_?b3sl#L+7d|-tO1g={BxzRF#q!}jh=)L}8c^Vj;olu{`eQ;WL zT^d@YRP)g94f0r~B?2$Q7)^>O9SywT>*6|O+r939B0jA~5?u0?#-?X=rr}P)xE+nJ zMw0$`4xIV!NWa!PBbsk@$s-pX9LAVP>$7}1^_QYeExv|mop-r}gGZxvlp=>TPBIo` zi2WKv27`H)55AXX9eFvGSPTEtzfbS!n*Y28d8&FwPV6C~K^vdDRyFH`g23tgR0oYY z7c(5;?779S_V1NC$H-!Y-8;NxS$7UwEgb?#XlkM81n1s6D6Ikt z?FJA;jX+}Zs?wIbOz|;)YyHIqfXi0vR^nvc%ox*7B76?tV7dC|pp!HaDD0(c|=5YWJdLCbGZfmPB`P%zxUQt|@#zm-Pb1x*vE{YTo za`1BTQFQdm?|0oji0;Stz8`NChz8?65!cf3%4*QXAfjEspXV*nU?J6~tpxn&=xWQs z`&C(X!}iL*cOo^Jpm1{I>q0BUopu1z<^i8)V#rW9-LX+?esyq)Eg7i>B6rD~>iS7do;0 z!~wU5I0TWm!b>>et>Y)F0;{Ic8_JL?Yr-BZ?!k*r;(G(i&=nn&jVknB9j3|%mwbO#u`e3$S@L;SKHPjnU&x?# zA2U7g@;RVk#(#fl=>sir4<*?$#)k`im+=g(b9w4K{;4eg35ij4h2PvrOn2PU>f%$!^s6c6TYLJr;dsQji!D95F+u6}ddsL@&Z z!fmOWg1HlN3-7g)PN9lxIul>VN(c!(qmB|@PO62O#br9ZwmjUgIc0e@?gY(;3sUml z59dmdy(0$A*1f+VK@+rmD{bH`V-W+s>VHBN#GG9=GP1t&_Ob^}`Q516mA$z*=lb8L zPM0n3&tXJy@T`gJ5xgOYT7AOd-B!4UdeAb z0KR$3Db#VEQdq3cDbY>bC*tun0cI!Sv~~WIew`RFhbs)U<}8kNKNcE3Jx^)$oP57q z8MM6G8P>QFHRqz^Mi2ik47V)7Z9a=HZfUVl!x1_RpWGd53fGzR4BM{l$dFf*$<@t1 z@#N*m1E8l`nS2i7X-5>ue~XM1glZZdqV}%88*B^Hz4c{|Z`3t3)5BZ+sTh#NEfv1R z64jk?Makb*#XEoE0*d>c&qm*~(z?JQe`m*E_cJ)V&dOP4xg{Cp(z`N^YvzUcp*S!V!v-X8$AE?u%KIS=sZqD_o2cr1?VTgPI4oDBve~tt?$2W2 z)2p~Si~x>c)}d&g0G7Q*ry((B88;IPT=8=%qUZkDsXECo8(X1t)Y)7A++Fsai%9)$ z*q1`{X$~6fkVmy%de%%B>e@JpKkUCXcu0GP>zW5EuoU+hvE)RWt{YQ2%Zk!!y)0=& z4dItAQ=lE9aQY$_SZIsNP?f?4WtHZGnh&3Aa~Mm#qL|ehaQ~KoH0sQr)0AIYU)4N)?R#x8zvjGwR(YY&2ihqu zBO~o&|G5ATKp8H7Tlq705+!xyNS&ih(S_UM+LtuC5J_&1yw`@$M>}W!i<1I3yNI3J zXV;Da+RI{j3stnV=VBQ-f@=Kg1st>pMw2#bO2yZ=^&ToMNz#D5Lhp-O7jZWM{kI0T zSWgH#8ovJRF~9LVCo;-t5Ik7tS3bZn*QU8WgYwVvVSK@N&20q{9YN*5;aoU=dh27WR?K#`*vSfLzb-XYn1#5QDuk}IyA4RUKHib<7w2mH&)C`nn*SA4Fw~{Vu$r=2^fBWYz^9gLvRpxytmtRkdxnuYMT! zKN2)T%mngW9GU9q7h_UAUve^1@4o3e6of)e5rmtsEBGDV{->O_co=Utv1Yj<0%+vf zcM?xAMD9|c)zo`8hQ9`HaRRwzSfQG-v496;AFjAb$V4sC=x}`Z!UDyKbG5N6Ly-I3 zA5`V$<74Ru_Z!&Hy4c`&I^Mesiq`A-#t*7$`VGr+7o~Cae;2}zc+z|-4i?m8ht{dB zf$kr#9maw;Z$eRN@MEl+#CfTY_B8naFuF7B1<_hO-#YX#UR>pA9FZMx|7%-BcXTwS ze9yqrj~z}t*Ke{Q|K_jL#*e@Sm9H#nlG5>gp?=?A^L6^Toz+rYGmv1KZRvbWmeQ#< zlNpN(JFhcWzaP5K@Os*S*syH2R=n{;<7lt`SGja;g~6|=O&j$q|EyAqHlZQmw>>JC z9_V{N0;W2l2d>a?#t{9*KwqH~(qoyae^eu&78cF9wb%e3v=FlNnczM^GQ;kx%!60iOvVz>4c{bu&w7XI!Qjpklz)--PUu(P1P5r_kUZ^4pFE zbxtt?B5g1YKL=9(DofUJMsEC(K z6VfRJS3l+lZACywMu=8H>)uyyu?IGL{5!@5Ew(Nqkp_(v>C0ijvj)S$Os_}4QPPfM zv-^86iDGavMjr?Lac#FHaiSY*nU>!!FDHo*okZ!5yXf&MQIg9lGZvmNKWozX;&L4H z8UYyUo)H6-H9TwlnU^o3HAbHNd~3+ertgl}s16ao(~A?8k!T(K?=zn%F3m=lNf@`j zZ8PABIp&LcPUn*6^oD`o)N^wHZ;#9!%W%qmy$n?f^#p?Bxss-zW{Z#wsYgEv+Peix@M>s1wgS$fFI)CRB(?<${8{f&f%i0A0V zR>y^lzw*G&doN{QJjc`q+&*}V3V&RmDS&O^Yyrf!l$Rv$kZ=o%>1#3HwxdIMk|_+xr5LxWa*ssa$<}B@P-Q zdah6qDfa^$w|pEm|N89sMg(r28k--P16?JVzfw#}E(~Y9yUTXK5mx~kG0|Dy5f+(S z{pU|bL3asjKdNoIN7pOB`%e#K0*j4&%9L{$&wwTp%axh^DWhr0=eB&lFqIN~!ft1s zD@(G7yp;G}^+MPAxwq};fgpJ%5(}zGO(sC+!AYeY8*{+JN9Cp4BuLEM#y{LD4mLvQ zM-F8aGRZ}g6}gZ3NWLbEf#@!#zoG&Kc8p^Smk3R$e5q#k3(Wkv8u~rMB49Bl5gH=i zL;H-l;f4|EqXqrxbV0q=)e$BKT*UFWdQAw#Ohk_p9%R@&TVe*bWh%YYn~-CY4S>2y zKOFyfJ5f%Dt7h5wfbyYxrBnPh+ zJ48c686TOk$&ZWl%IRrQB#PwLq72C;#6(xZt#wEXDc<}oL*d1xu&tCAA2hcFPZsD` zHVhGuQ(O#H=95-ja5D%f8#bQ|ed)Y=D@(JXg*oyKM~RYK`73pyP`_9w1bU1X+atRa z&mfW;D`BGXTjZWH+tA%KHPT3_a|SK0qB_X#?&;}qE?t*G9lrxj3)VMrZ+jMB0uf{rz$I8i;ii$99&*yc$>dm%Y9hVB0FmLC(8L@i zIt5EbDTpwC4sf9J!LS}Eorx~)Yp3IM=fkI$vme{^5F2(|VBUH@>F=-Zahy(#gnkSY zWqv_w1R^U)<15A%z_u3CA)$K@_cX<1!=a%A|MZnYd72-GAFQkM4*gFJr}0?F- z9F%-(JyIl8_tN=2Y%2olE&+|2u#qwAGIPhX%oNmE-ZGJ)2cC7U`ysJ@ z;T!R1;{4$)y6^N;9K0U>ab(1;RXa&10a90`6C6-e@s9wCQp+&H0}pP%JbFq%dHSDT zI(;T>Br3fcyw58#!t76*tOgTcv3w+#^se<5=pvr|O3!;3?a!{NU*QNb3V-XCfNmA| z+DM$v((@zL@9y?bW3|9v*Po(oTp8tJqZzWZ%^Gs(n9`YYXWTuB)!o)qCdIh2)ktlF z6U|)!ZgS&eu23*S-|^B5bBmnkhJ=|S_kkVJ4&M|)K&;aaiSzZTExN_gT7_}VGUzKv zl*rBtR(eQVWupE;+uWMg%#Vqf%7@(suyh~jbp00Hof0YQL1=zL_bD{z_3}_0^9=Ic zroMt$&^Q87rsC3ri2l9wm}H63z3~rBwdNmn1xwn0Zyj*ZtpuG66Gt#{x~2(=WKikt zywf4u1yLUy+-S6GH|pvZJBd<8r<+ZUcZ$)kXFN^tEzRSh7m_#r&h62EciI22DUX`8 zFaI1iP4{W#$L=o=a$eH?Fid=p+U>uW;x6G6YD53gBJ$ukIM7Yo-e-D#(?osncmsIp zc6?glo5?PIdCv(fpCbHv=zsPw?B;n3 zHV6M6_W%FK=*@ju_%T37yEE?%{hiV~3>(XZ4~TTmTX85UbRqaC`nHz^%O`a55ULCT zOq&7c`x+HlX4U(Nle&Y5j<^zL@;M?qOLsLh76+kDTcC?8A(np*-?flIJ)~f4BlvdN zSat$v1EWBUiB1JwO5I4D^%EL0vp&Rf8(?7}ak8+WSy`BD|1Av(v-~fm*8tG8iIfaw z8h3TX-K{kHz(7^H>J`-h#xhcOHYH@8^F|b`SXr1vM1@z9bigA6nbEzr5lMPR_Ht*F zu#PeL;uGbx2Rb>?&yd%3%2ipoiowpxyjrNDXbd5hGEO$olR_85JSxCP-B0@>A(nrr z1NP#*T?6)){tix$EA+g!e3IIBJ`BmSH|ijlnDq9?&+MJx;t#Cl1kL61DQ6G{Q!em< z>Z$b7OCjm1LntLVkI#l$w%2*Z6S7^!u5Gs$>HsWMee`j~@0ww7H+Zo_X<=;*!O7?O z%3y(#V+oV(RR+by`=d#K+Loi8n%9OOT2^A<1R*;`Y4|;i#XlF?XE^=+{_eLw$pF%9 zET@1`>PPYHb_C4&s zvi(0L-OvgJp4>Y2S8hM`j9a(LdBp4IDFsDiPy82w*;gwW+TRM5YxV7PEObs$Z8=?=g`?QgeF4Anf6 zSo)Jx0x}0R{kiUV8#ogz`mYj&S!~O|lCl5?VRN)ba^YJDg@G#9my(}WF)brDz(g!2kwIZ(6r{}I(Ih$Sz}dy=T4CmG8f z^y4Bb8hYTi?`o-Sl!Mlo(2q5;CvSZAusP54y|2>emVE4KYLPHoOZrJfvGxPgFE)UN z7mMayfMW6%?HnVZg+RMmDseSKwb4i={u_K=H#?is3E8TP-dX?^89Kd7=8uFV-32u7 z0{PM>V&9GxlU)W9$p%gL9)D$;@Qb?Lf#>arpxg0uxI9)(j+$cRDb7?<&s(zJg72AC zv^zME9H`H5`cfKO$}1}VmFq}m#a~HcSmCg+brI7G4j}P&fIKqAdrK-d_CnR8EqL+I zFBxR{#UajG$;7Q=Xm?h0J6>0n*e8jT;eJHoMjL%;Ffl2gWUwNE5H}2Juml3`0?(z;?Yb0B7Igc~ z6@z*bTwMMziL(r184`XEV>viG3crWl23Sa(L&7XfZQy_&G_aF6S+v*-4+B zDYtX|dG&S0ewWki4DqHhFMXv-gMhF;df9Ms#NqKgIc7Wamyt?K9U8pxyTC+|{|b%% z$`LNtIH3Rh^=7hluZl%OD3l{QEHhSKK8^R@8%(zWWG@OhiDeJhAd(Bc>`^(XBbJQ~ z%4l}l$KU^;3EK}Eqb{zT9goN_uHJwCDqN_lU;h!fSyC(9SU5{yPUQF@2MN|i2KpSO zem(W})yRH*g>z}B9kR>mog9qv@(__Wp-VP^jl4GmEVk0TJqwv5Mk-p{hb&d~`l}Qw zv}+KAoQ4Bd6%m9Bh;P5`d!KXF#rIpqUKF%PdQ=66Zp7!Mf(u2yoa@Y*ca@-nx5bD( z^|1j>VdH6v1ODYJ$W4{M?BCpzN{}1jj%MyvgbHnG(lb|hd@{6@h8bQjx0f3tgTcvG#$#BXnM=j z({H~bpBM%G6kI7a8k0u1toPZytJGB2ZX>C3|bx9Jhkzgol8244MV!}c#> zyM1tIWc_!i#&U45V*g*OnM_u!?y(5hNu2$i*(Q&#ZpJyud&NtcWWUlNip$-qx;6Ig z8(J@T9n-FjS)}E`D!``tUBn7z!#|fvKW3Tx%_qp|a-&Vg(2f?HwH|PB>@9qIqr^20 ztMMYXk5ogEza;ll@<|7Vt~ju$xmzDx0g5+@Osr@~MT_TG)_k-=pijq~Caky8)B3Id zDh?!HPbvVH(fUNOT&?8CYv*llgFhZUS3qOyrtu0d|9M^Em`A+Ta4x6782J~6`8iD- ztoPp}V|1&wzXj=^(9pI(-&`0Gs7jrjwgRei>qz*{8zk?hbrRRP!64n+z;gvOp{=51 zYFOdWY6G_sGuG!5$tF0t$HYCAv1N*;_Yze6Q9MdFwJoF`=^jbkYi1S{E&|H_IoO-L z;tyAvbe)bFI3Ia?)nfR$0vh*v^4;XDE?sa*8lAxC@C29FRF?O>(YRiMDIF&rou_Rv ziQPXpyT=Zg@Z96ijVhN~@d%pYa2jY#)$Q=NaCe2H@sgZ5|YGsmQ za2_Gy4d{lFWK(ezd@tvQ<_=Ep(UUwLbnZ7FU8gskW>(WCLG3A;{;DM$850G&FWzpp zJ|w!YJwm!}vUPA{sTUk^0 znPiJ1jS$=l9)Vtbd~47NEjC=VGe*4NY*x@#F))wbzZV<@wY=RHnzkblm*$Pp8oHpl zvNgjbp_05)pLWQMy^GYe%pe+Il zY;QyWYkYU!VZo*Hfcq`eOx#w@w{m9SU9bX=08&W!hP+Q@`~;#d$)M(b5SxprIvK}A zdK<0myxmokO8DxDwAf!)84TIwL1S<9<^0J9^Z2LRcFwd0x}hUh(}oK`ru@|%`aZKi zc%50nt;zp*@n zxc+`xUW@atdGB`Mq-Lh!-(kJqm#U>yhY>U1h;{gc6S;$9#9p}DjWZwR6vBO6pWRZ6 zXt|j0tWh_XAy1Z%@0}HAla#1*jeOwl)%tc@b5iAg-LtXL?Y)ZDJ64O5SDzjKD1YNg z>LdwYn`ikntsjBLy;M(DO}pj0`S90x&Fj4u{;{_&peX3x2NcA+j1L{TZGRDgyC zk#j>t(n*)Rw8U@G*w!Mbd!tUe*Jy7CA!~q0fAn?ONrG9SyOa-}T>e@2q4#e$>8y?D zdNFtgxwBUe-TSqKK(E*UE(Y@cHbWzSldnzKIcN}w!%ZVU2@YN0Z)-H&Xn4Z6|3ck% zHj~^onRm9CBEKWl7}J35=+H1ufMf?LzhWDbGbkFNMb(wx_V2DG;eP{_Z>%E zcx%aCLK1fX0`oFK@SMC)|waK?v5E{*NirGv#&hZw#qI$Jm z0O(dJee(1pEQwV0eHGv7>PSt?h^ypS&mpVvyDKO+2rEY`T}A2m7>4LIEl2EaT<#E{@Hf=|eld@Dka*hXrRCc8Rc3ixn!NFP80NTFnc+j2O1kmH>~9 zIA8tvyC*dQE=g^!x|CfLncjP>Ziw2WY#3i|5(jFjzk&conWp_dd%P>{dg`bTqrj6O zHxej1y@4*z93Uv&xaheWVSTqfMK^FF)1$>_XQ-(`*LgN&7!#*RG7sf<*`PP*bGzEC2Pnw{H08hKzs3J2 z{ogdRLB3rX`+Q#Jy{`|a+M!PoR=RAC!}6n zo~R(l?@*R{7Vsi)2l%K%-At^qhC+zoVh@i^)pmf`RB`L`No}*TIMYR(_baDM4gT*D>J*fcw395|! zz$rt~Qn)TkP`#%v}JI76j!FydR}Yi zu~ttuwo_}AFlSVZSk}SY{J(@}tZ!=N3nk{;tsU0u_!_5M_z5|{O)G}XOd6Km`1@wPu`2}kR9_HfJEy3Qjfc=vjE1#YCOc>fdIdYZw^2; zKLX!aZ9CH7eND#cCH+mcJT%;WnRCP-;CFT_tlysBX#+3&fy_>oCKj9P5I z$L<`w!_ePt{)u`tn=hnX7SIBK&T8aG6%vq%iDZ--B zwI9o15Av5Am-_6xDSd_XOH*I(%6n3@6d#H&qyGM~_`9@nmyu1NQ*JUHe5>(|@s#l^ zG^w9Sr#Mjq{6HXM@ek_P`^%$m*r7LQR-pIa?|(s-2Nz6G+5cY=Vh*i1*zKKKnj!kc zR~P#?OLAh@h|)bA7dqwaj+~=DL*1DAu997O;S1HVR)4qMP07M4;5hn}%CM7-UZCkv z-%hM7REf&KF^9n$5d-<&r;8%4sqSjLv6=tT`v?Kq6u%eN`=2SXg>jrnJY(BRDNL8pyR?n%=4HhDHm`2{JP+R zG9JS*3cM$)(^}}~>yH4A1IK_?r`)@)Z`B5~Zq=ZqCAGgVuG z#}6xO%|G-aqd=ODh3Xu}1^W{#+^EcmwQ4^Kv^r@(LSH{7B_8+*`Qe-Oi>WBXM*nM;#V?-=WbITuD@gNMNWJv!I_5$hL#d7|mF4`E4MuG^P`}G1|I8+@BKaEbVR2jam`AK{bIjH}|6+q2`E4D?zpeb*YS&T%w;1y<`=_)NA#%mnGl03X*-gaE-I23I7M2qYdUv(VZvLzne|Hg5gh;Bq6K8Q>4cc}b zJ$AhZDdFv!SKocVTvzvWkC2#4u@buR#1zx3|CVVJeK0?feO?1KzOqbH{%(_f1h_M3 zY50_)$7kF3ElWDl7WZ3{kv+bLciMYfdYsy|KTYmoIJj5ivGJ7gl)1QOJ1MHN9OQLl z+HK_%aeUTg=Cal{JL=rO!Sw%wjsC~BmtVou`prn*jo3_sV`s{)^%pc-Q+1r!1o*{b z`uh^C&%A=UKWR}uftxvfs)g{e$Vz|tnvU$wEmKW3$Ydn@Y;KPJMSFusN}q(^u6wm- z;|p zV?NARab-18J|uX|7Rw2w839^+P>*Z_GbRAh*nJ$}sP!w`y4c?XlM2NNeO8>34fov- z;POny7-Tmq@Y~HtV=x6PhinqlshcSbO~w%N0QR-?vlVHDIK9wP8J_IW z9A)HM4XR*braXTb|GCrqVLypVCr16r=KDT~;HFOu^MW3ExbUlB2*>{`Z~u|gly=n*%Oks4&6UD!_^FcUsbB+7`(R~1u*i?yYz#MPk~PJYYH3FjrhRzxp;KN zrXf^kS4w;?FK{!*XCvpsc1uH-@9>=M;gt*o8P+g40YG_xcnBwiN{HYomMUPG%sUEv zYGytb!=k^vJ@o>~i6q}IHW&^#Ln!un01%*9#hPs$M!pxB3 z^P35)V`rU9A(c%oW1BIr#KB;}h>#_hsJAYMGqSoRU1+_N4Pa;d>yUDnL$CS6Bpz^% zHt=d?r|ZUEM7ZH3OmKPjUFiq>1}5fN;B`n-aGD&nVfoPGJfgfQSU)Df+5;&*#fq%w z%<-dQJwG|eny`r9f2hL+$}6B3{%e}a`OW!|qX-)6SE8^ob+w{Gg}$jVVNBDdYMen@ z7X%sY4nTi~Vq&C1kf}MZufuolOGqQi>#~jSf}9ccn0TAP*%jP@{TC$gnLh z-KT15zi$0Pgzk((QBh%A>pQPI`&V-Ig{{*!0@kO50iEM;6EgUjGcacIyQV zX%}ar%5beF{FKP>)lFdsxoPa;h)J-ak%1{~YHVy|bV5;cF{cM<)@?sxxnS4vvD17i~43R|k?)RLYLq zxoO+E&R==)7pp=DA(n)@xAvB&VSWa^T!N~Uu@JGy<}>vF#Uo;=Z{!Sh)`hF(l(&&# z=ehU*v-js_e9cAJKm#Av*+hrm;86VTOrj49s3bO<0s+rVPZm8gQLkePfB|ekDKKFh4>e`_csyrH`4aGFpwuUcHoPqFH^s548Z}->o`g^q)R7Hmo2% z0-K9#wO912{2YQ6BuqsyzeD6$!7o($wGvBOIMOou9#rgzCkG2h!@<3+?v(HCRJ6Nej{?teFf@MLp&3H*jl^Z?+)WL|TlY^< zR5XT|2ak+a3Oju!FDH7Ln1HH|$FTUiXfQ}fYCTC|Rjp5z@=h(^q_OuV3V#1wqeh24 zr+@7*3{gDLZAVClvOd0_N|{+9zUZbW-{MgH#EQnGt2y2oyeTFC23^=+Cbrr?gh@@r zW?^vi2>DN7#<_f2{dh?Q;5j?&sV7ZK=^$Re{FLBPJG=-NUVYzz|31<<9gESo%qHKY zYZ?YYQ&);+H;PDi%@(JvGkaG2%lC3Pb_~WGxQaIlX7{EaIIW;;=XIEXX_M8)ajkqs z(G%cEWF-2z!eGWSGvM3Kbp(hQ{j7!<+tB3)n#U@$YW8MJ<9i77cZJR5`KH5*^lSkB zLl?{;04l;dV1%vA~uvQ(jh=v*AZM6}|kN1hWNW5!Tef04-Y^-g@ttxZLcJcgu^ zQM&ZT2A@k}Gc&%vmkVlVOLev2MBnm>Hk@r+o7poAX7Q{QJv=mh<29w$qD%x(vyJz5 zEG=K04o5Hnk%Qs0$@LXFU%IakwXp0cf|^6U(pcM4j*r#&RS}eO6c3Etz36M{5)hSA7KrF2B*K~;3dC~@P64S9F;~Q{ z`wDVxi$1qR8D5SKXHCdB_R&qb{xHvf@DT8!rG|^js79JkI_=>KA_g-cq?Oc@guPCg z=UOIChnrr-ZKenNgM;mRgZ+*tD8pWP)M2Job)9-3SrTWu;lQ78&&FnS>dkm5lJy(o58)lXr9}&3#$)vb#60@oarXUpU>EM z{YL$JoFwC0t8Rzpmn${rMwsn6Lgrr_RgJllEg|Rga!J@+cBZ~t1TP8^b9dUhRNpEz`hd6$>s@Pw#3O}va)g9m|KOevV(V9E;h4iFcXSj zu(qp!tHL5|%hMWL!4gYCz@OPV=elqieooYAjDQig`YEejwi9Dy?iHoZnuUpbMm8p;Gr};Wvv8`u!ns5&r!jzmUK1l(fc| zMIrS3{6q|NRJEV=V1@L_+tCUMNlxC=o_F)CMhGR(+daf$(N8dT$M1Slph`)WlD_f? zl<<;Uh!EfuJG_;s{53WVXA;1iB*EwUS#kwJm@bz=^Q~FVKPm zhRnRAPMEHM4uGcqRPR!_bJIswb+x;CKzUjF&5rV5=%Rh~R%Z2#HYLsLx)ui?)T$=~jXQ)FhR+Bkp=Z;)#14g_qp@ zP4qq6!FwNCM1ZRKcYS0(siLWCLsPO;C_*1!@dGYK`{ojNcgvVb=t&B6;UaeUwvf}`f^_chTzuCfWqtr=(Q zl=OF$tR<&{Q}lO~MxGZ&noZ?UmkT2+0`SSgKtqi(pOdrKJa2&O-d1}9sQ0VEFjn51 znCP~R76!;A@e`6DKa1WeLv9ma6;!SRLNLNLD~%@1a$18st~l%@mNiZR;~K3-VfL)l zA-_wxphUk1Gqn$t3pm#o^wTBWO5?yBu@onO$Ugp(M|}O(8Aj!$Flp1TCM`<|C&4^* zi{vwaOZsfjV{&6i86d!%S)|ScLy*(nx$R~Y|(dWrOW{;?yZhHM)!lki0f%l9GIHx`F z{XwsWu>g299VtL3o;K51{EijkZcl#j)1@xu$E&NB%2HSSGOwNQoVzr1CzfF92pz0; zTTBu;E$q}r^kW*daU{ng-@y>fzj{pW4Aq1|{L}Cn9?j*}#1@a1s_o+2+W%WBOALrt Yj2FvQTE2|@{o~B=rs<7}>#ouN0l?oVod5s; literal 0 HcmV?d00001 diff --git a/docs/assets/flight_controller/accton-godwit/ga1/power.png b/docs/assets/flight_controller/accton-godwit/ga1/power.png new file mode 100644 index 0000000000000000000000000000000000000000..a7d5525fec3a6f252658b4c15fe441bdd16e7f19 GIT binary patch literal 19514 zcmcF}1yEegw(cZ^5Zqk@1b4TA;K4&6I74s4*&oVYP?W+1pqvR z000klpI`w10O~xmNC4o`v9qCxkBN@9j4jwrz}gOMV=wT|%>(dPlT&!-VQuST@55qa z@969fWIgHZVP$c)1F{;6>j>$1DBC+Zzkqnz8$fgoZ6PkU(sry0@+@-iWZt=XxY_$y zv%GV2b@!He2W0&RuZ+95%wK9jR+fK2d|ZI6ihns|G0}O+q73%3XOR>T=C>6R5@L~* z7Lc~JwH33o=VK8O5)ly;5)~8{;};f|5s{D)mS*{9W0hx-^Rjc0d8MNEPiJ0s4nS5X zA0H1HK|z0ie*u3{0kD^&ps=*Gw4jiPpoj>+mz@K@cYwQ(^*erdZ?=CisMvekdO3Ue zID_3;{$jMY0sHy@Sy}%TgPX^{Y2Cg5xlguWH^Fz-9)iLGLVv~dk6`U=|BdtT^>Y1( zb30o>dsllmdv_miL16*me`7tIz&>DaC-8qk{qO1jeedlhRRdmyWbkcc?H&|lq9SV~4nQbt^uS4c`mNa$~<4%p7wA>e-p z6_Jn;k^E0kdmn2%Yai?XBiPPX#sTc*X6*xHb#}9Mv={VncVuPx_cqEXgI&R1I$%3{ zAgkyv;gk{z3x)U;$og8>*^%XtU8!ve8gNp?Oef9smIN zw+w~mjf{-`t^Zru-QDxI@HgylnT>{`zPZ?F)?vRM@M~q zLvwQrGcz+iJv|*Aoh^w3c&2_td*5jYiny`V^dXCH4hID85tQNAt5O#>D1Iz zJpfQ&-%wm!(%jtA)6-K}SOfq7=;`SJ06=eVUweDUz`$U2b|P7z}>K^pDpU z0FaQ7*wxkL>gw9n)rCMHr>AGi%Pa2h@Bhx!*RP2F{(;@y-KC}F(b2Kn+uNg~qx(s~ zJpjFF6A8Vmsd>gwt*E-pUB$9?-YcXoEVxw+ZZ1vk~#+uqs=aR6v5 zKW}Vo8Xg{QZ}0GNca4dO>Fn(4?(UwPoD||<`~GdVva+hGtTa40u(!7ln*CW`Ot>ct zfI^{~nwkd&20L0?9Nt*g)YP!DvMPuG+S=MnOUtIGXY%s$NJ&XgPEHmV7aJNH&wD0S zR8)SQoTJfbQBl!F1^YQc)5E-m9snRKE9>>^*Y))cmxx6KvBK@z&YD%oik{a_NS4VH zLO~9IgM&kIa9hs5C@ny*6m#}=z%P&di zqjMLhb;$ys+jfpG@BcrvKZGTp@&Eu9fQE{q;k%{7+#{Fe?@S}fc7<$n`fu4rnm^P# zjwE)L=zs%VIQNuWB4(obBKy`+%jQaN_<0k2>6cON*Q*OZH~a0ug2pcz?8B|*K7Yp7 zeTqx*ixrnZNw7-rr`LTiYR#KnVYHrMBGHC->UMMC6W<*}?#1-U2KvS0(3t7|ym zD}q8IOKioc1B(OM4@|a;!OuL^;f^d@xPmte*5M=dQ+R}ChjxLfb{3JK(1SrfKMHX> z!Pd;QGX`l$o1uFWeaQ~K%50k=XD|s--^SOj`IdLq;|HwK2f6hgf!FdEq4G4!tH&BDqRMQ7wDK51T+_x5`XwE;YSzLrDMptA0^s~S z9bAqIU6R1EVPHY$nqcaVvb2dGJV>w7cGVrMjsxsYawNi(YLCm4nKLO5C?SgTDsxdkoClxWwQ?`VHE_k zF#nT>r?Wu{#rh(N&uCN$3#Xqdp0wrfX6_hDVw9BDhH%rkM`sjYe>_DqDpyjc zO|hSoN)KL}g5HiM5!m?RRQ)%qb2tkqc9;ozu#vi4(SV0n0j@hAbKzW}62&blI$cOYe#ib3JaO1{(ODIy{26DkGA$wHbj>qI2yS zrcBTLXA6o5$*XnN*1<$iH#~34rkh?{7ap=HA)6TMlo3+6%lF6kbc(fDz(Y%Wl0G6y z0X%~Alz^az611CV9ZYEcNnOkw6WcYF>kuSOV7M9`Oz_k(k!gb8q>%at2QGvk^PvqK zepWI-8PUd)6z@5(zX3goWZGWH8ic_EO|=EBa-*+!j1hvvt8vh=(<9~N_$h%LwKq(3 zY(nUr-xI-Wk$aYEdV|67;T?8+v2v>zXTnqL_k1M;}Lbl~)rEq<*fpVe0){-du~jC9hVEl3s%hS=!OC z{I<73(0jh=S<#h`^hkO~uJO-;tAda^ppYC5yf=&Y*@|uCN{t!!AN@gysn~(Ntt#bj zU@cYWUH~Qhx@*E*btIzlqD%i}vp(u8vtayd-`1*=iKW)eTxGrdu)K@_e2fDNL2FAl z)<$Iej~T047(<~T=8>tNM%00NI}Q0vY0Z*%8#o%J(9`?1xvsml(RkUym||xqW3%gR zwpY;-q?{|ep}Y8yN^)GvYr)Ky04O|K`kBHu45j)+u%$(JviG9;ft(*+|4=tlOP@5G z2v2}!UbLnpKHd$TYfEk^Vj&7)*#5exaM^RroqioMw$DSDTi2!ksiEEd#{Ob{zXRrc zv(D{2zJ!VwS-Lu7Q%Bm;K*?T>eZ+=L@O3UM{p_cabx;C_*=HsS(BIi*+k^Qn&^sQ^ zGD^ap)CmV?KBL4btg}%}O*)`$*B-2oXT~%y>6#9$I~Oa_UY_7LhgXJk zac>YdX*PEpm@KrIR~t1!)mp;8Rx@Js+C%+S#*I+FK+1Q1CRaWf));w|%v4?0h6LFv z>Q6=ion$u+4@8Omn^5=aG`({xWXht55Z>dfc;fg?_JF>&sVmK3o`T=FVUwrRK|aS|kYy}39w6un_wPn;TBjZb}M?}e}4IE=v*of%U zPbI37Uj}rdUiJ^%+|@(AqkZckdfuPAD8K2aySefnPP`Fu+^(TVr|wK0RoN~XzQm;$ z|Gn%TjFZLneOXO0yalFCy4FDiY&n=_d8Hl4yuUc{{iBHTtv-5DugWnID*fHXa^(+N zR0S2E{>6~1yPN{`U5Qc*DC125go`XK8<(G3H7V?C5)K6}<|RD=-uc^^i4@J;R)*fktcV9!UKJf2uR%vO8n?_-ZU+-z7|&2@#3wP= zfYp0^>Vq&;K&PY()IzKP2aEh3-#_2~N|6A;Pj+fgJNBL8cB3HE&ZqdNU)u%lXY`&2 zmX+qr@o{ZHdBdj6`Ik3>rIhECleX21$F70K%vw824a<+)1*Pv?Y4ZAO*>ty!mc9MkoyMw$yaku2;JAIMWn z=+OL;Cp73)TtV^a*;1b3m5&=RF)VZLK5h(G@9dNbSX?mO$|)tKx-G41pwXDyIi&(- z_QzF?SX)Od(fnG#Nm-8oCLua(d|lwbcJRCGvV4aa&iqv@vj*{ftw~96g<%ChA_qOB z|Ng*#Xg$t8d)oGAs5qoB7ah#0LEl_e^rON3*$MK{-dodIr&434$JPPEf+h#bd1EKw zuak%x%OD3Pgp+sgS5}wxmNl7hPM^k#K*c>`dKo^zUXnd@R!UK`m?*Z0$VWCQZ8m8w zx6XAR&UPOj{NXneh|qiyPlcznuQUgpxoVnOyn4ZVG;oV`g)m7z8ng}kvXGQ2b*6>u z=9C&Fvz2xG6+FBx_zY5j3u|L?3e*hHoZT3vFOVdunz`de+`peAAP+6? z3kNeZ<}ge`i+lqt1;)WFLDk(22p^1x7j~v}iym0w(_m^OJ`cqEaDhfveTH0~E+jb+ zeMwNU_u!7rV(;qp+v(lpo0;1CjfoL^>Iw3nlTn8o#>U-L!)*!`d#W_Gnbwt3(M*TUyb6N(t-{MXmJFES;`l(A2XBADD71Of?$Vfxr3m%w;W(w(*?oA}TEuPJi89 z2W?cXy9W?1@t&&wvHZlaiH8vibNqBQo0A}-?bE=9o?CwC9*bJjEVhd8^5EU}3P@ZW zsI9%Je|giGfl@Aiiyhbd#BT9-3lfW9LL{FJ{VAmP>l6QR<&^_m%=^v_{E>T~&aSA# z+$YsPr)uTyadxWX`#=Q)=^BcA-NZ`;t&T0&tV_FL2N*O|z8I=Y5g@~(X z0?Tt=4P)e)a!q>XUEp1h4=Ha#(&eedt3ldMmz%=x)ZaDHbL=S=&Jpmy%k~fkPM1)3 z;YmCV@Xy$w1-~0yRB6jf9{GkhgUyN-qOKci4;k82pSa{(dWz_VKfE_@FDs5#Z#$#- z(s!bTg{fLOz)s3<-0Vg^xJzyV)KsGfXs7gsJC>1oxh z1)jSu^FFDqGie=|Qp?c+TT?q022vB8T=vp%&L|@!A68AEv$(b_lc8_Lm0`wpFKR8% z50?gN_2&17+7jYGa>8oAN*$Q@_Xr`qPFxDdc3#+fl~IZSG~*ynKMfkv{tNIp5dkmqLZ8E|5o=-uq>rIUE*k9zr(vE|iAe(aM#-69ff%RJxRU3t zD|o;!7H7K`@n5k3Yy-LTt!wlzXS?M8NEj z3j(MrDUV%xa$7Q&HBY{hNQUpM+Ldh$1$FK$)^T=8jl)qtfKjngxDebD3E&qC;e5^} z$ZwUkBA3hW&mgkplop6Uvpp|QuVPUd3sK`$>!^?yz4JJS&5)x^$5p08ltikD{pYzy z7b@?Xs7Tii%VM`RN6VTDQ&Jx8Ilp#RC+aWj`gp~Pwc$slnK#17^+yd*&xg1E!RLJE z$PDuCGbzE2a-ko(T@h*@_!#pFU?)m&d}TwLgYUeOanw&eXQU^okKdUA<*9Z21eM)3 zZB{?=Nc9JRrh3_C4Hr1zlkmrT&LwG`Q6L6Il>-mY6@Ao}QNi_oS?acF6DPqMH=D(; zunG=iWRg9E4U~hCTC=t4dH=N91^wXdM*P_u=FbmcSx0pPL=`i>c8ea^Q~=-*Zk5{DlKA7IF2sV068l4!co;%xKAyE;9H@?L$B+@?M2 zohNs3g|3Fy46G)blsF2@*QMf#PEtv_wegpAbmMb}m`5YyN0&8B8!_X#oQNj4Nb{W5 zFaXH2BnSC8F}mwO;~I7N7?M7PAw+ zRU;hIc9UFTIyFC?@HtamkZkx?ZCR*=Lq2i&y1pcFrIQ8@pyPJ%T~Io8ZS7i*Maws6 zn@OR|C1fjnqLMwL|Q)Wqz(f6i7=9(gIQ$Rz1vvOPJ3K{j^srGxk+6*LNr zukButW4?U6K2in+26sDU0cC)e(dNmZ#PABH+o1SyZ%M!41I=A{(=qw{GJDoQrwA zOm`P$e}#VPKO62}aW8q5P7houPg(vzRDpvWp@f_*VaBU7G7%w8>F|c~KzN7#^f0F} zrjj;yb|ZT+y0hzg6uo^g;xS-Txf{`i2nauLiT}CsFvN6b_fo`ExYkjgXNdrkD>^Bp zOkAfG&G4#b6?8`SUYbBO^*dVn=}C)BlavAw4wnM{_WM)f)ia-6A9b^zO-AYa0TiuW zLxP#{N-@(Th71r~;)!-dBx~1dm+p>Mjr+$gntLhj7(pG|U1NcCKt~wtA@J+=Q)k2s ztqjoT;{;>AE(|AuN9Tc1UV-tJRnDVc&C1=FE_~cY&Z*X(n6=+CDYrm6;5glJQ?hyn%VaV2y5aK{R07)yX5j8N;AO5QEV*S450LDR8}6cx2F@I5KkiuM2Y;JoKNxXA#@J zCJyAtexYalzPG(9?!^gxB#Iu!=3W5|H$p%RDVPm+5VPpZi4BT9Gjl~+o2UGdFUMn` zB^6~hNXF$4MYG%^;o^IX%nnF1AkIZV>GmV&73d@m90ue8((CJgv7kMog-uTgPjZ~~ zc@n4(;z-bNloroF&3PI<)Ne-4L<#3gkWo3wT=T_z(T<86l>eeht*GZqykHn;2wB#K z&2OePm>fHP&_vjI*+Xi*YUiJt_uk13V7*~Q;yP$?TwEy&PNy9V&KvXp34 zkRE%x4_{Y4wENXD4)<$SQ|gR6S^~o4ajFh*kD1dipR{wzs^XT)3t= zm3RE@7ir zutGTI_?_KXFBf8f;ekLm?Ay17-|9ZdrGxriH{$Dc!nfn%Wi5I*#iT$dpyYh&&k571 zywVxMCC0~00d#@(P?`QIyQe^&w?``pIKtj}KW4YdazVuvWj{|p?0O7gV>pTi9&5Kk z4u84pS~-Ajc1ZG64Z2XFv9Twd`Ca$XM(phy@!q1(afkox%{UZEu5K zQcB5@>>cS~iTz00*0f4C#QsJAw?D4YpZ>7xQTrJFW2}=!^08%Z%L3F;wAtyW-RND0 zZd8*}vg`u#aA1zFNC#mzNd6E;n#q7L4s%RmYG>oGSV3>l(+)5?-@HuyF*Z9{v#rqj z9onS%BI}jkww#65Sb9^-&(M+zr=6EGy>dHX7laU&e|vbzp6S{{fhK}^{?trFk6St1 zg$^iN8cGc5RYBQ$yz7fOUtuhh>3T!e-!z6yTmCxGEHzoDesWmk46p7!f8NNEx_71f zHDS+F4gBYRQMMH2HOV%Yp9+jCE8-)|dAMR^R9J?U((~K;ioup;?(EFp zBe0kwKlTV1H>tZ*{{u8zdE`(;4JKMv3P$x zg1)w|-2shY+`aiCnaHxg=c94|=R7YZCbC@EDNkoX2&7)7VmsTU?Z#tG|GOSJza&&)v!nbALrB5q}Vvo;`fu&v*&J z=7mGwnb<5&`SKd;3urB2W!k(t`(j#)!>|M4z$Eca2VRsKE3@iJKX@PD4gqYHiy2;l zexJ#TL7czu+Ai+xIk!C0DiNLNmM(JQ`Jz>zVnFz`p<@td1uOXR$PCrUlvpFFe zY_?`PIZPe4MivD<%j28Q30RHP z_p>Cwbk=$pkn%7LMuN6nhldvL%#IFMcS3{TL)5^>PeTCq`>xX95V`GAE^?n6KhdEzp%?AVi2q@js%gW0)fAIvkz4>seem3w?2TgW6!PlaZO9Fi57ydN*~=B}c+*ln z#5ngkJuwTx7{IHB?U;f1LCVYb`Rt4K4O4Hsc`OVq3s@Ooh7y{c!Gt4i&szWkCBs<@dpy1S@cj?Rb1zq3fBgPj+UJ75chnRU zew-Efzc0+O3hMI2fv29_sp=WkoIY%rT)4Q)+cVys|Fso`a}3-&D}uFR7O5h301S$l zYG+H*bp4{>^VEkE#u zUcPl zx3)-SuumDI*dM`Dw-mXIs|rzV?|t+6_p8g%Zq&shg-uq^!yLVZQhn0B$Yl6MX+j&@ zz5HR&sr(9&h^U5UL#KK_iq~4kJ1R?j5$4_`*i3uq#oVcdXN~Pjc#se_LwO`1*#|?w zIn#|K2QGF``>-amV7?ww$z!^I^Twk0)-|l0fVMB_Ai9W+rGjWvG1bwziY{6rNUZynhdENq%VMTMQB4GL1?An2DOq}L$Xw%YPIxWH zc=>~Y#~7M$Yc_qcsBO$f4}5bVrkdn5PH~K?SXojw!AIOIsoQvwrz5JvywRA#^9Mz8lowIT`+EgHg7^W_HmD4lEFHTIGR!=>qqw*U1n zz#pUm<90w)N#O>800z~Xi{BA+{U9WA`QBYE;$b}xbG673n!mBC?~AKOZus{yK?zg8 zF!4JQeRB5*u z*Vz5$8$)9sskcbgdW0FSs_k(}z@a${gcAGH^&V--g)pdXXWp>gsKkv_h6=_;F`)Qy zB#1*--Ah>V%0m$GmQt`#z4%dB>>vzSXbdu+`>_FA-x^gG)UK?=27Y}nm#34}R~gP> z83Q?=Zc3JfHv1(+u%#t{7@V&g%dFskMte$_4b9Ci?nYi?lmhm~f^OQeHL#QAJggCv z?oluVj z;iP3Ad0(@TvNOn3dU5x|4HT%oE>(>La`Argm{WK!7sp*?F?iHBkx6Lzoq~bA>$Gn3WaXvX#ya5ZJkiH6 z>_EOwPdLAQ6f~9I`onT%Uv)K=cqNVHv`+|a+WuzuEAUQw^33Qk9pzmy(2b~;n zk5fW5o+3L(JfnZkb<(eN3nVNBeM^hWaA;+rAU|)7c<8|>yyxB*&Tnr}Gf#6tU#CKR zua+%*6F>$uZSOabL$iOhY9Sj9--StpGO-`C6%~-&1VPoos>eF$HS z(nM8wb5O{Oz&82s{-={*kd-_>c2{eTwUXX_peiggPA$9_8~Cl2}3%PtwT*~`gVP~Q7a&(6tpzoe311~Z))hejeze0*g^Fq9uA zu()zQ^(g`r<%xVHkxuJ`$(~BDlSuvc4D)9T;{7ayf~T&Mfw$p{{b&vp6lQRd%81PI zd>iy>MJOL9k+NR6RAtezbJ-$xxDu0(G+^bX9C?;qku@K%gK=z~4*#=<>*s5x1YRNo zCTS__IM{@v#?u-*Z`peyo`dJ|<|pfZS3ZJKYejA~^`8DNbgc5I-+{R4!kY8+LVTIw z?FeP$kHbo@kpe6XhcXe^(Fs2cOa$fCd5= zwpg^4xr%*W7`z`Xp0#kqbc|n;#lOGbRK|iJ-*t{DCljkXD>iG;(m_IMx**|%@OvoK zX7WlG^txL)ztn%#?U;{&53;$@;YTzd3gRMt!meZo<4mWWA&vtlueqYDr8eMZ?xfU1}fL^YhAgH#gQyG zP>y6^55(Tv_ibWp03QtrTZa_sHX_uEq4a#gG1R!bo8eTL32`cM5El$)-2u>9~l(?dtFM*YK0t7T%|2(yn_k zu;>IqzXWoDk+hAt=M1(=dhPlSHi-0Br))8(sgdL$)|2moej4a!h(%T6xDqx0?E1T` z$%8)-8i-9Or-j}1?BWgpXz=hg4m@08+|?72c(%ZKC3e0oJ0FWytf2b3r1+Ov;0q|P z8XS~eG9PdGg(707xJh`5gdl_hrvO!)K??{^Y7UVrVHmU zU!WDI4ISxm;c+Cii3?p)R<<2=tZ`fEo0=*VYz2h|7S0dh@7z`yN(=n2Yh*ZAGtzjmb2Yxy;Gg#i>$h z>KXS}L7-6J5J^UV$|C!v^ z@n-upW#Lq!`|TnQo<}aD^rx~Pbq7r?Jt-ochw!{Y`hJpB0luj$nmm@TQ;UO?bY_{W zUmw;wYl}hbIVIKzV$6+xV0bLLl7pYqZ}?`q@ajc4woly3@=vDWvR&N39!`n=>L~aqpeB6*II}lGs+4(6=fvnr5hr#EiNJ~RO))^jt@%mC#j! zI~h>BW>+MT4${MMSP~2?ye3W_3(s@S3k6Ax;ClaoWhU_}+4nCl2?!)WJ|!l`(7eOQ ze0T1N3`CCw-nloF7Wn6#hDWE@?cxTELp6BcW_hq-i{G%nMeqEeb1zcd8Sm9i=Jiu} zjd9qVojuFyE#wpc2S$Ks$+=IC+DB0jR8AN-H&__q(M%s(TcgL)CI)dOIVvXZq^K^H zaH)1QnYs7f&VNCUn(0-$KiA6304wj238=>X0hJ^8;5d866Lv_sA>W7e!IzlR1f< z`Hc$rEdx~H;5FMO`#m=46*V2zWfw$?!JQT|(tRJjf3ue9gl-4=V6Jq~?c=E5lKYiU z{-P3rbonV0(z@47N0_(j&+RO^aK;5a%JI-EpCwnSJw3z&1ZZeEYGsp7n00*s1y%c^ zgU{ynZ;IE@S%uIEZvi(sPg)>rz)z#ZXZvSeq;TN@YxfGTVzA@4088Sfci?qjplfUJ zxhN*c?j+cMmOvz+scha_2@$=C7r^EwL_s%*-yCXgwZT@dCkW}TyN=Dldx#e>N$wtx z%*l9+Q&7tk#Uz+Z3JFx;M|0b^V;=?|ZtBt{%9%*MdIEvlMU%oUYQ)j8S+BU+=%%-9 zIyl!pDTAM?rx8=^7pS*o$pqe^3a-J|exhaDdwE|!Fu4Z1J_lQPd_d7105ua+ryE_1 z9tkbD(UnpJL&EjN z#NUU(EV4f5<$Z(_VFtak*iCsl_*9*TC>yrob`Q(Z!1HW5Jjks99i*-!gTbNv;M272 z^)}OpnXoOon2ZO*eRDKtyYy~vVPc=S>6MqW)S8n2IL*7j?VoZ`ld3{$dwE9iyD zWpuzes(^S~A35>k5LPN)@%Dft-}q6!NuXN?mQRt3G0%fKO=UszV1uWDm(e55XPak! zm-zI8bWGxsQ2#hoewx%Qx{fx9sc@B8jQOK^KPp=Oqq+*QhAN>ieE5|C5jsKRgAVBr!>$P6A$ZBundi-sR~9?9716)+S!u>YMyHq#!-s%LI}(7xB|7e z3q;qav{Zph14Gq}=HXBo`THdog>Z%PKX`;mp<6#H+j^j*GjWSX-|)EtUAIXKp;+Z; zN3?0Gabt5KH5&U9Q0<(HyvD7(%y^u#KSDMYXRo{z4}Qsk#Agbu+SZ3bwO&oPYDzK}_wXGVIJ9P?x&uH*M@CV*} zcJ6=uM*r5S-Z5P6_KH8F8LC`f2JFl$;&RBC%e1@Y4H|CyltCm9@rHn8)$9GL3QFY> z84e$l93JHWWw#58tBhai%c66q2C=QBGiuz5vn*7xl9(2?+PB!TAeqw_%A89bvWx}P z6j!dF)D^+?=s3e~8D7sau+w#wULz>`%}$&O9NG4Lulq_|l#`J7j{~np*sq9sW%U zu*Kc;rR1<6x&xbVPCYqo!wfkqvf`1`Lb!<9`~C|%E~ez=4En|Un`QHZhfhLfD!(KjJxc=$(fW6Ja!Vn03yY*|%-#BAd5bajQT0-yjZ$T^#bd1p&-Gk}Rvg|A9Wua4ecD^z z@1mQNfa=?y3ZbZmAs))+`L5pJPUaV=p{eI8@D}n7^56{**^#Bt?mrRBlxmrk#kBKQ zt?{7B1#dOz&ppsuVY6$!rs{7M#39d;CpP0Ug5crPC+J9PqoqA6h#A9>=nBpqcuB2R z{7{;m80LQzMhkx(!=%Bp&k5l$p8m#hPDR;LMB;CVv_*K#2``OYw)($D2I>(8wM@HU z2kMTcro&~=0|_}-@E~WJ%1<~jHVHa20y+-3=vZ;gx;X_EVsO1vPhN5q`w@KF-FP}& z!`=VcRGX)|5z!x3oIK#j_E?DVx3=qEzK_g>`Ho;V9UC>l@9+9AyP0dIQW~I}9qAi> zxilO7h3G{v_ju=gnY%)m4MI8~yS=~JpK{0LM_KDjrLP2@Bsc>DsYyuN?gL>vC-aI_ z2iKtwkxT|r69UX=X7us?@xk6SG+6N<}4k~F>0W&+8tz^>(S$^hA_hV`C}du zNyHTTORl+1gdE@Gn}Mi>l$vE6WP{1KV7|7Lb}fCU6`V%whg$;cv#F&$w=1qn19$OH z2-0Yczs(lj<%Jl?HQmK>^3}jJs*B{)%H zxbiUX2N`T1F)=V4qF#rLAvVxMf^(wH1w6(-U+|los2Wgh;Rms~DOOZn{*d=;Nfd|K7U3Y|R5NGk`P-!&=_K1k~+nI-|?ft%_+gS7;UiNd0-Z%QY z*SgvHGbp5dX*ap@ix4nTdhx0H#jxL@<%oWY&c6GMSS!cVr>i7%Gtd1sa-QW7F3w~k zb?}zu{aWvgehTqAi;=zKHhB{J;aMHwV}*s1sDNBpG zJGJ_%c=61O=@YN7;IEz{x~jLmrcv!?Sn%^I*t2LCB3PZ|n@1Qrx+y1^)3}xi}&iRauM9z|##yPR;TZ|^5Iow{H$5=|+sxqC|z*x)%{@YabdX~V3 zUaEH4?n$(Hk5+rE*uY=__ZR2UXXn@T3P1BkN6Z~dw+@>%pmsAua;TotaWAmgphP@V zxy1&<7qx891bcA${r1g70F0XXvnTN=@$) zZr`w9dvCGN(V1W4u+fx_aUd>#Zi5Gdi|x$gPHN=NkI$M`{)7Q{ZYfFC18dE!vQ-b+ z1JC@ZPhz&%$Xi=deu?&w0o7zQn(1Cc1};F8njBgb*tei@WPE&r0? za(isKNzTW-(R5ET$d*wNp|Mu)+_m$~lGAU+>m+;?fd2HAvQ=^^C@OwmFX(9w9McaX zP&XL1t#vz3IZLErp4hHe4Jqnhzgiu@iasN}uPn%0`^c$T9)?mWB)7Ujlvkmo39sCP zfVxrM;SSWQ(p_I3Fu3;~i_3D=D5DpdHrW05Ko6r`ZTd|Pn{_}u*P7ep*DAko5llS9 zGX1(Ugid8rs=kDnAIW0hf1K!cS3gfKa1)&;O8JAIBS!q#Q8J4wnRJGrk?p0wSfMWl zIp8SQ)7=j3uMc8{ijf4mrDl>gvgXC@8qEalOCE`tR7Y00626Z*`tT5FSFc9Yf*rg< zt*Ayfuyg3%$Tlgi@G}HP-p;4J|ySu!N!Fj24>?=NtmQ5xft` zrEA5QtsBaayg~b*pvD%Wf_cNLU0G=%k5|W!FQV0mXcqUjB<#2_AMBubjf>xeF~|{T z`Svg7Q|m~sr-PMIK_9AEX<(a)>n_EelHFeiT>u*^9 zNC0o}MF5bm=8p068{dsW-L7HfwU~L=UJGb2970i$Ws7xTht_4eovaCvj~==?IcDwmY^1O(Y_V4rntv631SeufAdKe2}YSMywbuiabLDZdpI^C`oa-w6s zR^`II_q?YHB&+z+4vwCi_0p>;dgG%LMKfCIl!zCZQh%}5o0?Fnk|`8NOztmT>tIE# zwd-RhQY1!`BW5yUDO+?#dDaA7T|f3{G~?}zCvj!M@nCJ4Ru+9d914Lk7)3pSY_I(9 zrFU8Kij{melo+n@qZFz^kzN{il2Y0*Dx_^ztGi?rlTw}nOA=pwR~u`MmQi&br&#H) z%}t{29iC~eIiHoc7@OtDW+g=mvpJArL)@l&_o*Am=5$N%lP-E}_P0|(Y0Z4jtNDZ6 z#oBpqRJOzC3&+xZ*J>$XM2&OQ?loZ*%`JFJc*UAnNoTUQbiG<1gAB}j!N@x{2yu7z z^e(M45w8LygjnS}G&7n5i-hVvD6( zOPz?V4MjStM(tEd{j^Fo_zaTPQXQnRL^{<*F-S!?W7jm67<*9-l}IqvU$hfTzhgSz zeA5~8{&UZ{=f2N60N8v^X5(kvLirZ!MY7)h{vLLm7rk3AW6jJmWcGexW<$YmokVTv!WSo538 z7Rp1uHwAiZ5Yz)KDYPpu!^8#kdD_uP9I&4oq@ekI237I8wq zAUrc4M&aMy7aw{h+@tD!(&bk=fpNH;&kN^(efDLDbFSFl3@P%cEZ~$QB93RJl~-N| z>AH^E)vp(W=yHkA91%a_rh^3YQ}K1B0Vbfu z5&h(;*6~PP(0j7vK)BD{^dsu#Mpweqc0+*b-9URDE5ekKJ^b`?am$u=`Oz=9_Q}&> zH%XHx@#)zkPd(~q=E7wlKy`L|K4#cZ8DK{G+g7VlQyyh5P$ZDH)ssBuL-vxaqpQg< z@+f6U0}Tc~d8TMvZNQNWIov6Q%Y?%ZFjhX3TqtHS{@1A1&R&Y&*&bs`|0sI&k#Nr3}Lo75RPJ$ z)0%Q%7b0{ILP4=Ib0FsMBLAiM2Zw&N7;_>SJ5%OZOcFK7`-h{-b;g@XwbDG%exzD_ zq8wYCm_q9C&!~q0n;BS1L^GS}(lZPN_9rGCTapIFdys0V1FQP{JC_=6!eno23`GSz zhQBr*ipwr>vx%?Gis`U0Ar;5Of9q19BI5224kieV18dG{9T{QJ(1#pdc(ZJl5~9tF zG1D}vl@%-YtCLXf}e z35IUC==s)AZV$@eU+e9yiiK}-SR;eGQY4Uj$Z$#GbbB1}f7DW!*~IkiOYZh-J1!+W}4r{1lJ~`v<_0 zL>MP^VK}rtCnpE+DZM&oy!Y9D8=E)mIOi`7m;|(+vjQKE976$z&|rmQi1kH`0&skk zOf}9o#yy5PG)i^P&gmU_MgxV5a7 zWlQW@`4`V{*5Qaft*__V_9jW+(Y(%tEls-RvjVx*HA4XpT;Kfy{blq`a~l|`aNPEK zr$BZ{5UfP*;^V(ch(!Y&`#&syk6^ne9b`p1Sdk7ANm4`-NQ7~6VI2D%bbpBcMe&z1 z|5SV&{{KecSOie#?LGCOQ5m0C;rJzAkwV#k7rT2q5mq^q2iN_xSRpZYGbgX8aQ&U? z3cF(pm2PkX9i?BO2FEq#`2DoT>0A8pJFko%c{;f;V2laT+0L#4)4Hqou`O&vijPdL zkGD3zrV7k_#R>n0gseb}Ti2ls=BmtyFvjVq{nCOs

W(3OoKfd* z!G4lRKlJ0ycUZu-Zl~z~OzvNo^SgqG{f$P!1TH1v`PU~JB}Aev7d(FtTF>@6GkZ89 zabcV!^`IvA(Ze{~OXmOp literal 0 HcmV?d00001 diff --git a/docs/assets/flight_controller/accton-godwit/ga1/radio.png b/docs/assets/flight_controller/accton-godwit/ga1/radio.png new file mode 100644 index 0000000000000000000000000000000000000000..6f1aef9e7511ae08fbf035543ff29508f1047cc9 GIT binary patch literal 25716 zcmbSxcTiMa)8_yph=K%>90UoXLzJ8pL?k0HcVNgFhMbdth@c=rkt9)3(%hLL4mn4a z3=TOX!6Ab~6x{N8-uKyezuMiec2AvK)z#~OjnUUtr>0`1f z&ED6VJJ8M5-A67^k>@X7Id>nqKWY&k?!O?uE{Z(&|2X6}*3suy_3*ammKGL++KP&b za!bn!%i7x7-nFy8!!0f%l)sxqr|P?ZRa3o@ZjOUoO#JtL?Hr&!LGHfRflzlJ-hVSZu=la` zcJ}mj_HgI^!)R^e;peN!!}ISP+&urGb@%z#KG}M>i3D1Eiiin|{>kaDWbJJK!Fl?5 zyZ+_e&Q`?U)!xnC-PcD%Ojzt6tf!NQuZNG5$Nz!)pXL9>L7-T$x0{Wr|V z!@)Pe+S~rVqrJQDe|w!ol(-c{{?y^$d5HYi6#rWLkDC2A+~C2(KjJ?vNQwJ@HZgm5 zJ4GIE9%UuX*Xkc35XdFZM)5||r|0Rt7)c?Kom(}}*hQ@#5{7;^ooLmwTlK-OlPvqZ(OiWDw z!S+9yNl8in2LCNUAP@-&iN7^eR8*9dl%%Aj@85s;Pr{s>+{#KE4-XF=9o^sh#>U1A z7cS)FFfja$VPRq6;^L~PsAOhl zCL<%Oudi=!?~s<3#^G>%ef>2xHJzQEXf&p>5=TNpLQhZM-QC^y*Px}PEh{UpsHo)Q zrIR*v>E-o%%Vd0XJlIz#6i;9Zgx^-)JcZZgi z_RgI?WQ{w^>uFg7+8%dD{I5vN1Xv0c(E!^ra0CM2(= zI{*TKcc6u#>$&IW z)At|XZ@etD65H-Hp84Fcmi_LT_8M+Ee`2OrRDWTr+2O5g5IC=CHF9EYIMxeCDGd7V zylj8}ejsl9_yl^yWmLDZb-e3fJNhP}bFvI~mgl*Q>kj&$Fq$-l?97}0ZMv1b^)o_q z`sj!Y?DE-14r!Vzm2s zX|9d4uaZ?>npV_5=l3t@kJdLVr)DONIB6Sv#xa%8ul!#5JqNSy^$jlCohY%6Pqk7v z)6PT`)iWltC$h^N8(1;lgE)J+o$t!oW``bx5((@W+P}NPe?L5wqWSV&nq9B5tc|s# z4f{N>qLHePfa-tYKPGaL%Z7D2wN)Q6-eCA36;z!3Mw|SK5$$zs z?5nC^4Wpk%A+?X+`&VTdg^DPmW5JWRfYnh>!iVT&)Q87#*!wDad~%q8DNVbvnwtbC z`?oYY#S5?LKHtA*G+T>Bcw9B}g9W3dSxg|3pSXl@MrM+~9;urY`&comyD8HcO|BPw zDHH#8g?AHqpg|NVzoIVJcK3yk6|N#l;`JNr2_b}IkM-JT!E$!hiA_`_|Ie!}rC^M= zz+g0C@JAOJ9H;c7;C^}L^VD}MEf3dvnm~6n(0DIK=~2SR!IXqx_3*D$Clp#LdbQ!q zaMkQvh5Z*loR3?{Ub9FF{2^K5OXfVH4EZQqDzk->?uTtAXLsQTcLnNDqV2ZWi{jdC zH{el@DBJu??sNDeOH*;PkwFvB6BoO0`1ln_9rg8!s!!s5GCq<$5ez;4-&^qQ>@^t6 zsZ@GH#|pV0DVrbI1Lu*5{Jpq46uKubB#lO0PusB<brye`v|b^ z`=^AV5-7D9{>5F)4S3WKE_|x5*4bpzo*7eNZ|i+^vokemGB}BMLADDA6P#p4MbN$} z%FK+s=wc1kQxNhLgw#+$+S4^&)7)m2ztqJASJM2{v`gQ!uzUQ1Oz79S%J+#Hs@J>` znbfQ_pCmTb>5Dx^jYR@rH-)jJ-(R}0*CIc)-}os=QQy2FkRv{fyjrmKi4N8YQ~E8gl8`Q6OHZHcEnVR;s$TInB3&#K-~OKRG= z#*X{Oe-=+3c^v+=uLbYQs#Et2gaj>o_7&HaEcQPaYtVl7+iFlK9#!(T-~l0>*qJ8F|GHhJHsD37aJ@x11fz3sLA64!tHL z``+`u>e}(bW4A8>G%i|SR{}-VRzKsb!VI3De8QJNYsJ?F=2%eBKJO8SkG0|Zj~|vy zOux5;BrpW}$a&iImmjvPCng?QCx(&8L`>x9c`HsCzdY5eS666Kt%f8gXAZnDQ#=w7 zxbQy9b(-A(clvyf{+`AU1y+At$QgU#h4;zRK?;k6!>clUko@oKk#um&>D6RNa?AD+_34=C&>4{+4gGPp1JejIIeTa!1Y>%=!IfpI(4s1b0kpawi0@hYT+;m~H4q*>2=<`lQD zx9i2xUQCa`HBRwOdW!}V zepV?1uOCPcr`Zuw%QQX9@BbX%uQkV5ggoqQ{&DGP+GyfAR(!5(Tj8kb5j=P9lL&;L z>8)J-*KafZwq???mc$7;K&L?`ewF$Gj!>r*P`XSJ%~5baMD@)NHuKA`-${hU-Atfy#^;ikzh&Zh5kJEVB=FWxo^S5;2`g(VCmo*39XM0k-J;; zgc5H3VTg=-?=d5sWQEy?2zi-h)CqekTUVExi>jd#)jRMpWQ3Clk^Vzf>%6rjbdS6y z*_MPEPO?%+07}L>U{9%v>ijh3h3?gwxE!p!7s8T$-y(#Sq&1^zs9r0d>O_E$S5*Jz zfM6GeT3p^PvCEi|r+-8h9xoZxQ0Zr(8fmbkM)&b-W+kM_Ig0rNRxD|9Hg0BiG`a=$ zbhv(U!Y#Jb$1mRk#PyF+ITDX1I}t(pbNOBi9iyYjbEtWZCpuqjbLGn^CcgwBe|ybB z5iV_tsUy@Nb_;F&?A#oW?=-bPK-$!MdAqpKC@&IE%2HYP&vRoom-j7k1WFSqT$+v8 z&Uq)}WMyq&(7)Ks+&Sx~cPQsv>G`aa)>MyA0IYiQNHuaCaRUwq0)FbvJAiPch zz(XMXY|9|Vdp`eamt7uwHdj?EUgV)^-QMw&-;T}2IOIBNDoq6KzGMe8o3St-YPK?U z{AQ1v>=_%7!j2Zq1QKc{1%KT|kNJvQdf-sETpX(_oUrcIMs{v@(jHQnLAUOr?;1VC z8G;4qdLMREV_mqPnr(=)`8JXjNyh>O7&X4i#?Vv2|Cd5b2oH{#5G+>cH2J9L_Wj3#CBeDh$P7WB#i< z&xgG0ClPc#ei7j14V2T5a15%pZtmKv6~eBUYE7Ld*4_P8b}-%y`jWmDWsut^hXrO} zQ*VdUizTNtVun)#Iu3NHMYOh%8Rzpza&z3-hZLFXRm;7@8MmN1S(32ww+Wza_%$z_ z5O&gl|E(GI(!0!8eIJ(}Vh#?b0!>b8>YCy}#yAkm4vg*Eul0^w7|gy+0GF1KjR|1N zKt$9_6_=`&xT;cHHaNIMsKxX@K?;0iC~Q!7u>PSrI5Tpvo1Iw=jw$nm>KjP7{SOIy*>r=#kG{if;GV_ zSSoob9bS};Td|>)F|-j3KS3)cT=gPSd&82CJ~b!fc-oO)%*{Q_e>tH+5W|XHB)qFf zSTWXYV5sP45^f`CJ%%tjstjD}Be^nmJA`({L>jTJiVnECDrn1Q+ zd)w#x@t1z>_AD3k>zYI_L`Boh6G&@Lz8tY{FqkPWpmYQCcl>Ck4{X}C&j)7D&MV_* zNg&lrrQMuDByrrdyQ;S+Z{Zn($w-FYLt*uK!}m=}vIb$OqCqUEpO2gw%B*6O{v`in zGNep1Kt$@t8(Qp)NfkYj9GO=)^g01$HkI)qbR*>#cj#SwSYF&$r@ zo@+N(c=N#3(}|sh)&{pQt}t{Qe&})}qg&#N*2h!=$cd|Q(^6&yA)+gQ^GZ`KUU((T z1!sk$vvu0&TWyKB=kavYDg;*(Tbx`$#T+bj*U@eA)y`t4iIv+zdAueEO+~QnnIjfv z2-Xb-w+M}dTR$EvlPK`pc%M17#5nNbz_#kE&6OIP4BXd?@(7bQu0aBL9TQA}aUbpv zn#_Y4SyErPG`u7VHXAoDAtVuvsfzlR62{r5L0hwZr?%GnSIv%O?mAiL=GDU|xpELn zQ9XNOYh!7fMG9@rbt2{jY_|8h$|2L{=5dq@Jnd+GIVQ%ikW(qx0NeZy)()qYCSgFz z??fkBkzJT5!jYX8?a7K(A!q0eBVfLtJTvfY>+614*hkpw@X2W*okZ%iqmHuj5f%Ti z)3u(OIHov5CcPNuRDfQ_SU&0%Uo2NL-~E)3nZ{2K2^J_!>g`&s&PZXE zRx`NxjLA{r@I_K>bM=0(bjJ4}HS@Hi$(m4r?Ap*hw`W!{BX*<`}1hL~2KAB(>%i4 z6~&7i+ut$aqk_$f1Mmlww#7xsx}Bc&aUB{VU+j|F?`uLQ*zQBi7zA#)T+Uldqn=Zk z(=CwIXj9Kj@8~qVMc(Kiguf2n{IP%GnOhhG`0B1AJdk*gYo@S5PIKhdBz$y?zTn5z z?W@T>5w}oy)dT+;fWr~5e$4h#D)p{0d8+q38Q_stc|y54Z6jXyHtycLC439=I!udh zK}Id)q0;p?FF5bs+_Z{xw`s`RaI_OtHpjK29Bm_207ZU4fW@JFhtTxc;ivogY+q0` z%P^W=QR2#of&X1Wt+KG;)z9lHznV=qTgGBH`C?QtoKB`+6E~!dp%ae#veZx&y1b5_}i{UW{fMtiRcrg&^8ej|l?NiFNpe=t0m(t=L#=B%5;V4V(n(hA4u zMSNEcHF2frm!wG3i_p+>Pq;FMdW*h@IIDe9REc-6HS3eUXA%phBZGgJ-Bf*(=##`O z5h>U~jL=DxnWA9RuoHiV@q#_Fqp!Ux5?eX}VUwmVm3fuuMU`x5DxbMVSvhUeh$o!7 z-a!!Ggr(*g2Pl-1ow`o`x`uxwWke6}!=%0h^&V)$?uYoRbPRnC9-@7PxV)_tT)5}0 zRfq^;_LgCyOut$$k6nk3UAzdobnCc z(~WPlpMn2=R#b3}?qS|G{hNwaUDB(EYpK6*NLnk|$7x5-hB4OO%Xd%V= zkZI$vkA0ETli!cdQ6@?+OwPV!ADV+1_)!2Q7FdKQ+iY0@aQ;?q{sYhOk}O?s=X@Sb z*n?5wye2n9z4(o2O*-MJtdE-8Hpd%c2w~zRgZqQJi zgp7QlH2Es23rq|+>A`>iM zI_mI&&m>JvaO2ban_80EjQM3S>rNMed|Ar+ctF)RR8i;Z)vF`cv`SXEu!hel`EK*(V;HPmAYBBVi8S?(Ruq#(Wye>lQszF#s81Fp7HM z1CR+FgHvy|gfqM^XL*st{Y@Mus1CNWGIc!qmH%lQ_ZY(|#ezGCYefa;P@BSj6Z&33 z?hHQ!*HoP@u3_rN_WaR!8aI8bNF6W6YO1rw6yfN0-q~Ai-AT$mg}SM{j45UaLdaikW_XegbX<*e$dR(P@kwIz?k9xJla- zdbySvK4k=Ue7(=PwSN+AWyhFV%On>Bu3mHw-kGMu)z{lwm!c{d6%UiT3HFaF!SvJ zgL=iu`Eax4LiSqyTsAXaxuLcGC)g|!I*)*sqrzJsPew#0W1C{p?uFa}9;0%2RO!RV zv#%#3c8sh?be=gRlQ~k8Vzz>Bf~(H2LPl#p&;x#!`cZ(M@=;pVvy!IMpP%vwnea)T z1`D}$1k~D3D&*W~IaKPzOG}Vq#n3Zx)g=chX*^=US`ZisgJLrf)T=9%I6LCkJRFCM z^;%sFKIk>am7z;3x2sPkUQM&QV{(;PK&@kr6RzAkK+BkV=%-3P&>h>QVg=UQRPLP+ zb`3G4w<+GX35RoIXH~rXj;;q@ovHu!v6@OVE=sgo&M9b2#fvz`HT<(^me8WEIQdqQ zYXM}_t-ga&k8M(luCgNTj~&B)4a75iKpYm73MhMGQcDru=lEF6-Y@q~L(8lS_>Z>B z^Hm+c6B|!MoNar^AYnERhrJW`eB&O7J-F!gI@2J@f9t$QvUA8{*Na>G|sL-!F$!d5GlRw1=`d|NGe|AQ2*p%;e*Q{6%}yf7MElOyq-+I&I#CN&B_C&CXxQ{e3Qz`z8F`s(yZCs zU^i)$L(!DkpvA2u+uKem@*NJrH%%5qdkOr^3sEq1Q=8r!ad|q0j#7Ztc)9R`b*yy3 zuy|efH>5mb`JQ$EborCu;NwYur`bi>(rdQkOfaOu7`kcP<0>klbgQ|=MD5PJxIbDm zNGifRh}PDRrOkfR{xn3dW zD-WL0Ns2ch@edVt@CJU*U{Ab5YJwO$)O~^dV}2lCA@d$&inkr9J3agy!Nk+;`ra9d zdy640O>Z9+eY7@bud@YLE5hw@$Kn;)fRYRp8G7+;`v&}#w24&bI=Wz@3&>Ysdj|8e z;26Y&Y3~!tZT#xF5q)laI9O@2qv}`-2NHMe6kK&}jRAK+>bOt98{!ff9sS~UM9Md8 zGR`nZPC_@D$BVmwWra+^Vt9G#1q$ykbrxSppWo^fdgQKBlltQ8;gVePZ&h|L_E@bm zX*^vXPz>92y+sdIf01qMMvkf~qeowde3n30(wpnZ#ED%S^)SwK7beW| z(J@#p;|tCbbcK>tz9HeJun@f{oXSuv?06@?uV}I*){?B`V9c~{uF6BQ(XHa}+Z~lC zKW}O#qU{yL(_hzdni#?hdk~|Jmjiw^AQ5CD{H~@rmilJ%c@uy0NAxZqVVKeI+#-BJ zRfc}gv^Rj+!g0ZRj1Noqk^a}`efk*$DGfnSBlTAu{x%NIX{NlV%p9aA8y~AWnQLHdS3Xpq^RXD-QM$<1yHQT(a|#F5=`ePbMyDb*iIfKyTfwMtQc{ z!)rC#y3=jb$&X;^Hx7J10rK5K!KJO%7_58WT#K=!8BV^Oa1lS?Xuot6xWNWAz(!bW z-ob7O2usD{>RLrdCdYJp#d;=#gYDm0f0Oi7xGkJY;ZE3crC+01t_Zt#35olNb_n2P zPzsW}ZH4B+?6P<};i*yEJ?UP-TTFnJCQW zY{PPJOEx!d!?RCu4w56|gq%5}o@I&V(k+w85~)7P=3m)5L_#z+qP`Usb3%J5k{$h>P2)G{0T@E$#Qb&rw7(9})C$MLxEQszzO&bhyi`S)pUj zKky)05p>sAEXfw&fC;U3r+i)gI6}z5=aTUsPXr~oY(>L@9Y=NnA7t6p3K;XE$;P}1 z=R9U>0aNE~vajZKY!R;KgSD7rKY7OJh|f0j8A7#~gxD&677GNOtXy24cB%N5!|o9n zC|VRE8zZ9(r6HvfC3Px9dMF71F;pcF%-ITu@ozJOc{3o=Q!(C1Sb0G zEFS_V_5ieOrbpLZBfWp`*0zn_bexqOw{_Rg>u$Bp(?nk-BA~UGiu+Cm@J&vB;m>r zefp+G37+o@1+E{Apy>a3sQUd2ZX*3nqa27gJT(8{Ni;E zr{bbshv-q;U=Y0(8hiLNA}NC*dOc6-TJ8() zmA;@a6li5mD~y97Z9#b*bGt+Bib0M}r5R_NarT2pVCDcA?7_mcuUP&vmKp6z@>G;+;d?(hm|P z&9+`6Yo30BSf}ENIVuQCpM--PWH?y1HaK3o+utP*V#ffvR+F>ueU-88LTP(lD;@Ed z&u1r$5+m1FV3T7FZ?{}8zIfK!bZ?vs+)BGIuiS174fT|0E4=}1G@yP;4p^q(*_(ap zAxE%QEo$H?<0KF}Fd6z_WVT!F3bqEwnBtbXW3r=ptv2+O|Q-$gXe>Jp6aZ$&sE*A85d| z_o%dcF-$VS+vTWPwAybS-~~Ai6wi0gzoX5R6lLWOIc_^sXGI*D`Gf#&oA6`j=yw+1 zOeDKhHm-aIj&I&unsLEj#0w0Vx;9eca zFpk5A<_dL?6ybKD>7>Zbtzat{bD&evRo9nd+FPzGpTZSW?%jD0VB*Fw_BbJY1}v1L zJ-NyxMas5AE_yLDXiOdzt(Cc_9$qFylALZ#`3$z*A7R~Z956RHmZkQ!nJu^bmy5Xr zF-@o2Bkb_k@p`JfX%f&X)&p#g?Ok8Z321r@O`AK7C35tm#7kyxe^u_*C*|kvHd#}Y zH0~Ouuz2eE;B?Y0pD9bODK|p25aE`}0LR6ieHpX|ruO=~Rwj}pK#CFtQ%I)ERtO_` zME42dsVj`T@#s^Q3~dWB=Jq|~!6vCP$OyujN$Rq7*&CR-rO*BMe?C9a0(Z`b;at@n z4EwG>fgry*{4}8=v?L(~wHz^^+wlQlQTh#vf72dU5O1kgYZrdS6~S z2kTgc1vOUj2UU{{G10A_Ey#0Jq>|U7%5I8dn&e((@a{rQF!z&)+b(OjM&ZBPO`=)~ zV7No0D|dS=b&~erQ4#DtSmm2UNpCFg7=~WT?XF5$eL8gb&L~( zzLAWbow&n$mzL)nJN5lKOSf>)N|g0VLXa~N-;=9A6;ZUd4#i*Z6yW<^dj50I?UD;o zICJ2YF0IY>s8B7Sejf1!b-A&yR4f|Tv@)%L3)TRC2XDFDcEu3kLAqv;kg|Er2jnqWa~|YJ%X zDIY4PN}(-(U6wY=&G>@+kWRth$ z9lx6t8*j(JD}SSlKViA9X*}J>2Y1O?ILg~oud$L{c29XavuKxZTv29Gp4>pTF-hgb zN@bW=l19plT6Wl_rtp*)e5y5!luQCfkpN<#LqzvGj$u=vVs5)Ppvk?rvG5URjU>3q z(P!$HoN#rG3iM8l+caoFjCWQ$84eJJr%}v;Uw4JPDPPV!%&F%>PLI4%AT#YjE+_r) z+H0Z9h0eFx;{s=gD>mDogq<#9TXhN(-28shKZShDWXw0GkH^do2KEU5Sbg6bv)E(LDJX1(%bZRXY_kQTwSmJ0mtFB<~%`$mz|p3(vN0 zZb-f>ZV~U8Tru=Mc>6hFh6jj&!5TCtAj{oCp?Z-ur=eC<&PI4Vbv*E zR$DFC!FwR@!L{d05^ZUp7FzBu^6|DyjC7#f!RBrk;)0`&NoXca-S8{z0Nap<=QDe=p{<$aDh zIR3?&tIK3rmWlBo?|_+Re6wd6UShX7Q9SH8V*8Z~g?Yw&IRsVcMZtCxAeuG?QLJZI z?p8RU`QJ)R5I!b%b(NE~4%eG?qmoU%4U!WJ1><&6we6yyK{hqzN95wq(TSFmik&Fq z_)cCMMp>mZn)Pg7qP7Ik`oM{u#W;UP?EQ$)>tQWOH7x(sh{-gC;EEt9N-Cw(I}Q}{ zH_MkHY#UA$N7;VZ4kp7C4`H^THRqADfD$NAv8=>Wa<#WCczXbYU|e_2Vi&KjG~2zB z^>s1?Hqg@EM)um(?|hS-vM`J~24;)Su?Ts(`!M+Yk}jC97|pIjv9p|N!2!E7vC&BA z4}zg976wBXe_~7eFYBq@zEXyK4cnREZ#rFTJqyq-qcYQd+DC{eo=Uya3&k}tsa!IR zfkmQo>JmL{W*W#Ro&2h}4tUXWp%%0>wiPEfGwA))moU(jygFy8F21QY7?lk~iKzF2 zVR|hr^RhH)ct=VwM1CAo#aTiRW;+slVP-v2Y`G9LkUve|Nus>jok}tL*msL-WuIc| zRC6uZ>RpiJ$3sO;8hS9=l)QR-$;9P}?|$Vapk3j8AZ;tITVJ^1)>!K5p{P3AtxB#e zZ<}5#GVLX72}5Np){DN%s_&KtYZ>BnOz*~ZiT{LH*MpD7ObbaIKuu0#rTR;ScsDnQ3kTTO0k(dVP3=n}!c;NOByzEeVNDZF zyJu&K9@0-f!W}WCD~$E%*GG4ZmWMxdDyAqa)_Vc#yH&Q zO||6Mj!@j)8|%Lx*i?ppkB~1zl7I~F1k3yRJ9XD^gu}o-jMov*lj&vtmcJcgeY zAn$FjE7D=zq8Ne?| zuiC=RGS=ZxI=5_{ID1>kv6+{!%O;q)fdU`oBI?z5i%l-fDpaB*fq<^49bGD_BrwO} z&%-)UDd=Z)p^I{b{JIh!IKPJ6&@Mf3%Ot>UgG)YS!&#&>&^ZsljB}8<2y2k^%D4n$ zIeyDh(lt=F@tx<6rIZF5F@ZGu!q}DQ!swxs<)9+jhg>K=2H*m!S1Op}L6IyY^Gcoy zJ+yx_ewZ$b5m@af;8+XXtOWp&a0!1GRQ7K<5z4CNITr{iTO2;H^Q)pgo_UFXYv*Td zQSrek<7%Lni6UB#-R*Gs_OGD%(L?C5YfJOi_pxFmICAA9p;Kl+v{$4@BVR509URSr z=VQcl2$i95LI)ZJfxUiGD>5*XvygQ_k-L2Bd&kE^9MEkH;EpRi60%>VDw$pzcvj>H z`}UO$iAwBY4@>kAM9t!{}xYP#S$)`dpi0AA`qMv%X(`Y@HGn zvw{)6t;mrdF^39#zpx&O-AviIeB_!3yIOwu&G;DqWB954EdOOE&yInd^3Rw;J0meg_ zL*^}Zr|WJ97QP?wqhqeITG9_q`rNLcesY_h_|*l;3fyWA zx0?04F{5Rye(UueL^}C0O|+B=gFydK8%4k4Jjy(Jw2Uz7CaH2@wMn#>*05GfZ^o{zO$7bu?lORqoL`;oBfbu$o>m#k)?;&2*)cZIuT4HFeW0 z7-bmq1zBP6>mOOc_E?zLS$Eu7i~1?QtM~>txa7ZkXIuZ7G0v0In0=uD6Dy*ME;-Q} zxoZK2oJM6`Y9E)&+&Ph(yVY3u60aKv*J{RR;H~lJo`wY1gwltohkssWPo>S=aPV9C zZ`AqwPzb>Rz4DElWt!;GJ}As2W!?3Y0pv+z;lUvawOCi%fANTRpyl=ziNfHeJZ&Rf zfO4Pc?GB+Bc%ro=I+=9dv?A!k3|+%HdN5_6g)YITj&y$9PimJo1`g#ak(#ak)I%s| z8EEO`XbqWZY7)Xv$P`ny5kz}X!Fo|E<0;-VQ;Ww2nB$kBByI0rAMxFnZg`B}6xqz- z1|pUZRh$;_VGlXCGJxG}F(bVab7vU3!fP_?{Sb@r2(I6gWLNO{E$2{4Uy{eBG!gCh z(K&a)idcL;qL%NgZClv<-cMv5e*W%9TWw2G-@bx$nu{&1G8dJ~UAkXzkO;t>xn28H( zPu~H*T~0D|kTT4U;&&MA$1~m%1_$pnDC9U<`RRKk#*Jrv6*5|l$9s9U6Q%{9&h2MXZ99Uud#06Xfu1Qfg6pry zE=2sntbRWQU_u=|y`}%!7^ms35lC6!c5yl44UoIibWRX{2%36$K5jh4kJ-p~CzMjD z$F6RH=xFgFC;kU$1b?;NN6FI&lY%*YFiK_XRed_Ti4J|fZ<$^c_U87r=f#ZnM4k<% zoCt=P3)=0KD% z5f3Tdg|wSD1$m69Zho{kxW_FdrYWGKLXbXcd9m5^rEna>z+hOAy(lK)vv}D*^}$!9 z9wIt+v^eA8{R@au|Cy=%=~vtRVf_JKTf)vhi9#)2K8~kbtH1XT!gJohD=<~I#xXk| za#ARdgOT}>~tt0;iLZuA)rmjkQv1T;#dIq_|+_D;+b9xmr&`7wPZaP zb0s{!jjD*gLm>PV;>=i93-4Ox$5Ht#R=KNo;#HaXSw%2T-N@(1>Q!=A*6(86uYenz zEWE>VrD`x`(S!vY3Vou)4v&JpmA#_(0bf6m!}@?I-TWJ3k1O=Z2ds6cx8C446!GKz zo6SPyv6+7J+k@%UnVxlgS3#DUI9c?pZ91y>qKkeG%kz{En!k2whK1~oPJW~qN6C8C zSARIDc(YO>x4Z}M@xMFiD$p;RAF5R|lK^g-3JIQ78K*Q1$HOT4*(=J52&M)eDMy3% z&~ww07jA12&%$ZTf#q)a<3B-+rs)Hwo(*b8Gv&bz7Dx1JTb;YCVZB|EOY&6vTotmC zPfG7S(W216c0BUdIjFetMRrJwHm9gb_DN@D9S=zJp`zo4BXLCUzT|GebB|sbv}Gx< zEzEY`ueaMc%EQnOHwG+r-N9jc9c^*Xu3qovpaLecYVaG1ovkiP1mV{Z73X)FUVZI>iemC=t{FfM&@QGB}i_5;Y~1{ z9sgi?GxB?rVb@G{KGWeFig3Xoa^*+LK~Lz7dJ^9O*=Fy3HPNHKJBf7zl6Uj2jt7i7 z_f-*oGdjYg(TAMpinerV;XZ&LyMvA)`L^qHnmvx(rPzK^sB)MbLx>z2K!iE43d_?*8kHcf{Gj-LW@g(WW9YpbcX-A?GQmX74FNKJu zUURJZ562QH{fJ$$GiAr?jt?{s@)4-&>^0^TnoyYRk;6=Qc6ui0l`2EvupXurkZHrw=;=yYph zDuH{zI;sGh5QB@!3LHQ%$iYYLuZ;g_bqNSHrm zbwhO0wu_kn_%v;B()LUuiSRi*2-N#o5L-3*jL3D7+VBm2^0G6l=$8T@@c>m3W6Gu@ z&XiYMd#eWp`zhl_WY!SAqw`c*kpAE#2a%CU*&mY6M|bzVwnNsni(^()2q@pG4P^38 zU`nPA7;H?8FEm`N>^gCA2#HJNvg^P5D>p0xrU`3mq&k25lk9d}33e9A+k3}Di7G6= zx2}7##X`-KmMx*U91*mCr6xu>k91pSrrfAm$3SbAXt)-$hSlt;FYb=G#MwAWC>ML-6SwT zx|@mA@Y_=N_hFSM;tS^Cd~}}#<#MhJe&IuIjdoSV<~j|2A=EgTyet!=E}M-6lpkVW zcbSBKBEy%74YkoOeU|fNNw5}vA&9+RcMUBbBsKNe%P$c>De`OUX*a=HPg$-!H$;4d zV6ijEmvwm+)DSiS;RX>UYaMrV3~y`)L$xmZdWzFnIPOh$RUu%0-*{Q&+~%Wo4?`5F zH^B<3!h^L)M%~CGL+rcg+#gyg>oPsD;EQ0WXRm|Ds2QaRC_3PFs zz$u^Kyj-H+iz1q7EBm@95%{gfM&{A5m>)kk?WAg*y>|c(omfCiga-P&VJ>0siS>?A zu``SUeCGvQLYA5ZeJF$7gt;34fEf;v54iAw-aRW5u3Qt@zmJg8MU2!hyWwgQ)odx~ za~r{eyuD1yR&mhMQN-s7BZujS)(^-L6dgd_dQw{zs^x_8_QDCaqeyI}J_l)~?zOdf z?>?1v__2)(Mu}s9q_t4AgRTyey1E-dZ|vWz5DT8@+DD4vM~IC+AZGhbxol zZ9W;?3OurV8b4FJ{(axU3?^Js|HkLA-p533`iy;a>cr$M(SJYHuGo89xJM|#(HK*< zY>U&_ltiKKoAzbczSLj^+a|nCv!jyNIz3Nx^u#WMP7hN|gdGS<;YXeq!q^`80MAuR z-T{oU)XhdOD-qA&n9o81t8+tF*A4rk;Xe8)WeC8btOg^MZZ=}n`eYpY1YJd4R4)`N z$sryj+vnAtA28~E&W(_c;o=OVJHJf|PFFhnNdmh~ zs?asFeTD;@S~0et?oxHOUbbupnZJF=5fVmRtj}Z(sRQnZ__!c85US}5??z@hJ!P!7ll9M2JO2> zxu|);!qEejCf>IMU^U6#IE=8hD*%Me@*mb_arP5dOn&A+~{Tn>!6bWc+I$jNI? zPh9&!i{*VNKh3kH2b4BOPXY-_bQg&mYYonl9-x$I{q&?$xl6)V1fFfZoS#>!wz#}; zx+qJ=7h4+!OqnhK>}s2PE;Zks8J{a=q-gZVot&LhGW>QJ=fZ@cB}wuQ1nC^)k_&j| zk6wx9{f{=jD;ll`{5A<9x)cOK1R*0@bWtOs6XF~UqxasUw;+j{5WPpAGoz1AbkXbR zqeLG;M2mjc@80`g_vL<1dwu2M+iS1=xZ7CYzd)@$$mjTxOHRkp;dWkq-bVdd~+^3X%4}pqWT~bjhy!*n6GnE(eOFi|h=@aPHbj)$)cF?qHRN?tKyD@VMkpG)p5vec#QZK1pSt z;Vl{=KN0KFFv+K@hgJWx(0T|G`2Su%Pfb;ECA>XZXG>#>HJTrf95BYY=i+a)Bm1P7 z!V5+x3q|#ekt2918c&lhL-!QxDo2Y|OAA9BYlDiuE4BkJ6>vw-@sUg4u6XFqD)&w8bow)?Lvb_JDQV);m*jJ`H{#IEt(C`%3mhD#ei11VyVt`D_2D&NGhO|= z$Gq5YRnid6VE&ZyPd11>_j=4qSE+86z)@1$*d6xtd6+D`Cf)1cOE_ZeB;4yg%k0$g zT4!G@Z!9k*NhA;3%Osv2k(v+j59Li*9bC5LH{}=3Cf(_6*Q1A&+`oP&8B^wG)@P1+ zetC!(I=Pg2ZT(b~IO#x4FD8d&AiSf>5u`_5?Phcj`7O4|ytJ?KoneQL!vQMf>&^no z=JmSa2=f{2LFi-AHdoGw68&CQW&F*phemh9qF6}N+y|kGvmuu1FM6cbj}14;j(sZ- zh6?;^U)lzr)jAH8pFPS%a%J*WMF(Ycu>M9K77W5v865}EuGU3nSriOPPc4IRzWV5p zTy;}yIPC60&4RsCz;FbjHa{iNFdQ3nVei#gZ3KO})AKc^|AV5KF&VYSH04mPxfXqS znyGNeEi98o;df~E2&65lJB|GRJQ4GRJ6Oez=DQTCa@r)LuH zZkm%i)^Y`iED;yz@r3EFa%Wyzr(^m+u$0#zA$VYR_vLf;nPLMhbX7;sRz0Z$Li^TJIbi06?tib zjY38s(C^B8-kxlij9TYq*z@ANM#-F+3YmA(!$O1S(p7~Zp8~{SF2fx{x`nqTjfn7E z{tD=&8dxjXM;37AlMbNPc0~G+AhRB8$xORVV6{cYXVay^qS z2%2^p&h4(VeP%SsN}z#I3uze>(e!XgY^f#(E3sS%pa6C9GebN!Ro%G_L z9JrzMECCte3agm0!VDk{wUHK{*UC&N6)(@6BDN9RNT9LR?hZf!YQ|s-rsm&f4|3`* zeSBV$z%^WD+6f8k53=hVwGsvYRr29KQ5!|1ebt+-Ua%63G2DvgdjGR~!(~SL_OZAW zZ|Q$5QA}fl<2DGcZoWg!5`gB#FZ7vczA&fe8Xb)NeikA9r$^_clPJ0Wh*P}8Ls`4Q zY_Lks?3~31XR}aQTaA!5OvmcaLW7Uf>DoMl9>;&A3-^AMujim}ksePNH*})wdP)$_5LOr2 zb;}m>nd`yV$tm`0Ow!xeCC*N&Gp%WCe^tVtEMVFi?)zjofx5fHPvI%p;14K?3W=o+ z3GY$^TU`bIvTUqXhuuS9!jkR9xx?{};KUEuU>5$xApW%C9W{1@UYrW$S1R6RXO_-d z8K3-(sGqwf+Ffof7K65q4irsN8>7W>a+1WZf8t4;650~gO~}@_KW`O+*xElSv!rah ziT%4t%v2Wn#>N(g>ek{wA4VG;NY_>vxxeu1TQMKXlHj@Ctq|BKa??0%PZ@u9+8Usk zTjjr$kL-5&jmHYqvVyv>{D))gI6>V>dU859ey?!FDz|&yX-H*Qy1tL2fPJb;e4e;+ zy#n4C(LH99_&v|#Ngap2g7aM>DD-sx-V_OL(P&5#8VtjdBcFqc;p1(29|nvL_O)eR zUs`Kc2q|(~SuF8n@O|DTOUDkXIKEmvpe^^4V2bNGP->;y2%{-R>IIOR4_oWyvy@3n z&exZ9!S1P$@8$Rwn=xly>r)0Y>RaLo#y>C7nkVkHa=+yS8+*4TdXT_ZY%}#RYlZDVoIWWp7b zgawcqjEnV|~>ONECjU zpaZ+N;>(nE4~omR6&|n?G!c%1QSV9KjI%#$ZP zlyT;GN9yeJvYbXbR$-87yuDCuOr>j*d=Niz=^=4h-9-9lvk{5<&dYQv2)YoO& z*n;N-o|ZHPp#%lnLPjBC+y8C0Pb5!LIvlD@f)or45z zg)!@oAf=mIe)8&QaI{WZvB(%DGVSkP5N^+!|JtSbZ);YT zQ|umRZ6J4~jH0lj<_sx#Q2eXn)@ZiEe#303hFW|op&Tn0IYlOa7jk#%ex>hn^kX%! zmj`!e%ha>WB82Znz6}=j?Az{1X75&9`i`Uv03J>4o}3Y61(!i&i)X?&{QR(QET(UR zWX0{)$%K9*#8>HQfQI0#gVN4b_@#!NSdg0g@VbLiG6IL{5i99Nw|l8>gpA_L5)f;R zCgro-Ye`q6t^JK9rw`3h_01-jP#E<)GyJaVjg~@tR>Iw%{}?TgqVL=K5Gx9;r)3}E z4?=3mYOE4xt8JUTfxsyJVS-pzw5<2%ub@5!sbwu_QQq!%O{8DN-@id z0@UXu4WFLfou&s>i$lX5UL?-b$l;|ppuUE7lBqCCP%B$KNRuzG`%mzMiu`1Wxl`Aj zHL{KQ-BB1SX(KIJpUFk+0_SZWGl(CHfZ^PK)Z05E{61iq%HX{OC+Gi+N;~m0EV6jl zd!J^w$^}r9Z@ZT9yUjk-=UG;sdJh?1eJ;r1|HW{3vkNKE86c8T6eYkpw3epRdWpR}+%K8@tUMiRv9O+v-Nj!73ip6`*F5v#mSEoEXH z&^hjnzCwUV7B3ZBt;hThIFLoE(NNZ>GN0Vt*SyY|K}WQlkW;hHHB+_kA;;1;es{zq zk@iix%A(zsO0B*lHS}ljEi!zmC7XDLxUob>dtmkf2o)E`zh8ehihKFk?_Dq6x~C^} zq?@Gu=cn0g9`#VF+aF&xPqKzeudTEMhXj*ULX(+m*5rBRZx>PHGA&wR ztFbv_OHPVZ!|zX};Hak#L&!>(60HAHNburlmmfo?-J<88pyS;WjN>8Yjel(1AM+zR zT@4@c)qJpiDV*QT9&1n(v*$}uHK#gd-(PW~L-`b5TmwU`ERPDU$Jbj?#_54{_0}RhsrmV`9B)eMDT{VR#_S^O)cd8jQ?e1)smK2_f zOUFlA8x6nF7WH!HQqg1b(D^6$C|em73cmB+sL0WH*`dH#ZvoN>*4d2UE1l3aa|0G1 zq2@Dzh#NX1HDQ%YI_#+kWAz*}u6G8bX{&Y5846S2pL_7MWHw*ip7*R2P7r}g%vRa=UJ8gtoj5?8O*K=1L}y5;)U(Hk39rjcKwhs#>RGp4R?R+}U; zJR4{YMo1QGrHZ0T&jt7}Stj8-v*k zCQbJ6p;$L%zQ}4r((Dp*%16dNbg?~t@U-1z0 z6*<*O&!d2f)zZ;i#_1l|w~_3pYo*MuqqJ#ypEk;V>>6(pFF$<6*o@&x<=M$e|1!LW zu!@OpH`YI`;kdai{Eu@GZ82Uf#o2Y>ADSNN4tv7!Y}3Jl&m2q(qtnfZM7LMc(n4Hh zfz1*z@qhgq3t$MpKJ5W~&x0e^Wn6&y#Ay2j?;*cJ06Y`OJCyjz1SVGiJ8%w3TDr|A z_T|3OPM76RpjKBVVHn3`Rk~yxKKL1LbG^VjjMBfMQ$ytQPRX;RFG)#F-w#*U^Y=E^ zH%70OvB-bRw0uUQ!}}NM*zl=8PHtz$InrR4{VxgG9ed4~XsyZ@x?M226g1&zI9enZ z7_npxC$d3e`bJm+5vjlpC!Bn}<*%Iq`9O6p(JJRUd}wy+OsFw^0amBi5bh*g^9A?Q zO0*unq7HJsKb^MovIJ!P4y20{0N0%oGjMIHjItQ<=~{ui{}&g^WtGCuA+)d@eT4MO+ielfhSJ7E`yCl>IH6YME- zk~!aGiRl^N6cy%H5Qk%u>vh<^qI-Z)aKQ+#b4%>nd-0>4MW&oUFdS192}f54Vfbmk z`v=e%I0izeyD8EDWZpx1gxwJXLx3B*izyoJ;&(!&eA4X;=bO}INPRXv%vzEzJOg7D zd-n|2KtYAHu$6l0shPtggIEcs$c8xFVhqqF6yY76>xEu#H0MR?HBY-Q6C`GP>s7wZ z@rC(sb5708UcF$ezCiJ{Iy;`$1)T5VYE*u$ViJTE3;@@Y+1|PK%pc0Lp;Mwog>@ct zM~sW%s)1@x7-HaZjp7WRA;ou79D{>T^0aO>n?wl5I#szG@S;c^RY76MThe7*FHu+S zeGSjer~WFw`#(REy=qPG&<*gwoXaK#UN{BG{mtAbEh<0AOXeG2{(GJJShlun+LQ=k z(Kv&36zDj!5jwfG=|XZ~?I5~0VYv`sT>v^3%q0mq9}x|OaASPaB*2VSS#E;k3M~Hk zZFQtXy92+Zh7P>RDOJbEILor*?&*aQtmH)5mfxhCAh-b>{l3c~Wm{ z_#-n2yI&t^>1a|3j);mGIs~RH=dn;E;p)BOqX+UllH=swgjO`7-UG`jle+6&O3dU8^VstnH4V;gCVJILm9V|)(F|+>hXX+Ns2tn;Pk34> zzM2{d2AK#u9&NEX&=_Dp1EwumrR~poRUoSAWOxnC5#A0~U;`WhLr;|ew1v+~{3NO` zEvX!E@C>TuA(4NCMh1vbW%1cgpZ<*}VaHZ>sGAo3cdJe03Bc4z*TR%WIORF?IBCUg+m=rA0OABM^44W8CF zJzH|bX_cyQqZq3CT1N5!zVMcE0H>cgRJ$t66J5vza!8?OD`9&GYz*-2X8NOP^CCc*3aUZDkWfQ~%6V{d8|dknD0iTJ=B1aYqld8swEnwk6$>8zh{jJN_k>WT z-&a*k0c}%k5}@D-$bikobKM`&_(_-wq-LC#^|Ao_iV7-3!F+W+EdVZH@fqlFgn)at zc19LHbiNCzMx|As;XgZ}N#6!U6BuCgu>6vLD2w#SwBbBzlE`O}>hO_0(25tkVr`n5sg7}T{7Y3Xw6yoJb`&^6>{~+`m#k+>G2ZMqyxgZX)1i5l{|w50 za2j(c+-aBXuiBg!b7`?*%lh>%1?4&;_f>iE>l}3`(rQUJ5TUO?pOQlG&E!$PS9e0;s{-B05rsv_M?5Oepl|fOSUNoYpSoYfjO%Yuj=~)HJMh>b(1#`X8c6IV|(TS?R&`^ z<-nt9yZd?pFJjSnp5L3(>Z`kIb#lSsL4-~oVmQ>fQn01G{Nqmx_rrQl@Aw-pJ>R6N zc-}N4eaNckUP;`^@&Ud36?^iZgro>_njb$5rN-qd+jwfbko^b`UZj-eCk*`~CI5S* z221kq-*avu$DE=w0xy?IDiY#Q^)pqmVDv8=N@(fMHuFi8BTdK`mf+9Sk{S0CoItf| zLa6-DfI)bEEmgpf-5um@c`pYVgRarHkW&rIBQyCnRwdVXCbudtZ?Vgja(@a!(^AF( zjs_n{@xoz*SN!mP{b8N$N~_tp{v}Nf(ir;V^ab-FIKa$pJ}8VxzP&u9O71#Lue9A? z%$Y`-G~(9jBe92@&R)=-l&u65=m2DcJ(p%b8l-NZXXWoFj3A|^w1qm4*`TE_Oo`Ry zbu^5LZnZyc?zFu78Peum1;4D^LQUc+3>=*x`P|1TuM1XI39Dy^D_2Hf6QZ%~vFG7# zN7p;JHjO!@N5T8`ts&MaWDK?wAB2hHgy@WUSWhSADQV+1ztI&>wA|bqy{>rmtNh*+ zvM~pNETC!~{~gWLbMtv$1THvp@4XVMD>=#Oi~F3V2y#s9fe8<<#@F!^pG7-b%~?m) zH49O~{=rW8<+82k2^`VFGTy?4c~h|Sdcnesy{7o`PnP=q^XezIVuO9ViSm2yJtv>-YXqZzvB0MVsugxGqnAFpJ;cU}cpUX3h0iXLH+Um!k(g*sZ9A?Lq*asfb!+?v}U`U*7SNL}sl=f)(3nl=nVF zi~H36-SS@h?c(z1t$?AIh~e6J`SI$-+>W4f88#{U)?LjU(Di~j6N%R z3|1Hd+R{{$!imtK{}0GP|F3 z?iYN&>YXxd`Ht0!XK}fwM*U+5Z{*hlL4Cj5+_QNKwI8!Un5N>73C$KK2P(qs@Z+3R z{U9MVT_o&}$1Mj4*f948l2;PYg;`ORe3DFFY3GdIwovJV3YCxADtV|dY6G6G4O^E( zzz*n<8>8&Pt0;d_$c&ZCtc=}Ixp>NSL)u6HV`ni+1FJFc^T*un!8(Q4kZZe~5DYs5 z4e~#xFnt_T@$_Y$F7=%trVzfAIyCjh(sIs9l-R3MDcKWUy51V)(eS5Y zZEe=Pu;Wn*7!m_Vzs4V`V5F?;9ZNE&OPviWakL2CqU5@#m{g-ZcwXdjWhtN=iD)r8 z!ug4qHDVYSoeci&)NsIw{wL_!TjaiB?V`!ip__&wNYyyO?$e7Sc8Jl~`%!xQ&Bs^k z+@$T5`}NH^1~8z-0U&-h^}btR-=66Q<(SQWeFBmx5Dnk;x!-A#^^$rzK3q2d`n9_g z{mutNoj1N97^A`>=z*(4j!S#0PY$Kde7!wA`@s9i_VRGQ<0#YBZC_zBi#rt-2|%7N z8@yg3KSugdd&huN@4K~-B?Sz&80D!PU-9H2?qr literal 0 HcmV?d00001 diff --git a/docs/assets/flight_controller/accton-godwit/ga1/sdcard.png b/docs/assets/flight_controller/accton-godwit/ga1/sdcard.png new file mode 100644 index 0000000000000000000000000000000000000000..796664b4dd34a6e7d059837b7270d9b19c6a8b24 GIT binary patch literal 18474 zcmd41WmH^C*Dl%wXtW6l-aybG!5U~>0>Rxi5NNcU;I1K9V+lcnySrO(8g~z_!97@z zgfsTL-*?~d-0|IW?mfS5jaqBWTJ_9lO3kXZeynhHRXGqY7#9ElfE47VH35JpAOHZZ z78@M^0HmJGhywr^CkSnQSA7*_VRHvNPMC#*nI)&Eog?6{Ci>db5oZ40(v{ZC(i&ke zMt|DUK~IaY5Tn=QQ-P>BN?F1Y^4`vtTHdPK=HBnkg)Hb_i_?mF3VYf)+F827Xg%$0 z?OlXD#pwUVD{Su~{MTbHdfIH@X9bDiJ{}0svO#e>?JnbA+RQ|E?-}+)__m2q|R~dKL|25i0 z+so0COViTD!Ohv+QpVlV-j(66XdH#5oGoFl4$j&R4z~YUDfR!jOv?l1gwV3+A?z(2 zJX~1+i-M&z%+*qio(ICi#{q$IaC2*OLxp+yh54Xt5J6!G%WBx3PT0| zC#a<>%mU^L``>~s%!RESob6z)V)O_*n6)LBqrEjf?LTQ0mU6Ila8_}!uoR=`{g)Ri zD#8l(F0L?pb4vwjF?vrsM@|I7LKtFcDJTfBu;k$9=jP^s@Ifs&1kEfgIbcFCD@$Go z%+g8-_8)y|2XnW-R`x&o7XKgh)tnL52z!|A|1r;B8}6@?5SB-{xH>p{{d-4fSvvh& zvPIDTs|ti+=6_YU7`^#l%W7#s|L@0$|Kkk&P3r--wEtf&_unuV2P;<(n6ss%wWYo5 z|F)dC#A!vj{@RCs$HDb~5Ak1f|7Fkq2d*hC`Fb- z`#U?k8X6iJ8yiPQN4vYb|K+9cOs;g_t%Pan20{{T6t*zD7HG_jg zg@r}q;}f;Db;ZRclao`Gl~s?Aj{pFGft+M)Y`nW0wY$5!xVSVhFnD`=dwhJ{(9k#n z;2r4gsj8~JxVVUkjF_33JwHF&+}y0KtuxS2YiVh1ZEb6B@A$E`r7R^eGBVQF*Vo+q z4Z_4QH#6;KZ(CMW*xA_?3U&_Vyl5e;#JlF1)s! z7Ew{2?=+)5;D(5{msV`E70O1*%o?005xaRZ~?9aN@Y$=~41gA}gA=bE0#do-nK> zIcucpnf^*y6>Wh|(u}mJRoKE=YoPL;L^nizaC|PKqi4^~OL48V2(~ji-S8=1bmg?y zwX$xr-*0&_&61`@``f`qY{>49VUDXU!ahir(=lhZ=$YBC^?`}=!`g?rChzsfQG@H7 zUn%ijzkWoUR?%Fa_02t;79B2KDPGwqU(BDJEl!2XhB7*ApS=>2Nt&_Mcr8qH_#&qo-!q-G9dXCQ6Ykm>H{)p^-Z^ejN~uAfX?(`|>T zCs8x#FJnk4rlV}v$RZdu<4-+rHcmHAiU=`C|KGJa)%Y*KPHK#|6IZN)-@INq}M4;KYx17a+MZ@&3mCrVG- zz2r{yvyz^AmgY1q%notgN-8H6TQ(fFP@7yg7xodaq2SAVTK_fP)m9i(q`h->O>_w= zm=GdpLG#4PFx!L=?*wRAKlQ@h4UTFP_lFTFn)Mkf3Hw{PjN4)~Nn*ISFz_eYW;;%V z(mFAlOl@P$t$k>2KucO_hAnm4dhtpFoW1JaE?p=H)De8jwFXm7SGkR@n`i0C2QU$^ zxGM-VU=+Z}rU2$Tj;dFZ=wHJP*{2@IE3^TK`B^AFb2#y5_(z~wQXkaT1KgTMtNvB- z!kaiGK2}Sb2lGJo$#fM6afalhWLNT3_>wSX^d!8eL}peIJqdaICPt_JV3+%EG%BY4LVvJ|F(Q^^GIl+ln4O0+Y zRaG-^gBU2DM)>)Ah@(?CWl=A9p8u!}f7*eskai1~2u&INg##@%XGw5u5>OdkI}Kkw z{`FBW)D*0~-1W^!dq7&%sUmZ3ny~n+8&IE z%Q$qjogRd5Fc!cHCkSQi19QGjI=ZeUbFENn8QS zLHXcU+%0+^#{=~UCz3u6KV8$3F5=#2am|M*zWy|=_ZYu_4h)m>P(w@m?9x`&%w>x^ zeHI8M43H?F&W155bTc%Ceat)y-m-$9fihZ8AeGsNJGwP7FS=!(eT7e?L51q+8^<81`xGYaK}vFU0RnA3R6R33w)^G63j+3C69$uLc=K)E?DkRtZEJx zhD+E>(smDMNeg{-eu?ok#Ucz#6mCKWmK{s0nR(&&nu?o5pov(66z+)!kj(_9Bu^I7 z4d9!DQ=q>zT<&v0YF#xNU-6tYX8E(m_GHmb_rmAvnp5}t`jG`6n}>=w7@pNg1oes5 zO?FC;eL_r4Y}tTuO;*J$ZvSkjE2D>|P-0^9ft#dRMxLSRex_8OTBqV!%4^S@W) zLQkb-Nu&T*%$l~$y+K`i9KJ2Ij{0(#=zNksA02KueeZDGR=XQ1CU4?Pkoo5u*#VRH zqW|NcKdY0!c^~gwPgiBPuV3-~d5A=X-W)YwOs?2(aiuxqFsTbmvIvE&(+PgfdazO5 zplk8Ll@7Wc4yu+wx0s{?Wx*&e5n210mz2a8wG{%t@5O)ZdE~P{eVN1Dp0rgTJ59eP z@*FQ=EZsmTUA8i0B$Q^{{->wZ_|(~NqS5m9zVFc2E`f8Kr-yH(e#}|#%WAQWYbq%v zM);~tb{=-Ia?Xy^r8b{;HRMSSvOWPqgIN-ljL9t%fD>SgGPNLw$Bid8Jw{eCB|ka_ z8N`O(Ulq0I;y;ciT*#)dp~iPyU*Aprdiyn`gjbKN$cW3~Hnsn@rcP6PEdTQ6^^zRA zQg^WS+1>;MO`^){(f~lvx;lS%PKZy(G1-Y5=%l(4GRZX(v{fM18##Ga*g;nr{np6% zUHOL=mWa(<%*hWrmQGsrXY$0BPEH&CY`3@c&R#dGjh}&IrwZygilIm)fRW7$>Qq2~ z3Oe3pDnR*d4&4TBTwdlZje~lksa!KD_-;Q*QZ+k208P0=0erF=q>}iDzoS*X7!%Kc zb=W~GZP9 zFeazLes8;L>t_zjaM*4j`&V5W(v52WM$-%~(qXQHg=t>|=VhzSp$|B5+5XCpZYl{Rzit7y7}wgVqbxV?} zlW!KQQ5)j*YjiUxzs}B^w)^=`>5$2|K7qdJaur5fdTWCbQgC@s2n?5!5F$%BBOixr zadLfPFY5u_LE&4-9XnKQM*u|BX!xx8VOsG-rgAH-%+vcVLj4s(hiAg8N8~O;xen|o z`j2ZI9OA!qNx}gt?wYBNN-m%5JJ22Xh6bbZURQI1?1VzZK{l${e}pCCkZLu)`wM#X zN8`IZ9g^fnDvH~n&CX#8A=I!E+w<|qY`4{JZZoS*?g7S@DTsMgh)dTY7))<(R#Is$ zH1g8$c7q^ZI~t~#35>w6owRof@&Z54D-i}gDqk#cy$m1U$yavhGDRn#P#R z{Jy%uVR<8a)vW{4vr$CXkUafF05)BD&t?46ltnts^3bDFaAb%e5RMWo!WmP{d$)kS7XaJC^ zIRtZ2#x`3-GbTnkLKx)&q5Dp^xxp&Xo>@2D3d5;8Iw+{7r?6MC0Sh)SNU)%2_#?kJ zRMej3&X{$}k&6yQ7j4YUW&=`QtH;8F$d57e*gQ z84tv+fPoQEZ!X)Sib_~FNI=$hv4Ozx3Wpdla+#d>$@P&yvJE;)CsaARi7(5A*|(`& zh%Hs9qU6p?oVlM-Ux8+q+9(Y2)KF5e;A>l6x8=gm$Wql^wo!-AZ3n(?In{h#efz$s zFr=yZL>HOu1Yrn8$afah%xC(R5ySoIs>(Q|n&*f1l%0I#Z+ftK2*Lg*eHO9epAWC; z4Z#3d3=kTs5Ug*8?vg|e%{mT4Ju7be{n}%9Zb>?}_uPF>)lFbXIc+3Z@R&S~vM<)< zX>&{uE=1xD1YN1F)=ZL3#VUURi?O})L!jS6IH@6?&>dY7oBv->dq2#2~}#g9_TFBXcU6rVZ0k$Nu|g6tUn zSsD7%n{KTMBG{K*gb|9`#cV!v5Ccv7@(f-C)=(+4(HvI(FeU<3A#pg8kERJz$&m`5 zoTx!kW*&`#!BbhHDe5jN;FP7LI<@*S;`A_OA4g-(*58#z%Pjm5e8nn{VD#3O&1~nA zUz%!CX%04zu6QuV)I?3i|nE!plnVr6p>T3{e_>u;f~=rr~m{nml@JQ!%*QpRbf+Ek0wGo z6K^wEOTJszJe=pIEe-PV;}bXy40_!fyb#l7fp!);3%v6Odz*{W9M&rZ>3D#MK#%Oi zt2>sK26m3*X&Zo3u16)#8!iTr-t@LXp%ZNcn_D)TD$kZs3v|zN;>bFp9Z=(-4*%uI zxXb?m?n+LzQI+4*p4(XS&~os_9#F@^CbQ3qZub=JXrfB`aAxk_`Uz+Ny+#G)T6{P7 zp%2V!(i-0(r00l0w^!H<(i}c8=KfrWVwvK5Co6us|dr zGUaCZ1mLX@8|W&ai=RMfo8aOrn+(qmA86}))@F%iT9d>2H)|bmF!K#6hYv)|X{rm| zbB+Ongk-@7m_f!=>%WuDP(|@mlZ458vLD8KO0B?)PmHYfuG3QalmVl;($DTB_uD6C zLrn)`kucm)2{y2yl>GG|Dd;Mwi-~|79JmY*#=0}k(`nDn{jI#vGdcerv(xdat@;D4 zE(dgH>`8Qyq?D^d?AILGVwwCB-C?o#VI$t928o-A-U7)XUd$2YMh}EBJqdVD;5CTc zcB85}Dpzu$F#H)Q*c8MYKYDEnPeL;V?zg^2%syn84>7N zH|`%#HtqC~a`?LU8|r{4O_e-lbgA^5cF25}WOFk;C%@xHEjDN{4--^{q`-xVoWj`_ zYr|u&5$wP8lROmB`&B-}+=QJj#o2#?aB zAYI=J(B>dGP?l;KMfiHbJS2CrDoH^?r0UOsA=>+-20h#oRl-tZiz4HV4SZ`Z{uvse zJC!4p{ftOU^tD@h2O7zY(^aTnat?Aq#`%I=E`IK}u)tHCkNO6@=}%1QaO!rQUc7Qj zFwUcmctie;Exy9xcOKday~wv3<8*g89D_W`iFP7-qsby7^xPY2&&$gpW9zZ1V;003 zfbozgS?FMzm(6Wz+KbkqiJ!S^%K7u_&sRkC3Q`9-QegZAW-de+wnS$+v3j+JCM*## zZ}b>%YT6?y1c8kapIMiQz;Gi+plNnB3PHramOjpx$VZNsf;%xULs5Nh$^!WIKWynOGbRQ4=X{DEsix|l$1Pu2HKv>EX(=DU`Li4zU;AQh8}&->!K!K zZ4)0T`M!TIaNoX}RbZ%6o&BL8}E-z{5X1&5#;X}7Kp~yVj)oM*#h$}roYH|BAef({R%-h zwyn}`fsb{gF^_dKVYaE~OPUs-rBxEvX|6y!X8}5coO(z{@`f6mb-r|3d-7N`XFo*FOXoO1SLL)HaXY%R*Kyw?iK&cbDdwl!Nj5hofH`p zgBcZb_glsc z=mn~i4yCGen$xr!h^owFBs4y5Y+4#j&KZKV9><0@#kVg>4Vp<7HTJVi?$4g6gDu<+Y41M<>4uz3A9u@3 zv17Nq&*9E##QVG$VkKO%1Z~nS(nQQ(2LYcG7`Clq)+@c07?x~aN*FE*HcyMP2?c7^ zCiv(mB_KV>!S86=VUgBtNd6iG#> z6Btz4oEZ38+Q?%UU{aP!3sTmH0-sY$s_#(?*pW62y>E)N073duUH%-C6K zJpVvnD7SC=%l?;-D9F-*ELY0(i5mK>tG4zrkEc(MEmh$|bstW>Im!VOC`Qnn0!_LA z*+P4|YTTYxZUT1K;nV!h*;UZ3+mPs#y=korGHu&Vq<&8i!5+O!iuZYUKOq$8L`d%Z+ z`W1L;Ixpo`gS8~Sl_m83N3q!6W9JXa@i#%2d+pho-OCMv}l{?&pDZfS19Hafh1 z6v^mDO1z-od~HEpjy)so*JM~6$5Dgg%{-Zb#YiEmqk10CmU!mp!C2uoWFpfV6fN)L z*D|HnOb4t??jlfhQ9zN}_lr-A)c7SFu|?ndozhPTVe|pWbIagbBZa2RGK;w|>)~3< z?q%z3omHGKs5ydUVEAREatYjp&ghFf@T2lo+qn}&gJj^m5g`9P2kqQFhEWN;nDRE^ zvF^|%M#Bt5luu`9_*jM*aPY1VU~kl-qG8cf5b;*F=b?UHasV1OuPrK-Je4Opkx|e3LFED~jwV0?c zJvi0%q3R159N|s%pONKQYD@91uioF&zt`(G&!8euqY>SVfzB`I9(QVU^6(l@yPs$F zWJ#7-VVP+kLh)0k&R&|_)`(HaCnDBqT8q#8rKi=~wnx|0yW>3me4$!QC|ydkO#~|Q zEm$EY`UqQcw$4(FVhwL+@u6iLeIf7PG=K&ejOadeYc-Q|heRPo>PeHMvLrKFmx_f5 z62zS83P?c1kxH8(9QU9B2GdOs=eYyLt?=Lc$3yj>Sb4+E^BYnJW_!ZZoD{g-OMw%ndD#swA5L)K9vdC6_W^R%YB76Eq|rHq}80Q zy%*#a#A?_^$>UmRurJdmF!7qTU89l=ku8~dB||T6(jzy)Kd_qT>F%}JF9hx}ZoXxI z#q0MO2Aq}4Oo3U=ka%ic;Jc`*q0eGTHck?|bwz`~&dr-Rmla0oU(0$MVrhr3u{AIy zJGxf3$U&N*xS?8(8Aw3=OQG<+j)tk^7b+Y3%5RS=VyF}%pr9cmd#q{NS;*UzA(hM* zL>!%Y=`<@RDzZa1rL;m|_ouV_E#E^=CaSK=bih4eD@foaJyyc7gt$5HNXbq?(-4G` z2jud)1*bEQ#xn?MXl3Zgi2Bhwpm!Cqbzdnw%^$`$g6%C!DX>Oc@-cn0RTiBD`}wf) zA@Eebke>RIp1RDiSpwzydQWbG@Muu;R+Jl@k+^&i`4EomON}!RcZ5)VmX@D9BY!E_ zz7+5Q<&-P=lYSv={Y_t3FLA`zqd#54&bN-c>)0F|OU(^1%p0+xm1}y?8;LI2V*KKf zI-_pwmbXLq!D6BO(~yW}Hjmp&Os*+f4B~K8am81>#&c`<<4V#Z8;dF^_UpK`Ia{{# zPiyMO)r<yCaU8}`#rgRaVFN(pM=2MdIr z$qBoiN08more-O2Mfq(K_;cFS)8daUu47HPltmGn(g#;XpRNufiec32$d|@rZ!q{pn-tDOPiV>;CrM6 zYwWX~^J)<3Pv{v;&)O?pbG>FD%q#{M$^DH1Irgb7}C5NUL76}(RZ{&P54qLUE9 z1fRH6HqlE5YE(;o=RKwayO$9NfyM8;BcVm?*d|4%f&E!%9vR&cz-|(|FPAbu->&9n zkDs3MhU4K(ICg)I;IG*Y@RdpRpLqe+bUz?=gI-F`Tc^CNQV6=DD)4x<*!TRVG$>c| zc77fS8v*aEoK$#&zp)dS*iB0qjKO^hbIN&fxwenu@Sv>-Er0Zi1Hr;mhjr5mW9Z%` zW!VF;hQuyiLtXW@e_vpk{G%fW!A#+3y`q%lxd`6qltjZ{>J^h`3$K?8VF-?1r*jL* z`<_=%$qsU*MZs0Bne6a^>2}{}7LZ}?IvC`CBhijVEGLmZR`zQ~Im(8AZ2}CcVKR!& z--in-MIaNA{0nVll>`06<-7DgzS?EPpT5q^z8%{cX-La1)fEcC@_-X2h|aTYfD1$z z;c(CI!XTViTDY=3PHbYJ3&M9gG%GFGWIBVJza;F?a|}Sd{f_(yZ2i*E&3@u|LN)1q zmg+x10R_i7{)uWwXp+PN@ThpX1lSgUH2|9;#0z8IA_gsBti*k3)+n4`a)PmZA55hu z3a=8YhEGG4$I4jlS=B`)*umX(JLrKL000fiU;hI59>71&m28o|vrzw9=h4LSb?aMq zrZD8da(c9H9O`U670p^51DJ~J85Izmlcf11EFJWQba3SIB%8Bm*?%JI^$d|@Bmq5^4WHbc;acX2RjgK;8Hq#Ja$I7^{Vr zlo94p^PIn+IFyk)q<~B9lV=Q2w~jYhrxU+$QT%s#sJ7VpCRivVsIuE2LZT_r^ zLh|B*%<2wg(>M1zLuTqi;qttjt}3rq%#y;>cb;i{=|X_>z)T6Fln8yDq4=K$6oCvWBbVUd_rVAW zuNY!OG3{4@F{wjh^8zz`VH?8`zUtza-U(kJ|$4)6senra$OMcJCBr_MP$> z93qq%pW|mWX~vF5QOiOBu%1iW^e>7 z=Wyg!f_H9v8%I)f~CYfxI$*4%Hh^gBR{6>qaFIjk@Kv;&%V^@!c z_wHh_pRR+US>7i#j&~CN(K!H_67HCaq+;Kkh#tvbl#+^Qaqs#SHbLvcu!=NdOhI;~ zkR>yVscCquzW8=5)4k1$KJxL5)mK05eWI+~(i^Fiw^Cw^?X(UqjahWVW)_*YM=0X% z;i{VG&X?dn$KJt04bNUVo=S2es?oS#WCFMLUD3g+TdJ#9+1D`eLmZNluos&*g=JE8 zl6Ha8Bv4zXrR;Uf!?m9MG$6^7>*k$N7M;B!dhl=Z7U#nLbJHe~Yf20d+ei}qa&OuC zB;jx{k!vuhK{bfKfObcK{L*O1#O`rj9E5uPRH#Nsh`PHDl%0wVmbLks?||_INJBk1 zKdLNnM*qH_6J%)(pZ~M!2Ie%O37u4SteC=(C`;@eO+_>kOA8nw}AuP97G5} zU5@cl1G#Z_xf?EjHW;1N`dd_C7Tj?#VWBR_Xsda6{ar7<&gz2IV%vwM<-FTWgAqzh8mlWz`-9^m_GO z50`=DiO(#VTd_UCJsASPbg9Dz0{z)ssFium51NWe=+*&m3WII?h`qu5YuNs#>k}BD zzN9y2l=2(2ot+o{_ZNlo;Ih2b?aG;HTHQKy`L+Q*0Q5HKkAkD&D62Egld3%`(9a*n z#eWL2s?2b)O{pT0K5w5^IXW`Fzx*tZy7pKj4BXh5R?~of;#$g=EQ9YVl`C(nD!;k| zfx%gAsc$ldKp3f6lDjpA6Y95YU#zLq1lOK*O9lo!K0K8N_Xv1<4-$aPWJG8rM`3d} z0>mSCl(CJRPDZ|M>ZdYqI%tqbE5vu$aos=Z&k@nCNeUZh9d`7B0}xyB4HX1rTp$Zh z$hL?^6M;m-#)6JcN;%5++Wwa>eh!%=j)`c^m7I7A(CI2p-=*3^+x-v6U+)TF_ivv= zmOGdyY5$~v!K6*AFo|9+#Yzwgn~OcT7ziC8Io2(3{=86_a-?OSrvgn2Pkr#=AF&NO zb6(lP**q%`L_NhYT|dpX4N?wzF7#v}SNk1RF{MPs3n3~P7y+P3PwepggMJ=f(5HoX zHtxDe)18|g!?e77myC1y+WI!GJ1hoiJ^n{+rTMDC$;ip~CA-)%iFQov8)JEmPmEJM zXa}4kv8+l_9L&*NC6@EC>D@9kQ%_Wb=zn(PER1$x$KGVr%phfR9cs9N%vbHyH6iJwnqgzhx%enoV+7 z_#L}81m=5*Nw&^juR@}2rE1(3PXu~QF5jSz1oIK(@4BaHchLrh$Ih&T(#*001cNg6 zou>#z2|D^JS#K*9P=&3q&gp10Ykt!+hwSXroLiq_63D&hFOZ%denJ`Fy(>?$=zdPN zrW^tQvZ>abAOK_ex%~9GNx$9qzi?qZhD84c{^}>yni&-MRR|LnK-&u0I-_%PGHx|n zeowBW*hvJMUE$k3PF3}tGK~?y_=I{J{PN&S2L%30#F~6Ugv}H_U>R~&9F$K-ZBl&H zI$e%l1EP+LqmCs55BQV^=1MNGVuYjK=FK*JQQqpr1iJOpc{rsLQwywD!fOin7Bh0#={=+LX zwTLE+a`$dCO2Z2%-w62_e_7<_#(_EWZtv{@ZmT)7^f`VM(t0ED_P|AF&Tt!nAZI#8 z9X0W9eF4T-Yz3h!ivBLq{cu<53xgP0B--g46RQV@OIHjx9BGY$tx_w&1;hN8+S&<| zFH+^?rGg+8)|}jWHZKLiPkJ}RT`A9u7c%#uzGGy-=b&S1IK7}m`?7{GxURwoO|L#D zk4`9(cuH)-UO93tX5w-o-a?v(ET32eBxwQ!VPb&-HqZWWy(g;_-^D}E0BYQSvg4NF zSI|K9sF8}>QUPUa`&vEcoHdP}^}ZJd;f;R)eWWnJqy1X9Gm;RjAZ3=1fIBWCKR(5q zx-#g5n!+H@%Q=^5BizAvwthT4U@Kdf9-nqJ6|~g49ZGhR{C%c^4GG6zjQU*9pP~=) z*NMOdKVlPQCcl8&QCBfVe{}TJI3l-y1t!1<&I*=BHHkt#?(plw3AcB< z#l%2)k{qu{< zDM3*w&B5m+m(pO*tuw~xUp4&r-aWyk@U2E;!VfKY?iY+46vX*u*+zV|~A#TY(Lx{hv;0bVSPW;-RBK%d{8{~y-tj+IXzxG zgcdwR%q(MEk5>Y7x3j-Cw?i2W8#^xm&1=psN~4kcgHWdiJW7yOX|R!;>u=`@aZsq( z)I_V`L}!-L#uN1xIG-|_HKi3Gsal(1x&iUR2@qRgC5+W+MoMViQZ)(Kc^P=hVt5DH zm`>>mmR6EVr(DSsRPV}a{QgU?#j!+7zt9UZWqMdqt(spw<`4~UNPsLLnR){VfMs@P zS?&lcaM*8RUpQQriUmfSMm%Ce_Kr_^M1h+heM(^!N_8zMb+I9Vhu+1Hk>{>ZHN)x% z)wgaTUwa$B;W5n)O$${;V*}+Sbx+w`ZFdELfs1k7lpup4@Q%RJTUPJ7D}M{qCUVPz zRw9heWoCEq9@8K{3Be^~Z&a5P%+w<>!^u{s)sGVNLl?higxtV{;rhax1u#xbO>O3o zh@WaEoK)nd>eq_U4?%MEcyIOWWn*>k*QJ~{+02kh$yQk~R2U;a_OxgTw27aY=H=A- zR~dc*0(Qur{WGq5JUq~NB~$lCyXUu*RQC~gSRvZ$o8sTtn4mj%ZCKU4x^*fuI0X}n zi5wf6miAQoxLX?~nt{HPwxCGE)aP)ff*xeI_bIz;HYfuQC!m@)?VO56lTRMXbLVbx zmOHQ$dP{33dZZ2!p~upwv75Y_TsX;$A|b=mei2 zrih6aXRgmYMaG|uo9&Wb923R5=HJa{yhO0RyDj0;TKE`tJozF6)6_lbo7~&Xmm>P9 zKqKXioNUy5NtEXCoL>@tLpF}1X^5m+tNAQvt+EYSdCm&57Bpkryo2wJ2jW?>O;j~+ zwv&M3U*~doOX)6Uy|VNMgFmD5;ui%Lo4rpeFIT<;=CU;o^MZIU*!n);@)n#4FZDWU z{*YYVQlN9KuL}mgJ^Fw?4bDYwb`k_}?sOFy=h()5_*AhhKca%7&=A$|JKDo^TCLIX zdq*syoWL%sIrhTIqF|SqdDpXW_h@+BG7h+zj=>s>AHD?k(V?cMc+k0pHW>z_?}Cq%1_-&jpvy#fNKen zrh+Z1H6ZP`v-@fh^74;PI$X{-q!-;Sz>Ref@Yjj`adbiGw^>dsg&>y(rF*wF1{*g( zFb=fpWU^vQ01gXzS>UPe8S3{NCgpgBjh+KL42VPGg#ptRw`mcMBkmOK8B?blGR-Y&u&ynWK%HG|_z~Y+)NY$j6kt=)kU~z)Ny0)ZXd8bzYJye= zA))59^~1&K@@QHQ3xfxA)mXwi`LR1fbvm-uOHE_gUp<8eYaGJTsI7DR8@=#(#TNLC=;$oUbRL^aJ~YYL4%xk;YDHz$$J+T7mArOYL^i){ zd&+_KoHpUEgc)3<7SSZWZ(WQe^Ws)*M5}(MENN1IaD4j7weMTqid}ci5-~^QdmaH@eC8?-fXnmj&AZpuMEmKr!PQj!#9%jrA>F@xnUEKCV6G>dpZ1cs&4#^)!A_3PxGYTByK*(ANmD_s>= zmRJl8&(9WK>J?=*LG8y~VmexpukG<~XSCs-gP|^WHPI8t5uEUPtx@8ro=5J#?$HAH_#L zz43^jdanysr7>3RT+;&lycPWrB_jGpvjS{|y_9RG*G zt;f42+>1<`o*W*eBmuvvrlXs(BX>}1mMVgfQN-X_c zJ>In6Ao!HrZWl*6elAr@0d4C#ip5 zo#T6U)=*PU>Yn-(YYh_LFk`oU-EuEud4K=aL(Itxw6`6e;z8uf7;6L%3rfsQdUQTm zbn@KXJAY>_z}@}n%Auy8m^j_z%)2}<-u{n92(!z@#yTZ(bIw6WX64@B$C`Ah&#CV` z`^UC3Yw0$fI`PZc8hJETi|G!EASfD(pNk)Uw9={H;K?+<(KcAd)k8RkK zO3hJI@qXf`|6*9`BZlOY{Jmwd5`GT6eTqe}8c&^O&$PLt%Mt(L9bSbKg#X``ast8R{x{G5mtx zg4=X&Q?O+?hnlsOKe21fAjKl+>Ny8nfq2x^8BOE~J9PuQl-b>M68UdI*~jkLMqCqD z3G$uNEM6bsavpvv>SAY|ld~^)wvh9=-)pPvYmH?;V;v$#;Xl$|*2o8~ygk>q_{|^v zXhhPxSR&~!&Pm^4+`2bR+PbS=YOwHvZ_hVD}{#~r+CF@1>0^|zT1Y@u2iVLMs zC{fd3ed9t`;>oUHvKC#hz&{f&(CX;>y<%&q8qiqjqowD1*12O{93wNO4ukNI0-c?V zJ~0<+5kW^}^W_IGB{c_5O7*)e1(i?LzC@|@Y<~Vkym9sm{%wSm;^mjXi9{ZbaH5R? zIqkFe{`4Z9$kp#AqZNfLUlK!bqDuYKat4rpj=UI0brwviBO=cye?0$86gRDz)}G$I zq5Nv?=R&DM{%@s|v-4*8oNTWkD6hb~0s%ASl8kKMgs(Xp`nJw#?k>=9W#(dt-XCT6 zK+r?igJCJpJe7Omcgyc%^mek|9itUv^d1Q tJs0*D1iPc;5mEQeoEU0EbGyPv+tg;~nv$Y+7^dGPW|C&R%}j7HcVE0<0mG#1-!pz~|h_7;TGefVL(*Bo> ziPZC(KPq7JAf6mM=BvsfG0!l)E6SI)>w^EMb7@RK`|6uvMpoZH+K z$&=(~DRr*5RUdaCXXoq4zPWNpQ5LHt(49AQ=cdy0PRl_l$b)trXrwm`|_=q ztLle758jx`$scwv@0)+Jy#ZSWiRP3er0l)5+?_Aq!A=JsmJ2I!yKh`bcE~U{4&{Cg z#dPm*@!cr!&1Pv72DwaFCzOF%!>Q7g_wl z%vYl%)l^OB>IdwEmAT?!Oc87yg@p)`+dU#y5PxJDiV|EEruJKN~rk}QN?RW20U(-ae zMk#V3n(f7xuT>lH8<+9;`H}a{mh0P|7k6Zwjg61)%46p{q%7EL+BeS zpH9iGnrS){yHJob>4HuI=s?@lg;XK9^E_sh#!RyEoydOaRc=g#5`6}6^+HYl`q zIiJF(4LH*M{4>}1B$WCK_PL&R1cj&;SddiliEV=29@UGD(#>^wYqffQ$9GDDPPlfI zcb@GkOTf)*PiUrkWojo-C(pEYBfMkyu*yl+e_)V4BvUM_Oq1GCCyY2$HDNJjsizUq z@e=*0_1X40r7OvuLM|eh8}Q=}*rF2CrAZeFeVQSn zA(}8Ya&zJ9(FmD;On{XexT8W%$^>m>*x%*yC>xZ6e&0F=P&)*JuI44;TLZ}P^B63a ztGb@oR1w)3yqYCu+7R*c{VaNeo~@a0&P#42J9bzGM`iq39?kWloIjVHS5E{fsz`o< zngt7X)60`+jG<%p+t^Tv!9bib<~mZLysxG z)?_Q_w?geHY!hq=%L)l_yxJ#Od3mP1>^larC|%8@u)c3Y{>LO_M77T_|9P2iVlTV( z{1x|vX1|;Q3CntSQPH%Mj|$iKA7H!d!u6D8{nXqW@7UUT{TEB#n0Yi-CZ~Z{#rk!j zg0(oG*_Iu=r>gFpN}jP{q3R}&p9dhA6Np=5$HnA;^k?k)F7Uehaim0cX{4&2P z!YH4U;V6B>@}bUA(PfeUns{~7o3j{4GW*>~r3Y3t46nmGe%1*pqeHZkqFs+bo;U zmmK+W<)ci{|2x_<%J`htADjET-!#!X_xDx%`nB74u7A_9@@x*@hCL6r1kCZ&h;==1 z<@XoqKVK5B_NUkFSe)}?lUw%}^P_EbU#G==F!?@J*7)SX1J6JHF!`ma8kFO#zt--T zYw#UeQB9NA@6%)!8qVz6regAY>P3%-)l09hnW=bT*5xyw=l%(HuQhvi&aqB>fANCz zsW$w{P!W?JRh0Gs|ax49B$- z{r4OeJF>l4Q2mYdb%OaV-}!ge9B)$yVz1q_TTlAi!iNdWISsrU7|jl_-C&STV9sIK zz<7X-L7IUGhQsMw1&qAx(x2`)oj%xR6S0g}nk($>eD~W2+j#4^WJ|IS|DB?7ZXMhE zjwx4apYA*Upk z6F1SiC&g$-Oa}A0|4VM`6xAAFRbtV9teIEhTpRB!tAtJ5IS1~j-(ZkUU_Pb^4S%A;{PoQOIo=i8d3h(< zw#?smW4oy229xmoJ$qY^n#wQuS#s>>uF@auVNov)BktUZWf#v=Y-K@CA;{o@<$rb+ WFaGb2&ptJR#64a8T-G@yGywpfW<7!c literal 0 HcmV?d00001 diff --git a/docs/assets/flight_controller/accton-godwit/ga1/wiring.png b/docs/assets/flight_controller/accton-godwit/ga1/wiring.png new file mode 100644 index 0000000000000000000000000000000000000000..54ab5d1bcf144d946dfa261711c6e08afc35f98f GIT binary patch literal 51536 zcmb@sbySpX7d|?KBGO$$mo!5Tt)xgvgOo6I&d?ny4TFMocSwzNH;;&bfFRN^bc(bR zXYu-e->KjEoml5yGi&YV-q+sOwf7y*{4vqbHB|^6(mn)%Km@8!6?H(Mdq@xno9zJ> z2n5=1_eX<3*ar@JMxI6*>XI-w7k*1?H!B-{Ul%y&Zb-}d!YyG=Hl9pYHg*oKGAxH} zT`Wuv)-o)Hq8fr4a0MHCho}DTHoE?rdN6+{n1nTpoGg>HucWUF+{MPzlF8S_+0{eR zSBB-EyppaSl6TVrEKL7EJe_1%p4<^K8EHIcQgCy(VUpk%wh#T3lTIOX15-v>tF@bt2iN~5 zz((?*6xNKix;BV^EoTR& ze|CYSCG2i@%do)imet0Z<=<(C|IZ!xo7TtP#`S-?+<##nZnmC2mhLuB>}*^;|8KXG zfGm@=z}-3gTZh2^vBZCT|C=-WAGnU9@}2qLD@c~OAP@)_ z{?yn51i~Y``(l7HvZz5IEYNdxJtY;mdQMJmPEPJE2$YkP3j%@uYy7ouZ~y&}k&&@d zQ~YyVf>^03@bU5g;#sLFSXo&C;1dW05)u*u{gWprC-=dF2W)Jt!otEiIk^}Z7=KyF z$;nx%DHtfo{=z^Y5C#TDXJ=PVPA(A<5eNigp}GV7Wy#ITW~Cy(o1~`5&CNrhKK`{? zsVQ=Da(Q`qadB}$AW(i*c5ZGSIXQVwPVQe9JuOX6PA)Yy_1~FWa&im|3|4A#T3T9G zDvH9wTre2SN=?B=L&-`_K|@0W0)dYI31?zr27y4#V7m79j@;Z_R;s(4Qc_Z6WMs_D z%>T{#H|-uH<6Z6ls69C$72)B+#Kg?a%?k#Ba&z+3BoEiXwQ&do_59Dv0|gqxdN zxVaudxbD@})sG84&&kO(5EH}3#vT~3XlrY?d@A>do&B~RR0RSZnlZJvyWak@7Dh$_ zx8tA*EUYa$x{;C5+glKfl$e#8LWY&O4g|`|!V$s6&GhlfqNcV5fu^T1e*AcRn+RH5 z6uSk1{QVW2oSa--K)1KIcdL1QEi5d23j&3NgmiUvu`n~UQd7vu$=%+9Mn}hbd;5rp zh&DGjkB*L(mzU?}<}EBNa&vRX#>N=v>EFf193CFZfj|if3Dnfo0s;axHMO5U4QXj< zU0z&=oc0eGSt!j0uoM7O~u2*tEi~> z^5x6a)YPq<+{wv_kB^V7t?g|{$Zc2G?cvY5y87$F;>Y5kTSG$)dAZxMvBAN?Cy%*r z`T1pp1#c4)xa6ZRPJS|KzodE`LP}M={kNE_SOQvMjOaq!YK<8d~PT zzoY|Kc`q3a&%cozCH!zqZ@gK#_`WY%plBP4s#w|n6+N^mP#F2guX&`;Z(Z(?c{*=) z@}uW<+-C8_=x*m|+F|nz(#3}0=LQi&F_NTaS@}Ivae^K@oYpmeGn7k>4 z=~h7Fw2Ke%^T91VfTRCS^30tQ~ZwY6Ln`-*Q~26t!JBG zL67B67G76yaoZs$9Yk8s(!Se^fB_lJ*!gXPXX}qJx*ZEIRHoE(B@A8u7`7{qRYlD| ziGF%Nbn3Z})|dLZOE1zfyN_gwzizioL7|>)OG*RVv%|-duC29ABk!<4ekTgY1>YN& z_C8az1SO+!KstMy6RzKpz^>jGg=f|vUvaOo_ATEtDNi#*#_D6tZmGVDO3N<8IaNbk zYmku#wTcWLCJo4HPCQ}#%@OqN0IrNR$hS@Jpa3@f&3iJP`j&?&-M?V?___#jv(J~*H&**+HD0wG0@dS=a0Ii@v5u}up8(? zi8dCQO@5e&A#-Qf1QH*rGFT)5pr7uvKKqI-YY_#xkr3;)f4nWQ}*pyn%qE z-;o;bK84M-Nv|(sb;r4S@16eSuEfCz{2f4PW#)6clf-+R*r0c>W10q` zjR72~BKJbOmv+2UHDXEj|QUwCihA6-=o?gU7CK<_-6SnfWK`c|d^G z**x)uAy2}@vAU^BGDaRDHy^Iu?4X+Q8quKZ5F>od<=qLTx%71e&+O#Bt02_E3%n$1QaES(Q)qt}(0W}R&`bAmPeAm~ z65cA=Q1;%h5{#M;l8p=5N>;x4(r!>NfnnDHI`Atvd_Tsalw~iuo@T^kBE@fhdp7rJ zp^x@O<~f0{68F9gvN+maS3G3KnFAh7cx~H7kpfh;C`aqA^BI?jjOx>#l}@VGz2p9w zx#}yHMOk%U!Y#&9_}%2O>oU>dtAtlAmWm0#e9J|=_s62*tHPG3fFw-6`3m2%KR!eK zM`fZFD*G{js`q<9ZRR4&;masnx6lAWk4a_jLAG4|POuPX=^@ee^jbDjNT3LbPcE#P&>`K|ums6jq`k;;9jKOw` zSCesyt43WH?GDaO;h!CF+FzRR^2Z%~|1)Cb01n8z^*%bC$Bqop%g1S2XF?7~7~r9s z8|#RHfyz%Y>Kwl6!moCkv&Ld8Ge{yn?XY}0TAnK?vAGk_`QP#MRuHhCRF24lUS*bwql`<1x@3fC! zDBD*g6F54pKZ-gG6xt6u$-LhjaA-FHk{*v{Py;e7wK@38tOsBxIZbNqFq<; z=$T{ieC5|z%Q`DsK-plbYC;6*)DJ=6_j42E9>V7nB!>21)LV%q;M~9w8FiV%ORUnG}XtT zmLbo3EY+IC z0ODM`IY8Eb>th`T0zZ(MJ-XwecobUAPmaH*h2l94bfBO_HcFqXyB zd}fGjsUfK)J0C(FjOA9(x0Y>Xs124P9W!p^;zWiCz|PfIxx_l#6WbYQ^8D1nSQdlP z{Z`)Yr`pk+`#25^AO5~THuf?`GBfEo{k*3=i1D);Z;Y?^PjG*^ulKPHNfNl%9aici{&PVwXl z#4l#ZxvU zJI7V);IC(#1@6ZwC9yv1C3rZJcQqoe-$N69AoN>_O*^xcyIb1e3@XjITZOluT7r_H z9LO*uHuIHI84VbM{jgFam@0q4aW-CxdfN**(&utVVD%P?T6LrZNK?%iIi(up7r0GN z7DbzXcqxf0fysdGOw}wSgm5e@`r7`yhON(cOgcEk=1^i=5%ZEBv8UpeptarlnG_Hn6%6N&RB*F zOMZ53_?v~erR~9~W}+ndpYWLek@s0A+h>sp=rH0SZK@|Mxj0Sd-WDR^OO>&$R0jR0 zQgW4foMQ(#T`C0O)V}Apc86DHCcsCitj2vUGJFnRbxU&?X(Rld?J@<&&lutv=4F;C zr^L5%mYL-iZMSduGk6MDUllN#lH)QHK&jeAgymNQK{ zLi-cI#og3!uCh5t5y0ZJoLw+#JCHfk733@$GZwN|;2XCqfW;^6vJITP6k*G%vy4GY zneE1x(3vN#hz2Nv3!fLm@$HT$Xuv9P=*`>JK^-+{?@@aD} zspPf|!@&FR9?;I=o4Lo6hli(Mqz>2xUT(?=X$ndz=ReyPHpMX$c@4WCiS{}P`!-8& z_~CIdx}uXAn)9Yn7&^V#4%>fs)HXhud6;Mj-qi{KCqeG2Dx`;+gpDjySChOkT*A>g z6br1PHMTu|?f{mPUGdF3W)27(K-ikZdASJsFZ!1yG`t~bk)5a(&V)G{;2)IG5e_}4 zTVh6PKN5vIk4&U>U)Cn0eQWeJ?61H~KFOy@U^eum6dJ6#E`z?{Qb>JErN9y!#91z_ zF?p(*Z}K~5@uyAS9t9#!KKU!BAXrKQ4A8wsC)rl&b2Uv$J|_fb?!S_E5k~HVk*_s+ zj*M9=X{EiDBJQnHhs%Sz%9$cz&9+_75TATq1S%qa)0)L z4m`O5r#f1uWWt(_ zcRtFp?Ft#kk-~=zxEbNL@K|@3$R?##r$q?`Fe|c2<#cxZrgV5=Vd0=OyN@=QaZa{` z$4Iqxky~g;SbQk!Aa*Z&pA|_0%vpK{cRD6%DwexZ-!Dd8hS#@7dR0!4rrdFto)l5d%@^5xb)%%IK>W6(`rPgqQwr6!|N!jrRG8FG|{j68gS28}(#j z83e~cl{=CgEmZ5fE9jFY8w0i{3Ot+ulb-6pllf#G2lpl~Mz{-9-?1$_Gr6FdG zT0a&!C8=S%qaq0#)Ofmg=XaDQd=L1T;nD}5BzL^*gRZc3p)P~<;WD=m-}tMdka_Xw z2Z@8>zRseAcL;(hNVL)y+3%I!G^Z|8<%PfUTtH*T@bTq55so#1OM1x>$yI7Zdvv0a z(S(~PeI|##`!(PlT~cAj~p;3@V0Eu>Pa_&m1jPKYY|@Y5I|RPR>wA2ePAtdWIqj_RYURprzItUnY75hZyyZzD~?J_QdU%!2n*oo2%=PMTrKd z(3snUwidoGFyb~$MBIxHqiN1LL(H5P4K4|Odtr-ayT5ex)g8W2OO)mp(?rM(pkU1z zD|6ya;`gp$b+ORF{3c701M;UyObP6#8fM2c;bsquoG9~;umWloT%RYsTV|IW4Mqih z|Am!EVjK*tfe>-C-n4eogP3?+`=amZKi;sfg)ux84=ob0ZQ3OCVIl3;yjht4$+|HR zq0|wHbLrpYONEG=Wm`()D}jioT)J;Ds+H4MNLov&yaoJh)Fv;&W~wcdx-FJ#+EAO? z!$&i(c@z8!BcRF@XAAtYJ=;WKAnzW3f@;Ql#%F8+^7Yx`D$zu`)0dXt^rxz7A8!&> zh_ZR4WGyJuIBrjzhl`==s;o0d9Pkiv++|6&iWut+hDx;oZu(I#P=NE2FY;}Exf--GPJNc33D>sD%d2pYnyfsQUHKNRXdK=rA33DL zWUTixfRx!QFdC{{o`BYsl#`uLX0>;XJr0s~S#{)2qu6;YyKI^!B;xI2@W_~SxTDUR zdFcgWFC%uH1({mbh*dT1kC0{rOJSxq_f@w1q-N%+hUrSs_T@Z|UVXPJlGABuCC_|p z1%o?d53=05zv_$fe$YJQkGM)6ol=boY?rZ{^ZF{2;+tY9AT7omOX0LyJjIOI&x1P( zqfr-a!&9wQR6wlT49BW(bnucVc#OTLg)_xo2)$DYRHeE%xYlmm8uOa#t~@s=s1#mD zaV-j(IikoOfopbtd?W_g6~*X*rC+JS6oGFWe}%BSE$f}EN;1XprQ^_oV+9_3lG&-% zu~6DG4ufB#7W6@YwGz($8mvbqEr7=H@FI_Vd`v^FtL)60VPro`?6&MWuv5$z9w+BQ?C{JG6CBX|~JNuV#jB;(BV z?u98cZDg$ty1@LNUB1~37c&8pRr^nKoC(SstksUkdMIHMh29@L(&zV3$$gE6&=l85 zZp&Tgu(`#R%-2c*ep@!Z=tlWiksdMqhc%*;-3}YnvzZqXvBie?w{Xq(_xLO?JjIF zbXbnPzx?m(_n)w2Vv#slRay*W?$;UmX`&f?&R>$+n)SK7g~uKzeBg(sXQGXtFNM;F zzgj_sgqOGX{+7B-qpc(YR9bkSu63Uh$>dj>&obd4jN!V?*;JM_EP7lQ;b!7nDfT&L$7We{f6(+4sKam zE979QMI9Lwg?4pT_W@1*dRZ0l@GQkcaz-o@3b|`f zZd-bl_q|>*rPk;DveVLfjDYR*!^Ro++>#SwU@i)+7Q&2F;fl)D_1oT6<96fd9V)g` z??)A#b@NZC4-q$UPJi}!@mYDd1XM`LS>5-P~Lq^agT`>$mT7M9C)TP zKI^(GH%WkRkH?4#Zljis7&U^WH4h4hh%o_LE{|+xr1+>TVRd(cy~U%X)WMJN=yr9~ zew2&@`N6shcx>fjEaa*(=O!E1JN5SWp<~_Zi(O$MP4jJ2Vt_#j+*PVc%U)*vT-f{B z%$WBF!r;fL^6M51g83GT)O2m zI{x+~#k|x9{J+DVv%Rq@^JD%tx@@Xu4b3Juz+OM1@`)^ze*1x!w}Ic=8Ea%?_|j|k%E zMsGv{2u&ToQ1m^p$(Ch|+Nndz=Q(OAbKNZi!xR_)OS3wW6>Fhuj0M?~!Rx13pn8sH zoBD}UOTXQYZWV7D!gOfdK9LLMvEm&SBec#rOYsp7=RNDun4%_(xT#fL?mRK}Z9m(;zC}>mD1b4aLoI}a` zidah$WU;}euh3mrzgf5B!Y*=t)!d?U6)fgndT^OuRr`7{P@&$Q{=6uX#o?Q7<1~Cc zZC&vh*H@jA6tozbkI45OvW}NM^D}{34F|p*W5fn}2pqh1KdR1}--2gRa-TT1 zeV{k0M%UsBU;(XH?k8Uby+YlWzfg=ep%gnCvSkR4DqwEv1z!C}~Mxx_+#?{r4qS0lWz@K(M`IJHpg% zq+ag<&KxsaSAg%STYM5ghBTz2V53m;gUE~Ociqw&P{J3Za(QK6A>rzaVn;C-N3df8 zL4+F5(`WBu%5SK3)XVK&!Q_fK$4yRgm#N`dIN(%bGfCGW!VL#`9;PF*S6>k^m(rZJ zL2qt8r#2_MOFoMq47Z4&XsRK{X2nCe<-CCen?9k!1Y;qO-=KSwJN6jbhGg?R2-O#2 zfJg$`x(ROvvM32%tYI#~bb9djAlQ!}w1j_$FiMxt*{!t3FI?Oo8D6SRR0&rJ#!Qtj|e+b=pp zcGYQlyHPU1?6GqAMN7s5Sr3>z2 z>~~F9b$rWK_F=}{=7(AfV+T*ek(tU}6BY|Jx=-$&d%zSZ%x(IeYvMiXa zr1JKNu;`a(J7zh(@b(NRFm1^@Ol0!u6ek!SIKLbVizE(+fXP3tfHpQuw__rOdk_>f zhknwrNtW^ZD>Sb?zVN-&cA(yF9;Bu(4Y};Xb13il9ptK8CUxfQBD%Zc(T~VqJ?=-5 z#Dxb-ppV~di6Fk%$-3kqu1d9{Pv_zgruLl{fjf^*id~b+X;b9a(h4&^X)(W2|ME=Y zb*!9Ucx}PU$|SgMC(+!KregAfH@5PdZG}@+2-6gZ3Rq<#g$K!}3A_I*4y`q$<(DRk zR1*zg|6F$ew)mrdgFh8WJBQF+ZIys$XJ|pay2H1Hq1Wv<4eS6yGu6!K<}1t8KRCO| zM_EEySMgI}In4w@uneUGQ|(N|q>}*O_!=F^T1_z{+^1URR~)b?Q>ukC2%gKr9`e>| zHpU*&(@eg$&TM|Mjp@K<2yHag+L)Si(n16#_4-<}w;t5eCzgE8Cef8L!;+_%*LVE< za2*G2;LX$DuNd%Hee}L2*nLb7tA3$=+Oh3bQK8G5qNfA`uV3>=(h))>>6Gz00;wxJ zTP~jk#GtEtvj?XmQ1-=NMF!p!!_ubgv1D~YzrK+OUvxJouJ0#S(cIfPa(xjNlv(bB z6S>ekwJIk0BhMfHJZKVQ;I)aA&er9l>V&F*79r?uyo>x#d=L}(#QFLFG%feA4c zpJC=8;#@kbbm*^gV>O@2{mw{U^#DA9MEfo7-N!nyxOG8{PJtTW@$t0vZcP$6J``E% zKXL*QchHGte&^Bo8TRIz2GN(tXiu+M`4>WRiL)j1qruJRP3r7qNn!c!1E^iWoafwF zNDKfK7TB%D=}g(&3mcw$fLWz;-?{``XRmcQ!X_3=@9EVVJ1k?#lm7Vqp*MWw49D5r z69bM99S!H?0C=}+rGLiPJ#R5f63Lcud;-TZ%RaQXiE%cGc5}(KtMAn*m$3Xjrw0N; z(OFk}Hhh{z6ZT-t__`Mvws@j}LApnoO0_Ig)w^vbsiYJwQuG$LalXq&m@7%hAVhPM+zZ5`9{GWp=~J~f*gy^Jo*pGoQDajxdkZl1;D8@s$NWbkUd9 z&SiQdU2pyC)2BxZ%rIe{KhLrTaKMK&NDC1+d?UV45WrheD>Qv#mhApOKaL{~@HazH z-v0cxWv}7zc_{(O){RPo-p4?q%ZFO8FI~5OkEX1^Ug0M+$oI)(UXrg{9r=$igcXvF zW+O2GrstZ7FE4hccQus1jW^J+;TjedxxC-h}#W$@Lmc`#r@@v)Nexl zYnK-|5*bpo!Yb))1;(Ifc8j>n)Yzo=0JF1K(E(%6PhIStV_;+V?&V! zGRopHb_|?Dn=~6I@eupH>Hh!t7V|O~A^`@kteI1wH6~sgpB69elSwzkz`PWRg$y4+ zH2D79AF<3kOHC4Sq_=2k{vp);Btqrt5B?CbH^jP-ddtcP_-uG6 zWhm0T=za?P^4DRVKqzb+ekH_rd`(tl8BjKHkCO)8uBySFQuiS~a0g;&^jxEXK&2!0 z7?(VH>**IM>Q7O3d-I}E^d0lk>*Kx!p4f`h89prIZ> zcchITeF!Eq>Q$XB!vY^-4~h!A$4H+RD}aQS(@F#8cl{I+b~3}%gY=mv(St{${3Rav zP)Y`1VA_^(p!b3DItJ3O70|UJe5>rGa>`l~y~QwrKM`#~UHV`jjD@^6fGFp)OnLwC zbnP%KG8BEfGno6vXH(tM$-ZK{E&sK>^c0G3frcCPVf78~2M{X-49#~nM#ajI`H6{MjRz(2vBtwtd>C+E7UY_B6*8V(L=+N%~2QDA{%Bhj%DB$K0Fo`lb_!8O{V-ePXdju7oE z6R!jMrHr64&A{p$AJ$fO5Hh^)NQw2Pub3Gl0R!0mCfbzM-mg-<>?hrg3WaLQ!@C7ODcZ>meXo6CFceH4qpt0)6IBt1JI$mdXtKvi-KsM>anm<^%q2bKlMZxKBoT zw#;=;*z)0^I#Gm-wT?e=tT*{P1?u~+)A6x-x%V8jWCYZHP@YZ5Br}|Ro$)s(?)Q!p zQy28Zp?dP^8P1>j?-RrIGL15)GO9PnS1R7%+jqt1tS~99#N-}-#@mzYYd@2LBaXf8 zMB!^DkA@(yibcgssJSqbY+!zeL-))xSZTs;ySx?Apd%cr{b34Z-yl%B(Jd-mDKD@C zy+6$F@)rVAx*el0HcFZtO2#Y7zpgW@wqTRnJ>!sriL4EqV#pP!#rTWN`(T6>YHh z=nAU2&OJwgG?512U*Lg6;KQ05LbuUg5l*s&-jN7MgVFDH7jsTcQg3^+Ns?#c%rLrYv|5S>xRYM=;o!2E5Nv%sI`^k~&tqP`$AcsaRpoT#pO*ZfTpA)`%=e)0D9Crd;Vlw> zvUTcRu#=Z)L$yyp%GBI2C ze;nRZHb*I+V!1Rcxie48y<@30vtyas3}c>}@S->7235quicC6QE?j)yBaB$_J%b4xCP%tD_ipsXYjVWl09W&aSX}xhFm3uHF zbw)Jw=Z61Ks(D5#r_un zaA|+K*7MEIV3n&wWA&+??xe`@PFaQRHqz1S36%rwS@IJ@ENbAz+ZW?;CUb@n=r;64 z;k_mI!gLBdmstsOX{GwhoX)v8Z4CFc+?}Gx<&{s`Zdf31ENo+Tc zvDacI

-Qv{5fT3tOI%o0xm$1E|DDQCKCC^$T%QNEp3m&NUQ#=STDTl7(}vqbrX$ zS_(3yTUwRJg!%!|(5*_cYglAvMZOLhnC?mNn(E1vIuOYAH>;9*BJPSZDT-KuvOxKD z-nH#^_I}4w%$$4-+|p|xl((##X0^W|cwy2HRrjVJvh=w808sK`R_26y(XUuys*SXD z6xEHXfN#v5{*^Bu#iXlxO%N| zud{}HanYASh{~cJK0xZ7t^$u+Vw9SxCS5_NotqEaJnDAuN%{yNuG*KbHYaN}PRE3H z4-dVA)8Z|#TqDr-%g}pe4?ZzTf1eC3WLc$W1&QFu<+a|g9gg$F+(C7i9bG^tsM_g1 zlPOXGoxhkUQJXtxUnYb1LxuQwX&tYOQk0?}5GbGu63_*Y(2-YBMk}s80&ldz9;D-f z581YGVlS%LNrcm)D6%jq0{O!g2>`@Zvo@ltk*c-4GxtMP%gf)~K^d#mNE)OMDG>er zoB3qqHReF<@Sqw4E)BG2ZjBrFw^cjU#uWdm$3HT49h4hUMBhdGp z;RjJ&1HPs48><}b6J>cntV5$P*U(Xd^>?ftd>4GjM57zsr3e%OcRkF*9Yh}wOs zC*Js6&2$BGuk=Au{WGhplLo)18%?viJOl(D3Wplbu<*e%vr{ zvwa@GESQ>m^3_M~?|8r;$90y&|5Xn z8ksgDzU&PsU*PR&^wQ774Fkh6 z4AIi>T}`8KRBvHs@@t$6d_+nPJEilOHthJ`gHuRACkIih`naZ<3oPzw#>J3VaB^> zaXb*yItzJBM6lh?hBTpwKvSf@KQZE7r;@=$r*SHM?SZCX&3)SEN6Ii+ELfC8$;359 zq9fHSsegXoc4+m}0`H0-#||M7*=TX3s-FrYVBT<_>zepVCqD6$LKFAwhwV@n3>3an zoa>`AsRnHd=9uMFr264kntNavliW}P|KU3u#5f30XN5rtv5=}}^HnZsu2PkL&|ruR zaCvXa$LeZhoQTY^v0@RVBKqVlN1|-hY22d?35&|N5;aFJFn+OjX(+X@B?glvesvow z@eOt(N!)RY{wB}KtTm;^gSq`c#oz3~<)>BZxp9a+?-&jOL|V^)^dRIYxwv2{vMd4SCh?Z0)x#S81%VUDA7sapIU@Fmp_n?F z2H6w~JCBoTD8zXAR#Dt3U$Kb>x_HY+L7s1DyAz2EiJ-??C|k(8hp3Qbj8>WV7=f-667vY8%X&k>DBoI(UT z*JUY~MVTn*5@U|BJilh>>vz1)b@AJUm#;M{mfBT)au0V|e5n_p5j-!xAl^_>0cWZO8C$m zI~He;c31`@9w4sv&)?PGIuirNJN)llABwy!7d26+SfPIMBy}*!cP#43BdyS1g6~W5 z<^8B<`nAs#{DQ!#L)=WTeCZn9`KOO+JWJDC?AmKuru|zJkpNvU1ce=vg;7((Ggbb) z+FXA&lIhQeeeRL?d+5#0T&~;PjYb^9?_oJqkP<A~hY0EAT#Q3R8jY>XNsTN_K$B-XndZOpyB5q>eYzLQw0-gM6NeJ@9*kRJ1L#Mp zpAzR}uB5H_qM-~XZF(+zKOA>|Mrp(d&cJq7%Vq4KwoqH>B0ZRK+;JcorT6Ze#7ps{ zd_hU^l3$R%Bgg$8Q~}KOrT73z4w6hrgYu8e+d3cd8W*%57+8NlzTV#2rj`-LT0^{55kl%XH1Wjy z<+(-oEoOpZ@@J)ceuM!g20B;75-2|7j|_X~INHvlANQdCm%BB=iEqCWqz6^|ncQ4M zz$PD1u{GQGffDEeVOI8&0Ey1@afXBX)N-^Ue|BJ@r&7uAqB<^;Z{!?4Uj)WsGvn-V zh61cMoP^IxZhmoYeMlEZt>N={QaVFz zaR1o>H@FW1rdw`qbCYv%P_2h|iV+8u2K1}0(;Vy@1o5Z$5Vz8fq_GWXQUW-;jfi#+ z!CmG%8T6Y*4`fmfENXcT|D4p5wQ3#KB^B+P#*f_-spiDeaX#%|aQG90_LW8~DPZ(pjt_};yN&MP z)OJ>4a34a=gZDwxpi@|T(w6j?#Jp!_{moC@M~$A8MWbD z0M0+2O5xO7wtcs3c6V=|{6mIh6a(_Ze#h&(y#SrQRr)hd@4(#TB_ET0x^TVU38daD z;F&sGyekX>rhE2h#O*%&c5k1xkl#uL+x5*6uNMLf^KarqHJ_X3PBU*{C$C{pjvPlF zdrczje_ZO|A!qf(yRxW}(S7mRWkOlK%Uu5dPOO86X#sq<%D=k%cND$Arx<_Z=4tL^ zMZo@H@bb9oqXmVuSv=ZAXH{$qlZeoG)#u~-dcsQ>kK z8Cssr5dAG}wXyr3-je-&g#Jrkbo1tZ!N0=p(VBSu#Q7TwDMpdk{(iFZPcK#JX-yVC zg#MLX{goOiQ?zt7LR1=ulzM!;6z4C)j!yTaAI@Bz5`-tc-1 zEu)9D_vnB6>Po>)cx@;lYqv8_WBgBJ6)g&M*3}?Ah*)^#+Fd_Zo#j!eGD=#=HO z?z^%+=#Q4;0+hC&1!7i$QSYDFEQFBJWsm;~=qLzak)vAL*Y)TtoUYkE+y5x)aH#tF zv)-5QPM`I@Z0OnuojDOTokp_i!qqDuf=yD=;WGkmnFZIo3{&&5o(?&$CrQF7mbP0~ zxOTsgVjzM!RIrvl29pPV- z>}MFX(vG4&8d%KO{jkHkTdPbr-8f}(Yuny}t;cl*`xzStxpHnE+I0n0`<@@<+h;<} z!?)Us%qErgYkGd!Ds@p)Qmr?2?4E5s1d~C%aRHt}UB~qLRdpNwn5jc46Z%+xyNqgN zkiOwWl$l>_!GzaQWFMs;KA@33^}-Gs0pk%N96m+W45O5B!BPXLU!B8Cu`C5j41EaU z%_k$f%6+JNw8Qw7^?Z_3kHTP_5|r3WaqShK9)XiGrj=KkSJ-}+eEUs}G)aOz`4KJk zqEU(hsp@AX8ViFqc4typj&B+jV&7f9m(n@W7t3jSYI;C;;mV9Nd5lWwa&x$ZLBxJI zD+!b%nQTHE+=tqJQ~HL#3l>ib^~M0?jnaGJ>J@Ns{1h*8WkwoUR~hI*3?roLSQM|6 zp{_((^c4F0mAMoFx5eqFNkY4&8ETY$#=7mKP%)ZIshv1RWXI^y+C~lCAT$T8<6&mz zp=cDn6{4E(o6=0|#^(Gp7zJOAwlqa71zvbQPWLH)DYT zDV1(QWM&R}Y{0w%cIW{XnU^9Q<-K{8HM!TJ3Mn|mNr2sMvN`Yl^e zYo)P|F~8c!Q^}t~dl96_?ARRE$9FeZ^S4UDW*#?9dTB9yplE}Ng+5Z{?m9wTg9XmN z;JltBOEPfJ(%06=&GI_YM4fkR0E>_6%o!XSTPD?dQJXO^sOuwOsSk0?kSs1SKTgu_ zdcm&00!>XsCTu(!@$aZFnrZXITq^Y0sq|5E(-LU82OOyB`5^ECf|Z%ua0`v+=BJ!D zR;|m;(a`E+cKr=#Q>uZ+NQpOIoq1JH^Xb3%#Xae7Bd~-qtz~@0o zs=kh;4UC)3g%HJO;DiVzlm6E*0rxD;;$!+{XVh-(iR_Y;tp9oIS7@;D7X5J3FFI34 z&aO3oZUVp+ZFJuJ5bBBztdu)Z%{}vT*B(jYq;d-^;QB=VLkzS2l4=hVAg$r*LV}+1=elR*grx5Q`cvT}Y-@vZ`iH%|wIQXD9=y z0V2XYW}d^SvoW>Ye5+bxU*r?GJsfP- zfhH84-v6wo_G9&Fbniu!PdMxlnW7n2`3Ov))10hvo!jxp&js9u1>(o$%LsdQA59`L z!{@5w)Y1Qv2v?K4?HjY|>!ITQNL#fC@(KEfCf?~;nEC$;jb{B8Rr_^uq(n*)=>v$g z@V)iyP42cQRP|#?PhZF5b6u%bT6W zn556ZZ8kRU_zu!^(;qGk+$)np&9-20D~A11a|`T!u-NiiltoR$;=-7xj7&Jf&6EHB zu5My&Kj!UIbrPkF8fWOz6UbN>mCl*UJ6}qVy&IJCj9?B$ZcUS85|g^BZ7^Uwf8iH! z7IIjQG@Q#EJ1#2PH4gQR>kf?BIsFs8`?pvow>|t9T{;$r1}eC%Z0MlaK35;X%DIBe zSJwTJ0rK1AvOlC{Wihg0w&x_l*-@DA=3bqO-g9nR*1iE99Z5R3-{ybvx8o_kwdn*L z+K?IF%}~{%i5N4(&~XyxJhR{KkKvhUFb#vhI1@B}OW;B7OPu3LuC9|S8+g<$Yu}#W zKHuoSoAY?>-rT5zr}NA{-fUIeYS~}2AnOzH6~7BWw2#$yCB1Nhu3qMk)R1#)&Z%cW z-X}97Mdx_>oj%=E<%QhIFYDWqPM`VnH+NIxt$vr*{5eC<@HU^mc$*1>nqvZU$yIKz zoG5x`ot7QW8t%JcjEO{ve`Ig{MEUqWb}J*Bw(82}VQA3-Vn2+`J>nO)4li^G^%p>V zm*N{X>Bp#sAy`y{#7x)e(OV3VhRgkDxuy2HAcOD6Q%}%-MbgPZAcf}1aH*=%y`u>g zK-^7u@kfl=HZ2YHRoU>es?h+xfOY{+=>_(*mrm8lAc=glI>qPD9I6+slr$advv6Wi z_}6i>rd-j#Zlinb{s@1eCL!1^ZdVGe7ozLBKv*s|Y*C>S~AkkeNsi@4gbSP>Ec*TWF~ zH}3+HJqe?}E=EDO)lELQPqQOI=qC=Z>ZT3Yv;=phc%pVo5TskPOzS7*hBy=j54v#4 z$XfiR*3bTB6J#A3pTeB!jQDto?G%4YQkFglB3j;NaEELEYO?kGV&HSJz`MAVek!@x z35H%LvQ)*K>Nb_lX3>hHgyX<%KtRUTJ zgr7hwrR<>Az->nBk)GIAt^+IKtj00f=O+0u6Y(zLgFNDIw|1c8CT5_~WWOEcVs z;(sg!&zXMEB?T$DByn&DQrgqO+4@ve;Y@1ITUN&yFGb^r8TkiCnFC>n4q*NPn3fcj zq-Mr@uU}mM|NjDb`hr40x3jkJ(w|!A{AuDDhuA_kwzx6#sh2D3`kB>f<-Lq&L`ITY zT~#7qpJ&wn7G-d!KBr$f5SCRDBJ8ZUa^k-!bRKPz;~C_E#};B%TY@^4TcJk>A)ufKvnLC`v$4FsJ~J|N z6DB@!o>=s(uJ{KvPCX;1?6Opi{)5qVFWDP>o9%g9>m5Ry%1yWhSAS1gEkSS1!O1J45cyk$JuW$q>kI>?!6 zc6=C+?BTlE1xll5IHg1KOc@m$y@-}mE~B@<*&b`I{mtq4*q6_(cW+U2O?h)DH7s^q z+{loFqBzPZZ0d*^@|uv1xbtj(=*WIE7yFCG6$ZXfc6XZj2_QkC)%0fsPjaxtCCtbD zVBHF_POb$b-v`Uo!;c#Ac4ME9Xl0j92F>ZcPn3r>{vN8SV2W?}U&X*FkNZ%)T__pa z0bx4!5gDwF7YFzhyLIvceKAD$qa8>{z$(4U?0edci|mi-2d1-W^!UtyU55|PA3h-T zeoDmdwB_oaC6xy$7#R{3b3Vaea6SfTf0B%-Ds@K7BESO(#*BIaO$k%wl3K^nWKd36 z@YNDZ%Rse0L9K`@yG3*_E*<`&jxcw_NO~t1D`T%3j{Qphjg(NMR6XX0*ij2oIZ0h% zKKki5=GA%%dCT{C-xnf1wL>Ood(1?p!?Bu;16zJ>LqB1n)B#kEt0&5|eRWX&$WnQ= z_Q29Wf6Onf&9d4+S9r4tk4y`Y@CGYB9&^#s9^(gg9r7FZy5QY^LPPPvGjc%e=oeC1 zz`5RV^yMNT$o$ch+!m}0qP^`oEEgJWQjP7SZ+(6TqIywhP^J1p%Bh%~tHfJiK8xD$eR8Qx9bb#wtin z+<^B>jSDDS@U4ri-RU}%AW4AF#j#zW6D$B|{X=l!yZg-Uo{b#^Wn`{G`eT^- zU||RrCWs>LrhxG`lnV`?X_y_t4--rC4gXs=iefElOCw(O*i^z$%b1gB)F&H&CW?57 zD|EQhdc6BV-k1kgz&?;TH;s*6trd^d4ab@;Vft`bwX!aZc;wTNi2j({OzFs8+_qFo zbfwuGA4s5-;ye!eia%R>c*kzGh%sRYV{H(|QBvVVq)7E%SM=7-6>Tk?_Qj%9)%g!0 zk48wJu3t#mYHDxKnpYg($wyzBYR;hCmBHZCM;6d9^{@z%!OIf z*xl!?d@9Z|g*2mb=A^me4bJxV?7c(a8TZ1A{oRRnJ88FUK9ge5a{A-fjU3V{^Y-CC zT`qq}KySof=^#NEl#UD?2X8$H{b-62CWW4S?7|V^tsr!tcl}^Y*us#GV9~V$iQ#S_ z)=NfvgyYFD>Lk>+t;!Y1XP70C7<-SEzZz*@U75E6u2-MZLLbQ)&!|3H0#NIe3w&pZ zzFEBdJ83U$g&w^n2@*7BB5hClNzd;jUOJw9#D88zYN&OH=@1TM?Lr=GjH0Pt`b$Cx zDf&D{sPeQPR{stVJwG^3uI@jaUQ$>kky7NnHRr&%3VXlv-B&X}-& z(k;y_E!nJqDi`x-Q{w;M(BFBq!+Jp%B}b{wv)c9Z8U}H z+AH%F-hj&x+G-utbg&2T(8#1wl^}b{S$CH zN9?(?>R{;c{=Ce&!QudGf;;c^z}#i?_rxp|-u#rC=z;POmDfhoq?T^M?;2eqrsuXB zYsC>RUXPbQP^tzA#Rbr3hJQ~_!LDU)_B3x!H$T1EZq(o0c4~L*ps5wd%M~$7IvJzq z$@9nKDy(_Ce@9)qG`rfzq$tke1ZV5^Pr6s*us;_}MSk0I zG6L79JF_O6-QO!^7Z`n4VF5v#LgOr#CD}-}QrXn|xA%3Eo;`)H5I(sJuLoGu7}t~! zKPd!;T@-%kD+4k_Z&N`(PDtK-t45c&!wy-$%&1)B8?%OX!&yi`+->1?k9jkc?5i=* z2+ZB$b-oS}S!48F##Pjx%?B3nu%_!+QFe%a?cyKZ>}-a=n`IFbdGEPE-=L5Jub>6v zCnz_)gkB-g`NBcK^$|NZbGLyn_@QZ#U)N+-^Wh1)1BZvo68=Rmi*}hxJ=Rb*n>V;> zXqNlS=!?Z2PtQBI$J}-)Mc##eb2SD1;)LE1`I;E03EYKSzwD5E%VGHe!r7D`4q5~a zGsLTJj&2w_!T?^6*>{PU3<*v zyNJu!+t`Uc{5}S&PfhFk$$tjp!~$5p@qQq-;!9DzRL%g&<9n;MwfvjADQU4A*R2@% z;7IJtK_ZA|WI-i)qC4x3Lg;J_TKVU)=CQ`VkHz|SqcMElb@FRU`?Ltqyw!h8DX75O%gQz7%*<`tg zp3mmwp@Pr;I$s{AVe?m}kLrc9IDrPRA|_Q)ncXBT z?#_3LHah5XWU>e%1cxN<+%R`vHk0A-kP(O3%D8R=LJH|3@+SO`yDl(@l8V>)MIQXB z%2Wl;=6%Z;`9N!CR=QqolKN~nDALJ!g}noY^(#iatFc zO+GV9Y-?B6%j?GIOBz>oZIznWOS!X01y?Z(H>7h4DH$lBT3m&n+M0U>l%ejoTqvIbo6J@Du z#O=i>Mv?{l7JU!EWYawHxK_7RKjf(NuwDY)q;Cg^g3*~s(1NfnnQsry!F&c9#agUh ztpVXI$9#_WD<-}wI!~xO` zekZqqaq{P%fAHV#qSaaTBj>D-cT{GX-k|@3+y6k~o(|Zz(L$Dq(H?9!;ysC+gjZ@g z-g3M(oS(fIVk~Td-90U49NeFm5XGjWdf`Vsu=-RSP(4a@l64mg2taJH@d}3 zy_J@p=K}j*HNffbVZtB-6o*B3qg14qep#0(P;GQfjcS24JGq?kvH?M%v7=^TZ>z-W z!!mOaU{tUt|GucqM!Ul_M<4tJAPNrfLJpMY<&C8V>@(hO93mik>od;JL+oe;bM)7x z6kC^`iq%ZtZ^dk7AocSsy5sJs!~W}NgFQLBC&^qVx0#K7G(4FMIg^$Q^?jG34MJtT zZovAc+tw2dBa`9KlC83Y z+cKQZe--XMVzFJDPJqYRg<$S~-WY#VCWWqku{OYz$B;C#6|a8AMf9JFIOH{eY!!#X zi!gx+U8P71j4f>UJyP^>Ck-TtuDt)eEe|_XpaqssbWK#qq!^(hwzKmKFwOJ3#n$!> zd;ea=7s&Sr5aXx;+;e5)tpXdhESdA0k+v5>9)MzE^c`AGGN|~RNTD8>*zUTUq9R)L zxCGNn+5y8(GDEjMiaV5nHw}{onR4;wyYV`JBQG4tfn$?y_= zHs0`3ddeEH=adVj?lQbnNwWN5yh;h`Q^G{(>5xCYV+RZizYk8EVrIJc`(d*2l1JwY zm~mq*buV^kK-yDA9OmhrQY&SR@ApDkjO=S~j3(vF5xBP6`nQx1-6+n%My$$u5D5FH ziwSbn<4_?{F7T2B+_So2%<;bN@_f$N?S@q**+bK5F9!=|NEASX%)LRbzU({pqZ}yH zosYFM{=gGQ3q3ds=0t9nsYSOsf)Ald$NM*cenWT>aGm@w`)w$E+QX5+gBu*KOZ)l~ zw~`1!f2?6FC6JpVucL?!%yjQL@vE6vOn3q~-^iR}oYigN`i*p3Jy{L?=5aB>L<{~n zb4*6c(He=s8SG_82_vq>BGyj`aSt((H4xP>`azK%ee=@KOhKbZ9i-ikrCEv^P1sQH#8|peLP- zQzE&Mxlx0-$`1MXe7#Ip!0m`Re>y-fh>1iPL3{w06Qd{u{AYCOrpHu>;`N*I60U>& z7kd-%vFWI-_sDed3EdS1qFWbh!={DaOkGQGv=lVmG+t{N@|!QA#%c_d?ii4ktgl-! zy{5VqE@*6ML6SSlTf2+xlU`Ckh?wI-YZkO_XKU|L&dvBdJ7{!0XhYtG zy#A~jfkP$vZg6daoL<=Lb}UTcJuGW))A>1#S`~NM*Z9xc&r2aTq-RbfYaIZmY3bkrs{nA=+&SkHuiXqBU~t7e-21XG^6buWRui{C7nqM^_~m)W2Z zY(92o?2hk4Xm+ltK|G? zzb~GI6u2Q_f9CU~29camhPVG$RUsx75%pAr(pr*b?_3duchT*{JWznJwl=W7T*;_D zB|Qwtv`zHXM7YU=;X^}XGUNMnB5=&-w?GzHm>k`^RD)gvE$ znNR^^mzy-UCq>WbA6w|GGd1zZp+adD2q&_f?m3eK zsOHbLebX}V?=0Cf9`CJr?)bSkN%3hRnm2%JD>3ma zWrRuzvPeu*6}qZ>V;wE^BH+^v`Chz2AFm)QvGKr*4_wfgHx!TRg|t*498vhJ!pozP zxwNBC%aZyy4JD|(y6-b1nX`(X;TKCivoN+hz0=anlN;;lA_~^nLzT@w$uOaYcwkPo$zlf^VZn?h zhV|u3T>+NnH$XFD+ZIf4Dh<%ulNrDV6phk8=3U=Uk#i5C+@E4xH09YTuc+8@nf}{M zyH8^>?kOWpf{1$MGm!UnobFu`jV&E{um+HyA0BS?x31ak{@KgYA6aEf4NI12#s^s>x2cfP+^hH14cXSm~^0d!plVpTvWCcol^N4Tw3BY=iyO zYsa|`N%Gk-1cl#)W_fHrF4Hrw-<7^!Yn8{yJRcRkVAqUa@$)MWPT*;jr{+tn&c=ue zAD^IbsxJ(D3QWE$DIT8uPITWd;kGqBx|gZxRE0t!Y{W4N8LV3K8&JK_R0`?bH_5`f z(PeaRGLlF0A$B4lduI>+Hv*_F(%U{!yif|3){0{r{5gO3%*dau6?8KP6+J1x$wBfi z)8esdX}9L&UtujnEbp)3j&7TRRaCt`eAV!OebAi5f-^($$ic$O{gC{=_vxp6EX)Hj z1aGk+bo3jl@4A85<}l&sXQklR+ssDEG*V!L{qpnn?diWBymgO~X;QGp*h$&D@nNu{ zsSwB<3?tQc1zDLVjTgCypxp#A^*8N-GabX<1A_jtgGfrTPMFizTh|qL3F&rx0rOsr z3zx9_S8v|rZ$f5l%Snfq2~R`d2!wxdVc_r5iNAxT0rr0oDpM*YgXN{HeVuhmX}uVC z-Gdv#JTY>tQlGV#OMuqJO}qkX>GO8ClsbBa%F5$Ek^mY?}7q`971aCs5S8>zk_=NDDcqle!_e59tG3GRs$=uFh&>RqG%L_#BTaD z1z|)0eIb{(yFSFt_dNd4?0}(S=mie?}PHq zPB7nV%D#LOUN}*|-3?ow6oZ~U+&HA1?!x^{E|Ms}f{*T`n)F)(x0Yl=&X(wI^q?Z* zmF`E9x2h~4FJFHug@bv-nbuo|)>v6SvDi=Cl~cEfWe*0X+A;dkW$U3AFDma5{s{8b zA3w>~+>h?MekcC!oN1!?Ss_p(06CYA$CsB5@6un6OA-qX;A+{RhR3LhoN7NKAXFy> zx!C1K)hxvik@|G}o|<^9whaHHQ*@cAKli}#Hnj0jwps(XbdzZD2`2(&9(9U+GWJ^< zdl;O8^;z}{oa)wV6zNegRE~pd&oaX_4(PibIcs?xQzAU}SSV}XV9TLd2nbPEy z>Hsylu-q*$wLlriKt8^sqx)?Ze>Mt#JN|LG`}iW@mfpoi_Jaead-OuVN=iM8Fej(D z{)n1xEOR$(Ien@2E)dwAsbYBxBrB-MSYATmvMdWM1i+~+*_3Yr%OHk8%JmiUha;#+ z4-%l3&2V^M%XjDxZKhw%mzFxQem8i%!z<=+tG?mWC!vKOYj-%z-}g@^4Fp-{O9KBc zSu^0A`ypvs&941#vGk;B4ASmPV}A4iJNMx`d8JZ4OYZGAp;rcIXVqWtGveUN!{^o6cWosa@`C! zBEGVvxC<35c2+*&Lqq#){+s%d*ccmXh{u;d|MQkdv?nA2{hq<}Vg!BpbDyB06l6Ch z70{?d7BRt#@ZOSsf9=7)W#kZaW$7RRW!Z<>`<;+o86f#9HD?}!4639=vwu_YBzJxW zb)iKYA!1O^PWhIRm7Ve%q?KJ{FQ%e0&x@

;qr`@=@9`xV|u8xr&0bfaP^p1M`($0;AC;LowpPyyTcl!O2@ZevXkl-{t^oBS= zZ*Pc|6Fl^WhTnhNN%y=EHv?-daz-7ygpo50cC9%hYYnt}e* zPWV%fbN2C<*bbGte2d-&5pNVYc6Zf}=PIH7^Rq^K!G1hxIPIQikNNE9#wX8rlR}JG zq(n-drgCSinJnvpyIXgfP-!*h*+?$Y@KCoGF9b`LYb~=Z`*11Ji5?BqZm)(=j_SAL zUnvBcLO8X&0fcO%1;=H9;)QFzDOWAo?8gFnUAayH>t z+V0yX)`(qk$XY{TLOR)V<{gl*Mb(6o-1#O2b#craG*Qg`u^sSh3}T;HFwN+WMP%o* zYjgjcL7}7V01f8Z7P0R?3%fu!?`PQ>*dJ77YinFOosQA^W*-^U?Ub`cd7J41wD*xHU?FGQ1SdbAPXl^ zwOV@}v-MMZK<3AMIcS9aSuYbigjzf)mPtI`M4{nwCj)i}73NvnTU&-XUC)(88d^}` zd6pJ1A24$dyjDWE-3EVVQ@lFfUKv=(KwDaKWd98aUn<WIM6in-zcCDLd368K{KPu{ZsdU8kD~b zN`^yBPiH=y6SJ)S|6c&0h78&fu${t=sf1(StO@=;{A3URTTCT9|a2K zO1lMvKUv!@B=o?V{iiedDOjIH`k*H5wTju((~jy@(~NF3S4+BYoT;7iBVxbZsl`QH zt1KcuD9AMrIVv$?N%k@25(w{iZ<}9`w0NsK#(KtDd2H#sChfJ>P;dVb>-#77i=vAr z;z~Zycj9+PYR8R>-Yu_$kyuUL)H=q3Quw>FmvKw#YR}6!^hGlgV7iin`v)MupLLDt!9D%KK2lNpltC2=$L75>y-}d%nq-VW%ZS=+>D z?xN2`s}x=$BeW^Z(&9c}6*46?NmkeN2C>Z^C{GWRP4Gs%#3I{ZjMp~FuRG+tG~p^w z1ZjmxKS?~+JC7Y&?L~mBS zL}mi{IEd*ItnmB0)Ie6O0nS?GDhY7$rJ#@1JTC?(HCX^qdYzeD#6O1d>ZS)d5cm#> z3w|maQaSvizUDA|(CB6_0bp|V=U`D&oEj3c@-WU31x8vQ#o-W)aAL5j2UGjlT59Nr zdHvwBbJfxfa3BMbgNwZ7Y57iYu1VzVqBj5NpiCmzE`#76%)f1Id&x#m+ zyPEjX_q^SZpDQ8>z_{KYGhXHdmz5;FQj{cnZ;p*9^wQs~q=yrOVaVI4E%yxHIFE5I z2scTX_L$A97d~gbtDI-CKZZM(Foq`fA3&pZNi-cKH~#6`;sh8Go~4s07@D93X&pR?<62-jC}KM|-!x7GG)= zZT>BBZAien+{(}cyZ;WifozdRC^d=B_>VE_H;UW6@CwG{WDJI4EW5<5W<}_jTbMp2OGquxV z|4C=XNApBvaB}gz|-M5lsUSn-i+ZtbyfqY%eM~9Q1YZ8 zq}*>3N4;#?!0!`>Z4gYC?vN3y=$NO*O7L-gWc|8W;j<8olUG#eS ztoNk4?j_Tx&ZkN)DjJN{>e}@IP`Y{hm#f{{n0mTw083vsUL`d%N3uAskgV^6%!?}8{cV~yi{_`2*3#UX0Aim3+ zh3Upn!^2GHFv<6heY|_MA|w5JoxEKnhbZ>rOc7*nd5Ql^)-hU!Ch6fAA82noqlAjF z+%;{*wa!+iA&v@?p7_|RuVo+u;5<&f`|tRk$Kd~$ifteoQQ!p_r0-@SPxY;{jACS< z;l$xD$Idy+aGAwqIA|uu=MY@=%6c@1c#pwKzW#tznL=`;nh}VEfl|vwQ~2&`dr!dcDX>N0sS9QL_Ctd zaU-tI3*zG~)Lnzm+*Pd;yE{74HWd9XmJ57eA|W_PCi};r|2gT02N#SA{DleP)hWmZAaSb+ z)B3kHb)ohi@b9x_cM#h9^g8(et+N?8CcuOP10g+mYL6VGV!&WeG-1(0%W-M#+q7M)L=! zx6j}VgE3m~u;qQ`Q(+sfc@`LRn)=(5Ta?EC3;n2c#k`joXfF;E2RZ7S9{d*H5r;hU zm@;_Hx#}H7_zvEJ6R;IUqd%W2_IrS2tnj*3OYZ**eaQSI7`R@!r{-5bvY6 zfi#~G6+%hbD{w8G4}4`LaR+|Yx;zf3raO`$sYkqc|6#5lO>TEJRDEvcKMv?j2rbi$ zSuih{meFw}5Mq|nZC~trSqD*HJL`=^I(*{;(?Vx6kU3oz!9D2xE1v&xdD$e=+i)Eaee`w3sdH{QFb@p#-3gk_V7{LJb^Rq#Uhj9Q#7%*nv~ z zzfu+o`n9qFhq?cRWy@X^^Hcl>`c1?Us>{$San7>4)T9X5J&M9M=6H^=gG2X}{?;q{>M2@V^hxy1OL@$+4rG9 zAvMRwkgo=FKDQuKhA%zqaFEbnj{e4fR3rm>{Glwis#mt8vdgu`eDhY^t+>#quYu(H zjGB-d%hESw&-p-tTHTiPRewNi+f-0V3+TC#iFzvTl4uro_@2hE4(6NH5KNKzAVLhd zc@jyq-txc0I6Hu`tn6R}(Zry1R++G8W3$keZ7Ws~E}>)GmSpkxA1z{+uYXBufCC`2M4M8Kv{x{elO5 zahebz7Sg<5O#=fq8jY*uWr9eps>k(Crlf1|!VhLQ00Jmy(NFyr59s?7 zv-m5R40Nt+^EsoDEgrb#&+lwG=l{G5!{K@m!2M4``;uX=${Z%dyLVJ*nTDQ=j(=Tf zSuYHaC~eQO3%9QK#iK0nQw!=xCQWpV7 zYO&>VLLDOtVt}(Y!J|Z*7{;U44;HLW4r{-p_2X}6?=V35Nc*eNliA&esZcb=Iw9L% zSuA0Julz%i96ggX5zvs0Rm1)^{KNq1_J*X6aeA1H6l5A7r$tG%mwblbCXS=yV0kw-ysq8@)?}JP{gHMTplVHhu2%Pv+mR5GXhw$%KA&XNBF!FhsxJ}L4N&< zB57mtL+!)1y_nUEhOE^Filx>07ot_0(Mu*6itX!XIV$^ucTCO&Fy56N8v`ScQiP$eW6gzX{ScOxqi9s*~4dW?+t9#^oMw zZH5LX%tusU<~ZYfnfZEYZMs|TF*EJg%>k=HXv@dS&^w)~#?QeoW(sZY1ovVHIwbKl zq;~P~p@Cd!%N;oTovqz*q2ovSW7Rzb@9BIO^IA-jhfbPuj$Ym+pnnp`XnQSMcZ4hF z(i?#4up}s%vNAOe4S0Z(8L$0$9gAm>Lc|hIBch}A?+I#+vDG9h1}qhps`&heV$u`-!m-1GAAa|6e2?-$lr*ft|@>j2Mm@KJc?lG6J` zpYvGH(l|1=>``&!cWQ@ACV#z?pS>*cR6SOCuyR6zm{Th#90Xcfs16FEwi0YWP!V_X zg9nUW#3k4`Z{1_IFA_%Yz|S23Fs)lIAFEE&hZ4+GKb%&GDovkxjqvGXSY3}wkPX9r z>5uP2ok_;o&bqK%1ZZPxuhe(+2pEhK_E{r;Xdh}O@WLwF)&ZSs@+JFJc4D+32qq*U zTN8@ok=H%lsJ|?s38Q}WEZ4Fw@k79u0%J7O6LyF%H7vvwRxOpXXii&3t9#RmYV*eZ*}DJ^#dueAi{C5`L>cKqjlg&V1L!M zE5?>Haj+ty2xZyt?@^}Z6&Skv=Y&9l;wvS*+3I1MMhy~F9fY^W*Xn#dU5CNtaAq2R z+69Hw4P&W%*=vh)_S%|>_{rMdL2TSBa6b@}n#qQ`nDKzUy}ZPetxyE@e)jfH>pIPf z#UCG2q!IXoa;eb;`cp}4QaRlL9%b5I=Xf;Cxj%otUp$rzijfb7*NPt=vU+epMw7d+ zApWxJ9&L%0Nkwc&XQ1*(E0O~mSs?23Eud}PPi!-#NMw*>KeQgYAbSfUa)hB&_3sWm zyv-$P_vCqK-Ty>m=_M*6v9K+?(*%psgM>w=vfQF?HDNBC&zRJV>Wsvy!{DCe-1V1x zy415SLnxcUEsUvfHqC1Ur9Sf2!i=oXT6f@3!{{H^qTL6?B0>f!qn~GElWCGy;Cka3 z4ph$h_W&p?;KI}W%Q;=mlgD3L$0pxk-{*D1F1)dY^5CLU4cVQR8X2cFCDC}~O|Re91I{L@6y+`Cc|$S>w%Yb(&t#p5)A@eSa>Rtx8v$SWQWx(X5o=n%DHgeuUlgV$A>jUEd$mvcwv;Ep(`z6RX8Z zM&_GYUp!d9ol058AHGwx@QTB}08QS#lZ6{|*9U(+UO(}MXqJ651(36tkG2HTQ9y3` z>XiAj(&XbZHH`sDz4xyv?=%3n7`VC^d-nO&pW`~z0G+3am!tY>8>9jewAI_^pQ}!I zR!*#z{T{IVxOHU6Vva0Y^XvG9BP5*_^C{OF?lCavxus~Q{18(gNyi7h#1ajXdxhSy zWH+t-E`8+w85cA%BQU!r@+~+$@~s(bB-WrZ;hU?w@M1Y-8&^zaJkKo zd|#S{%qt7|&Ir&c{E@VNBUa+^`CYq-GF=d$nuPUaKs+w~(*d(h7?+hJNx+5@O{A_C zW3Dz_0AzY3wqOYkv|`?0sgMYKM0^*2Ql$9?OM-5kB@apXFiT44W@`oqN!Hi2@~h^pJ7MjFMmBo#AHPPqO=FV}TPzVytN35tuxg%*z20m5JPiq}(1m zu!($dA+O8mX_SL?QZ-<&->&i}@{4gQs@ zagRZO4f%z^eGHf%$v2)w8S2F&`g;xCWiE0sdpi@4W7O$y!o{Rj{@ zdnZ*|32*8CUWW%7|IuE@w(lYi5)TFbv-!!)`f!1Akw%)7C*TuwA@R1J)HlAmo@(@^ z*1^f?UwB7sq~Sv%zO5|5{(I=H-e0ogGUSmsgNY%`r_9qxJb2Vk=S+v!PLsd6p6F`< zd;_Y_WcC`aX!D(VOFAb~`q2FOH)g%aeqh(&82~ceosS~3SYro}4q$Q$YTQ3^Jz;c~ zjXuKd8@!Wv8>4C$DKR8~TRg<$sy{@`Fw*4Y1y%0siH7cT zCWZND8*&fVRsN*ozvL#-(=xr|`mRt~>rtO2&+YbrEVuot06a0H$y5UErY9p_CjR+P zi07gpJk=dh7?ivMulwW8(D(sCDJ~ZxeIuS3-qDl)kMC9|rwAP|wA8}|U|aeHlk*$o zU@-zyS?vxovU#AY!kLJLbJIa_(Yd-n2av&!@k@!*%-~3aFzPXZ0=2h>Us=ueVcel} z)H^CnuAjtBDCVf~GfL|^v|d{*B~;B%mCudf4GGj!w-x*)R*4DGap2tS?{Sf^I}4{2 zmAi7pXJki=cMN21fKAZA^~Rre9i7}}xvQ6bE{}dNcA~nOrA?$XldxjK%B|JlZvS1; znHi&8K-y>d&BHWJc}W<2gqYprZWI(%EwddpeZ=;H;e z^o7=^8@KTu9((qpl;HgW#zXs{318|o2}s?lRg02o^jserHHj#NE!FO@o57at^QPOI znvN5Pa15+NxHM-{XtKBP4Yplh(8N3rakOxPm41QTypo)P+4BuYFQvaa@*GqV_a5YW zt)i+0OgvMVmayYfkgw)vbJw`+Y#JA_E8G;O$&32+bwp`_p2nW@nOn;i<{lcL085=M z*1lL-3M|Y4U%)QZ$suIpRA!aU`x3Xmp;Xi6__Pko2JtC^)R}${tBoY+>Qfg|KWV@q z7GPeKhFS6)Y{I`byqY5l9di%er^v&d*(Dd;E| z8El2k7+THdWY7$0t8JVnGIC_ZAV6ZMa&2?|ym>bkUl(f# z><+_eMKOeqyPvaHx1D`Fg4PSv3m&Gi#pK0|^2zYJnSNOIQ!D0v>#5aQ|D6{|LsY!3 zzi%4GeoWF&p}gluz`IwA@#nwQy~L1jTI054FHG=j;W@23kkHt5H*P?;n4{}h!SQHf`sUa-bE%M zx*5F_Em0msiyjf3=)FaKbU}m=b&OszdiPt%`+nEGf86!Gcda{X)|s=;v(Mh2z0W@T z%pcELpMLW3Cahd)a>t?bk=-$(>sxG}IgIz|({Jr-(VwX%XP&%A*f9D`_}wbp2l+uq z{-h*QAoUAVT!v}?HcSP9n*t|u4Amdfp-(?8dz}UjG-TAc6^}zmGrOJ=+$>lHN{g-1 zYI@Z2a8x*KO_=-7jLY0RQeba;TfEA9LyA1toqWA1G399Pvs{7unBP&6gKBTFt)iX3MD*oJ?yvp^OFZbxQ#i9K zT1O*+;N5%aiDw%y(14sy2;8cMeWOuj%xa8q*5Haj3lu{9yJoFFeohFx;j;YdxK)$0 zLa)8Vp@&8OxdW_RMQy?Go$OZcds?NoFP2;XLc55Le%wEpxkCqQUwF_hCTxt~>|#+U zuDT6+Kc3N9xyrbHB}EKJuXOgYxz=9`Grzfw?45cW2=;BWtW^50t)BI}*AKAQniqq; zj_y|HaXY87rvP~tVz#jMJ|g)xJ~@x>>}w3HL_kAA{%PkvY?lRG77_G!`X^hsYN%xfmv{Dp)_r2Vc!(~7c|gTR2iQ>8|VQzQ$c#Gz6=nx4jn9Z z7~48LnI@$T+YOd*dV(MZ_Q=cF&XN4KyWs^+2ET;~8?$)|*wrbn?@gbmXYcJB-t2G+ zl7&@JXy1-YsyA%C@>YRwb3}L%p?*;fo>!(O0jTuGtCUF7OD&((7iGL&&d9tcL8#S7y9F{1Dnf(gC9lf z9Ng|qr5G6+>FF7@kvo>>iy3`socq=w`;@#sIHE>@^nMz1ZQRk2cess~_!Y4$&N_pO ztGA#70|F$^+=@$li$_l`H05?l$T7fqzffDB@S$f?l8|X@G77&73&(Hq5Q^z)er_yEpn93~p zHNCLKE|F-+6GNBG7~1w!*vCEvZ8nttGuA|XU?V<`z1{+E&D=5|9F2gm&lz*5W?WuH zFOl+#Y%jyEtL-BHn0u~%YUk{~Z=SH|w4Rh+hqzq?Z|@1OZAaRDW*nsHW#;N5qDuYB z{XOM1&~htfoi&8_MtDMZX+oEKQ?v8xm!u<*8*|u-XhnRm$hzHO%2GLum?6hYi@$+{vF8o~udi zY=%>8UZ)D*b&th~MoA3m69vq*t}dBAwR>!DuH>~lK8@3ajahQO;)@&GmrqDyQ04P6 zO@$MD`t7Q>fwXc;msp9jm2W`YeJxDq#h`~+ph3TyXk^EoE#|NG;?ul7xI$$(kc*-Z>19dkb60a@^J6~wC!_p+@WLf zmt_$YjJ$~l7S?s{rV^%)GmrWLw;~3tM`8zhO-!%d`(2K-!*PTeUpX4U*B*s!T!mc1 z96YDRX8D7JyT;#BQhazqqANmlrF@_i7sBKd619EO`-^6es%++;=eJNwe^T>=C0Vg^ z9HY4`#+Ve2u9$`W46)393Tu#384=rHfRcxxZ*Q%>fj7;S(F;5Cf=9BIBW1?od#vUG|sWoy^IYO3}SqXe3a&C*lxyEWT=(lhG%-`da zw4M^Uk@rNTs~nf#fI`82dirw{B~hVR8?u4+;Q~@PeW!@{EwAd-=)+l>O_9u_V`+=j z(pLU?{|gY)Oe4QMx!62XiTwdPXgfwdvCwu{AR zTeP)ZG;AFb-}Isv3};3y-1{jE-K|@(Zxn*fh)u06A}JKzAL5GK=jqm(78)g(_qd%gwUjP+XVZQ$F*Xx^ zF?c8!ZF&yl6`O{?XZ_nh2s)0O;%Ec$DF#(ErYVZWrpT_F>d8Cg>xY)Yg7z605}Y_7?MP!j9dV zPMn(7*JtAxf=~CmeEzcFeAX?9vE5u>REi3dmY}#98Vna z!f?YOn%f_rGfE2D^a)w|BDl>0;2>)S5)f`eo>4k(eq%JwvSH2)N2tZUEkueMO2%m8 z9la%pxHXdPm{i>XYeTXw*xivU!`}Tai=r8MAuEC)In;Ot*3(*ZgHvC6t@%5L51wwVh0x}p zJ=m9*W<7w)-@3jQ#ZQ-ELVZ1Zz1`}rlD@BIv04_7s;|`*geRu)KeJ)4WEjD5Q4L2= z6L$B=f_Ts&OoRwBdH*WAtz}yvBA~kZS{=!pX)9eXQSHuN#q2)MFfab&F(>=eKP#c? zfLR^`g!}~+Z`I5>@Ooq%@h0p_jMELi`08rbHhY^Q;nm#^7W4P$xxPcKK`GOxa@$CC zAtTicwH4LrsN+Zms73H@q-&U+(yfV13DW9z{%#BIKbk;Z$X7WQg$)<4=ObS?k@+s% zZ%;G*LqoRAjGaOeQh$ZP9TgEqNO)z$rZ<`Iw5}Xx+I}PpQDt?oEJZpNF$6Vs+p^>S zEt0SaZlCTh6s{CL+m+m1U&ylNA;;Ob|JAW}Egk1(5F6LKkFp6G$QaK2E9rMx%KV&! z#+dbD27EZJsl&>K6`tk|KTFE3Uo~5cc*8Y*tiY%4a?xU)9g8&>Ib6!fl78fP7aEE8D&)RtQ|@3(2O_Y zEFy(Ap9dkPHdj|mR6CJ9=<9`wr8f(c(B9z>prNSc154fEhY~$)Si_ge=#-^~LP=5) z2`|wAfShJ%mt%ZNNL@@=vXq4$QlCyj7ihDMyq3?Eike%Thy2WWVnF?2@lLj3z!qU? zISVtovGv7BiC!<{YX)fJ^TUGK{|mPQ7|`oz;=KhVkId)*4O_fiA(SbO5oAzcGjdKf zy_=s#a|00}i;p%z)scTC4U=vL6EM-ylNkF4Nq4P@`K>q`ld!9xdzI?F0 zI?l?S9IhC(hd;j`xBM5bWd;>``vK##`zwiBv%9@mY@*1SSO1z2)Vy-yafk5Pe5Y)6 z8@#K<`fi)-BW~x}trzpYlMo zKW3CGBUh8KvExVn2J^c|Z8!3bs|=bH7pj~kpo8ZrpIG?9M4^5#*}HCPYD5wbFwB1p z)IEA6tX{&Iyz0{*i5?=E+b4n>LCQRM1GBIXFW)mmAGqYT-ln|ftPo;Kh?~ZKrxke{ z%zR)K!g>eeX*{X?5|u|}xLj2Ic~1>S_KNOi*vWx#ojOiOsnHeIerzL{wBUl$bB?3% z3R8c)wC_2;{n;v-jZp&63AS!6A&COcuD}}XDO#B!dnDq*}kDX*)dJ$^ZBk9rriN8RdOd4z1#QKYh>`e|eCCJ9pLPX$xW%cCVsP zXOCybMMx=B6mqswI)0d|>47NfUkc5v$=Ga~F~4j7xpXOgoTB2~JURR{nVS2RZxKf@ zMO-WLbvWBfubb~{Vk?ufO|8aLrhB~vNijUC_kwOl{YK8^yhA*|j4z8*Ik&gZ z@!#dS{bvwR2VQ_pD)Wo56`eYF59cwL)Ln65AEQDY{!QR)<0{I-5uos`;z+pbgBinK z1GUS!Gmh9l<_YOvQ#BU`UAsNIZiZJo6eyLQ%@+PUxjaUSWo7 zU%!iA#R$#qa|Lc*F$sq}%>lo9{7&q#t|3pkfWy=+0aiIWMJ;T~7k_VCO;zWpW9%~~w63p5Y-PG|@GNq+j`=gLDji`G_!YoIY67<9{6SufdS zuPK}G3Oo?dr|A-0)g5TT(sBj$--aTURXW05i!~w_?x;NDycaCFGC0!E*^RSHSvl}k z5sbYRZ&8{S6&@0)O`qm4^orrS-_55^p-pjQa`CtyOeqs=e&)W#aXQ;sWpeW> ziUck!7EMh~!4v>#0(d8Bb-ZltGOiyX_vWEQ^G!$Oetv6-m2b|F5~BlU`8#~qn1Sb7 zie+iM*E^9$N?;r6X}RXjJdOfi_=@l-TeBz3D|>pMz^b~NpUbZ9RT%o(=S3tb{MY*r zW>IfS?H2@a(Q8s5Gh_;HN6ZN6?2S&tKBxpJAxT&gXK9SmI#Y}Db;9rS@09BO7N}`< zo*#cmS{=*Oz|CoIRKY=Dsxigqb=SkFgxIm7y{lmR&P?bamv#VowZbh}OYxtVf<#u% z4lOs3^4k^t?-4*a-^{+~oDRpU(>+%~;&fG;#7_md@IWAOfhIrb(JO7GZh-YIrwNF_ zF{)@~dF;z)_B%iNWb<0PURf6=;cxpM%3$!mTQ;0G_JFp(G<1UVui9=8mA*$Qdv#qL z4jGc?;por#QG-VG^g3CyJar?F4M5F;}bfi?m& zc5sLXk4}NTpCBcEB8KMJRW)I*owCHE^iMukIVJ9lFI7(2ZHO4#T`skJ^Z0<*Vr|h% z%iiqau=X75H>^WOv)MT1-#8U`GwDX*y>%)5B$?$@%}>kkvG zkI3b!PKn1IzR2(4=tYG>gpl`ADjdSYw~{1>GrUJL1uC1{lic$Bc1op$(@~tOBlRAQ zTFTH7_o*GKj@HS47GnHNajJwtm{Y4t3q#Ip3SBRoxThOQUzxYXEzb%LtrtNQq~Bek z2!snV)3UjEmVK-n%O1R^`v$`KI=AZ5gf{v2dzbH4}+&-+2(&wL@;5O+Ws*?Yav^Sw*R=a)RSeO)fLa8pk)* zHC?;6+1+)_ht*ZM%d-^f9qboPQgjj{EZ7J_b&3K)xofq)jAoad1x)S@%8+~7?jPXO z;EM~2PanlxyOa1Ar%BGZVMA=gP}tMU*{V|`hCc3<`4Vb~-Ty~9olL;PbRTq|y+;+f ze%uvE8P=e0p77ah5*J#t3neN?%%Re_`2xEDV|OX0hKlDoG(yv(R|`SRaWaZ@cZ zQc+(IF6)(!N0dp3{o;a3W1p8+w!gD98F0%WcEVdC2g9Qb?2l<->$f4r)Q1V7M=gVI zSX)=dSU2so0J#?E*nvsF2gQ1k^`&2{yTQD^E4UyjW>n~`n>bU!L;PM_ zfqqn~;R6C+G{ek(up_bwqvsk!nY^UK4>Sn%ByeiZ|nAWAStHGgnS(HnST}+lD*CS>>UYEd0XXd+uhG^&r1}x z-^M5j6q$D+Z*TnVK{_I?*;(;G$yDSp;df~BxNgT`A|UVUe&3_j_iNU-cgs|4TNz(X zrDN`_!6ZUAdyw;&uhdV#VufdGjDM$GhiMhL49A6X%;l+AXO+4roVeL2!%P=8UC=r` zIOngu=hH#FIcm7vH4nov_vF$k!_`0VoJ#LVO9um`_O5kEgGW)9*Fk=%yAHy~LVhg% zV$<^I^dD3a)OQD^Vwkv5J$)EtJHKEQ0k8sLzrL~hB!cxp;K3R;^vd)kb$m)UZzEoE z#lNj!ak6N^KGy7%&e_m$GGZ_Ts^Zx^Z5`}0|RMh8v}L3fPcR8OZzX+RmO!wU$*?wH=8>xTC&wCY>1eu?+e zhDU8?k*wgJrP%*yR#K!yZ+Uzm0O-CW9j}f=zF~k#WVI_lviV4_O&wl6tD_}~4?50` z0#BGJjL!kvTYVApvmAIi#0_x2Rf@}htJ6N(innHOU?@HxjL<#zEfVoML9U5OdlnaJ zM*$v;0f7$>g1?eOg3kEmA#&UmnRwq|%kOGysVR^GROxZQ9VR|Bw6-c80os)37H|6^ zT3}=YMwLuU<)q*qrVWt-i;V+)5r*(s9Go${phT?8s?sG$P>jpuywotrS>XvFQW6!0{Y zA(tQGR>I=#yd9vjsaLa*)X{(Q0k4PTlV`IAGpEB{H@?W!vToj^?eE37?&O%PkJIS%v>1xnE*;0v#(40 zdk4$$X33^beod5ly-Q&JdZH*8_lER!63T;T!Q~3PVzR`bh4*JP-PrmvD=JlGV>vyoX_u-mAmaA- z;ii>a(qgZ6(#176>n`pMk^q)%SQ68h%Iw4UU6XoCmNugmKmw1*!=~|H88M^ItQQv; zYNODN&XiD|mHvd05@vR5HZxd7beaYh`23F3;cP(28R2*Y_0i3e7lu}&!n19oYdjv+ zBsZL7JJ#w(29oFyD9zXoYu2*~{VKZYst2stJe%23$U)vJ#9~BTrHFlDpUaL!7#CWY zak+id2(Lpvzr1>c5VE}0JJ%d0?&N>P<~B`6)^%7n5Y&lvw2ES5X-wD}8*n6lF-C_2 zDk6_mM5${(B<0>hh9*pp>1<`X9 z(=;&Q_XxTaneTzz$kNtn|RfkUd%_4cVYp3<+d16~JUG`Sh+VDP)s{kH^k5W3l^WAB#JZR)N@pReA7TerxN_H38_RR0moBl7s(NkS=~jp;NtC zS3Fh<5cnXbN14DA2K|}uim-~>7E6DGJMvZEhXqdP?N61hHy?$l=l=$eM4O0IXK3U< z_L{CDhF6%}ow={tpZwI$sAFIi7KCI|;w8Hidh*` z-SQntjS~OPQ&9ba_fZo4QvLi8i{i9qAEdZl!3W1?xkwAQ51IwHpJ{aRX~h zpn()u*F`pn!TQ9{@7)-^I!L}F0iQ<~3}D)V_h>-wfVomu=3vzTh2q&Vjr{joyAkbG zHTThJqF|)hm?6M;=!=;C6t#c-NcRfp9)gxz3ItMby;oFsohuQK(Jt?~TN?6Ai5=<= zGHgTs^z%VXe+su79ND{W*Fz4$&0CWmJBBt;`fJ;E>`1AD$di{^DWlB=cly8Cro|%W zJ~&Z8pxJkRyB>MYx^W+LpPh$Bm6y!7soCfoj})$FI0f0G>gtDH_0>;MLH%U4@6mTV z&#&(7aYM$&R_qN&zOByGj%1=8ka&bXxWTwh^cB(govd|yzW-5kDw6YV4O2-4luwIpRJT*5jZvT`6##YuQWwwnh z*fsWKKeEl33g-h6&ELgLbNws>KjCn&1h7r^L#O7<(-hE;2-mJ{b|A|JQu4p^i(@1f zK6O{hLKcwPdt22fHTe3=pL_d)op(Q7)fPq}6CR*g2yN|*o|$AMyhq4BggOlEc{@}p z(6ndicg?13CpFGD+jr!YeNr>LIpY(b3I;Pi=i*}yjz$$Y86@2mf5iS*&c0dxi8*16 z8AjgZ=xaOrWOcn!ly)g0c=vRsbj#zh4}x&IY6KoDD^5YiLK9Lpu=Y$dUEhzo`GDB; zI>N~;b5Mxc1jaW%Ntl&I#A5!1gmHC_(SfG^S_@R>m5@#IE?M` zPoy+_(Gv4I=xf69JM-$R%Uc;Wga?l6%0|(_RAJib-am<;#k183Rm*WbS_oTu9hS&) zv-LAk-3@=*>#vHwhwuvc)^Zy96C1YLO(^TH^F~lVNOZj~O2ZKqkmiU`vQc=(Cx0)x z%!n;-T|q>U z3*!5pGuw$1L0^sx(5R87x?d*EZcIp--9%9dF9|9r zTCgYffGt-kW?#PCvinfpaeHE9gap=p_ng)zB^2FL5a4H|4a!ZO6kfTouy?#ny`k~o;~aFMaRz%BaZ>bU1Ofj-}C+3>#1GKwaiZ>mJ#;> ziYw4o4|a&U*wP>lkE%^~!?6Urf~Ig)yWcpzu}9^$GscPw)t3YSuZeVh(YmsVjbVxC zA#FV4(!Gef24h}EhTQ|N&EN4+<;bPBPeZct=qQ`eoiTHG1<<8EcB2p;3!OYjJz`Y_!v_ z=xa+f%?@7+U==O=c2Ww8>OfxcH+nY<(Wc6m%gv}a0}dHc z$-VUYJUaC-u!UaO_&T@*mo{fJ1?L>1L(;=7#Qg3`$#Y-ZinXsrsNcF(iXcuO~=Hh!ocT&esn$ z`ltKu*hcvbpVYnXI6P95^`~_3a&fQiEN_K;{!F5JYb?^yJXNdkS6poxyP@Z8C)FhpQEsTUmwZ(1U)jy8#OBzfvow)c2@_w}_)<3=bt zzsZI&BO~_*e}2;z~Kg%X0xU`29}-f}qX( zx9g*^O;HJ~>Gj0i;?ZVLgEpr>rLacJ-r90V*J?PbSxjFZ^D`-2*4gZSya<=(4ErG0 z(T`agH)3Iov0O@?DID}ixY-~}%S8s4Kedr$NQHz_uVL(~bstUIGLE{}8%r1}Zp_L4 zCI*J=iN~4K`Q%HUnnz%BT(^&Eq8lH1Aopiy_|#4@!{`@$F+K=4n-_w8S6Xe zX{nu3e_PyeF-+wJ?dumXVLyAnam$jO35`j;()+f`7>*0BSp~!$c*QmqG#CRnRDf=m zFugIFOJ|?vF{f+FvXRgkm&PZ)o+H;>@X(Bl*!hAwGo#oaupF$K8Knq3%zu7k@Kz10 zf#GOVvsD6uxL*s9OGn7u$scD)`cvcp%UqcLH0XoY>G}~d8;GvE;o7f7mFK=3`K~OO zrRtY%TB5Tp>{kl|VI@_HNLcEP^AdV5ta_hge{vQUtFSsh8f`RbiR4l0cXYP{l69{_ z+W??W+dY|lW{o^XAFs^CjKXyz$+aT;Ywm;e8AU_A#dlx#Y4p1}wem+%UI;7xNj_5p z&NfPq|L%yBohJasFGOSF-OwD&pt~Rn(R+Q;KgW?%6`2oLhYyinLO7V-Kb~4xSdjEe zf?A56EwqeaS%f!n`{56l{m)5Lk*k1rb;Raa zp~v>{Nr=ddOkCK<*@Ht~Fhe={#(Dg}WOVz{UzrYM#_7GP9mVBcy|7O!O-u)~VP{69 zX>`^ghBrX^93spHjH!;(RtDdoYuN204rA(agJkAIh+T)9ianGvE|tY2?kUEFiNqKI zalDQD4Ruw~gJ(bCy2U@W{VoJjXrU(9zGy-|VP}{PCQIR@dw7Q)5W8a$Z~-<6(0-@R zNw%EfgH~8bs}s>?Z)D?R0c};a9*AF%z5;uT`-qmkm0pSo-UN;sLs^cR9P&7?d(-=$ zXN%wr<_u|(L z?=B=*V5T(}z5kn)^S=c%pIChU%WCVd;*SW%`5(-pH^F;X{=@HUrxXj%c~C1AvzBSI zaJ08^nMJShT@y~%OdkFbIFOh4 zE(4~OxOkziLr9(HDjq_WqPZ8o{A)AGiUWdcS5>6zR9s|5#J%=G{V1w$oQq8hXJ#8- zdg;$7aLC-Rw}vM65(qS35Vecx)l$%d@y3|_A0LJ?jx{$dv*ymN z?T%iFM!;hc5$DZg5TgT1oj17fSOgsZqPY;eXf9+T5b(($c;;j6c7;sJa~O5h20{hr zqtzkHy0EB_Q|gyokXBEo`tm)9#2z>HC>wcL4TQHlFK{2;gGhR*1wEB=Qps17J|dKO zcR$oRZ=9Ym_21*hk0ORwyox|XApZB=izyGP&!;Hy&W#2)%}Ij=G-P1$l|OoCJ4)B~ zdvK+|JDMhC?&cEJ%TMbDIa-*7{`GgfU$-}yn`QAN1asTNHfUGMS==F|KWi;_&bULR_LN(f>5D= zAHe!Q9lL21FbB8k=5L#GIU*&%(7-3-EokmOglBRRoWu!A6~jT4d4gp73yv_+wPW+z zC`m004Lp!M2K`{e=20J`yK3C>0lL1f-~8N?M-i|;AgeA$SkIQ zm6XAuNQRHGPD4HgrNGGZ4I}%%?!bP)8-#pnD?9m7Bx1tq$DR@Cwj|sr5;4aE zH7&a^%P4dpB|MN`43#rlJE+ZZ;-of5GYM^&N~HFkY>m5!n3}n72)ORPV}1(GoG67Y zs0eq}Mouo*ci(II0JQM->#eSTeJW&1cn)jsd{>jd&j~>=_9crsGj#KJ@Y~kdIhD|R zzDy2);uHfJ<~~`U!gNUkKU1Y93G6dLR@Hj@;dndTk1V}OP(7L0PK5_NYl-cQbDv0! z9|mfnnTQSZ$xuBt>L$W<0KpQe9M0UQ9ec_tvf_5B9aRvggMS4M2F0T{Z_44!(ZKO9 zHr)T)PTm-+dCBNIoZcL<7c_#yzlUz)TgZT`{>mP{w~gE^++hcik?1FLmR-km|VxxOOpee*bg}qu{H!GQgJ@zj6FB0;2=YOk|#wzd)-r#nDSn!8lH) z5q{^f+z_t3*^6oB6E)Il^jaUVz8E~2-#<0T_&Z!)auM627ND>W_`a!^eG$1;9*8fM zE`v61>S!f>iV!M7dM%SH4 z^3T6qYXr`s8LQp%5(`cJUYfrEXDaFMHCoR@VFgn&1KJ>Wn3I~V+%T%zVCmHS2~tf} z{{-V=`Jr;k%{lZLxc3IE-7%c3lSUPbMM=X0aTlt_$i|1)ovPGqo>rsaD>kv|rXPPz z#-kfMu}ytg1!rR*P*KV`tL}DSNXTCEYj&MwiMtcFZ65%cNcgv3D`ENiQ?To3SRsnyujV3!2~b;Wl6`rBQ;RzGn=Y=PXYg%IiGNw}+logNQT7huHA9J(b``Tn{o=$FDtaR^RMDETYp6O$}z zwBApW#5K;`*mTa|6?w097&$7*TY0cVjG+y1?)^3&C&0_Gr8_vmVe1(kx8NdiEDxqd z0A}W;TE9mRv=ZgVx+;thVvVg|7)?oK>2l|c(T5v=Q*T^518kl@14~T>xjB+|EV&aJ zBgc7i_rB#VdYNRzeszLS#|dn@F$hjJXo6O|<*d?Kq9BaT4EV(!k>2*%kF|p*@cXMK zTAm-wLG|~U<4FA{_9KRDI@p6Aksr`R**-5%8y|YWE^-1rtxeQIcys}(G!R!wz#xnH+s>x*utK3iTSEOFN^o|4v_(k#GszYz?y<5~PLz{b9B6?85 z@#I6*SwsH-goy6O^r@}oTZyks4P@!ebBqO=3mURSy{a~l5|xD(XeLBJ?%pnO% zBMAtpiF#fzF>%kC!mYgh(ICI5EQE7^X;hmRfQ0`BA5%Du=cy<~Yo&!j4J?;Fe+1JN z6c@CZ+q=2{@b=Al`*FeI%(^AKtXtPeQbJ7ai7%BTF6sp6nmgkbTmDJN2o4E(IVqE|?^Rixi%MK0h9_^t!!o7?ImBZ=+i%8J#`2@6S>1WEQCn49U4xYT{ z5ir^*WBU)vFb%_{QHf+{^o#IB|FFT$o(~4MeJS9V8k8MZUDE`#1FLyk+PUY=)BrYX-9f3DmZN&$)1R;Ovz9q36X>iwlD9RaAqP|U+flf|~w;o*z#Sb}? ztDM?bC3TtzZ%i~Xlz8Pp@^@tzIjv9c-kvlg4aHR&NQPuR5g(sxt{ifmlwESM-S|92 z#}ncd00z0&_k9DfchV6)9G?-%Q--1y1cf8mM?={4Q}AT6d`V{)<7NBu3#xJ|<|J7~ zyX#~^4-zXeYY3M$tt0I`X^0MzL-mL8e~HC&)d|OUASpT#rOG9xpAw|^CT!M%h~_%haWAy&)+VoeWl26jkde=s*fx$VtviM`FQntr;~nP)Q$l%W z*ZK5RAuXuFZPh`%#9KUqK(=VtIejK&b?OJw*5x(+UeJ0>Q})U!|8B>@+s6=&ejd7c zdGs5z&7#gE>f|di{fb*b$?X>v@}eo!+*(U6+GKJqr;f$V!^~vPyWutInc&_Zp83nU zpJgmLBisvg-^41oM?tr4(RK1S zjisd=1ae0s#1nx#(jr?3PIpEJ4^M7ehexzO_`g>yyPO&%8_I~sIP-~v)O&{-o?qQF z!&4|PO2TJE6cTToI9o?gFRd$l;YXOA0j;}sis$>*d5e@Tne&Z}peLqutDt^frXe0n z%_w=-Fy;PUYUSFJdSfv?;blINIvBL?8l{j{myT?bG0KI7C2G*;ttHn9u>NOHDA$#@ zq01gfkR?bMeazua9A9)rFy}6|6n{lHgo3!jBS=n1jXN@9YmblT@iWXqJmVakewP)C z^7Gx>io+m_Iq9P=s?_Kcs6D5lr1qV^v{C|A$0)aq%VVnlOLyt~3NJ9uVE5tH3-)K1 z)$R*|RjW3};q@$*M?-NkMuDC&%Z$34Z{8+8z}S|J{^MoUlY{iwk)nkXp@?d#hr_bj z6~^@>_47MQmqm?&e*CFT&Id@>LP+exuVokmab!oUKf2>y(q&y16BSmwAN>M3z5IQ} z!zvC~`BU1vxT6NUd*OFcJZOz+%7tm%W$pj94@=Q`GroyTxF3YLtOj(;I$65eME0Je zxBNe8I{yqKwzjq?b%+T;RS(_xw^1E0OAjr&UR$A=Ip^zLV zn5-=waTx|o`wdc9Dk9hsXu*FOG~ZGtzWMlFC>d-UH)!!1fBPirpeh^w<7sgT}Nm_c`Flrxy? z)k5-Y^JPHTzoRT2k>)2f5EHu0Yb~$UcVwN*6udHW{J4!pYq+b?|6*~z8$g>BRWeX} z)ZmZ_Tl#BE?bFXal3b#}Th#e}iOD81Wl1bt`Z81V5!}8c_w-}~3YurLE z=2gXk-bpEy-j4MJ3r{W#c({pDZK&us*37GaxtK2@4>|IEUdl5c7ulRlt(vB9{O4y1 z&NV5vyrM?R~OY+(kJ+Etcfv(`VMN$|&72v}{>|t-w~AVG$iLlG7jPIXoJp z1{X(6a)si~=}NzjMzJU0h0WjgGRfuhKI16i|L)i}i>bW7wGfvyy!LeunmQgljx8m_ f`Tz7GZ#lzN4~-}}%QQ7OS0MjX<;gecm+$@$`XUa| literal 0 HcmV?d00001 diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index d3ae165ee6..7f7110aaf2 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -157,6 +157,7 @@ - [mRo (3DR) Pixhawk Wiring Quickstart](assembly/quick_start_pixhawk.md) - [Holybro Pixhawk Mini (FMUv3) - Discontinued](flight_controller/pixhawk_mini.md) - [Manufacturer-Supported Autopilots](flight_controller/autopilot_manufacturer_supported.md) + - [Accton Godwit GA1](flight_controller/accton-godwit_ga1.md) - [AirMind MindPX](flight_controller/mindpx.md) - [AirMind MindRacer](flight_controller/mindracer.md) - [ARK Electronics ARKV6X](flight_controller/ark_v6x.md) diff --git a/docs/en/flight_controller/accton-godwit_ga1.md b/docs/en/flight_controller/accton-godwit_ga1.md new file mode 100644 index 0000000000..e3671c20c6 --- /dev/null +++ b/docs/en/flight_controller/accton-godwit_ga1.md @@ -0,0 +1,153 @@ +# Accton Godwit G-A1 + +:::warning +PX4 does not manufacture this (or any) autopilot. +Contact the [manufacturer](https://cubepilot.org/#/home) for hardware support or compliance issues. +::: + +The G-A1 is a state-of-the-art flight controller developed derived from the [Pixhawk Autopilot v6X Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-012%20Pixhawk%20Autopilot%20v6X%20Standard.pdf). + +It includes an STM32H753 double-precision floating-point FMU processor and an STM32F103 IO coprocessor, multiple IMUs with 6-axis inertial sensors, two pressure/temperature sensors, and a geomagnetic sensor. +It also has independent buses and power supplies, and is designed for safety and rich expansion capabilities. + +With an integrated 10/100M Ethernet Physical Layer (PHY), the G-A1 can also communicate with a mission computer (airborne computer), high-end surveying and mapping cameras, and other UxV-mounted equipment for high-speed communications, meeting the needs of advanced UxV systems. + +:::tip +Visit [Accton-IoT Godwit](https://www.accton-iot.com/godwit/) for more information. +::: + +![AccGodwitGA1](../../assets/flight_controller/accton-godwit/ga1/outlook.png "Accton Godwit G-A1") + +![AccGodwitGA1 Top View](../../assets/flight_controller/accton-godwit/ga1/orientation.png "Accton Godwit G-A1 Top View") + +::: info +This flight controller is [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md). +::: + +## Specifications + +### Processor + +- STM32H753IIK (Arm® Cortex®-M7 480MHz) +- STM32F103 (Arm® Cortex®-M3, 72MHz) + +### Sensors + +- Bosch BMI088 (vibration isolated) +- TDK InvenSense ICM-42688-P x 2 (one vibration isolated) +- TDK Barometric Pressure and Temperature Sensor CP-20100 x 2 (one vibration isolated) +- PNI RM3100 Geomagnetic Sensor (vibration isolated) + +### Power + +- 4.6V to 5.7V + +### External ports + +- 2 CAN Buses (CAN1 and CAN2) +- 3 TELEM Ports (TELEM1, TELEM2 and TELEM3) +- 2 GPS Ports (GPS1 with safety switch, LED, buzzer, and GPS2) +- 1 PPM IN +- 1 SBUS OUT +- 2 USB Ports (1 TYPE-C and 1 JST GH1.25) +- 1 10/100Base-T Ethernet Port +- 1 DSM/SBUS RC +- 1 UART 4 +- 1 AD&IO Port +- 2 Debug Ports (1 IO Debug and 1 FMU Debug) +- 1 SPI6 Bus +- 4 Power Inputs (Power 1, Power 2, Power C1 and Power C2) +- 16 PWM Servo Outputs (A1-A8 from FMU and M1-M8 from IO) +- Micro SD Socket (supports SD 4.1 & SDIO 4.0 in two databus modes: 1 bit (default) and 4 bits) + +### Size and Dimensions + +- 92.2 (L) x 51.2 (W) x 28.3 (H) mm +- 77.6g (carrier board with IMU) + +## Where to Buy + +- [Accton-IoT Godwit](https://www.accton-iot.com/godwit/) +- [sales@accton-iot.com](sales@accton-iot.com) + +## Pinout + +![G-A1 Pin definition](../../assets/flight_controller/accton-godwit/ga1/pin_definition.png "G-A1 Pin definition") + +## UART Mapping + +| Serial# | Protocol | Port | Notes | +| ------- | --------- | ------ | ---------- | +| SERIAL1 | Telem1 | UART7 | /dev/ttyS6 | +| SERIAL2 | Telem2 | UART5 | /dev/ttyS4 | +| SERIAL3 | GPS1 | USART1 | /dev/ttyS0 | +| SERIAL4 | GPS2 | UART8 | /dev/ttyS7 | +| SERIAL5 | Telem3 | USART2 | /dev/ttyS1 | +| SERIAL6 | UART4 | UART4 | /dev/ttyS3 | +| SERIAL7 | FMU Debug | USART3 | | +| SERIAL8 | OTG2 | USB | | + +## Wiring Diagram + +![G-A1 Wiring](../../assets/flight_controller/accton-godwit/ga1/wiring.png "G-A1 Wiring") + +## PWM Output + +PWM M1-M8 (IO Main PWM), A1-A8(FMU PWM). +All these 16 support normal PWM output formats. +FMU PWM A1-A6 can support DShot and B-Directional DShot. +A1-A8(FMU PWM) are grouped as: + +- Group 1: A1, A2, A3, A4 +- Group 2: A5, A6 +- Group 3: A7, A8 + +The motor and servo system should be connected to these ports according to the order outlined in the fuselage reference for your carrier. + +![G-A1 PWM Motor Servo](../../assets/flight_controller/accton-godwit/ga1/motor_servo.png "G-A1 PWM Motor Servo") + +## RC Input + +For DSM/SBUS receivers, connect them to the DSM/SBUS interface which provides dedicated 3.3V and 5V power pins respectively, and check above "Pinout" for detailed pin definition. +PPM receivers should be connected to the PPM interface. And other RC systems can be connected via other spare telemetry ports. + +![G-A1 Radio](../../assets/flight_controller/accton-godwit/ga1/radio.png "G-A1 Radio") + +## GPS/Compass + +The Godwit G-A1 has a built-in compass +Due to potential interference, the autopilot is usually used with an external I2C compass as part of a GPS/Compass combination. + +![G-A1 GPS](../../assets/flight_controller/accton-godwit/ga1/gps.png "G-A1 GPS") + +## Power Connection and Battery Monitor + +This universal controller features a CAN PMU module that supports 3 to 14s lithium batteries. +To ensure proper connection, attach the module's 6-pin connector to the flight control Power C1 and/or Power C2 interface. + +This universal controller does not provide power to the servos. +To power them, an external BEC must be connected to the positive and negative terminals of any A1–A8 or M1–M8 port. + +![G-A1 Power](../../assets/flight_controller/accton-godwit/ga1/power.png "G-A1 Power") + +## SD Card + +The SD card is NOT included in the package, you need to prepare the SD card and insert it into the slot. + +![G-A1 SD Card](../../assets/flight_controller/accton-godwit/ga1/sdcard.png "G-A1 SD Card") + +## Firmware + +The autopilot is compatible with PX4 firmware. And G-A1 can be detected by QGroundControl automatically. Users can also build it with target "accton-godwit_ga1" + +To [build PX4](../dev_setup/building_px4.md) for this target, open up the terminal and enter: + +```sh +make accton-godwit_ga1 +``` + +## More Information and Support + +- [Accton-IoT Godwit](https://www.accton-iot.com/godwit/) +- [sales@accton-iot.com](sales@accton-iot.com) +- [support@accton-iot.com](mailto:support@accton-iot.com) diff --git a/docs/en/flight_controller/autopilot_manufacturer_supported.md b/docs/en/flight_controller/autopilot_manufacturer_supported.md index cb88202875..4b5f74504b 100644 --- a/docs/en/flight_controller/autopilot_manufacturer_supported.md +++ b/docs/en/flight_controller/autopilot_manufacturer_supported.md @@ -12,6 +12,7 @@ This category includes boards that are not fully compliant with the pixhawk stan The boards in this category are: +- [Accton Godwit GA1](../flight_controller/accton-godwit_ga1.md) - [AirMind MindPX](../flight_controller/mindpx.md) - [AirMind MindRacer](../flight_controller/mindracer.md) - [ARK Electronics ARKV6X](../flight_controller/ark_v6x.md) (and [ARK Electronics Pixhawk Autopilot Bus Carrier](../flight_controller/ark_pab.md)) From 264b8fe27720bae6c7ac543ecc850378ec69470d Mon Sep 17 00:00:00 2001 From: Holden Ramsey <68555040+HTRamsey@users.noreply.github.com> Date: Wed, 10 Sep 2025 22:01:37 -0400 Subject: [PATCH 022/812] Tools: Support Setup for Linux Mint (#25486) --- Tools/setup/ubuntu.sh | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/Tools/setup/ubuntu.sh b/Tools/setup/ubuntu.sh index b043b133c2..95173279b8 100755 --- a/Tools/setup/ubuntu.sh +++ b/Tools/setup/ubuntu.sh @@ -54,6 +54,22 @@ if [[ ! -f "${DIR}/${REQUIREMENTS_FILE}" ]]; then return 1 fi +# Linux Mint compatibility: use upstream Ubuntu values +if [ -r /etc/upstream-release/lsb-release ]; then + . /etc/upstream-release/lsb-release + UBUNTU_CODENAME="${DISTRIB_CODENAME:-${UBUNTU_CODENAME:-}}" + UBUNTU_RELEASE="${DISTRIB_RELEASE:-${UBUNTU_RELEASE:-}}" + + lsb_release() { + if [ "$1" = "-cs" ]; then + printf '%s' "$UBUNTU_CODENAME" + elif [ "$1" = "-rs" ]; then + printf '%s' "$UBUNTU_RELEASE" + else + command lsb_release "$@" + fi + } +fi # check ubuntu version # otherwise warn and point to docker? From d1da30911e022b83f357dca20d9822858afa0294 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 11 Sep 2025 16:06:51 +1000 Subject: [PATCH 023/812] Update metadata and tidy a few docs (#25547) * Fix up metadata except for uorb graphs * Additional customization of startup tidy --- docs/en/SUMMARY.md | 3 + docs/en/_sidebar.md | 77 +++--- .../en/advanced_config/parameter_reference.md | 232 +++++++++++++++--- docs/en/airframes/airframe_reference.md | 13 +- docs/en/concept/system_startup.md | 33 ++- docs/en/modules/modules_driver_ins.md | 35 +++ docs/en/msg_docs/ActionRequest.md | 34 +-- docs/en/msg_docs/ActuatorMotors.md | 12 +- docs/en/msg_docs/ActuatorServos.md | 8 +- docs/en/msg_docs/Airspeed.md | 10 +- docs/en/msg_docs/ArmingCheckReply.md | 46 ++-- docs/en/msg_docs/ArmingCheckRequest.md | 8 +- docs/en/msg_docs/ArmingCheckRequestV0.md | 30 +++ docs/en/msg_docs/CellularStatus.md | 60 ++--- docs/en/msg_docs/RoverSpeedSetpoint.md | 14 ++ docs/en/msg_docs/RoverSpeedStatus.md | 18 ++ docs/en/msg_docs/VehicleAirData.md | 30 +-- docs/en/msg_docs/index.md | 7 +- docs/ko/_sidebar.md | 94 ++++--- docs/uk/_sidebar.md | 94 ++++--- docs/zh/_sidebar.md | 94 ++++--- 21 files changed, 674 insertions(+), 278 deletions(-) create mode 100644 docs/en/msg_docs/ArmingCheckRequestV0.md create mode 100644 docs/en/msg_docs/RoverSpeedSetpoint.md create mode 100644 docs/en/msg_docs/RoverSpeedStatus.md diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index 7f7110aaf2..b234fae75f 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -660,6 +660,8 @@ - [RoverPositionSetpoint](msg_docs/RoverPositionSetpoint.md) - [RoverRateSetpoint](msg_docs/RoverRateSetpoint.md) - [RoverRateStatus](msg_docs/RoverRateStatus.md) + - [RoverSpeedSetpoint](msg_docs/RoverSpeedSetpoint.md) + - [RoverSpeedStatus](msg_docs/RoverSpeedStatus.md) - [RoverSteeringSetpoint](msg_docs/RoverSteeringSetpoint.md) - [RoverThrottleSetpoint](msg_docs/RoverThrottleSetpoint.md) - [RoverVelocitySetpoint](msg_docs/RoverVelocitySetpoint.md) @@ -720,6 +722,7 @@ - [YawEstimatorStatus](msg_docs/YawEstimatorStatus.md) - [AirspeedValidatedV0](msg_docs/AirspeedValidatedV0.md) - [ArmingCheckReplyV0](msg_docs/ArmingCheckReplyV0.md) + - [ArmingCheckRequestV0](msg_docs/ArmingCheckRequestV0.md) - [BatteryStatusV0](msg_docs/BatteryStatusV0.md) - [EventV0](msg_docs/EventV0.md) - [HomePositionV0](msg_docs/HomePositionV0.md) diff --git a/docs/en/_sidebar.md b/docs/en/_sidebar.md index e8807c40eb..2d1ed64e69 100644 --- a/docs/en/_sidebar.md +++ b/docs/en/_sidebar.md @@ -1,10 +1,9 @@ -- [Introduction](/index.md) +- [Introduction](/index.md) - [Basic Concepts](/getting_started/px4_basic_concepts.md) - [Multicopters](/frames_multicopter/index.md) - - [Features](/features_mc/index.md) - [Flight Modes](/flight_modes_mc/index.md) - [Position Mode (MC)](/flight_modes_mc/position.md) @@ -37,7 +36,7 @@ - [Static Pressure Buildup](/advanced_config/static_pressure_buildup.md) - [Flying (Basics)](/flying/basic_flying_mc.md) - [Complete Vehicles](/complete_vehicles_mc/index.md) - - [ModalAI Starling](/complete_vehicles_mc/modalai_starling.md) + - [ModalAI Starling (PX4 Dev Kit)](/complete_vehicles_mc/modalai_starling.md) - [PX4 Vision Kit](/complete_vehicles_mc/px4_vision_kit.md) - [MindRacer BNF & RTF](/complete_vehicles_mc/mindracer_BNF_RTF.md) - [MindRacer 210](/complete_vehicles_mc/mindracer210.md) @@ -58,7 +57,6 @@ - [DJI F450 (CUAV v5 nano)](/frames_multicopter/dji_f450_cuav_5nano.md) - [Planes (Fixed-Wing)](/frames_plane/index.md) - - [Assembly](/assembly/assembly_fw.md) - [Config/Tuning](/config_fw/index.md) - [Auto-tune](/config/autotune_fw.md) @@ -86,7 +84,6 @@ - [Wing Wing Z84 (Pixracer)](/frames_plane/wing_wing_z84.md) - [VTOL](/frames_vtol/index.md) - - [Assembly](/assembly/assembly_vtol.md) - [VTOL Config/Tuning](/config_vtol/index.md) - [Auto-tune](/config/autotune_vtol.md) @@ -111,7 +108,6 @@ - [Complete Vehicles](/complete_vehicles_vtol/index.md) - [Operations](/config/operations.md) - - [Safety](/config/safety_intro.md) - [Safety Configuration (Failsafes)](/config/safety.md) - [Failsafe Simulation](/config/safety_simulation.md) @@ -132,7 +128,6 @@ - [QGroundControl Flight-Readiness Status](/flying/pre_flight_checks.md) - [Hardware Selection & Setup](/hardware/drone_parts.md) - - [Flight Controllers (Autopilots)](/flight_controller/index.md) - [Flight Controller Selection](/getting_started/flight_controller_selection.md) - [Pixhawk Series](/flight_controller/pixhawk_series.md) @@ -164,18 +159,18 @@ - [mRo (3DR) Pixhawk Wiring Quickstart](/assembly/quick_start_pixhawk.md) - [Holybro Pixhawk Mini (FMUv3) - Discontinued](/flight_controller/pixhawk_mini.md) - [Manufacturer-Supported Autopilots](/flight_controller/autopilot_manufacturer_supported.md) + - [Accton Godwit GA1](/flight_controller/accton-godwit_ga1.md) - [AirMind MindPX](/flight_controller/mindpx.md) - [AirMind MindRacer](/flight_controller/mindracer.md) - [ARK Electronics ARKV6X](/flight_controller/ark_v6x.md) - [ARK FPV Flight Controller](/flight_controller/ark_fpv.md) - [ARK Pi6X Flow Flight Controller](/flight_controller/ark_pi6x.md) - - [CUAV X7](/flight_controller/cuav_x7.md) - [CUAV Nora](/flight_controller/cuav_nora.md) - [CUAV V5+ (FMUv5)](/flight_controller/cuav_v5_plus.md) - [Wiring Quickstart](/assembly/quick_start_cuav_v5_plus.md) - [CUAV V5 nano (FMUv5)](/flight_controller/cuav_v5_nano.md) - [CUAV V5 nano Wiring Quickstart](/assembly/quick_start_cuav_v5_nano.md) - - [CUAV Pixhack v3 (FMUv3)](/flight_controller/pixhack_v3.md) + - [CUAV X25 EVO](/flight_controller/cuav_x25-evo.md) - [CubePilot Cube Orange+ (CubePilot)](/flight_controller/cubepilot_cube_orangeplus.md) - [CubePilot Cube Orange (CubePilot)](/flight_controller/cubepilot_cube_orange.md) - [CubePilot Cube Yellow (CubePilot)](/flight_controller/cubepilot_cube_yellow.md) @@ -188,11 +183,8 @@ - [Wiring Quickstart](/assembly/quick_start_durandal.md) - [Holybro Pix32 v5](/flight_controller/holybro_pix32_v5.md) - [Wiring Quickstart](/assembly/quick_start_holybro_pix32_v5.md) - - [ModalAI Flight Core v1](/flight_controller/modalai_fc_v1.md) - - [ModalAI VOXL Flight](/flight_controller/modalai_voxl_flight.md) - [ModalAI VOXL 2](/flight_controller/modalai_voxl_2.md) - - [mRobotics-X2.1 (FMUv2)](/flight_controller/mro_x2.1.md) - - [mRo Control Zero F7)](/flight_controller/mro_control_zero_f7.md) + - [mRo Control Zero F7](/flight_controller/mro_control_zero_f7.md) - [Sky-Drones AIRLink](/flight_controller/airlink.md) - [SPRacing SPRacingH7EXTREME](/flight_controller/spracingh7extreme.md) - [ThePeach FCC-K1](/flight_controller/thepeach_k1.md) @@ -206,18 +198,20 @@ - [Discontinued Autopilots/Vehicles](/flight_controller/autopilot_discontinued.md) - [Drotek Dropix (FMUv2)](/flight_controller/dropix.md) - [Omnibus F4 SD](/flight_controller/omnibus_f4_sd.md) - - [BetaFPV Beta75X 2S Brushless Whoop](/complete_vehicles_mc/betafpv_beta75x.md) - [Bitcraze Crazyflie 2.0 ](/complete_vehicles_mc/crazyflie2.md) - [Aerotenna OcPoC-Zynq Mini](/flight_controller/ocpoc_zynq.md) + - [CUAV X7](/flight_controller/cuav_x7.md) - [CUAV v5](/flight_controller/cuav_v5.md) + - [CUAV Pixhack v3 (FMUv3)](/flight_controller/pixhack_v3.md) - [Holybro Kakute F7](/flight_controller/kakutef7.md) - [Holybro Pixfalcon](/flight_controller/pixfalcon.md) - [Holybro pix32 (FMUv2)](/flight_controller/holybro_pix32.md) + - [ModalAI Flight Core v1](/flight_controller/modalai_fc_v1.md) + - [ModalAI VOXL Flight](/flight_controller/modalai_voxl_flight.md) + - [mRo X2.1 (FMUv2)](/flight_controller/mro_x2.1.md) - [mRo AUAV-X2](/flight_controller/auav_x2.md) - [NXP RDDRONE-FMUK66 FMU](/flight_controller/nxp_rddrone_fmuk66.md) - [3DR Pixhawk 1](/flight_controller/pixhawk.md) - - [Snapdragon Flight](/flight_controller/snapdragon_flight.md) - - [Intel® Aero RTF Drone](/complete_vehicles_mc/intel_aero.md) - [Pixhawk Autopilot Bus (PAB) & Carriers](/flight_controller/pixhawk_autopilot_bus.md) - [ARK Electronics Pixhawk Autopilot Bus Carrier](/flight_controller/ark_pab.md) - [Mounting the Flight Controller](/assembly/mount_and_orient_controller.md) @@ -241,6 +235,7 @@ - [Compass Power Compensation](/advanced_config/compass_power_compensation.md) - [Airspeed Sensors](/sensor/airspeed.md) - [Calibration](/config/airspeed.md) + - [Airspeed Validation](/advanced_config/airspeed_validation.md) - [TFSlot Airspeed Sensor](/sensor/airspeed_tfslot.md) - [Barometers](/sensor/barometer.md) - [Distance Sensors \(Rangefinders\)](/sensor/rangefinders.md) @@ -272,6 +267,7 @@ - [CUAV C-RTK](/gps_compass/rtk_gps_cuav_c-rtk.md) - [CUAV C-RTK2 PPK/RTK GNSS](/gps_compass/rtk_gps_cuav_c-rtk2.md) - [CUAV C-RTK 9Ps](/gps_compass/rtk_gps_cuav_c-rtk-9ps.md) + - [DATAGNSS NANO HRTK GNSS](/gps_compass/rtk_gps_datagnss_nano_hrtk.md) - [DATAGNSS GEM1305 RTK GNSS](/gps_compass/rtk_gps_gem1305.md) - [Femtones MINI2 Receiver](/gps_compass/rtk_gps_fem_mini2.md) - [Freefly RTK GPS](/gps_compass/rtk_gps_freefly.md) @@ -287,6 +283,7 @@ - [Trimble MB-Two](/gps_compass/rtk_gps_trimble_mb_two.md) - [CubePilot Here+ (Discontined)](/gps_compass/rtk_gps_hex_hereplus.md) - [INS (Inertial Navigation/GNSS)](/sensor/inertial_navigation_systems.md) + - [InertialLabs](/sensor/inertiallabs.md) - [VectorNav](/sensor/vectornav.md) - [Optical Flow](/sensor/optical_flow.md) - [ARK Flow](/dronecan/ark_flow.md) @@ -308,7 +305,6 @@ - [Zubax Telega](/dronecan/zubax_telega.md) - [PX4 Sapog ESC Firmware](/dronecan/sapog.md) - [Holybro Kotleta](/dronecan/holybro_kotleta.md) - - [Zubax Orel](/dronecan/zubax_orel.md) - [Vertiq](/peripherals/vertiq.md) - [VESC](/peripherals/vesc.md) - [Radio Control (RC)](/getting_started/rc_transmitter_receiver.md) @@ -320,6 +316,7 @@ - [Telemetry Radios](/telemetry/index.md) - [SiK Radio](/telemetry/sik_radio.md) - [RFD900 (SiK) Telemetry Radio](/telemetry/rfd900_telemetry.md) + - [ThunderFly TFSIK01 Telemetry Radio](/telemetry/tfsik_telemetry.md) - [HolyBro (SIK) Telemetry Radio](/telemetry/holybro_sik_radio.md) - [Telemetry Wifi](/telemetry/telemetry_wifi.md) - [ESP8266 WiFi Module](/telemetry/esp8266_wifi_module.md) @@ -335,6 +332,7 @@ - [FrSky Telemetry](/peripherals/frsky_telemetry.md) - [TBS Crossfire (CRSF) Telemetry](/telemetry/crsf_telemetry.md) - [Satellite Comms (Iridium/RockBlock)](/advanced_features/satcom_roadblock.md) + - [Power Systems](/power_systems/index.md) - [Battery Estimation Tuning](/config/battery.md) - [Battery Chemistry Overview](/power_systems/battery_chemistry.md) @@ -401,7 +399,6 @@ - [Full Parameter Reference](/advanced_config/parameter_reference.md) - [Other Vehicles](/airframes/index.md) - - [Airships (experimental)](/frames_airship/index.md) - [Autogyros (experimental)](/frames_autogyro/index.md) - [ThunderFly Auto-G2 (Holybro pix32)](/frames_autogyro/thunderfly_auto_g2.md) @@ -409,17 +406,17 @@ - [Helicopter (experimental)](/frames_helicopter/index.md) - [Helicopter Config/Tuning](/config_heli/index.md) - [Rovers (experimental)](/frames_rover/index.md) - - [Ackermann Rovers](/frames_rover/ackermann.md) - - [Drive Modes](/flight_modes_rover/ackermann.md) - - [Configuration/Tuning](/config_rover/ackermann.md) - - [Differential Rovers](/frames_rover/differential.md) - - [Drive Modes](/flight_modes_rover/differential.md) - - [Configuration/Tuning](/config_rover/differential.md) - - [Aion Robotics R1](/frames_rover/aion_r1.md) - - [Mecanum Rovers](/frames_rover/mecanum.md) - - [Drive Modes](/flight_modes_rover/mecanum.md) - - [Configuration/Tuning](/config_rover/mecanum.md) - - [(Deprecated) Rover Position Control](/frames_rover/rover_position_control.md) + - [Drive Modes](/flight_modes_rover/index.md) + - [Manual](/flight_modes_rover/manual.md) + - [Auto](/flight_modes_rover/auto.md) + - [Configuration/Tuning](/config_rover/index.md) + - [Basic Setup](/config_rover/basic_setup.md) + - [Rate Tuning](/config_rover/rate_tuning.md) + - [Attitude Tuning](/config_rover/attitude_tuning.md) + - [Velocity Tuning](/config_rover/velocity_tuning.md) + - [Position Tuning](/config_rover/position_tuning.md) + - [Complete Vehicles](/complete_vehicles_rover/index.md) + - [Aion Robotics R1](/complete_vehicles_rover/aion_r1.md) - [Submarines (experimental)](/frames_sub/index.md) - [BlueROV2](/frames_sub/bluerov2.md) - [Airframes Reference](/airframes/airframe_reference.md) @@ -531,6 +528,7 @@ - [Airspeed](/msg_docs/Airspeed.md) - [AirspeedWind](/msg_docs/AirspeedWind.md) - [AutotuneAttitudeControlStatus](/msg_docs/AutotuneAttitudeControlStatus.md) + - [BatteryInfo](/msg_docs/BatteryInfo.md) - [ButtonEvent](/msg_docs/ButtonEvent.md) - [CameraCapture](/msg_docs/CameraCapture.md) - [CameraStatus](/msg_docs/CameraStatus.md) @@ -549,6 +547,7 @@ - [DifferentialPressure](/msg_docs/DifferentialPressure.md) - [DistanceSensor](/msg_docs/DistanceSensor.md) - [DistanceSensorModeChangeRequest](/msg_docs/DistanceSensorModeChangeRequest.md) + - [DronecanNodeStatus](/msg_docs/DronecanNodeStatus.md) - [Ekf2Timestamps](/msg_docs/Ekf2Timestamps.md) - [EscReport](/msg_docs/EscReport.md) - [EscStatus](/msg_docs/EscStatus.md) @@ -623,6 +622,7 @@ - [MountOrientation](/msg_docs/MountOrientation.md) - [NavigatorMissionItem](/msg_docs/NavigatorMissionItem.md) - [NavigatorStatus](/msg_docs/NavigatorStatus.md) + - [NeuralControl](/msg_docs/NeuralControl.md) - [NormalizedUnsignedSetpoint](/msg_docs/NormalizedUnsignedSetpoint.md) - [ObstacleDistance](/msg_docs/ObstacleDistance.md) - [OffboardControlMode](/msg_docs/OffboardControlMode.md) @@ -662,6 +662,8 @@ - [RoverPositionSetpoint](/msg_docs/RoverPositionSetpoint.md) - [RoverRateSetpoint](/msg_docs/RoverRateSetpoint.md) - [RoverRateStatus](/msg_docs/RoverRateStatus.md) + - [RoverSpeedSetpoint](/msg_docs/RoverSpeedSetpoint.md) + - [RoverSpeedStatus](/msg_docs/RoverSpeedStatus.md) - [RoverSteeringSetpoint](/msg_docs/RoverSteeringSetpoint.md) - [RoverThrottleSetpoint](/msg_docs/RoverThrottleSetpoint.md) - [RoverVelocitySetpoint](/msg_docs/RoverVelocitySetpoint.md) @@ -721,7 +723,13 @@ - [Wind](/msg_docs/Wind.md) - [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md) - [AirspeedValidatedV0](/msg_docs/AirspeedValidatedV0.md) + - [ArmingCheckReplyV0](/msg_docs/ArmingCheckReplyV0.md) + - [ArmingCheckRequestV0](/msg_docs/ArmingCheckRequestV0.md) + - [BatteryStatusV0](/msg_docs/BatteryStatusV0.md) + - [EventV0](/msg_docs/EventV0.md) + - [HomePositionV0](/msg_docs/HomePositionV0.md) - [VehicleAttitudeSetpointV0](/msg_docs/VehicleAttitudeSetpointV0.md) + - [VehicleLocalPositionV0](/msg_docs/VehicleLocalPositionV0.md) - [VehicleStatusV0](/msg_docs/VehicleStatusV0.md) - [MAVLink Messaging](/mavlink/index.md) - [Adding Messages](/mavlink/adding_messages.md) @@ -761,7 +769,7 @@ - [Debugging with GDB](/debug/gdb_debugging.md) - [SWD Debug Port](/debug/swd_debug.md) - [JLink Probe](/debug/probe_jlink.md) - - [Black Magic/DroneCode Probe](/debug/probe_bmp.md) + - [Black Magic/Zubax BugFace BF1 Probe](/debug/probe_bmp.md) - [STLink Probe](/debug/probe_stlink.md) - [MCU-Link Probe](/debug/probe_mculink.md) - [Hardfault Debugging](/debug/gdb_hardfault.md) @@ -785,6 +793,9 @@ - [Camera Integration/Architecture](/camera/camera_architecture.md) - [Computer Vision](/advanced/computer_vision.md) - [Motion Capture (VICON, Optitrack, NOKOV)](/tutorials/motion-capture.md) + - [Neural Networks](/advanced/neural_networks.md) + - [Neural Network Module Utilities](/advanced/nn_module_utilities.md) + - [TensorFlow Lite Micro (TFLM)](/advanced/tflm.md) - [Installing driver for Intel RealSense R200](/advanced/realsense_intel_driver.md) - [Switching State Estimators](/advanced/switching_state_estimators.md) - [Out-of-Tree Modules](/advanced/out_of_tree_modules.md) @@ -816,8 +827,12 @@ - [Test MC_02 - Full Autonomous](/test_cards/mc_02_full_autonomous.md) - [Test MC_03 - Auto Manual Mix](/test_cards/mc_03_auto_manual_mix.md) - [Test MC_04 - Failsafe Testing](/test_cards/mc_04_failsafe_testing.md) - - [Test MC_05 - Indoor Flight (Manual Modes)](/test_cards/mc_05_indoor_flight_manual_modes.md) + - [Test MC_05 - Manual Modes (Inside)](/test_cards/mc_05_indoor_flight_manual_modes.md) + - [Test MC_06 - Optical Flow (Inside)](/test_cards/mc_06_optical_flow.md) + - [Test MC_07 - VIO (Inside)](/test_cards/mc_07_vio.md) + - [Test MC_08 - DSHOT ESC](/test_cards/mc_08_dshot.md) - [Unit Tests](/test_and_ci/unit_tests.md) + - [Fuzz Tests](/test_and_ci/fuzz_tests.md) - [Continuous Integration](/test_and_ci/continous_integration.md) - [Integration Testing](/test_and_ci/integration_testing.md) - [MAVSDK Integration Testing](/test_and_ci/integration_testing_mavsdk.md) diff --git a/docs/en/advanced_config/parameter_reference.md b/docs/en/advanced_config/parameter_reference.md index 1a7acb4363..9c8c4b9a15 100644 --- a/docs/en/advanced_config/parameter_reference.md +++ b/docs/en/advanced_config/parameter_reference.md @@ -692,6 +692,16 @@ to 0 and 4096. Other standard params follows the same rule. | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 65535 | | 0 | +### PCA9685_EN_BUS (`INT32`) {#PCA9685_EN_BUS} + +Enable the PCA9685 output driver. + +The integer refers to the I2C bus number where PCA9685 is connected. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 10 | | 0 | + ### PCA9685_FAIL1 (`INT32`) {#PCA9685_FAIL1} PCA9685 Output Channel 1 Failsafe Value. @@ -14435,9 +14445,9 @@ Set bits in the following positions to enable: ### FW_AT_MAN_AUX (`INT32`) {#FW_AT_MAN_AUX} -Enable/disable auto tuning using an RC AUX input. +Enable/disable auto tuning using a manual control AUX input. -Defines which RC_MAP_AUXn parameter maps the RC channel used to enable/disable auto tuning. +Defines which RC_MAP_AUXn parameter maps the manual control channel used to enable/disable auto tuning. **Values:** @@ -16242,21 +16252,6 @@ Expect and require a healthy MAVLink parachute system. | ------ | -------- | -------- | --------- | ------------ | ---- | |   | | | | Disabled (0) | -### COM_POSCTL_NAVL (`INT32`) {#COM_POSCTL_NAVL} - -Position mode navigation loss response. - -This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control in manual Position mode. - -**Values:** - -- `0`: Altitude mode -- `1`: Land mode (descend) - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - ### COM_POS_FS_EPH (`FLOAT`) {#COM_POS_FS_EPH} Horizontal position error threshold for hovering systems. @@ -16363,7 +16358,7 @@ A negative value disables the check. ### COM_RCL_EXCEPT (`INT32`) {#COM_RCL_EXCEPT} -RC loss exceptions. +Manual control loss exceptions. Specify modes where manual control loss is ignored and no failsafe is triggered. External modes requiring stick input will still failsafe. @@ -16381,7 +16376,7 @@ External modes requiring stick input will still failsafe. ### COM_RC_ARM_HYST (`INT32`) {#COM_RC_ARM_HYST} -RC input arm/disarm command duration. +Manual control input arm/disarm command duration. The default value of 1000 requires the stick to be held in the arm or disarm position for 1 second. @@ -16429,9 +16424,9 @@ Ensure the value is not set lower than the update interval of the RC or Joystick ### COM_RC_OVERRIDE (`INT32`) {#COM_RC_OVERRIDE} -Enable RC stick override of auto and/or offboard modes. +Enable manual control stick override. -When RC stick override is enabled, moving the RC sticks more than COM_RC_STICK_OV +When enabled, moving the sticks more than COM_RC_STICK_OV immediately gives control back to the pilot by switching to Position mode and if position is unavailable Altitude mode. Note: Only has an effect on multicopters, and VTOLs in multicopter mode. @@ -16447,7 +16442,7 @@ Note: Only has an effect on multicopters, and VTOLs in multicopter mode. ### COM_RC_STICK_OV (`FLOAT`) {#COM_RC_STICK_OV} -RC stick override threshold. +Stick override threshold. If COM_RC_OVERRIDE is enabled and the joystick input is moved more than this threshold the autopilot the pilot takes over control. @@ -16591,11 +16586,10 @@ action will be executed. ### NAV_RCL_ACT (`INT32`) {#NAV_RCL_ACT} -Set RC loss failsafe mode. +Set manual control loss failsafe mode. -The RC loss failsafe will only be entered after a timeout, -set by COM_RC_LOSS_T in seconds. If RC input checks have been disabled -by setting the COM_RC_IN_MODE param it will not be triggered. +The manual control loss failsafe will only be entered after a timeout, +set by COM_RC_LOSS_T in seconds. **Values:** @@ -16876,7 +16870,7 @@ armed. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1 | 0.01 | 0.055 | % | +|   | 0 | 1 | 0.01 | 0.055 | norm | ### DSHOT_TEL_CFG (`INT32`) {#DSHOT_TEL_CFG} @@ -19929,7 +19923,7 @@ Yaw behaviour during orbit flight. - `1`: Hold Initial Heading - `2`: Uncontrolled - `3`: Hold Front Tangent to Circle -- `4`: RC Controlled +- `4`: Manually (yaw stick) Controlled | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20268,6 +20262,7 @@ Modes 1 and 2 require each F9P UART1 to be connected to the Autopilot. In additi F9P units are connected to each other. Modes 3 and 4 only require UART1 on each F9P connected to the Autopilot or Can Node. UART RX DMA is required. RTK is still possible with this setup. +Mode 6 is intended for use with a ground control station (not necessarily an RTK correction base). **Values:** @@ -20277,6 +20272,7 @@ RTK is still possible with this setup. - `3`: Heading (Rover With Moving Base UART1 Connected to Autopilot Or Can Node At 921600) - `4`: Moving Base (Moving Base UART1 Connected to Autopilot Or Can Node At 921600) - `5`: Rover with Static Base on UART2 (similar to Default, except coming in on UART2) +- `6`: Ground Control Station (UART2 outputs NMEA) | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -29542,6 +29538,16 @@ Distance from the center of the right wheel to the center of the left wheel. | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 100 | 0.001 | 0 | m | +### RD_YAW_STK_GAIN (`FLOAT`) {#RD_YAW_STK_GAIN} + +Yaw stick gain for Manual mode. + +Assign value <1.0 to decrease stick response for yaw control. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.1 | 1 | 0.01 | 1 | + ## Rover Mecanum ### RM_COURSE_CTL_TH (`FLOAT`) {#RM_COURSE_CTL_TH} @@ -29567,6 +29573,16 @@ Distance from the center of the right wheel to the center of the left wheel. | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 100 | 0.001 | 0 | m | +### RM_YAW_STK_GAIN (`FLOAT`) {#RM_YAW_STK_GAIN} + +Yaw stick gain for Manual mode. + +Assign value <1.0 to decrease stick response for yaw control. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.1 | 1 | 0.01 | 1 | + ## Rover Rate Control ### RO_YAW_ACCEL_LIM (`FLOAT`) {#RO_YAW_ACCEL_LIM} @@ -29591,6 +29607,18 @@ Set to -1 to disable. | ------ | -------- | -------- | --------- | ------- | ------- | |   | -1 | 10000 | 0.01 | -1. | deg/s^2 | +### RO_YAW_EXPO (`FLOAT`) {#RO_YAW_EXPO} + +Yaw rate expo factor. + +Exponential factor for tuning the input curve shape. +0 Purely linear input curve +1 Purely cubic input curve + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1 | | 0. | + ### RO_YAW_RATE_CORR (`FLOAT`) {#RO_YAW_RATE_CORR} Yaw rate correction factor. @@ -29651,6 +29679,19 @@ Percentage of stick input range that will be interpreted as zero around the stic | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 1 | 0.01 | 0.1 | +### RO_YAW_SUPEXPO (`FLOAT`) {#RO_YAW_SUPEXPO} + +Yaw rate super expo factor. + +"Superexponential" factor for refining the input curve shape tuned using RO_YAW_EXPO. +0 Pure Expo function +0.7 reasonable shape enhancement for intuitive stick feel +0.95 very strong bent input curve only near maxima have effect + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 0.95 | | 0. | + ## Rover Velocity Control ### RO_ACCEL_LIM (`FLOAT`) {#RO_ACCEL_LIM} @@ -29838,6 +29879,24 @@ Selects the algorithm used for logfile encryption | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 2 | +### SDLOG_BACKEND (`INT32`) {#SDLOG_BACKEND} + +Logging Backend (integer bitmask). + +If no logging is set the logger will not be started. +Set bits true to enable: +0: SD card logging +1: Mavlink logging + +**Bitmask:** + +- `0`: SD card logging +- `1`: Mavlink logging + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 3 | | 3 | + ### SDLOG_BOOT_BAT (`INT32`) {#SDLOG_BOOT_BAT} Battery-only Logging. @@ -29924,10 +29983,12 @@ Logging Mode. Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming. +Note: The logging start/end points that can be configured here only apply to +SD logging. The mavlink backend is started/stopped independently +of these points. **Values:** -- `-1`: disabled - `0`: when armed until disarm (default) - `1`: from boot until disarm - `2`: from boot until shutdown @@ -33018,6 +33079,31 @@ The mode will switch from long to short range when the distance is less than the | ------ | -------- | -------- | --------- | ------- | ---- | |   | 1 | 50 | | 4 | m | +### SENS_BAHRS_CFG (`INT32`) {#SENS_BAHRS_CFG} + +Serial Configuration for EULER-NAV BAHRS. + +Configure on which serial port to run EULER-NAV BAHRS. + +**Values:** + +- `0`: Disabled +- `6`: UART 6 +- `101`: TELEM 1 +- `102`: TELEM 2 +- `103`: TELEM 3 +- `104`: TELEM/SERIAL 4 +- `201`: GPS 1 +- `202`: GPS 2 +- `203`: GPS 3 +- `300`: Radio Controller +- `301`: Wifi Port +- `401`: EXT2 + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | + ### SENS_BARO_QNH (`FLOAT`) {#SENS_BARO_QNH} QNH for barometer. @@ -35562,6 +35648,86 @@ Note: certain drivers such as the GPS can determine the Baudrate automatically. | ------- | -------- | -------- | --------- | ------- | ---- | | ✓ | | | | 1 | +## Simulation + +### SIM_GZ_EN_ASPD (`INT32`) {#SIM_GZ_EN_ASPD} + +Enable airspeed sensor in Gazebo bridge. + +**Values:** + +- `0`: Disabled +- `1`: Enabled + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ----------- | ---- | +| ✓ | | | | Enabled (1) | + +### SIM_GZ_EN_BARO (`INT32`) {#SIM_GZ_EN_BARO} + +Enable barometer/air pressure sensor in Gazebo bridge. + +**Values:** + +- `0`: Disabled +- `1`: Enabled + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ----------- | ---- | +| ✓ | | | | Enabled (1) | + +### SIM_GZ_EN_FLOW (`INT32`) {#SIM_GZ_EN_FLOW} + +Enable optical flow sensor in Gazebo bridge. + +**Values:** + +- `0`: Disabled +- `1`: Enabled + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ----------- | ---- | +| ✓ | | | | Enabled (1) | + +### SIM_GZ_EN_GPS (`INT32`) {#SIM_GZ_EN_GPS} + +Enable GPS/NavSat sensor in Gazebo bridge. + +**Values:** + +- `0`: Disabled +- `1`: Enabled + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ----------- | ---- | +| ✓ | | | | Enabled (1) | + +### SIM_GZ_EN_LIDAR (`INT32`) {#SIM_GZ_EN_LIDAR} + +Enable laser/lidar sensors in Gazebo bridge. + +**Values:** + +- `0`: Disabled +- `1`: Enabled + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ----------- | ---- | +| ✓ | | | | Enabled (1) | + +### SIM_GZ_EN_ODOM (`INT32`) {#SIM_GZ_EN_ODOM} + +Enable odometry in Gazebo bridge. + +**Values:** + +- `0`: Disabled +- `1`: Enabled + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ----------- | ---- | +| ✓ | | | | Enabled (1) | + ## Simulation In Hardware ### SIH_DISTSNSR_MAX (`FLOAT`) {#SIH_DISTSNSR_MAX} @@ -41075,3 +41241,11 @@ SPC_VEHICLE_RESP. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0.5 | + +### ZENOH_DOMAIN_ID (`INT32`) {#ZENOH_DOMAIN_ID} + +ROS2 RMW_ZENOH_CPP Domain id. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 232 | | 0 | diff --git a/docs/en/airframes/airframe_reference.md b/docs/en/airframes/airframe_reference.md index 4ede6221a5..fdcefc78d9 100644 --- a/docs/en/airframes/airframe_reference.md +++ b/docs/en/airframes/airframe_reference.md @@ -628,7 +628,16 @@ div.frame_variant td, div.frame_variant th { ### Free-Flyer

@@ -638,7 +647,7 @@ div.frame_variant td, div.frame_variant th { - KTH-ATMOS + KTH-ATMOS Maintainer: DISCOWER

SYS_AUTOSTART = 70000

diff --git a/docs/en/concept/system_startup.md b/docs/en/concept/system_startup.md index 76bf291956..4ef80d0de1 100644 --- a/docs/en/concept/system_startup.md +++ b/docs/en/concept/system_startup.md @@ -13,9 +13,9 @@ The first executed file is the [init.d/rcS](https://github.com/PX4/PX4-Autopilot The following sections are split according to the operating system that PX4 runs on. -## Posix (Linux/MacOS) +## POSIX (Linux/MacOS) -On Posix, the system shell is used as script interpreter (e.g. /bin/sh, being symlinked to dash on Ubuntu). +On POSIX, the system shell is used as script interpreter (e.g. /bin/sh, being symlinked to dash on Ubuntu). For that to work, a few things are required: - PX4 modules need to look like individual executables to the system. @@ -54,7 +54,7 @@ cd /build/px4_sitl_default/bin ### Dynamic Modules Normally, all modules are compiled into a single PX4 executable. -However, on Posix, there's the option of compiling a module into a separate file, which can be loaded into PX4 using the `dyn` command. +However, on POSIX, there's the option of compiling a module into a separate file, which can be loaded into PX4 using the `dyn` command. ```sh dyn ./test.px4mod @@ -90,7 +90,7 @@ This is documented below. The best way to customize the system startup is to introduce a [new frame configuration](../dev_airframes/adding_a_new_frame.md). The frame configuration file can be included in the firmware or on an SD Card. -#### Dynamic customization +#### Dynamic Customization If you only need to "tweak" the existing configuration, such as starting one more application or setting the value of a few parameters, you can specify these by creating two files in the `/etc/` directory of the SD Card: @@ -148,27 +148,36 @@ The following example shows how to start custom applications: mandatory_app start # Will abort boot if mandatory_app is unknown or fails ``` -#### Additional customization +#### Additional Init-File Customization -In rare cases where the desired setup cannot be achieved through frame configuration or dynamic customization, -you can add a script that will be contained in the binary. +In rare cases where the desired setup cannot be achieved through frame configuration or dynamic customization, you can add a script that will be compiled into the binary for a particular `make` target build variant. -**Note**: In almost all cases, you should use a frame configuration. This method should only be used for -edge-cases such as customizing `cannode` based boards. +::: warning +In almost all cases, you should use a frame configuration. +This method should only be used for edge-cases such as customizing `cannode` based boards. +::: + +The steps are: + +- Add a new init script in `boards///init` that will run during board startup. + For example: -- Add a new init script in `boards///init` that will run during board startup. For example: ```sh # File: boards///init/rc.additional param set-default ``` -- Add a new board variant in `boards///.px4board` that includes the additional script. For example: +- Add a new board variant in `boards///.px4board` that includes the additional script. + For example: + ```sh # File: boards///var.px4board CONFIG_BOARD_ADDITIONAL_INIT="rc.additional" ``` -- Compile the firmware with your new variant by appending the variant name to the compile target. For example: +- Compile the firmware with your new variant by appending the variant name to the compile target. + For example: + ```sh make _var ``` diff --git a/docs/en/modules/modules_driver_ins.md b/docs/en/modules/modules_driver_ins.md index 408066a914..6d72447f28 100644 --- a/docs/en/modules/modules_driver_ins.md +++ b/docs/en/modules/modules_driver_ins.md @@ -45,6 +45,41 @@ MicroStrain [arguments...] status Driver status ``` +## eulernav_bahrs + +Source: [drivers/ins/eulernav_bahrs](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/eulernav_bahrs) + +### Description + +Serial bus driver for the EULER-NAV Baro-Inertial AHRS. + +### Examples + +Attempt to start driver on a specified serial device. + +``` +eulernav_bahrs start -d /dev/ttyS1 +``` + +Stop driver + +``` +eulernav_bahrs stop +``` + +### Usage {#eulernav_bahrs_usage} + +``` +eulernav_bahrs [arguments...] + Commands: + start Start driver + -d Serial device + + status Print driver status + + stop Stop driver +``` + ## ilabs Source: [drivers/ins/ilabs](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/ilabs) diff --git a/docs/en/msg_docs/ActionRequest.md b/docs/en/msg_docs/ActionRequest.md index 3579870754..1c724dabb7 100644 --- a/docs/en/msg_docs/ActionRequest.md +++ b/docs/en/msg_docs/ActionRequest.md @@ -15,25 +15,25 @@ Request are published by `manual_control` and subscribed by the `commander` and # It allows mapping triggers from various external interfaces like RC channels or MAVLink to cause an action. # Request are published by `manual_control` and subscribed by the `commander` and `vtol_att_control` modules. -uint64 timestamp # [us] Time since system start +uint64 timestamp # [us] Time since system start -uint8 action # [@enum ACTION] Requested action -uint8 ACTION_DISARM = 0 # Disarm vehicle -uint8 ACTION_ARM = 1 # Arm vehicle -uint8 ACTION_TOGGLE_ARMING = 2 # Toggle arming -uint8 ACTION_UNKILL = 3 # Revert a kill action -uint8 ACTION_KILL = 4 # Kill vehicle (instantly stop the motors) -uint8 ACTION_SWITCH_MODE = 5 # Switch mode. The target mode is set in the `mode` field. -uint8 ACTION_VTOL_TRANSITION_TO_MULTICOPTER = 6 # Transition to hover flight -uint8 ACTION_VTOL_TRANSITION_TO_FIXEDWING = 7 # Transition to fast forward flight -uint8 ACTION_TERMINATION = 8 # Irreversably output failsafe values on all outputs, trigger parachute +uint8 action # [@enum ACTION] Requested action +uint8 ACTION_DISARM = 0 # Disarm vehicle +uint8 ACTION_ARM = 1 # Arm vehicle +uint8 ACTION_TOGGLE_ARMING = 2 # Toggle arming +uint8 ACTION_UNKILL = 3 # Revert a kill action +uint8 ACTION_KILL = 4 # Kill vehicle (instantly stop the motors) +uint8 ACTION_SWITCH_MODE = 5 # Switch mode. The target mode is set in the `mode` field. +uint8 ACTION_VTOL_TRANSITION_TO_MULTICOPTER = 6 # Transition to hover flight +uint8 ACTION_VTOL_TRANSITION_TO_FIXEDWING = 7 # Transition to fast forward flight +uint8 ACTION_TERMINATION = 8 # Irreversibly output failsafe values on all outputs, trigger parachute -uint8 source # [@enum SOURCE] Request trigger type, such as a switch, button or gesture -uint8 SOURCE_STICK_GESTURE = 0 # Triggered by holding the sticks in a certain position -uint8 SOURCE_RC_SWITCH = 1 # Triggered by an RC switch moving into a certain position -uint8 SOURCE_RC_BUTTON = 2 # Triggered by a momentary button on the RC being pressed or held -uint8 SOURCE_RC_MODE_SLOT = 3 # Mode change through the RC mode selection mechanism +uint8 source # [@enum SOURCE] Request trigger type, such as a switch, button or gesture +uint8 SOURCE_STICK_GESTURE = 0 # Triggered by holding the sticks in a certain position +uint8 SOURCE_RC_SWITCH = 1 # Triggered by an RC switch moving into a certain position +uint8 SOURCE_RC_BUTTON = 2 # Triggered by a momentary button on the RC being pressed or held +uint8 SOURCE_RC_MODE_SLOT = 3 # Mode change through the RC mode selection mechanism -uint8 mode # Requested mode. Only applies when `action` is `ACTION_SWITCH_MODE`. Values for this field are defined by the `vehicle_status_s::NAVIGATION_STATE_*` enumeration. +uint8 mode # Requested mode. Only applies when `action` is `ACTION_SWITCH_MODE`. Values for this field are defined by the `vehicle_status_s::NAVIGATION_STATE_*` enumeration. ``` diff --git a/docs/en/msg_docs/ActuatorMotors.md b/docs/en/msg_docs/ActuatorMotors.md index 06fbd1b908..ca739f6c22 100644 --- a/docs/en/msg_docs/ActuatorMotors.md +++ b/docs/en/msg_docs/ActuatorMotors.md @@ -15,14 +15,14 @@ Published by the vehicle's allocation and consumed by the ESC protocol drivers e uint32 MESSAGE_VERSION = 0 -uint64 timestamp # [us] Time since system start -uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on -uint16 reversible_flags # Bitset indicating which motors are configured to be reversible +uint16 reversible_flags # Bitset indicating which motors are configured to be reversible -uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 +uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 # -uint8 NUM_CONTROLS = 12 -float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) +uint8 NUM_CONTROLS = 12 # +float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) ``` diff --git a/docs/en/msg_docs/ActuatorServos.md b/docs/en/msg_docs/ActuatorServos.md index ffe01e2f49..6f0a677dbf 100644 --- a/docs/en/msg_docs/ActuatorServos.md +++ b/docs/en/msg_docs/ActuatorServos.md @@ -15,10 +15,10 @@ Published by the vehicle's allocation and consumed by the actuator output driver uint32 MESSAGE_VERSION = 0 -uint64 timestamp # [us] Time since system start -uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on -uint8 NUM_CONTROLS = 8 -float32[8] control # [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. +uint8 NUM_CONTROLS = 8 # +float32[8] control # [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. ``` diff --git a/docs/en/msg_docs/Airspeed.md b/docs/en/msg_docs/Airspeed.md index 7309747f66..949af8d5e7 100644 --- a/docs/en/msg_docs/Airspeed.md +++ b/docs/en/msg_docs/Airspeed.md @@ -13,10 +13,10 @@ It is subscribed by the airspeed selector module, which validates the data from # This is published by airspeed sensor drivers, CAN airspeed sensors, simulators. # It is subscribed by the airspeed selector module, which validates the data from multiple sensors and passes on a single estimation to the EKF, controllers and telemetry providers. -uint64 timestamp # [us] Time since system start -uint64 timestamp_sample # [us] Timestamp of the raw data -float32 indicated_airspeed_m_s # [m/s] Indicated airspeed -float32 true_airspeed_m_s # [m/s] True airspeed -float32 confidence # [@range 0,1] Confidence value for this sensor +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Timestamp of the raw data +float32 indicated_airspeed_m_s # [m/s] Indicated airspeed +float32 true_airspeed_m_s # [m/s] True airspeed +float32 confidence # [@range 0,1] Confidence value for this sensor ``` diff --git a/docs/en/msg_docs/ArmingCheckReply.md b/docs/en/msg_docs/ArmingCheckReply.md index d5e3322506..8d619f5aaf 100644 --- a/docs/en/msg_docs/ArmingCheckReply.md +++ b/docs/en/msg_docs/ArmingCheckReply.md @@ -21,39 +21,39 @@ The message is not used by internal/FMU components, as their mode requirements a # Note that the external component is identified by its registration_id, which is allocated to the component during registration (arming_check_id in RegisterExtComponentReply). # The message is not used by internal/FMU components, as their mode requirements are known at compile time. -uint32 MESSAGE_VERSION = 1 +uint32 MESSAGE_VERSION = 1 uint64 timestamp # [us] Time since system start. -uint8 request_id # Id of ArmingCheckRequest for which this is a response. -uint8 registration_id # Id of external component emitting this response. +uint8 request_id # Id of ArmingCheckRequest for which this is a response. +uint8 registration_id # Id of external component emitting this response. -uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies. +uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies. -uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX] -bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json). +uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX] +bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json). +bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json). +bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json). -bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed. +bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed. -uint8 num_events # Number of queued failure messages (Event) in the events field. +uint8 num_events # Number of queued failure messages (Event) in the events field. -Event[5] events # Arming failure reasons (Queue of events to report to GCS). +Event[5] events # Arming failure reasons (Queue of events to report to GCS). # Mode requirements -bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope). -bool mode_req_attitude # Requires an attitude estimate. -bool mode_req_local_alt # Requires a local altitude estimate. -bool mode_req_local_position # Requires a local position estimate. -bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate. -bool mode_req_global_position # Requires a global position estimate. -bool mode_req_global_position_relaxed # Requires a relaxed global position estimate. -bool mode_req_mission # Requires an uploaded mission. -bool mode_req_home_position # Requires a home position (such as RTL/Return mode). -bool mode_req_prevent_arming # Prevent arming (such as in Land mode). -bool mode_req_manual_control # Requires a manual controller +bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope). +bool mode_req_attitude # Requires an attitude estimate. +bool mode_req_local_alt # Requires a local altitude estimate. +bool mode_req_local_position # Requires a local position estimate. +bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate. +bool mode_req_global_position # Requires a global position estimate. +bool mode_req_global_position_relaxed # Requires a relaxed global position estimate. +bool mode_req_mission # Requires an uploaded mission. +bool mode_req_home_position # Requires a home position (such as RTL/Return mode). +bool mode_req_prevent_arming # Prevent arming (such as in Land mode). +bool mode_req_manual_control # Requires a manual controller -uint8 ORB_QUEUE_LENGTH = 4 # +uint8 ORB_QUEUE_LENGTH = 4 ``` diff --git a/docs/en/msg_docs/ArmingCheckRequest.md b/docs/en/msg_docs/ArmingCheckRequest.md index cfa4b52c23..653d58d2d2 100644 --- a/docs/en/msg_docs/ArmingCheckRequest.md +++ b/docs/en/msg_docs/ArmingCheckRequest.md @@ -21,10 +21,12 @@ The reply will also include the registration_id for each external component, pro # The reply will include the published request_id, allowing correlation of all arming check information for a particular request. # The reply will also include the registration_id for each external component, provided to it during the registration process (RegisterExtComponentReply). -uint32 MESSAGE_VERSION = 0 +uint32 MESSAGE_VERSION = 1 -uint64 timestamp # [us] Time since system start. +uint64 timestamp # [us] Time since system start. -uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. +uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. + +uint32 valid_registrations_mask # Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) ``` diff --git a/docs/en/msg_docs/ArmingCheckRequestV0.md b/docs/en/msg_docs/ArmingCheckRequestV0.md new file mode 100644 index 0000000000..f5680c11f2 --- /dev/null +++ b/docs/en/msg_docs/ArmingCheckRequestV0.md @@ -0,0 +1,30 @@ +# ArmingCheckRequestV0 (UORB message) + +Arming check request. + +Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. +All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. +The request is sent regularly, even while armed, so that the FMU always knows the current arming state for external modes, and can forward it to ground stations. + +The reply will include the published request_id, allowing correlation of all arming check information for a particular request. +The reply will also include the registration_id for each external component, provided to it during the registration process (RegisterExtComponentReply). + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/ArmingCheckRequestV0.msg) + +```c +# Arming check request. +# +# Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. +# All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. +# The request is sent regularly, even while armed, so that the FMU always knows the current arming state for external modes, and can forward it to ground stations. +# +# The reply will include the published request_id, allowing correlation of all arming check information for a particular request. +# The reply will also include the registration_id for each external component, provided to it during the registration process (RegisterExtComponentReply). + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # [us] Time since system start. + +uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. + +``` diff --git a/docs/en/msg_docs/CellularStatus.md b/docs/en/msg_docs/CellularStatus.md index 6579d3fe85..04ca0a65dc 100644 --- a/docs/en/msg_docs/CellularStatus.md +++ b/docs/en/msg_docs/CellularStatus.md @@ -11,39 +11,39 @@ This is currently used only for logging cell status from MAVLink. # # This is currently used only for logging cell status from MAVLink. -uint64 timestamp # [us] Time since system start +uint64 timestamp # [us] Time since system start -uint16 status # [@enum STATUS_FLAG] Status bitmap -uint16 STATUS_FLAG_UNKNOWN = 1 # State unknown or not reportable -uint16 STATUS_FLAG_FAILED = 2 # Modem is unusable -uint16 STATUS_FLAG_INITIALIZING = 4 # Modem is being initialized -uint16 STATUS_FLAG_LOCKED = 8 # Modem is locked -uint16 STATUS_FLAG_DISABLED = 16 # Modem is not enabled and is powered down -uint16 STATUS_FLAG_DISABLING = 32 # Modem is currently transitioning to the STATUS_FLAG_DISABLED state -uint16 STATUS_FLAG_ENABLING = 64 # Modem is currently transitioning to the STATUS_FLAG_ENABLED state -uint16 STATUS_FLAG_ENABLED = 128 # Modem is enabled and powered on but not registered with a network provider and not available for data connections -uint16 STATUS_FLAG_SEARCHING = 256 # Modem is searching for a network provider to register -uint16 STATUS_FLAG_REGISTERED = 512 # Modem is registered with a network provider, and data connections and messaging may be available for use -uint16 STATUS_FLAG_DISCONNECTING = 1024 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated -uint16 STATUS_FLAG_CONNECTING = 2048 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered -uint16 STATUS_FLAG_CONNECTED = 4096 # One or more packet data bearers is active and connected +uint16 status # [@enum STATUS_FLAG] Status bitmap +uint16 STATUS_FLAG_UNKNOWN = 1 # State unknown or not reportable +uint16 STATUS_FLAG_FAILED = 2 # Modem is unusable +uint16 STATUS_FLAG_INITIALIZING = 4 # Modem is being initialized +uint16 STATUS_FLAG_LOCKED = 8 # Modem is locked +uint16 STATUS_FLAG_DISABLED = 16 # Modem is not enabled and is powered down +uint16 STATUS_FLAG_DISABLING = 32 # Modem is currently transitioning to the STATUS_FLAG_DISABLED state +uint16 STATUS_FLAG_ENABLING = 64 # Modem is currently transitioning to the STATUS_FLAG_ENABLED state +uint16 STATUS_FLAG_ENABLED = 128 # Modem is enabled and powered on but not registered with a network provider and not available for data connections +uint16 STATUS_FLAG_SEARCHING = 256 # Modem is searching for a network provider to register +uint16 STATUS_FLAG_REGISTERED = 512 # Modem is registered with a network provider, and data connections and messaging may be available for use +uint16 STATUS_FLAG_DISCONNECTING = 1024 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated +uint16 STATUS_FLAG_CONNECTING = 2048 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered +uint16 STATUS_FLAG_CONNECTED = 4096 # One or more packet data bearers is active and connected -uint8 failure_reason # [@enum FAILURE_REASON] Failure reason -uint8 FAILURE_REASON_NONE = 0 # No error -uint8 FAILURE_REASON_UNKNOWN = 1 # Error state is unknown -uint8 FAILURE_REASON_SIM_MISSING = 2 # SIM is required for the modem but missing -uint8 FAILURE_REASON_SIM_ERROR = 3 # SIM is available, but not usable for connection +uint8 failure_reason # [@enum FAILURE_REASON] Failure reason +uint8 FAILURE_REASON_NONE = 0 # No error +uint8 FAILURE_REASON_UNKNOWN = 1 # Error state is unknown +uint8 FAILURE_REASON_SIM_MISSING = 2 # SIM is required for the modem but missing +uint8 FAILURE_REASON_SIM_ERROR = 3 # SIM is available, but not usable for connection -uint8 type # [@enum CELLULAR_NETWORK_RADIO_TYPE] Cellular network radio type -uint8 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0 # None -uint8 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1 # GSM -uint8 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2 # CDMA -uint8 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3 # WCDMA -uint8 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4 # LTE +uint8 type # [@enum CELLULAR_NETWORK_RADIO_TYPE] Cellular network radio type +uint8 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0 # None +uint8 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1 # GSM +uint8 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2 # CDMA +uint8 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3 # WCDMA +uint8 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4 # LTE -uint8 quality # [dBm] Cellular network RSSI/RSRP, absolute value -uint16 mcc # [@invalid UINT16_MAX] Mobile country code -uint16 mnc # [@invalid UINT16_MAX] Mobile network code -uint16 lac # [@invalid 0] Location area code +uint8 quality # [dBm] Cellular network RSSI/RSRP, absolute value +uint16 mcc # [@invalid UINT16_MAX] Mobile country code +uint16 mnc # [@invalid UINT16_MAX] Mobile network code +uint16 lac # [@invalid 0] Location area code ``` diff --git a/docs/en/msg_docs/RoverSpeedSetpoint.md b/docs/en/msg_docs/RoverSpeedSetpoint.md new file mode 100644 index 0000000000..9eea46e60f --- /dev/null +++ b/docs/en/msg_docs/RoverSpeedSetpoint.md @@ -0,0 +1,14 @@ +# RoverSpeedSetpoint (UORB message) + +Rover Speed Setpoint + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverSpeedSetpoint.msg) + +```c +# Rover Speed Setpoint + +uint64 timestamp # [us] Time since system start +float32 speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction +float32 speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction + +``` diff --git a/docs/en/msg_docs/RoverSpeedStatus.md b/docs/en/msg_docs/RoverSpeedStatus.md new file mode 100644 index 0000000000..8c212e2b0f --- /dev/null +++ b/docs/en/msg_docs/RoverSpeedStatus.md @@ -0,0 +1,18 @@ +# RoverSpeedStatus (UORB message) + +Rover Velocity Status + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverSpeedStatus.msg) + +```c +# Rover Velocity Status + +uint64 timestamp # [us] Time since system start +float32 measured_speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Measured speed in body x direction +float32 adjusted_speed_body_x_setpoint # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction that is being tracked (Applied slew rates) +float32 pid_throttle_body_x_integral # [] [@range -1, 1] Integral of the PID for the closed loop controller of the speed in body x direction +float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction +float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates) +float32 pid_throttle_body_y_integral # [] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction + +``` diff --git a/docs/en/msg_docs/VehicleAirData.md b/docs/en/msg_docs/VehicleAirData.md index 86cf87e44c..dccfefc095 100644 --- a/docs/en/msg_docs/VehicleAirData.md +++ b/docs/en/msg_docs/VehicleAirData.md @@ -1,24 +1,26 @@ # VehicleAirData (UORB message) +Vehicle air data +Data from the currently selected barometer (plus ambient temperature from the source specified in temperature_source). +Includes calculated data such as barometric altitude and air density. [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleAirData.msg) ```c +# Vehicle air data +# +# Data from the currently selected barometer (plus ambient temperature from the source specified in temperature_source). +# Includes calculated data such as barometric altitude and air density. -uint64 timestamp # time since system start (microseconds) - -uint64 timestamp_sample # the timestamp of the raw data (microseconds) - -uint32 baro_device_id # unique device ID for the selected barometer - -float32 baro_alt_meter # Altitude above MSL calculated from temperature compensated baro sensor data using an ISA corrected for sea level pressure SENS_BARO_QNH. -float32 baro_pressure_pa # Absolute pressure in Pascals -float32 ambient_temperature # Abient temperature in degrees Celsius -uint8 temperature_source # Source of temperature data: 0: Default Temperature (15°C), 1: External Baro, 2: Airspeed - -float32 rho # air density - -uint8 calibration_count # Calibration changed counter. Monotonically increases whenever calibration changes. +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Timestamp of the raw data +uint32 baro_device_id # Unique device ID for the selected barometer +float32 baro_alt_meter # [m] [@frame MSL] Altitude above MSL calculated from temperature compensated baro sensor data using an ISA corrected for sea level pressure SENS_BARO_QNH +float32 baro_pressure_pa # [Pa] Absolute pressure +float32 ambient_temperature # [degC] Ambient temperature +uint8 temperature_source # Source of temperature data: 0: Default Temperature (15°C), 1: External Baro, 2: Airspeed +float32 rho # [kg/m^3] Air density +uint8 calibration_count # Calibration changed counter. Monotonically increases whenever calibration changes. ``` diff --git a/docs/en/msg_docs/index.md b/docs/en/msg_docs/index.md index c6e0c5c298..2c8085dc85 100644 --- a/docs/en/msg_docs/index.md +++ b/docs/en/msg_docs/index.md @@ -229,10 +229,10 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [RoverPositionSetpoint](RoverPositionSetpoint.md) — Rover Position Setpoint - [RoverRateSetpoint](RoverRateSetpoint.md) — Rover Rate setpoint - [RoverRateStatus](RoverRateStatus.md) — Rover Rate Status +- [RoverSpeedSetpoint](RoverSpeedSetpoint.md) — Rover Speed Setpoint +- [RoverSpeedStatus](RoverSpeedStatus.md) — Rover Velocity Status - [RoverSteeringSetpoint](RoverSteeringSetpoint.md) — Rover Steering setpoint - [RoverThrottleSetpoint](RoverThrottleSetpoint.md) — Rover Throttle setpoint -- [RoverVelocitySetpoint](RoverVelocitySetpoint.md) — Rover Velocity Setpoint -- [RoverVelocityStatus](RoverVelocityStatus.md) — Rover Velocity Status - [Rpm](Rpm.md) - [RtlStatus](RtlStatus.md) - [RtlTimeEstimate](RtlTimeEstimate.md) @@ -281,7 +281,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [UlogStreamAck](UlogStreamAck.md) — Ack a previously sent ulog_stream message that had the NEED_ACK flag set - [VehicleAcceleration](VehicleAcceleration.md) -- [VehicleAirData](VehicleAirData.md) +- [VehicleAirData](VehicleAirData.md) — Vehicle air data - [VehicleAngularAccelerationSetpoint](VehicleAngularAccelerationSetpoint.md) - [VehicleConstraints](VehicleConstraints.md) — Local setpoint constraints in NED frame setting something to NaN means that no limit is provided @@ -301,6 +301,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [YawEstimatorStatus](YawEstimatorStatus.md) - [AirspeedValidatedV0](AirspeedValidatedV0.md) - [ArmingCheckReplyV0](ArmingCheckReplyV0.md) +- [ArmingCheckRequestV0](ArmingCheckRequestV0.md) — Arming check request. - [BatteryStatusV0](BatteryStatusV0.md) — Battery status - [EventV0](EventV0.md) — this message is required here in the msg_old folder because other msg are depending on it Events interface diff --git a/docs/ko/_sidebar.md b/docs/ko/_sidebar.md index 79834ec3ad..6fda5a26c0 100644 --- a/docs/ko/_sidebar.md +++ b/docs/ko/_sidebar.md @@ -1,10 +1,8 @@ - [Introduction](/index.md) - - [기본 개념](/getting_started/px4_basic_concepts.md) - [멀티콥터](/frames_multicopter/index.md) - - [Features](/features_mc/index.md) - [비행 모드 ](/flight_modes_mc/index.md) - [위치 모드 (멀티콥터)](/flight_modes_mc/position.md) @@ -37,7 +35,7 @@ - [정압 축적](/advanced_config/static_pressure_buildup.md) - [Flying (Basics)](/flying/basic_flying_mc.md) - [완성 기체](/complete_vehicles_mc/index.md) - - [ModalAI Starling](/complete_vehicles_mc/modalai_starling.md) + - [ModalAI Starling (PX4 Dev Kit)](/complete_vehicles_mc/modalai_starling.md) - [PX4 비전 키트](/complete_vehicles_mc/px4_vision_kit.md) - [마인드레이서 BNF & RTF](/complete_vehicles_mc/mindracer_BNF_RTF.md) - [마인드레이서 210](/complete_vehicles_mc/mindracer210.md) @@ -58,7 +56,6 @@ - [DJI F450 (CUAV v5 nano)](/frames_multicopter/dji_f450_cuav_5nano.md) - [Planes (Fixed-Wing)](/frames_plane/index.md) - - [Assembly](/assembly/assembly_fw.md) - [Config/Tuning](/config_fw/index.md) - [Auto-tune](/config/autotune_fw.md) @@ -86,7 +83,6 @@ - [Wing Wing Z84 (Pixracer)](/frames_plane/wing_wing_z84.md) - [수직이착륙기(VTOL)](/frames_vtol/index.md) - - [Assembly](/assembly/assembly_vtol.md) - [VTOL 설정 및 튜닝](/config_vtol/index.md) - [Auto-tune](/config/autotune_vtol.md) @@ -111,7 +107,6 @@ - [Complete Vehicles](/complete_vehicles_vtol/index.md) - [Operations](/config/operations.md) - - [안전 설정](/config/safety_intro.md) - [Safety Configuration (Failsafes)](/config/safety.md) - [Failsafe Simulation](/config/safety_simulation.md) @@ -132,7 +127,6 @@ - [QGroundControl Flight-Readiness Status](/flying/pre_flight_checks.md) - [Hardware Selection & Setup](/hardware/drone_parts.md) - - [비행 컨트롤러 (오토파일럿)](/flight_controller/index.md) - [Flight Controller Selection](/getting_started/flight_controller_selection.md) - [Pixhawk Series](/flight_controller/pixhawk_series.md) @@ -169,13 +163,12 @@ - [ARK Electronics ARKV6X](/flight_controller/ark_v6x.md) - [ARK FPV Flight Controller](/flight_controller/ark_fpv.md) - [ARK Pi6X Flow Flight Controller](/flight_controller/ark_pi6x.md) - - [CUAV X7](/flight_controller/cuav_x7.md) - [CUAV Nora](/flight_controller/cuav_nora.md) - [CUAV V5+ (FMUv5)](/flight_controller/cuav_v5_plus.md) - [Wiring Quickstart](/assembly/quick_start_cuav_v5_plus.md) - [CUAV V5 nano (FMUv5)](/flight_controller/cuav_v5_nano.md) - [CUAV V5 nano 배선 퀵 스타트](/assembly/quick_start_cuav_v5_nano.md) - - [CUAV Pixhack v3 (FMUv3)](/flight_controller/pixhack_v3.md) + - [CUAV X25 EVO](/flight_controller/cuav_x25-evo.md) - [CubePilot Cube Orange+ (CubePilot)](/flight_controller/cubepilot_cube_orangeplus.md) - [CubePilot Cube Orange (CubePilot)](/flight_controller/cubepilot_cube_orange.md) - [CubePilot Cube Yellow (CubePilot)](/flight_controller/cubepilot_cube_yellow.md) @@ -188,11 +181,8 @@ - [Wiring Quickstart](/assembly/quick_start_durandal.md) - [Holybro Pix32 v5](/flight_controller/holybro_pix32_v5.md) - [Wiring Quickstart](/assembly/quick_start_holybro_pix32_v5.md) - - [ModalAI Flight Core v1](/flight_controller/modalai_fc_v1.md) - - [ModalAI VOXL Flight](/flight_controller/modalai_voxl_flight.md) - [ModalAI VOXL 2](/flight_controller/modalai_voxl_2.md) - - [mRobotics-X2.1 (FMUv2)](/flight_controller/mro_x2.1.md) - - [mRo Control Zero F7)](/flight_controller/mro_control_zero_f7.md) + - [mRo Control Zero F7](/flight_controller/mro_control_zero_f7.md) - [Sky-Drones AIRLink](/flight_controller/airlink.md) - [SPRacing SPRacingH7EXTREME](/flight_controller/spracingh7extreme.md) - [ThePeach FCC-K1](/flight_controller/thepeach_k1.md) @@ -206,18 +196,20 @@ - [Discontinued Autopilots/Vehicles](/flight_controller/autopilot_discontinued.md) - [Drotek Dropix (FMUv2)](/flight_controller/dropix.md) - [Omnibus F4 SD](/flight_controller/omnibus_f4_sd.md) - - [BetaFPV Beta75X 2S Brushless Whoop](/complete_vehicles_mc/betafpv_beta75x.md) - [Bitcraze Crazyflie 2.0 ](/complete_vehicles_mc/crazyflie2.md) - [Aerotenna OcPoC-Zynq Mini](/flight_controller/ocpoc_zynq.md) + - [CUAV X7](/flight_controller/cuav_x7.md) - [CUAV v5](/flight_controller/cuav_v5.md) + - [CUAV Pixhack v3 (FMUv3)](/flight_controller/pixhack_v3.md) - [Holybro Kakute F7](/flight_controller/kakutef7.md) - [Holybro Pixfalcon](/flight_controller/pixfalcon.md) - [Holybro pix32 (FMUv2)](/flight_controller/holybro_pix32.md) + - [ModalAI Flight Core v1](/flight_controller/modalai_fc_v1.md) + - [ModalAI VOXL Flight](/flight_controller/modalai_voxl_flight.md) + - [mRo X2.1 (FMUv2)](/flight_controller/mro_x2.1.md) - [mRo AUAV-X2](/flight_controller/auav_x2.md) - [NXP RDDRONE-FMUK66 FMU](/flight_controller/nxp_rddrone_fmuk66.md) - [3DR Pixhawk 1](/flight_controller/pixhawk.md) - - [Snapdragon Flight](/flight_controller/snapdragon_flight.md) - - [Intel® Aero RTF Drone](/complete_vehicles_mc/intel_aero.md) - [Pixhawk Autopilot Bus (PAB) & Carriers](/flight_controller/pixhawk_autopilot_bus.md) - [ARK Electronics Pixhawk Autopilot Bus Carrier](/flight_controller/ark_pab.md) - [Mounting the Flight Controller](/assembly/mount_and_orient_controller.md) @@ -229,7 +221,9 @@ - [Bootloader Update](/advanced_config/bootloader_update.md) - [Bootloader Update FMUv6X-RT via USB](/advanced_config/bootloader_update_v6xrt.md) - [Bootloader Flashing onto Betaflight Systems](/advanced_config/bootloader_update_from_betaflight.md) + - [Airframe Selection](/config/airframe.md) + - [센서](/sensor/index.md) - [가속도계](/sensor/accelerometer.md) - [Calibration](/config/accelerometer.md) @@ -241,6 +235,7 @@ - [나침반 전력 보정](/advanced_config/compass_power_compensation.md) - [항속 센서](/sensor/airspeed.md) - [Calibration](/config/airspeed.md) + - [Airspeed Validation](/advanced_config/airspeed_validation.md) - [TFSlot Airspeed Sensor](/sensor/airspeed_tfslot.md) - [Barometers](/sensor/barometer.md) - [거리 센서](/sensor/rangefinders.md) @@ -272,6 +267,7 @@ - [CUAV C-RTK](/gps_compass/rtk_gps_cuav_c-rtk.md) - [CUAV C-RTK2 PPK/RTK GNSS](/gps_compass/rtk_gps_cuav_c-rtk2.md) - [CUAV C-RTK 9Ps](/gps_compass/rtk_gps_cuav_c-rtk-9ps.md) + - [DATAGNSS NANO HRTK GNSS](/gps_compass/rtk_gps_datagnss_nano_hrtk.md) - [DATAGNSS GEM1305 RTK GNSS](/gps_compass/rtk_gps_gem1305.md) - [Femtones MINI2 Receiver](/gps_compass/rtk_gps_fem_mini2.md) - [Freefly RTK GPS](/gps_compass/rtk_gps_freefly.md) @@ -287,6 +283,7 @@ - [Trimble MB-Two](/gps_compass/rtk_gps_trimble_mb_two.md) - [CubePilot Here+ (Discontined)](/gps_compass/rtk_gps_hex_hereplus.md) - [INS (Inertial Navigation/GNSS)](/sensor/inertial_navigation_systems.md) + - [InertialLabs](/sensor/inertiallabs.md) - [VectorNav](/sensor/vectornav.md) - [광류 센서](/sensor/optical_flow.md) - [ARK Flow](/dronecan/ark_flow.md) @@ -297,6 +294,7 @@ - [ThunderFly TFRPM01 타코미터 센서](/sensor/thunderfly_tachometer.md) - [IMU Factory Calibration](/advanced_config/imu_factory_calibration.md) - [센서 온도 보정](/advanced_config/sensor_thermal_calibration.md) + - [액츄에이터](/actuators/index.md) - [ADSB/FLARM (트래픽 회피)](/config/actuators.md) - [ESC 보정](/advanced_config/esc_calibration.md) @@ -308,19 +306,22 @@ - [Zubax Telega](/dronecan/zubax_telega.md) - [PX4 Sapog ESC Firmware](/dronecan/sapog.md) - [Holybro Kotleta](/dronecan/holybro_kotleta.md) - - [Zubax Orel](/dronecan/zubax_orel.md) - [Vertiq](/peripherals/vertiq.md) - [VESC](/peripherals/vesc.md) + - [Radio Control (RC)](/getting_started/rc_transmitter_receiver.md) - [무선 조종기 설정](/config/radio.md) - [비행 모드](/config/flight_mode.md) + - [Joysticks](/config/joystick.md) + - [Data Links](/data_links/index.md) - [MAVLink 텔레메트리(OSD/GCS) ](/peripherals/mavlink_peripherals.md) - [텔레메트리 무선통신](/telemetry/index.md) - [SiK 무선통신](/telemetry/sik_radio.md) - [RFD900 (SiK) 텔레메트리](/telemetry/rfd900_telemetry.md) + - [ThunderFly TFSIK01 Telemetry Radio](/telemetry/tfsik_telemetry.md) - [HolyBro (SIK) Telemetry Radio](/telemetry/holybro_sik_radio.md) - [Wifi 텔레메트리](/telemetry/telemetry_wifi.md) - [ESP8266 WiFi 모듈](/telemetry/esp8266_wifi_module.md) @@ -338,6 +339,7 @@ - [TBS Crossfire (CRSF) Telemetry](/telemetry/crsf_telemetry.md) - [Satellite Comms (Iridium/RockBlock)](/advanced_features/satcom_roadblock.md) + - [Power Systems](/power_systems/index.md) - [Battery Estimation Tuning](/config/battery.md) - [Battery Chemistry Overview](/power_systems/battery_chemistry.md) @@ -356,6 +358,7 @@ - [Sky-Drones SmartAP PDB](/power_module/sky-drones_smartap-pdb.md) - [Smart/MAVLink Batteries](/smart_batteries/index.md) - [Rotoye Batmon 배터리 스마트 키트](/smart_batteries/rotoye_batmon.md) + - [탑재중량과 카메라](/payloads/index.md) - [Use Cases](/payloads/use_cases.md) - [Package Delivery Mission](/flying/package_delivery_mission.md) @@ -367,19 +370,25 @@ - [Gimbal \(Mount\) Configuration](/advanced/gimbal_control.md) - [Grippers](/peripherals/gripper.md) - [Servo Gripper](/peripherals/gripper_servo.md) + - [Peripherals](/peripherals/index.md) - [ADSB/FLARM/UTM (Traffic Avoidance)](/peripherals/adsb_flarm.md) - [낙하산](/peripherals/parachute.md) - [Remote ID](/peripherals/remote_id.md) + - [I2C Peripherals](/sensor_bus/i2c_general.md) - [I2C bus accelerators](/sensor_bus/i2c_general.md#i2c-bus-accelerators) - [TFI2CADT01 I2C address translator](/sensor_bus/translator_tfi2cadt.md) + - [CAN Peripherals](/can/index.md) + - [DroneCAN Peripherals](/dronecan/index.md) - [PX4 DroneCAN Firmware](/dronecan/px4_cannode_fw.md) - [ARK CANnode](/dronecan/ark_cannode.md) - [RaccoonLab CAN Nodes](/dronecan/raccoonlab_nodes.md) + - [배선 개요](/assembly/cable_wiring.md) + - [보조 컴퓨터](/companion_computer/index.md) - [Pixhawk + Companion Setup](/companion_computer/pixhawk_companion.md) - [RPi Pixhawk Companion](/companion_computer/pixhawk_rpi.md) @@ -395,16 +404,19 @@ - [리얼센스 T265 트래킹 카메라 (VIO)](/camera/camera_intel_realsense_t265_vio.md) - [동영상 스트리밍](/companion_computer/video_streaming.md) - [Video Streaming using WFB-ng Wifi (Long range)](/companion_computer/video_streaming_wfb_ng_wifi.md) + - [직렬 포트 설정 ](/peripherals/serial_configuration.md) + - [PX4 이더넷 설정](/advanced_config/ethernet_setup.md) + - [Standard Configuration](/config/index.md) + - [고급 설정](/advanced_config/index.md) - [Using PX4's Navigation Filter (EKF2)](/advanced_config/tuning_the_ecl_ekf.md) - [매개변수 검색 및 수정](/advanced_config/parameters.md) - [전체 매개변수 정의서](/advanced_config/parameter_reference.md) - [Other Vehicles](/airframes/index.md) - - [Airships (experimental)](/frames_airship/index.md) - [Autogyros (experimental)](/frames_autogyro/index.md) - [선더플라이 Auto-G2 (Holybro pix32)](/frames_autogyro/thunderfly_auto_g2.md) @@ -412,17 +424,17 @@ - [Helicopter (experimental)](/frames_helicopter/index.md) - [Helicopter Config/Tuning](/config_heli/index.md) - [Rovers (experimental)](/frames_rover/index.md) - - [Ackermann Rovers](/frames_rover/ackermann.md) - - [Drive Modes](/flight_modes_rover/ackermann.md) - - [Configuration/Tuning](/config_rover/ackermann.md) - - [Differential Rovers](/frames_rover/differential.md) - - [Drive Modes](/flight_modes_rover/differential.md) - - [Configuration/Tuning](/config_rover/differential.md) - - [Aion Robotics R1](/frames_rover/aion_r1.md) - - [Mecanum Rovers](/frames_rover/mecanum.md) - - [Drive Modes](/flight_modes_rover/mecanum.md) - - [Configuration/Tuning](/config_rover/mecanum.md) - - [(Deprecated) Rover Position Control](/frames_rover/rover_position_control.md) + - [Drive Modes](/flight_modes_rover/index.md) + - [Manual](/flight_modes_rover/manual.md) + - [Auto](/flight_modes_rover/auto.md) + - [Configuration/Tuning](/config_rover/index.md) + - [Basic Setup](/config_rover/basic_setup.md) + - [Rate Tuning](/config_rover/rate_tuning.md) + - [Attitude Tuning](/config_rover/attitude_tuning.md) + - [Velocity Tuning](/config_rover/velocity_tuning.md) + - [Position Tuning](/config_rover/position_tuning.md) + - [Complete Vehicles](/complete_vehicles_rover/index.md) + - [Aion Robotics R1](/complete_vehicles_rover/aion_r1.md) - [Submarines (experimental)](/frames_sub/index.md) - [블루로브2](/frames_sub/bluerov2.md) - [기체 프레임 정의서](/airframes/airframe_reference.md) @@ -534,6 +546,7 @@ - [Airspeed](/msg_docs/Airspeed.md) - [AirspeedWind](/msg_docs/AirspeedWind.md) - [AutotuneAttitudeControlStatus](/msg_docs/AutotuneAttitudeControlStatus.md) + - [BatteryInfo](/msg_docs/BatteryInfo.md) - [ButtonEvent](/msg_docs/ButtonEvent.md) - [CameraCapture](/msg_docs/CameraCapture.md) - [CameraStatus](/msg_docs/CameraStatus.md) @@ -552,6 +565,7 @@ - [DifferentialPressure](/msg_docs/DifferentialPressure.md) - [DistanceSensor](/msg_docs/DistanceSensor.md) - [DistanceSensorModeChangeRequest](/msg_docs/DistanceSensorModeChangeRequest.md) + - [DronecanNodeStatus](/msg_docs/DronecanNodeStatus.md) - [Ekf2Timestamps](/msg_docs/Ekf2Timestamps.md) - [EscReport](/msg_docs/EscReport.md) - [EscStatus](/msg_docs/EscStatus.md) @@ -626,6 +640,7 @@ - [MountOrientation](/msg_docs/MountOrientation.md) - [NavigatorMissionItem](/msg_docs/NavigatorMissionItem.md) - [NavigatorStatus](/msg_docs/NavigatorStatus.md) + - [NeuralControl](/msg_docs/NeuralControl.md) - [NormalizedUnsignedSetpoint](/msg_docs/NormalizedUnsignedSetpoint.md) - [ObstacleDistance](/msg_docs/ObstacleDistance.md) - [OffboardControlMode](/msg_docs/OffboardControlMode.md) @@ -724,7 +739,12 @@ - [Wind](/msg_docs/Wind.md) - [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md) - [AirspeedValidatedV0](/msg_docs/AirspeedValidatedV0.md) + - [ArmingCheckReplyV0](/msg_docs/ArmingCheckReplyV0.md) + - [BatteryStatusV0](/msg_docs/BatteryStatusV0.md) + - [EventV0](/msg_docs/EventV0.md) + - [HomePositionV0](/msg_docs/HomePositionV0.md) - [VehicleAttitudeSetpointV0](/msg_docs/VehicleAttitudeSetpointV0.md) + - [VehicleLocalPositionV0](/msg_docs/VehicleLocalPositionV0.md) - [VehicleStatusV0](/msg_docs/VehicleStatusV0.md) - [MAVLink Messaging](/mavlink/index.md) - [Adding Messages](/mavlink/adding_messages.md) @@ -734,6 +754,7 @@ - [Protocols/Microservices](/mavlink/protocols.md) - [Standard Modes Protocol](/mavlink/standard_modes.md) - [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](/middleware/uxrce_dds.md) + - [UORB Bridged to ROS 2](/middleware/dds_topics.md) - [모듈과 명령어](/modules/modules_main.md) - [자동 튜닝](/modules/modules_autotune.md) - [명령어](/modules/modules_command.md) @@ -763,7 +784,7 @@ - [Debugging with GDB](/debug/gdb_debugging.md) - [SWD Debug Port](/debug/swd_debug.md) - [JLink Probe](/debug/probe_jlink.md) - - [Black Magic/DroneCode Probe](/debug/probe_bmp.md) + - [Black Magic/Zubax BugFace BF1 Probe](/debug/probe_bmp.md) - [STLink Probe](/debug/probe_stlink.md) - [MCU-Link Probe](/debug/probe_mculink.md) - [Hardfault Debugging](/debug/gdb_hardfault.md) @@ -787,6 +808,9 @@ - [Camera Integration/Architecture](/camera/camera_architecture.md) - [컴퓨터 비전](/advanced/computer_vision.md) - [Motion Capture (VICON, Optitrack, NOKOV)](/tutorials/motion-capture.md) + - [Neural Networks](/advanced/neural_networks.md) + - [Neural Network Module Utilities](/advanced/nn_module_utilities.md) + - [TensorFlow Lite Micro (TFLM)](/advanced/tflm.md) - [Intel RealSense R200용 드라이버 설치](/advanced/realsense_intel_driver.md) - [상태 추정기 전환](/advanced/switching_state_estimators.md) - [트리 외부 모듈](/advanced/out_of_tree_modules.md) @@ -818,8 +842,12 @@ - [시험 MC_02 - 완전 자동](/test_cards/mc_02_full_autonomous.md) - [시험 MC_03 - 자동 / 수동 혼합](/test_cards/mc_03_auto_manual_mix.md) - [시험 MC_04 - 안전 장치 시험](/test_cards/mc_04_failsafe_testing.md) - - [시험 MC_05 - 실내 비행 (수동 모드)](/test_cards/mc_05_indoor_flight_manual_modes.md) + - [Test MC_05 - Manual Modes (Inside)](/test_cards/mc_05_indoor_flight_manual_modes.md) + - [Test MC_06 - Optical Flow (Inside)](/test_cards/mc_06_optical_flow.md) + - [Test MC_07 - VIO (Inside)](/test_cards/mc_07_vio.md) + - [Test MC_08 - DSHOT ESC](/test_cards/mc_08_dshot.md) - [단위 테스트](/test_and_ci/unit_tests.md) + - [Fuzz Tests](/test_and_ci/fuzz_tests.md) - [지속 통합](/test_and_ci/continous_integration.md) - [Integration Testing](/test_and_ci/integration_testing.md) - [MAVSDK 통합 테스트](/test_and_ci/integration_testing_mavsdk.md) @@ -862,8 +890,8 @@ - [출시](/releases/index.md) - [main (alpha)](/releases/main.md) - - [1.16 (release candidate)](/releases/1.16.md) - - [1.15 (stable)](/releases/1.15.md) + - [1.16 (stable)](/releases/1.16.md) + - [1.15](/releases/1.15.md) - [1.14](/releases/1.14.md) - [1.13](/releases/1.13.md) - [1.12](/releases/1.12.md) diff --git a/docs/uk/_sidebar.md b/docs/uk/_sidebar.md index cc14b8eb8a..e441417899 100644 --- a/docs/uk/_sidebar.md +++ b/docs/uk/_sidebar.md @@ -1,10 +1,8 @@ - [Введення](/index.md) - - [Основні поняття](/getting_started/px4_basic_concepts.md) - [Мультикоптери](/frames_multicopter/index.md) - - [Функції](/features_mc/index.md) - [Режим польоту](/flight_modes_mc/index.md) - [Position Mode (MC)](/flight_modes_mc/position.md) @@ -37,7 +35,7 @@ - [Static Pressure Buildup](/advanced_config/static_pressure_buildup.md) - [Flying (Basics)](/flying/basic_flying_mc.md) - [Complete Vehicles](/complete_vehicles_mc/index.md) - - [ModalAI Starling](/complete_vehicles_mc/modalai_starling.md) + - [ModalAI Starling (PX4 Dev Kit)](/complete_vehicles_mc/modalai_starling.md) - [PX4 Vision Kit](/complete_vehicles_mc/px4_vision_kit.md) - [MindRacer BNF & RTF](/complete_vehicles_mc/mindracer_BNF_RTF.md) - [MindRacer 210](/complete_vehicles_mc/mindracer210.md) @@ -58,7 +56,6 @@ - [DJI F450 (CUAV v5 nano)](/frames_multicopter/dji_f450_cuav_5nano.md) - [Літаки (з фіксованим крилом)](/frames_plane/index.md) - - [Збірка](/assembly/assembly_fw.md) - [Конфігурація/підлаштування](/config_fw/index.md) - [Auto-tune](/config/autotune_fw.md) @@ -86,7 +83,6 @@ - [Wing Wing Z84 (Pixracer)](/frames_plane/wing_wing_z84.md) - [VTOL (Вертикальний зліт та посадка)](/frames_vtol/index.md) - - [Assembly](/assembly/assembly_vtol.md) - [Конфігурація/Налаштування VTOL](/config_vtol/index.md) - [Auto-tune](/config/autotune_vtol.md) @@ -111,7 +107,6 @@ - [Complete Vehicles](/complete_vehicles_vtol/index.md) - [Operations](/config/operations.md) - - [Безпека](/config/safety_intro.md) - [Конфігурація безпеки (запобіжники)](/config/safety.md) - [Моделювання відмовостійкості](/config/safety_simulation.md) @@ -132,7 +127,6 @@ - [QGroundControl Flight-Readiness Status](/flying/pre_flight_checks.md) - [Вибір обладнання & Налаштування](/hardware/drone_parts.md) - - [Flight Controllers (Autopilots)](/flight_controller/index.md) - [Польотні контролери](/getting_started/flight_controller_selection.md) - [Серія Pixhawk](/flight_controller/pixhawk_series.md) @@ -169,13 +163,12 @@ - [ARK Electronics ARKV6X](/flight_controller/ark_v6x.md) - [ARK FPV Flight Controller](/flight_controller/ark_fpv.md) - [ARK Pi6X Flow Flight Controller](/flight_controller/ark_pi6x.md) - - [CUAV X7](/flight_controller/cuav_x7.md) - [CUAV Nora](/flight_controller/cuav_nora.md) - [CUAV V5+ (FMUv5)](/flight_controller/cuav_v5_plus.md) - [Wiring Quickstart](/assembly/quick_start_cuav_v5_plus.md) - [CUAV V5 nano (FMUv5)](/flight_controller/cuav_v5_nano.md) - [Швидке підключення CUAV V5 nano](/assembly/quick_start_cuav_v5_nano.md) - - [CUAV Pixhack v3 (FMUv3)](/flight_controller/pixhack_v3.md) + - [CUAV X25 EVO](/flight_controller/cuav_x25-evo.md) - [CubePilot Cube Orange+ (CubePilot)](/flight_controller/cubepilot_cube_orangeplus.md) - [CubePilot Cube Orange (CubePilot)](/flight_controller/cubepilot_cube_orange.md) - [CubePilot Cube Yellow (CubePilot)](/flight_controller/cubepilot_cube_yellow.md) @@ -188,11 +181,8 @@ - [Wiring Quickstart](/assembly/quick_start_durandal.md) - [Holybro Pix32 v5](/flight_controller/holybro_pix32_v5.md) - [Wiring Quickstart](/assembly/quick_start_holybro_pix32_v5.md) - - [ModalAI Flight Core v1](/flight_controller/modalai_fc_v1.md) - - [ModalAI VOXL Flight](/flight_controller/modalai_voxl_flight.md) - [ModalAI VOXL 2](/flight_controller/modalai_voxl_2.md) - - [mRobotics-X2.1 (FMUv2)](/flight_controller/mro_x2.1.md) - - [mRo Control Zero F7)](/flight_controller/mro_control_zero_f7.md) + - [mRo Control Zero F7](/flight_controller/mro_control_zero_f7.md) - [Sky-Drones AIRLink](/flight_controller/airlink.md) - [SPRacing SPRacingH7EXTREME](/flight_controller/spracingh7extreme.md) - [ThePeach FCC-K1](/flight_controller/thepeach_k1.md) @@ -206,18 +196,20 @@ - [Зняті з виробництва автопілоти/транспортні засоби](/flight_controller/autopilot_discontinued.md) - [Drotek Dropix (FMUv2)](/flight_controller/dropix.md) - [Omnibus F4 SD](/flight_controller/omnibus_f4_sd.md) - - [BetaFPV Beta75X 2S Brushless Whoop](/complete_vehicles_mc/betafpv_beta75x.md) - [Bitcraze Crazyflie 2.0 ](/complete_vehicles_mc/crazyflie2.md) - [Aerotenna OcPoC-Zynq Mini](/flight_controller/ocpoc_zynq.md) + - [CUAV X7](/flight_controller/cuav_x7.md) - [CUAV v5](/flight_controller/cuav_v5.md) + - [CUAV Pixhack v3 (FMUv3)](/flight_controller/pixhack_v3.md) - [Holybro Kakute F7](/flight_controller/kakutef7.md) - [Holybro Pixfalcon](/flight_controller/pixfalcon.md) - [Holybro pix32 (FMUv2)](/flight_controller/holybro_pix32.md) + - [ModalAI Flight Core v1](/flight_controller/modalai_fc_v1.md) + - [ModalAI VOXL Flight](/flight_controller/modalai_voxl_flight.md) + - [mRo X2.1 (FMUv2)](/flight_controller/mro_x2.1.md) - [mRo AUAV-X2](/flight_controller/auav_x2.md) - [NXP RDDRONE-FMUK66 FMU](/flight_controller/nxp_rddrone_fmuk66.md) - [3DR Pixhawk 1](/flight_controller/pixhawk.md) - - [Snapdragon Flight](/flight_controller/snapdragon_flight.md) - - [Intel® Aero RTF Drone](/complete_vehicles_mc/intel_aero.md) - [Pixhawk Autopilot Bus (PAB) & Carriers](/flight_controller/pixhawk_autopilot_bus.md) - [ARK Electronics Pixhawk Autopilot Bus Carrier](/flight_controller/ark_pab.md) - [Кріплення польотного контролера](/assembly/mount_and_orient_controller.md) @@ -229,7 +221,9 @@ - [Оновлення завантажувача](/advanced_config/bootloader_update.md) - [Оновлення бутлоадера FMUv6X-RT через USB](/advanced_config/bootloader_update_v6xrt.md) - [Bootloader прошивка на системи Betaflight](/advanced_config/bootloader_update_from_betaflight.md) + - [Airframe Selection](/config/airframe.md) + - [Сенсори](/sensor/index.md) - [Акселерометр](/sensor/accelerometer.md) - [Калібрування](/config/accelerometer.md) @@ -241,6 +235,7 @@ - [Compass Power Compensation](/advanced_config/compass_power_compensation.md) - [Датчики швидкості повітря](/sensor/airspeed.md) - [Калібрування](/config/airspeed.md) + - [Airspeed Validation](/advanced_config/airspeed_validation.md) - [ВЗІП Датчик польоту](/sensor/airspeed_tfslot.md) - [Барометри](/sensor/barometer.md) - [Датчики відстані \(далекодобива\)](/sensor/rangefinders.md) @@ -272,6 +267,7 @@ - [CUAV C-RTK](/gps_compass/rtk_gps_cuav_c-rtk.md) - [CUAV C-RTK2 PPK/RTK GNSS](/gps_compass/rtk_gps_cuav_c-rtk2.md) - [CUAV C-RTK 9Ps](/gps_compass/rtk_gps_cuav_c-rtk-9ps.md) + - [DATAGNSS NANO HRTK GNSS](/gps_compass/rtk_gps_datagnss_nano_hrtk.md) - [DATAGNSS GEM1305 RTK GNSS](/gps_compass/rtk_gps_gem1305.md) - [Femtones MINI2 Receiver](/gps_compass/rtk_gps_fem_mini2.md) - [Freefly RTK GPS](/gps_compass/rtk_gps_freefly.md) @@ -287,6 +283,7 @@ - [Trimble MB-Two](/gps_compass/rtk_gps_trimble_mb_two.md) - [CubePilot Here+ (Discontined)](/gps_compass/rtk_gps_hex_hereplus.md) - [INS (Інерціальна навігація/GNSS)](/sensor/inertial_navigation_systems.md) + - [InertialLabs](/sensor/inertiallabs.md) - [VectorNav](/sensor/vectornav.md) - [Optical Flow](/sensor/optical_flow.md) - [ARK Flow](/dronecan/ark_flow.md) @@ -297,6 +294,7 @@ - [Датчик тахометра ThunderFly TFRPM01](/sensor/thunderfly_tachometer.md) - [Заводське калібрування IMU](/advanced_config/imu_factory_calibration.md) - [Sensor Thermal Compensation](/advanced_config/sensor_thermal_calibration.md) + - [Актуатори](/actuators/index.md) - [Розподіл приводу](/config/actuators.md) - [Калібрування ESC (плати контролю двигунів)](/advanced_config/esc_calibration.md) @@ -308,19 +306,22 @@ - [Zubax Telega](/dronecan/zubax_telega.md) - [Прошивка PX4 Sapog ESC](/dronecan/sapog.md) - [Holybro Kotleta](/dronecan/holybro_kotleta.md) - - [Zubax Orel](/dronecan/zubax_orel.md) - [Vertiq](/peripherals/vertiq.md) - [VESC](/peripherals/vesc.md) + - [Радіокерування (RC)](/getting_started/rc_transmitter_receiver.md) - [Налаштування радіо](/config/radio.md) - [Режими польоту](/config/flight_mode.md) + - [Джойстики](/config/joystick.md) + - [Посилання даних](/data_links/index.md) - [MAVLink Telemetry (OSD/GCS)](/peripherals/mavlink_peripherals.md) - [Телеметричні радіостанції](/telemetry/index.md) - [SiK Radio](/telemetry/sik_radio.md) - [Телеметричне радіо RFD900 (SiK)](/telemetry/rfd900_telemetry.md) + - [ThunderFly TFSIK01 Telemetry Radio](/telemetry/tfsik_telemetry.md) - [HolyBro (SIK) Телеметричне радіо](/telemetry/holybro_sik_radio.md) - [Телеметрія Wi-Fi](/telemetry/telemetry_wifi.md) - [Модуль WiFi ESP8266](/telemetry/esp8266_wifi_module.md) @@ -338,6 +339,7 @@ - [TBS Crossfire (CRSF) телеметрія](/telemetry/crsf_telemetry.md) - [Супутниковий зв'язок (Iridium/RockBlock)](/advanced_features/satcom_roadblock.md) + - [Енергетичні системи](/power_systems/index.md) - [Налаштування оцінки батареї](/config/battery.md) - [Battery Chemistry Overview](/power_systems/battery_chemistry.md) @@ -356,6 +358,7 @@ - [Sky-Drones SmartAP PDB](/power_module/sky-drones_smartap-pdb.md) - [Акумулятори Smart/MAVLink](/smart_batteries/index.md) - [Rotoye Batmon Комплект інтелектуального акумулятора](/smart_batteries/rotoye_batmon.md) + - [Вантажі & камери](/payloads/index.md) - [Випадки використання](/payloads/use_cases.md) - [Місія доставки посилок](/flying/package_delivery_mission.md) @@ -367,19 +370,25 @@ - [Конфігурація Gimbal \(Mount\)](/advanced/gimbal_control.md) - [Grippers](/peripherals/gripper.md) - [Servo Gripper](/peripherals/gripper_servo.md) + - [Периферія](/peripherals/index.md) - [ADSB/FLARM/UTM (уникнення трафіку)](/peripherals/adsb_flarm.md) - [Парашут](/peripherals/parachute.md) - [Remote ID](/peripherals/remote_id.md) + - [Периферійні пристрої I2C](/sensor_bus/i2c_general.md) - [Прискорювачі шини I2C](/sensor_bus/i2c_general.md#i2c-bus-accelerators) - [TFI2CADT01 Транслятор адреси I2C](/sensor_bus/translator_tfi2cadt.md) + - [Периферійні пристрої CAN](/can/index.md) + - [Периферійні пристрої DroneCAN](/dronecan/index.md) - [Прошивка PX4 DroneCAN](/dronecan/px4_cannode_fw.md) - [ARK CANnode](/dronecan/ark_cannode.md) - [RaccoonLab CAN Nodes](/dronecan/raccoonlab_nodes.md) + - [Підключення дротів](/assembly/cable_wiring.md) + - [Комп’ютери-супутники](/companion_computer/index.md) - [Налаштування Pixhawk + Companion](/companion_computer/pixhawk_companion.md) - [RPi Pixhawk Companion](/companion_computer/pixhawk_rpi.md) @@ -395,16 +404,19 @@ - [Realsense T265 Tracking Camera (VIO)](/camera/camera_intel_realsense_t265_vio.md) - [Потокове відео](/companion_computer/video_streaming.md) - [Потокове відео за допомогою WFB-ng Wi-Fi (далекий діапазон)](/companion_computer/video_streaming_wfb_ng_wifi.md) + - [Serial Port Configuration](/peripherals/serial_configuration.md) + - [PX4 Ethernet Setup](/advanced_config/ethernet_setup.md) + - [Стандартна конфігурація](/config/index.md) + - [Розширені налаштування](/advanced_config/index.md) - [Using PX4's Navigation Filter (EKF2)](/advanced_config/tuning_the_ecl_ekf.md) - [Finding/Updating Parameters](/advanced_config/parameters.md) - [Full Parameter Reference](/advanced_config/parameter_reference.md) - [Інші транспортні засоби](/airframes/index.md) - - [Airships (experimental)](/frames_airship/index.md) - [Autogyros (experimental)](/frames_autogyro/index.md) - [ThunderFly Auto-G2 (Holybro pix32)](/frames_autogyro/thunderfly_auto_g2.md) @@ -412,17 +424,17 @@ - [Helicopter (experimental)](/frames_helicopter/index.md) - [Конфігурація/Підлаштування](/config_heli/index.md) - [Rovers (experimental)](/frames_rover/index.md) - - [Ackermann Rovers](/frames_rover/ackermann.md) - - [Drive Modes](/flight_modes_rover/ackermann.md) - - [Конфігурація/Підлаштування](/config_rover/ackermann.md) - - [Differential Rovers](/frames_rover/differential.md) - - [Drive Modes](/flight_modes_rover/differential.md) - - [Конфігурація/Підлаштування](/config_rover/differential.md) - - [Aion Robotics R1](/frames_rover/aion_r1.md) - - [Mecanum Rovers](/frames_rover/mecanum.md) - - [Drive Modes](/flight_modes_rover/mecanum.md) - - [Конфігурація/Підлаштування](/config_rover/mecanum.md) - - [(Deprecated) Rover Position Control](/frames_rover/rover_position_control.md) + - [Drive Modes](/flight_modes_rover/index.md) + - [Manual](/flight_modes_rover/manual.md) + - [Auto](/flight_modes_rover/auto.md) + - [Configuration/Tuning](/config_rover/index.md) + - [Basic Setup](/config_rover/basic_setup.md) + - [Rate Tuning](/config_rover/rate_tuning.md) + - [Attitude Tuning](/config_rover/attitude_tuning.md) + - [Velocity Tuning](/config_rover/velocity_tuning.md) + - [Position Tuning](/config_rover/position_tuning.md) + - [Complete Vehicles](/complete_vehicles_rover/index.md) + - [Aion Robotics R1](/complete_vehicles_rover/aion_r1.md) - [Submarines (experimental)](/frames_sub/index.md) - [BlueROV2](/frames_sub/bluerov2.md) - [Airframes Reference](/airframes/airframe_reference.md) @@ -534,6 +546,7 @@ - [Airspeed](/msg_docs/Airspeed.md) - [AirspeedWind](/msg_docs/AirspeedWind.md) - [AutotuneAttitudeControlStatus](/msg_docs/AutotuneAttitudeControlStatus.md) + - [BatteryInfo](/msg_docs/BatteryInfo.md) - [ButtonEvent](/msg_docs/ButtonEvent.md) - [CameraCapture](/msg_docs/CameraCapture.md) - [CameraStatus](/msg_docs/CameraStatus.md) @@ -552,6 +565,7 @@ - [DifferentialPressure](/msg_docs/DifferentialPressure.md) - [DistanceSensor](/msg_docs/DistanceSensor.md) - [DistanceSensorModeChangeRequest](/msg_docs/DistanceSensorModeChangeRequest.md) + - [DronecanNodeStatus](/msg_docs/DronecanNodeStatus.md) - [Ekf2Timestamps](/msg_docs/Ekf2Timestamps.md) - [EscReport](/msg_docs/EscReport.md) - [EscStatus](/msg_docs/EscStatus.md) @@ -626,6 +640,7 @@ - [MountOrientation](/msg_docs/MountOrientation.md) - [NavigatorMissionItem](/msg_docs/NavigatorMissionItem.md) - [NavigatorStatus](/msg_docs/NavigatorStatus.md) + - [NeuralControl](/msg_docs/NeuralControl.md) - [NormalizedUnsignedSetpoint](/msg_docs/NormalizedUnsignedSetpoint.md) - [ObstacleDistance](/msg_docs/ObstacleDistance.md) - [OffboardControlMode](/msg_docs/OffboardControlMode.md) @@ -724,7 +739,12 @@ - [Wind](/msg_docs/Wind.md) - [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md) - [AirspeedValidatedV0](/msg_docs/AirspeedValidatedV0.md) + - [ArmingCheckReplyV0](/msg_docs/ArmingCheckReplyV0.md) + - [BatteryStatusV0](/msg_docs/BatteryStatusV0.md) + - [EventV0](/msg_docs/EventV0.md) + - [HomePositionV0](/msg_docs/HomePositionV0.md) - [VehicleAttitudeSetpointV0](/msg_docs/VehicleAttitudeSetpointV0.md) + - [VehicleLocalPositionV0](/msg_docs/VehicleLocalPositionV0.md) - [VehicleStatusV0](/msg_docs/VehicleStatusV0.md) - [MAVLink Messaging](/mavlink/index.md) - [Adding Messages](/mavlink/adding_messages.md) @@ -734,6 +754,7 @@ - [Protocols/Microservices](/mavlink/protocols.md) - [Standard Modes Protocol](/mavlink/standard_modes.md) - [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](/middleware/uxrce_dds.md) + - [UORB Bridged to ROS 2](/middleware/dds_topics.md) - [Модулі & Команди](/modules/modules_main.md) - [Автоматичне підлаштування](/modules/modules_autotune.md) - [Команди](/modules/modules_command.md) @@ -763,7 +784,7 @@ - [Відлагодження з GDB](/debug/gdb_debugging.md) - [Порт для налагодження SWD](/debug/swd_debug.md) - [JLink адаптер](/debug/probe_jlink.md) - - [Black Magic / Dronecode адаптери](/debug/probe_bmp.md) + - [Black Magic/Zubax BugFace BF1 Probe](/debug/probe_bmp.md) - [STLink адаптер](/debug/probe_stlink.md) - [MCU-Link адаптер](/debug/probe_mculink.md) - [Відлагодження Hardfault ](/debug/gdb_hardfault.md) @@ -787,6 +808,9 @@ - [Інтеграція камери/Архітектура](/camera/camera_architecture.md) - [Комп'ютерний зір](/advanced/computer_vision.md) - [Захоплення руху (VICON, Optitrack, NOKOV)](/tutorials/motion-capture.md) + - [Neural Networks](/advanced/neural_networks.md) + - [Neural Network Module Utilities](/advanced/nn_module_utilities.md) + - [TensorFlow Lite Micro (TFLM)](/advanced/tflm.md) - [Встановлюється драйвер для Intel RealSense R200](/advanced/realsense_intel_driver.md) - [Перемикання оцінювачів стану](/advanced/switching_state_estimators.md) - [Out-of-Tree модулі](/advanced/out_of_tree_modules.md) @@ -818,8 +842,12 @@ - [Тест MC_02 - Повна автономність](/test_cards/mc_02_full_autonomous.md) - [Тест MC_03 - поєднання автоматичного і ручного керування](/test_cards/mc_03_auto_manual_mix.md) - [Тест MC_04 - Тестування відмовостійкості](/test_cards/mc_04_failsafe_testing.md) - - [Тест MC_05 - Політ у приміщенні (ручні режими)](/test_cards/mc_05_indoor_flight_manual_modes.md) + - [Test MC_05 - Manual Modes (Inside)](/test_cards/mc_05_indoor_flight_manual_modes.md) + - [Test MC_06 - Optical Flow (Inside)](/test_cards/mc_06_optical_flow.md) + - [Test MC_07 - VIO (Inside)](/test_cards/mc_07_vio.md) + - [Test MC_08 - DSHOT ESC](/test_cards/mc_08_dshot.md) - [Модульні Тести](/test_and_ci/unit_tests.md) + - [Fuzz Tests](/test_and_ci/fuzz_tests.md) - [Безперервна інтеграція](/test_and_ci/continous_integration.md) - [Integration Testing](/test_and_ci/integration_testing.md) - [MAVSDK Тестування інтеграції ](/test_and_ci/integration_testing_mavsdk.md) @@ -862,8 +890,8 @@ - [Релізи](/releases/index.md) - [main (alpha)](/releases/main.md) - - [1.16 (release candidate)](/releases/1.16.md) - - [1.15 (stable)](/releases/1.15.md) + - [1.16 (stable)](/releases/1.16.md) + - [1.15](/releases/1.15.md) - [1.14](/releases/1.14.md) - [1.13](/releases/1.13.md) - [1.12](/releases/1.12.md) diff --git a/docs/zh/_sidebar.md b/docs/zh/_sidebar.md index 6938152abc..d95b8103d5 100644 --- a/docs/zh/_sidebar.md +++ b/docs/zh/_sidebar.md @@ -1,10 +1,8 @@ - [Introduction](/index.md) - - [基本概念](/getting_started/px4_basic_concepts.md) - [多旋翼](/frames_multicopter/index.md) - - [Features](/features_mc/index.md) - [飞行模式](/flight_modes_mc/index.md) - [位置模式(多旋翼)](/flight_modes_mc/position.md) @@ -37,7 +35,7 @@ - [静态压力生成](/advanced_config/static_pressure_buildup.md) - [Flying (Basics)](/flying/basic_flying_mc.md) - [整机](/complete_vehicles_mc/index.md) - - [ModalAI Starling](/complete_vehicles_mc/modalai_starling.md) + - [ModalAI Starling (PX4 Dev Kit)](/complete_vehicles_mc/modalai_starling.md) - [PX4 视觉套件](/complete_vehicles_mc/px4_vision_kit.md) - [MindRacer BNF & RTF](/complete_vehicles_mc/mindracer_BNF_RTF.md) - [MindRacer 210](/complete_vehicles_mc/mindracer210.md) @@ -58,7 +56,6 @@ - [DJI F450 (CUAV v5 nano)](/frames_multicopter/dji_f450_cuav_5nano.md) - [Planes (Fixed-Wing)](/frames_plane/index.md) - - [Assembly](/assembly/assembly_fw.md) - [Config/Tuning](/config_fw/index.md) - [Auto-tune](/config/autotune_fw.md) @@ -86,7 +83,6 @@ - [Wing Wing Z84 (Pixracer)](/frames_plane/wing_wing_z84.md) - [垂直起降](/frames_vtol/index.md) - - [Assembly](/assembly/assembly_vtol.md) - [垂直起降配置/调试](/config_vtol/index.md) - [Auto-tune](/config/autotune_vtol.md) @@ -111,7 +107,6 @@ - [Complete Vehicles](/complete_vehicles_vtol/index.md) - [Operations](/config/operations.md) - - [安全性](/config/safety_intro.md) - [Safety Configuration (Failsafes)](/config/safety.md) - [Failsafe Simulation](/config/safety_simulation.md) @@ -132,7 +127,6 @@ - [QGroundControl Flight-Readiness Status](/flying/pre_flight_checks.md) - [Hardware Selection & Setup](/hardware/drone_parts.md) - - [飞行控制器(Autopilots)](/flight_controller/index.md) - [Flight Controller Selection](/getting_started/flight_controller_selection.md) - [Pixhawk Series](/flight_controller/pixhawk_series.md) @@ -169,13 +163,12 @@ - [ARK Electronics ARKV6X](/flight_controller/ark_v6x.md) - [ARK FPV Flight Controller](/flight_controller/ark_fpv.md) - [ARK Pi6X Flow Flight Controller](/flight_controller/ark_pi6x.md) - - [CUAV X7](/flight_controller/cuav_x7.md) - [CUAV Nora](/flight_controller/cuav_nora.md) - [CUAV V5+ (FMUv5)](/flight_controller/cuav_v5_plus.md) - [Wiring Quickstart](/assembly/quick_start_cuav_v5_plus.md) - [CUAV V5 nano (FMUv5)](/flight_controller/cuav_v5_nano.md) - [CUAV V5 nano Wiring Quickstart](/assembly/quick_start_cuav_v5_nano.md) - - [CUAV Pixhack v3 (FMUv3)](/flight_controller/pixhack_v3.md) + - [CUAV X25 EVO](/flight_controller/cuav_x25-evo.md) - [CubePilot Cube Orange+ (CubePilot)](/flight_controller/cubepilot_cube_orangeplus.md) - [CubePilot Cube Orange (CubePilot)](/flight_controller/cubepilot_cube_orange.md) - [CubePilot Cube Yellow (CubePilot)](/flight_controller/cubepilot_cube_yellow.md) @@ -188,11 +181,8 @@ - [Wiring Quickstart](/assembly/quick_start_durandal.md) - [Holybro Pix32 v5](/flight_controller/holybro_pix32_v5.md) - [Wiring Quickstart](/assembly/quick_start_holybro_pix32_v5.md) - - [ModalAI Flight Core v1](/flight_controller/modalai_fc_v1.md) - - [ModalAI VOXL Flight](/flight_controller/modalai_voxl_flight.md) - [ModalAI VOXL 2](/flight_controller/modalai_voxl_2.md) - - [mRobotics-X2.1 (FMUv2)](/flight_controller/mro_x2.1.md) - - [mRo Control Zero F7)](/flight_controller/mro_control_zero_f7.md) + - [mRo Control Zero F7](/flight_controller/mro_control_zero_f7.md) - [Sky-Drones AIRLink](/flight_controller/airlink.md) - [SPRacing SPRacingH7EXTREME](/flight_controller/spracingh7extreme.md) - [ThePeach FCC-K1](/flight_controller/thepeach_k1.md) @@ -206,18 +196,20 @@ - [Discontinued Autopilots/Vehicles](/flight_controller/autopilot_discontinued.md) - [Drotek Dropix (FMUv2)](/flight_controller/dropix.md) - [Omnibus F4 SD](/flight_controller/omnibus_f4_sd.md) - - [BetaFPV Beta75X 2S Brushless Whoop](/complete_vehicles_mc/betafpv_beta75x.md) - [Bitcraze Crazyflie 2.0 ](/complete_vehicles_mc/crazyflie2.md) - [Aerotenna OcPoC-Zynq Mini](/flight_controller/ocpoc_zynq.md) + - [CUAV X7](/flight_controller/cuav_x7.md) - [CUAV v5](/flight_controller/cuav_v5.md) + - [CUAV Pixhack v3 (FMUv3)](/flight_controller/pixhack_v3.md) - [Holybro Kakute F7](/flight_controller/kakutef7.md) - [Holybro Pixfalcon](/flight_controller/pixfalcon.md) - [Holybro pix32 (FMUv2)](/flight_controller/holybro_pix32.md) + - [ModalAI Flight Core v1](/flight_controller/modalai_fc_v1.md) + - [ModalAI VOXL Flight](/flight_controller/modalai_voxl_flight.md) + - [mRo X2.1 (FMUv2)](/flight_controller/mro_x2.1.md) - [mRo AUAV-X2](/flight_controller/auav_x2.md) - [NXP RDDRONE-FMUK66 FMU](/flight_controller/nxp_rddrone_fmuk66.md) - [3DR Pixhawk 1](/flight_controller/pixhawk.md) - - [Snapdragon Flight](/flight_controller/snapdragon_flight.md) - - [Intel® Aero RTF Drone](/complete_vehicles_mc/intel_aero.md) - [Pixhawk Autopilot Bus (PAB) & Carriers](/flight_controller/pixhawk_autopilot_bus.md) - [ARK Electronics Pixhawk Autopilot Bus Carrier](/flight_controller/ark_pab.md) - [Mounting the Flight Controller](/assembly/mount_and_orient_controller.md) @@ -229,7 +221,9 @@ - [Bootloader Update](/advanced_config/bootloader_update.md) - [Bootloader Update FMUv6X-RT via USB](/advanced_config/bootloader_update_v6xrt.md) - [Bootloader Flashing onto Betaflight Systems](/advanced_config/bootloader_update_from_betaflight.md) + - [Airframe Selection](/config/airframe.md) + - [传感器](/sensor/index.md) - [加速度计](/sensor/accelerometer.md) - [Calibration](/config/accelerometer.md) @@ -241,6 +235,7 @@ - [指南针动力补偿](/advanced_config/compass_power_compensation.md) - [空速传感器](/sensor/airspeed.md) - [Calibration](/config/airspeed.md) + - [Airspeed Validation](/advanced_config/airspeed_validation.md) - [TFSlot Airspeed Sensor](/sensor/airspeed_tfslot.md) - [Barometers](/sensor/barometer.md) - [距离传感器 \(测距仪\)](/sensor/rangefinders.md) @@ -272,6 +267,7 @@ - [CUAV C-RTK](/gps_compass/rtk_gps_cuav_c-rtk.md) - [CUAV C-RTK2 PPK/RTK GNSS](/gps_compass/rtk_gps_cuav_c-rtk2.md) - [CUAV C-RTK 9Ps](/gps_compass/rtk_gps_cuav_c-rtk-9ps.md) + - [DATAGNSS NANO HRTK GNSS](/gps_compass/rtk_gps_datagnss_nano_hrtk.md) - [DATAGNSS GEM1305 RTK GNSS](/gps_compass/rtk_gps_gem1305.md) - [Femtones MINI2 Receiver](/gps_compass/rtk_gps_fem_mini2.md) - [Freefly RTK GPS](/gps_compass/rtk_gps_freefly.md) @@ -287,6 +283,7 @@ - [Trimble MB-Two](/gps_compass/rtk_gps_trimble_mb_two.md) - [CubePilot Here+ (Discontined)](/gps_compass/rtk_gps_hex_hereplus.md) - [INS (Inertial Navigation/GNSS)](/sensor/inertial_navigation_systems.md) + - [InertialLabs](/sensor/inertiallabs.md) - [VectorNav](/sensor/vectornav.md) - [光流](/sensor/optical_flow.md) - [ARK 光流](/dronecan/ark_flow.md) @@ -297,6 +294,7 @@ - [ThunderFly TFRPM01 转速传感器](/sensor/thunderfly_tachometer.md) - [IMU Factory Calibration](/advanced_config/imu_factory_calibration.md) - [传感器热补偿](/advanced_config/sensor_thermal_calibration.md) + - [执行器](/actuators/index.md) - [ADSB/FLARM (空中防撞)](/config/actuators.md) - [电调(ESC)校准](/advanced_config/esc_calibration.md) @@ -308,19 +306,22 @@ - [Zubax Telega](/dronecan/zubax_telega.md) - [PX4 Sapog ESC Firmware](/dronecan/sapog.md) - [Holybro Kotleta](/dronecan/holybro_kotleta.md) - - [Zubax Orel](/dronecan/zubax_orel.md) - [Vertiq](/peripherals/vertiq.md) - [VESC](/peripherals/vesc.md) + - [Radio Control (RC)](/getting_started/rc_transmitter_receiver.md) - [无线电系统设置](/config/radio.md) - [飞行模式](/config/flight_mode.md) + - [Joysticks](/config/joystick.md) + - [Data Links](/data_links/index.md) - [MAVLink 回传(OSD/GCS)](/peripherals/mavlink_peripherals.md) - [数传电台](/telemetry/index.md) - [SiK 电台](/telemetry/sik_radio.md) - [RFD900 (SiK) 数传电台](/telemetry/rfd900_telemetry.md) + - [ThunderFly TFSIK01 Telemetry Radio](/telemetry/tfsik_telemetry.md) - [HolyBro (SIK) 数传电台](/telemetry/holybro_sik_radio.md) - [WiFi 数传](/telemetry/telemetry_wifi.md) - [ESP8266 WiFi 模块](/telemetry/esp8266_wifi_module.md) @@ -338,6 +339,7 @@ - [TBS Crossfire (CRSF) Telemetry](/telemetry/crsf_telemetry.md) - [Satellite Comms (Iridium/RockBlock)](/advanced_features/satcom_roadblock.md) + - [Power Systems](/power_systems/index.md) - [Battery Estimation Tuning](/config/battery.md) - [Battery Chemistry Overview](/power_systems/battery_chemistry.md) @@ -356,6 +358,7 @@ - [Sky-Drones SmartAP PDB](/power_module/sky-drones_smartap-pdb.md) - [Smart/MAVLink Batteries](/smart_batteries/index.md) - [Rotoye Batmon 电池智能套装](/smart_batteries/rotoye_batmon.md) + - [载荷 & 相机](/payloads/index.md) - [Use Cases](/payloads/use_cases.md) - [Package Delivery Mission](/flying/package_delivery_mission.md) @@ -367,19 +370,25 @@ - [Gimbal \(Mount\) Configuration](/advanced/gimbal_control.md) - [Grippers](/peripherals/gripper.md) - [Servo Gripper](/peripherals/gripper_servo.md) + - [Peripherals](/peripherals/index.md) - [ADSB/FLARM/UTM (Traffic Avoidance)](/peripherals/adsb_flarm.md) - [降落伞](/peripherals/parachute.md) - [Remote ID](/peripherals/remote_id.md) + - [I2C Peripherals](/sensor_bus/i2c_general.md) - [I2C bus accelerators](/sensor_bus/i2c_general.md#i2c-bus-accelerators) - [TFI2CADT01 I2C address translator](/sensor_bus/translator_tfi2cadt.md) + - [CAN Peripherals](/can/index.md) + - [DroneCAN Peripherals](/dronecan/index.md) - [PX4 DroneCAN Firmware](/dronecan/px4_cannode_fw.md) - [ARK CANnode](/dronecan/ark_cannode.md) - [RaccoonLab CAN Nodes](/dronecan/raccoonlab_nodes.md) + - [Cable Wiring](/assembly/cable_wiring.md) + - [机载电脑](/companion_computer/index.md) - [Pixhawk + Companion Setup](/companion_computer/pixhawk_companion.md) - [RPi Pixhawk Companion](/companion_computer/pixhawk_rpi.md) @@ -395,16 +404,19 @@ - [Realsense T265 跟踪相机 (VIO)](/camera/camera_intel_realsense_t265_vio.md) - [视频流](/companion_computer/video_streaming.md) - [Video Streaming using WFB-ng Wifi (Long range)](/companion_computer/video_streaming_wfb_ng_wifi.md) + - [串口配置](/peripherals/serial_configuration.md) + - [PX4 Ethernet Setup](/advanced_config/ethernet_setup.md) + - [Standard Configuration](/config/index.md) + - [高级配置](/advanced_config/index.md) - [Using PX4's Navigation Filter (EKF2)](/advanced_config/tuning_the_ecl_ekf.md) - [查找/更新参数](/advanced_config/parameters.md) - [Full Parameter Reference](/advanced_config/parameter_reference.md) - [Other Vehicles](/airframes/index.md) - - [Airships (experimental)](/frames_airship/index.md) - [Autogyros (experimental)](/frames_autogyro/index.md) - [ThunderFly Auto-G2 (Holybro pix32)](/frames_autogyro/thunderfly_auto_g2.md) @@ -412,17 +424,17 @@ - [Helicopter (experimental)](/frames_helicopter/index.md) - [Helicopter Config/Tuning](/config_heli/index.md) - [Rovers (experimental)](/frames_rover/index.md) - - [Ackermann Rovers](/frames_rover/ackermann.md) - - [Drive Modes](/flight_modes_rover/ackermann.md) - - [Configuration/Tuning](/config_rover/ackermann.md) - - [Differential Rovers](/frames_rover/differential.md) - - [Drive Modes](/flight_modes_rover/differential.md) - - [Configuration/Tuning](/config_rover/differential.md) - - [Aion Robotics R1](/frames_rover/aion_r1.md) - - [Mecanum Rovers](/frames_rover/mecanum.md) - - [Drive Modes](/flight_modes_rover/mecanum.md) - - [Configuration/Tuning](/config_rover/mecanum.md) - - [(Deprecated) Rover Position Control](/frames_rover/rover_position_control.md) + - [Drive Modes](/flight_modes_rover/index.md) + - [Manual](/flight_modes_rover/manual.md) + - [Auto](/flight_modes_rover/auto.md) + - [Configuration/Tuning](/config_rover/index.md) + - [Basic Setup](/config_rover/basic_setup.md) + - [Rate Tuning](/config_rover/rate_tuning.md) + - [Attitude Tuning](/config_rover/attitude_tuning.md) + - [Velocity Tuning](/config_rover/velocity_tuning.md) + - [Position Tuning](/config_rover/position_tuning.md) + - [Complete Vehicles](/complete_vehicles_rover/index.md) + - [Aion Robotics R1](/complete_vehicles_rover/aion_r1.md) - [Submarines (experimental)](/frames_sub/index.md) - [BlueROV2](/frames_sub/bluerov2.md) - [机架参考](/airframes/airframe_reference.md) @@ -534,6 +546,7 @@ - [Airspeed](/msg_docs/Airspeed.md) - [AirspeedWind](/msg_docs/AirspeedWind.md) - [AutotuneAttitudeControlStatus](/msg_docs/AutotuneAttitudeControlStatus.md) + - [BatteryInfo](/msg_docs/BatteryInfo.md) - [ButtonEvent](/msg_docs/ButtonEvent.md) - [CameraCapture](/msg_docs/CameraCapture.md) - [CameraStatus](/msg_docs/CameraStatus.md) @@ -552,6 +565,7 @@ - [DifferentialPressure](/msg_docs/DifferentialPressure.md) - [DistanceSensor](/msg_docs/DistanceSensor.md) - [DistanceSensorModeChangeRequest](/msg_docs/DistanceSensorModeChangeRequest.md) + - [DronecanNodeStatus](/msg_docs/DronecanNodeStatus.md) - [Ekf2Timestamps](/msg_docs/Ekf2Timestamps.md) - [EscReport](/msg_docs/EscReport.md) - [EscStatus](/msg_docs/EscStatus.md) @@ -626,6 +640,7 @@ - [MountOrientation](/msg_docs/MountOrientation.md) - [NavigatorMissionItem](/msg_docs/NavigatorMissionItem.md) - [NavigatorStatus](/msg_docs/NavigatorStatus.md) + - [NeuralControl](/msg_docs/NeuralControl.md) - [NormalizedUnsignedSetpoint](/msg_docs/NormalizedUnsignedSetpoint.md) - [ObstacleDistance](/msg_docs/ObstacleDistance.md) - [OffboardControlMode](/msg_docs/OffboardControlMode.md) @@ -724,7 +739,12 @@ - [Wind](/msg_docs/Wind.md) - [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md) - [AirspeedValidatedV0](/msg_docs/AirspeedValidatedV0.md) + - [ArmingCheckReplyV0](/msg_docs/ArmingCheckReplyV0.md) + - [BatteryStatusV0](/msg_docs/BatteryStatusV0.md) + - [EventV0](/msg_docs/EventV0.md) + - [HomePositionV0](/msg_docs/HomePositionV0.md) - [VehicleAttitudeSetpointV0](/msg_docs/VehicleAttitudeSetpointV0.md) + - [VehicleLocalPositionV0](/msg_docs/VehicleLocalPositionV0.md) - [VehicleStatusV0](/msg_docs/VehicleStatusV0.md) - [MAVLink Messaging](/mavlink/index.md) - [Adding Messages](/mavlink/adding_messages.md) @@ -734,6 +754,7 @@ - [Protocols/Microservices](/mavlink/protocols.md) - [Standard Modes Protocol](/mavlink/standard_modes.md) - [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](/middleware/uxrce_dds.md) + - [UORB Bridged to ROS 2](/middleware/dds_topics.md) - [模块 & 命令](/modules/modules_main.md) - [自动调参](/modules/modules_autotune.md) - [命令](/modules/modules_command.md) @@ -763,7 +784,7 @@ - [Debugging with GDB](/debug/gdb_debugging.md) - [SWD Debug Port](/debug/swd_debug.md) - [JLink Probe](/debug/probe_jlink.md) - - [Black Magic/DroneCode Probe](/debug/probe_bmp.md) + - [Black Magic/Zubax BugFace BF1 Probe](/debug/probe_bmp.md) - [STLink Probe](/debug/probe_stlink.md) - [MCU-Link Probe](/debug/probe_mculink.md) - [Hardfault Debugging](/debug/gdb_hardfault.md) @@ -787,6 +808,9 @@ - [Camera Integration/Architecture](/camera/camera_architecture.md) - [机器视觉](/advanced/computer_vision.md) - [Motion Capture (VICON, Optitrack, NOKOV)](/tutorials/motion-capture.md) + - [Neural Networks](/advanced/neural_networks.md) + - [Neural Network Module Utilities](/advanced/nn_module_utilities.md) + - [TensorFlow Lite Micro (TFLM)](/advanced/tflm.md) - [安装英特尔 RealSense R200 的驱动程序](/advanced/realsense_intel_driver.md) - [切换状态估计器](/advanced/switching_state_estimators.md) - [外部模块](/advanced/out_of_tree_modules.md) @@ -818,8 +842,12 @@ - [测试 MC_02-完全自主](/test_cards/mc_02_full_autonomous.md) - [测试 MC_03 - 自动手动混合](/test_cards/mc_03_auto_manual_mix.md) - [测试 MC_04 -故障安全测试](/test_cards/mc_04_failsafe_testing.md) - - [测试 MC_05-室内飞行(手动模式)](/test_cards/mc_05_indoor_flight_manual_modes.md) + - [Test MC_05 - Manual Modes (Inside)](/test_cards/mc_05_indoor_flight_manual_modes.md) + - [Test MC_06 - Optical Flow (Inside)](/test_cards/mc_06_optical_flow.md) + - [Test MC_07 - VIO (Inside)](/test_cards/mc_07_vio.md) + - [Test MC_08 - DSHOT ESC](/test_cards/mc_08_dshot.md) - [单元测试](/test_and_ci/unit_tests.md) + - [Fuzz Tests](/test_and_ci/fuzz_tests.md) - [持续集成](/test_and_ci/continous_integration.md) - [Integration Testing](/test_and_ci/integration_testing.md) - [MAVSDK集成测试](/test_and_ci/integration_testing_mavsdk.md) @@ -862,8 +890,8 @@ - [版本发布](/releases/index.md) - [main (alpha)](/releases/main.md) - - [1.16 (release candidate)](/releases/1.16.md) - - [1.15 (stable)](/releases/1.15.md) + - [1.16 (stable)](/releases/1.16.md) + - [1.15](/releases/1.15.md) - [1.14](/releases/1.14.md) - [1.13](/releases/1.13.md) - [1.12](/releases/1.12.md) From 05394162cecf876460e26b5550263c645ea0b84c Mon Sep 17 00:00:00 2001 From: SolderSyntax <133851002+SolderSyntax@users.noreply.github.com> Date: Thu, 11 Sep 2025 10:55:02 +0300 Subject: [PATCH 024/812] Update dev_env_windows_wsl.md (#25441) * Update dev_env_windows_wsl.md Add info about enabling broadcasting or streaming to work with PX4 SITL on WSL and QGC on Windows. * Update dev_env_windows_wsl.md Fix links * Update dev_env_windows_wsl.md moved troubleshooting section at the bottom of WSL2<>Windows section. * Move under troubleshooting --------- Co-authored-by: Hamish Willee --- docs/en/dev_setup/dev_env_windows_wsl.md | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/docs/en/dev_setup/dev_env_windows_wsl.md b/docs/en/dev_setup/dev_env_windows_wsl.md index a2efeed2e2..92e0de4cbd 100644 --- a/docs/en/dev_setup/dev_env_windows_wsl.md +++ b/docs/en/dev_setup/dev_env_windows_wsl.md @@ -33,7 +33,7 @@ _QGroundControl for Windows_ is additionally required if you need to: Note that you can also use it to monitor a simulation, but you must manually [connect to the simulation running in WSL](#qgroundcontrol-on-windows). ::: info -Connecting to an USB device from within WSL is not natively supported, however it can still be achieved by using the [USBIPD-WIN](https://learn.microsoft.com/en-us/windows/wsl/connect-usb) project. With this you can automatically upload firmware from the command line in WSL using the [`upload`](../dev_setup/building_px4.md#uploading-firmware-flashing-the-board) function. +Connecting to an USB device from within WSL is not natively supported, however it can still be achieved by using the [USBIPD-WIN](https://learn.microsoft.com/en-us/windows/wsl/connect-usb) project. With this you can automatically upload firmware from the command line in WSL using the [`upload`](../dev_setup/building_px4.md#uploading-firmware-flashing-the-board) function. ::: ::: info @@ -325,3 +325,9 @@ sudo add-apt-repository ppa:kisak/kisak-mesa sudo apt update sudo apt upgrade ``` + +### QGroundControl not connecting to PX4 SITL + +- The connection between PX4 SITL on WSL2 and QGroundControl on Windows requires [broadcasting](../simulation/index.md#enable-udp-broadcasting) or [streaming to a specific address](../simulation/index.md#enable-streaming-to-specific-address) to be enabled. + Streaming to a specific address should be enabled by default, but is something to check if a connection can't be established. +- Network traffic might be blocked by firewall or antivirus on you system. From b2672910da53db265f6430523ca1b5bb96329308 Mon Sep 17 00:00:00 2001 From: Samuel Toledano Date: Thu, 11 Sep 2025 10:37:41 +0200 Subject: [PATCH 025/812] sbgecom: Implement sbgECom INS driver (#24137) * Add new INS driver sbgECom Implement sbgECom messages handling to provide IMU sensors, GNSS and EKF data to the autopilot Be able to parametrize the serial port, baudrate and the communicating mode Clone sbgECom library only if sbgecom support is enabled and apply a patch Be able to send SBG Systems INS settings in several ways when starting sbgecom driver * Fix sensor airspeed simulator units * Fix HIGHRES_IMU pressure unit * Allow HIGHRES_IMU to support 4 IMUs * sbgECom: Add documentation * Use submodule instead of fetching sbgECom using CMake * Remove patch strategy * Fix dates * Remove patch file * Update SBG dev type ID Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> --------- Co-authored-by: Samuel Toledano Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> --- .gitmodules | 3 + .../ellipse-inertial-navigation-system.png | Bin 0 -> 46104 bytes docs/en/SUMMARY.md | 1 + docs/en/releases/main.md | 2 +- docs/en/sensor/inertial_navigation_systems.md | 1 + docs/en/sensor/sbgecom.md | 150 +++ src/drivers/drv_sensor.h | 2 + src/drivers/ins/Kconfig | 3 +- src/drivers/ins/sbgecom/CMakeLists.txt | 73 ++ src/drivers/ins/sbgecom/Kconfig | 5 + src/drivers/ins/sbgecom/module.yaml | 50 + src/drivers/ins/sbgecom/sbgECom | 1 + src/drivers/ins/sbgecom/sbgecom.cpp | 1125 +++++++++++++++++ src/drivers/ins/sbgecom/sbgecom.hpp | 294 +++++ src/modules/mavlink/streams/HIGHRES_IMU.hpp | 6 +- .../sensor_airspeed_sim/SensorAirspeedSim.cpp | 2 +- .../sensor_airspeed_sim/SensorAirspeedSim.hpp | 1 + 17 files changed, 1713 insertions(+), 6 deletions(-) create mode 100644 docs/assets/hardware/sensors/inertial/ellipse-inertial-navigation-system.png create mode 100644 docs/en/sensor/sbgecom.md create mode 100644 src/drivers/ins/sbgecom/CMakeLists.txt create mode 100644 src/drivers/ins/sbgecom/Kconfig create mode 100644 src/drivers/ins/sbgecom/module.yaml create mode 160000 src/drivers/ins/sbgecom/sbgECom create mode 100644 src/drivers/ins/sbgecom/sbgecom.cpp create mode 100644 src/drivers/ins/sbgecom/sbgecom.hpp diff --git a/.gitmodules b/.gitmodules index a4c12ecebd..4061b65c11 100644 --- a/.gitmodules +++ b/.gitmodules @@ -100,3 +100,6 @@ [submodule "src/drivers/ins/microstrain/mip_sdk"] path = src/drivers/ins/microstrain/mip_sdk url = https://github.com/PX4/LORD-MicroStrain_mip_sdk.git +[submodule "src/drivers/ins/sbgecom/sbgECom"] + path = src/drivers/ins/sbgecom/sbgECom + url = https://github.com/PX4/sbgECom.git diff --git a/docs/assets/hardware/sensors/inertial/ellipse-inertial-navigation-system.png b/docs/assets/hardware/sensors/inertial/ellipse-inertial-navigation-system.png new file mode 100644 index 0000000000000000000000000000000000000000..617f2e676cc8e35d0f7ef046b8a8eff6e215e5d5 GIT binary patch literal 46104 zcmZ^}Q*bU$^ep;)v2EM7ZQHhO+fH_DXUDc}+sTe??d+WTo%-K%?|HaWwW_9i&Fb#z zhpBm(Xe9+nco-ZQ0000lEhVM`000jF0H8h;C;$MsHc)^A003Z?!t%lZKw~28Ut@3p z004AVkrV;c&EZ`D0KiCVH7z$Sc{v_aM|%ciGe;A11}}Rjz<-NR(96l#)YjaM$i&>z z+JT?)uDhR-$l8pbQj=YtN#04++{#+Y$HiRLM?uZh$JUhFj8ael9){10$IITy-rUWY z$jjc&!Ij60pX7fN^EkNj{0B3V2=KX>S@5WcN&L?V7c&cf5-T@1Cmu#dPft$?2RCCcdIwk1{~-`FcQtjfc5<_JbRhbV(AdP$-Ho5b z-QC)Z$HLfx-Nej{o!-Ql)r_8*+02;U*o>8#-i(#ijFX+2i^YQ3gyetZ-K;JCUwsGH z|B1oW(Vp?Y4kI%I(|?x#+w&;8SerYz8UH6Kz|8l*`~Mfl$M~O-|Btc%K~%&f1o#;L zPcr|-^ncPdcQE6p^rRFNpi9ey1pol#ZsJ;QX2x#jJob)e))w9X7A6)ZdS+&N7Irlj z79J)x9yT^wCMF&xrmXMf=l^TK)WzJ`&HVp=;JnaQ3IG5=J4tD~0st7~{}oVLh3p;x z00k(?sfkNE$sMh3ck~PeWR_l@U*A7GU0>gw9-STU9zEPY?T^f67glapx344@)U*#Z zDHuk?q%B(d6_mGhH+6J(^tl8^N@*K+_YV*GM1_RMh{&mJhNfG(_-z(7P;d$wnc8ox z9=Q2LcPHllscN;=HL5ak)Fh@X6jd}JqnYMc$`MtV6;@kSGA|O4TT`_fVihhFS78;C zRl_G)mNh69Q(Y3%1OWmW1;pmWwZdrFas_0z^jy72XaXsiyy-Za*hLkUG-WaImK99L z#5DYwc!Fry{YdG9S@=B&C?;j}_Kdx^H0{fTy&y4c0`ErX-!IBHk~Ibh&rWR)j) z@NvniP_l9NiK#a;@TzGVu4~vP({oKLnuvYj;UIvunWo)ke0CsA7O# z6TSWWcX@HUY~qzJC^ILcpG(Q=PQ@Yz18-qr*Tf^MZ)RV~Dc&!wQzoMcg@oqB#Epc3 zT`i`1zI%cR1r^RF5Jo_*frgDw&oWEN?->v^iOnFXYgS24%Zo=iW9ZhWV3bQno=iY? zvb=LVzO=|HO@ocQ-#gK-X5oa2qiXGL42L|XZP!b|waTZ~jz<@lob4Z*-pWBQ#K623 zn4FSRe(IYBPfGo;QIIdI)gq>HHyf}~+NA3lrpznwc~SLwJ7gA?vK*JQmQnukxM!xW z9TgQ*iio?_&~r0nHn+JsYwiDb7Smc=UriE~6n}njC-zC+3V}APDji$~= z*&M4~g|C~YCAk^LIrX_=AvsO`%Qca`*`Z^d?d=1#y|Jb_?p9s)GNoD^GuqU$CIhAb z0D!_xML`wd8Ssw{hFnq~D=90xrtDwm&Y})i&iLOkm%YW|k)yqq!@r(2dnjoed;kCu zKw3;#&1>sAXWn*O2V>l@(BEE0W};51%P)4JNE;3`xSdIjwgMkg6z5)s0_xTmZv9k; z>wH(z)G;hdY}%+sJI=_+E3JAB#M*1!%M=c^Ck1o9FrKq0M0jD>?i4Z8^$&)HV5$5R zf7>6z&5PkT-@Y@gk5gRr-)dDVWir2L)PMgg=<@eo}y}G4$ zXYOM;-0SLYd}%mcGa5j4qT3G|{QPrmE=MbiYbA-=Nx2 zBqz%N?`lbFI%o>)sm=X_INm*q!Zhn%b383_^Ck(W0|TVTscxw&_={d`)Au=Y&Lm#4 z&&qk_8-=k-n1e9DM-5hz7qynVT;@b+;+WTbuJ|^~Aq{o@$z{4#O^D-8ReL16;7qOM zz0BS%{WZql=E(W4f@S^*i<1lOBupnwM;b%|o*!FQq&%Q7_w)3C{?+~oRTp(dH@i70 z4HqK3Z`wPm^c#g4c&*~1!>h5Kh^ySr*)&eM;EGFS%o>@R0WFzMLaD=IZ5~FgoKx8%htNk7_@?%PlU=45mnp65;|AZ->;{+$N{cH!7Cp1iFCh} zo0kb2XncBoH|9W4Ai3y`)SX8(C(ff7D?oxk?RErKQI16Q1&wwfFEXQRtawvZFTd+! z#>cBq+wSMZ5kY&zbucd{SE4|9+d~*Hf$xbHzoXE->mgYcK8vM_>A(-5e%)u%V?FKI zKk|37`Bha9+@pUSVOt;5>+{Nww2Kyv)70U#NhDd%OM5V@!8OB0BUgSkxdG+?Q|_STv_T1j}ZEux+tcbB;nmD3Y&dZFRY1 zRLObEB`kVVm{s&cbY^3r+G4HjXatm&V3F@YOW1RA879n?ILk8Oh>{|NymofeIdQ`$ z$kFE;t$LO-lL9ov6@ z?~Y;cxo>~;;J;Ng)g#vi<)SNgdGBz0rj|IsR;qx`;D}wBcDz#i0V>jaq-69XdpUnJ z6uz~uUL{_;Be-+2S%vt*hamg#__2! z2^dR-NJFQ^2{PwGRo6SK)b?%UwDY=FzrP@YVIy10eFbNAfS zTa9g_AjuLt`@vkfzmzt3!u+wJHvBP#BPM&zNe9mCC2nI)tIq(o2Xm+KpCN5rjStB+In#ebqg*WaPS z2O7dmM}hl^vRx>x)Bc(|0FkIDP6F^``Beb)*!L(Qh1|Q=7$~f^n}Jm~2d^-mcya)R zVQtwAV_{p0k%{y{z8kt_K7Fwgu5L6^yyC4vz5yJ&d*{%I0TM^BTa@X%ae~Ac{G3TlwEXeB>;Kj|q zz=at?UmF&blQqo$HMvRmra>82glft?H2A|0(sQu<-U|HAoD9JY(}Y(+*J*;o=)^5! z5gl;#cj*ih%X_1wuEc6zQQo@_|K~9w>aPThB!Igd_Q8kJj9@I5c6%vUwez?ayMk|Hbu~Bn0rzdoLq*I2vC9olrV9|d zaJe2M*WYn-n(Gj6zS!{>gjwoI!p{4%5Gwi6@k_$macMTzpx6-3Cluw<=)T8*FepZN zsPOPJG6KZU{l&_$jfaoV%j5n!k#W!OeY{@qFL*J=?@aG2Zz$0g(kbGL5+i1%{*7(S zkpW(d!>j{;ZALcvF`$sbmw#<{*qW|h!q=_$w!Cjr=@ieZW@ZY9EZLVgaPLviUC4xh9m?)S7_gYex>HIM{{}R}q zj&!G)mni~yHb=a0TZDL3{|Htd;{#@tb^khOA3EEKFm~N#<=&%SeZT)(y({?pB_Qza zX*1GvNh{A~p}Ltj;5YuyO{8Fvs_XceGW1s+{6pvU_`xI-F+O+4ub!Dlj0Z3xk1#T| zAv-zUl-Evk<=gc~sJkbt#77HMfFT?b)fP)>HBSUx67%~@&iaq}8Jxkk#4^*|Ub?ZT z@9xtONlgt$hz*f?1$tc3O7mD1F?%L~nNDyM7C9A#aFer{mKt;05svYf(y|bhaP-X) z+BQ7h;6X~NzmrfTds=w#!qqd1RfI>n|GuKb8RLSyq50@-S(0JFng5>V{#mitCOi-l zs$;M8<+TXxI~lE7j`w78-+=<=%5xvoL?{+?I_ByqS4E;d;s@L|Io9QBCQnZ1B=#BR zc1TrU9C$WX0{$59sklO2Y8S+vE4YlP&mkq z@@qX3F`htv0J%p*6iTS!<&oRrDNUmmzDU-|s5q#NOvRK;2YzGZjg2jIK4c&{B?WOO zlyJ!i3hXG&*D*}zoXlz59h?e(FLvF|ol)tblIbxo2O7qVBA5-}`gR_5BHPn2RyBb< z=%n2H37XNn=t+}rH!0v8B`+b3rf7jQWTqGWWpIltYuA!P$3H%7yZ8HRi~@q-@ZE}& zsH&D*V%5tdTjS@udgb8Y!ModBcKFo&t-H6nlR~$y%C9JJ)ymU58UD2&`-q08oiG84 z=}RWHMx@8r0m36d9EsP`IWY@_g2~}J&UnGo?R=C>Lj6=^af|LhI9%$ z{G0J%-zJt-M-dwwvQGgzzhW5%|X3?Os(P3x&&&&eMpa-x0`nUdxSNy9w_lD8Cu$1sBE6(EiV zFDh0pq*=*}fZQ00!VnUahoXGfF_|zDR9O>{ykx&5PUnA)J@Tz~@gLZJ z*Kp2Hsyts`^7XFKE0Q8p^*E^A<_T|yfoqZD76ID{o6Jt6!samlT&)OqyuWJ>Y{|M{ z+|%Q14;Kw5ng9R$6l-xs7a7=;zVCp z?TL5pxMsX*?5tT>qNwUOSkor%`)0f)V$sO75U0Zh^P!+A^^0}=ffi-fmRrr6d2Iqt zndg|M!_xCu4Ja-aO^T=L%-qxE@#oX)S~#eu)X0cyXwKp$+9>w!Bv4P*wPJ8P{_@TD z*~{``aO>}w6;*~fm>JOcRicA73Y+JMkB?23I|57J6=kghaP{CCnFj7s0P)Jt0l;?b z{E8!|V{T=8xCH>HJo~ zPm~+v;!SBaHI5fBr2 z*=&v0bQ2yPo*tFuk{6lJSlAjf!bKY0$pnXT%kib%R`Z}uzL118-b%lS&8*2wz&_=J zs8c)DAqwyhPvQT@n$T#^(^2A0Xy74PjO(Ftm4t{606`p<(PF8yW5yf7T#3xz0RzYn z)+;z!%2f4rXBu>?b*px+0!?h1I=)ouYMAY^)gL`M8Ty#T7zi9F5+Jd+B%0h<%@Ytc zYK;tJL_Et$xyt=?nQp0~LxknT2M23}TWA1^uqv*LDDUiI?*_a4;+x&$&3x-yEnlLA z7`hyb9z)tv$&wfdDOv`VSwuM{r#=7rkrtIIvJ|(IgEl-t?$p6%Rk<4&-05f@*=953 zq1o_|io^15Bj7Sye2{eY2tYrk(L2A*+spClW-}rimp_3f#{6jQE%mF_a?j6=7veWW zlN4rY4UM;Q*rzR0SD)YavmA#3xwFHs;5nE4lf*IvxS=4z=R@dPOv2JI{l=6PsXQn|pD7|`CDJUM5gId*nliz1v(|zum=(w~$LZ|s zBsrngu)8_pYZhs{)%i zh6`|r2nyBTCo)2!6FtR)`wjDcRO~;%aaud%;7d{FdYW&OFYmKEF>Te;FEAJHLH1V$ z1Ah6JmC&j?9BAZR$U`d}=q{XDHIIU7---c7ymv76UKla0)&QAKGBIS9Sy9+W{paYf z6YOj^`Rr^CMqOROwz=-TLE*=4fxCDOS(%bj>G*cB{*d5tj0y22^eN03#)I%FSw;{H zz^PW8$N4;f2Mq7e=dNlXhWx@9caYG|2WMYby=l(e<#;pvn_Y$Kt(|?FPwF_W=fN2_`*FU7#^Jw8uEE`iPZU^g|%>I z;p|WdB8SFPKk7U67PY24`0P^F-MiUhz$>>N4`10 z<>_QPpwULqRC(v?3CXE2D2FZzb{6Fhj!l}6*$RK~aqu{tMV?TSHFtdcE&xshU3%{eSXcQ(4(-!wN@iPO4Mjy5W>cM*mLa{DPnEjE6GFxtSvp;7Kfxr>VbVmy{dX+CIA2uDdK(fcDybR0XkrFgEm zPAJ&tyWV;Gb|<(cST~2jxw6AoYh{@si5)nP9))#;o@JX`-c;#bz?4K0j}^Ze!zKyl zga`S{lmiTp?trq;h=eA)$r*h@kabmDIqNqS0i7|Qa}FP?ftxTuM2*j zf4*GZ?R`90DiH(|3O$Hk#0e1Mv!_d8fwaJ6S1-drQ}URBb8gJVbK%>RZ2_s9X3bcz z;P6HD^J@9|p)zBzE)OP$-B|JzC{?u!^(xImC?Sst27G;x3376Nv<>pJvb6J|Xa9aB z-bw>xZO)L1s#jHjse=NKPPy!jRQe!V0(MqJMzDVi@-7!U_1K9Ms0d+J+TTQ&*rmh!X_MGQyf(J}F+Ns`?jOVUL; z{F8qYxrnjnp+1bPp4#r(?z}m>E@sQ*y$nHkxwxFLTMyQxH*3h*nc5oZby(Dec+)St zh<7Nkol1bTFNis7^qM*C?QQMtui`&bewvuXa1a+5NE|q+7cQ+TMy88aB!q!JG$W{l zm zm*Dj4*j4u!pa4*Z17;q8vQ*&uz% zqY1seum>fK!W_HMC>#m$Z8|hTnCD|$399);A8DjJlOS4`*tt#U4RWQ`b9^>+xg<&0c5pk zEx&!HZ6^i(L9Vv|l28vGE))dF5Ig`+*27+4lE8r_E@$xtVS$>?Vv?P^oE*C)CBeF@h-L+@5g$X;UqVcD)q0Ja;?%o z<=*Kf3?}~tKU=;uG}~vn2R-ZN>x=b%%b#8U3&Hlul(g2qI$Z`B2l*nQoyPdcZ$eA? zz%_25^`zf3^v=w1-0wXj(0|u!(fFCFQr(uX3Y8GpSbRm}(jnqQZg$;})LC|0{$9Qg7E+ zVE6zuEZ59Vy)h?><&bgEE|x86WP1v?mm#Z`eBinIl>*mM6ePQ6xfkVcyzcum8VfD& z>(JN2&+gu1fP3jutC2G4Ml}i1>4o$m0feXIbX-Qd$?KwvtyV7<&JUA*vCQLUf}>Tbj}IubICP>uWL7$w1%H8W^<{M;5tv8~K9m|JiDlf?*`vVbF%K7d7Wd zMuIU9Mg-R`#Wm6Lbsl&@;IN~yy^YCpfi;IOa-h< zoiRhk>}41~h}h!Hz9B@gWy|hHz6)vBLfdY4w0ER;B>eGSXc?C%iMA?ALJJ|JL}p|J z=r#DcpSAbTH(Ws?`9E~w<)xV+WAc~(rTM!=CL1jJB6C3&&1GeykYX7e8$bu@Kz4x0 zo^3okD^;fkgPD^k?rg#RO9uZe!0LCSq@IXWK(^dtQR1ND6VaZW9#WWJ`6FL}(Kx~w z_7hjvxi5+_1TH?CeR-lXPMmejs*2~L4}Z)CHMw>|-gx~q9uDMt?V+)f6PLL6fsm0BMY+u$`W(ctTH$fA*Mb)K_osZQ z%67*$gmJ|zNmLOrwbTNVOq=BZLdTU5>RniiugmuW3hg?HUK1(u8#UD^@*mbtx`SLUZF7LiWff2 zCAH>Y3K`J#akHFxO4DAtx{7q^*Aykd@$X^8t7WK3?AH#dp`uYv(eT>(B0)7v)X$=lR+S$2e z?o7(`o5rNol`$Awb2fvp>n&gnIFy#?KD{DU=|E15`&ICtsg_fVDm6L_+s)$MyIU|M z1GXA0yEYJ9@u9^gB)Ep2k|)Uo8@_K(!{uS}>MY>X$9;%0;O`_q*-R3dY)mgru`!9^ zwJQ~IuT7CBq)}1n`Z1=@-)PbQ?j*v}Yg*djY^S<3e{GsRwC(Ns!}Gk!mJLVUS|>?K zNjzLwu#eQbBH|o-`{&N_%LlDmg7)zn4pO6ta;y=QGGjbt>PB9aVIstXX7OdW9_ z{6DW^kEVv42kUda!4&P|mHy)zzKa6PwTsUuBPNY#$fNhO;;DoEz+|t0R{M$>VGs1< z->J5)uB|dBzwKw^BT{b#2t!3Z<=z~-E>?L;IKCHjA_jupNI|kf!|NNb1bic<9c(ng`saWhYZ@BUKmU`FmWoTmB!EAi9x7!f^ ziWqEIGi9qIyu}mn#L`b^(U1;*tZrpT6u#!@M!pjT_$k5+i49IQuf*t8N<3E+L8pt{ zkp&5l`W)5#Oz(Y+v;FrD^m(Fu!u;zRh?F{OR_rN|n}wIdC3>fo8*Z7ak~mH??RpYi zNXwqmZ44_}^hBM1g?}NsJ-x<+HLInI0j-bg7sFwkqrieR4SjxC}H=lU-^c~Pl)hi&Y+IuAkG&qP-o{ zTAK^NqyGDIIO5oo{D-zf5c&4pYAA=N?wd~)X*|t1$@#rGHN8X+qwJ6?ULf|%rp40h zJSy)6x>kASZ3IpsETp+?*U^B3m?T8D%x*51!OuBfLb) z^{UMgymVu3FHFWJo@=L``kOWeq_%ZzYhBv#Es}h)BFo~s{RdUQ3KcDjb zYqhHy)~(^mbEWHDiA@2LhltbD<0Hj#EEh^-F~x;`RD58OZEUtw*PP1O*e{;G7#98c z@t*DN^5e(;u&TS7-35tuBJGVF%8;@rj1&{vOJn6KB=WWA8DnIy!;B36zfZRmu|Wro z7O0`(bSA;xpQx+lx;V&xisi~;vJQ|#Ie$&ewAID2?t9X=3 z9qSr98U$E;d;`ltpLN-Y1UzVlx%S?iiP%``CD+&I6A}^==jP-++dV_WzA#Dd1kPZk zHRzqsud^dO6hy;lv)oLwgP$9yuHBQCqKGK^gK4+9>ORsIv7uthFd6iyKA$m0+q$F<*Vd`99Ayq`CC-AdprU~9Cc^^X z;))g@S(LyMKRLg@T2$skhq#;`ghlw+U*rQT`XhnpiUj}9UjW|rhIc!wtz%$nfM)scEHx4!1YEq5lS%x=J)d!@b?_(WgK6Z_8V%4T{Q1A@2 zhv%dW^z5`WrPtyhmhsuLc}h)L=Bt+hi&YjMa)B77B@Ep(P%v;1W9hOCCy4YWh|cLcQqnG@4Oax zJ~yK#>*bOmhAs(=ZRp(Z#tlthIo?{|RaFMRhn$r;0VKgHL6 z%~xXo(H32C=T*>8pOnBRi8+7A_G{{ zeZCbh8FaGg3<~bf8%-q@f_+$*0E~HuMDdivuZx=%u%e;Fe7WB21VsXwji+aG=Z1lwmg?TpHRYQs) z{j$87cJ5ntHZm9h*2&w_Xn+dJ?|$^PMWD)ragl+=19|Mvxo#6XO~dM?mQ;!R{gOuV ztW$79p1oelpjRl}M_yfQCt-^6rmjn62Uh-trjF(p;)g|*DjWo;!e0&`qaOxcfN^>{Ih+?*VS2%5`%3opEm0TQGUA>at29%9FXWurRTY!fGEcO%#BVyZ}nD0W^( zwTu_?q8zj0>_)dXW}l8;JybT<42&olf#>Id+`+qNR#$1kr97Ny%?Jw|8TXm>>FKG2 zcmVd_4kf*V7n=UFykukm+vrc{xs=TDd*dqX32UmQY-W--;nt1*8#~d(?QA3g@Zh(Pr8w*i>X3<)kLlQO}js;@q zU>zxLH=w^iwHEYF0=r$jt-kDZ+$XCu)@nUW5jB8{b`CUEVIMMyv8~NPU;LCPb^4bJ zgc_eP5hB3YeUKRv-daiC*k9IL7#8U@Phi4YC>r~-{`8c9FS7vtMf|InxTmw^M}z9w zYGj!YAHVL^#|UczAOE8@8u}2-=vqBF3ql3iQYy$k?a#spjuS5=WP8OkBXG~ge1!~Z zSiCCCB>M1&|6o?y{0{jcTk0()ll6dJIW5TKa8!mny$(U}k5Sv`T5uHcz6f@6Z?6Z` zm@WCf4x_4jun%ppU0E2{o6>D$)=n| z+QYXE?MgRw$5}31R@Ecg1o{*L6uFd$HxF;L?cYuwQVvNYMXS5mZxt_7Y0dxCnI@LEa}FERK6?R~nc7-%1!h+7 zaPaZ)@d2A`7YkTaCC#ym;~B+y3C-;22l}(=%LQdxM)rUOy)UaD8SEFbw)x4hDEJh&JUy z{Tx!wS98f1r8;0U)+|=kAoXs%rAl_q(dIDu%*6d7sw0b z*`la*;JXR|%GZA8hDr1a{L?1e3-^G`*Wk)YFt-62c? zX*t#LkX339R4?c8QX)Z&&^h10A_NkeP%WZqg>$0qE5mWeH3E?eR^Eliquy7tX0ETV zOJ>xJoSg$qVD67BaZgz{XG%UEA@^s^75!H+}$E6)B(FLX`%rCO~p7%ex zug!toOBops@w=@h4V9Hnks}V8-FlaKx-t38upI!cTDk7`WoTJPwvheH&MY?;GlXzH z+2odSl$bC+3r@Ob%1Q2E8p_eF8K{zcVx6xD35kevPN*$`3Eg^^_eS8#G>vN=2jOp! zw_iX*HbZT2>&#ylGRc`cScFNmB{2o-BbfPZrm9PnR2_-HIcAQa7(wpk6rz!mYOmeW zXzEyV8*})JBgy%u*sRufk`}3~&P5Z!)28oAqa`M9r{w_Q`Z7ATlQyU#o(vz|?f@Y`rxQWYXitBC(KGrR-`?zj~|pMq}Gut_AxVADaQWKC)dH z{R)L~0@gZ{WUhK+Wd2@9r}ZZTo5i_h22hl`s$?uBHjn5AC{|HFtO<0&Uc!n)vYHe2 z6$gk9ivl`Eg<8GD3Y+bi*u%R4K_bnCN|c!A2fl-)oj)J)ZL&}xuRf@lhy@?V=#_Kc zeJJa5#qQW^;Mf|L9r#1Kl9HC9o}B2G=5FnMhg*MCCXO4$Fp4R*hvLZ5UbTk&*kJk} zWE2J^8)c6gSX~Nzq=%!h)%cD=D^Ez33H`{26XSJhp&3D^+2Gue8?;6!7ACaEUC^1( zQzIUtUGL-K)bu#C9{JE6x0+OAXU}lAVPIikU_Cn&aFG}|=un^m9DpN61j7}toTdlg zhiK>pr&nnU5`siapQ9Qg6A1P03W3x>UG^ahkbKgMpvg9H-v5#SX zVzi^jtjJMf!G1;~3$0RKw+GLDze@^^{i?^-UD1cIPhe`359+v@;e9MgRi!!{_iT<; zJXL+LgIPE-4-a;Ko%}HACw#~Fie+5FgKft}XahO$GYliO?An4^j98m!t@yDc%&{?= zY9`!nBN#=iq-o^QtzAQ~l_L+URwzN6)vQ+oim)!kiwyyrx$U6Ab{d1WkB?sjB3Z40 zq!7FarS|0(krAYbYg~DF#A7+CtV?_>M?|MWeR=(#D3OFoq?cHGW4Yj($sXGKvdB0* z26`s?bT%!fgRPxJiVLm}|nqgKjRMo@h*=i`p`F@d$o<^|Ok#pG7?NmTamm z`YTm2qYVPOwajwbVe3|Z0QG6hv>%lQ?(&o4M4I3x7;k1mfQ zcXb^aJCFL36wB5oE96cuLw#8L!oB?>QP#d6I>i*K!9ZfAK2A~%MN-rd?Fn3(?;9Bha%@Lfxh6WzyHr7v6}L$mmd4e?5BM76kqQ)Tv^XkqkeJ0R{t1=w?4EyR(KO? zmBxzA@8B6`c#tP+;hK_|?S<>WzR39i4YPJ|z>Yrbl-QRxOR=SD)dDjG z-W3^U1|F`>_SYcXrm5*Tr!3(xX380PqminhHjd{tM~adqL>$%gunm>yW@MQb_cx^Ss1(OuZ4ipyXu1XvD6NMdf>uwQfOPd z5U%n1m9yvaonV2*))Yc8d$84%kJ;vZYQMTpr1$H^7LDn3V0RaNXbky2JSVMW(Usrw zxMT@sU`o6sDYIT)@sWZY6XfRKbon34F$}xqd?|iM(36m~t3?m)Ke1zR+_rW#n}=>q z@lg8@gn$1?4k}LncB;=kH)7(HFG2YqGY?5A;zVfOC5AI8hzB+1>2Uz;J-^k}z;SnHqilp1g588x4@1Vm| zC!MJN%8v^OkE{S;VPzUc*=snr<&DPV;5Q&vUC3#VNYb;VIw#}nYks{# zzC%9eJ|#5wwip|Z5;`+51^mr@;+yxjwD@=NH-29~(1lh)v*dcP`VvmOHqA zr(id0>hBrqejFR>S!7}T*j)SLVy`FhB(ts933kEZS{HaRV@QlR4pG~KJ^?{`Jc_K> z^QhkT7so+eOM8D+@W|F4J&${ujuWLd;}e??Kv%9r3{DVmqwYxuk@9)c-&Wp61vPko zY$>QvG`4`v3?GK)@hIsrg!vIm8Xhd6pOJy4t)aepr#XPGB-2c`N*@sd5gMk1QW9<< z7Vi^Fnv=VG-!gZUP;w}F`0%htF?En;`Q!AWSYnMd^XqwP880Er;7`z4Nx=Y4?>|M# zJTlsNOBTHAEa9LBFuX8^0bdFq>c1JC$)^)g=ePvCt3%z~9xmQQ$wIn+06|4UkpLsP zd~s!=AfU-M+Hl5r0TkgN4FY_pgg1R4X&=*B<3{VSSJkw#20G8D`?I z>)^I)uqw(bYVym^J|)UWbaJWL4JpsFHbYWgxIP%NT8cLi$HukjqI017m z(qjgdbG6zfZ{1)dj4T;3ZX|;v%~UFVgXgeHzD`t8EV0p%MRkUbbB)P(00t$m`QW^Y?QVFE-bCeC*v$cD3_31UeGNheRKUZ$`?(?nL{fQo^ZT6eUVE# z{BAf{{Rbg~XAjvR6`Iy{BC1a7&U`Y02n`27M<)&P#xVV&A`0oIE}xF7VN7(qgf3p& z%>vE}jMgIYyQnJ}>$>OEwRsT?*nHU07Spw_V#;p6TS=x1R) zfBJw3Zf$USnnN<#b-c%{S&Za7LkOkasRgc8{zANd?*vgm1%U=&2`i8x?OR{>9ig#k z{W&KH9!o6mcuNz@py;omS@o+;5RIJGsfD1}thcJuPlQO{WV9|bTAcOp z>tH?ykRq9`msYTYCJuMMcmm(w!RKOI!7QQn6O~D|Ji_G6j+6ho)N~!%jxxcG0V9^osXjS zzh7>abyL@@Sm%DK(=_G_4|syF^X)`HA0#RX*VoqWefhtC(BgbH={+8f+%(rlr^8}X zO&~!IGDq)W0>>b6T`;)fVPF?VY2t6Nh^Bd~KRu*Z-Q6vHRKv%r z`+E|3uDW+|%5-BwimTHqv{k`yna0@uJl}Uc^Lw2lYjyiNBHllw!tN;%ja14aQC>%| zlen&|uiwm?-2{i*wL=*4!|$1^>nx!(F=&COst?{BD2PfR54t-G0_<3f*jrjB|FmMU zUc@*w(Z zepoEcIMZ0;pSAI*yDaR!h%`2*qRi-o!*Sv{#14V_uT>o9l{B8vJ5R@WjLM>e80~V z9eO?>JoVVeVGwoU>NYe5jqeORz(5d?=1*KUjX5cmwHD)b>MdbF5ppucYEO{8r<$Ew z5}iCBl2@bRyPPczG=IBmKhlkaZpV<>s^hSjvg0uNsmH^}tAZObbQwNN20ekw(07P%*s|+3gS%ohu)A~q-V6rvsyT8i zV@=@MVX{D8zMjkkCEGj6@h*cN(LhO=psc>1wGoZI3|_y>Q?vz*cHA9TkIp-)X)Ir? zNM7W7*;xhfLtgnHAeW=`YDE9@|7&a2C-2P8!ouv)<}UkT;AwbXxCpQl_2`b)bxNCt z<;dC0WZ2+3j*jeMYT$_O)gn`rW5=;WbjCJ7ROo&cs+#aE`yPZc3=4pBXH2+ELgyQ~EYcr2Z`8#yB|-M|qMHf0R3V*ubu8sCJ91ekx1 zd7dbFVm?XCfTk+PD5*`do~GElc<=;IImER(S&}z=V(ee+q|0{ov=?|jilYNO)wc`Gut*H1@7Epr0t!P9AkS&f9Rl`;cngSi|-*usjlc|kA@ z(90HF96)@!oe%ut;;fNf8ikr5{>_>@l_COTvNbt63J^mVj(+my`A=TWeL>B4oT~H9 zqiuacN1nP49L{_v&pQFUq&WEfix+3gA%T#@vdkF>Lk}h~Z8NGf@4LTXvblLmGT}8m zHi@?l23>Vk3%cF#1rQZ%#E~7`(W68L<9v*^l41KDHq;fEB)Z|<_nYclq>^5HfZz=n z^*KcQ>6V!_5(rnOq6LDOqA3a9*|L2a97r?E0X6w!Odp?Awnk@z~1x_1t8R7)&gl{I>V?tFON} zWba6L>{Od&?nrKaD{xRYIWJ%7>f$?#&S_6Nmpc2+igrOOhRpfX?j89#*E3P7m^uMtzJ1d%>BOa_nk6sb}lUJ z2c_j`Na(}!ynoO4o$e^d0LUh#rno?|AprY$SRA}vJYY<+>Sew(?b!`1ZmO1(ErhtK zy8V;MrE4b;)p&dXR!z;)($e@hi?1Ki&IT5~GfnR|R`_p#-#9z2JZ?pZS&hM)x5a{L z-Sr3YIeSV?1i9NsrVNl?!9y$1US%cXYs+qUpLPp!#)bdcJoJ?SO3i>6lRou|unzpN z#w;s1RXRp)M$mva)&%ypG{|iZgtuWj6f(Xl5#T+FS}ffiTc04$IxpF)0I;H`PS)fi zx?3+v`lL#xbAdow6eDg)ZLgCyv0x8JtX5jq+17(mg_4t^{rz&|Lq!6ykD$x4jKJVx zSzg5(w54Vbz~b?D22BWY)87Wh$5)qDR|la;M&+(-4?zX10R zcU(Eyn#-A1P)!4YfL3vS^hEsX-IPvn2{LV|OcVAF2?;i04QnOHsUUtC1X@C|yjDxw zTWx}mY$p}8u0-Newl!hVVs3>8xPdGi@y@A6V@r#%g{&_crV-xjpZ-)DzM)7{=O?KlQEm< zzDq7*T`cf&i>pnRY>d#t#g&WjV$@ZSM=(;}LI|e#P9uRqokJ_elWSE!mIUxeULDdG zXCnk-w9`?yGXYplieGu2TPvG2Cble-Q0sRql&YXT9M0$AZ#t4pVjdl_*I^cIYYh@Y zR+rq1CyCT z;Yp$J_W930KY#nSP$*;`z4-3(3|clooy)f8Q6vEO_Bwkz?#w=e{Mj6fMMQBby`eO@ zuEcv=Q#v2c8EA3^*czl@f4~-DHk!?5OCs3{L0BL*030{bidZ1u!uLaM@Glpj@^uk- zN9!TG0_rwkl7-n7k!V8S*|oK`!#|aDCfgoUik9wlIb=hf3Gh{$JR|_ihB}g2$&2`J zWN#hLd%0*dC+71uTX?;$6~`n5)@(2b*~65WPNp%7hHH@+{9XEP2QoHW>|MF0;^SQ`CSkN|mW8uj9v&gdzb8H=eG*?#AdKjg7$V|4M z;VhBX$wLCIl_9%wk#j{rn~ivHYhy!8aZTSt`W^s$=c;}z3ELY{K@%; z4u`%--{O`9jKoT%yt!LLe6jN8GHQY*&rlCbF>4?aux6J{cFY)T;aWEd!ujY%P~!4% zX){VQD`c<0^31!7!2NK$J-FRv<1)nUW2YyVGMU2L)1MrK2z+i}AX8Y)kQ3`}oa_9} zw!MiT0KmNj;9lqLQ%9%!Q@Z8m*wcV578akedh@iu=el06L9F=7XJj4|-ssPVtzm&N z3p^S96CV%ZFW_qi-fCT#N0V-~3jubyEcFChL>I$v0|~&>AyntkY!$!@3@!=aT}B5K z?i1&iqtQg@PJE%lc}cJHP|GuB(6vR=v+RyF$@V#gvbe)cL6=ffr^vzYV+&X#Nsl*| z^hjBRIi?8K=IxRcv`3OE4bYb@N;8eSvPR=I1OICK7VlkU)PmVQGc*3r)y&N&2L~}O zpBo=o1%O}vdvT_7yle+vhz}kBzPFuD1Q?%>AAg+6op(RY2B2UNlZ?81*dL!y=~V#M z#U%XVfN{cS6Yt9NLKg)V12ADM!CMw;(&!o`!I#{YzJ*9MMqoL=x_577rQweVF91CE zaVY@r_8&9p)DsXGK_M+I_v3wyw=c=QShd`RR?3|$lZ>wk9dyf4i6hP|93#NhTHL&# zP(WG{6UDGXT8?_42o_aANhN|hC%LE;h2YBpz*L$ITL{Ail22PauXf@o+eKWq?We~E zzg{iBS?E0Y_jUmIoAFGc@%i^J$IktJM}{?!=wXm(XYW-8Ln$A>+7rAsiZhv7|F&!!<5vjj%Q&`j}!a63e2hzP7aEQa7aDr<8K#Tc?H z1lNdnx^4)CR$3tXk~_~Mz@-!cyZZb`ztT}%R+O)w!t2m_5rWG|O>_ zxzD?IXQsgqe>*VQbb4{-*5qoYt1CkeAzbb18p-VY;bn=9t6!1mVWjU>__+P&YuC

FzcJ(>5^;=@x*P@C4F#T}WTq&I4cD zXa@-a-VUFLtmfb!GmBLJ6er{yC!1RaGCC@-FRatf^V(FjG^Gnv1HsFW&3v z8<}(KQKmgarE$g}H=ku|6&KXmrl!(C4Yy2N(h6Ctl?q86OPd&|h!os;>{p5bv@UF_ zcz#Qq4V1mb{F$MQW;yNr{7zk=z~aHhN1gu|U(IAHD$2>qG%db<{b;BAd-edppv+f$ z0p5y*g+mL64xvXV{$*=!LS=AiF^XCQwR+^?&}1~lJnj)9>05|)cvD1_H5p@16F z`Ut|jkM=yU`O${9jZx$;Jjjjdja%g}Ipe%#9;myY$n)G<)mpYBfX^H%ACV!}sdF(~ znBnX1`}?}~ZdFU3Vz-h!fUO#78S>>oKByLBZt8_r$WtMB%}G)nnf@x5r6l$*t+q5H zv2xwZyhGqEfbkW}9&;YpyK~#`hh<|gFAt8N>#W99y6|LX5!cv`&8C=S0ldAZu9cr@ zgoXF`@z>z#KOLT2PFd;F5*AxL`o}%~BmH_chFK;kJQZz`ZbLHMs^zt2pFkcY0?Woc zNUi8D=6a*7&WLY4L3g?(gwc1nYHjW?)<;z+(fg~?rMycY)zp-i9~!CY`J&&U%VV$6 zmfr{(@Aw;UeoJ)wX@L|O3R#y%{cXJQxY?m&1hdw#VoAfhn%+RA zrj0JGmS?F@6MO+)3ptwJNU4jb0ucs>5MELnVeo|v`Y;lBt!ge^k{V_FC}Sf_HD_l{ zxx8qzis^j7w6SvM%+g;m+rnO@n&4aeALh<3Ce1X9<8CvXnRJ_J?W}A(Uph#4V z2rNY+Wk3Ous0v*jqIkA zG+eMWO^wb4WiR~5lI_Kw^E~g1olCM@%o9q{izfEx|D69h&v~Ag2YJHhkTASa=mLRzL}^wwS7!zAnVwm4Y0v2F z-oe2h6u|JYCkqO`Q&CZ&OGf5{^Aj=8d$C~9I-&PYdu3*`d8KbK8dceB01XNqx4iO( z!mIeJN`=)?{=a_kIsCSKO7z2WIoss`{kr9D8xD|Zq)c68BE_$Xt$ycLTS;v+P87UF za`4vpc1FeIJ_U@3m9;#r-{El#I5v(%0qK;!vF!^LL98b2=Rip1RNr43@D0w)aCs1c zHwObH1+2?r2J222?L1d9b#FQz6KBPK1>ZJs1@ca%*{Bp}3GmyqvwviVhhAT|-6pZ9>R*b4{etyV8+*eq5Umq+?R#qz5LD0$r`O{M5tq1XJqQ#%a8 zwXGU(%u-G_iBG$ks9(Hxlk2dayJdS7x2j(nI%$7ZK zih-tKb`Fblol6K`>a4glEF0eFZsc>z^J}L7uTrT1z*#w$vEGA#>3I}#TR=lr6x>!g zDLX#2h93prvwM8L#e@C!a8N&8Y&J?H3Sr-J-xr%vryTSPGS-;n{Vi>PSfwq2Zy31O zKf96MLL~diXvz#Wwsj?CM2tHOQlJas{R(R%49VcG_`sRNfm959hcX0wQBMS1++N(? zE^927v|5gUqr>j=JrNX0S7^=+FB9KACFY+`ZqS-`mSPe&)omloXL=T#1u3$SzbM$5`zV4W2P zZEg)$)3cShnyRrfJlPm4X)IntLDR@iY(|9Tsj~^z( zjmF;s+$y0?A`wcKr@nV?IzO}-uy+9}ZfYr9S-I1zEg+4oa=P1uXG}@9GNB}v5 zj~GdGCM#=z->PFnGyskf1^*=rE;=u{8+p_n49E83AmG$ND(+d_pEq8qy3(u@3WX9e zAXX?5v9=QUVW8I7S}HqMraMJiHJgGFa=DxUM!ZED6I~i9ZvN8b`_5Sx zbd!gcT3)pFkJbWSwbA@}ixVt0H@!~?d|CZUrD+pQd(S9eDasd0UNBc6VLl;@3p{kD zfPbYYF1k@~4O*do4+3UjY#dYJ)*(5wqE)%4^b_Vks8s5vFPqc>i{EZvs+_s6^4LB8 zj|3$1GG#ECnk1ixxx_lNMek|mHROkgdIenYRv4Wb#A3+7_s(YrFc9vpBO#jPVAtIX zIavUFydIv2Ii5F^-F`J2jK!b&50l5KMB;anHr*r&7?wf-;TnFHF=uqMsmLaOu)XB- zeY+YMQ?9i2J5|Hzu^GHj|KcSvQWBi&!C7Hz(qx(&nX6x0y~E+;afpKX6fhRTfH#l7 zRhpL};4=ugxKSUzc6$OVcs*6ISF+%A(rYNyO`=Navel|!YNnciYSHdF+BsU>2!$+k zQ#CHX;?0}9t4j|1fM@N- zPJck7^fnJVMO-(@&TcuLpK2xjD+tbrmf2aDn_F9z7IHWhd3h{gER)7dsfZy)^D_l( z&CT`7T(c*xvb#ZS(CG1u9w3(K7U-#9ax7`McG;?*yn!lKt3xwR$H2hS{XoeZjSaS! zh4VOE!k6gQ;7;q;z$RY-c&l{s6*B=E6}*rwz)%gJxo{EIuP>a*&aDUMbnAzQkzJQ7 zwm0h<{kW`bHg$X{kxE=jyf#)D%@B-?M$oWCCxn+!r=02-jBaX+w(UFHcKgo8&6(CI z?^OS0Wh)_U!%Nys8ci$2=T;N5w=g$XkDV)s&Ur&aDB+{>+!3eKivfh&vyr{Rs;+s6Bz0iJm-KtX`V=Qy?({2Z)+lmO9IhF-%*IIf7zV| zqTXS|%RSvMVhpr_*ex!x&l>brbSaqt4Scf;m`r>BGJAIqog3PV)!}0l!?Sx4*X?WF z6UT|;L<$JM-v65y4<@68#X_VDFR;|gjzOnN-Lm8H*d3mo?I*kiiMM*QpcUh@O+%N7 zX<*UT#t7i8EyVB)fFU-cfblI4K=WxX-r|gBHnEfQw$+zMMjT7!ih_%RB~VMC4h}Y!2p=lO+w>xC;az0 zi=NnhANdD-KU@_(FiN7lRSgOl>4JDszH=ti-%Y6BwKYvONSCHxlrSm>#nhsPp zrRmb6`xu@D>0zsMdjn%L!?@f~KV>$*pu;B2i3r^n+LJUG+P*KmE++?vIXt6KyqV()w-Hn5cS5 zYh$%`h{M_|>ap_R#pjSfP3#ub!WoWa<-BD*eERs|3y;I&dH&+r`m<*ZE>}=b`W`ZD zUrsB>`klm0H#LdW!Ay%uSC=7#nj%vo8%G(0B*p3In6+CI zYeoYuF%e;j(wHrc5dzrueCM1XyBFK#F2@k{j>(hv{oe1K@Be>#!?U<`WeJ~%x!)eg z3722m4s+My=nUe8P(lq_D8z^bs)zPXu;^_OtzZoRu5$Ti zeQw{}e5lRsx47HdF1dSrHC@ue4y@qQ-v*ovEwZlpMz3Kx#%p5CT9Yd{EdDR;SK$Vp^p7{X}duyTn+CYY31=6&v-|j&T+5XBkn^L823iokxnV$a1923X2r11#Srl_SjK$L znxz4L)3j^zVpz-NM__G10gEe=wEBOmZ@j{xA~6TYcww|goS zaE;rIji^uZ1p*UtBZ^rvBw&=HalmTNL~x-HH#avItJS(IhU}c-!+TJEUi)HfZ9i6T zY6aM{8PUDiS9CT8^F>T!ScyQF!wIXGMQJk_JD;^?X?@>{XFFR5m7ZI?m!8gggxAxg zJk?~!WjH!I8jm#*#MOJ?@hZb(m)n{SJ?hWDQW(ugh)vT^Iik$1$KT`A^?)ju2MJsb3@#uWIwE=vg)}8~H46$m40js8qL9G*d z@mYUg+VJnPe_n0qtao@!S4aQG8$eM@dFqt1z7Z)nnhj%XYz%nA1_;!LwhlMJt(`s} z{>z{G4YITi>rp9=OOHeP6>}GbtFS}Ik`dY1grro2w^T%vGqq{FF(9IVg+f7u12$N2 zn`HHeW~N7`L++r(YT;Reu6dV#!YIdpg~*`6o+a(*55k)w6BIYAyAfdnT2G(G=UlJM zICSac-HYJMMP#B5F!o>2edq3bkm#opB9Ld0l`-SiIoRNWzjx z2E4NOoAEC6L7flGg+eGsPtD9*EXG!w&E^LMw{)N`i3nJQUcxIeGt&=;Ua2r*AZ&m~ zDk9kCb(NKHpAWcEMpoIi3;ESpzAT)l05a`|C|SH?$p?dmkxqnHmApj2KgWD`>IY2q zra=>L)d7uua6qroSflrTwikfuI+T+N`wP+3Tcp1!gN!}Au6UU5K6X1G+^oD zz=RcjSReW)=4S)Jalgh^Wwcr3a;+SfU?gDF_Nt0ii)e~E#D=a zy`!Qcz9Kt5J})md|0thD>2g@4?Tul=o0W(&LkJUd2EY;_^Hx+;)UsvEmoH!OL$=y~ z34qV%Ivula)2LEe-#O?S4A@blWMQ*u5#A6@-^fr;VTU0j>xJ_2=hw>O(odwTk75DG zE(~vkcdoeUBwK}#6{v>sbdF4j%P&zcuD}9;K(aofEn3^*^ZAeCByIHv?G~-wW&JQ0 z;e`{pmQoS$Eyh=;=^o#{IXOLNuA3aX_wW1nbaI1vG2n_kg@NHMMw`ZojS8z+O*PHYW4f@sZy!C&3rk`O2TkPW@&#b-a zz-VKEePD1vlUrpmO4Gob$@L#KHR#m^vjDJ4n_~~>Y~7f(F)nUn()J8IyTOg6EiZ@| zCZW06>QZv5K;yHFj9wA#l5mwm$}cu)L1ZiVsgySn@>{g`7d86s7Ay;g4g%KyfV+-M$hq?>|Q~X-OWM3me(JZ6c>UDcWdZX8XDOw>8 z(UE7-Z-&>3s2}@9y;`l`ZiF&S){*gmt;EXHqGc?+g7|`gBECAq^piVx?mT%oG+3a}a_dc;G8x1e@Jky}v>3nW7YPD$#coFDAxzTC2{leMPyr&{@~y&6TMb0p_?Kk9THfyP*NR9fTP}i$G&=X z!)mmC{kxJ9i>$bXr**lEc)MdiXd*C>tFdV1twy74 zWpSJxw>4#V+L_%Cewh8TQ)nEgE{(NOYtkkZ(=Z(!o3wqxBxW|7iTDz_ZV^I=FMZNy zgHx==NtsTTRBajp4OG??BpC?=B)+gJC^5xUlt^e+#n!c8mjTP3bMF&vXTYuVsW%DL z(hnuS=YL-AIrrQ|4%_VU_))>=hSB#98^Q)RxEmFC9Ac@R%J#qDnZ&Qpodmw8O7RdV z@y4f4ee!31-zpn36T-V$FU3pCNLj$3VCz5M8Nj(87#P+IW{}K&aB*x)pRw00Ha}Yc zFYE@s%`Y-9Wa@=cTmu>fcwfM4wORv5Ca+CC!TWA!lF7}P?e@p>tE*$l>_myk?VdpSyX*}f74gA@u;0X`*6j^$m6;s6(qOQq>FfQf{EILC zbguMPDW3hM0xqpAJ&VoGTAJ(`OnlI*BgqR3ik0{FnY!S`1(gO^oX3_W-_ zG0bva&adh2>h*}tXPz-?kJzI|z83G)=+n_*vr5utwb`ryxX~JTj@Eg8E;>FIpFzTB zS05*n<8#Cf2Lib70rvSa9$5hef7@y$sy)H?ZUEn65_17p_y~Cyj4^a0L|Es~S7^0g z%0R-5-hzPbZcCVB!h04Fe{-h+2z!4_FV4>Xn5fY=H#Bi<&=s_cJp;rg)KHV24-BXsUwu|iW+Ktkp;&Ri*lI_+O1`Nb7Vmu(JH>^cEJ<18k$=4#fZwyQ z(*~2yZMQeuEf#p(5wN!UA`*V|bUG9YrC%(l4Ur!Iuzx^RSKVl}HrnVr@Q>x?k&)=w zSUkSD34}LSul%q&5+6U~{NX__1zbfBoLvP46CW%*K?F>CH!z;2bp|xfLgDEGjG-~a zI*l<_S%tPPUyXy14Hk<|XK!v+bDS@4&o(?kzo!E{O8QxPcJV(qV9#zul%&COUd`+5aCKlinQx@ckDBt z0cSa*hNZS6AHNeMjwXo!03ZNKL_t)5b1j_LYqFbk7MwV4mr=m*0A2w%?0lq|dXY{~ zFLCY*E-?9qsEGWb@xPafJ1i(^l->{lt8AA_)*UzXKj%B^6rMln=BeOaG*}}rJTBlqiueITTG#sF1#R#i)b#5+7@WP6YjZelm<4;;&C1>WG&H(Za z^mZX%biz28gPLd|Un(Tt7majbw$MObF%fa+U7QV~l@FV6h9BO>%eYt;+(#&qx7Y5a zU^o@&0S&t?>ghx{91eEqLBWix1^^QQ*VeX}f;sE6c;;+rJ(5@t$z-EuO%ZNfqKJze zfqAPhRKXZ$|*Yy~-?EzM+mNSi1|CD7ITlWs4t)G#f=r6voq?!@eNoB_F^# zeE7XzHdo_N?$P%@`up*rdzVk$yZ7+k(1%A4>>IGb8xDK%+?uNg@PbObewDVmqPnfs zVFuTQm+4_ArGj+jfQA9Ft*Yb__4z$sC@7ipGErxI=H9MP1<>B~(*;FRXsM)+dO|)4P)M3*OZdr=; z3ASGZCSGQ+fC~n=wfXr|v6?1)0-7O^j->NumuAybQ^RICB}@Ugby31u{boZd$?K+B zs>p(slFw^@K}1|;J8ub+<%4&PsOAs*K8*J3qaT&m4-F07xKMt)^hP}vsvq9}`sn@! ztO*zs!y#fXhYRf>XY$ll1Ixx%hZ9Vjv(E|Xq8!4DifXz6ZL>K(e>pckIUXIE8JPhQ zQ~izu?G5Ah%trFDN<{!W+S+--SFcxHY_k#pW1d864nlGSiBy(^yEO-5r#tW3qWzp4qRJX_mnFU zuiu;yi)(!P(0bnD($dYFnJJlH1%R;=pw39>?ns#8R8rflq(K#_C`h}J=$UTb181cx zr9a>kVEb~QCddXcErI_z6RgqiZ}gzx!+K;(ru3DUm)@$!GjNslL-#-37h-`|2GL76 zlFp>l@NI@d)9_8&RZ_IYw%cuwP{dBB25U%lV4Y}@uuS>i<>kpqfI5dd{pQir3ujkHArcMP0?z&2S}ZoPhHD}i3$}bOH#K#L8}0yOQBH)@`Rru3#_y*^|EXA0 z)5Ox!gm~+(YyFAE*(Ge%Pot4W0T;=Oj8{;>ZRDa8g%V4=*;2k@$MbfBEmm~%@+GUA z54EHUax#w)uCDDU@%dOESQK0qE+*=Kd%_3be^}4oL4adLKD%}9#&HPjZ&g;FymY^G zABY7Uqc$11NCu1`n8FN>`Urb1ElOi6DC2ej+$f~pmuQ#obN{ZGTIUnw1dEUg_=K@; zG`tmNOfrbATrPTTstdwlgUkB{;6sNe)?y-Elgrl>%vo7mi}}B=RSnnZvE`_LZ7b4L z<05Kq7-+!&D?h&n{*6eqlFA9@#Ke}=($ckS*S@*t9q_0K;G#O?6(Zp_s^FcNO0u)3 z!N*oeRa&8_kV?;Be>l9#q|``DY1SkuJJw;h__z+S8@J&a#J(8Y)c>}g__rq?UdT?# z#gPQ%7mh>nR)4Y*)~%Bd?|<^vS5pgEavimyhx1O;MU1sUcdWM!0%q&&#$G2;u?B}J zp^D2Y29GSqf#Q=Vb2DS#p!21ClOr=58{5Xm;DiCN!(nt73E=iB+{-$PfQ8g77f{X+ zLKlC>_u1|A>>y!DExQu&8cgKiGv$kfe+KwaPHZKp?`Uv$xI3Cf|6}ZIL)uESIL??( zt?RUuVV8m35Bp&twNAGhqeiW0gn=KVz670wp zn@KNzm_@+|Qdi2R6QTx^0YxJwML~wnrrok_2Q0X>>^bMT(X{NS*P5FIKiK^IpO@!3 z&pFR!0JybFZZLG3`JinsD-(lpb2WM73G~2SC0(AF3SWj_WEF7p;&A#KH@8evQ>|Jo zysW5b!2x4#RzIk3dM_c8$f8;s1{qYk8q~RG%n$492l3~1eLg#HQ(W`e?RFqst?-7! z=7J+y=WotQ&G~2xgdWbF1H#R8DVzWB;ER(*M+c1aT*w&WP)zAWxs8+8yD=$3#P`@q zJwn{nHuGvRolY-jwlkS%;;-O-S67$Q>*hjBH0)hzxN19$-^AAMo){4^c56U25=86}K&Jt&&_VAB2IgwHOhxUn$+3~`??9233SqZINV`_1H4 zYTI^+O=x2itZ|qgT4^N)Tktjepyo)35io1gL0D$rtwlqh#9RWEq6sgU1N!f}s7(b?&k(1QO({gx!D9=KY3`0%H>7^KOj+qZ}9Q^sWb!bAmD1awP) zNyGi)^?PB}e$tBwb!4E~UA?E}S}B;u7_60jzSS@Y~n&>h-J&N6B8Q{uFCf?HA zvNY`--XXRaVO!dgAYYHkgJeZEngH>lnBkQz!k|Z z_#F)(;|W}Sn*i%8X9gN#EHk>~yQUv^Uv0)7ZEcxSE5f`cIh@q6%1gPt#U;&w#3KF= z{O%ybtKQ=ZOdE94b3EPwVwUzEAhXi?1n?Y!L!sz2n{A>f8bxoc;Bf0ac}r??-O)kq zH9^0KR;h$2T8W6!L^H%^AN>C0@k14C%C+f%JlIcwX#^LlSfepJtF+$xM@)}s;Ri)+$}$g{QWw?qGkM#g8XbyiES`-*h9uncZsqNPoSoP8c0 z#R$4|6ay@l6xZn&yeW{c-{Ya^%E<9trzY2Erd{z*F)x`cD!41#$;!eCl>$D$xGWCA z^gIDB0m7}V)S?eJi`Wt+3iL?~0goAfSlQitl)8E2M?U54OeTj-Nd(;0EiY+txujX2 zmVWh~=Vi%Ho_!_@4Q%0|wwAqF3ygt2(|c3X%)PsU!mJT#x>4BUiF-{NMeq>7g*oe- zQ}BgLx9F%;Ba5##!$=e>a1>e?-jPyK!7j0t+dHc z8m7{Y(aK7;v4jzHIhburNm7G^ZcK+9EKTHNWy?LgcNWZQ(mSOR=^{-@pDmCf&0Zm-zP!<|X|zc0-9fswB0 z2EahqMS%PBLS~i)k-r@TmIxLR>l$=;YzLo^)o#FD!@;)t>7gmJH}wK8JOr28+1bg4 zY=XcY2)O8z$=NS2T-YbfMtIS1muAe6;Hs)pLOiWxp%z>@D7o{k70O zGmocXaTg+n=u5##zIa4J+;e9QJnrh^QUU;PY(yd`-=!tUn&6GK^wQG1Y4~ZU+iC&8 zWfvjFx-2P}LT469W5rH+rQ~`agM>%x>K8((M*vG*;(6>uaq;QXr;C4a;sbMZ zf){wR3F+cL%!HqdJ@?s?m6ps6>(imFfFuduE_v!ez}JNDH~+o4^;szOA~fcJTnx;X zQMlKGd6Jp{yZ=ZE);Cd9EWwrVl5qD4OLvN;(OjbkZko|5V%ZlvkLE&lX-A2`~?RPoM)p>8wUnzaG9g329Q<_G(xo1+O({E@sxy zW-msT66@2wR=h0ki`SWn#+wUGG%L4bR+<5RTw2cRqgzVaWjk{o39rY-6(8na3e7xN zXOAqklTBse0?sksP(f<#s$g)b_6kJI_6nbJlokt5HsQ+rAjUmD-smt6d%VVb1X!zf zU2(ZxOu@8fk#o0_=cU*=@2ZsmH?Rc{b^V~eep>4Y$76mQ1X*Bt1c4W@B*iZ9oa)p; z*7;T*Ugm_^FemW6^j%X!e5>Gg^;{!)Vtk{y`HKhNoID`IE-W_M?VQTt-~{fspPo8( z`qw_6Lz6!(5mYSnfrn_mMboR0{6@C7GXNM@DzP>T7q`Gjk6Z453%0tg z02m`I5HSI+lhWWycFG%!b#C{+wERvz1kZc&_4rjsn1x$t<9S|X^U7pdx@7TKSmdX) z6jF7S^ht>$KNg$2cU6%>-g{m95Q`iuYA3LSBz2rh!zy6%?!w~T zAY*vDQCWp5t{DJTpM5ZSurL1Lv)f0^#;ie1tzs$;1il*?p8+EcZus@f=-NhNDe`vu zKiiqN)8o#soZsqu>(D;q8VM-4jJl7Om0iCG3NB}Bm7|pSvPc@YmnxlYC|~cMd^!J- zc3z6YKo>ql1zcu)fOMEwnH53%gdEe}uela;vQ~C?!$JGC zAja!q(FdNVqM}b7022*C79&i_Enw9VT*g(s=XZ7N=sSDa(11IKGkuy^9R9}aLHyM? z&VhJU4iYg)`2Pcj)acUt*7-sQ>l1<^g^*dvA}Vmh&CN6`0t*BGN88!Pv~^x_JPQd4 zBFoZN$*N9DHB}-|LdP{+zmQN~5(pxtwM|Qi{Gt%gj(O2=El<`R*eS#zjwvq%s}6I5 zZA_U07z;43KLcyu0}RomSSF1L*gG1zGyRm@&|IlO~59KXo} z=P^DM${TT4PR7{NBO6{gKH!}aD#j}w-GlV#?w{}8``2|TO?AMQ0IV1@z}OdnfPaz& z%wjBby_Ii%e59JfXaL+R%6DkUC3@fIt+^D1ZW7|n~deT%d zv^EW1xPJ4?AO7*%`^ovB+cFKGEo|EYz$FZ@KsMTdbVZ4>X$Fsl%{lotG51{C60n1H zhR{kcULatZ%*c_AMiZ@d&phcT_Z^KNYt0?~b8M6dUlQd@>ylzL)y7;g!j+$30Tl{K2cIZ@7?98f!K)9y1q-*UCdS4d;c3HURKhUcv1;4i}V3aT?%U)oo zaqR*KmvpMLcDhsj<)7})Vf{gC{N(HVu2hn9TZX1%Lqm21Tv9UOMZgZPmjE}{HYpU@ zDI_A%%u^}OC}Fsp!TF|A^V%STi$RrbW=3!4fH0Y8txYQ3`=oV_pQh9|oBy&ye~@om zRil{svIF#hFeXdX){8K)>k|<3V`GiDDUv$5c|e@6ihcI3_KYhg#9Bfu3>cik>?HiE z`X8OIQph;|wgHv|x|dhnmA;bFEXr(I`D6<7c;*o_zh zh6HOuPyt=M0kAS_pR-w!7&gM}SeB??}HS&dyEX7i*P5l_^@&#c6@<{LL|G~LA6vN#6(XJXfE z^%07zSQ1?M<`F|F$ydbdvRLvvk8k&DQZ&e%g)SXfXHMixi1k7D0uym5v28F@86t_r zJE{^xv{j(9%|j3!OKMqH&xBK@!a&+VPMGwmV9~PZbs14*M$#;0YAG>7=4;V2yl@Al zJqIBr*}eC`Yc`+H*V8j|_zAqb_wn)8*4EL-4D@MAj!3y1WBV+gqDt>iWUWVFdr_Ks-{gNRrHGrY+t??=mu{yB2 z3X#ktAfBjw`_$VL6B8!QB2HeZQ>j$%zI*YbI;Vq%ozZF~OM?eAo2h~|*EGQ;`R3c1 zR&=mOIupb&S{B^c&~Y2S89kS|&=qe$R?HBSoeqGh>Fa`sS#0XD6|Cv>^A>E~Tv@@I zgvr#)OteG5Oqh-G!!8!3C|gBS<^iZrGF#me*aW=uGCgIz7+ir`3$rbeyYPB)(Pr-` zPaCJ{fO2-M6P=lfbE?Ox;uq5IuV3x|)z($(`nspzx_se5I1&km@YI(v#3-kL8hL|~ z;if>FO`pJA3J~wf$57j6jAychnTl--8Zgw54pkU5*qC=~wZ)9#j6}jV<7yW1ymkUy z2Y{!X0wqaD*#5%G>YC=#>4MME@3M9(taUC}Duf13Ta+L%>Z6aUv(P$T?3;_ep%K z*-XxtgA9%GU75@$J@m{^Dp=>!8M339wGF0Th@Kn6A3gdZWAdA%Ma%GFU0S;FY(wR&!C-?_QDY3_eH4fiRF)Q5a}o$e{F0bw(q%s7L%Q+<1gYRUTfq$S3=-PijDODW_w z4S;}A!7PksfN@ZiQt=-S_#{4$o5A^}MCVIaPtU<;F4FAzQT*6@tu!z*6F_70BujnE zBcV_zT$TXQE-fV<#H-pO50;nUAJMH)I2;Pa-L~@l=5{!w`iE{jaFvCsQ zLB+4+6K=Kp>^A9v{q6Ry#|^c?J0)OekMg)igP&}}IG)F_I5M(0a&u&4+&Qkgc(IOr zFwJronm0kdbIkkB&ABYoFLrh|MlgqcvK(T)KDfaaKF}4jPhsEfGs$Eu7SkDH76=(7 zCboVJfE`|vFyw&-Qtl1WL^ow~UZ&w@^B_3i7$;h1xMrTi`4)XYeu>3aqZB}A>b``x zt?lyqRyrDurlZSCe$UeHAmyn#>+z%$OIJM~0Bw0VvYtq+!xu3Prg)k%VCIK$o=6qS zmmD;XZycJXqjNkrp79mocAQHAcJG z(J}KFQRju2XcXHr{Q%(LdL2xcGk0~rNv2u6as8;7kJOl%i>{gM#Ke@)m2_ANMB7mCqaR^P1forWOb6RS z+bI>P#FSx16m4nVX}g-BVV(BvYw871wl-)dP`yDCAvI)7CSDAg7?VjhX7Bb7*mKVF zzO-Job)wFrfN){7KYr)@&c|~O!29Hmjag^-3faKd{WN`i;L9`1~FBU#=t}azDurU*U}P#d^HFF2QQ)r*4F8M z`pdio@BH<*Lf>^)Jh#zKR|IumUtmZy)I*f04zLkCfxto^S?3#|p)UqWWNF7}Vk0ov zq^*<*TV44(kDuJb;#C8|tBwwQvZ;*N{gL}JuDPY;#=7_Ipu{9r1(iz9c%PiGa6az! z#QO^#&)uxY^UP9|-3Q2oq9@`_@Pf4%0id(IoKhWfN`J8FPo$=4U5JJfA1caG1Nhs8 zxTev@T0ST&mRJmO3$K=r4dTs!R@dz8@-l)92!qZ>AAGSjf2l%W^uCv>tKR0Ru8poo z#R##Fm6(8X)ri8<^&6k+$9r@K@p38S>$`qZj&-+ z4Ue|qe0P0#*-e>^Ftf~)?IOH5;8rU9!UJo9N@cx%GHc~uCUWv4xxyqbsFJ*jvz(22 zy>SJ9Uy!A|kpg@Xc!ai%*=UV4Ifkf=2~BjyB*4&$EBJi}x8sZbsHiKgTU2RsWa>rGq4Qk|tcOOJ z5^Zoa&TY<)>V57bV&ZC&0$_0_Iqtu7V^xq2tlX+RlwJPiKx#*JY22KvIWzh(MvaK#l8liFI?sJ5`ogtq$B;;Eq)Ed)n{ zL2URPbBdWPN_1e9bdnX7T4ysXG^%912X1ZdW_Et$?&xILhQ;(G+ULs%uTqaqIn}5!cZL+L-q~dd4Pr`!0rU2n*Nu!Z3Yf_-M;)OIptYO6@z|kNRhd`mC)*y@VEgKq? z-j<=>y`wg2Grx|oKa{D{f_?kp>e4a*j2wou>}quems)g0U(x-Ze*5&5ez*ss1hJa2 zc)iTj$JzmKh5gVXU>z_q!|a6L^l$=UZ?k#H$4^q~s)<==78=oC8ExF$`R@9#!`<1* z-0u-eaL^Vu#FtZ2Q=O4{V2;v_Ad!&IST;~{8sk|@vR{}4uM0+5C>OnviNph=AQW(g z5quiYqW%K-3>5nsa623rR zL>EoPO^|MTl7q0wJdHZi_>p67h1ola9#= z{B`1@0*HfepVTrZ+~f+_L0gTG^QAA0ukq78Td~f#IT6>rbaqOWg$~>jL2IYoN@kZ) zM=Lpf#YThGro5IgnJA?M{w08!$i;CT@?Bnd76*9a*|riEBHFAPX`D6XJqT&$kH5EI zV5}FDUI4v3%^%#Bk7F!Gge4ZMLyO?pfW0l#s9qM}WHKS!e}DdkmGv2Y-|YyR9gZl3 zsWlF@nA=i276U9pT^BfWW+4zb)Yp8{DWQvv3*doiDHPyK*-9|dtzS@4P|es2$I40^F3AX`0TCu?2}zpd*&pB8`N`B#|NqEzMIV^0N6ya zFXfq?RBJeC!kOoo&1(H(qw_@u4@5V2zM!2uaPuibi_emErow{W?bb_-6%R*5b~8RB z@~Zo#R03k9Trq346jQ0(xw24*0eye-dK20Hu0+J^N%1l(&s)$38${-+D)Vv?VTD3r zVMCG8a$EGfx2aTX!BF?ELu?CWuy@|Prla9_zpuf`tayH7`gy+R&d2Xf=elAvyY zz>c|Mg!g9O6q;l0RW02y!Y31P`8I-l`*r6_1isaHVDq2T9<Eb=im*e)NuHQahpHPha<(au~@2DE(-!5M(Z5QDvA+!0i6}eLAZ3T>seb` zNE(@%Vj#1Hi&pC}06a=ZVZ}WoqxIX(Edj&>p$ficv(1-*=ik@zYb&d(Pk)`6SzGhZ zM_&AN<;r8E@6M|Cc19d_31D@DU0qRIz~km)*q=d{PiP(z^SfFtrlOm=4~<}65DzgVu^w9Wy+b1w4Ny}dTSJ2u#yB9X=zomi@R1x#N_8=DN9)& znE>xQT22Z=0uWB6fYQY{&V@=86oO2{)U$@R0?91H7OUb*1p+K$Jep3AhPR(QBo>PR z_v(6mKEF9{&YzxNeR^f4$K0zstuwzsfUoq7?5KK==hH?p@gZg?9KIGYw{^4m*m1m@ zKQ%=c^p75GqO8U-W}VFt`HI$AjC{B9-`JnLfTvSDVM$(nO)c#VSDMQ}90t5WK8F0$Ci7_8HU#xuS7{LE>8$QSbY#(fLA8UM-)5YY`aJKrb1ReL{p zbgRL>&SHCm16?sX;^yY&DZJOqX1Y&xPc>0q(quZ}^51*)=WqeXdq^#LUJf{%)DFRM-fwhIQ zHHELGZwy`ZX_rMDWsb&p*lNYbWd%~0F&JOd58q4zRUp>&_{T$_t!DfVYQpr5-^%o4 zF8#bZ@_y;dqW79xkL>mejloXOQR3s~6yQ76-R*MK;V&FYNiCHpT$y{Xuw_H68DU=X zz}CK{yT5xV0({{iq0F*ZxPRIW0M{!kCfR6QM_13xHO9nfp0U@RsI1a!$}w;5ZoykB zm-|bYjgF)YUBl;)-|mz|N{a!ND5D$ZM_`)fT9%qkY|kE@Dh$M^7}J=nj~l zNY)v@58!-1+v@j!|F!22;hdKk46hXYvc@``$$(&ridnqJz!WsbzyLA3u%hAcT7$}H zl*zkFUAc&-kV~Y?ibAmnu;!4y#k3&Et%6KYyeze`RU%9~TNUgOu%xu$kyiZg58!}7 zQ_uDJ-e}0*3kWw5gMFc1f9QqxZ&iPiv#}ij?KDDMhwMEh!Rx|B=PuXmDgWbF8$u(s zdSGtroxLA)KJPeut-tO2;o+~ayk@#_w!Qr_PTIij@%2jNupZ+g%4TuQHjCksTU1^6 z0lTk)O?BXRv&BRlYsE!D5RyX91HqC-NNRH6l?AH|KGTS?(J+8nT^@?!ZmH$w1KAd7(}E+q9sMAw15It z5QXD*+uCizxKW|4VC|%WI*Hq~k=9c&(iSo`gAhwdHb??oNH8&T)0k#V9AdaLz25JA zzjJ`yn2b(Iwi`a0hHD<)|33nl_Q|)jJnf!+>d7sMiso(IiCL}IHN?@;rqWV8Zr)Ye z)wREL2of}-eh1OcC9B#Qih>`JU;XmAP9;On=1jwbk$c|{8jT0P0mLA?bg)|mg$9;- zSV6(BMyP0rsh)B>@x|SoZ*Wx878B_{1V}{ zx!rYOfB`JE!6?#Cj{Q`aCjE3z+nYCs{Vm;x>t|=5;+s9}nVi}yDx$Y-tsQ_$XEfv= zB}^|v;%#_z)a8P*L^{75xA59o1IG8Gypw%DKj>*cUhY$98K$?VuHn(W$5w0eX}z95 zA&-ih)l$N1DN34_R*jSBR*U8r3@|j>K`mcqP)lV$jfFE=NHSGy~?ocLi1fw(ffQ`dYWQo4C`Bw_wBR57vw{oGzy|2I4$RpFAHKibM`}=xgDS zJWm*WX_z2msUhaYnPIMH7H6dDaa9mo-HG_Z(LJ~cV@Sm^oiRG!VB#_fr#+A$mN@)^ zGoyMogZ(utm4e&MlNC6-JCFaq;9z9xwdXL=&h?&&*DE<#7@NP==-DeOvbW=pLh~i@ zw16*eTWE2l({Zc=dRz1PbSvLNe|LK4$L8Pm881r!u>$y(`%=DliH_$#mqx57j_GR& zT{#QY2IzCAH3zDo5wJFuB_45-gN6)M5T?J?(18`i!hTSlN(Bv=bPh6{c_HD%3^m7J z#I@O0eJddV=0hdq%hcZfOTmA-T@xNGF11a*eEnwS&FcwI+k5uJ{_o!>7NO(Ap&?=m zL!Rm7m3&^DZY8dRw?zCl?!bS5k2Agk;2}xr<*s{=8hVKov&WMOd-!BB^JHW&Vm%O~ zh!LA%yv}$ywu>h!p`F_0JMN13Nb7kU`FUFGp;8MKz zY$Jx&Mzr&)Qbt`(J!-d7${H>;7Y_KdNe@k29&UskYp|!zQ;dKi@j*?oqt)-X5N|m> zHwW9DOJEAc>rKz40r2#NFMdsG;EN#%T(WKMe{@FI?)z~p>`XcX+L-)we^bPGR;%}^ zU;`ErWb)C1{9;O)xYaQd{RB>CxrN1qJvqaSgJDKLOUAd+34CR^&_Nn|!kLBKhRG~w zV}NQ_u6u5`Nv-NVAgTGXaOF2~3#$*XuBQz*#@_j_J+VdepdA1JJElWXizS}6_`wiQ zlW(uZ6$jcMR1|!_4aSqyfcR#E&X@XeArP2fNIElFBE@CKOFlhrC}ib67L2e8ivPq6 zk7r*5?2AyvUs$v!Oi;@;2pe_`XojKax7ykc@~o4}c-Pqssb@3VU04&UR8r9eU-}27 zjMZJ0NCqkj2mI+&BXj@&-nPbDu(z&g0h9kmXufpBqoHVvC9ZLS*GxPvzsu|LLhsdw z<|W??m=K0rw!;MRnU3-CcVmfwJt<4h$13j`%bLDZfV%}rOORs17+NY**AoOQ%rua& zcP0~~J?zj0tHMPMprWbdqAcqe{#vR@YBQPFgjH!)t|mI%z};xTe$M5>-`UScG zf`m(6aV}p-_MA9bt7qjeSAn9gWPJLCL?Rgo%!D(sufMmJ4SrWk5X->|%Tq*!I|Jd1 z9LHtsfrlvrB(Lat9Z=5vED|l+)9ws{S*n(qq=I%<3MmaLz2I-rkK4wg_|^d6gBt*N zOTCwBXxImgfE%xE7Zvf_{_L$K6ooK28iknHA988Z;$?9mV;8#z=|SrK^r(CjLHwYH z@v-j~lJ@YTLavZC9JQ7W-7eSr6vX=edi1>&U`Dyrb-6wFT=ah^z0sJ zZGJWdtNKz1jaJn$Z*C>#j6M z%7%LNdJ++Ilq$2 z&p9+D1&+$Yf&>F|i~# zGRdS2w#zX=72R-$y>krml~L!}28k;~TxX;9*H(v~6%}clN>0QV(ZbK6>WU4zi@N=j zJ@v5c?OfZRckb9)?0kumCLymQEndkjy;{oUmZ8YdS`gr`2Klq{Rs6B>s;1#4<50y- z%zU)h5*hZ@D&)QWk0WKx9r{{@AqI0v@`OG7f{STcR;A7+lN|~f)z7%160??qs+J0c zL8_nK?zQ^hn#Pv0!As5PTvdR6J~U8$;yKRFiRk&4apL#qn}Qd%Mp^II}(dLuJ;AZ%E9<%2|b)>q|Jp z54n^|om#L5#`;oF4W^>Yuc~CwmF80$W*Y3G=%S+~WU$OOx6))_dnzPgdI2uHf$9Ul z5pBk|?JZv+<~MEu?O(V!{!4&MQGz9_W&o3WVVzb=SR{4aeZByg~t+R}{gz zkwJo3r!SX70V2iqg`J7NWx2k<3{(tpi4GC()Q9PLg?QXSiwp$;-q$68JjecF>+qy_;#!Hz8yQ8yr37*R&7KbZ zaXMeiR|SQh9P|1( z2~r!Z?yr*bV0H=FBOt)l@Y|`)3ixx)dI@$w4cJl`;3kP=XjXIKf+x4Klv`QJP1Sq7 zexq=Xy6I?tLr)MI@o>MLLaPJB#;Z_;P-zXpzRbeBn!#oMK^)@88A8<4>x{2ZP^bg0 zlsJ65&BXdv4xn}>-W3QiZ-oDOYGAVhjuJN-cZ%~8tkFyt6x{s*;^2}{$RfU$(gM_f#tY-Pl0nF$qR(ZL1qEp_Spz$bxNS402nxwc8eME|^Bd z5n7l)9at(MlzFh=!{osSpGrgsTf$6c9tv4-_hHZPcg{8L%TT7i)uYDtru5~*_xJDo z&iREz!S{GMNAj-y%~Gj0Bm3f*FfkPmju6B>qoc$Tlbm>{=bU~T>X%<6d*Rr>+EfcS zo`L^mXF{jW(i2CXR!g1dU~>>tVv-wKA5r;&bw;>O9teBA1o1}-_|Or!2C)@n1qAN+ zhy8!29%^4l1JPowQLi`lYA-dKkmQTS3M3mIR4X5|#*qip(7A>8kiy)n;RhrwUh7Ye zL2Jjwizbs58ZLn^JsmpC>@$L7!PUXe5w=2m%uw10rWlV?tzKK|K<-@SKq@?Xm$$H_1-QA*TGk`fvS4umYe0-Y~_8YZt< zt^L9D@E8fGlXTRIX(9#n%SAv89a`-8ikY2B@wBodN>&9;p_AZh(Wb+!mu5#!>V3VG zuh+Y}`nyBj)rocLyPpkQV6#@t%LH?D#^(zKgEPU9Woe@TcZ1Ne@<#GqAZhWHi@l?S zZxUsE|IX8gTxM<&0&2Y40q?UrC|w=IR@69ug?w)i>wK10CRxnvRDCabgL#G+%eDGx zmrY03iFvmi@FyA#jTo(0cZ=?r#r-&uaL+vUxeJgjtx>|*5HOeerXLW)I4nXqV(m{6 z#3RFFNji)YF3{1d!Ig*QM6I4HqJ~AoO7z`XW zv%VZpYioh=Wgico5j7{z-VQ@)!%o#pV1)K7jWkQzy48E${YOId`+Wi>`I(4 zuq2AXMzy{p1veI2`LGd3Qxnd8sp*OPfSBH&WztU*#FN)dV*NN|NkD^RbC z2gVMX8@2Efz`t|>cL;C=XPt8S+)GVvcei552a5N;tXJ#x`i|mTnry|bkE31IJ&?}dog@IkS~vb4|mygrf#A!0AT+=n$363 zoyvZ7FHsVz_u#13UQQO*Csh}WK9~{)72|1_tE0Vm(IFg8TTF3tW>2fUaUf%C#_~XJ zH2!2R?7-;CPNhp2dmSwKrEJODMfiGMzjOh2sA{tBM+FC))pyP9H>JI5tr#E)Q)92T zSrR2_o$*Bzty2L*1E%ij^XbK&-Z7X^2?tuNw-#>wQt>|iniWgTGaK{u}5pf)~`{kSMYV$u^`;A61&+S+DYf!cn2w)@R!f}kTRKDPg z3F0||c=&4X)u9N^5RP2yGlPk~p;~3EMbn(=Y{YsCw`?itg1krCcJPQ4lcb*VwvozD>n2xMs0u>|Dfz zSMmI9f*t&YR0-}!qA8O{ABo&?>e5aXE=12f_+A9diW{ihRUXKbf7AusDZn!bSoUpg z?^K&VRrfTd&8R4Ac5|iWVqW6b3oM2kz(oV?QU&aAeeQb|$Oa65{tHrwNgOAuT^w-v-y z2$<1T)r+b{^9JhcW)JU@m=*3-IX35BFjTsP-)9{@ zO&puAc<*Myk}r}~DHe>nh1l+lAS-O7JjsEh0mTyaN2C5FE;C4TUogpGHH=pEt7Cjs z5yy@86pVpzI_J&@GLj5f# zC~%X3z)59;tVEA=3I6&zt{6fxC*^nk6jdZ&xm+wK3bWz0g^SB53ep}vm6|6H) zvm~CnU~H0xcG{Hy+%O|>GF%u%z7=1V%YE5xwfyyUS`NBt;fg3j;0%>=rMNz;4bLuY zB>dzV{3ff>l>JHWwY5v>~@C@cYT2) z-!5K=oXJB%xRnMYWz2!e3a7&aY*teK$KKh4wy|Y#e2F&;OJIw2w z5*BDQDTPvKu%rQFBE(?G5C+^#V-d{cH5RxS4_Ih;2$d>SWeJa|97vnO4XO9*LG z@Az;c~6oMxnCUGhD!_v*m9Pq7YyR_T(k!^^1ZYc^E zmmdJIrYQDd>&Y}h`6h2aZA_!m)I-4G#Z1ZMtMp}p#ALJTrF6mYZBRKe5HINWq-j*J zpS^Bc2A~7`e4gKg2O$2~LgbIuH=RPaM5}mbZD_dVGI(-v?71 z`u;GCO0JJXTxPab?BnA5*Na6@U2JS@Ou-E=j`Z$ucvz#2u;7~F-OG*l?-xG!Xb=7bhP(q6@rupz zDBm{-^bO&a8rEc(1*ZDs%IVh*|QYmtD z)$>#ku=mT=CohW9MGp8@z_Gi#@9AM2cc1Qheh7RoKfIU&;G)u>@OIO#K1|de*zv=e zJ*%-{?z4^VODoM4OIf`P1Y)8LK^B~YCVmlM%Yra#Z*R3~CCsz*yZj&g8>rLc2GVc2 z6<>b*`T6zDyX)(BA3t5ceEICkPkJA6z_*^AlKbRr+TNw-#oppA2>9*Wd8>vA4-v+N z^7Gjo|EUEcJyN8B&WyASwwQ5H3^d6YO?2}BL=2w?2$zj}7u>0@&=j)qe$5C^@x1U$w%7*&W{i(_eT4>_d(P2#^j1wBL!)xX7 zQ4&?F`k8pi8B0H`h&m;!m>QxUgBO{ejI}sDUuP z9M#AacVqzF&%XCF!Wd>{!8A2(HPHnlUtGC|N$^T`gwA)5N|R%2Z)v3WsK|kl7w8u^ zL(Rf8^n1Fa_Gsp+llX}`o%V9TUk0pqeel4}uh-9?J;!r>^H%qqi<%&;j9N4(3y;mO zRfcH15rvc#g9r7Qv zseo6K;KZmL@K*uGl@HFYx7%({&yLSL-9b%9?p%ntUu!K93lSHU&)jh4f@K)}nq&+g zifJ?vFB@n%Zi8zZ7Q0?~cT~>`(V}YyG9&}!n}i81Ao1k38TiIC-@58XUW@*ciKcTj zg;;uj+D69)PR@_9oG>d2f;Ky0Kx_v~JI#=bt4c0XVOpU;nh0xwVi-*W%`@m16fEBx zjma$2zn?|We9=Ju7vwtwyuOZTX_6mVXTccf2_+kO3(wa9ZXe@{isNJOY_tVF1i}%O zC212i+G%XI;~5UxZ!i`K@|uyx(>Hjdv55jUs`9ZfJKiyq9j{a=Nx$fWtLNZ-LzFK{ zm+11+Hz0f@JaMY$7W(S|tNUl|v$OW`VzDoNhlJRj*Ay;Gf{H=HlN!xZnsC!QU-B9(%WTH$r3$XSmL$;{FvR*w0?~7YTbkAeFo~kFQu8Mh_ zkSaNDlxM+T0t~?^DVRo} zaM7#+TGOahsgJTs>XrJn2Nwt3VKeWO{))3%ib=sw z_S-b%zK!egbct9`BD}qs;}tNdSV6?K$pj}>YBi~1Mf7wiMG2V9G^fHCMVlC5VH|Cl zR=p~aj>kg2Ea#|Kn%aj$W8Pk4pk9x z2#DQirU=9oXH9TcIE_=HH>7Nrxjj0|mV}6liXrHdgz>$Ch?>WAtn6~1T`vV!2Isyc zUlgz&ZRN)JcOc#h-OzD#@2S4?;NJGV&7C-M)C@7WVnBQ$qpiVYgkcsk&fbA*SquEi zTcx5#i2GFGAiyAD5b#)#6%t-4UvZb^X|+-uCTX1X$T)+3(=_jZ{(a}qo7>y>?rm>B z6o&6%A&GU&MToHKpev3JYgE$!#G}y&5Dz9|?%mou!=-?Q8}6feDGw$Y*Xx!P?|50| zsLKv4NPf*S=DwlMc)eV{-v)WXkI@&4bpgw0ix6ugdxV5*Vk+8i6V@ooQj7zpO9g2N zv$E)UwM7S=uSKo!W+q=sk3hZ;ava~{{OKQ&&jO~13!^O;5VMGt35eL949FK}gYTBL zN^L1)1bjderfQZUE%SIa7v>oa_zL_~%GV?Ls=0i>-Fdj>CK=+M?qfiGF)J<+k4BTp z#1=z$R;DVg93@atx_C&!hDm_=pRDwpwO^TT~4**oG{Qh<-oGzzll10mNz!Gg#<8e8 z!)LUUUnG2=XbX3Z_p$Y+wUO*s>;m7e2sm)W3EDI?!XrNM-)rfJHnBYgO4qW1;)_A>eAb93$dtz!C9nLoKs4iZ9(OvA8;F?sHY(JcC3B;yC4=XlIPs&+{I~n#91mRak*=;F=6eQ3 zHgpU+0QhmaK_YHc0Cj~nwF~)HgO$>im&^Bu({X|ZT0g=s5pB(DJeq^gKp6ny$K^77 zqNy$uV4eyMxe?1(XXo4V)Lgzl+WE;PFHDGa-3P>O1c-~WM+>6r4iW}K-8n6H5VT1< z>&{uei7(`fj3Ic=<@=+Z?MG3f(>dyLZ3_^$Sj9*g_zs9Moicn@Dm)sTq2_=INT!=9yV`h5@ znKESQkiqL=C}i@Qx$j9%KZ8%azs=#GbrPx4w9O&A!P!*>^D!3o9T%qX4m( zBc8txZhIly@B|O<_&d#hK=It~JC*$3x}xm6u!(rpSsq-Ra-IgnSZ(3E;PxCb;6=h0 zO;{7}?e1NHeftX5zCm5G??P*N)j9~#JjG9*YBw*ay@$8FcY}c;L|=U0Ik;*bnR{ha z^2(R&yXab}G2`)KPgsh3Tey9BwAH@edUbFcQ!y2YSlZ&( zQ5_F@)ay4lw>S#GO3VIsM&aZD+SduPZ)FN8N<_;)=C$y6faz13&wk$aW|aLv}E6^Ra=|Z32$KF z+|}q`TNDM$XVYmp@OEbAynOH-=3rlH->zao?J!0I0B z0H>6Ft6FV+mP#PwY-kX$G|Fioq+#vEWWm0@EDaONzE!Ta)_t{=4YeN!Fq-&T0WQo8 zkW4R)hqh1ltu$f>h_hD0(6Nm}=8Q2w*q7BTn-0jnRo6QxsE=Ex3S%@*3ouG492bC& ze(p`EqpbQ`uGz!87LIX|%;_MDhL&Y-gZ`c<;&l3Q=Lhx3!YJgc{E#g(E@=!-9D2Vr zXDj$Bhj02D_6J;ZO)#a#*_0- zue?+`857`0^mf$ZT*DGcjLMVgr}LBYInkT|$Fo?PAYfP_>HPPfv)1Kdu9X%!0gfjL zcXMAp<35LUPNg_GfB?s%jU*SIu;xITXN{Z_;HavsGz@eBxPTS`lY^tu$BcXbLJ|fC z=UF2WfOEKA{+`9gn8JQij+kQT~l1e|-o&XR#6(i&q(SVIbi z91MUNqc_2EdAP=y2@V!Hw~VewicTw=npu3|@6`G#;f<5=8fs;k&T)`PBoc{4B9TZW d5{VR<{sA9B)xe7lFI4~l002ovPDHLkV1oY2B%lBQ literal 0 HcmV?d00001 diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index b234fae75f..feb8bf2ecc 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -282,6 +282,7 @@ - [CubePilot Here+ (Discontined)](gps_compass/rtk_gps_hex_hereplus.md) - [INS (Inertial Navigation/GNSS)](sensor/inertial_navigation_systems.md) - [InertialLabs](sensor/inertiallabs.md) + - [sbgECom](sensor/sbgecom.md) - [VectorNav](sensor/vectornav.md) - [Optical Flow](sensor/optical_flow.md) - [ARK Flow](dronecan/ark_flow.md) diff --git a/docs/en/releases/main.md b/docs/en/releases/main.md index 45c5ef51c6..84fb901659 100644 --- a/docs/en/releases/main.md +++ b/docs/en/releases/main.md @@ -52,7 +52,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Sensors -- TBD +- Add [sbgECom INS driver](../sensor/sbgecom.md) ([PX4-Autopilot#24137](https://github.com/PX4/PX4-Autopilot/pull/24137)) ### Simulation diff --git a/docs/en/sensor/inertial_navigation_systems.md b/docs/en/sensor/inertial_navigation_systems.md index 7d03ce3299..090fd5bca6 100644 --- a/docs/en/sensor/inertial_navigation_systems.md +++ b/docs/en/sensor/inertial_navigation_systems.md @@ -9,6 +9,7 @@ However PX4 can also use some INS devices as either sources of raw data, or as a INS systems that can be used as a replacement for EKF2 in PX4: - [InertialLabs](../sensor/inertiallabs.md) +- [SBG Systems](../sensor/sbgecom.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data. - [VectorNav](../sensor/vectornav.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data. ## PX4 Firmware diff --git a/docs/en/sensor/sbgecom.md b/docs/en/sensor/sbgecom.md new file mode 100644 index 0000000000..673856387c --- /dev/null +++ b/docs/en/sensor/sbgecom.md @@ -0,0 +1,150 @@ +# SBG Systems INS/AHRS (Pulse, Ellipse, etc.) + +[SBG-Systems](https://www.sbg-systems.com/) designs, manufactures, and support an extensive range of state-of-the-art inertial sensors such as Inertial Measurement Units (IMU), Attitude and Heading Reference Systems (AHRS), Inertial Navigation Systems with embedded GNSS (INS/GNSS), and so on. + +PX4 supports [all SBG Systems products](https://www.sbg-systems.com/products/) and can use these as an [external INS](../sensor/inertial_navigation_systems.md) (bypassing/replacing the EKF2 estimator), or as a source of raw sensor data provided to the navigation estimator. + +![Ellipse](../../assets/hardware/sensors/inertial/ellipse-inertial-navigation-system.png) + +## Overview + +SBG Systems products provide a range of benefits to PX4 users and can be integrated for: + +- Higher accuracy heading, pitch, and roll estimates +- More robust and reliable GNSS positioning +- Improved positioning and attitude performance in GNSS-contested environments +- Performance under challenging dynamic conditions (e.g. catapult launches, VTOL operations, high-g or high angular rate operations) + +The sbgECom PX4 driver is streamlined to provide a simple plug-and-play architecture, removing engineering obstacles and allowing the acceleration of the design, development, and launch of platforms to keep pace with the rapid rate of innovation. + +The driver supports [all SBG Systems products](https://www.sbg-systems.com/products/). +In particular the following systems are recommended: + +- **Pulse:** Recommended for fixed-wing systems without hovering, where static heading is not necessary. +- **Ellipse:** Recommended for multicopter systems where hovering and low dynamics requires the use of static heading. + +## Where to Buy + +SBG Systems solutions are available directly from [MySBG](https://my.sbg-systems.com) (FR) or through their Global Sales Representatives. For more information on their solutions or for international orders, please contact contact@sbg-systems.com. + +## Hardware Setup + +### Wiring + +Connect any unused flight controller serial interface, such as a spare `GPS` or `TELEM` port, to the SBG Systems product MAIN port (required by PX4). + +### Mounting + +The SBG Systems product sensor can be mounted in any orientation, in any position on the vehicle, without regard to center of gravity. +All SBG Systems product sensors default to a coordinate system of x-forward, y-right, and z-down, making the default mounting as connector-back, base down. +This can be changed to any rigid rotation using the sbgECom Reference Frame Rotation register. + +If using a GNSS-enabled product, the GNSS antenna must be mounted rigidly with respect to the inertial sensor and with an unobstructed sky view. If using a dual-GNSS-enabled product (Ellipse-D), the secondary antenna must be mounted rigidly with respect to the primary antenna and the inertial sensor with an unobstructed sky view. + +For more mounting and configuration requirements and recommendations, see the relevant [SBG SUPPORT CENTER](https://support.sbg-systems.com/sc). + +## Firmware Configuration + +### PX4 Configuration + +To use the sbgECom driver: + +1. Include the module in firmware in the [kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) by setting the kconfig variables: `CONFIG_DRIVERS_INS_SBGECOM` or `CONFIG_COMMON_INS`. +2. [Set the parameter](../advanced_config/parameters.md) [SENS_SBG_CFG](../advanced_config/parameter_reference.md#SENS_SBG_CFG) to the hardware port connected to the SBG Systems product (for more information see [Serial Port Configuration](../peripherals/serial_configuration.md)). + + ::: warning + Disable or change port of other sensors that are using the same one, for example [GPS_1_CONFIG](../advanced_config/parameter_reference.md#GPS_1_CONFIG) if using GPS1 port. + ::: + +3. Set [SBG_BAUDRATE](../advanced_config/parameter_reference.md#SBG_BAUDRATE) to the desired default baudrate value. +4. Allow the sbgECom driver to initialize by restarting PX4. +5. Configure driver to provide IMU data, GNSS data and INS : + + 1. Set [SBG_MODE](../advanced_config/parameter_reference.md#SBG_MODE) to the desired mode. + 2. Make sensor module select sensors by enabling [SENS_IMU_MODE](../advanced_config/parameter_reference.md#SENS_IMU_MODE). + 3. Prioritize SBG Systems sensors using [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO), [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO), [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO), [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO), where _n_ is the instance number of the IMU component (0, 1, etc.). + + ::: tip + In most cases the external IMU (SBG) is the highest-numbered. + You can get a list of the IMU components available using [`uorb top -1`](../middleware/uorb.md#uorb-top-command), you can differentiate between them using the [`listener`](../modules/modules_command.md#listener) command and looking through the data, or just the rates. + + Alternatively, you can check [CAL_GYROn_ID](../advanced_config/parameter_reference.md#CAL_GYRO0_ID) to see the device id. + The priority is 0-255, where 0 is entirely disabled and 255 is highest priority. + ::: + + ::: warning + When configuring both SBG Systems and Pixhawk sensors to have non-zero priority, if the selected sensor is errored (timeout), it can change during operation without being notified. + In this case, MAVLink messages will be updated with the newly selected sensor. + + If you don't want to have this fallback mechanism, you must disable unwanted sensors. + ::: + + 4. If using the sbgECom as an INS, disable EKF2 using [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN). + +6. Restart PX4. + +Once enabled, the module will be detected on boot. +IMU data should be published at 200Hz. + +## SBG Systems Configuration + +All High Performance and Ellipse 3.0 and higher SBG Systems INS can be configured directly from PX4 firmware: + +1. Enable [SBG_CONFIGURATION_EN](../advanced_config/parameter_reference.md#SBG_CONFIGURATION_EN) +2. Provide a JSON file `sbg_settings.json` containing SBG Systems INS settings to be applied in your PX4 board `extras` directory (ex: `boards/px4/fmu-v5/extras`). The settings JSON file will be installed in `/etc/extras/sbg_settings.json` on the board. + + ::: tip + The settings can be retrieved using [sbgEComAPI](https://github.com/SBG-Systems/sbgECom/tree/main/tools/sbgEComApi) or [sbgInsRestApi](https://developer.sbg-systems.com/sbgInsRestApi/1.3/#tag/Settings) and then modified as a JSON file. + ::: + + ::: tip + The settings file can be provided in the SD card in q`/fs/microsd/etc/extras/sbg_settings.json` to avoid rebuilding a new firmware to change JSON settings file. + ::: + +3. For testing purpose, it's also possible to modify SBG Systems INS settings on the fly: + + - By passing a JSON file path as argument when starting sbgecom driver (ex: `sbgecom start -f /fs/microsd/new_sbg_settings.json`) + - By passing a JSON string as argument when starting sbgecom driver: (ex: `sbgecom start -s {"output":{"comA":{"messages":{"airData":"onChange"}}}}`) + +For older Ellipse SBG Systems INS or to configure any SBG Systems INS directly, all commands and registers can be found in the [SBG SUPPORT CENTER](https://support.sbg-systems.com/sc). + +::: warning +If the baudrate of the serial port on the INS product (used to communicate with PX4) is changed, the parameter [SBG_BAUDRATE](../advanced_config/parameter_reference.md#SBG_BAUDRATE) must be changed to match. +::: + +## Published Data + +Upon initialization, the driver should print the following information to console (printed using `PX4_INFO`) + +- Unit model number +- Unit hardware version +- Unit serial number +- Unit firmware number + +This should be accessible using the [`dmesg`](../modules/modules_system.md#dmesg) command. + +The sbgECom driver always publishes the unit's data to the following uORB topics: + +- [sensor_accel](../msg_docs/SensorAccel.md) +- [sensor_gyro](../msg_docs/SensorGyro.md) +- [sensor_mag](../msg_docs/SensorMag.md) + +if configured as a GNSS, publishes: + +- [sensor_gps](../msg_docs/SensorGps.md) + +and, if configured as an INS, publishes: + +- [estimator_status](../msg_docs/EstimatorStatus.md) +- [vehicle_local_position](../msg_docs/VehicleLocalPosition.md) +- [vehicle_global_positon](../msg_docs/VehicleGlobalPosition.md) +- [vehicle_attitude](../msg_docs/VehicleAttitude.md) + +::: tip +Published topics can be viewed using the `listener` command. +::: + +## Hardware Specifications + +- [Product Briefs](https://www.sbg-systems.com/products/) +- [Datasheets](https://www.sbg-systems.com/contact/#products) diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h index 32eadbb067..147eb049d6 100644 --- a/src/drivers/drv_sensor.h +++ b/src/drivers/drv_sensor.h @@ -256,6 +256,8 @@ #define DRV_INS_DEVTYPE_MICROSTRAIN 0xEA #define DRV_INS_DEVTYPE_BAHRS 0xEB +#define DRV_INS_DEVTYPE_SBG 0xEC + #define DRV_DEVTYPE_UNUSED 0xff #endif /* _DRV_SENSOR_H */ diff --git a/src/drivers/ins/Kconfig b/src/drivers/ins/Kconfig index 70db3d9fcb..8b99c3a215 100644 --- a/src/drivers/ins/Kconfig +++ b/src/drivers/ins/Kconfig @@ -5,7 +5,8 @@ menu "Inertial Navigation Systems (INS)" select DRIVERS_INS_VECTORNAV select DRIVERS_INS_ILABS select DRIVERS_INS_MICROSTRAIN - select DRIVERS_INS_EULERNAV_BAHRS + select DRIVERS_INS_EULERNAV_BAHRS + select DRIVERS_INS_SBGECOM ---help--- Enable default set of INS sensors rsource "*/Kconfig" diff --git a/src/drivers/ins/sbgecom/CMakeLists.txt b/src/drivers/ins/sbgecom/CMakeLists.txt new file mode 100644 index 0000000000..e4c8362da3 --- /dev/null +++ b/src/drivers/ins/sbgecom/CMakeLists.txt @@ -0,0 +1,73 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +add_compile_definitions(SBG_CONFIG_LOG_MAX_SIZE=128) + +set(SBGECOM_DIR ${CMAKE_CURRENT_SOURCE_DIR}/sbgECom) +px4_add_git_submodule(TARGET git_sbgECom PATH ${SBGECOM_DIR}) + +add_subdirectory(sbgECom) + +add_dependencies(sbgECom prebuild_targets) + +target_compile_options(sbgECom + PRIVATE + -Wno-format + -Wno-format-security + -Wno-bad-function-cast + -Wno-double-promotion + -Wno-type-limits + -Wno-maybe-uninitialized + -Wno-float-equal +) + +if("${PX4_PLATFORM}" MATCHES "nuttx") + target_compile_definitions(sbgECom PUBLIC __NUTTX__) +endif() + + +px4_add_module( + MODULE drivers__ins__sbgecom + MAIN sbgecom + INCLUDES + sbgECom/common + sbgECom/src + COMPILE_FLAGS + SRCS + sbgecom.cpp + sbgecom.hpp + MODULE_CONFIG + module.yaml + DEPENDS + sbgECom + ) diff --git a/src/drivers/ins/sbgecom/Kconfig b/src/drivers/ins/sbgecom/Kconfig new file mode 100644 index 0000000000..2569367c7a --- /dev/null +++ b/src/drivers/ins/sbgecom/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_INS_SBGECOM + bool "sbgecom" + default n + ---help--- + Enable support for sbgecom diff --git a/src/drivers/ins/sbgecom/module.yaml b/src/drivers/ins/sbgecom/module.yaml new file mode 100644 index 0000000000..c32971e183 --- /dev/null +++ b/src/drivers/ins/sbgecom/module.yaml @@ -0,0 +1,50 @@ +module_name: sbgECom + +serial_config: + - command: sbgecom start -d ${SERIAL_DEV} + port_config_param: + name: SENS_SBG_CFG + group: Sensors + +parameters: + - group: Sensors + definitions: + SBG_MODE: + description: + short: sbgECom driver mode + long: | + Modes available for sbgECom driver. + In Sensors Only mode, use external IMU and magnetometer. + In GNSS mode, use external GNSS in addition to sensors only mode. + In INS mode, use external Kalman Filter in addition to GNSS mode. + + In INS mode, requires EKF2_EN 0. Keeping both enabled + can lead to an unexpected behavior and vehicle instability. + category: System + type: enum + values: + 0: Sensors Only + 1: GNSS + 2: INS (default) + default: 2 + SBG_BAUDRATE: + description: + short: sbgECom driver baudrate + long: | + Baudrate used by default for serial communication between PX4 + and SBG Systems INS through sbgECom driver. + category: System + type: int32 + min: 9600 + max: 921600 + default: 921600 + reboot_required: true + SBG_CONFIGURE_EN: + description: + short: sbgECom driver INS configuration enable + long: | + Enable SBG Systems INS configuration through sbgECom driver + on start. + category: System + type: boolean + default: 0 diff --git a/src/drivers/ins/sbgecom/sbgECom b/src/drivers/ins/sbgecom/sbgECom new file mode 160000 index 0000000000..80b121c771 --- /dev/null +++ b/src/drivers/ins/sbgecom/sbgECom @@ -0,0 +1 @@ +Subproject commit 80b121c7714083cc4868c0fdb8c41623c7ef9c93 diff --git a/src/drivers/ins/sbgecom/sbgecom.cpp b/src/drivers/ins/sbgecom/sbgecom.cpp new file mode 100644 index 0000000000..17c422839d --- /dev/null +++ b/src/drivers/ins/sbgecom/sbgecom.cpp @@ -0,0 +1,1125 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file sbgecom.cpp + * Driver for the SBG Systems products + * + * @author SBG Systems + */ + +#include "sbgecom.hpp" + +#include +#include + +#include +#include +#include + +#define DEFAULT_DEVNAME "/dev/ttyS0" + +#define SBG_MODE_SENSOR 0 +#define SBG_MODE_GNSS 1 +#define SBG_MODE_INS 2 + +#define SBG_ESTIMATOR_ATTITUDE (1 << 0) ///< 0 - attitude estimate is good +#define SBG_ESTIMATOR_VELOCITY_HORIZ (1 << 1) ///< 1 - horizontal velocity estimate is good +#define SBG_ESTIMATOR_VELOCITY_VERT (1 << 2) ///< 2 - vertical velocity estimate is good +#define SBG_ESTIMATOR_POS_HORIZ_REL (1 << 3) ///< 3 - horizontal position (relative) estimate is good +#define SBG_ESTIMATOR_POS_HORIZ_ABS (1 << 4) ///< 4 - horizontal position (absolute) estimate is good +#define SBG_ESTIMATOR_POS_VERT_ABS (1 << 5) ///< 5 - vertical position (absolute) estimate is good +#define SBG_ESTIMATOR_POS_VERT_AGL (1 << 6) ///< 6 - vertical position (above ground) estimate is good +#define SBG_ESTIMATOR_CONST_POS_MODE (1 << 7) ///< 7 - EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) +#define SBG_ESTIMATOR_PRED_POS_HORIZ_REL (1 << 8) ///< 8 - EKF has sufficient data to enter a mode that will provide a (relative) position estimate +#define SBG_ESTIMATOR_PRED_POS_HORIZ_ABS (1 << 9) ///< 9 - EKF has sufficient data to enter a mode that will provide a (absolute) position estimate +#define SBG_ESTIMATOR_GPS_GLITCH (1 << 10) ///< 10 - EKF has detected a GPS glitch +#define SBG_ESTIMATOR_ACCEL_ERROR (1 << 11) ///< 11 - EKF has detected bad accelerometer data + +#define DEFAULT_CONFIG_PATH "/etc/extras/sbg_settings.json" +#define OVERRIDE_CONFIG_PATH CONFIG_BOARD_ROOT_PATH DEFAULT_CONFIG_PATH +#define NEED_REBOOT_STR "\"needReboot\":true" + +using matrix::Vector2f; + +SbgEcom::SbgEcom(const char *device_name, uint32_t baudrate, const char *config_file, const char *config_string): + ModuleParams(nullptr), + ScheduledWorkItem(MODULE_NAME, px4::serial_port_to_wq(device_name)), + _baudrate(baudrate), + _config_file(config_file), + _config_string(config_string) +{ + if (device_name) { + strncpy(_device_name, device_name, sizeof(_device_name) - 1); + _device_name[sizeof(_device_name) - 1] = '\0'; + } + + device::Device::DeviceId device_id{}; + device_id.devid_s.bus_type = device::Device::DeviceBusType_SERIAL; + device_id.devid_s.devtype = DRV_INS_DEVTYPE_SBG; + + set_device_id(device_id.devid); + _px4_accel.set_device_id(device_id.devid); + _px4_gyro.set_device_id(device_id.devid); + _px4_mag.set_device_id(device_id.devid); +} + +SbgEcom::~SbgEcom() +{ + sbgEComClose(&_com_handle); + sbgInterfaceDestroy(&_sbg_interface); + + perf_free(_accel_pub_interval_perf); + perf_free(_gyro_pub_interval_perf); + perf_free(_mag_pub_interval_perf); + perf_free(_gnss_pub_interval_perf); + + perf_free(_attitude_pub_interval_perf); + perf_free(_local_position_pub_interval_perf); + perf_free(_global_position_pub_interval_perf); +} + +void SbgEcom::set_device_id(uint32_t device_id) +{ + _device_id = device_id; +} + +uint32_t SbgEcom::get_device_id() +{ + return _device_id; +} + +SbgErrorCode SbgEcom::getAndPrintProductInfo(SbgEComHandle *handle) +{ + SbgErrorCode error_code; + SbgEComDeviceInfo device_info; + + assert(handle); + + error_code = sbgEComCmdGetInfo(handle, &device_info); + + if (error_code == SBG_NO_ERROR) { + char calib_version_str[32]; + char hw_revision_str[32]; + char fmw_version_str[32]; + + sbgVersionToStringEncoded(device_info.calibationRev, calib_version_str, sizeof(calib_version_str)); + sbgVersionToStringEncoded(device_info.hardwareRev, hw_revision_str, sizeof(hw_revision_str)); + sbgVersionToStringEncoded(device_info.firmwareRev, fmw_version_str, sizeof(fmw_version_str)); + + PX4_INFO(" Serial Number: %09" PRIu32, device_info.serialNumber); + PX4_INFO(" Product Code: %s", device_info.productCode); + PX4_INFO(" Hardware Revision: %s", hw_revision_str); + PX4_INFO(" Firmware Version: %s", fmw_version_str); + PX4_INFO(" Calib. Version: %s", calib_version_str); + + } else { + SBG_LOG_WARNING(error_code, "Unable to retrieve device information"); + } + + return error_code; +} + +void SbgEcom::printLogCallBack(const char *file_name, const char *function_name, uint32_t line, const char *category, + SbgDebugLogType log_type, SbgErrorCode error_code, const char *message) +{ + const char *base_name; + + assert(file_name); + assert(function_name); + assert(category); + assert(message); + + base_name = strrchr(file_name, '/'); + + if (!base_name) { + base_name = file_name; + + } else { + base_name++; + } + + switch (log_type) { + case SBG_DEBUG_LOG_TYPE_DEBUG: + PX4_DEBUG("%s:%" PRIu32 ": %s: %s", base_name, line, function_name, message); + break; + + case SBG_DEBUG_LOG_TYPE_INFO: + PX4_INFO("%s:%" PRIu32 ": %s: %s", base_name, line, function_name, message); + break; + + case SBG_DEBUG_LOG_TYPE_WARNING: + PX4_WARN("%s:%" PRIu32 ": %s: err:%s: %s", base_name, line, function_name, sbgErrorCodeToString(error_code), message); + break; + + case SBG_DEBUG_LOG_TYPE_ERROR: + PX4_ERR("%s:%" PRIu32 ": %s: err:%s: %s", base_name, line, function_name, sbgErrorCodeToString(error_code), message); + break; + } +} + +void SbgEcom::handleLogImuShort(const SbgEComLogUnion *ref_sbg_data, void *user_arg) +{ + assert(ref_sbg_data); + assert(user_arg); + + SbgEcom *instance = static_cast(user_arg); + + const float temperature = sbgEComLogImuShortGetTemperature(&ref_sbg_data->imuShort); + + // publish sensor_accel + instance->_px4_accel.update(hrt_absolute_time(), + sbgEComLogImuShortGetDeltaVelocity(&ref_sbg_data->imuShort, 0), + sbgEComLogImuShortGetDeltaVelocity(&ref_sbg_data->imuShort, 1), + sbgEComLogImuShortGetDeltaVelocity(&ref_sbg_data->imuShort, 2)); + instance->_px4_accel.set_error_count(perf_event_count(instance->_comms_errors)); + instance->_px4_accel.set_temperature(temperature); + perf_count(instance->_accel_pub_interval_perf); + + // publish sensor_gyro + instance->_px4_gyro.update(hrt_absolute_time(), + sbgEComLogImuShortGetDeltaAngle(&ref_sbg_data->imuShort, 0), + sbgEComLogImuShortGetDeltaAngle(&ref_sbg_data->imuShort, 1), + sbgEComLogImuShortGetDeltaAngle(&ref_sbg_data->imuShort, 2)); + instance->_px4_gyro.set_error_count(perf_event_count(instance->_comms_errors)); + instance->_px4_gyro.set_temperature(temperature); + perf_count(instance->_gyro_pub_interval_perf); +} + +void SbgEcom::handleLogMag(const SbgEComLogUnion *ref_sbg_data, void *user_arg) +{ + assert(ref_sbg_data); + assert(user_arg); + + SbgEcom *instance = static_cast(user_arg); + + // publish sensor_mag + instance->_px4_mag.update(ref_sbg_data->magData.timeStamp, + (ref_sbg_data->magData.magnetometers[0]), + (ref_sbg_data->magData.magnetometers[1]), + (ref_sbg_data->magData.magnetometers[2])); + instance->_px4_mag.set_error_count(perf_event_count(instance->_comms_errors)); + perf_count(instance->_mag_pub_interval_perf); +} + +void SbgEcom::updateEstimatorStatus(uint32_t ekf_status, estimator_status_s *estimator_status) +{ + SbgEComSolutionMode ekf_nav_status = sbgEComLogEkfGetSolutionMode(ekf_status); + + estimator_status->solution_status_flags |= ((ekf_status & SBG_ECOM_SOL_ATTITUDE_VALID) + && (ekf_status & SBG_ECOM_SOL_HEADING_VALID)) ? SBG_ESTIMATOR_ATTITUDE : 0; + estimator_status->solution_status_flags |= (ekf_status & SBG_ECOM_SOL_VELOCITY_VALID) ? SBG_ESTIMATOR_VELOCITY_HORIZ : + 0; + estimator_status->solution_status_flags |= (ekf_status & SBG_ECOM_SOL_VELOCITY_VALID) ? SBG_ESTIMATOR_VELOCITY_VERT : 0; + estimator_status->solution_status_flags |= (ekf_status & SBG_ECOM_SOL_POSITION_VALID) ? SBG_ESTIMATOR_POS_HORIZ_REL : 0; + estimator_status->solution_status_flags |= (ekf_status & SBG_ECOM_SOL_POSITION_VALID) ? SBG_ESTIMATOR_POS_HORIZ_ABS : 0; + estimator_status->solution_status_flags |= (ekf_status & SBG_ECOM_SOL_POSITION_VALID) ? SBG_ESTIMATOR_POS_VERT_ABS : 0; + estimator_status->solution_status_flags |= (ekf_status & SBG_ECOM_SOL_POSITION_VALID) ? SBG_ESTIMATOR_POS_VERT_AGL : 0; + estimator_status->solution_status_flags |= (ekf_status & SBG_ECOM_SOL_ZUPT_USED) ? SBG_ESTIMATOR_CONST_POS_MODE : 0; + + estimator_status->solution_status_flags |= (ekf_nav_status == SBG_ECOM_SOL_MODE_NAV_POSITION) ? + SBG_ESTIMATOR_PRED_POS_HORIZ_REL : 0; + estimator_status->solution_status_flags |= (ekf_nav_status == SBG_ECOM_SOL_MODE_NAV_POSITION) ? + SBG_ESTIMATOR_PRED_POS_HORIZ_ABS : 0; +} + +void SbgEcom::handleLogEkfQuat(const SbgEComLogUnion *ref_sbg_data, void *user_arg) +{ + const hrt_abstime time_now_us = hrt_absolute_time(); + + assert(ref_sbg_data); + assert(user_arg); + + SbgEcom *instance = static_cast(user_arg); + + // publish estimator_status + estimator_status_s estimator_status{}; + estimator_status.timestamp = time_now_us; + estimator_status.timestamp_sample = ref_sbg_data->ekfQuatData.timeStamp; + estimator_status.accel_device_id = instance->get_device_id(); + estimator_status.gyro_device_id = instance->get_device_id(); + estimator_status.mag_device_id = instance->get_device_id(); + + instance->updateEstimatorStatus(ref_sbg_data->ekfQuatData.status, &estimator_status); + + instance->_estimator_status_pub.publish(estimator_status); + + // publish attitude + vehicle_attitude_s attitude{}; + + attitude.timestamp = time_now_us; + attitude.timestamp_sample = ref_sbg_data->ekfQuatData.timeStamp; + + attitude.q[0] = ref_sbg_data->ekfQuatData.quaternion[0]; + attitude.q[1] = ref_sbg_data->ekfQuatData.quaternion[1]; + attitude.q[2] = ref_sbg_data->ekfQuatData.quaternion[2]; + attitude.q[3] = ref_sbg_data->ekfQuatData.quaternion[3]; + + instance->_attitude_pub.publish(attitude); + perf_count(instance->_attitude_pub_interval_perf); + + matrix::Quatf q{attitude.q}; + instance->_heading = matrix::Eulerf{q}.psi(); +} + +void SbgEcom::handleLogEkfNav(const SbgEComLogUnion *ref_sbg_data, void *user_arg) +{ + const hrt_abstime time_now_us = hrt_absolute_time(); + + assert(ref_sbg_data); + assert(user_arg); + + SbgEcom *instance = static_cast(user_arg); + + // publish estimator_status + estimator_status_s estimator_status{}; + estimator_status.timestamp = time_now_us; + estimator_status.timestamp_sample = ref_sbg_data->ekfNavData.timeStamp; + + instance->updateEstimatorStatus(ref_sbg_data->ekfNavData.status, &estimator_status); + + instance->_estimator_status_pub.publish(estimator_status); + + SbgEComSolutionMode ekf_nav_status = sbgEComLogEkfGetSolutionMode(ref_sbg_data->ekfNavData.status); + + // don't publish local and global positions if not reliable + if (ekf_nav_status != SBG_ECOM_SOL_MODE_NAV_POSITION) { + return; + } + + const double latitude = ref_sbg_data->ekfNavData.position[0]; + const double longitude = ref_sbg_data->ekfNavData.position[1]; + const double altitude = ref_sbg_data->ekfNavData.position[2]; + + const double north_velocity = ref_sbg_data->ekfNavData.velocity[0]; + const double east_velocity = ref_sbg_data->ekfNavData.velocity[1]; + const double down_velocity = ref_sbg_data->ekfNavData.velocity[2]; + + if (!instance->_pos_ref.isInitialized()) { + instance->_pos_ref.initReference(latitude, longitude, time_now_us); + instance->_gps_alt_ref = altitude; + } + + const Vector2f pos_ned = instance->_pos_ref.project(latitude, longitude); + + // publish local_position + vehicle_local_position_s local_position{}; + + local_position.timestamp = time_now_us; + local_position.timestamp_sample = ref_sbg_data->ekfNavData.timeStamp; + + local_position.xy_valid = math::isFinite(latitude) && math::isFinite(longitude); + local_position.z_valid = math::isFinite(altitude); + local_position.v_xy_valid = math::isFinite(north_velocity) && math::isFinite(east_velocity); + local_position.v_z_valid = math::isFinite(down_velocity); + + local_position.x = pos_ned(0); + local_position.y = pos_ned(1); + local_position.z = -(altitude - instance->_gps_alt_ref); + + local_position.vx = north_velocity; + local_position.vy = east_velocity; + local_position.vz = down_velocity; + + local_position.heading = instance->_heading; + local_position.heading_good_for_control = true;; + + if (instance->_pos_ref.isInitialized()) { + local_position.xy_global = true; + local_position.z_global = true; + local_position.ref_timestamp = instance->_pos_ref.getProjectionReferenceTimestamp(); + local_position.ref_lat = instance->_pos_ref.getProjectionReferenceLat(); + local_position.ref_lon = instance->_pos_ref.getProjectionReferenceLon(); + local_position.ref_alt = instance->_gps_alt_ref; + } + + local_position.dist_bottom_valid = false; + + local_position.eph = sqrt(pow(ref_sbg_data->ekfNavData.positionStdDev[0], 2) + + pow(ref_sbg_data->ekfNavData.positionStdDev[1], 2)); + local_position.epv = ref_sbg_data->ekfNavData.positionStdDev[2]; + local_position.evh = sqrt(pow(ref_sbg_data->ekfNavData.velocityStdDev[0], 2) + + pow(ref_sbg_data->ekfNavData.velocityStdDev[1], 2)); + local_position.evv = ref_sbg_data->ekfNavData.velocityStdDev[2]; + + + local_position.dead_reckoning = false; + + local_position.vxy_max = INFINITY; + local_position.vz_max = INFINITY; + local_position.hagl_min = INFINITY; + local_position.hagl_max_xy = INFINITY; + local_position.hagl_max_z = INFINITY; + + instance->_local_position_pub.publish(local_position); + perf_count(instance->_local_position_pub_interval_perf); + + // publish global_position + vehicle_global_position_s global_position{}; + + global_position.timestamp = time_now_us; + global_position.timestamp_sample = ref_sbg_data->ekfNavData.timeStamp; + + global_position.lat = latitude; + global_position.lon = longitude; + global_position.alt = altitude; + global_position.alt_ellipsoid = ref_sbg_data->ekfNavData.undulation; + + global_position.lat_lon_valid = math::isFinite(latitude) && math::isFinite(longitude); + global_position.alt_valid = math::isFinite(altitude); + + global_position.eph = sqrt(pow(ref_sbg_data->ekfNavData.positionStdDev[0], 2) + + pow(ref_sbg_data->ekfNavData.positionStdDev[1], 2)); + global_position.epv = ref_sbg_data->ekfNavData.positionStdDev[2]; + + global_position.dead_reckoning = false; + + instance->_global_position_pub.publish(global_position); + perf_count(instance->_global_position_pub_interval_perf); +} + +void SbgEcom::handleLogGnssPosVelHdt(SbgEComMsgId msg, const SbgEComLogUnion *ref_sbg_data, void *user_arg) +{ + const hrt_abstime time_now_us = hrt_absolute_time(); + uint8_t type; + uint8_t state; + uint8_t spoofing; + + assert(msg); + assert(ref_sbg_data); + assert(user_arg); + + SbgEcom *instance = static_cast(user_arg); + GnssData *gnss_data = &instance->gnss_data; + + // Store the data based on its type + switch (msg) { + case SBG_ECOM_LOG_GPS1_POS: + gnss_data->gps_pos = ref_sbg_data->gpsPosData; + gnss_data->pos_received = true; + gnss_data->pos_timestamp = time_now_us; + break; + + case SBG_ECOM_LOG_GPS1_VEL: + gnss_data->gps_vel = ref_sbg_data->gpsVelData; + gnss_data->vel_received = true; + gnss_data->vel_timestamp = time_now_us; + break; + + case SBG_ECOM_LOG_GPS1_HDT: + gnss_data->gps_hdt = ref_sbg_data->gpsHdtData; + gnss_data->hdt_received = true; + gnss_data->hdt_timestamp = time_now_us; + break; + } + + if (gnss_data->pos_received && gnss_data->vel_received && gnss_data->hdt_received) { + // publish sensor_gps + sensor_gps_s sensor_gps{}; + + sensor_gps.timestamp = time_now_us; + sensor_gps.timestamp_sample = gnss_data->gps_pos.timeStamp; + + sensor_gps.device_id = instance->get_device_id(); + + sensor_gps.latitude_deg = gnss_data->gps_pos.latitude; + sensor_gps.longitude_deg = gnss_data->gps_pos.longitude; + sensor_gps.altitude_msl_m = gnss_data->gps_pos.altitude; + sensor_gps.altitude_ellipsoid_m = gnss_data->gps_pos.undulation; + + sensor_gps.s_variance_m_s = sqrt(pow(gnss_data->gps_vel.velocityAcc[0], 2) + + pow(gnss_data->gps_vel.velocityAcc[1], 2) + + pow(gnss_data->gps_vel.velocityAcc[2], 2)); + sensor_gps.c_variance_rad = math::radians(gnss_data->gps_vel.courseAcc); + + type = sbgEComLogGnssPosGetType(&gnss_data->gps_pos); + + switch (type) { + case SBG_ECOM_GNSS_POS_TYPE_NO_SOLUTION: + sensor_gps.fix_type = 0; + break; + + case SBG_ECOM_GNSS_POS_TYPE_PSRDIFF: + case SBG_ECOM_GNSS_POS_TYPE_SBAS: + sensor_gps.fix_type = 4; + break; + + case SBG_ECOM_GNSS_POS_TYPE_RTK_FLOAT: + sensor_gps.fix_type = 5; + break; + + case SBG_ECOM_GNSS_POS_TYPE_RTK_INT: + sensor_gps.fix_type = 6; + break; + + case SBG_ECOM_GNSS_POS_TYPE_FIXED: + sensor_gps.fix_type = 7; + break; + + case SBG_ECOM_GNSS_POS_TYPE_PPP_FLOAT: + case SBG_ECOM_GNSS_POS_TYPE_PPP_INT: + sensor_gps.fix_type = 8; + break; + + default: + sensor_gps.fix_type = 3; + break; + } + + sensor_gps.eph = sqrt(pow(gnss_data->gps_pos.longitudeAccuracy, 2) + + pow(gnss_data->gps_pos.latitudeAccuracy, 2)); + sensor_gps.epv = gnss_data->gps_pos.altitudeAccuracy; + + state = sbgEComLogGnssPosGetIfmStatus(&gnss_data->gps_pos); + + switch (state) { + case SBG_ECOM_GNSS_IFM_STATUS_UNKNOWN: + sensor_gps.jamming_state = 0; + break; + + case SBG_ECOM_GNSS_IFM_STATUS_CLEAN: + sensor_gps.jamming_state = 1; + break; + + case SBG_ECOM_GNSS_IFM_STATUS_MITIGATED: + sensor_gps.jamming_state = 2; + break; + + case SBG_ECOM_GNSS_IFM_STATUS_CRITICAL: + sensor_gps.jamming_state = 3; + break; + } + + spoofing = sbgEComLogGnssPosGetSpoofingStatus(&gnss_data->gps_pos); + + switch (spoofing) { + case SBG_ECOM_GNSS_SPOOFING_STATUS_UNKNOWN: + sensor_gps.spoofing_state = 0; + break; + + case SBG_ECOM_GNSS_SPOOFING_STATUS_CLEAN: + sensor_gps.spoofing_state = 1; + break; + + case SBG_ECOM_GNSS_SPOOFING_STATUS_SINGLE: + sensor_gps.spoofing_state = 2; + break; + + case SBG_ECOM_GNSS_SPOOFING_STATUS_MULTIPLE: + sensor_gps.spoofing_state = 3; + break; + } + + sensor_gps.vel_m_s = sqrt(pow(gnss_data->gps_vel.velocity[0], 2) + + pow(gnss_data->gps_vel.velocity[1], 2) + + pow(gnss_data->gps_vel.velocity[2], 2)); + sensor_gps.vel_n_m_s = gnss_data->gps_vel.velocity[0]; + sensor_gps.vel_e_m_s = gnss_data->gps_vel.velocity[1]; + sensor_gps.vel_d_m_s = gnss_data->gps_vel.velocity[2]; + sensor_gps.vel_ned_valid = true; + + sensor_gps.cog_rad = math::radians(gnss_data->gps_vel.course); + + sensor_gps.timestamp_time_relative = sensor_gps.timestamp_sample - time_now_us; + sensor_gps.time_utc_usec = 0; + + sensor_gps.satellites_used = gnss_data->gps_pos.numSvUsed; + + sensor_gps.heading = math::radians(gnss_data->gps_hdt.heading); + sensor_gps.heading_offset = math::radians(gnss_data->gps_hdt.pitch); + sensor_gps.heading_accuracy = math::radians(gnss_data->gps_hdt.headingAccuracy); + + // Check timestamp synchronization + const hrt_abstime max_time_diff = 1000000; // Maximum allowed time difference in microseconds (e.g., 1 second) + hrt_abstime pos_time = gnss_data->pos_timestamp; + hrt_abstime vel_time = gnss_data->vel_timestamp; + hrt_abstime hdt_time = gnss_data->hdt_timestamp; + + if (((time_now_us - pos_time) < max_time_diff) && + ((time_now_us - vel_time) < max_time_diff) && + ((time_now_us - hdt_time) < max_time_diff) && + ((pos_time - vel_time) < max_time_diff) && + ((pos_time - hdt_time) < max_time_diff) && + ((vel_time - hdt_time) < max_time_diff)) { + instance->_sensor_gps_pub.publish(sensor_gps); + perf_count(instance->_gnss_pub_interval_perf); + } + + // Reset the flags and timestamps + gnss_data->pos_received = false; + gnss_data->vel_received = false; + gnss_data->hdt_received = false; + + gnss_data->pos_timestamp = 0; + gnss_data->vel_timestamp = 0; + gnss_data->hdt_timestamp = 0; + } +} + +SbgErrorCode SbgEcom::onLogReceived(SbgEComHandle *handle, SbgEComClass msg_class, SbgEComMsgId msg, + const SbgEComLogUnion *ref_sbg_data, void *user_arg) +{ + SBG_UNUSED_PARAMETER(handle); + + assert(msg_class); + assert(msg); + assert(ref_sbg_data); + assert(user_arg); + + SbgEcom *instance = static_cast(user_arg); + + if (msg_class == SBG_ECOM_CLASS_LOG_ECOM_0) { + int32_t mode; + int32_t ekf2_en; + param_get(param_find("SBG_MODE"), &mode); + param_get(param_find("EKF2_EN"), &ekf2_en); + + bool ekf_failure = (ekf2_en && mode == SBG_MODE_INS); + + if (!instance->_ekf_failure && ekf_failure) { + PX4_WARN("Both SBG EKF and EKF2 are configured, this can lead to an unexpected behaviour"); + instance->_ekf_failure = true; + + } else if (instance->_ekf_failure && !ekf_failure) { + PX4_INFO("EKF management is back to good"); + instance->_ekf_failure = false; + } + + switch (msg) { + case SBG_ECOM_LOG_IMU_SHORT: + instance->handleLogImuShort(ref_sbg_data, user_arg); + break; + + case SBG_ECOM_LOG_MAG: + instance->handleLogMag(ref_sbg_data, user_arg); + break; + + case SBG_ECOM_LOG_GPS1_POS: + case SBG_ECOM_LOG_GPS1_VEL: + case SBG_ECOM_LOG_GPS1_HDT: + if (mode == SBG_MODE_GNSS || mode == SBG_MODE_INS) { + instance->handleLogGnssPosVelHdt(msg, ref_sbg_data, user_arg); + } + + break; + + case SBG_ECOM_LOG_EKF_QUAT: + if (mode == SBG_MODE_INS) { + instance->handleLogEkfQuat(ref_sbg_data, user_arg); + } + + break; + + case SBG_ECOM_LOG_EKF_NAV: + if (mode == SBG_MODE_INS) { + instance->handleLogEkfNav(ref_sbg_data, user_arg); + } + + break; + + default: + PX4_DEBUG("Received unknown SBG message (class %u, id %u)", msg_class, msg); + break; + } + + } else { + PX4_INFO("Received message from unsupported SBGEcom class %u", msg_class); + } + + return SBG_NO_ERROR; +} + +SbgErrorCode SbgEcom::handleOneLog(SbgEComHandle *handle) +{ + SbgErrorCode error_code; + SbgEComProtocolPayload payload; + uint8_t received_msg; + uint8_t received_msg_class; + + assert(handle); + + sbgEComProtocolPayloadConstruct(&payload); + + perf_begin(_sample_perf); + + error_code = sbgEComProtocolReceive2(&handle->protocolHandle, &received_msg_class, &received_msg, &payload); + + if (error_code == SBG_NO_ERROR) { + if (sbgEComMsgClassIsALog((SbgEComClass)received_msg_class)) { + error_code = sbgEComLogParse((SbgEComClass)received_msg_class, (SbgEComMsgId)received_msg, + sbgEComProtocolPayloadGetBuffer(&payload), sbgEComProtocolPayloadGetSize(&payload), &_log_data); + + if (error_code == SBG_NO_ERROR) { + if (handle->pReceiveLogCallback) { + error_code = handle->pReceiveLogCallback(handle, (SbgEComClass)received_msg_class, (SbgEComMsgId)received_msg, + &_log_data, handle->pUserArg); + } + + sbgEComLogCleanup(&_log_data, (SbgEComClass)received_msg_class, (SbgEComMsgId)received_msg); + + perf_end(_sample_perf); + + } else { + perf_count(_comms_errors); + } + + } else { + PX4_ERR("command received %d", error_code); + } + + } else if (error_code != SBG_NOT_READY) { + PX4_WARN("Invalid frame received %d", error_code); + perf_count(_comms_errors); + } + + sbgEComProtocolPayloadDestroy(&payload); + + return error_code; +} + +SbgErrorCode SbgEcom::sendAirDataLog(SbgEComHandle *handle, SbgEcom *instance) +{ + SbgErrorCode error_code = SBG_NO_ERROR; + SbgEComLogAirData air_data_log; + uint8_t output_buffer[64]; + SbgStreamBuffer output_stream; + + assert(handle); + assert(instance); + + vehicle_air_data_s air_data{}; + + if (instance->_air_data_sub.update(&air_data)) { + memset(&air_data_log, 0x00, sizeof(air_data_log)); + + air_data_log.timeStamp = hrt_absolute_time() - air_data.timestamp; + air_data_log.status |= SBG_ECOM_AIR_DATA_TIME_IS_DELAY; + + air_data_log.pressureAbs = air_data.baro_pressure_pa; + air_data_log.status |= SBG_ECOM_AIR_DATA_PRESSURE_ABS_VALID; + + air_data_log.altitude = air_data.baro_alt_meter; + air_data_log.status |= SBG_ECOM_AIR_DATA_ALTITUDE_VALID; + + air_data_log.airTemperature = air_data.ambient_temperature; + air_data_log.status |= SBG_ECOM_AIR_DATA_TEMPERATURE_VALID; + + differential_pressure_s differential_pressure{}; + + if (instance->_diff_pressure_sub.update(&differential_pressure)) { + air_data_log.pressureDiff = differential_pressure.differential_pressure_pa; + air_data_log.status |= SBG_ECOM_AIR_DATA_PRESSURE_DIFF_VALID; + } + + airspeed_s airspeed{}; + + if (instance->_airspeed_sub.update(&airspeed)) { + air_data_log.trueAirspeed = airspeed.true_airspeed_m_s; + air_data_log.status |= SBG_ECOM_AIR_DATA_AIRPSEED_VALID; + } + + sbgStreamBufferInitForWrite(&output_stream, output_buffer, sizeof(output_buffer)); + + perf_begin(_write_perf); + + error_code = sbgEComLogAirDataWriteToStream(&air_data_log, &output_stream); + + if (error_code == SBG_NO_ERROR) { + error_code = sbgEComProtocolSend(&handle->protocolHandle, SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_AIR_DATA, + sbgStreamBufferGetLinkedBuffer(&output_stream), sbgStreamBufferGetLength(&output_stream)); + + if (error_code != SBG_NO_ERROR) { + PX4_ERR("Unable to send the AirData log %d", error_code); + + } else { + perf_end(_write_perf); + } + + } else { + PX4_ERR("Unable to write the AirData payload. %d", error_code); + } + } + + return error_code; +} + +SbgErrorCode SbgEcom::sendMagLog(SbgEComHandle *handle, SbgEcom *instance) +{ + SbgErrorCode error_code = SBG_NO_ERROR; + SbgEComLogMag mag_log; + uint8_t output_buffer[64]; + SbgStreamBuffer output_stream; + + assert(handle); + assert(instance); + + vehicle_magnetometer_s mag{}; + + if (instance->_mag_sub.update(&mag)) { + memset(&mag_log, 0x00, sizeof(mag_log)); + + mag_log.timeStamp = mag.timestamp_sample; + // mag_log.status = 0; // STO: don't know how to set it + + mag_log.magnetometers[0] = mag.magnetometer_ga[0]; + mag_log.magnetometers[1] = mag.magnetometer_ga[1]; + mag_log.magnetometers[2] = mag.magnetometer_ga[2]; + + sbgStreamBufferInitForWrite(&output_stream, output_buffer, sizeof(output_buffer)); + + perf_begin(_write_perf); + + error_code = sbgEComLogMagWriteToStream(&mag_log, &output_stream); + + if (error_code == SBG_NO_ERROR) { + error_code = sbgEComProtocolSend(&handle->protocolHandle, SBG_ECOM_CLASS_LOG_ECOM_0, SBG_ECOM_LOG_MAG, + sbgStreamBufferGetLinkedBuffer(&output_stream), sbgStreamBufferGetLength(&output_stream)); + + if (error_code != SBG_NO_ERROR) { + PX4_ERR("Unable to send the Mag log %d", error_code); + + } else { + perf_end(_write_perf); + } + + } else { + PX4_ERR("Unable to write the Mag payload. %d", error_code); + } + } + + return error_code; +} + +void SbgEcom::send_config(SbgEComHandle *pHandle, const char *config) +{ + SbgEComCmdApiReply reply; + + assert(pHandle); + assert(config); + + sbgEComCmdApiReplyConstruct(&reply); + + sbgEComCmdApiPost(pHandle, "/api/v1/settings", NULL, config, &reply); + + if (!sbgEComCmdApiReplySuccessful(&reply)) { + PX4_ERR("Fail to apply SBG configuration: %s", reply.pContent); + + } else { + bool need_reboot = (strstr(reply.pContent, NEED_REBOOT_STR) != NULL); + sbgEComCmdApiPost(pHandle, "/api/v1/settings/save", NULL, NULL, &reply); + + if (need_reboot) { + PX4_INFO("Reboot SBG device"); + sbgEComCmdApiPost(pHandle, "/api/v1/system/reboot", NULL, NULL, &reply); + } + } + + sbgEComCmdApiReplyDestroy(&reply); +} + +void SbgEcom::send_config_file(SbgEComHandle *pHandle, const char *file_path) +{ + int fd; + char *body = NULL; + struct stat s; + + assert(pHandle); + assert(file_path); + + fd = open(file_path, O_RDONLY); + + if (fd == -1) { + PX4_ERR("Failed to open config"); + return; + } + + fstat(fd, &s); + body = (char *)malloc(s.st_size + 1); + + if (!body) { + PX4_ERR("Failed to allocate memory (%ld) - %s", s.st_size + 1, strerror(get_errno())); + close(fd); + return; + } + + read(fd, body, s.st_size); + body[s.st_size] = '\0'; + + send_config(pHandle, body); + + free(body); + + if (close(fd) == -1) { + perror("Error closing the file"); + return; + } +} + +int SbgEcom::init() +{ + SbgErrorCode error_code; + struct termios options; + int *pSerialHandle; + + error_code = sbgInterfaceSerialCreate(&_sbg_interface, _device_name, _baudrate); + + if (error_code == SBG_NO_ERROR) { + PX4_INFO("Serial interface created successfully on port: %s, baudrate: %ld", _device_name, _baudrate); + } + + pSerialHandle = (int *)_sbg_interface.handle; + + if (tcgetattr((*pSerialHandle), &options) != -1) { + // add custom options + options.c_cflag &= CSIZE; + options.c_iflag &= ~(IXON | IXOFF | IXANY); + options.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | ICRNL | INPCK); + options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG | ECHONL | IEXTEN); + + if (tcsetattr((*pSerialHandle), TCSANOW, &options) != -1) { + error_code = sbgInterfaceFlush(&_sbg_interface, SBG_IF_FLUSH_ALL); + + } else { + error_code = SBG_ERROR; + } + + } else { + error_code = SBG_ERROR; + } + + error_code = sbgEComInit(&_com_handle, &_sbg_interface); + // Increase sbgECom timeout for the initialization + sbgEComSetCmdTrialsAndTimeOut(&_com_handle, 3, 5000); + + if (error_code == SBG_NO_ERROR) { + int32_t ins_config_enable; + param_get(param_find("SBG_CONFIGURE_EN"), &ins_config_enable); + + getAndPrintProductInfo(&_com_handle); + + if (ins_config_enable) { + if (_config_string != nullptr) { + PX4_INFO("Apply config string instead of config file"); + send_config(&_com_handle, _config_string); + + } else { + send_config_file(&_com_handle, _config_file); + } + } + + // Reset sbgECom timeout to its defaut value + sbgEComSetCmdTrialsAndTimeOut(&_com_handle, 3, SBG_ECOM_DEFAULT_CMD_TIME_OUT); + sbgEComSetReceiveLogCallback(&_com_handle, onLogReceived, this); + return PX4_OK; + + } else { + PX4_ERR("sbgECom initialization failed (%d)", error_code); + return PX4_ERROR; + } +} + +void SbgEcom::Run() +{ + if (should_exit()) { + ScheduleClear(); + exit_and_cleanup(); + return; + } + + if (!_initialized) { + init_result = init(); + _initialized = true; + } + + if (init_result == PX4_OK) { + SbgErrorCode error_code; + + error_code = handleOneLog(&_com_handle); + + if (error_code == SBG_NO_ERROR) { + ScheduleDelayed(time_literals::operator ""_ms(0)); + + if (failure) { + assert(iteration_count >= 0); + iteration_count--; + failure = false; + } + + } else if (error_code != SBG_NOT_READY) { + PX4_ERR("Unable to process incoming sbgECom logs %d", error_code); + } + + if (error_code != SBG_NO_ERROR) { + ScheduleDelayed(time_literals::operator ""_ms(1)); + failure = true; + } + + error_code = sendAirDataLog(&_com_handle, this); + + if (error_code != SBG_NO_ERROR) { + PX4_WARN("Unable to send AirData log %d", error_code); + } + + error_code = sendMagLog(&_com_handle, this); + + if (error_code != SBG_NO_ERROR) { + PX4_WARN("Unable to send Mag log %d", error_code); + } + } +} + +int SbgEcom::task_spawn(int argc, char **argv) +{ + sbgCommonLibSetLogCallback(printLogCallBack); + + bool error_flag = false; + + const char *myoptarg = nullptr; + int myoptind = 1; + int ch; + + int32_t baudrate; + param_get(param_find("SBG_BAUDRATE"), &baudrate); + const char *dev_name = DEFAULT_DEVNAME; + const char *config_file = DEFAULT_CONFIG_PATH; + + /* INS settings can be overwritten from the SD card */ + if (access(OVERRIDE_CONFIG_PATH, F_OK) == 0) { + config_file = OVERRIDE_CONFIG_PATH; + + } else { + config_file = DEFAULT_CONFIG_PATH; + } + + const char *config_string = nullptr; + + while ((ch = px4_getopt(argc, argv, "b:d:f:s:", &myoptind, &myoptarg)) != EOF) { + switch (ch) { + case 'b': + baudrate = atoi(myoptarg); + break; + + case 'd': + dev_name = myoptarg; + break; + + case 'f': + config_file = myoptarg; + break; + + case 's': + config_string = myoptarg; + break; + + case '?': + PX4_WARN("unrecognized flag ?"); + error_flag = true; + break; + + default: + PX4_WARN("unrecognized flag"); + error_flag = true; + break; + } + } + + if (error_flag) { + return -1; + } + + if (dev_name && (access(dev_name, R_OK | W_OK) == 0)) { + SbgEcom *instance = new SbgEcom(dev_name, baudrate, config_file, config_string); + + if (instance == nullptr) { + PX4_ERR("alloc failed"); + return PX4_ERROR; + } + + _task_id = task_id_is_work_queue; + _object.store(instance); + instance->ScheduleNow(); + return PX4_OK; + + } else { + if (dev_name) { + PX4_ERR("invalid device (-d) %s", dev_name); + + } else { + PX4_ERR("valid device required"); + } + } + + return PX4_ERROR; +} + +int SbgEcom::custom_command(int argc, char **argv) +{ + return print_usage("unrecognized command"); +} + +int SbgEcom::print_usage(const char *reason) +{ + if (reason) { + PX4_WARN("%s\n", reason); + } + + PRINT_MODULE_DESCRIPTION("Description du module"); + + PRINT_MODULE_USAGE_NAME("sbgecom", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("ins"); + PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start driver"); + PRINT_MODULE_USAGE_PARAM_STRING('d', DEFAULT_DEVNAME, nullptr, "Serial device", true); + PRINT_MODULE_USAGE_PARAM_INT('b', 921600, 9600, 921600, "Baudrate device", true); + PRINT_MODULE_USAGE_PARAM_STRING('f', DEFAULT_CONFIG_PATH, nullptr, "Config JSON file path", true); + PRINT_MODULE_USAGE_PARAM_STRING('s', nullptr, nullptr, "Config JSON string", true); + PRINT_MODULE_USAGE_COMMAND_DESCR("status", "Driver status"); + PRINT_MODULE_USAGE_COMMAND_DESCR("stop", "Stop driver"); + + return PX4_OK; +} + +int SbgEcom::print_status() +{ + printf("Using port '%s'\n", _device_name); + + perf_print_counter(_sample_perf); + perf_print_counter(_write_perf); + perf_print_counter(_comms_errors); + + return 0; +} + +extern "C" __EXPORT int sbgecom_main(int argc, char **argv) +{ + return SbgEcom::main(argc, argv); +} diff --git a/src/drivers/ins/sbgecom/sbgecom.hpp b/src/drivers/ins/sbgecom/sbgecom.hpp new file mode 100644 index 0000000000..332f8def2c --- /dev/null +++ b/src/drivers/ins/sbgecom/sbgecom.hpp @@ -0,0 +1,294 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file sbgecom.hpp + * Driver for the SBG Systems products + * + * @author SBG Systems + */ + +#pragma once + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +class SbgEcom : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem +{ +public: + + SbgEcom(const char *port, uint32_t baudrate, const char *config_file, const char *config_string); + ~SbgEcom() override; + + /** @see ModuleBase */ + static int task_spawn(int argc, char **argv); + + /** @see ModuleBase */ + static int custom_command(int argc, char **argv); + + /** @see ModuleBase */ + static int print_usage(const char *reason = nullptr); + + /** @see ModuleBase */ + int print_status() override; + + /** @see ModuleBase::run() */ + void Run() override; + + int init(); + +private: + + /** + * @brief Type for logging functions. + * + * @param file_name File name where the error occurred. + * @param function_name Function name where the error occurred. + * @param line Line number where the error occurred. + * @param category Category for this log or "None" if no category has been specified. + * @param log_type Define if we have an error, a warning, an info or a debug log. + * @param error_code The error code associated with the message. + * @param message The message to log. + */ + static void printLogCallBack(const char *file_name, const char *function_name, uint32_t line, const char *category, + SbgDebugLogType log_type, SbgErrorCode error_code, const char *message); + + /** + * @brief Parse IMU (Inertial Measurement Unit) measurement logs. + * + * @param ref_sbg_data Contains the received log data as an union. + * @param user_arg Optional user supplied argument. + */ + static void handleLogImuShort(const SbgEComLogUnion *ref_sbg_data, void *user_arg); + + /** + * @brief Parse magnetic field measurements logs. + * + * @param ref_sbg_data Contains the received log data as an union. + * @param user_arg Optional user supplied argument. + */ + static void handleLogMag(const SbgEComLogUnion *ref_sbg_data, void *user_arg); + + /** + * @brief Parse EKF quaternion measurement logs. + * + * @param ref_sbg_data Contains the received log data as an union. + * @param user_arg Optional user supplied argument. + */ + static void handleLogEkfQuat(const SbgEComLogUnion *ref_sbg_data, void *user_arg); + + /** + * @brief Parse EKF navigation measurement logs. + * + * @param ref_sbg_data Contains the received log data as an union. + * @param user_arg Optional user supplied argument. + */ + static void handleLogEkfNav(const SbgEComLogUnion *ref_sbg_data, void *user_arg); + + /** + * @brief GNSS position, velocity and heading related logs. + * + * @param msg Message ID of the log received. + * @param ref_sbg_data Contains the received log data as an union. + * @param user_arg Optional user supplied argument. + */ + static void handleLogGnssPosVelHdt(SbgEComMsgId msg, const SbgEComLogUnion *ref_sbg_data, void *user_arg); + + /** + * @brief Update estimator status message from EKF status flags. + * + * @param ekf_status EKF status flags. + * @param estimator_status Estimator status message. + */ + static void updateEstimatorStatus(uint32_t ekf_status, estimator_status_s *estimator_status); + + /** + * @brief Callback definition called each time a new log is received. + * + * @param handle Valid handle on the sbgECom instance that has called this callback. + * @param msg_class Class of the message we have received + * @param msg Message ID of the log received. + * @param ref_sbg_data Contains the received log data as an union. + * @param user_arg Optional user supplied argument. + * @return SBG_NO_ERROR if the received log has been used successfully. + */ + static SbgErrorCode onLogReceived(SbgEComHandle *handle, SbgEComClass msg_class, SbgEComMsgId msg, + const SbgEComLogUnion *ref_sbg_data, void *user_arg); + + /** + * @brief Send a config to the INS + * + * @param pHandle SbgECom instance. + * @param config Config json string. + */ + static void send_config(SbgEComHandle *pHandle, const char *config); + + /** + * @brief Send a config file to the INS + * + * @param pHandle SbgECom instance. + * @param file_path Config file path. + */ + static void send_config_file(SbgEComHandle *pHandle, const char *file_path); + + /** + * @brief Get and print product info. + * + * @param handle SbgECom instance. + * @return SBG_NO_ERROR if successful. + */ + SbgErrorCode getAndPrintProductInfo(SbgEComHandle *handle); + + /** + * @brief Try to parse one log from the input interface and then return. + * + * @param handle A valid sbgECom handle. + * @return SBG_NO_ERROR if no error occurs during incoming log parsing. + */ + SbgErrorCode handleOneLog(SbgEComHandle *handle); + + /** + * @brief Get air data and send it. + * + * @param handle A valid sbgECom handle. + * @param instance An SbgEcom object. + * @return SBG_NO_ERROR if no error occurs during incoming log parsing. + */ + SbgErrorCode sendAirDataLog(SbgEComHandle *handle, SbgEcom *instance); + + /** + * @brief Get magnetometer data and send it. + * + * @param handle A valid sbgECom handle. + * @param instance An SbgEcom object. + * @return SBG_NO_ERROR if no error occurs during incoming log parsing. + */ + SbgErrorCode sendMagLog(SbgEComHandle *handle, SbgEcom *instance); + + void set_device_id(uint32_t device_id); + uint32_t get_device_id(void); + + // SBG interface and state variables + SbgInterface _sbg_interface; + SbgEComHandle _com_handle; + SbgEComLogUnion _log_data; + + uint32_t _baudrate; + const char *_config_file; + const char *_config_string; + char _device_name[25]; + uint32_t _device_id{0}; + + const int log_interval = 10; + int iteration_count = log_interval; + + bool failure = false; + bool _ekf_failure = false; + + bool _initialized = false; + int init_result; + + MapProjection _pos_ref{}; + double _gps_alt_ref{NAN}; + + struct GnssData { + bool pos_received = false; + bool vel_received = false; + bool hdt_received = false; + + SbgEComLogGnssPos gps_pos; + SbgEComLogGnssVel gps_vel; + SbgEComLogGnssHdt gps_hdt; + + hrt_abstime pos_timestamp = 0; + hrt_abstime vel_timestamp = 0; + hrt_abstime hdt_timestamp = 0; + }; + + GnssData gnss_data; + float _heading; + + px4::atomic _time_last_valid_imu_us{false}; + + // Sensors topics + PX4Accelerometer _px4_accel{0}; + PX4Gyroscope _px4_gyro{0}; + PX4Magnetometer _px4_mag{0}; + + // Publications with topic dependent on multi-mode + uORB::PublicationMulti _sensor_gps_pub{ORB_ID(sensor_gps)}; + uORB::PublicationMulti _attitude_pub{ORB_ID(vehicle_attitude)}; + uORB::PublicationMulti _local_position_pub{ORB_ID(vehicle_local_position)}; + uORB::PublicationMulti _global_position_pub{ORB_ID(vehicle_global_position)}; + uORB::Publication _estimator_status_pub{ORB_ID(estimator_status)}; + + // Subscription for INS EKF aiding + uORB::Subscription _air_data_sub{ORB_ID(vehicle_air_data)}; + uORB::Subscription _airspeed_sub{ORB_ID(airspeed)}; + uORB::Subscription _diff_pressure_sub{ORB_ID(differential_pressure)}; + uORB::Subscription _mag_sub{ORB_ID(vehicle_magnetometer)}; + + // Performance mounters for monitoring and debugging + perf_counter_t _comms_errors{perf_alloc(PC_COUNT, MODULE_NAME": errors")}; + perf_counter_t _sample_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": sample")}; + perf_counter_t _write_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": write")}; + + perf_counter_t _accel_pub_interval_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": accel publish interval")}; + perf_counter_t _gyro_pub_interval_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": gyro publish interval")}; + perf_counter_t _mag_pub_interval_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": mag publish interval")}; + perf_counter_t _gnss_pub_interval_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": GNSS publish interval")}; + + perf_counter_t _attitude_pub_interval_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": attitude publish interval")}; + perf_counter_t _local_position_pub_interval_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": local position publish interval")}; + perf_counter_t _global_position_pub_interval_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": global position publish interval")}; +}; diff --git a/src/modules/mavlink/streams/HIGHRES_IMU.hpp b/src/modules/mavlink/streams/HIGHRES_IMU.hpp index 7a3d96cb38..c6e4d7580b 100644 --- a/src/modules/mavlink/streams/HIGHRES_IMU.hpp +++ b/src/modules/mavlink/streams/HIGHRES_IMU.hpp @@ -63,7 +63,7 @@ public: private: explicit MavlinkStreamHighresIMU(Mavlink *mavlink) : MavlinkStream(mavlink) {} - uORB::SubscriptionMultiArray _vehicle_imu_subs{ORB_ID::vehicle_imu}; + uORB::SubscriptionMultiArray _vehicle_imu_subs{ORB_ID::vehicle_imu}; uORB::Subscription _estimator_sensor_bias_sub{ORB_ID(estimator_sensor_bias)}; uORB::Subscription _estimator_selector_status_sub{ORB_ID(estimator_selector_status)}; uORB::Subscription _sensor_selection_sub{ORB_ID(sensor_selection)}; @@ -190,8 +190,8 @@ private: msg.xmag = mag(0); msg.ymag = mag(1); msg.zmag = mag(2); - msg.abs_pressure = air_data.baro_pressure_pa; - msg.diff_pressure = differential_pressure.differential_pressure_pa; + msg.abs_pressure = air_data.baro_pressure_pa * 0.01f; // Pa to hPa + msg.diff_pressure = differential_pressure.differential_pressure_pa * 0.01f; // Pa to hPa msg.pressure_alt = air_data.baro_alt_meter; msg.temperature = air_data.ambient_temperature; msg.fields_updated = fields_updated; diff --git a/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp b/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp index 7b0d9556ca..5566efbb1c 100644 --- a/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp +++ b/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp @@ -144,7 +144,7 @@ void SensorAirspeedSim::Run() // report.timestamp_sample = time; differential_pressure.device_id = 1377548; // 1377548: DRV_DIFF_PRESS_DEVTYPE_SIM, BUS: 1, ADDR: 5, TYPE: SIMULATION differential_pressure.differential_pressure_pa = (double)diff_pressure * 100.0; // hPa to Pa; - differential_pressure.temperature = temperature_local; + differential_pressure.temperature = temperature_local + ABSOLUTE_ZERO_C; // K to C differential_pressure.timestamp = hrt_absolute_time(); _differential_pressure_pub.publish(differential_pressure); diff --git a/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.hpp b/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.hpp index 64305dccca..3aafc9ca93 100644 --- a/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.hpp +++ b/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.hpp @@ -49,6 +49,7 @@ using namespace time_literals; +static constexpr float ABSOLUTE_ZERO_C = -273.15; // absolute 0 temperature [C] static constexpr float TEMPERATURE_MSL = 288.15; // temperature at MSL [K] (15 [C]) static constexpr float PRESSURE_MSL = 101325.0; // pressure at MSL [Pa] static constexpr float LAPSE_RATE = 0.0065; // reduction in temperature with altitude for troposphere [K/m] From 7b68c5dbfcaee8f9b9973a620ea2fd77a6182a90 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 11 Sep 2025 20:47:45 +0200 Subject: [PATCH 026/812] parameters: remove parameters_injected.xml and support for it in the build system (#25549) This was apparently added 10 years ago to store metadata of UAVCAN components within the PX4 binary. The parameters in the xml are mostly early UAVCAN ESC parameters that are presumably out of date and not used. Also it does not scale to maintain metadata for all the possible UAVCAN components and it causes confusion when users read the metadata documentation because these parameters are not available in PX4. That's why I suggest to remove it. --- cmake/metadata.cmake | 3 - src/lib/parameters/CMakeLists.txt | 5 +- src/lib/parameters/parameters_injected.xml | 198 --------------------- src/lib/parameters/px4params/jsonout.py | 2 +- src/lib/parameters/px_process_params.py | 13 +- 5 files changed, 4 insertions(+), 217 deletions(-) delete mode 100644 src/lib/parameters/parameters_injected.xml diff --git a/cmake/metadata.cmake b/cmake/metadata.cmake index 82b2042701..803d14c9e2 100644 --- a/cmake/metadata.cmake +++ b/cmake/metadata.cmake @@ -71,18 +71,15 @@ add_custom_target(metadata_parameters COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/src/lib/parameters/px_process_params.py --src-path `find ${PX4_SOURCE_DIR}/src -maxdepth 4 -type d` ${generated_params_dir} - --inject-xml ${PX4_SOURCE_DIR}/src/lib/parameters/parameters_injected.xml --markdown ${PX4_BINARY_DIR}/docs/parameters.md COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/src/lib/parameters/px_process_params.py --src-path `find ${PX4_SOURCE_DIR}/src -maxdepth 4 -type d` ${generated_params_dir} - --inject-xml ${PX4_SOURCE_DIR}/src/lib/parameters/parameters_injected.xml --json ${PX4_BINARY_DIR}/docs/parameters.json --compress COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/src/lib/parameters/px_process_params.py --src-path `find ${PX4_SOURCE_DIR}/src -maxdepth 4 -type d` ${generated_params_dir} - --inject-xml ${PX4_SOURCE_DIR}/src/lib/parameters/parameters_injected.xml --xml ${PX4_BINARY_DIR}/docs/parameters.xml COMMENT "Generating full parameter metadata (markdown, xml, and json)" diff --git a/src/lib/parameters/CMakeLists.txt b/src/lib/parameters/CMakeLists.txt index 81b609080a..cfa118b2dd 100644 --- a/src/lib/parameters/CMakeLists.txt +++ b/src/lib/parameters/CMakeLists.txt @@ -123,7 +123,6 @@ add_custom_command(OUTPUT ${parameters_xml} ${parameters_json} ${parameters_json --xml ${parameters_xml} --json ${parameters_json} --compress - --inject-xml ${CMAKE_CURRENT_SOURCE_DIR}/parameters_injected.xml --overrides ${PARAM_DEFAULT_OVERRIDES} --board ${PX4_BOARD} #--verbose @@ -136,13 +135,11 @@ add_custom_command(OUTPUT ${parameters_xml} ${parameters_json} ${parameters_json ${param_src_files} ${generated_serial_params_file} ${generated_module_params_file} - parameters_injected.xml px4params/srcparser.py px4params/srcscanner.py px4params/jsonout.py px4params/xmlout.py px_process_params.py - parameters_injected.xml COMMENT "Generating parameters.xml" ) add_custom_target(parameters_xml DEPENDS ${parameters_xml}) @@ -161,7 +158,7 @@ add_custom_target(parameters_header DEPENDS px4_parameters.hpp) set(SRCS) list(APPEND SRCS - parameters.cpp + parameters.cpp atomic_transaction.cpp autosave.cpp ) diff --git a/src/lib/parameters/parameters_injected.xml b/src/lib/parameters/parameters_injected.xml deleted file mode 100644 index b927adc289..0000000000 --- a/src/lib/parameters/parameters_injected.xml +++ /dev/null @@ -1,198 +0,0 @@ - - - 3 - - - Speed controller bandwidth - Speed controller bandwidth, in Hz. Higher values result in faster speed and current rise times, but may result in overshoot and higher current consumption. For fixed-wing aircraft, this value should be less than 50 Hz; for multirotors, values up to 100 Hz may provide improvements in responsiveness. - Hz - 10 - 250 - - - Reverse direction - Motor spin direction as detected during initial enumeration. Use 0 or 1 to reverse direction. - 0 - 1 - - - Speed (RPM) controller gain - Speed (RPM) controller gain. Determines controller - aggressiveness; units are amp-seconds per radian. Systems with - higher rotational inertia (large props) will need gain increased; - systems with low rotational inertia (small props) may need gain - decreased. Higher values result in faster response, but may result - in oscillation and excessive overshoot. Lower values result in a - slower, smoother response. - C/rad - 3 - 0.00 - 1.00 - - - Idle speed (e Hz) - Idle speed (e Hz) - Hz - 3 - 0.0 - 100.0 - - - Spin-up rate (e Hz/s) - Spin-up rate (e Hz/s) - 1/s^2 - 5 - 1000 - - - Index of this ESC in throttle command messages. - Index of this ESC in throttle command messages. - 0 - 15 - - - Extended status ID - Extended status ID - 1 - 1000000 - - - Extended status interval (µs) - Extended status interval (µs) - us - 0 - 1000000 - - - ESC status interval (µs) - ESC status interval (µs) - us - 1000000 - - - Motor current limit in amps - Motor current limit in amps. This determines the maximum - current controller setpoint, as well as the maximum allowable - current setpoint slew rate. This value should generally be set to - the continuous current rating listed in the motor’s specification - sheet, or set equal to the motor’s specified continuous power - divided by the motor voltage limit. - A - 3 - 1 - 80 - - - Motor Kv in RPM per volt - Motor Kv in RPM per volt. This can be taken from the motor’s - specification sheet; accuracy will help control performance but - some deviation from the specified value is acceptable. - rpm/V - 0 - 4000 - - - READ ONLY: Motor inductance in henries. - READ ONLY: Motor inductance in henries. This is measured on start-up. - H - 3 - - - Number of motor poles. - Number of motor poles. Used to convert mechanical speeds to - electrical speeds. This number should be taken from the motor’s - specification sheet. - 2 - 40 - - - READ ONLY: Motor resistance in ohms - READ ONLY: Motor resistance in ohms. This is measured on start-up. When - tuning a new motor, check that this value is approximately equal - to the value shown in the motor’s specification sheet. - Ohm - 3 - - - Acceleration limit (V) - Acceleration limit (V) - V - 3 - 0.01 - 1.00 - - - Motor voltage limit in volts - Motor voltage limit in volts. The current controller’s - commanded voltage will never exceed this value. Note that this may - safely be above the nominal voltage of the motor; to determine the - actual motor voltage limit, divide the motor’s rated power by the - motor current limit. - V - 3 - 0 - - - - - device health warning - Set the device health to Warning if the dimensionality of - the GNSS solution is less than this value. 3 for the full (3D) - solution, 2 for planar (2D) solution, 1 for time-only solution, - 0 disables the feature. - - 0 - 3 - - disables the feature - time-only solution - planar (2D) solution - full (3D) solution - - - - - Set the device health to Warning if the number of satellites - used in the GNSS solution is below this threshold. Zero - disables the feature - - - - GNSS dynamic model - Dynamic model used in the GNSS positioning engine. 0 – - Automotive, 1 – Sea, 2 – Airborne. - - 0 - 2 - - Automotive - Sea - Airborne - - - - Broadcast old GNSS fix message - Broadcast the old (deprecated) GNSS fix message - uavcan.equipment.gnss.Fix alongside the new alternative - uavcan.equipment.gnss.Fix2. It is recommended to - disable this feature to reduce the CAN bus traffic. - - 0 - 1 - - Fix2 - Fix and Fix2 - - - - - Set the device health to Warning if the number of satellites - used in the GNSS solution is below this threshold. Zero - disables the feature - - us - 0 - 1000000 - - - diff --git a/src/lib/parameters/px4params/jsonout.py b/src/lib/parameters/px4params/jsonout.py index e4a8b021bd..ba97c740d9 100644 --- a/src/lib/parameters/px4params/jsonout.py +++ b/src/lib/parameters/px4params/jsonout.py @@ -5,7 +5,7 @@ import sys class JsonOutput(): - def __init__(self, groups, board, inject_xml_file_name): + def __init__(self, groups, board): all_json=dict() all_json['version']=1 all_params=[] diff --git a/src/lib/parameters/px_process_params.py b/src/lib/parameters/px_process_params.py index feefa684c8..2d35e3e95d 100755 --- a/src/lib/parameters/px_process_params.py +++ b/src/lib/parameters/px_process_params.py @@ -75,12 +75,6 @@ def main(): metavar="FILENAME", help="Create XML file" " (default FILENAME: parameters.xml)") - parser.add_argument("-i", "--inject-xml", - nargs='?', - const="parameters_injected.xml", - metavar="FILENAME", - help="Inject additional param XML file" - " (default FILENAME: parameters_injected.xml)") parser.add_argument("-b", "--board", nargs='?', const="", @@ -138,8 +132,6 @@ def main(): #inject parameters at front of set cur_dir = os.path.dirname(os.path.realpath(__file__)) - groups_to_inject = injectxmlparams.XMLInject(os.path.join(cur_dir, args.inject_xml)).injected() - param_groups=groups_to_inject+param_groups override_dict = json.loads(args.overrides) if len(override_dict.keys()) > 0: @@ -174,8 +166,7 @@ def main(): if args.verbose: print("Creating Json file " + args.json) cur_dir = os.path.dirname(os.path.realpath(__file__)) - out = jsonout.JsonOutput(param_groups, args.board, - os.path.join(cur_dir, args.inject_xml)) + out = jsonout.JsonOutput(param_groups, args.board) out.Save(args.json) output_files.append(args.json) @@ -184,7 +175,7 @@ def main(): if args.verbose: print("Compressing file " + f) save_compressed(f) - + if __name__ == "__main__": main() From 1aad8b6ec9f0ec822080ef70c23cd494dacdeb2d Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Thu, 11 Sep 2025 12:32:34 -0800 Subject: [PATCH 027/812] serial: nuttx: revert tcdrain back to fsync (#25538) * serial: nuttx: revert tcdrain back to fsync * serial: do not print error on EAGAIN --------- Co-authored-by: Alexander Lerach --- platforms/nuttx/src/px4/common/SerialImpl.cpp | 7 +++++-- platforms/posix/src/px4/common/SerialImpl.cpp | 8 +++++--- platforms/qurt/src/px4/SerialImpl.cpp | 5 +++-- 3 files changed, 13 insertions(+), 7 deletions(-) diff --git a/platforms/nuttx/src/px4/common/SerialImpl.cpp b/platforms/nuttx/src/px4/common/SerialImpl.cpp index cd9caa4982..f3a9f2389b 100644 --- a/platforms/nuttx/src/px4/common/SerialImpl.cpp +++ b/platforms/nuttx/src/px4/common/SerialImpl.cpp @@ -355,12 +355,15 @@ ssize_t SerialImpl::write(const void *buffer, size_t buffer_size) } int written = ::write(_serial_fd, buffer, buffer_size); - tcdrain(_serial_fd); // Wait until all output is transmitted if (written < 0) { - PX4_ERR("%s write error %d", _port, written); + if (errno != EAGAIN) { + PX4_ERR("%s write error %d", _port, written); + } } + ::fsync(_serial_fd); + return written; } diff --git a/platforms/posix/src/px4/common/SerialImpl.cpp b/platforms/posix/src/px4/common/SerialImpl.cpp index 6d9b64a828..9ad8d62567 100644 --- a/platforms/posix/src/px4/common/SerialImpl.cpp +++ b/platforms/posix/src/px4/common/SerialImpl.cpp @@ -337,13 +337,15 @@ ssize_t SerialImpl::write(const void *buffer, size_t buffer_size) } int written = ::write(_serial_fd, buffer, buffer_size); - ::fsync(_serial_fd); if (written < 0) { - PX4_ERR("%s write error %d", _port, written); - + if (errno != EAGAIN) { + PX4_ERR("%s write error %d", _port, written); + } } + ::fsync(_serial_fd); + return written; } diff --git a/platforms/qurt/src/px4/SerialImpl.cpp b/platforms/qurt/src/px4/SerialImpl.cpp index e176f528c9..c2c88e43b9 100644 --- a/platforms/qurt/src/px4/SerialImpl.cpp +++ b/platforms/qurt/src/px4/SerialImpl.cpp @@ -268,8 +268,9 @@ ssize_t SerialImpl::write(const void *buffer, size_t buffer_size) int ret_write = qurt_uart_write(_serial_fd, (const char *) buffer, buffer_size); if (ret_write < 0) { - PX4_ERR("%s write error %d", _port, ret_write); - + if (errno != EAGAIN) { + PX4_ERR("%s write error %d", _port, ret_write); + } } return ret_write; From 8669947bcbde50f11d23ede8f01b264480f0cd30 Mon Sep 17 00:00:00 2001 From: jmackay2 <1.732mackay@gmail.com> Date: Thu, 11 Sep 2025 23:30:27 -0400 Subject: [PATCH 028/812] Support Gazebo Jetty (#25521) * Support Gazebo Jetty * Gazebo jetty cmake spelling fix --------- Co-authored-by: jmackay2 --- .../simulation/gz_bridge/CMakeLists.txt | 9 +++++++-- .../gz_bridge/GZMixingInterfaceServo.cpp | 2 ++ .../simulation/gz_plugins/CMakeLists.txt | 19 +++++++++++++++---- .../gz_plugins/buoyancy/CMakeLists.txt | 8 ++++---- .../gz_plugins/generic_motor/CMakeLists.txt | 8 ++++---- .../gz_plugins/gstreamer/CMakeLists.txt | 8 ++++---- .../moving_platform_controller/CMakeLists.txt | 8 ++++---- .../gz_plugins/optical_flow/CMakeLists.txt | 8 ++++---- .../spacecraft_thruster/CMakeLists.txt | 8 ++++---- .../gz_plugins/template_plugin/CMakeLists.txt | 8 ++++---- 10 files changed, 52 insertions(+), 34 deletions(-) diff --git a/src/modules/simulation/gz_bridge/CMakeLists.txt b/src/modules/simulation/gz_bridge/CMakeLists.txt index d6565d0b1f..aa4b1be37e 100644 --- a/src/modules/simulation/gz_bridge/CMakeLists.txt +++ b/src/modules/simulation/gz_bridge/CMakeLists.txt @@ -32,7 +32,7 @@ ############################################################################ if(NOT DEFINED ENV{GZ_DISTRO} OR NOT "$ENV{GZ_DISTRO}" STREQUAL "harmonic") - find_package(gz-transport NAMES gz-transport14 gz-transport13) + find_package(gz-transport NAMES gz-transport gz-transport14 gz-transport13) else() find_package(gz-transport NAMES gz-transport13) endif() @@ -41,6 +41,11 @@ file(GLOB gz_worlds ${PX4_SOURCE_DIR}/Tools/simulation/gz/worlds/*.sdf) file(GLOB gz_airframes ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes/*_gz_*) if (gz-transport_FOUND) + if (gz-transport_VERSION VERSION_LESS "15") + set(GZ_TRANSPORT_TARGET "gz-transport${gz-transport_VERSION_MAJOR}::core") + else() + set(GZ_TRANSPORT_TARGET "gz-transport::core") + endif() px4_add_module( MODULE modules__simulation__gz_bridge MAIN gz_bridge @@ -60,7 +65,7 @@ if (gz-transport_FOUND) DEPENDS mixer_module px4_work_queue - gz-transport${gz-transport_VERSION_MAJOR}::core + ${GZ_TRANSPORT_TARGET} MODULE_CONFIG module.yaml ) diff --git a/src/modules/simulation/gz_bridge/GZMixingInterfaceServo.cpp b/src/modules/simulation/gz_bridge/GZMixingInterfaceServo.cpp index aaca2a3035..ae53bb637a 100644 --- a/src/modules/simulation/gz_bridge/GZMixingInterfaceServo.cpp +++ b/src/modules/simulation/gz_bridge/GZMixingInterfaceServo.cpp @@ -33,6 +33,8 @@ #include "GZMixingInterfaceServo.hpp" +#include + float GZMixingInterfaceServo::get_servo_angle_max(const size_t index) diff --git a/src/modules/simulation/gz_plugins/CMakeLists.txt b/src/modules/simulation/gz_plugins/CMakeLists.txt index 1eb9f59886..7fc65c8b5b 100644 --- a/src/modules/simulation/gz_plugins/CMakeLists.txt +++ b/src/modules/simulation/gz_plugins/CMakeLists.txt @@ -34,10 +34,10 @@ project(px4_gz_plugins) if(NOT DEFINED ENV{GZ_DISTRO} OR NOT "$ENV{GZ_DISTRO}" STREQUAL "harmonic") - find_package(gz-transport NAMES gz-transport14 gz-transport13) - find_package(gz-sim NAMES gz-sim9 gz-sim8) - find_package(gz-sensors NAMES gz-sensors9 gz-sensors8) - find_package(gz-plugin NAMES gz-plugin3 gz-plugin2 COMPONENTS register) + find_package(gz-transport NAMES gz-transport gz-transport14 gz-transport13) + find_package(gz-sim NAMES gz-sim gz-sim9 gz-sim8) + find_package(gz-sensors NAMES gz-sensors gz-sensors9 gz-sensors8) + find_package(gz-plugin NAMES gz-plugin gz-plugin3 gz-plugin2 COMPONENTS register) else() find_package(gz-transport NAMES gz-transport13) find_package(gz-sim NAMES gz-sim8) @@ -46,6 +46,17 @@ else() endif() if (gz-transport_FOUND) + if (gz-transport_VERSION VERSION_LESS "15") + set(GZ_TRANSPORT_TARGET "gz-transport${gz-transport_VERSION_MAJOR}::gz-transport${gz-transport_VERSION_MAJOR}") + set(GZ_SIM_TARGET "gz-sim${gz-sim_VERSION_MAJOR}::gz-sim${gz-sim_VERSION_MAJOR}") + set(GZ_SENSORS_TARGET "gz-sensors${gz-sensors_VERSION_MAJOR}::gz-sensors${gz-sensors_VERSION_MAJOR}") + set(GZ_PLUGIN_TARGET "gz-plugin${gz-plugin_VERSION_MAJOR}::gz-plugin${gz-plugin_VERSION_MAJOR}") + else() + set(GZ_TRANSPORT_TARGET "gz-transport::gz-transport") + set(GZ_SIM_TARGET "gz-sim::gz-sim") + set(GZ_SENSORS_TARGET "gz-sensors::gz-sensors") + set(GZ_PLUGIN_TARGET "gz-plugin::gz-plugin") + endif() # Create a flat output directory for all plugin libraries set(PX4_GZ_PLUGIN_OUTPUT_DIR "${CMAKE_CURRENT_BINARY_DIR}" CACHE PATH "Directory for all Gazebo plugin libraries") file(MAKE_DIRECTORY ${PX4_GZ_PLUGIN_OUTPUT_DIR}) diff --git a/src/modules/simulation/gz_plugins/buoyancy/CMakeLists.txt b/src/modules/simulation/gz_plugins/buoyancy/CMakeLists.txt index a89818eb11..762cd701d8 100644 --- a/src/modules/simulation/gz_plugins/buoyancy/CMakeLists.txt +++ b/src/modules/simulation/gz_plugins/buoyancy/CMakeLists.txt @@ -48,10 +48,10 @@ add_library(${PROJECT_NAME} SHARED target_link_libraries(${PROJECT_NAME} PUBLIC px4_gz_msgs - PUBLIC gz-sensors${gz-sensors_VERSION_MAJOR}::gz-sensors${gz-sensors_VERSION_MAJOR} - PUBLIC gz-plugin${gz-plugin_VERSION_MAJOR}::gz-plugin${gz-plugin_VERSION_MAJOR} - PUBLIC gz-sim${gz-sim_VERSION_MAJOR}::gz-sim${gz-sim_VERSION_MAJOR} - PUBLIC gz-transport${gz-transport_VERSION_MAJOR}::gz-transport${gz-transport_VERSION_MAJOR} + PUBLIC ${GZ_SENSORS_TARGET} + PUBLIC ${GZ_PLUGIN_TARGET} + PUBLIC ${GZ_SIM_TARGET} + PUBLIC ${GZ_TRANSPORT_TARGET} # Add other dependencies as needed # PUBLIC ${OtherLib_LIBS} ) diff --git a/src/modules/simulation/gz_plugins/generic_motor/CMakeLists.txt b/src/modules/simulation/gz_plugins/generic_motor/CMakeLists.txt index 5753d45ca6..db3ac3f3cd 100644 --- a/src/modules/simulation/gz_plugins/generic_motor/CMakeLists.txt +++ b/src/modules/simulation/gz_plugins/generic_motor/CMakeLists.txt @@ -48,10 +48,10 @@ add_library(${PROJECT_NAME} SHARED target_link_libraries(${PROJECT_NAME} PUBLIC px4_gz_msgs - PUBLIC gz-sensors${gz-sensors_VERSION_MAJOR}::gz-sensors${gz-sensors_VERSION_MAJOR} - PUBLIC gz-plugin${gz-plugin_VERSION_MAJOR}::gz-plugin${gz-plugin_VERSION_MAJOR} - PUBLIC gz-sim${gz-sim_VERSION_MAJOR}::gz-sim${gz-sim_VERSION_MAJOR} - PUBLIC gz-transport${gz-transport_VERSION_MAJOR}::gz-transport${gz-transport_VERSION_MAJOR} + PUBLIC ${GZ_SENSORS_TARGET} + PUBLIC ${GZ_PLUGIN_TARGET} + PUBLIC ${GZ_SIM_TARGET} + PUBLIC ${GZ_TRANSPORT_TARGET} # Add other dependencies as needed # PUBLIC ${OtherLib_LIBS} ) diff --git a/src/modules/simulation/gz_plugins/gstreamer/CMakeLists.txt b/src/modules/simulation/gz_plugins/gstreamer/CMakeLists.txt index 09e5b1d23d..bb453df805 100644 --- a/src/modules/simulation/gz_plugins/gstreamer/CMakeLists.txt +++ b/src/modules/simulation/gz_plugins/gstreamer/CMakeLists.txt @@ -47,10 +47,10 @@ else() target_link_libraries(${PROJECT_NAME} PUBLIC px4_gz_msgs - PUBLIC gz-sensors${gz-sensors_VERSION_MAJOR}::gz-sensors${gz-sensors_VERSION_MAJOR} - PUBLIC gz-plugin${gz-plugin_VERSION_MAJOR}::gz-plugin${gz-plugin_VERSION_MAJOR} - PUBLIC gz-sim${gz-sim_VERSION_MAJOR}::gz-sim${gz-sim_VERSION_MAJOR} - PUBLIC gz-transport${gz-transport_VERSION_MAJOR}::gz-transport${gz-transport_VERSION_MAJOR} + PUBLIC ${GZ_SENSORS_TARGET} + PUBLIC ${GZ_PLUGIN_TARGET} + PUBLIC ${GZ_SIM_TARGET} + PUBLIC ${GZ_TRANSPORT_TARGET} PUBLIC ${GSTREAMER_LIBRARIES} PUBLIC ${GSTREAMER_APP_LIBRARIES} ) diff --git a/src/modules/simulation/gz_plugins/moving_platform_controller/CMakeLists.txt b/src/modules/simulation/gz_plugins/moving_platform_controller/CMakeLists.txt index f0ddf3322f..88e2da59cb 100644 --- a/src/modules/simulation/gz_plugins/moving_platform_controller/CMakeLists.txt +++ b/src/modules/simulation/gz_plugins/moving_platform_controller/CMakeLists.txt @@ -39,10 +39,10 @@ add_library(${PROJECT_NAME} SHARED target_link_libraries(${PROJECT_NAME} PUBLIC px4_gz_msgs - PUBLIC gz-sensors${gz-sensors_VERSION_MAJOR}::gz-sensors${gz-sensors_VERSION_MAJOR} - PUBLIC gz-plugin${gz-plugin_VERSION_MAJOR}::gz-plugin${gz-plugin_VERSION_MAJOR} - PUBLIC gz-sim${gz-sim_VERSION_MAJOR}::gz-sim${gz-sim_VERSION_MAJOR} - PUBLIC gz-transport${gz-transport_VERSION_MAJOR}::gz-transport${gz-transport_VERSION_MAJOR} + PUBLIC ${GZ_SENSORS_TARGET} + PUBLIC ${GZ_PLUGIN_TARGET} + PUBLIC ${GZ_SIM_TARGET} + PUBLIC ${GZ_TRANSPORT_TARGET} ) target_include_directories(${PROJECT_NAME} diff --git a/src/modules/simulation/gz_plugins/optical_flow/CMakeLists.txt b/src/modules/simulation/gz_plugins/optical_flow/CMakeLists.txt index 21c7afc3a3..a03ee39598 100644 --- a/src/modules/simulation/gz_plugins/optical_flow/CMakeLists.txt +++ b/src/modules/simulation/gz_plugins/optical_flow/CMakeLists.txt @@ -46,10 +46,10 @@ add_library(${PROJECT_NAME} SHARED target_link_libraries(${PROJECT_NAME} PUBLIC px4_gz_msgs - PUBLIC gz-sensors${gz-sensors_VERSION_MAJOR}::gz-sensors${gz-sensors_VERSION_MAJOR} - PUBLIC gz-plugin${gz-plugin_VERSION_MAJOR}::gz-plugin${gz-plugin_VERSION_MAJOR} - PUBLIC gz-sim${gz-sim_VERSION_MAJOR}::gz-sim${gz-sim_VERSION_MAJOR} - PUBLIC gz-transport${gz-transport_VERSION_MAJOR}::gz-transport${gz-transport_VERSION_MAJOR} + PUBLIC ${GZ_SENSORS_TARGET} + PUBLIC ${GZ_PLUGIN_TARGET} + PUBLIC ${GZ_SIM_TARGET} + PUBLIC ${GZ_TRANSPORT_TARGET} PUBLIC ${OpenCV_LIBS} PUBLIC ${OpticalFlow_LIBS} ) diff --git a/src/modules/simulation/gz_plugins/spacecraft_thruster/CMakeLists.txt b/src/modules/simulation/gz_plugins/spacecraft_thruster/CMakeLists.txt index 5f196526dd..1955c497dd 100644 --- a/src/modules/simulation/gz_plugins/spacecraft_thruster/CMakeLists.txt +++ b/src/modules/simulation/gz_plugins/spacecraft_thruster/CMakeLists.txt @@ -48,10 +48,10 @@ add_library(${PROJECT_NAME} SHARED target_link_libraries(${PROJECT_NAME} PUBLIC px4_gz_msgs - PUBLIC gz-sensors${gz-sensors_VERSION_MAJOR}::gz-sensors${gz-sensors_VERSION_MAJOR} - PUBLIC gz-plugin${gz-plugin_VERSION_MAJOR}::gz-plugin${gz-plugin_VERSION_MAJOR} - PUBLIC gz-sim${gz-sim_VERSION_MAJOR}::gz-sim${gz-sim_VERSION_MAJOR} - PUBLIC gz-transport${gz-transport_VERSION_MAJOR}::gz-transport${gz-transport_VERSION_MAJOR} + PUBLIC ${GZ_SENSORS_TARGET} + PUBLIC ${GZ_PLUGIN_TARGET} + PUBLIC ${GZ_SIM_TARGET} + PUBLIC ${GZ_TRANSPORT_TARGET} # Add other dependencies as needed # PUBLIC ${OtherLib_LIBS} ) diff --git a/src/modules/simulation/gz_plugins/template_plugin/CMakeLists.txt b/src/modules/simulation/gz_plugins/template_plugin/CMakeLists.txt index c7e582fd9f..a0caaf2b33 100644 --- a/src/modules/simulation/gz_plugins/template_plugin/CMakeLists.txt +++ b/src/modules/simulation/gz_plugins/template_plugin/CMakeLists.txt @@ -48,10 +48,10 @@ add_library(${PROJECT_NAME} SHARED target_link_libraries(${PROJECT_NAME} PUBLIC px4_gz_msgs - PUBLIC gz-sensors${gz-sensors_VERSION_MAJOR}::gz-sensors${gz-sensors_VERSION_MAJOR} - PUBLIC gz-plugin${gz-plugin_VERSION_MAJOR}::gz-plugin${gz-plugin_VERSION_MAJOR} - PUBLIC gz-sim${gz-sim_VERSION_MAJOR}::gz-sim${gz-sim_VERSION_MAJOR} - PUBLIC gz-transport${gz-transport_VERSION_MAJOR}::gz-transport${gz-transport_VERSION_MAJOR} + PUBLIC ${GZ_SENSORS_TARGET} + PUBLIC ${GZ_PLUGIN_TARGET} + PUBLIC ${GZ_SIM_TARGET} + PUBLIC ${GZ_TRANSPORT_TARGET} # Add other dependencies as needed # PUBLIC ${OtherLib_LIBS} ) From db8a1f11a742d265e64952bdcb8ccc932b60c4d4 Mon Sep 17 00:00:00 2001 From: Silvan Date: Fri, 12 Sep 2025 10:17:43 +0200 Subject: [PATCH 029/812] EstimatorCheck: fix reporting of low position accuracy failsafe Signed-off-by: Silvan --- .../commander/HealthAndArmingChecks/checks/estimatorCheck.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp index 2b90f78c84..60b922bd18 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp @@ -621,8 +621,7 @@ void EstimatorChecks::lowPositionAccuracy(const Context &context, Report &report position_valid_but_low_accuracy = (_param_com_low_eph.get() > FLT_EPSILON && lpos.eph > _param_com_low_eph.get()); } - if (!reporter.failsafeFlags().position_accuracy_low && position_valid_but_low_accuracy - && _param_com_pos_low_act.get()) { + if (position_valid_but_low_accuracy && _param_com_pos_low_act.get()) { // only report if armed if (context.isArmed()) { From 27f91614584de152a49be9b631601c188f3d7356 Mon Sep 17 00:00:00 2001 From: Jacob Dahl Date: Sun, 14 Sep 2025 12:02:06 -0800 Subject: [PATCH 030/812] ark: UAVCAN_ESC_IFACE per board, v6x uses CAN2 --- boards/ark/fmu-v6x/init/rc.board_defaults | 2 ++ boards/ark/fpv/init/rc.board_defaults | 2 ++ boards/ark/pi6x/init/rc.board_defaults | 2 ++ 3 files changed, 6 insertions(+) diff --git a/boards/ark/fmu-v6x/init/rc.board_defaults b/boards/ark/fmu-v6x/init/rc.board_defaults index d0732e90ef..d20bbfa1c3 100644 --- a/boards/ark/fmu-v6x/init/rc.board_defaults +++ b/boards/ark/fmu-v6x/init/rc.board_defaults @@ -25,6 +25,8 @@ param set-default SENS_IMU_TEMP 10.0 #param set-default SENS_IMU_TEMP_I 0.025 #param set-default SENS_IMU_TEMP_P 1.0 +param set-default UAVCAN_ESC_IFACE 2 + if ver hwtypecmp ARKV6X000 then param set-default SENS_TEMP_ID 2818058 diff --git a/boards/ark/fpv/init/rc.board_defaults b/boards/ark/fpv/init/rc.board_defaults index 5605f60d02..dc7a548573 100644 --- a/boards/ark/fpv/init/rc.board_defaults +++ b/boards/ark/fpv/init/rc.board_defaults @@ -30,6 +30,8 @@ param set-default BAT1_V_DIV 21.0 param set-default RC_CRSF_PRT_CFG 300 param set-default RC_SBUS_PRT_CFG 0 +param set-default UAVCAN_ESC_IFACE 1 + param set-default IMU_GYRO_DNF_EN 3 # Single IMU diff --git a/boards/ark/pi6x/init/rc.board_defaults b/boards/ark/pi6x/init/rc.board_defaults index 1b92949d1d..9ddf3f88c4 100644 --- a/boards/ark/pi6x/init/rc.board_defaults +++ b/boards/ark/pi6x/init/rc.board_defaults @@ -26,6 +26,8 @@ param set-default SENS_IMU_TEMP 10.0 #param set-default SENS_IMU_TEMP_I 0.025 #param set-default SENS_IMU_TEMP_P 1.0 +param set-default UAVCAN_ESC_IFACE 1 + if ver hwtypecmp ARKPI6X000 then # TODO: Add the correct sensor ID From 5d0bbaabb202956b6a46de24aff034ef87b53a54 Mon Sep 17 00:00:00 2001 From: Jacob Dahl Date: Mon, 15 Sep 2025 08:45:53 -0800 Subject: [PATCH 031/812] codestyle: exclude sgbecom submodule from style check --- Tools/astyle/files_to_check_code_style.sh | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/astyle/files_to_check_code_style.sh b/Tools/astyle/files_to_check_code_style.sh index 4ab53874a2..7ade8982c1 100755 --- a/Tools/astyle/files_to_check_code_style.sh +++ b/Tools/astyle/files_to_check_code_style.sh @@ -39,4 +39,5 @@ exec find boards msg src platforms test \ -path boards/modalai/voxl2/libfc-sensor-api -prune -o \ -path src/drivers/actuators/vertiq_io/iq-module-communication-cpp -prune -o \ -path src/lib/tensorflow_lite_micro/tflite_micro -prune -o \ + -path src/drivers/ins/sbgecom/sbgECom -prune -o \ \( -type f \( -name "*.c" -o -name "*.h" -o -name "*.cpp" -o -name "*.hpp" \) -print \) | grep $PATTERN From 0068fea2f5a0394849715eb0fa457b5d04a8208d Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Tue, 16 Sep 2025 08:56:46 +1000 Subject: [PATCH 032/812] New Crowdin translations - zh-CN (#25559) Co-authored-by: Crowdin Bot --- docs/zh/SUMMARY.md | 5 + docs/zh/airframes/airframe_reference.md | 13 +- docs/zh/assembly/_assembly.md | 2 +- docs/zh/concept/system_startup.md | 33 ++-- docs/zh/config/safety.md | 12 +- docs/zh/dev_setup/dev_env_windows_wsl.md | 8 +- .../zh/flight_controller/accton-godwit_ga1.md | 153 +++++++++++++++++ .../autopilot_manufacturer_supported.md | 1 + docs/zh/flight_modes_mc/throw_launch.md | 2 +- docs/zh/modules/modules_driver_ins.md | 35 ++++ docs/zh/msg_docs/ActionRequest.md | 34 ++-- docs/zh/msg_docs/ActuatorMotors.md | 12 +- docs/zh/msg_docs/ActuatorServos.md | 8 +- docs/zh/msg_docs/Airspeed.md | 10 +- docs/zh/msg_docs/ArmingCheckReply.md | 46 ++--- docs/zh/msg_docs/ArmingCheckRequest.md | 8 +- docs/zh/msg_docs/ArmingCheckRequestV0.md | 30 ++++ docs/zh/msg_docs/CellularStatus.md | 60 +++---- docs/zh/msg_docs/RoverSpeedSetpoint.md | 14 ++ docs/zh/msg_docs/RoverSpeedStatus.md | 18 ++ docs/zh/msg_docs/VehicleAirData.md | 32 ++-- docs/zh/msg_docs/index.md | 7 +- docs/zh/releases/main.md | 2 +- docs/zh/ros2/index.md | 42 ++--- docs/zh/ros2/multi_vehicle.md | 52 +++--- docs/zh/ros2/offboard_control.md | 2 +- docs/zh/ros2/px4_ros2_control_interface.md | 16 +- docs/zh/ros2/px4_ros2_interface_lib.md | 42 ++--- docs/zh/ros2/px4_ros2_msg_translation_node.md | 4 +- docs/zh/ros2/px4_ros2_navigation_interface.md | 18 +- docs/zh/sensor/accelerometer.md | 2 +- docs/zh/sensor/inertial_navigation_systems.md | 1 + docs/zh/sensor/sbgecom.md | 159 ++++++++++++++++++ docs/zh/sim_gazebo_classic/worlds.md | 6 +- .../integration_testing_px4_ros2_interface.md | 4 +- 35 files changed, 665 insertions(+), 228 deletions(-) create mode 100644 docs/zh/flight_controller/accton-godwit_ga1.md create mode 100644 docs/zh/msg_docs/ArmingCheckRequestV0.md create mode 100644 docs/zh/msg_docs/RoverSpeedSetpoint.md create mode 100644 docs/zh/msg_docs/RoverSpeedStatus.md create mode 100644 docs/zh/sensor/sbgecom.md diff --git a/docs/zh/SUMMARY.md b/docs/zh/SUMMARY.md index 88cb6dc8d8..048ee16c6b 100644 --- a/docs/zh/SUMMARY.md +++ b/docs/zh/SUMMARY.md @@ -157,6 +157,7 @@ - [mRo (3DR) Pixhawk Wiring Quickstart](assembly/quick_start_pixhawk.md) - [Holybro Pixhawk Mini (FMUv3) - Discontinued](flight_controller/pixhawk_mini.md) - [Manufacturer-Supported Autopilots](flight_controller/autopilot_manufacturer_supported.md) + - [Accton Godwit GA1](flight_controller/accton-godwit_ga1.md) - [AirMind MindPX](flight_controller/mindpx.md) - [AirMind MindRacer](flight_controller/mindracer.md) - [ARK Electronics ARKV6X](flight_controller/ark_v6x.md) @@ -283,6 +284,7 @@ - [CubePilot Here+ (Discontined)](gps_compass/rtk_gps_hex_hereplus.md) - [INS (Inertial Navigation/GNSS)](sensor/inertial_navigation_systems.md) - [InertialLabs](sensor/inertiallabs.md) + - [sbgECom](sensor/sbgecom.md) - [VectorNav](sensor/vectornav.md) - [光流](sensor/optical_flow.md) - [ARK 光流](dronecan/ark_flow.md) @@ -679,6 +681,8 @@ - [RoverPositionSetpoint](msg_docs/RoverPositionSetpoint.md) - [RoverRateSetpoint](msg_docs/RoverRateSetpoint.md) - [RoverRateStatus](msg_docs/RoverRateStatus.md) + - [RoverSpeedSetpoint](msg_docs/RoverSpeedSetpoint.md) + - [RoverSpeedStatus](msg_docs/RoverSpeedStatus.md) - [RoverSteeringSetpoint](msg_docs/RoverSteeringSetpoint.md) - [RoverThrottleSetpoint](msg_docs/RoverThrottleSetpoint.md) - [RoverVelocitySetpoint](msg_docs/RoverVelocitySetpoint.md) @@ -739,6 +743,7 @@ - [YawEstimatorStatus](msg_docs/YawEstimatorStatus.md) - [AirspeedValidatedV0](msg_docs/AirspeedValidatedV0.md) - [ArmingCheckReplyV0](msg_docs/ArmingCheckReplyV0.md) + - [ArmingCheckRequestV0](msg_docs/ArmingCheckRequestV0.md) - [BatteryStatusV0](msg_docs/BatteryStatusV0.md) - [EventV0](msg_docs/EventV0.md) - [HomePositionV0](msg_docs/HomePositionV0.md) diff --git a/docs/zh/airframes/airframe_reference.md b/docs/zh/airframes/airframe_reference.md index cc3884a39e..1d821bd5ad 100644 --- a/docs/zh/airframes/airframe_reference.md +++ b/docs/zh/airframes/airframe_reference.md @@ -628,7 +628,16 @@ div.frame_variant td, div.frame_variant th { ### Free-Flyer

- + + + + + + + + + +
常规输出接法
  • Motor1: back left thruster, +x thrust
  • Motor2: front left thruster, -x thrust
  • Motor3: back right thruster, +x thrust
  • Motor4: front right thruster, -x thrust
  • Motor5: front left thruster, +y thrust
  • Motor6: front right thruster, -y thrust
  • Motor7: back left thruster, +y thrust
  • Motor8: back right thruster, -y thrust
@@ -638,7 +647,7 @@ div.frame_variant td, div.frame_variant th { - KTH-ATMOS + KTH-ATMOS Maintainer: DISCOWER

SYS_AUTOSTART = 70000

diff --git a/docs/zh/assembly/_assembly.md b/docs/zh/assembly/_assembly.md index 49f25eedd1..15e97dc7ed 100644 --- a/docs/zh/assembly/_assembly.md +++ b/docs/zh/assembly/_assembly.md @@ -291,7 +291,7 @@ If you're using [DroneCAN ESC](../peripherals/esc_motors.md#dronecan) the contro ### Flight Controller Power Pixhawk FCs require a regulated power supply that can supply at around 5V/3A continuous (check your specific FC)! -This is sufficient to power the controller itself and a few low-power peripherals, such as a GNSS module, RC transmitter, and low power telemetry radio, but not for motors, actuators, and other peripherals. +This is sufficient to power the controller itself and a few low-power peripherals, such as a GNSS module, RC receiver, and low power telemetry radio, but not for motors, actuators, and other peripherals. [Power modules](../power_module/index.md) are commonly used to "split off" this regulated power supply for the FC and also to provide measurements of the battery voltage and total current to the whole system — which PX4 can use to estimate power levels. The power module is connected to the FC power port, which is normally labeled `POWER` (or `POWER 1` or `POWER 2` for FCs that have redundant power supply). diff --git a/docs/zh/concept/system_startup.md b/docs/zh/concept/system_startup.md index e635ca3b23..3986658e97 100644 --- a/docs/zh/concept/system_startup.md +++ b/docs/zh/concept/system_startup.md @@ -13,9 +13,9 @@ The first executed file is the [init.d/rcS](https://github.com/PX4/PX4-Autopilot 根据 PX4 运行的操作系统将本文后续内容分成了如下各小节。 -## Posix (Linux/MacOS) +## POSIX (Linux/MacOS) -在 Posix 操作系统上,系统的 shell 将会作为脚本文件的解释器(例如, 在 Ubuntu 中 /bin/sh 与 Dash 建立了符号链接)。 +On POSIX, the system shell is used as script interpreter (e.g. /bin/sh, being symlinked to dash on Ubuntu). 为了使 PX4 可以在 Posix 中正常运行,需要做到以下几点: - PX4 的各个模块需要看起来像系统的单个可执行文件。 @@ -59,7 +59,7 @@ cd /build/px4_sitl_default/bin ### Dynamic Modules 通常,所有模块都被编入一个 PX4 可执行程序。 -However, on Posix, there's the option of compiling a module into a separate file, which can be loaded into PX4 using the `dyn` command. +However, on POSIX, there's the option of compiling a module into a separate file, which can be loaded into PX4 using the `dyn` command. ```sh dyn ./test.px4mod @@ -95,7 +95,7 @@ The whole boot can be replaced by creating a file `/etc/rc.txt` on the microSD c The best way to customize the system startup is to introduce a [new frame configuration](../dev_airframes/adding_a_new_frame.md). 机架配置文件可以在固件中,也可以在SD卡上。 -#### Dynamic customization +#### Dynamic Customization If you only need to "tweak" the existing configuration, such as starting one more application or setting the value of a few parameters, you can specify these by creating two files in the `/etc/` directory of the SD Card: @@ -153,27 +153,36 @@ Calling an unknown command in system boot files may result in boot failure. mandatory_app start # Will abort boot if mandatory_app is unknown or fails ``` -#### Additional customization +#### Additional Init-File Customization -In rare cases where the desired setup cannot be achieved through frame configuration or dynamic customization, -you can add a script that will be contained in the binary. +In rare cases where the desired setup cannot be achieved through frame configuration or dynamic customization, you can add a script that will be compiled into the binary for a particular `make` target build variant. -**Note**: In almost all cases, you should use a frame configuration. This method should only be used for -edge-cases such as customizing `cannode` based boards. +:::warning +In almost all cases, you should use a frame configuration. +This method should only be used for edge-cases such as customizing `cannode` based boards. +::: + +步骤如下: + +- Add a new init script in `boards///init` that will run during board startup. + 例如: -- Add a new init script in `boards///init` that will run during board startup. 例如: ```sh # File: boards///init/rc.additional param set-default ``` -- Add a new board variant in `boards///.px4board` that includes the additional script. 例如: +- Add a new board variant in `boards///.px4board` that includes the additional script. + 例如: + ```sh # File: boards///var.px4board CONFIG_BOARD_ADDITIONAL_INIT="rc.additional" ``` -- Compile the firmware with your new variant by appending the variant name to the compile target. 例如: +- Compile the firmware with your new variant by appending the variant name to the compile target. + 例如: + ```sh make _var ``` diff --git a/docs/zh/config/safety.md b/docs/zh/config/safety.md index a928faa4ea..4fcba64ce9 100644 --- a/docs/zh/config/safety.md +++ b/docs/zh/config/safety.md @@ -206,23 +206,13 @@ The relevant parameters shown below. ### Position Loss Failsafe Action -The failure action is controlled by [COM_POSCTL_NAVL](../advanced_config/parameter_reference.md#COM_POSCTL_NAVL), based on whether RC control is assumed to be available (and altitude information): - -- `0`: Remote control available. - Switch to _Altitude mode_ if a height estimate is available, otherwise _Stabilized mode_. -- `1`: Remote control _not_ available. - Switch to _Descend mode_ if a height estimate is available, otherwise enter flight termination. - _Descend mode_ is a landing mode that does not require a position estimate. +Multicopters will switch to [Altitude mode](../flight_modes_mc/altitude.md) if a height estimate is available, otherwise [Stabilized mode](../flight_modes_mc/manual_stabilized.md). Fixed-wing planes, and VTOLs not configured to land in hover ([NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT)), have a parameter ([FW_GPSF_LT](../advanced_config/parameter_reference.md#FW_GPSF_LT)) that defines how long they will loiter (circle with a constant roll angle ([FW_GPSF_R](../advanced_config/parameter_reference.md#FW_GPSF_R)) at the current altitude) after losing position before attempting to land. If VTOLs have are configured to switch to hover for landing ([NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT)) then they will first transition and then descend. The relevant parameters for all vehicles shown below. -| 参数 | 描述 | -| -------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [COM_POSCTL_NAVL](../advanced_config/parameter_reference.md#COM_POSCTL_NAVL) | Position control navigation loss response during mission. Values: `0` - assume use of RC, `1` - Assume no RC. | - Parameters that only affect Fixed-wing vehicles: | 参数 | 描述 | diff --git a/docs/zh/dev_setup/dev_env_windows_wsl.md b/docs/zh/dev_setup/dev_env_windows_wsl.md index d0800244f0..769ce4fc46 100644 --- a/docs/zh/dev_setup/dev_env_windows_wsl.md +++ b/docs/zh/dev_setup/dev_env_windows_wsl.md @@ -33,7 +33,7 @@ _QGroundControl for Windows_ is additionally required if you need to: Note that you can also use it to monitor a simulation, but you must manually [connect to the simulation running in WSL](#qgroundcontrol-on-windows). :::info -Connecting to an USB device from within WSL is not natively supported, however it can still be achieved by using the [USBIPD-WIN](https://learn.microsoft.com/en-us/windows/wsl/connect-usb) project. With this you can automatically upload firmware from the command line in WSL using the [`upload`](../dev_setup/building_px4.md#uploading-firmware-flashing-the-board) function. +Connecting to an USB device from within WSL is not natively supported, however it can still be achieved by using the [USBIPD-WIN](https://learn.microsoft.com/en-us/windows/wsl/connect-usb) project. With this you can automatically upload firmware from the command line in WSL using the [`upload`](../dev_setup/building_px4.md#uploading-firmware-flashing-the-board) function. ::: :::info @@ -349,3 +349,9 @@ sudo add-apt-repository ppa:kisak/kisak-mesa sudo apt update sudo apt upgrade ``` + +### QGroundControl not connecting to PX4 SITL + +- The connection between PX4 SITL on WSL2 and QGroundControl on Windows requires [broadcasting](../simulation/index.md#enable-udp-broadcasting) or [streaming to a specific address](../simulation/index.md#enable-streaming-to-specific-address) to be enabled. + Streaming to a specific address should be enabled by default, but is something to check if a connection can't be established. +- Network traffic might be blocked by firewall or antivirus on you system. diff --git a/docs/zh/flight_controller/accton-godwit_ga1.md b/docs/zh/flight_controller/accton-godwit_ga1.md new file mode 100644 index 0000000000..20e78c102b --- /dev/null +++ b/docs/zh/flight_controller/accton-godwit_ga1.md @@ -0,0 +1,153 @@ +# Accton Godwit G-A1 + +:::warning +PX4 does not manufacture this (or any) autopilot. +Contact the [manufacturer](https://cubepilot.org/#/home) for hardware support or compliance issues. +::: + +The G-A1 is a state-of-the-art flight controller developed derived from the [Pixhawk Autopilot v6X Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-012%20Pixhawk%20Autopilot%20v6X%20Standard.pdf). + +It includes an STM32H753 double-precision floating-point FMU processor and an STM32F103 IO coprocessor, multiple IMUs with 6-axis inertial sensors, two pressure/temperature sensors, and a geomagnetic sensor. +It also has independent buses and power supplies, and is designed for safety and rich expansion capabilities. + +With an integrated 10/100M Ethernet Physical Layer (PHY), the G-A1 can also communicate with a mission computer (airborne computer), high-end surveying and mapping cameras, and other UxV-mounted equipment for high-speed communications, meeting the needs of advanced UxV systems. + +:::tip +Visit [Accton-IoT Godwit](https://www.accton-iot.com/godwit/) for more information. +::: + +![AccGodwitGA1](../../assets/flight_controller/accton-godwit/ga1/outlook.png "Accton Godwit G-A1") + +![AccGodwitGA1 Top View](../../assets/flight_controller/accton-godwit/ga1/orientation.png "Accton Godwit G-A1 Top View") + +:::info +This flight controller is [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md). +::: + +## 产品规格 + +### 处理器 + +- STM32H753IIK (Arm® Cortex®-M7 480MHz) +- STM32F103 (Arm® Cortex®-M3, 72MHz) + +### 传感器 + +- Bosch BMI088 (vibration isolated) +- TDK InvenSense ICM-42688-P x 2 (one vibration isolated) +- TDK Barometric Pressure and Temperature Sensor CP-20100 x 2 (one vibration isolated) +- PNI RM3100 Geomagnetic Sensor (vibration isolated) + +### 电源 + +- 4.6V to 5.7V + +### External ports + +- 2 CAN Buses (CAN1 and CAN2) +- 3 TELEM Ports (TELEM1, TELEM2 and TELEM3) +- 2 GPS Ports (GPS1 with safety switch, LED, buzzer, and GPS2) +- 1 PPM IN +- 1 SBUS OUT +- 2 USB Ports (1 TYPE-C and 1 JST GH1.25) +- 1 10/100Base-T Ethernet Port +- 1 DSM/SBUS RC +- 1 UART 4 +- 1 AD&IO Port +- 2 Debug Ports (1 IO Debug and 1 FMU Debug) +- 1 SPI6 Bus +- 4 Power Inputs (Power 1, Power 2, Power C1 and Power C2) +- 16 PWM Servo Outputs (A1-A8 from FMU and M1-M8 from IO) +- Micro SD Socket (supports SD 4.1 & SDIO 4.0 in two databus modes: 1 bit (default) and 4 bits) + +### Size and Dimensions + +- 92.2 (L) x 51.2 (W) x 28.3 (H) mm +- 77.6g (carrier board with IMU) + +## 购买渠道 + +- [Accton-IoT Godwit](https://www.accton-iot.com/godwit/) +- [sales@accton-iot.com](sales@accton-iot.com) + +## 针脚定义 + +![G-A1 Pin definition](../../assets/flight_controller/accton-godwit/ga1/pin_definition.png "G-A1 Pin definition") + +## UART Mapping + +| Serial# | Protocol | Port | 备注 | +| ------- | --------- | ------ | ---------- | +| SERIAL1 | Telem1 | UART7 | /dev/ttyS6 | +| SERIAL2 | Telem2 | UART5 | /dev/ttyS4 | +| SERIAL3 | GPS1 | USART1 | /dev/ttyS0 | +| SERIAL4 | GPS2 | UART8 | /dev/ttyS7 | +| SERIAL5 | Telem3 | USART2 | /dev/ttyS1 | +| SERIAL6 | UART4 | UART4 | /dev/ttyS3 | +| SERIAL7 | FMU Debug | USART3 | | +| SERIAL8 | OTG2 | USB | | + +## Wiring Diagram + +![G-A1 Wiring](../../assets/flight_controller/accton-godwit/ga1/wiring.png "G-A1 Wiring") + +## PWM Output + +PWM M1-M8 (IO Main PWM), A1-A8(FMU PWM). +All these 16 support normal PWM output formats. +FMU PWM A1-A6 can support DShot and B-Directional DShot. +A1-A8(FMU PWM) are grouped as: + +- Group 1: A1, A2, A3, A4 +- Group 2: A5, A6 +- Group 3: A7, A8 + +The motor and servo system should be connected to these ports according to the order outlined in the fuselage reference for your carrier. + +![G-A1 PWM Motor Servo](../../assets/flight_controller/accton-godwit/ga1/motor_servo.png "G-A1 PWM Motor Servo") + +## RC Input + +For DSM/SBUS receivers, connect them to the DSM/SBUS interface which provides dedicated 3.3V and 5V power pins respectively, and check above "Pinout" for detailed pin definition. +PPM receivers should be connected to the PPM interface. And other RC systems can be connected via other spare telemetry ports. + +![G-A1 Radio](../../assets/flight_controller/accton-godwit/ga1/radio.png "G-A1 Radio") + +## GPS/Compass + +The Godwit G-A1 has a built-in compass +Due to potential interference, the autopilot is usually used with an external I2C compass as part of a GPS/Compass combination. + +![G-A1 GPS](../../assets/flight_controller/accton-godwit/ga1/gps.png "G-A1 GPS") + +## Power Connection and Battery Monitor + +This universal controller features a CAN PMU module that supports 3 to 14s lithium batteries. +To ensure proper connection, attach the module's 6-pin connector to the flight control Power C1 and/or Power C2 interface. + +This universal controller does not provide power to the servos. +To power them, an external BEC must be connected to the positive and negative terminals of any A1–A8 or M1–M8 port. + +![G-A1 Power](../../assets/flight_controller/accton-godwit/ga1/power.png "G-A1 Power") + +## SD Card + +The SD card is NOT included in the package, you need to prepare the SD card and insert it into the slot. + +![G-A1 SD Card](../../assets/flight_controller/accton-godwit/ga1/sdcard.png "G-A1 SD Card") + +## 固件 + +The autopilot is compatible with PX4 firmware. And G-A1 can be detected by QGroundControl automatically. Users can also build it with target "accton-godwit_ga1" + +To [build PX4](../dev_setup/building_px4.md) for this target, open up the terminal and enter: + +```sh +make accton-godwit_ga1 +``` + +## More Information and Support + +- [Accton-IoT Godwit](https://www.accton-iot.com/godwit/) +- [sales@accton-iot.com](sales@accton-iot.com) +- [support@accton-iot.com](mailto:support@accton-iot.com) diff --git a/docs/zh/flight_controller/autopilot_manufacturer_supported.md b/docs/zh/flight_controller/autopilot_manufacturer_supported.md index 97e54edd3b..e97d848ed7 100644 --- a/docs/zh/flight_controller/autopilot_manufacturer_supported.md +++ b/docs/zh/flight_controller/autopilot_manufacturer_supported.md @@ -12,6 +12,7 @@ This category includes boards that are not fully compliant with the pixhawk stan The boards in this category are: +- [Accton Godwit GA1](../flight_controller/accton-godwit_ga1.md) - [AirMind MindPX](../flight_controller/mindpx.md) - [AirMind MindRacer](../flight_controller/mindracer.md) - [ARK Electronics ARKV6X](../flight_controller/ark_v6x.md) (and [ARK Electronics Pixhawk Autopilot Bus Carrier](../flight_controller/ark_pab.md)) diff --git a/docs/zh/flight_modes_mc/throw_launch.md b/docs/zh/flight_modes_mc/throw_launch.md index 8bfa6c55f3..fed2552df0 100644 --- a/docs/zh/flight_modes_mc/throw_launch.md +++ b/docs/zh/flight_modes_mc/throw_launch.md @@ -1,6 +1,6 @@ # Throw Launch (Multicopter) - +<0/> <1/> :::warning Experimental diff --git a/docs/zh/modules/modules_driver_ins.md b/docs/zh/modules/modules_driver_ins.md index 25978210ef..d52df4c6a6 100644 --- a/docs/zh/modules/modules_driver_ins.md +++ b/docs/zh/modules/modules_driver_ins.md @@ -45,6 +45,41 @@ MicroStrain [arguments...] status Driver status ``` +## eulernav_bahrs + +Source: [drivers/ins/eulernav_bahrs](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/eulernav_bahrs) + +### 描述 + +Serial bus driver for the EULER-NAV Baro-Inertial AHRS. + +### 示例 + +Attempt to start driver on a specified serial device. + +``` +eulernav_bahrs start -d /dev/ttyS1 +``` + +Stop driver + +``` +eulernav_bahrs stop +``` + +### Usage {#eulernav_bahrs_usage} + +``` +eulernav_bahrs [arguments...] + Commands: + start Start driver + -d Serial device + + status Print driver status + + stop Stop driver +``` + ## ilabs Source: [drivers/ins/ilabs](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/ilabs) diff --git a/docs/zh/msg_docs/ActionRequest.md b/docs/zh/msg_docs/ActionRequest.md index 3579870754..1c724dabb7 100644 --- a/docs/zh/msg_docs/ActionRequest.md +++ b/docs/zh/msg_docs/ActionRequest.md @@ -15,25 +15,25 @@ Request are published by `manual_control` and subscribed by the `commander` and # It allows mapping triggers from various external interfaces like RC channels or MAVLink to cause an action. # Request are published by `manual_control` and subscribed by the `commander` and `vtol_att_control` modules. -uint64 timestamp # [us] Time since system start +uint64 timestamp # [us] Time since system start -uint8 action # [@enum ACTION] Requested action -uint8 ACTION_DISARM = 0 # Disarm vehicle -uint8 ACTION_ARM = 1 # Arm vehicle -uint8 ACTION_TOGGLE_ARMING = 2 # Toggle arming -uint8 ACTION_UNKILL = 3 # Revert a kill action -uint8 ACTION_KILL = 4 # Kill vehicle (instantly stop the motors) -uint8 ACTION_SWITCH_MODE = 5 # Switch mode. The target mode is set in the `mode` field. -uint8 ACTION_VTOL_TRANSITION_TO_MULTICOPTER = 6 # Transition to hover flight -uint8 ACTION_VTOL_TRANSITION_TO_FIXEDWING = 7 # Transition to fast forward flight -uint8 ACTION_TERMINATION = 8 # Irreversably output failsafe values on all outputs, trigger parachute +uint8 action # [@enum ACTION] Requested action +uint8 ACTION_DISARM = 0 # Disarm vehicle +uint8 ACTION_ARM = 1 # Arm vehicle +uint8 ACTION_TOGGLE_ARMING = 2 # Toggle arming +uint8 ACTION_UNKILL = 3 # Revert a kill action +uint8 ACTION_KILL = 4 # Kill vehicle (instantly stop the motors) +uint8 ACTION_SWITCH_MODE = 5 # Switch mode. The target mode is set in the `mode` field. +uint8 ACTION_VTOL_TRANSITION_TO_MULTICOPTER = 6 # Transition to hover flight +uint8 ACTION_VTOL_TRANSITION_TO_FIXEDWING = 7 # Transition to fast forward flight +uint8 ACTION_TERMINATION = 8 # Irreversibly output failsafe values on all outputs, trigger parachute -uint8 source # [@enum SOURCE] Request trigger type, such as a switch, button or gesture -uint8 SOURCE_STICK_GESTURE = 0 # Triggered by holding the sticks in a certain position -uint8 SOURCE_RC_SWITCH = 1 # Triggered by an RC switch moving into a certain position -uint8 SOURCE_RC_BUTTON = 2 # Triggered by a momentary button on the RC being pressed or held -uint8 SOURCE_RC_MODE_SLOT = 3 # Mode change through the RC mode selection mechanism +uint8 source # [@enum SOURCE] Request trigger type, such as a switch, button or gesture +uint8 SOURCE_STICK_GESTURE = 0 # Triggered by holding the sticks in a certain position +uint8 SOURCE_RC_SWITCH = 1 # Triggered by an RC switch moving into a certain position +uint8 SOURCE_RC_BUTTON = 2 # Triggered by a momentary button on the RC being pressed or held +uint8 SOURCE_RC_MODE_SLOT = 3 # Mode change through the RC mode selection mechanism -uint8 mode # Requested mode. Only applies when `action` is `ACTION_SWITCH_MODE`. Values for this field are defined by the `vehicle_status_s::NAVIGATION_STATE_*` enumeration. +uint8 mode # Requested mode. Only applies when `action` is `ACTION_SWITCH_MODE`. Values for this field are defined by the `vehicle_status_s::NAVIGATION_STATE_*` enumeration. ``` diff --git a/docs/zh/msg_docs/ActuatorMotors.md b/docs/zh/msg_docs/ActuatorMotors.md index 06fbd1b908..ca739f6c22 100644 --- a/docs/zh/msg_docs/ActuatorMotors.md +++ b/docs/zh/msg_docs/ActuatorMotors.md @@ -15,14 +15,14 @@ Published by the vehicle's allocation and consumed by the ESC protocol drivers e uint32 MESSAGE_VERSION = 0 -uint64 timestamp # [us] Time since system start -uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on -uint16 reversible_flags # Bitset indicating which motors are configured to be reversible +uint16 reversible_flags # Bitset indicating which motors are configured to be reversible -uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 +uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 # -uint8 NUM_CONTROLS = 12 -float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) +uint8 NUM_CONTROLS = 12 # +float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) ``` diff --git a/docs/zh/msg_docs/ActuatorServos.md b/docs/zh/msg_docs/ActuatorServos.md index ffe01e2f49..6f0a677dbf 100644 --- a/docs/zh/msg_docs/ActuatorServos.md +++ b/docs/zh/msg_docs/ActuatorServos.md @@ -15,10 +15,10 @@ Published by the vehicle's allocation and consumed by the actuator output driver uint32 MESSAGE_VERSION = 0 -uint64 timestamp # [us] Time since system start -uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on -uint8 NUM_CONTROLS = 8 -float32[8] control # [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. +uint8 NUM_CONTROLS = 8 # +float32[8] control # [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. ``` diff --git a/docs/zh/msg_docs/Airspeed.md b/docs/zh/msg_docs/Airspeed.md index 7309747f66..949af8d5e7 100644 --- a/docs/zh/msg_docs/Airspeed.md +++ b/docs/zh/msg_docs/Airspeed.md @@ -13,10 +13,10 @@ It is subscribed by the airspeed selector module, which validates the data from # This is published by airspeed sensor drivers, CAN airspeed sensors, simulators. # It is subscribed by the airspeed selector module, which validates the data from multiple sensors and passes on a single estimation to the EKF, controllers and telemetry providers. -uint64 timestamp # [us] Time since system start -uint64 timestamp_sample # [us] Timestamp of the raw data -float32 indicated_airspeed_m_s # [m/s] Indicated airspeed -float32 true_airspeed_m_s # [m/s] True airspeed -float32 confidence # [@range 0,1] Confidence value for this sensor +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Timestamp of the raw data +float32 indicated_airspeed_m_s # [m/s] Indicated airspeed +float32 true_airspeed_m_s # [m/s] True airspeed +float32 confidence # [@range 0,1] Confidence value for this sensor ``` diff --git a/docs/zh/msg_docs/ArmingCheckReply.md b/docs/zh/msg_docs/ArmingCheckReply.md index d5e3322506..8d619f5aaf 100644 --- a/docs/zh/msg_docs/ArmingCheckReply.md +++ b/docs/zh/msg_docs/ArmingCheckReply.md @@ -21,39 +21,39 @@ The message is not used by internal/FMU components, as their mode requirements a # Note that the external component is identified by its registration_id, which is allocated to the component during registration (arming_check_id in RegisterExtComponentReply). # The message is not used by internal/FMU components, as their mode requirements are known at compile time. -uint32 MESSAGE_VERSION = 1 +uint32 MESSAGE_VERSION = 1 uint64 timestamp # [us] Time since system start. -uint8 request_id # Id of ArmingCheckRequest for which this is a response. -uint8 registration_id # Id of external component emitting this response. +uint8 request_id # Id of ArmingCheckRequest for which this is a response. +uint8 registration_id # Id of external component emitting this response. -uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies. +uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies. -uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX] -bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json). +uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX] +bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json). +bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json). +bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json). -bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed. +bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed. -uint8 num_events # Number of queued failure messages (Event) in the events field. +uint8 num_events # Number of queued failure messages (Event) in the events field. -Event[5] events # Arming failure reasons (Queue of events to report to GCS). +Event[5] events # Arming failure reasons (Queue of events to report to GCS). # Mode requirements -bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope). -bool mode_req_attitude # Requires an attitude estimate. -bool mode_req_local_alt # Requires a local altitude estimate. -bool mode_req_local_position # Requires a local position estimate. -bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate. -bool mode_req_global_position # Requires a global position estimate. -bool mode_req_global_position_relaxed # Requires a relaxed global position estimate. -bool mode_req_mission # Requires an uploaded mission. -bool mode_req_home_position # Requires a home position (such as RTL/Return mode). -bool mode_req_prevent_arming # Prevent arming (such as in Land mode). -bool mode_req_manual_control # Requires a manual controller +bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope). +bool mode_req_attitude # Requires an attitude estimate. +bool mode_req_local_alt # Requires a local altitude estimate. +bool mode_req_local_position # Requires a local position estimate. +bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate. +bool mode_req_global_position # Requires a global position estimate. +bool mode_req_global_position_relaxed # Requires a relaxed global position estimate. +bool mode_req_mission # Requires an uploaded mission. +bool mode_req_home_position # Requires a home position (such as RTL/Return mode). +bool mode_req_prevent_arming # Prevent arming (such as in Land mode). +bool mode_req_manual_control # Requires a manual controller -uint8 ORB_QUEUE_LENGTH = 4 # +uint8 ORB_QUEUE_LENGTH = 4 ``` diff --git a/docs/zh/msg_docs/ArmingCheckRequest.md b/docs/zh/msg_docs/ArmingCheckRequest.md index cfa4b52c23..653d58d2d2 100644 --- a/docs/zh/msg_docs/ArmingCheckRequest.md +++ b/docs/zh/msg_docs/ArmingCheckRequest.md @@ -21,10 +21,12 @@ The reply will also include the registration_id for each external component, pro # The reply will include the published request_id, allowing correlation of all arming check information for a particular request. # The reply will also include the registration_id for each external component, provided to it during the registration process (RegisterExtComponentReply). -uint32 MESSAGE_VERSION = 0 +uint32 MESSAGE_VERSION = 1 -uint64 timestamp # [us] Time since system start. +uint64 timestamp # [us] Time since system start. -uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. +uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. + +uint32 valid_registrations_mask # Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) ``` diff --git a/docs/zh/msg_docs/ArmingCheckRequestV0.md b/docs/zh/msg_docs/ArmingCheckRequestV0.md new file mode 100644 index 0000000000..f5680c11f2 --- /dev/null +++ b/docs/zh/msg_docs/ArmingCheckRequestV0.md @@ -0,0 +1,30 @@ +# ArmingCheckRequestV0 (UORB message) + +Arming check request. + +Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. +All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. +The request is sent regularly, even while armed, so that the FMU always knows the current arming state for external modes, and can forward it to ground stations. + +The reply will include the published request_id, allowing correlation of all arming check information for a particular request. +The reply will also include the registration_id for each external component, provided to it during the registration process (RegisterExtComponentReply). + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/ArmingCheckRequestV0.msg) + +```c +# Arming check request. +# +# Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. +# All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. +# The request is sent regularly, even while armed, so that the FMU always knows the current arming state for external modes, and can forward it to ground stations. +# +# The reply will include the published request_id, allowing correlation of all arming check information for a particular request. +# The reply will also include the registration_id for each external component, provided to it during the registration process (RegisterExtComponentReply). + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # [us] Time since system start. + +uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. + +``` diff --git a/docs/zh/msg_docs/CellularStatus.md b/docs/zh/msg_docs/CellularStatus.md index 6579d3fe85..04ca0a65dc 100644 --- a/docs/zh/msg_docs/CellularStatus.md +++ b/docs/zh/msg_docs/CellularStatus.md @@ -11,39 +11,39 @@ This is currently used only for logging cell status from MAVLink. # # This is currently used only for logging cell status from MAVLink. -uint64 timestamp # [us] Time since system start +uint64 timestamp # [us] Time since system start -uint16 status # [@enum STATUS_FLAG] Status bitmap -uint16 STATUS_FLAG_UNKNOWN = 1 # State unknown or not reportable -uint16 STATUS_FLAG_FAILED = 2 # Modem is unusable -uint16 STATUS_FLAG_INITIALIZING = 4 # Modem is being initialized -uint16 STATUS_FLAG_LOCKED = 8 # Modem is locked -uint16 STATUS_FLAG_DISABLED = 16 # Modem is not enabled and is powered down -uint16 STATUS_FLAG_DISABLING = 32 # Modem is currently transitioning to the STATUS_FLAG_DISABLED state -uint16 STATUS_FLAG_ENABLING = 64 # Modem is currently transitioning to the STATUS_FLAG_ENABLED state -uint16 STATUS_FLAG_ENABLED = 128 # Modem is enabled and powered on but not registered with a network provider and not available for data connections -uint16 STATUS_FLAG_SEARCHING = 256 # Modem is searching for a network provider to register -uint16 STATUS_FLAG_REGISTERED = 512 # Modem is registered with a network provider, and data connections and messaging may be available for use -uint16 STATUS_FLAG_DISCONNECTING = 1024 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated -uint16 STATUS_FLAG_CONNECTING = 2048 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered -uint16 STATUS_FLAG_CONNECTED = 4096 # One or more packet data bearers is active and connected +uint16 status # [@enum STATUS_FLAG] Status bitmap +uint16 STATUS_FLAG_UNKNOWN = 1 # State unknown or not reportable +uint16 STATUS_FLAG_FAILED = 2 # Modem is unusable +uint16 STATUS_FLAG_INITIALIZING = 4 # Modem is being initialized +uint16 STATUS_FLAG_LOCKED = 8 # Modem is locked +uint16 STATUS_FLAG_DISABLED = 16 # Modem is not enabled and is powered down +uint16 STATUS_FLAG_DISABLING = 32 # Modem is currently transitioning to the STATUS_FLAG_DISABLED state +uint16 STATUS_FLAG_ENABLING = 64 # Modem is currently transitioning to the STATUS_FLAG_ENABLED state +uint16 STATUS_FLAG_ENABLED = 128 # Modem is enabled and powered on but not registered with a network provider and not available for data connections +uint16 STATUS_FLAG_SEARCHING = 256 # Modem is searching for a network provider to register +uint16 STATUS_FLAG_REGISTERED = 512 # Modem is registered with a network provider, and data connections and messaging may be available for use +uint16 STATUS_FLAG_DISCONNECTING = 1024 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated +uint16 STATUS_FLAG_CONNECTING = 2048 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered +uint16 STATUS_FLAG_CONNECTED = 4096 # One or more packet data bearers is active and connected -uint8 failure_reason # [@enum FAILURE_REASON] Failure reason -uint8 FAILURE_REASON_NONE = 0 # No error -uint8 FAILURE_REASON_UNKNOWN = 1 # Error state is unknown -uint8 FAILURE_REASON_SIM_MISSING = 2 # SIM is required for the modem but missing -uint8 FAILURE_REASON_SIM_ERROR = 3 # SIM is available, but not usable for connection +uint8 failure_reason # [@enum FAILURE_REASON] Failure reason +uint8 FAILURE_REASON_NONE = 0 # No error +uint8 FAILURE_REASON_UNKNOWN = 1 # Error state is unknown +uint8 FAILURE_REASON_SIM_MISSING = 2 # SIM is required for the modem but missing +uint8 FAILURE_REASON_SIM_ERROR = 3 # SIM is available, but not usable for connection -uint8 type # [@enum CELLULAR_NETWORK_RADIO_TYPE] Cellular network radio type -uint8 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0 # None -uint8 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1 # GSM -uint8 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2 # CDMA -uint8 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3 # WCDMA -uint8 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4 # LTE +uint8 type # [@enum CELLULAR_NETWORK_RADIO_TYPE] Cellular network radio type +uint8 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0 # None +uint8 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1 # GSM +uint8 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2 # CDMA +uint8 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3 # WCDMA +uint8 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4 # LTE -uint8 quality # [dBm] Cellular network RSSI/RSRP, absolute value -uint16 mcc # [@invalid UINT16_MAX] Mobile country code -uint16 mnc # [@invalid UINT16_MAX] Mobile network code -uint16 lac # [@invalid 0] Location area code +uint8 quality # [dBm] Cellular network RSSI/RSRP, absolute value +uint16 mcc # [@invalid UINT16_MAX] Mobile country code +uint16 mnc # [@invalid UINT16_MAX] Mobile network code +uint16 lac # [@invalid 0] Location area code ``` diff --git a/docs/zh/msg_docs/RoverSpeedSetpoint.md b/docs/zh/msg_docs/RoverSpeedSetpoint.md new file mode 100644 index 0000000000..9eea46e60f --- /dev/null +++ b/docs/zh/msg_docs/RoverSpeedSetpoint.md @@ -0,0 +1,14 @@ +# RoverSpeedSetpoint (UORB message) + +Rover Speed Setpoint + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverSpeedSetpoint.msg) + +```c +# Rover Speed Setpoint + +uint64 timestamp # [us] Time since system start +float32 speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction +float32 speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction + +``` diff --git a/docs/zh/msg_docs/RoverSpeedStatus.md b/docs/zh/msg_docs/RoverSpeedStatus.md new file mode 100644 index 0000000000..8c212e2b0f --- /dev/null +++ b/docs/zh/msg_docs/RoverSpeedStatus.md @@ -0,0 +1,18 @@ +# RoverSpeedStatus (UORB message) + +Rover Velocity Status + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverSpeedStatus.msg) + +```c +# Rover Velocity Status + +uint64 timestamp # [us] Time since system start +float32 measured_speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Measured speed in body x direction +float32 adjusted_speed_body_x_setpoint # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction that is being tracked (Applied slew rates) +float32 pid_throttle_body_x_integral # [] [@range -1, 1] Integral of the PID for the closed loop controller of the speed in body x direction +float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction +float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates) +float32 pid_throttle_body_y_integral # [] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction + +``` diff --git a/docs/zh/msg_docs/VehicleAirData.md b/docs/zh/msg_docs/VehicleAirData.md index 75363b8571..dccfefc095 100644 --- a/docs/zh/msg_docs/VehicleAirData.md +++ b/docs/zh/msg_docs/VehicleAirData.md @@ -1,22 +1,26 @@ # VehicleAirData (UORB message) +Vehicle air data + +Data from the currently selected barometer (plus ambient temperature from the source specified in temperature_source). +Includes calculated data such as barometric altitude and air density. + [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleAirData.msg) ```c +# Vehicle air data +# +# Data from the currently selected barometer (plus ambient temperature from the source specified in temperature_source). +# Includes calculated data such as barometric altitude and air density. -uint64 timestamp # time since system start (microseconds) - -uint64 timestamp_sample # the timestamp of the raw data (microseconds) - -uint32 baro_device_id # unique device ID for the selected barometer - -float32 baro_alt_meter # Altitude above MSL calculated from temperature compensated baro sensor data using an ISA corrected for sea level pressure SENS_BARO_QNH. -float32 baro_pressure_pa # Absolute pressure in Pascals -float32 ambient_temperature # Abient temperature in degrees Celsius -uint8 temperature_source # Source of temperature data: 0: Default Temperature (15°C), 1: External Baro, 2: Airspeed - -float32 rho # air density - -uint8 calibration_count # Calibration changed counter. Monotonically increases whenever calibration changes. +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Timestamp of the raw data +uint32 baro_device_id # Unique device ID for the selected barometer +float32 baro_alt_meter # [m] [@frame MSL] Altitude above MSL calculated from temperature compensated baro sensor data using an ISA corrected for sea level pressure SENS_BARO_QNH +float32 baro_pressure_pa # [Pa] Absolute pressure +float32 ambient_temperature # [degC] Ambient temperature +uint8 temperature_source # Source of temperature data: 0: Default Temperature (15°C), 1: External Baro, 2: Airspeed +float32 rho # [kg/m^3] Air density +uint8 calibration_count # Calibration changed counter. Monotonically increases whenever calibration changes. ``` diff --git a/docs/zh/msg_docs/index.md b/docs/zh/msg_docs/index.md index c35c9f1399..9e80e1af98 100644 --- a/docs/zh/msg_docs/index.md +++ b/docs/zh/msg_docs/index.md @@ -229,10 +229,10 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [RoverPositionSetpoint](RoverPositionSetpoint.md) — Rover Position Setpoint - [RoverRateSetpoint](RoverRateSetpoint.md) — Rover Rate setpoint - [RoverRateStatus](RoverRateStatus.md) — Rover Rate Status +- [RoverSpeedSetpoint](RoverSpeedSetpoint.md) — Rover Speed Setpoint +- [RoverSpeedStatus](RoverSpeedStatus.md) — Rover Velocity Status - [RoverSteeringSetpoint](RoverSteeringSetpoint.md) — Rover Steering setpoint - [RoverThrottleSetpoint](RoverThrottleSetpoint.md) — Rover Throttle setpoint -- [RoverVelocitySetpoint](RoverVelocitySetpoint.md) — Rover Velocity Setpoint -- [RoverVelocityStatus](RoverVelocityStatus.md) — Rover Velocity Status - [Rpm](Rpm.md) - [RtlStatus](RtlStatus.md) - [RtlTimeEstimate](RtlTimeEstimate.md) @@ -281,7 +281,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [UlogStreamAck](UlogStreamAck.md) — Ack a previously sent ulog_stream message that had the NEED_ACK flag set - [VehicleAcceleration](VehicleAcceleration.md) -- [VehicleAirData](VehicleAirData.md) +- [VehicleAirData](VehicleAirData.md) — Vehicle air data - [VehicleAngularAccelerationSetpoint](VehicleAngularAccelerationSetpoint.md) - [VehicleConstraints](VehicleConstraints.md) — Local setpoint constraints in NED frame setting something to NaN means that no limit is provided @@ -301,6 +301,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [YawEstimatorStatus](YawEstimatorStatus.md) - [AirspeedValidatedV0](AirspeedValidatedV0.md) - [ArmingCheckReplyV0](ArmingCheckReplyV0.md) +- [ArmingCheckRequestV0](ArmingCheckRequestV0.md) — Arming check request. - [BatteryStatusV0](BatteryStatusV0.md) — Battery status - [EventV0](EventV0.md) — this message is required here in the msg_old folder because other msg are depending on it Events interface diff --git a/docs/zh/releases/main.md b/docs/zh/releases/main.md index 47f39e4554..ce9b6b6e95 100644 --- a/docs/zh/releases/main.md +++ b/docs/zh/releases/main.md @@ -52,7 +52,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### 传感器 -- TBD +- Add [sbgECom INS driver](../sensor/sbgecom.md) ([PX4-Autopilot#24137](https://github.com/PX4/PX4-Autopilot/pull/24137)) ### 仿真 diff --git a/docs/zh/ros2/index.md b/docs/zh/ros2/index.md index 25e075eaf8..bf9ad53aa0 100644 --- a/docs/zh/ros2/index.md +++ b/docs/zh/ros2/index.md @@ -1,45 +1,45 @@ # ROS 2 -[ROS 2](https://docs.ros.org/en/humble/#) is a powerful general purpose robotics library that can be used with the PX4 Autopilot to create powerful drone applications. +ROS 2 是ROS (机器人操作系统)最新版本 , 一个通用的机器人库,可以与 PX4 自驾仪一起创建强大的无人机应用。 :::warning -Tip -The PX4 development team highly recommend that you use/migrate to this version of ROS! +小提示 +PX4开发团队强烈建议您使用/迁移到此版本的 ROS! -This is the newest version of [ROS](https://www.ros.org/) (Robot Operating System). -It significantly improves on ROS "1", and in particular allows a much deeper and lower-latency integration with PX4. +这是最新版本的 [ROS](https://www.ros.org/) (机器人操作系统)。 +它大大改进了外空军备竞赛“1”,尤其是允许与PX4更深、更低的延迟结合。 ::: ROS得益于一个活跃的生态系统,在这个生态系统里,开发者会解决常见的机器人问题,他们也有权使用为Linux编写的其他软件库。 -It can be used, for example, for [computer vision](../computer_vision/index.md) solutions. +例如,它可以用于[计算机视图](../computer_vision/index.md)解决方案。 -ROS 2 enables a very deep integration with PX4, to the extent that you can create flight modes in ROS 2 that are indistinguisable from internal PX4 modes, and directly read from and write to internal uORB topics at high rate. -It is recommended (in particular) for control and communication from a companion computer where low latency is important, when leveraging existing libraries from Linux, or when writing new high level flight modes. +ROS 2能够非常深入地与 PX4 集成 只要你可以在交战规则2中创建无法与内部的 PX4 模式区分的飞行模式, 并以高费率直接读取内部uORB主题。 +建议(尤其是)从同伴计算机进行控制和通信,因为这种计算机的延迟率很低。 当利用来自Linux的现有库时,或在编写新的高层飞行模式时。 -Communication between ROS 2 and PX4 uses middleware that implements the [XRCE-DDS protocol](../middleware/uxrce_dds.md). -This middleware exposes PX4 [uORB messages](../msg_docs/index.md) as ROS 2 messages and types, effectively allowing direct access to PX4 from ROS 2 workflows and nodes. +ROS 2 和 PX4 之间的通信使用中间件实现[XRCE-DDS] (../middleware/uxrce_dds.md)。 +这个中间件将以 ROS 2 消息和类型显示 PX4 [uORB 消息](../msg_docs/index.md), 有效地允许从 ROS 2 工作流和节点直接访问 PX4。 中间件使用 uORB 消息定义生成代码来序列化和反序列化来处理PX4 的收发消息。 -These same message definitions are used in ROS 2 applications to allow the messages to be interpreted. +在ROS 2 应用中使用相同的消息定义可直接进行解析。 :::info -ROS 2 can also connect with PX4 using [MAVROS](https://github.com/mavlink/mavros/tree/ros2/mavros) instead of XRCE-DDS. -This option is supported by the MAVROS project (it is not documented here). +ROS 2 也可以使用 [MAVROS](https://github.com/mavlink/mavros/tree/ros2/mavros而不是 XRCE-DDS连接到 PX4。 +这一备选办法得到了MAVROS项目的支持(此处没有记录)。 ::: -To use the [ROS 2](../ros2/user_guide.md) over XRCE-DDS effectively, you must (at time of writing) have a reasonable understanding of the PX4 internal architecture and conventions, which differ from those used by ROS. +在XRCE-DDS上有效使用[ROS2](../ros2/user_guide.md)。 (撰写本文时)你必须对PX4内部结构和公约有合理的理解,这些结构和公约不同于交战规则所用的内部结构和公约。 我们计划近期提供ROS 2 API 以对 PX4 的特性进行封装,并举例说明它们的用途。 ## Topics 本节的主要主题是: -- [ROS 2 User Guide](../ros2/user_guide.md): A PX4-centric overview of ROS 2, covering installation, setup, and how to build ROS 2 applications that communicate with PX4. -- [ROS 2 Offboard Control Example](../ros2/offboard_control.md): A C++ tutorial examples showing how to do position control in [offboard mode](../flight_modes/offboard.md) from a ROS 2 node. -- [ROS 2 Multi Vehicle Simulation](../ros2/multi_vehicle.md): Instructions for connecting to multipole PX4 simulations via single ROS 2 agent. -- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md): A C++ library that simplies interacting with PX4 from ROS 2. - Can be used to create and register flight modes wrtten using ROS2 and send position estimates from ROS2 applications such as a VIO system. -- [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md): A ROS 2 message translation node that enables communcation between PX4 and ROS 2 applications that were compiled with different sets of messages versions. +- ROS 2 用户指南: PX4 视角下的 ROS 2,包括安装、设置和如何构建与 PX4 通信的 ROS 2 应用。 +- [ROS 2 离板控制示例](../ros2/offboard_control.md):一个 C++ 教程示例显示如何在 [离板模式] (../flight_modes/offboard.md) 中使用 ROS 2 节点进行位置控制。 +- [ROS 2 多车辆模拟](../ros2/multi_vehicle.md):通过单独的ROS2 代理商连接到多极PX4 模拟的说明。 +- [PX4 ROS2 接口库](../ros2/px4_ros2_interface_lib.md):一个C++ 库,它与ROS2的 PX4 交互。 + 可以使用 ROS 2 创建和注册飞行模式,并从 ROS2 应用程序如VIO 系统发送位置估计数。 +- [ROS 2 消息翻译节点](../ros2/px4_ros2_msg_translation_node.md):一个 ROS 2 消息翻译节点,它允许在 PX4 和 ROS 2 应用程序之间共享,这些应用程序被编译成不同的消息版本。 ## 更多信息 -- [XRCE-DDS (PX4-ROS 2/DDS Bridge)](../middleware/uxrce_dds.md): PX4 middleware for connecting to ROS 2. +- [XRCE-DDS (PX4-ROS 2/DDS Bridge)](../middleware/uxrce_dds.md): PX4 使用中间件链接到 ROS 2。 diff --git a/docs/zh/ros2/multi_vehicle.md b/docs/zh/ros2/multi_vehicle.md index 9af8e2a777..ab366b4a5a 100644 --- a/docs/zh/ros2/multi_vehicle.md +++ b/docs/zh/ros2/multi_vehicle.md @@ -1,54 +1,54 @@ -# Multi-Vehicle Simulation with ROS 2 +# 使用 ROS 2 进行多车辆仿真 -[XRCE-DDS](../middleware/uxrce_dds.md) allows for multiple clients to be connected to the same agent over UDP. -This is particular useful in simulation as only one agent needs to be started. +[XRCE-DDS](../middleware/uxrce_dds.md) 支持多个客户端通过 UDP 协议连接到同一个代理。 +这在模拟中特别有用,因为只有一个代理需要启动。 -## Setup and Requirements +## 设置和要求 -The only requirements are +唯一的要求是 -- To be able to run [multi-vehicle simulation](../simulation/multi-vehicle-simulation.md) without ROS 2 with the desired simulator ([Gazebo](../sim_gazebo_gz/multi_vehicle_simulation.md), [Gazebo Classic](../sim_gazebo_classic/multi_vehicle_simulation.md#multiple-vehicle-with-gazebo-classic), [FlightGear](../sim_flightgear/multi_vehicle.md) and [JMAVSim](../sim_jmavsim/multi_vehicle.md)). -- To be able to use [ROS 2](../ros2/user_guide.md) in a single vehicle simulation. +- 能够在不依赖 ROS 2 的情况下,使用所需的仿真器([Gazebo](../sim_gazebo_gz/multi_vehicle_simulation.md), [Gazebo Classic](../sim_gazebo_classic/multi_vehicle_simulation.md#multiple-vehicle-with-gazebo-classic), [FlightGear](../sim_flightgear/multi_vehicle.md) 和 [JMAVSim](../sim_jmavsim/multi_vehicle.md))运行多车辆仿真[multi-vehicle simulation](../simulation/multi-vehicle-simulation.md)。 +- 能够在单车辆仿真中使用ROS 2(机器人操作系统 2) -## Principle of Operation +## 工作原理 -In simulation each PX4 instance receives a unique `px4_instance` number starting from `0`. -This value is used to assign a unique value to [UXRCE_DDS_KEY](../advanced_config/parameter_reference.md#UXRCE_DDS_KEY): +在仿真中,每个 PX4 实例都会获得一个唯一的px4_instance编号,编号从0开始。 +该值用于为 [UXRCE_DDS_KEY](../advanced_config/parameter_reference.md#UXRCE_DDS_KEY)分配一个唯一值: ```sh -param set UXRCE_DDS_KEY $((px4_instance+1)) +参数设置 UXRCE_DDS_KEY $(px4_instance+1)) ``` :::info -By doing so, `UXRCE_DDS_KEY` will always coincide with [MAV_SYS_ID](../advanced_config/parameter_reference.md#MAV_SYS_ID). +通过这种方式,UXRCE_DDS_KEY 将始终与 [MAV_SYS_ID] 保持一致(../advanced_config/parameter_reference.md#MAV_SYS_ID) ::: -Moreover, when `px4_instance` is greater than zero, a unique ROS 2 [namespace prefix](../middleware/uxrce_dds.md#customizing-the-namespace) in the form `px4_$px4_instance` is added: +此外,当 px4_instance 大于 0 时,会添加一个格式为 px4_$px4_instance 的唯一 ROS 2 命名空间前缀: ```sh uxrce_dds_ns="-n px4_$px4_instance" ``` :::info -The environment variable `PX4_UXRCE_DDS_NS`, if set, will override the namespace behavior described above. +环境变量 PX4_UXRCE_DDS_NS 若已设置,将覆盖上文所述的命名空间行为。 ::: -The first instance (`px4_instance=0`) does not have an additional namespace in order to be consistent with the default behavior of the `xrce-dds` client on a real vehicle. -This mismatch can be fixed by manually using `PX4_UXRCE_DDS_NS` on the first instance or by starting adding vehicles from index `1` instead of `0` (this is the default behavior adopted by [sitl_multiple_run.sh](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/simulation/gazebo-classic/sitl_multiple_run.sh) for Gazebo Classic). +第一个实例(px4_instance=0)没有额外的命名空间,此举是为了与真实载具上 xrce-dds 客户端的默认行为保持一致。 +这种不匹配可以通过手动使用 `PX4_UXRCE_DDS_NS` 来修复,或者通过从索引 `1` 中添加车辆而不是 `0` (这是Gazebo Classic的 [sitl_multiple_run.sh](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/simulation/gazebo-classic/sitl_multiple_run.sh) 的默认行为)。 -The default client configuration in simulation is summarized as follows: +模拟中的默认客户端配置概述如下: -| `PX4_UXRCE_DDS_NS` | `px4_instance` | `UXRCE_DDS_KEY` | client namespace | +| `PX4_UXRCE_DDS_NS` | `px4_instance` | `UXRCE_DDS_KEY` | 客户端命名空间 | | ------------------ | -------------- | ---------------- | --------------------- | -| not provided | 0 | `px4_instance+1` | 无 | -| provided | 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | -| not provided | > 0 | `px4_instance+1` | `px4_${px4_instance}` | -| provided | > 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | +| 未提供 | 0 | `px4_instance+1` | 无 | +| 已提供 | 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | +| 未提供 | > 0 | `px4_instance+1` | `px4_${px4_instance}` | +| 已提供 | > 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | -## Adjusting the `target_system` value +## 调整 `target_system` 值 -PX4 accepts [VehicleCommand](../msg_docs/VehicleCommand.md) messages only if their `target_system` field is zero (broadcast communication) or coincides with `MAV_SYS_ID`. -In all other situations, the messages are ignored. -Therefore, when ROS 2 nodes want to send `VehicleCommand` to PX4, they must ensure that the messages are filled with the appropriate `target_system` value. +PX4 只在他们的 `target_system` 字段为 0 (路由通信) 或与 `MAV_SYS_ID` 一致时,才接受 [VehicleCommand](../msg_docs/VehicleCommand.md)。 +在所有其他情况下,信息都被忽视。 +因此,当 ROS 2 节点需向 PX4 发送 VehicleCommand(载具指令)消息时,必须确保消息中填写了合适的 target_system(目标系统)字段值。 For example, if you want to send a command to your third vehicle, which has `px4_instance=2`, you need to set `target_system=3` in all your `VehicleCommand` messages. diff --git a/docs/zh/ros2/offboard_control.md b/docs/zh/ros2/offboard_control.md index 438b02df09..12c4217bf7 100644 --- a/docs/zh/ros2/offboard_control.md +++ b/docs/zh/ros2/offboard_control.md @@ -1,6 +1,6 @@ # ROS 2 Offboard 控制示例 -The following C++ example shows how to do position control in [offboard mode](../flight_modes/offboard.md) from a ROS 2 node. +以下的 C++ 示例展示了如何在 [离板模式] (../flight_modes/offboard.md) 中从 ROS 2 节点进行位置控制。 示例将首先发送设置点、进入offboard模式、解锁、起飞至5米,并悬停等待。 虽然简单,但它显示了如何使用offboard控制以及如何向无人机发送指令。 diff --git a/docs/zh/ros2/px4_ros2_control_interface.md b/docs/zh/ros2/px4_ros2_control_interface.md index 2fcce99656..cc1e139124 100644 --- a/docs/zh/ros2/px4_ros2_control_interface.md +++ b/docs/zh/ros2/px4_ros2_control_interface.md @@ -1,6 +1,6 @@ # PX4 ROS 2 Control Interface - +<0/> <1/> :::warning Experimental @@ -104,26 +104,26 @@ The above concepts provide a number of advantages over traditional [offboard con The following steps are required to get started: -1. Make sure you have a working [ROS 2 setup](../ros2/user_guide.md), with [`px4_msgs`](https://github.com/PX4/px4_msgs) in the ROS 2 workspace. +1. 请确保您在 ROS 2 工作区中有 [ROS 2 设置](../ros2/user_guide.md) 与 [`px4_msgs`](https://github.com/PX4/px4_msgs]。 -2. Clone the repository into the workspace: +2. 将代码仓库克隆到工作空间中 ```sh cd $ros_workspace/src git clone --recursive https://github.com/Auterion/px4-ros2-interface-lib ``` - ::: info - To ensure compatibility, use the latest _main_ branches for PX4, _px4_msgs_ and the library. - See also [here](https://github.com/Auterion/px4-ros2-interface-lib#compatibility-with-px4). + 提示信息 + 为确保兼容性,请使用 PX4、px4_msgs(PX4 消息包)及该库的最新 main 分支。 + 另请参阅 [here](https://github.com/Auterion/px4-ros2-interface-lib#compatibility-with-px4) ::: -3. Build the workspace: +3. 构建工作空间: ```sh cd .. - colcon build + colcon building source install/setup.bash ``` diff --git a/docs/zh/ros2/px4_ros2_interface_lib.md b/docs/zh/ros2/px4_ros2_interface_lib.md index 00cb138ebc..b689861fbe 100644 --- a/docs/zh/ros2/px4_ros2_interface_lib.md +++ b/docs/zh/ros2/px4_ros2_interface_lib.md @@ -1,48 +1,48 @@ -# PX4 ROS 2 Interface Library +# PX4 ROS 2 接口库 - +<0/> <1/> :::warning Experimental -At the time of writing, parts of the PX4 ROS 2 Interface Library are experimental, and hence subject to change. +在撰写本文时,PX4 ROS 2 接口库的部分内容仍处于试验阶段,因此可能会发生变动。 ::: -The [PX4 ROS 2 Interface Library](https://github.com/Auterion/px4-ros2-interface-lib) is a C++ library that simplifies controlling and interacting with PX4 from ROS 2. +[PX4 ROS 2 接口库 ](https://github.com/Auterion/px4-ros2-interface-lib)是一个 C++ 库,可简化从 ROS 2 对 PX4 进行控制和交互的操作。 -The library provides two high-level interfaces for developers: +该库为开发者提供了两个高级接口。 -1. The [Control Interface](./px4_ros2_control_interface.md) allows developers to create and dynamically register modes written using ROS 2. - It provides classes for sending different types of setpoints, ranging from high-level navigation tasks all the way down to direct actuator controls. -2. The [Navigation Interface](./px4_ros2_navigation_interface.md) enables sending vehicle position estimates to PX4 from ROS 2 applications, such as a VIO system. +1. [Control Interface](./px4_ros2_control_interface.md) 允许开发者创建并动态注册使用 ROS2 编写的模式。 + 它为发送不同类型的设置点提供了课程,涵盖范围从高级导航任务一直到直接执行器控制。 +2. [导航界面](./px4_ros2_navigation_interface.md) 允许从ROS 2应用程序(如VIO系统)向PX4发送车辆位置估计数。 -## Installation in a ROS 2 Workspace +## 在 ROS 2 工作区中安装 -To get started using the library within an existing ROS 2 workspace: +要开始使用现有ROS2工作空间内的库: -1. Make sure you have a working [ROS 2 setup](../ros2/user_guide.md), with [`px4_msgs`](https://github.com/PX4/px4_msgs) in the ROS 2 workspace. +1. 请确保您在 ROS 2 工作区中有 [ROS 2 设置](../ros2/user_guide.md) 与 [`px4_msgs`](https://github.com/PX4/px4_msgs]。 -2. Clone the repository into the workspace: +2. 将代码仓库克隆到工作空间中 ```sh cd $ros_workspace/src git clone --recursive https://github.com/Auterion/px4-ros2-interface-lib ``` - ::: info - To ensure compatibility, use the latest _main_ branches for PX4, _px4_msgs_ and the library. - See also [here](https://github.com/Auterion/px4-ros2-interface-lib#compatibility-with-px4). + 提示信息 + 为确保兼容性,请使用 PX4、px4_msgs(PX4 消息包)及该库的最新 main 分支。 + 另请参阅 [here](https://github.com/Auterion/px4-ros2-interface-lib#compatibility-with-px4) ::: -3. Build the workspace: +3. 构建工作空间: ```sh cd .. - colcon build + colcon building source install/setup.bash ``` @@ -50,9 +50,9 @@ To get started using the library within an existing ROS 2 workspace: ## How to Use the Library --> -## CI: Integration Tests +## ROS集成测试 -When opening a pull request to PX4, CI runs the library integration tests. -These test that mode registration, failsafes, and mode replacement, work as expected. +向 PX4 提交拉取请求(pull request)时,持续集成(CI)会运行该库的集成测试 +这些测试用于验证模式注册、故障保护(failsafes)和模式替换功能是否按预期工作。 -For more information see [PX4 ROS2 Interface Library Integration Testing](../test_and_ci/integration_testing_px4_ros2_interface.md). +欲了解更多信息,请访问[PX4 ROS2 接口库集成测试](../test_and_ci/integration_testing_px4_ros2_interface.md)。 diff --git a/docs/zh/ros2/px4_ros2_msg_translation_node.md b/docs/zh/ros2/px4_ros2_msg_translation_node.md index 253ae12527..6d69dc3c01 100644 --- a/docs/zh/ros2/px4_ros2_msg_translation_node.md +++ b/docs/zh/ros2/px4_ros2_msg_translation_node.md @@ -65,7 +65,7 @@ The translation node will print a warning if it encounters an unknown topic vers After making a modification in PX4 to the message definitions and/or translation node code, you will need to rerun the steps above from point 2 to update your ROS workspace accordingly. ::: -### In ROS Applications +### 在ROS 应用中 While developing a ROS 2 application that communicates with PX4, it is not necessary to know the specific version of a message being used. The message version can be added generically to a topic name like this: @@ -183,7 +183,7 @@ class MinimalPubSub(Node): On the PX4 side, the DDS client automatically adds the version suffix if a message definition contains the field `uint32 MESSAGE_VERSION = x`. :::info -Version 0 of a topic means that no `_v` suffix should be added. +主题版本0意味着不应添加`_v`后缀。 ::: ## Development diff --git a/docs/zh/ros2/px4_ros2_navigation_interface.md b/docs/zh/ros2/px4_ros2_navigation_interface.md index e0cab8d948..c726973a17 100644 --- a/docs/zh/ros2/px4_ros2_navigation_interface.md +++ b/docs/zh/ros2/px4_ros2_navigation_interface.md @@ -1,10 +1,10 @@ -# PX4 ROS 2 Navigation Interface +# PX4 ROS2 导航接口 - +<0/> <1/> :::warning Experimental -At the time of writing, parts of the PX4 ROS 2 Interface Library are experimental, and hence subject to change. +在撰写本文时,PX4 ROS 2 接口库的部分内容仍处于试验阶段,因此可能会发生变动。 ::: The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) navigation interface enables developers to send their position measurements to PX4 directly from ROS 2 applications, such as a VIO system or a map matching system. @@ -18,22 +18,22 @@ The `update` method expects a position measurement `struct` ([`LocalPositionMeas The following steps are required to get started: -1. Make sure you have a working [ROS 2 setup](../ros2/user_guide.md), with [`px4_msgs`](https://github.com/PX4/px4_msgs) in the ROS 2 workspace. +1. 请确保您在 ROS 2 工作区中有 [ROS 2 设置](../ros2/user_guide.md) 与 [`px4_msgs`](https://github.com/PX4/px4_msgs]。 -2. Clone the repository into the workspace: +2. 将代码仓库克隆到工作空间中 ```sh cd $ros_workspace/src git clone --recursive https://github.com/Auterion/px4-ros2-interface-lib ``` - ::: info - To ensure compatibility, use the latest _main_ branches for PX4, _px4_msgs_ and the library. - See also [here](https://github.com/Auterion/px4-ros2-interface-lib#compatibility-with-px4). + 提示信息 + 为确保兼容性,请使用 PX4、px4_msgs(PX4 消息包)及该库的最新 main 分支。 + 另请参阅 [here](https://github.com/Auterion/px4-ros2-interface-lib#compatibility-with-px4) ::: -3. Build the workspace: +3. 构建工作空间: ```sh cd .. diff --git a/docs/zh/sensor/accelerometer.md b/docs/zh/sensor/accelerometer.md index 5aebbe6aae..126b56c53d 100644 --- a/docs/zh/sensor/accelerometer.md +++ b/docs/zh/sensor/accelerometer.md @@ -5,7 +5,7 @@ PX4使用加速计数据进行速度估计。 你无需将加速度计作为独立的外部设备进行连接。 - 大多数飞行控制器,例如[Pixhawk系列](../flight_controller/pixhawk_series.md)中的飞行控制器,都将加速度计作为飞行控制器[惯性测量单元(IMU)](https://en.wikipedia.org/wiki/Inertial_measurement_unit)的一部分。 -- 陀螺仪作为[外部惯性导航系统、姿态与航向参考系统或惯性导航增强型全球导航卫星系统](../sensor/inertial_navigation_systems.md)的一部分而存在。 +- Gyroscopes are present as part of an [external INS, AHRS or INS-enhanced GNSS system](../sensor/inertial_navigation_systems.md). 在首次使用载具之前必须校准加速计: diff --git a/docs/zh/sensor/inertial_navigation_systems.md b/docs/zh/sensor/inertial_navigation_systems.md index d5d5d675ea..12cf108625 100644 --- a/docs/zh/sensor/inertial_navigation_systems.md +++ b/docs/zh/sensor/inertial_navigation_systems.md @@ -9,6 +9,7 @@ However PX4 can also use some INS devices as either sources of raw data, or as a INS systems that can be used as a replacement for EKF2 in PX4: - [InertialLabs](../sensor/inertiallabs.md) +- [SBG Systems](../sensor/sbgecom.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data. - [VectorNav](../sensor/vectornav.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data. ## PX4 Firmware diff --git a/docs/zh/sensor/sbgecom.md b/docs/zh/sensor/sbgecom.md new file mode 100644 index 0000000000..315365ab74 --- /dev/null +++ b/docs/zh/sensor/sbgecom.md @@ -0,0 +1,159 @@ +# SBG Systems INS/AHRS (Pulse, Ellipse, etc.) + +[SBG-Systems](https://www.sbg-systems.com/) designs, manufactures, and support an extensive range of state-of-the-art inertial sensors such as Inertial Measurement Units (IMU), Attitude and Heading Reference Systems (AHRS), Inertial Navigation Systems with embedded GNSS (INS/GNSS), and so on. + +PX4 supports [all SBG Systems products](https://www.sbg-systems.com/products/) and can use these as an [external INS](../sensor/inertial_navigation_systems.md) (bypassing/replacing the EKF2 estimator), or as a source of raw sensor data provided to the navigation estimator. + +![Ellipse](../../assets/hardware/sensors/inertial/ellipse-inertial-navigation-system.png) + +## 综述 + +SBG Systems products provide a range of benefits to PX4 users and can be integrated for: + +- Higher accuracy heading, pitch, and roll estimates +- More robust and reliable GNSS positioning +- Improved positioning and attitude performance in GNSS-contested environments +- Performance under challenging dynamic conditions (e.g. catapult launches, VTOL operations, high-g or high angular rate operations) + +The sbgECom PX4 driver is streamlined to provide a simple plug-and-play architecture, removing engineering obstacles and allowing the acceleration of the design, development, and launch of platforms to keep pace with the rapid rate of innovation. + +The driver supports [all SBG Systems products](https://www.sbg-systems.com/products/). +In particular the following systems are recommended: + +- **Pulse:** Recommended for fixed-wing systems without hovering, where static heading is not necessary. +- **Ellipse:** Recommended for multicopter systems where hovering and low dynamics requires the use of static heading. + +## 购买渠道 + +SBG Systems solutions are available directly from [MySBG](https://my.sbg-systems.com) (FR) or through their Global Sales Representatives. For more information on their solutions or for international orders, please contact contact@sbg-systems.com. + +## 硬件安装 + +### 布线 + +Connect any unused flight controller serial interface, such as a spare `GPS` or `TELEM` port, to the SBG Systems product MAIN port (required by PX4). + +### Mounting + +The SBG Systems product sensor can be mounted in any orientation, in any position on the vehicle, without regard to center of gravity. +All SBG Systems product sensors default to a coordinate system of x-forward, y-right, and z-down, making the default mounting as connector-back, base down. +This can be changed to any rigid rotation using the sbgECom Reference Frame Rotation register. + +If using a GNSS-enabled product, the GNSS antenna must be mounted rigidly with respect to the inertial sensor and with an unobstructed sky view. If using a dual-GNSS-enabled product (Ellipse-D), the secondary antenna must be mounted rigidly with respect to the primary antenna and the inertial sensor with an unobstructed sky view. + +For more mounting and configuration requirements and recommendations, see the relevant [SBG SUPPORT CENTER](https://support.sbg-systems.com/sc). + +## Firmware Configuration + +### PX4 配置 + +To use the sbgECom driver: + +1. Include the module in firmware in the [kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) by setting the kconfig variables: `CONFIG_DRIVERS_INS_SBGECOM` or `CONFIG_COMMON_INS`. + +2. [Set the parameter](../advanced_config/parameters.md) [SENS_SBG_CFG](../advanced_config/parameter_reference.md#SENS_SBG_CFG) to the hardware port connected to the SBG Systems product (for more information see [Serial Port Configuration](../peripherals/serial_configuration.md)). + + ::: warning + Disable or change port of other sensors that are using the same one, for example [GPS_1_CONFIG](../advanced_config/parameter_reference.md#GPS_1_CONFIG) if using GPS1 port. + +::: + +3. Set [SBG_BAUDRATE](../advanced_config/parameter_reference.md#SBG_BAUDRATE) to the desired default baudrate value. + +4. Allow the sbgECom driver to initialize by restarting PX4. + +5. Configure driver to provide IMU data, GNSS data and INS : + + 1. Set [SBG_MODE](../advanced_config/parameter_reference.md#SBG_MODE) to the desired mode. + 2. Make sensor module select sensors by enabling [SENS_IMU_MODE](../advanced_config/parameter_reference.md#SENS_IMU_MODE). + 3. Prioritize SBG Systems sensors using [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO), [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO), [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO), [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO), where _n_ is the instance number of the IMU component (0, 1, etc.). + + ::: tip + In most cases the external IMU (SBG) is the highest-numbered. + You can get a list of the IMU components available using [`uorb top -1`](../middleware/uorb.md#uorb-top-command), you can differentiate between them using the [`listener`](../modules/modules_command.md#listener) command and looking through the data, or just the rates. + + Alternatively, you can check [CAL_GYROn_ID](../advanced_config/parameter_reference.md#CAL_GYRO0_ID) to see the device id. + The priority is 0-255, where 0 is entirely disabled and 255 is highest priority. + +::: + + ::: warning + When configuring both SBG Systems and Pixhawk sensors to have non-zero priority, if the selected sensor is errored (timeout), it can change during operation without being notified. + In this case, MAVLink messages will be updated with the newly selected sensor. + + If you don't want to have this fallback mechanism, you must disable unwanted sensors. + +::: + + 4. If using the sbgECom as an INS, disable EKF2 using [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN). + +6. Restart PX4. + +Once enabled, the module will be detected on boot. +IMU data should be published at 200Hz. + +## SBG Systems Configuration + +All High Performance and Ellipse 3.0 and higher SBG Systems INS can be configured directly from PX4 firmware: + +1. Enable [SBG_CONFIGURATION_EN](../advanced_config/parameter_reference.md#SBG_CONFIGURATION_EN) + +2. Provide a JSON file `sbg_settings.json` containing SBG Systems INS settings to be applied in your PX4 board `extras` directory (ex: `boards/px4/fmu-v5/extras`). The settings JSON file will be installed in `/etc/extras/sbg_settings.json` on the board. + + ::: tip + The settings can be retrieved using [sbgEComAPI](https://github.com/SBG-Systems/sbgECom/tree/main/tools/sbgEComApi) or [sbgInsRestApi](https://developer.sbg-systems.com/sbgInsRestApi/1.3/#tag/Settings) and then modified as a JSON file. + +::: + + ::: tip + The settings file can be provided in the SD card in q`/fs/microsd/etc/extras/sbg_settings.json` to avoid rebuilding a new firmware to change JSON settings file. + +::: + +3. For testing purpose, it's also possible to modify SBG Systems INS settings on the fly: + + - By passing a JSON file path as argument when starting sbgecom driver (ex: `sbgecom start -f /fs/microsd/new_sbg_settings.json`) + - By passing a JSON string as argument when starting sbgecom driver: (ex: `sbgecom start -s {"output":{"comA":{"messages":{"airData":"onChange"}}}}`) + +For older Ellipse SBG Systems INS or to configure any SBG Systems INS directly, all commands and registers can be found in the [SBG SUPPORT CENTER](https://support.sbg-systems.com/sc). + +:::warning +If the baudrate of the serial port on the INS product (used to communicate with PX4) is changed, the parameter [SBG_BAUDRATE](../advanced_config/parameter_reference.md#SBG_BAUDRATE) must be changed to match. +::: + +## Published Data + +Upon initialization, the driver should print the following information to console (printed using `PX4_INFO`) + +- Unit model number +- Unit hardware version +- Unit serial number +- Unit firmware number + +This should be accessible using the [`dmesg`](../modules/modules_system.md#dmesg) command. + +The sbgECom driver always publishes the unit's data to the following uORB topics: + +- [sensor_accel](../msg_docs/SensorAccel.md) +- [sensor_gyro](../msg_docs/SensorGyro.md) +- [sensor_mag](../msg_docs/SensorMag.md) + +if configured as a GNSS, publishes: + +- [sensor_gps](../msg_docs/SensorGps.md) + +and, if configured as an INS, publishes: + +- [estimator_status](../msg_docs/EstimatorStatus.md) +- [vehicle_local_position](../msg_docs/VehicleLocalPosition.md) +- [vehicle_global_positon](../msg_docs/VehicleGlobalPosition.md) +- [vehicle_attitude](../msg_docs/VehicleAttitude.md) + +:::tip +Published topics can be viewed using the `listener` command. +::: + +## Hardware Specifications + +- [Product Briefs](https://www.sbg-systems.com/products/) +- [Datasheets](https://www.sbg-systems.com/contact/#products) diff --git a/docs/zh/sim_gazebo_classic/worlds.md b/docs/zh/sim_gazebo_classic/worlds.md index 804df72e9d..5baf68e163 100644 --- a/docs/zh/sim_gazebo_classic/worlds.md +++ b/docs/zh/sim_gazebo_classic/worlds.md @@ -1,6 +1,6 @@ -# Gazebo Classic Worlds +# Gazebo 经典世界 -This topic provides imagery/information about the [Gazebo Classic](../sim_gazebo_classic/index.md) worlds supported by PX4. +这个主题提供了 PX4 支持的 [Gazebo Classic](../sim_gazebo_classic/index.md) 世界的图像/信息。 The [empty.world](#empty_world) is spawned by default, though this may be overridden by a [model specific world](#model_specific_worlds). Developers can also manually specify the world to load: [Gazebo Classic > Loading a Specific World](../sim_gazebo_classic/index.md#loading-a-specific-world). @@ -69,4 +69,4 @@ The model specific worlds are: - [uuv_hippocampus.world](https://github.com/PX4/PX4-SITL_gazebo-classic/blob/main/worlds/uuv_hippocampus.world): An empty world used to simulate an underwater environment for the [HippoCampus UUV](../sim_gazebo_classic/vehicles.md#hippocampus-tuhh-uuv). - [typhoon_h480.world](https://github.com/PX4/PX4-SITL_gazebo-classic/blob/main/worlds/typhoon_h480.world): Used by [Typhoon H480 (Hexrotor)](../sim_gazebo_classic/vehicles.md#typhoon-h480-hexrotor) vehicle model and includes a video widget to enable / disable video streaming. The world includes a gazebo plugin for a simulated camera. -- [iris_irlock.world](https://github.com/PX4/PX4-SITL_gazebo-classic/blob/main/worlds/iris_irlock.world): Includes a IR beacon for testing [precision landing](../advanced_features/precland.md). +- [iris_irlock.world](https://github.com/PX4/PX4-SITL_gazebo-classic/blob/main/worlds/iris_irlock.world): 包括用于测试[精确着陆]的IR 信标(../advanced_features/precland.md)。 diff --git a/docs/zh/test_and_ci/integration_testing_px4_ros2_interface.md b/docs/zh/test_and_ci/integration_testing_px4_ros2_interface.md index 1c967e89f6..17d80ec588 100644 --- a/docs/zh/test_and_ci/integration_testing_px4_ros2_interface.md +++ b/docs/zh/test_and_ci/integration_testing_px4_ros2_interface.md @@ -2,11 +2,11 @@ This topic outlines the integration tests for the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md). -These test that mode registration, failsafes, and mode replacement, work as expected. +这些测试用于验证模式注册、故障保护(failsafes)和模式替换功能是否按预期工作。 ## CI Testing -When opening a pull request to PX4, CI runs the library integration tests. +向 PX4 提交拉取请求(pull request)时,持续集成(CI)会运行该库的集成测试 ## Running Tests Locally From d42aebe10078914a295108473c65c97f01e9acd8 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Tue, 16 Sep 2025 08:57:19 +1000 Subject: [PATCH 033/812] New Crowdin translations - uk (#25558) Co-authored-by: Crowdin Bot --- docs/uk/SUMMARY.md | 5 + docs/uk/advanced/gimbal_control.md | 2 +- docs/uk/advanced/system_tunes.md | 2 +- ..._flight_controller_orientation_leveling.md | 2 +- docs/uk/advanced_config/bootloader_update.md | 112 ++++----- docs/uk/advanced_config/esc_calibration.md | 28 +-- docs/uk/advanced_config/ethernet_setup.md | 122 ++++----- docs/uk/advanced_config/prearm_arm_disarm.md | 50 ++-- .../sensor_thermal_calibration.md | 8 +- docs/uk/advanced_config/tuning_the_ecl_ekf.md | 40 +-- docs/uk/advanced_features/precland.md | 8 +- docs/uk/advanced_features/satcom_roadblock.md | 126 +++++----- docs/uk/airframes/airframe_reference.md | 13 +- docs/uk/assembly/_assembly.md | 2 +- docs/uk/camera/fc_connected_camera.md | 12 +- docs/uk/camera/mavlink_v1_camera.md | 2 +- docs/uk/camera/mavlink_v2_camera.md | 2 +- .../holybro_pixhawk_jetson_baseboard.md | 134 +++++----- .../holybro_pixhawk_rpi_cm4_baseboard.md | 62 ++--- docs/uk/companion_computer/pixhawk_rpi.md | 154 ++++++------ .../video_streaming_wfb_ng_wifi.md | 14 +- .../complete_vehicles_mc/amov_F410_drone.md | 2 +- docs/uk/complete_vehicles_mc/crazyflie2.md | 56 ++--- docs/uk/complete_vehicles_mc/crazyflie21.md | 80 +++--- .../complete_vehicles_mc/modalai_starling.md | 12 +- .../uk/complete_vehicles_mc/px4_vision_kit.md | 158 ++++++------ docs/uk/complete_vehicles_rover/aion_r1.md | 24 +- .../computer_vision/collision_prevention.md | 114 ++++----- .../visual_inertial_odometry.md | 12 +- docs/uk/concept/flight_tasks.md | 80 +++--- docs/uk/concept/system_startup.md | 33 ++- docs/uk/config/_autotune.md | 36 +-- docs/uk/config/actuators.md | 92 +++---- docs/uk/config/airspeed.md | 10 +- docs/uk/config/compass.md | 30 +-- docs/uk/config/firmware.md | 4 +- docs/uk/config/flight_mode.md | 20 +- docs/uk/config/safety.md | 12 +- docs/uk/config/safety_simulation.md | 2 +- docs/uk/config_fw/trimming_guide_fixedwing.md | 6 +- docs/uk/config_heli/index.md | 16 +- docs/uk/config_mc/filter_tuning.md | 12 +- .../pid_tuning_guide_multicopter_basic.md | 70 +++--- docs/uk/config_rover/basic_setup.md | 14 +- docs/uk/config_rover/index.md | 16 +- docs/uk/config_rover/velocity_tuning.md | 2 +- .../uk/config_vtol/vtol_quad_configuration.md | 2 +- docs/uk/contribute/docs.md | 202 +++++++-------- docs/uk/contribute/git_examples.md | 56 ++--- docs/uk/debug/eclipse_jlink.md | 34 +-- docs/uk/debug/failure_injection.md | 12 +- docs/uk/dev_airframes/adding_a_new_frame.md | 56 ++--- docs/uk/dev_log/log_encryption.md | 34 +-- docs/uk/dev_setup/dev_env_linux_ubuntu.md | 22 +- docs/uk/dev_setup/dev_env_mac.md | 78 +++--- .../dev_env_windows_cygwin_packager_setup.md | 14 +- docs/uk/dev_setup/dev_env_windows_vm.md | 20 +- docs/uk/dev_setup/dev_env_windows_wsl.md | 200 ++++++++------- docs/uk/dev_setup/vscode.md | 20 +- docs/uk/dronecan/holybro_h_rtk_zed_f9p_gps.md | 20 +- docs/uk/dronecan/pomegranate_systems_pm.md | 10 +- docs/uk/dronecan/raccoonlab_power.md | 4 +- .../uk/flight_controller/accton-godwit_ga1.md | 153 +++++++++++ .../autopilot_manufacturer_supported.md | 1 + docs/uk/flight_modes_fw/mission.md | 26 +- docs/uk/flight_modes_fw/takeoff.md | 2 +- docs/uk/flight_modes_mc/follow_me.md | 12 +- docs/uk/flight_modes_mc/mission.md | 26 +- docs/uk/flight_modes_mc/throw_launch.md | 28 +-- docs/uk/flying/geofence.md | 2 +- docs/uk/flying/package_delivery_mission.md | 4 +- .../frames_multicopter/dji_f450_cuav_5nano.md | 32 +-- .../frames_multicopter/dji_f450_cuav_5plus.md | 32 +-- .../holybro_qav250_pixhawk4_mini.md | 68 ++--- .../holybro_s500_v2_pixhawk4.md | 128 +++++----- .../holybro_x500V2_pixhawk5x.md | 86 +++---- .../holybro_x500_pixhawk4.md | 108 ++++---- .../holybro_x500v2_pixhawk6c.md | 42 ++-- ...dplane_falcon_vertigo_hybrid_rtf_dropix.md | 60 ++--- .../vtol_quadplane_foxtech_loong_2160.md | 66 ++--- .../vtol_tiltrotor_omp_hobby_zmo_fpv.md | 90 +++---- docs/uk/gps_compass/index.md | 10 +- docs/uk/gps_compass/rtk_gps.md | 28 +-- docs/uk/hardware/board_support_guide.md | 4 +- docs/uk/hardware/porting_guide_nuttx.md | 28 +-- docs/uk/middleware/uxrce_dds.md | 82 +++--- docs/uk/modules/hello_sky.md | 238 +++++++++--------- docs/uk/modules/module_template.md | 30 +-- docs/uk/modules/modules_driver_ins.md | 35 +++ docs/uk/msg_docs/ActionRequest.md | 34 +-- docs/uk/msg_docs/ActuatorMotors.md | 12 +- docs/uk/msg_docs/ActuatorServos.md | 8 +- docs/uk/msg_docs/Airspeed.md | 10 +- docs/uk/msg_docs/ArmingCheckReply.md | 46 ++-- docs/uk/msg_docs/ArmingCheckRequest.md | 8 +- docs/uk/msg_docs/ArmingCheckRequestV0.md | 30 +++ docs/uk/msg_docs/CellularStatus.md | 60 ++--- docs/uk/msg_docs/RoverSpeedSetpoint.md | 14 ++ docs/uk/msg_docs/RoverSpeedStatus.md | 18 ++ docs/uk/msg_docs/VehicleAirData.md | 32 +-- docs/uk/msg_docs/index.md | 7 +- docs/uk/payloads/generic_actuator_control.md | 2 +- docs/uk/peripherals/gripper.md | 12 +- docs/uk/peripherals/remote_id.md | 8 +- docs/uk/releases/1.14.md | 12 +- docs/uk/releases/main.md | 2 +- docs/uk/ros/mavros_custom_messages.md | 2 +- docs/uk/ros/mavros_installation.md | 22 +- docs/uk/ros/offboard_control.md | 4 +- docs/uk/ros2/px4_ros2_control_interface.md | 130 +++++----- docs/uk/ros2/px4_ros2_msg_translation_node.md | 180 ++++++------- docs/uk/ros2/px4_ros2_navigation_interface.md | 102 ++++---- docs/uk/ros2/user_guide.md | 212 ++++++++-------- docs/uk/sensor/accelerometer.md | 2 +- docs/uk/sensor/inertial_navigation_systems.md | 1 + docs/uk/sensor/inertiallabs.md | 8 +- docs/uk/sensor/rangefinders.md | 6 +- docs/uk/sensor/sbgecom.md | 159 ++++++++++++ docs/uk/sensor/vectornav.md | 16 +- docs/uk/sim_flightgear/index.md | 32 +-- docs/uk/sim_gazebo_classic/index.md | 32 +-- .../multi_vehicle_simulation.md | 104 ++++---- docs/uk/sim_gazebo_gz/gazebo_models.md | 12 +- docs/uk/sim_gazebo_gz/index.md | 66 ++--- docs/uk/sim_gazebo_gz/plugins.md | 4 +- docs/uk/sim_gazebo_gz/tools_avl_automation.md | 40 +-- docs/uk/sim_jmavsim/index.md | 22 +- docs/uk/simulation/index.md | 18 +- docs/uk/telemetry/crsf_telemetry.md | 42 ++-- docs/uk/telemetry/jfi_telemetry.md | 6 +- docs/uk/test_and_ci/fuzz_tests.md | 6 +- docs/uk/test_and_ci/index.md | 6 +- .../integration_testing_ros1_mavros.md | 128 +++++----- docs/uk/test_and_ci/unit_tests.md | 40 +-- docs/uk/test_cards/mc_04_failsafe_testing.md | 8 +- .../uart/user_configurable_serial_driver.md | 46 ++-- 136 files changed, 3113 insertions(+), 2676 deletions(-) create mode 100644 docs/uk/flight_controller/accton-godwit_ga1.md create mode 100644 docs/uk/msg_docs/ArmingCheckRequestV0.md create mode 100644 docs/uk/msg_docs/RoverSpeedSetpoint.md create mode 100644 docs/uk/msg_docs/RoverSpeedStatus.md create mode 100644 docs/uk/sensor/sbgecom.md diff --git a/docs/uk/SUMMARY.md b/docs/uk/SUMMARY.md index 90a224480d..037c8e78fe 100644 --- a/docs/uk/SUMMARY.md +++ b/docs/uk/SUMMARY.md @@ -157,6 +157,7 @@ - [Швидке підключення mRo (3DR) Pixhawk](assembly/quick_start_pixhawk.md) - [Holybro Pixhawk Mini (FMUv3) - Припинено](flight_controller/pixhawk_mini.md) - [Автопілоти, що підтримуються виробником](flight_controller/autopilot_manufacturer_supported.md) + - [Accton Godwit GA1](flight_controller/accton-godwit_ga1.md) - [AirMind MindPX](flight_controller/mindpx.md) - [AirMind MindRacer](flight_controller/mindracer.md) - [ARK Electronics ARKV6X](flight_controller/ark_v6x.md) @@ -283,6 +284,7 @@ - [CubePilot Here+ (Discontined)](gps_compass/rtk_gps_hex_hereplus.md) - [INS (Інерціальна навігація/GNSS)](sensor/inertial_navigation_systems.md) - [InertialLabs](sensor/inertiallabs.md) + - [sbgECom](sensor/sbgecom.md) - [VectorNav](sensor/vectornav.md) - [Optical Flow](sensor/optical_flow.md) - [ARK Flow](dronecan/ark_flow.md) @@ -679,6 +681,8 @@ - [RoverPositionSetpoint](msg_docs/RoverPositionSetpoint.md) - [RoverRateSetpoint](msg_docs/RoverRateSetpoint.md) - [RoverRateStatus](msg_docs/RoverRateStatus.md) + - [RoverSpeedSetpoint](msg_docs/RoverSpeedSetpoint.md) + - [RoverSpeedStatus](msg_docs/RoverSpeedStatus.md) - [RoverSteeringSetpoint](msg_docs/RoverSteeringSetpoint.md) - [RoverThrottleSetpoint](msg_docs/RoverThrottleSetpoint.md) - [RoverVelocitySetpoint](msg_docs/RoverVelocitySetpoint.md) @@ -739,6 +743,7 @@ - [YawEstimatorStatus](msg_docs/YawEstimatorStatus.md) - [AirspeedValidatedV0](msg_docs/AirspeedValidatedV0.md) - [ArmingCheckReplyV0](msg_docs/ArmingCheckReplyV0.md) + - [ArmingCheckRequestV0](msg_docs/ArmingCheckRequestV0.md) - [BatteryStatusV0](msg_docs/BatteryStatusV0.md) - [EventV0](msg_docs/EventV0.md) - [HomePositionV0](msg_docs/HomePositionV0.md) diff --git a/docs/uk/advanced/gimbal_control.md b/docs/uk/advanced/gimbal_control.md index 3cf2fbbaf4..3a8bbe08ff 100644 --- a/docs/uk/advanced/gimbal_control.md +++ b/docs/uk/advanced/gimbal_control.md @@ -131,7 +131,7 @@ The on-screen gimbal control can be used to move/test a connected MAVLink camera 2. Open QGroundControl and enable the on-screen camera control (Application settings). - ![Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../../assets/qgc/fly/gimbal_control_x500gz.png) + ![Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../../assets/qgc/fly/gimbal_control_x500gz.png) 3. Make sure the vehicle is armed and flying, e.g. by entering with `commander takeoff`. diff --git a/docs/uk/advanced/system_tunes.md b/docs/uk/advanced/system_tunes.md index 2d169f624c..a7bcaa0e16 100644 --- a/docs/uk/advanced/system_tunes.md +++ b/docs/uk/advanced/system_tunes.md @@ -52,7 +52,7 @@ PX4 визначає ряд [стандартних мелодій/тем](../ge 7. Коли ви будете готові зберегти музику: - Натисніть **F2**, щоб дати мелодії назву та зберегти її у підпапці _/Music_ вашої інсталяції Melody Master. - Натисніть **F7**, прокрутіть список вихідних форматів праворуч, щоб перейти до ANSI. - Файл буде експортовано в _кореневий каталог_ каталогу Melody Master (з такою самою назвою та розширенням типу файлу). + Файл буде експортовано в _кореневий каталог_ каталогу Melody Master (з такою самою назвою та розширенням типу файлу). 8. Відкрийте файл. Результат може виглядати так: diff --git a/docs/uk/advanced_config/advanced_flight_controller_orientation_leveling.md b/docs/uk/advanced_config/advanced_flight_controller_orientation_leveling.md index 5b033e1371..f21f7bbb51 100644 --- a/docs/uk/advanced_config/advanced_flight_controller_orientation_leveling.md +++ b/docs/uk/advanced_config/advanced_flight_controller_orientation_leveling.md @@ -23,7 +23,7 @@ 1. Відкрийте меню QGroundControl: **Settings > Parameters > Sensor Calibration**. 2. Параметри, розташовані в розділі, як показано нижче (або ви можете знайти їх): - ![FC Orientation QGC v2](../../assets/qgc/setup/sensor/fc_orientation_qgc_v2.png) + ![FC Orientation QGC v2](../../assets/qgc/setup/sensor/fc_orientation_qgc_v2.png) ## Підсумок параметра diff --git a/docs/uk/advanced_config/bootloader_update.md b/docs/uk/advanced_config/bootloader_update.md index 9d9c19989d..faed8e2e0e 100644 --- a/docs/uk/advanced_config/bootloader_update.md +++ b/docs/uk/advanced_config/bootloader_update.md @@ -37,8 +37,8 @@ You can enable this key in your own custom firmware if needed. 2. [Оновіть прошивку](../config/firmware.md#custom) з образом, що містить новий/потрібний завантажувач. - ::: info - The updated bootloader might be included the default firmware for your board or supplied in custom firmware. + ::: info + The updated bootloader might be included the default firmware for your board or supplied in custom firmware. ::: @@ -47,7 +47,7 @@ You can enable this key in your own custom firmware if needed. 4. [Знайдіть](../advanced_config/parameters.md) та увімкніть параметр [SYS_BL_UPDATE](../advanced_config/parameter_reference.md#SYS_BL_UPDATE). 5. Перезавантажте (відключіть / підключіть плату). - Оновлення завантажувача займе лише кілька секунд. + Оновлення завантажувача займе лише кілька секунд. Зазвичай на цьому етапі ви можливо захочете [оновити прошивку](../config/firmware.md) ще раз, використовуючи правильно/ново встановлений загрузчик. @@ -89,80 +89,80 @@ PX4 boards up to FMUv5X (before STM32H7) used the [PX4 bootloader](https://githu 1. Отримайте бінарний файл, який містить завантажувальник (або від команди розробників, або [зіберіть його самостійно](#building-the-px4-bootloader)). 2. Get a [Debug Probe](../debug/swd_debug.md#debug-probes-for-px4-hardware). - Підключіть зонд до комп'ютера за допомогою USB та налаштуйте `gdbserver`. + Підключіть зонд до комп'ютера за допомогою USB та налаштуйте `gdbserver`. 3. Перейдіть до каталогу, що містить бінарний файл, і запустіть команду для обраного вами завантажувача в терміналі: - - FMUv6X + - FMUv6X - ```sh - arm-none-eabi-gdb px4_fmu-v6x_bootloader.elf - ``` + ```sh + arm-none-eabi-gdb px4_fmu-v6x_bootloader.elf + ``` - - FMUv6X-RT + - FMUv6X-RT - ```sh - arm-none-eabi-gdb px4_fmu-v6xrt_bootloader.elf - ``` + ```sh + arm-none-eabi-gdb px4_fmu-v6xrt_bootloader.elf + ``` - - FMUv5 + - FMUv5 - ```sh - arm-none-eabi-gdb px4fmuv5_bl.elf - ``` + ```sh + arm-none-eabi-gdb px4fmuv5_bl.elf + ``` - H7 Завантажувачі з [PX4/PX4-Autopilot](https://github.com/PX4/PX4-Autopilot) мають назву за шаблоном `*._bootloader.elf`. - Завантажувачі з [PX4/PX4-Bootloader](https://github.com/PX4/PX4-Bootloader) мають назву за шаблоном `*_bl.elf`. + H7 Завантажувачі з [PX4/PX4-Autopilot](https://github.com/PX4/PX4-Autopilot) мають назву за шаблоном `*._bootloader.elf`. + Завантажувачі з [PX4/PX4-Bootloader](https://github.com/PX4/PX4-Bootloader) мають назву за шаблоном `*_bl.elf`. ::: 4. The _gdb terminal_ appears and it should display (something like) the following output: - ```sh - GNU gdb (GNU Tools for Arm Embedded Processors 7-2017-q4-major) 8.0.50.20171128-git - Copyright (C) 2017 Free Software Foundation, Inc. - License GPLv3+: GNU GPL version 3 or later - This is free software: you are free to change and redistribute it. - There is NO WARRANTY, to the extent permitted by law. - Type "show copying" and "show warranty" for details. - This GDB was configured as "--host=x86_64-linux-gnu --target=arm-none-eabi". - Type "show configuration" for configuration details. - For bug reporting instructions, please see: - . - Find the GDB manual and other documentation resources online at: - . - For help, type "help". - Type "apropos word" to search for commands related to "word"... - Reading symbols from px4fmuv5_bl.elf...done. - ``` + ```sh + GNU gdb (GNU Tools for Arm Embedded Processors 7-2017-q4-major) 8.0.50.20171128-git + Copyright (C) 2017 Free Software Foundation, Inc. + License GPLv3+: GNU GPL version 3 or later + This is free software: you are free to change and redistribute it. + There is NO WARRANTY, to the extent permitted by law. + Type "show copying" and "show warranty" for details. + This GDB was configured as "--host=x86_64-linux-gnu --target=arm-none-eabi". + Type "show configuration" for configuration details. + For bug reporting instructions, please see: + . + Find the GDB manual and other documentation resources online at: + . + For help, type "help". + Type "apropos word" to search for commands related to "word"... + Reading symbols from px4fmuv5_bl.elf...done. + ``` 5. Find your `` by running an `ls` command in the **/dev/serial/by-id** directory. 6. Тепер підключіться до debug probe з наступною командою: - ```sh - tar ext /dev/serial/by-id/ - ``` + ```sh + tar ext /dev/serial/by-id/ + ``` 7. Увімкніть Pixhawk за допомогою іншого USB-кабелю та під’єднайте зонд до порту `FMU-DEBUG`. - ::: info - If using a Zubax BugFace BF1 you may need to remove the case in order to connect to the `FMU-DEBUG` port (e.g. on Pixhawk 4 you would do this using a T6 Torx screwdriver). + ::: info + If using a Zubax BugFace BF1 you may need to remove the case in order to connect to the `FMU-DEBUG` port (e.g. on Pixhawk 4 you would do this using a T6 Torx screwdriver). ::: 8. Використовуйте таку команду, щоб знайти SWD Pixhawk і підключитися до нього: - ```sh - (gdb) mon swdp_scan - (gdb) attach 1 - ``` + ```sh + (gdb) mon swdp_scan + (gdb) attach 1 + ``` 9. Завантажте двійковий файл в Pixhawk: - ```sh - (gdb) load - ``` + ```sh + (gdb) load + ``` Після оновлення завантажувача ви можете [завантажити прошивку PX4](../config/firmware.md) за допомогою _QGroundControl_. @@ -181,25 +181,25 @@ This example explains how you can use [QGC Bootloader Update](qgc-bootloader-upd 1. Вставте SD-карту (це дозволяє реєструвати журнали завантаження для відлагодження будь-яких проблем). 2. [Оновіть програмне забезпечення](../config/firmware.md) до версії PX4 _master_ (під час оновлення програмного забезпечення перевірте **Розширені налаштування** і виберіть **Розробницьку збірку (master)** із випадаючого списку). - _QGroundControl_ автоматично виявить, що апаратне забезпечення підтримує FMUv2 і встановить відповідне програмне забезпечення. + _QGroundControl_ автоматично виявить, що апаратне забезпечення підтримує FMUv2 і встановить відповідне програмне забезпечення. - ![FMUv2 update](../../assets/qgc/setup/firmware/bootloader_update.jpg) + ![FMUv2 update](../../assets/qgc/setup/firmware/bootloader_update.jpg) - Зачекайте, доки транспортний засіб перезавантажиться. + Зачекайте, доки транспортний засіб перезавантажиться. 3. [Знайдіть](../advanced_config/parameters.md) та увімкніть параметр [SYS_BL_UPDATE](../advanced_config/parameter_reference.md#SYS_BL_UPDATE). 4. Перезавантажте (відключіть / підключіть плату). - Оновлення завантажувача займе лише кілька секунд. + Оновлення завантажувача займе лише кілька секунд. 5. Тоді знову [Оновити програмне забезпечення](../config/firmware.md). - На цей раз _QGroundControl_ повинен автоматично визначити обладнання як FMUv3 і відповідним чином оновити програмне забезпечення. + На цей раз _QGroundControl_ повинен автоматично визначити обладнання як FMUv3 і відповідним чином оновити програмне забезпечення. - ![FMUv3 update](../../assets/qgc/setup/firmware/bootloader_fmu_v3_update.jpg) + ![FMUv3 update](../../assets/qgc/setup/firmware/bootloader_fmu_v3_update.jpg) - ::: info - Якщо апаратне забезпечення має [Помилки в кремнієвій мікросхемі](../flight_controller/silicon_errata.md#fmuv2-pixhawk-silicon-errata), воно все одно буде виявлене як FMUv2, і ви побачите, що FMUv2 було знову встановлено (у консолі). - У цьому випадку ви не зможете встановити апаратне забезпечення FMUv3. + ::: info + Якщо апаратне забезпечення має [Помилки в кремнієвій мікросхемі](../flight_controller/silicon_errata.md#fmuv2-pixhawk-silicon-errata), воно все одно буде виявлене як FMUv2, і ви побачите, що FMUv2 було знову встановлено (у консолі). + У цьому випадку ви не зможете встановити апаратне забезпечення FMUv3. ::: diff --git a/docs/uk/advanced_config/esc_calibration.md b/docs/uk/advanced_config/esc_calibration.md index b2fce9058f..c48d3ecf1d 100644 --- a/docs/uk/advanced_config/esc_calibration.md +++ b/docs/uk/advanced_config/esc_calibration.md @@ -92,29 +92,29 @@ ESC OneShot слід [налаштувати на використання ре - Мінімальне значення для мотора (за замовчуванням: 1100 мкс) повинно забезпечувати повільний, але надійний оберт мотора, а також надійно запускати його після зупинки. - Ви можете підтвердити, що мотор обертається мінімально (без пропеллерів) в [TestActuator](../config/actuators. d#actuator-testing), увімкнувши повзунки, а потім переміщуючи повзунок виводу тесту для двигуна в першу позицію відключення від низу. - Правильне значення має зробити так, що мотор обертається негайно і надійно при пересуванні повзунка зі стану роззброєності до мінімуму. + Ви можете підтвердити, що мотор обертається мінімально (без пропеллерів) в [TestActuator](../config/actuators. d#actuator-testing), увімкнувши повзунки, а потім переміщуючи повзунок виводу тесту для двигуна в першу позицію відключення від низу. + Правильне значення має зробити так, що мотор обертається негайно і надійно при пересуванні повзунка зі стану роззброєності до мінімуму. - Щоб знайти «оптимальне» мінімальне значення, пересуньте повзунок вниз (режим роззброєності). - Потім збільшуйте значення PWM-виходу в режимі `роззброєності` невеликими інкрементами (наприклад, 1025 мкс, 1050 мкс і т. д.), доки мотор не почне надійно обертатися (краще бути трохи вище, ніж трохи нижче). - Введіть це значення в параметр «мінімум» для всіх вихідних PWM сигналів мотора, а вихідний сигнал `роззброєності` відновіть до `1100 мкс`. + Щоб знайти «оптимальне» мінімальне значення, пересуньте повзунок вниз (режим роззброєності). + Потім збільшуйте значення PWM-виходу в режимі `роззброєності` невеликими інкрементами (наприклад, 1025 мкс, 1050 мкс і т. д.), доки мотор не почне надійно обертатися (краще бути трохи вище, ніж трохи нижче). + Введіть це значення в параметр «мінімум» для всіх вихідних PWM сигналів мотора, а вихідний сигнал `роззброєності` відновіть до `1100 мкс`. - Максимальне значення для мотора (за замовчуванням: `1900 мкс`) слід вибрати так, щоб збільшення значення не зробило мотор обертатися швидше. - Ви можете підтвердити, що мотор обертається швидко при максимальному значенні у режимі [Тестування приводів](../config/actuators.md#actuator-testing), перемістивши пов'язаний слайдер випробування вверх. + Ви можете підтвердити, що мотор обертається швидко при максимальному значенні у режимі [Тестування приводів](../config/actuators.md#actuator-testing), перемістивши пов'язаний слайдер випробування вверх. - Щоб знайти "оптимальне" максимальне значення, спочатку перемістіть повзунок вниз (роззброєно). - Потім збільште налаштування вихідної потужності PWM `вимкненої` близько до максимального значення за замовчуванням (`1900`) - мотори повинні розганятися. - Слухайте тон мотора, коли збільшуєте максимальне значення PWM для виводу поетапно (наприклад, 1925 мкс, 1950 мкс і так далі). - Оптимальне значення визначається в той момент, коли звук моторів не змінюється при збільшенні значення виводу. - Введіть це значення в параметр `максимум` для всіх виводів ШІМ мотора, а також відновіть значення виводу `знято` на `1100 мкс`. + Щоб знайти "оптимальне" максимальне значення, спочатку перемістіть повзунок вниз (роззброєно). + Потім збільште налаштування вихідної потужності PWM `вимкненої` близько до максимального значення за замовчуванням (`1900`) - мотори повинні розганятися. + Слухайте тон мотора, коли збільшуєте максимальне значення PWM для виводу поетапно (наприклад, 1925 мкс, 1950 мкс і так далі). + Оптимальне значення визначається в той момент, коли звук моторів не змінюється при збільшенні значення виводу. + Введіть це значення в параметр `максимум` для всіх виводів ШІМ мотора, а також відновіть значення виводу `знято` на `1100 мкс`. - Значення виводу «знято» для мотора (за замовчуванням: `1000 мкс`) повинно зупиняти мотор і залишати його зупиненим. - Ви можете підтвердити це в розділі [Тестування виконавчих механізмів](../config/actuators.md#actuator-testing), перемістивши слайдер виводу тестування до фіксованого положення у нижній частині слайдера і спостерігаючи, що двигун не обертається. + Ви можете підтвердити це в розділі [Тестування виконавчих механізмів](../config/actuators.md#actuator-testing), перемістивши слайдер виводу тестування до фіксованого положення у нижній частині слайдера і спостерігаючи, що двигун не обертається. - Якщо ESC обертається за замовчуванням на значенні 1000 мкс, то ESC не правильно калібрується. - Якщо використовуєте ESC, який не може бути калібрований, вам слід зменшити значення виведення ШІМ для виводу до значення, коли мотор більше не обертається (наприклад, 950 мкс або 900 мкс). + Якщо ESC обертається за замовчуванням на значенні 1000 мкс, то ESC не правильно калібрується. + Якщо використовуєте ESC, який не може бути калібрований, вам слід зменшити значення виведення ШІМ для виводу до значення, коли мотор більше не обертається (наприклад, 950 мкс або 900 мкс). ::: info VTOL and fixed-wing motors do not need any special PWM configuration. diff --git a/docs/uk/advanced_config/ethernet_setup.md b/docs/uk/advanced_config/ethernet_setup.md index 87dacceeda..7a977ab488 100644 --- a/docs/uk/advanced_config/ethernet_setup.md +++ b/docs/uk/advanced_config/ethernet_setup.md @@ -87,14 +87,14 @@ DNS=10.41.10.254 3. Введіть команди "like" до наведених нижче у _Консоль MAVLink_ (щоб записати значення у файл конфігурації): - ```sh - echo DEVICE=eth0 > /fs/microsd/net.cfg - echo BOOTPROTO=fallback >> /fs/microsd/net.cfg - echo IPADDR=10.41.10.2 >> /fs/microsd/net.cfg - echo NETMASK=255.255.255.0 >>/fs/microsd/net.cfg - echo ROUTER=10.41.10.254 >>/fs/microsd/net.cfg - echo DNS=10.41.10.254 >>/fs/microsd/net.cfg - ``` + ```sh + echo DEVICE=eth0 > /fs/microsd/net.cfg + echo BOOTPROTO=fallback >> /fs/microsd/net.cfg + echo IPADDR=10.41.10.2 >> /fs/microsd/net.cfg + echo NETMASK=255.255.255.0 >>/fs/microsd/net.cfg + echo ROUTER=10.41.10.254 >>/fs/microsd/net.cfg + echo DNS=10.41.10.254 >>/fs/microsd/net.cfg + ``` 4. Після встановлення конфігурації мережі можна від’єднати кабель USB. @@ -113,36 +113,36 @@ Note that there are many more [examples](https://github.com/canonical/netplan/tr Для установки Ubuntu комп'ютера: 1. In a terminal, create and open a `netplan` configuration file: `/etc/netplan/01-network-manager-all.yaml` - Below we do this using the _nano_ text editor. + Below we do this using the _nano_ text editor. - ``` - sudo nano /etc/netplan/01-network-manager-all.yaml - ``` + ``` + sudo nano /etc/netplan/01-network-manager-all.yaml + ``` 2. Скопіюйте та вставте наступну конфігураційну інформацію у файл (зверніть увагу: відступи мають значення!): - ``` - network: - version: 2 - renderer: NetworkManager - ethernets: - enp2s0: - addresses: - - 10.41.10.1/24 - nameservers: - addresses: [10.41.10.1] - routes: - - to: 10.41.10.1 - via: 10.41.10.1 - ``` + ``` + network: + version: 2 + renderer: NetworkManager + ethernets: + enp2s0: + addresses: + - 10.41.10.1/24 + nameservers: + addresses: [10.41.10.1] + routes: + - to: 10.41.10.1 + via: 10.41.10.1 + ``` - Збережіть і закрийте файл. + Збережіть і закрийте файл. 3. Застосуйте конфігурацію _netplan_, введіть наступну команду в термінал Ubuntu. - ``` - sudo netplan apply - ``` + ``` + sudo netplan apply + ``` ### Комп’ютер-супутник Налаштування мережі Ethernet @@ -189,9 +189,9 @@ Assuming you have already [Set up the Ethernet Network](#setting-up-the-ethernet 3. Запустіть QGroundControl та [визначте комунікаційний канал](https://docs.qgroundcontrol.com/master/en/SettingsView/SettingsView.html) (**Налаштування додатка > Канали зв'язку**), вказавши _адресу сервера_ та порт як IP-адресу та порт, призначений в PX4, відповідно. - Припускаючи, що значення встановлені так, як описано в решті цієї теми, налаштування виглядатиме наступним чином: + Припускаючи, що значення встановлені так, як описано в решті цієї теми, налаштування виглядатиме наступним чином: - ![QGC comm link for ethernet setup](../../assets/qgc/settings/comm_link/px4_ethernet_link_config.png) + ![QGC comm link for ethernet setup](../../assets/qgc/settings/comm_link/px4_ethernet_link_config.png) 4. Після цього QGroundControl має підключитися, якщо ви виберете це посилання. @@ -205,14 +205,14 @@ Assuming you have already [Set up the Ethernet Network](#setting-up-the-ethernet 1. [Set up the Ethernet Network](#setting-up-the-ethernet-network) so your companion computer and PX4 run on the same network. 2. Modify the [PX4 Ethernet Port Configuration](#px4-ethernet-network-setup) to connect to a companion computer. - You might change the parameters [MAV_2_REMOTE_PRT](../advanced_config/parameter_reference.md#MAV_2_REMOTE_PRT) and [MAV_2_UDP_PRT](../advanced_config/parameter_reference.md#MAV_2_UDP_PRT) to `14540`, and [MAV_2_MODE](../advanced_config/parameter_reference.md#MAV_2_MODE) to `2` (Onboard). + You might change the parameters [MAV_2_REMOTE_PRT](../advanced_config/parameter_reference.md#MAV_2_REMOTE_PRT) and [MAV_2_UDP_PRT](../advanced_config/parameter_reference.md#MAV_2_UDP_PRT) to `14540`, and [MAV_2_MODE](../advanced_config/parameter_reference.md#MAV_2_MODE) to `2` (Onboard). 3. Дотримуйтесь інструкцій у [MAVSDK-python](https://github.com/mavlink/MAVSDK-Python), щоб установити та використовувати MAVSDK. - Наприклад, ваш код буде підключатися до PX4 за допомогою: + Наприклад, ваш код буде підключатися до PX4 за допомогою: - ```python - await drone.connect(system_address="udp://10.41.10.2:14540") - ``` + ```python + await drone.connect(system_address="udp://10.41.10.2:14540") + ``` :::info MAVSDK can connect to the PX4 on port `14550` if you don't modify the PX4 Ethernet port configuration. @@ -235,38 +235,38 @@ MAVSDK can connect to the PX4 on port `14550` if you don't modify the PX4 Ethern 1. Підключіть ваш автопілот і компаньйон комп'ютер за допомогою Ethernet. 2. [Start the uXRCE-DDS client on PX4](../middleware/uxrce_dds.md#starting-the-client), either manually or by customizing the system startup script. - Note that you must use the IP address of the companion computer and the UDP port on which the agent is listening (the example configuration above sets the companion IP address to `10.41.10.1`, and the agent UDP port is set to `8888` in the next step). + Note that you must use the IP address of the companion computer and the UDP port on which the agent is listening (the example configuration above sets the companion IP address to `10.41.10.1`, and the agent UDP port is set to `8888` in the next step). 3. [Start the micro XRCE-DDS agent on the companion computer](../middleware/uxrce_dds.md#starting-the-agent). - For example, enter the following command in a terminal to start the agent listening on UDP port `8888`. + For example, enter the following command in a terminal to start the agent listening on UDP port `8888`. - ```sh - MicroXRCEAgent udp4 -p 8888 - ``` + ```sh + MicroXRCEAgent udp4 -p 8888 + ``` 4. Run a [listener node](../ros2/user_guide.md#running-the-example) in a new terminal to confirm the connection is established: - ```sh - source ~/ws_sensor_combined/install/setup.bash - ros2 launch px4_ros_com sensor_combined_listener.launch.py - ``` + ```sh + source ~/ws_sensor_combined/install/setup.bash + ros2 launch px4_ros_com sensor_combined_listener.launch.py + ``` - Якщо все налаштовано правильно, в терміналі повинен відображатися наступний вивід: + Якщо все налаштовано правильно, в терміналі повинен відображатися наступний вивід: - ```sh - RECEIVED SENSOR COMBINED DATA - ============================= - ts: 855801598 - gyro_rad[0]: -0.00339938 - gyro_rad[1]: 0.00440091 - gyro_rad[2]: 0.00513893 - gyro_integral_dt: 4997 - accelerometer_timestamp_relative: 0 - accelerometer_m_s2[0]: -0.0324082 - accelerometer_m_s2[1]: 0.0392213 - accelerometer_m_s2[2]: -9.77914 - accelerometer_integral_dt: 4997 - ``` + ```sh + RECEIVED SENSOR COMBINED DATA + ============================= + ts: 855801598 + gyro_rad[0]: -0.00339938 + gyro_rad[1]: 0.00440091 + gyro_rad[2]: 0.00513893 + gyro_integral_dt: 4997 + accelerometer_timestamp_relative: 0 + accelerometer_m_s2[0]: -0.0324082 + accelerometer_m_s2[1]: 0.0392213 + accelerometer_m_s2[2]: -9.77914 + accelerometer_integral_dt: 4997 + ``` ## Дивіться також diff --git a/docs/uk/advanced_config/prearm_arm_disarm.md b/docs/uk/advanced_config/prearm_arm_disarm.md index e59c5ae39a..d7da93d801 100644 --- a/docs/uk/advanced_config/prearm_arm_disarm.md +++ b/docs/uk/advanced_config/prearm_arm_disarm.md @@ -152,14 +152,14 @@ PX4 також видає підмножину інформації переві Типова послідовність запуску: 1. Увімкнення живлення. - - Усі приводи заблоковано у беззбройному(вимкненому) положенні - - Неможливо озброїти(збурити). + - Усі приводи заблоковано у беззбройному(вимкненому) положенні + - Неможливо озброїти(збурити). 2. Перемикання безпеки натиснуто. - - Система зараз перевіряється перед збурюванням: актуатори без збурювання можуть рухатися (наприклад, елерони). - - Безпека системи відключена: можливість озброєння(збурення). + - Система зараз перевіряється перед збурюванням: актуатори без збурювання можуть рухатися (наприклад, елерони). + - Безпека системи відключена: можливість озброєння(збурення). 3. Видається команда на озброєння(збурення). - - Система озброєна(збурена). - - Усі мотори та приводи можуть рухатися. + - Система озброєна(збурена). + - Усі мотори та приводи можуть рухатися. ### COM_PREARM_MODE=Disabled та Safety Switch @@ -169,14 +169,14 @@ PX4 також видає підмножину інформації переві Послідовність запуску така: 1. Увімкнення живлення. - - Усі приводи заблоковано у беззбройному(вимкненому) положенні - - Неможливо озброїти(збурити). + - Усі приводи заблоковано у беззбройному(вимкненому) положенні + - Неможливо озброїти(збурити). 2. Перемикання безпеки натиснуто. - - _All actuators stay locked into disarmed position (same as disarmed)._ - - Безпека системи відключена: можливість озброєння(збурення). + - _All actuators stay locked into disarmed position (same as disarmed)._ + - Безпека системи відключена: можливість озброєння(збурення). 3. Видається команда на озброєння(збурення). - - Система озброєна(збурена). - - Усі мотори та приводи можуть рухатися. + - Система озброєна(збурена). + - Усі мотори та приводи можуть рухатися. ### COM_PREARM_MODE=Always and Safety Switch @@ -187,13 +187,13 @@ PX4 також видає підмножину інформації переві Послідовність запуску така: 1. Увімкнення живлення. - - Система зараз перевіряється перед збурюванням: актуатори без збурювання можуть рухатися (наприклад, елерони). - - Неможливо озброїти(збурити). + - Система зараз перевіряється перед збурюванням: актуатори без збурювання можуть рухатися (наприклад, елерони). + - Неможливо озброїти(збурити). 2. Перемикання безпеки натиснуто. - - Безпека системи відключена: можливість озброєння(збурення). + - Безпека системи відключена: можливість озброєння(збурення). 3. Видається команда на озброєння(збурення). - - Система озброєна(збурена). - - Усі мотори та приводи можуть рухатися. + - Система озброєна(збурена). + - Усі мотори та приводи можуть рухатися. ### COM_PREARM_MODE=Safety(Безпека) або вимкнено(Disabled) та без перемикача безпеки(No Safety Switch) @@ -203,11 +203,11 @@ PX4 також видає підмножину інформації переві Послідовність запуску така: 1. Увімкнення живлення. - - Усі приводи заблоковано у беззбройному(вимкненому) положенні - - Безпека системи відключена: можливість озброєння(збурення). + - Усі приводи заблоковано у беззбройному(вимкненому) положенні + - Безпека системи відключена: можливість озброєння(збурення). 2. Видається команда на озброєння(збурення). - - Система озброєна(збурена). - - Усі мотори та приводи можуть рухатися. + - Система озброєна(збурена). + - Усі мотори та приводи можуть рухатися. ### COM_PREARM_MODE=Завжди і без зміни безпеки @@ -217,11 +217,11 @@ PX4 також видає підмножину інформації переві Послідовність запуску така: 1. Увімкнення живлення. - - Система зараз перевіряється перед збурюванням: актуатори без збурювання можуть рухатися (наприклад, елерони). - - Безпека системи відключена: можливість озброєння(збурення). + - Система зараз перевіряється перед збурюванням: актуатори без збурювання можуть рухатися (наприклад, елерони). + - Безпека системи відключена: можливість озброєння(збурення). 2. Видається команда на озброєння(збурення). - - Система озброєна(збурена). - - Усі мотори та приводи можуть рухатися. + - Система озброєна(збурена). + - Усі мотори та приводи можуть рухатися. ### Параметри diff --git a/docs/uk/advanced_config/sensor_thermal_calibration.md b/docs/uk/advanced_config/sensor_thermal_calibration.md index 2bb2ebe4ed..01464d59ec 100644 --- a/docs/uk/advanced_config/sensor_thermal_calibration.md +++ b/docs/uk/advanced_config/sensor_thermal_calibration.md @@ -94,11 +94,11 @@ PX4 підтримує два процедури калібрування: 9. Відкрийте вікно терміналу в каталозі **Firmware/Tools** і запустіть сценарій калібрування python: - ```sh - python process_sensor_caldata.py - ``` + ```sh + python process_sensor_caldata.py + ``` - Буде створено файл **.pdf**, у якому відображатимуться вимірювані дані та підгонка кривої для кожного датчика, а також файл **.params**, що містить параметри калібрування. + Буде створено файл **.pdf**, у якому відображатимуться вимірювані дані та підгонка кривої для кожного датчика, а також файл **.params**, що містить параметри калібрування. 10. Увімкніть плату, підключіть _QGroundControl_ та завантажте параметри зі створеного файлу **.params** на плату за допомогою _QGroundControl_. Відсоток виконання друкується на системній консолі під час калібрування. diff --git a/docs/uk/advanced_config/tuning_the_ecl_ekf.md b/docs/uk/advanced_config/tuning_the_ecl_ekf.md index 9974f16781..41a92aa4a0 100644 --- a/docs/uk/advanced_config/tuning_the_ecl_ekf.md +++ b/docs/uk/advanced_config/tuning_the_ecl_ekf.md @@ -152,29 +152,29 @@ Three axis body fixed magnetometer data at a minimum rate of 5Hz is required to Magnetometer data fusion can be configured using [EKF2_MAG_TYPE](../advanced_config/parameter_reference.md#EKF2_MAG_TYPE): 0. Automatic: - - The magnetometer readings only affect the heading estimate before arming, and the whole attitude after arming. - - Heading and tilt errors are compensated when using this method. - - Incorrect magnetic field measurements can degrade the tilt estimate. - - The magnetometer biases are estimated whenever observable. + - The magnetometer readings only affect the heading estimate before arming, and the whole attitude after arming. + - Heading and tilt errors are compensated when using this method. + - Incorrect magnetic field measurements can degrade the tilt estimate. + - The magnetometer biases are estimated whenever observable. 1. Magnetic heading: - - Only the heading is corrected. - The tilt estimate is never affected by incorrect magnetic field measurements. - - Tilt errors that could arise when flying without velocity/position aiding are not corrected when using this method. - - The magnetometer biases are estimated whenever observable. + - Only the heading is corrected. + The tilt estimate is never affected by incorrect magnetic field measurements. + - Tilt errors that could arise when flying without velocity/position aiding are not corrected when using this method. + - The magnetometer biases are estimated whenever observable. 2. Deprecated 3. Deprecated 4. Deprecated 5. None: - - Magnetometer data is never used. - This is useful when the data can never be trusted (e.g.: high current close to the sensor, external anomalies). - - The estimator will use other sources of heading: [GPS heading](#yaw-measurements) or external vision. - - When using GPS measurements without another source of heading, the heading can only be initialized after sufficient horizontal acceleration. - See [Estimate yaw from vehicle movement](#yaw-from-gps-velocity) below. + - Magnetometer data is never used. + This is useful when the data can never be trusted (e.g.: high current close to the sensor, external anomalies). + - The estimator will use other sources of heading: [GPS heading](#yaw-measurements) or external vision. + - When using GPS measurements without another source of heading, the heading can only be initialized after sufficient horizontal acceleration. + See [Estimate yaw from vehicle movement](#yaw-from-gps-velocity) below. 6. Init only: - - Magnetometer data is only used to initialize the heading estimate. - This is useful when the data can be used before arming but not afterwards (e.g.: high current after the vehicle is armed). - - After initialization, the heading is constrained using other observations. - - Unlike mag type `None`, when combined with GPS measurements, this method allows position controlled modes to run directly during takeoff. + - Magnetometer data is only used to initialize the heading estimate. + This is useful when the data can be used before arming but not afterwards (e.g.: high current after the vehicle is armed). + - After initialization, the heading is constrained using other observations. + - Unlike mag type `None`, when combined with GPS measurements, this method allows position controlled modes to run directly during takeoff. The following selection tree can be used to select the right option: @@ -236,7 +236,7 @@ The following selection tree can be used to select the right option: 2. Витягніть `.ulg` файл журналу за допомогою, наприклад, [QGroundControl: Аналізувати > Завантажити журнал](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/analyze_view/log_download.html) - Той самий файл журналу можна використовувати для налаштування оцінювача вітру багатовертольотника [multirotor wind estimator](#mc_wind_estimation_using_drag). + Той самий файл журналу можна використовувати для налаштування оцінювача вітру багатовертольотника [multirotor wind estimator](#mc_wind_estimation_using_drag). ::: @@ -449,8 +449,8 @@ PX4 дозволяє постійно об'єднувати дальномер 1. Проведіть польоти один раз у режимі позиції [Position mode](../flight_modes_mc/position.md) повторно вперед/назад/ліворуч/праворуч/вгору/вниз між спокоєм і максимальною швидкістю (найкращі результати отримуються, коли цей тест проводиться в спокійних умовах). 2. Extract the **.ulg** log file using, for example, [QGroundControl: Analyze > Log Download](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/analyze_view/log_download.html) - ::: info - The same **.ulg** log file can also be used to tune the [static pressure position error coefficients](#correction-for-static-pressure-position-error). + ::: info + The same **.ulg** log file can also be used to tune the [static pressure position error coefficients](#correction-for-static-pressure-position-error). ::: 3. Використовуйте журнал зі сценарієм Python [mc_wind_estimator_tuning.py](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/ekf2/EKF/python/tuning_tools/mc_wind_estimator), щоб отримати оптимальний набір параметрів. diff --git a/docs/uk/advanced_features/precland.md b/docs/uk/advanced_features/precland.md index 73bd09bed1..3081e1ef81 100644 --- a/docs/uk/advanced_features/precland.md +++ b/docs/uk/advanced_features/precland.md @@ -38,14 +38,14 @@ PX4 підтримує точне приземлення для _Multicopters_ Режим Точної посадки має три етапи: 1. **Горизонтальний підхід:** Транспортний засіб підходить до цілі горизонтально, утримуючи свою поточну висоту. - Як тільки положення цілі відносно транспортного засобу опускається нижче порогового значення ([PLD_HACC_RAD](../advanced_config/parameter_reference.md#PLD_HACC_RAD)), відбувається вхід до наступної фази. - Якщо ціль втрачається під час цієї фази (не видно довше, ніж [PLD_BTOUT](../advanced_config/parameter_reference.md#PLD_BTOUT)), ініціюється процедура пошуку (під час необхідної точної посадки) або транспортний засіб робить звичайну посадку (під час можливої точної посадки). + Як тільки положення цілі відносно транспортного засобу опускається нижче порогового значення ([PLD_HACC_RAD](../advanced_config/parameter_reference.md#PLD_HACC_RAD)), відбувається вхід до наступної фази. + Якщо ціль втрачається під час цієї фази (не видно довше, ніж [PLD_BTOUT](../advanced_config/parameter_reference.md#PLD_BTOUT)), ініціюється процедура пошуку (під час необхідної точної посадки) або транспортний засіб робить звичайну посадку (під час можливої точної посадки). 2. **Спуск над ціль:** Транспортний засіб спускається, залишаючись при цьому над ціллю. - Якщо ціль втрачається під час цієї фази (не видно довше, ніж `PLD_BTOUT`), ініціюється процедура пошуку (під час необхідної точної посадки) або транспортний засіб робить звичайну посадку (під час можливої точної посадки). + Якщо ціль втрачається під час цієї фази (не видно довше, ніж `PLD_BTOUT`), ініціюється процедура пошуку (під час необхідної точної посадки) або транспортний засіб робить звичайну посадку (під час можливої точної посадки). 3. **Останній підхід:** Коли транспортний засіб знаходиться близько до землі (ближче, ніж [PLD_FAPPR_ALT](../advanced_config/parameter_reference.md#PLD_FAPPR_ALT)), він спускається, залишаючись при цьому над ціллю. - Якщо ціль втрачається під час цієї фази, спуск продовжується незалежно від виду точної посадки. + Якщо ціль втрачається під час цієї фази, спуск продовжується незалежно від виду точної посадки. Процедури пошуку ініціюються на перших і других етапах і виконуються не більше [PLD_MAX_SRCH разів](../advanced_config/parameter_reference.md#PLD_MAX_SRCH). Діаграма потоку фаз посадки diff --git a/docs/uk/advanced_features/satcom_roadblock.md b/docs/uk/advanced_features/satcom_roadblock.md index c1c84a8dd4..91702bb349 100644 --- a/docs/uk/advanced_features/satcom_roadblock.md +++ b/docs/uk/advanced_features/satcom_roadblock.md @@ -54,19 +54,19 @@ To [switch between the two antennas modes](https://docs.groundcontrol.com/iot/ro Стандартна швидкість передачі даних модуля - 19200. However, the PX4 _iridiumsbd_ driver requires a baud rate of 115200 so it needs to be changed using the [AT commands](https://www.groundcontrol.com/wp-content/uploads/2022/02/IRDM_ISU_ATCommandReferenceMAN0009_Rev2.0_ATCOMM_Oct2012.pdf). 1. Connect to the module with using a 19200/8-N-1 setting and check if the communication is working using the command: `AT`. - Відповідь має бути: `OK`. + Відповідь має бути: `OK`. 2. Змінити швидкість передачі: - ``` - AT+IPR=9 - ``` + ``` + AT+IPR=9 + ``` 3. Знову підключіться до моделі з параметрами 115200/8-N-1 і збережіть конфігурацію за допомогою: - ``` - AT&W0 - ``` + ``` + AT&W0 + ``` Модуль тепер готовий до використання з PX4. @@ -101,55 +101,55 @@ drivers/telemetry/iridiumsbd Сервер relay має бути запущений або на Ubuntu 16.04 або 14.04 OS. 1. Сервер, який працює як ретранслятор повідомлень, повинен мати статичну IP-адресу та два загальнодоступних відкритих TCP-порти: - - `5672` для брокера повідомлень _RabbitMQ_ (можна змінити в налаштуваннях _rabbitmq_) - - `45679` для інтерфейсу HTTP POST (можна змінити у файлі **relay.cfg**) + - `5672` для брокера повідомлень _RabbitMQ_ (можна змінити в налаштуваннях _rabbitmq_) + - `45679` для інтерфейсу HTTP POST (можна змінити у файлі **relay.cfg**) 2. Встановіть необхідні модулі python: - ```sh - sudo pip install pika tornado future - ``` + ```sh + sudo pip install pika tornado future + ``` 3. Встановіть брокер повідомлень `rabbitmq`: - ```sh - sudo apt install rabbitmq-server - ``` + ```sh + sudo apt install rabbitmq-server + ``` 4. Налаштуйте облікові дані брокера (змініть PWD на ваш бажаний пароль): - ```sh - sudo rabbitmqctl add_user iridiumsbd PWD - sudo rabbitmqctl set_permissions iridiumsbd ".*" ".*" ".*" - ``` + ```sh + sudo rabbitmqctl add_user iridiumsbd PWD + sudo rabbitmqctl set_permissions iridiumsbd ".*" ".*" ".*" + ``` 5. Clone the [SatComInfrastructure](https://github.com/acfloria/SatComInfrastructure) repository: - ```sh - git clone https://github.com/acfloria/SatComInfrastructure.git - ``` + ```sh + git clone https://github.com/acfloria/SatComInfrastructure.git + ``` 6. Перейдіть до розташування репозиторію _SatComInfrastructure_ і налаштуйте черги брокера: - ```sh - ./setup_rabbit.py localhost iridiumsbd PWD - ``` + ```sh + ./setup_rabbit.py localhost iridiumsbd PWD + ``` 7. Перевірте налаштування: - ```sh - sudo rabbitmqctl list_queues - ``` + ```sh + sudo rabbitmqctl list_queues + ``` - Це повинно дати вам список із 4 черг: `MO`, `MO_LOG`, `MT`, `MT_LOG` + Це повинно дати вам список із 4 черг: `MO`, `MO_LOG`, `MT`, `MT_LOG` 8. Edit the `relay.cfg` configuration file to reflect your settings. 9. Запустіть скрипт реле в режимі відокремленого виконання: - ```sh - screen -dm bash -c 'cd SatcomInfrastructure/; ./relay.py - ``` + ```sh + screen -dm bash -c 'cd SatcomInfrastructure/; ./relay.py + ``` Інші інструкції включають: @@ -177,15 +177,15 @@ drivers/telemetry/iridiumsbd 1. Встановіть необхідні модулі python: - ```sh - sudo pip install pika tornado future - ``` + ```sh + sudo pip install pika tornado future + ``` 2. Клонуйте репозиторій SatComInfrastructure: - ```sh - git clone https://github.com/acfloria/SatComInfrastructure.git - ``` + ```sh + git clone https://github.com/acfloria/SatComInfrastructure.git + ``` 3. Відредагуйте конфігураційний файл **udp2rabbit.cfg**, щоб відображати ваші налаштування. @@ -193,20 +193,20 @@ drivers/telemetry/iridiumsbd 5. Додавайте UDP з'єднання в QGC з параметрами: - - Порт прослуховування: 10000 - - Цільові хости: 127.0.0.1:10001 - - Висока затримка: позначено + - Порт прослуховування: 10000 + - Цільові хости: 127.0.0.1:10001 + - Висока затримка: позначено - ![High Latency Link Settings](../../assets/satcom/linksettings.png) + ![High Latency Link Settings](../../assets/satcom/linksettings.png) ### Перевірка 1. Відкрийте термінал на комп'ютері наземної станції та перейдіть до розташування репозиторію _SatComInfrastructure_. - Потім запустіть скрипт **udp2rabbit.py**: + Потім запустіть скрипт **udp2rabbit.py**: - ```sh - ./udp2rabbit.py - ``` + ```sh + ./udp2rabbit.py + ``` 2. Надішліть тестове повідомлення з облікового запису [RockBlock](https://rockblock.rock7.com/Operations) до створеної групи доставки на вкладці `Тестові групи доставки`. @@ -217,36 +217,36 @@ drivers/telemetry/iridiumsbd ## Запуск системи 1. Запустіть _QGroundControl_. - Спочатку вручну підключіть високо запізнюваний зв'язок, а потім звичайний телеметрійний зв'язок: + Спочатку вручну підключіть високо запізнюваний зв'язок, а потім звичайний телеметрійний зв'язок: - ![Connect the High Latency link](../../assets/satcom/linkconnect.png) + ![Connect the High Latency link](../../assets/satcom/linkconnect.png) 2. Відкрийте термінал на комп'ютері наземної станції та перейдіть до розташування репозиторію _SatComInfrastructure_. - Потім запустіть скрипт **udp2rabbit.py**: + Потім запустіть скрипт **udp2rabbit.py**: - ```sh - ./udp2rabbit.py - ``` + ```sh + ./udp2rabbit.py + ``` 3. Увімкніть транспортний засіб. 4. Дочекайтеся, доки на QGC не буде отримано перше повідомлення `HIGH_LATENCY2`. - Це можна перевірити за допомогою віджету _Інспектора MAVLink_ або на панелі інструментів за допомогою _індикатора зв'язку(LinkIndicator)_. - Це можна перевірити за допомогою віджету _Інспектора MAVLink_ або на панелі інструментів за допомогою _індикатора зв'язку(LinkIndicator)_: + Це можна перевірити за допомогою віджету _Інспектора MAVLink_ або на панелі інструментів за допомогою _індикатора зв'язку(LinkIndicator)_. + Це можна перевірити за допомогою віджету _Інспектора MAVLink_ або на панелі інструментів за допомогою _індикатора зв'язку(LinkIndicator)_: - ![Link Toolbar](../../assets/satcom/linkindicator.jpg) + ![Link Toolbar](../../assets/satcom/linkindicator.jpg) - Індикатор зв'язку завжди показує назву пріоритетного зв'язку. + Індикатор зв'язку завжди показує назву пріоритетного зв'язку. 5. Супутникова система зв'язку тепер готова до використання. - Пріоритетний зв'язок, через який надсилаються команди, визначається наступними способами: - - Якщо користувач не вказав зв'язок, звичайний радіо телеметрійний зв'язок віддається перевагу перед високозапізнюваним зв'язком. - - Автопілот та QGC перехоплюватимуть звичайний радіо телеметрійний зв'язок на високозапізнюваний зв'язок, якщо транспортний засіб зброєний, а радіо телеметрійний зв'язок втрачений (не отримано жодного повідомлення MAVLink протягом певного часу). - Як тільки радіо телеметрійний зв'язок відновлюється, QGC та автопілот повертаються до нього. - - Користувач може вибрати пріоритетний зв'язок через індикатор зв'язку на панелі інструментів. - Це посилання зберігається як пріоритетне посилання, поки воно активне або користувач вибирає інше пріоритетне посилання: + Пріоритетний зв'язок, через який надсилаються команди, визначається наступними способами: + - Якщо користувач не вказав зв'язок, звичайний радіо телеметрійний зв'язок віддається перевагу перед високозапізнюваним зв'язком. + - Автопілот та QGC перехоплюватимуть звичайний радіо телеметрійний зв'язок на високозапізнюваний зв'язок, якщо транспортний засіб зброєний, а радіо телеметрійний зв'язок втрачений (не отримано жодного повідомлення MAVLink протягом певного часу). + Як тільки радіо телеметрійний зв'язок відновлюється, QGC та автопілот повертаються до нього. + - Користувач може вибрати пріоритетний зв'язок через індикатор зв'язку на панелі інструментів. + Це посилання зберігається як пріоритетне посилання, поки воно активне або користувач вибирає інше пріоритетне посилання: - ![Prioritylink Selection](../../assets/satcom/linkselection.png) + ![Prioritylink Selection](../../assets/satcom/linkselection.png) ## Усунення проблем diff --git a/docs/uk/airframes/airframe_reference.md b/docs/uk/airframes/airframe_reference.md index 73e677a2e3..53f18bc47c 100644 --- a/docs/uk/airframes/airframe_reference.md +++ b/docs/uk/airframes/airframe_reference.md @@ -628,7 +628,16 @@ div.frame_variant td, div.frame_variant th { ### Free-Flyer
- + + + + + + + + + +
Загальні виводи
  • Motor1: back left thruster, +x thrust
  • Motor2: front left thruster, -x thrust
  • Motor3: back right thruster, +x thrust
  • Motor4: front right thruster, -x thrust
  • Motor5: front left thruster, +y thrust
  • Motor6: front right thruster, -y thrust
  • Motor7: back left thruster, +y thrust
  • Motor8: back right thruster, -y thrust
@@ -638,7 +647,7 @@ div.frame_variant td, div.frame_variant th { - KTH-ATMOS + KTH-ATMOS Maintainer: DISCOWER

SYS_AUTOSTART = 70000

diff --git a/docs/uk/assembly/_assembly.md b/docs/uk/assembly/_assembly.md index bd458a8866..68998b05e1 100644 --- a/docs/uk/assembly/_assembly.md +++ b/docs/uk/assembly/_assembly.md @@ -291,7 +291,7 @@ If you're using [DroneCAN ESC](../peripherals/esc_motors.md#dronecan) the contro ### Flight Controller Power Pixhawk FCs require a regulated power supply that can supply at around 5V/3A continuous (check your specific FC)! -This is sufficient to power the controller itself and a few low-power peripherals, such as a GNSS module, RC transmitter, and low power telemetry radio, but not for motors, actuators, and other peripherals. +This is sufficient to power the controller itself and a few low-power peripherals, such as a GNSS module, RC receiver, and low power telemetry radio, but not for motors, actuators, and other peripherals. [Power modules](../power_module/index.md) are commonly used to "split off" this regulated power supply for the FC and also to provide measurements of the battery voltage and total current to the whole system — which PX4 can use to estimate power levels. The power module is connected to the FC power port, which is normally labeled `POWER` (or `POWER 1` or `POWER 2` for FCs that have redundant power supply). diff --git a/docs/uk/camera/fc_connected_camera.md b/docs/uk/camera/fc_connected_camera.md index f0efca7c45..648c29a108 100644 --- a/docs/uk/camera/fc_connected_camera.md +++ b/docs/uk/camera/fc_connected_camera.md @@ -188,16 +188,16 @@ PX4 видає повідомлення MAVLink [CAMERA_TRIGGER](https://mavlink 1. На консолі PX4: - ```shell - camera_trigger test - ``` + ```shell + camera_trigger test + ``` 2. Від _QGroundControl_: - Клацніть на **Запуск камери** на головній панелі інструментів. - Ці знімки не відображаються або не підраховуються для геотегування. + Клацніть на **Запуск камери** на головній панелі інструментів. + Ці знімки не відображаються або не підраховуються для геотегування. - ![QGC Тестова Камера](../../assets/camera/qgc_test_camera.png) + ![QGC Тестова Камера](../../assets/camera/qgc_test_camera.png) ## Приклад Sony QX-1 (Фотограметрія) diff --git a/docs/uk/camera/mavlink_v1_camera.md b/docs/uk/camera/mavlink_v1_camera.md index 75338d6c61..1321fc29ca 100644 --- a/docs/uk/camera/mavlink_v1_camera.md +++ b/docs/uk/camera/mavlink_v1_camera.md @@ -86,7 +86,7 @@ PX4 переістовує їх з тим самим ідентифікатор 1. Змініть невикористаний параметр `MAV_n_CONFIG`, такий як [MAV_2_CONFIG](../advanced_config/parameter_reference.md#MAV_2_CONFIG), щоб він був присвоєний порту, до якого підключена ваша камера. 2. Встановіть відповідний [MAV_2_MODE](../advanced_config/parameter_reference.md#MAV_2_MODE) на `2` (На борту). - Це забезпечує, що правильний набір повідомлень MAVLink випромінюється та пересилається. + Це забезпечує, що правильний набір повідомлень MAVLink випромінюється та пересилається. 3. Можливо, вам доведеться встановити деякі інші параметри, залежно від вашого з'єднання - наприклад, швидкість передачі даних. Підключіться та налаштуйте камеру, як рекомендовано в її посібнику користувача. diff --git a/docs/uk/camera/mavlink_v2_camera.md b/docs/uk/camera/mavlink_v2_camera.md index 29a58d2e96..c979c40845 100644 --- a/docs/uk/camera/mavlink_v2_camera.md +++ b/docs/uk/camera/mavlink_v2_camera.md @@ -112,7 +112,7 @@ PX4 видає команди [MAVLink Camera Protocol v2](https://mavlink.io/en 1. Змініть невикористаний параметр `MAV_n_CONFIG`, такий як [MAV_2_CONFIG](../advanced_config/parameter_reference.md#MAV_2_CONFIG), щоб він був присвоєний порту, до якого підключена ваша камера/компаньйонський комп'ютер. 2. Встановіть відповідний [MAV_2_MODE](../advanced_config/parameter_reference.md#MAV_2_MODE) на `2` (На борту). - Це забезпечує, що правильний набір повідомлень MAVLink випромінюється для супутнього комп'ютера (або камери). + Це забезпечує, що правильний набір повідомлень MAVLink випромінюється для супутнього комп'ютера (або камери). 3. Встановіть [MAV_2_FORWARD](../advanced_config/parameter_reference.md#MAV_2_FORWARD), щоб дозволити пересилання комунікацій з порту на інші порти, такі як той, що підключений до наземної станції. 4. Можливо, вам доведеться встановити деякі інші параметри, залежно від типу підключення та будь-яких конкретних вимог камери щодо очікуваної швидкості передачі даних і т. д. diff --git a/docs/uk/companion_computer/holybro_pixhawk_jetson_baseboard.md b/docs/uk/companion_computer/holybro_pixhawk_jetson_baseboard.md index 974ceb168a..97aa227df0 100644 --- a/docs/uk/companion_computer/holybro_pixhawk_jetson_baseboard.md +++ b/docs/uk/companion_computer/holybro_pixhawk_jetson_baseboard.md @@ -892,95 +892,95 @@ These instructions approximately mirror the [PX4 Ethernet setup](../advanced_con Next we modify the Jetson IP address to be on the same network as the Pixhawk: 1. Make sure `netplan` is installed. - You can check by running the following command: + You can check by running the following command: - ```sh - netplan -h - ``` + ```sh + netplan -h + ``` - If not, install it using the commands: + If not, install it using the commands: - ```sh - sudo apt update - sudo apt install netplan.io - ``` + ```sh + sudo apt update + sudo apt install netplan.io + ``` 2. Check `system_networkd` is running: - ```sh - sudo systemctl status systemd-networkd - ``` + ```sh + sudo systemctl status systemd-networkd + ``` - You should see output like below if it is active: + You should see output like below if it is active: - ```sh - ● systemd-networkd.service - Network Configuration - Loaded: loaded (/lib/systemd/system/systemd-networkd.service; enabled; vendor preset: enabled) - Active: active (running) since Wed 2024-09-11 23:32:44 EDT; 23min ago - TriggeredBy: ● systemd-networkd.socket - Docs: man:systemd-networkd.service(8) - Main PID: 2452 (systemd-network) - Status: "Processing requests..." - Tasks: 1 (limit: 18457) - Memory: 2.7M - CPU: 157ms - CGroup: /system.slice/systemd-networkd.service - └─2452 /lib/systemd/systemd-networkd + ```sh + ● systemd-networkd.service - Network Configuration + Loaded: loaded (/lib/systemd/system/systemd-networkd.service; enabled; vendor preset: enabled) + Active: active (running) since Wed 2024-09-11 23:32:44 EDT; 23min ago + TriggeredBy: ● systemd-networkd.socket + Docs: man:systemd-networkd.service(8) + Main PID: 2452 (systemd-network) + Status: "Processing requests..." + Tasks: 1 (limit: 18457) + Memory: 2.7M + CPU: 157ms + CGroup: /system.slice/systemd-networkd.service + └─2452 /lib/systemd/systemd-networkd - Sep 11 23:32:44 ubuntu systemd-networkd[2452]: lo: Gained carrier - Sep 11 23:32:44 ubuntu systemd-networkd[2452]: wlan0: Gained IPv6LL - Sep 11 23:32:44 ubuntu systemd-networkd[2452]: eth0: Gained IPv6LL - Sep 11 23:32:44 ubuntu systemd-networkd[2452]: Enumeration completed - Sep 11 23:32:44 ubuntu systemd[1]: Started Network Configuration. - Sep 11 23:32:44 ubuntu systemd-networkd[2452]: wlan0: Connected WiFi access point: Verizon_7YLWWD (78:67:0e:ea:a6:0> - Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: Re-configuring with /run/systemd/network/10-netplan-eth0.netwo> - Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: DHCPv6 lease lost - Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: Re-configuring with /run/systemd/network/10-netplan-eth0.netwo> - Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: DHCPv6 lease lost - ``` + Sep 11 23:32:44 ubuntu systemd-networkd[2452]: lo: Gained carrier + Sep 11 23:32:44 ubuntu systemd-networkd[2452]: wlan0: Gained IPv6LL + Sep 11 23:32:44 ubuntu systemd-networkd[2452]: eth0: Gained IPv6LL + Sep 11 23:32:44 ubuntu systemd-networkd[2452]: Enumeration completed + Sep 11 23:32:44 ubuntu systemd[1]: Started Network Configuration. + Sep 11 23:32:44 ubuntu systemd-networkd[2452]: wlan0: Connected WiFi access point: Verizon_7YLWWD (78:67:0e:ea:a6:0> + Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: Re-configuring with /run/systemd/network/10-netplan-eth0.netwo> + Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: DHCPv6 lease lost + Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: Re-configuring with /run/systemd/network/10-netplan-eth0.netwo> + Sep 11 23:34:16 ubuntu systemd-networkd[2452]: eth0: DHCPv6 lease lost + ``` - If `system_networkd` is not running, it can be enabled using: + If `system_networkd` is not running, it can be enabled using: - ```sh - sudo systemctl start systemd-networkd - sudo systemctl enable systemd-networkd - ``` + ```sh + sudo systemctl start systemd-networkd + sudo systemctl enable systemd-networkd + ``` 3. Open the Netplan configuration file (so we can set up a static IP for the Jetson). - The Netplan configuration file is usually located in the `/etc/netplan/` directory and named something like `01-netcfg.yaml` (the name can vary). - Below we use `nano` to open the file, but you can use your preferred text editor: + The Netplan configuration file is usually located in the `/etc/netplan/` directory and named something like `01-netcfg.yaml` (the name can vary). + Below we use `nano` to open the file, but you can use your preferred text editor: - ```sh - sudo nano /etc/netplan/01-netcfg.yaml - ``` + ```sh + sudo nano /etc/netplan/01-netcfg.yaml + ``` 4. Modify the yaml configuration, by overwriting the contents with the following information and then saving: - ```sh - network: - version: 2 - renderer: networkd - ethernets: - eth0: - dhcp4: no - addresses: - - 10.41.10.1/24 - routes: - - to: 0.0.0.0/0 - via: 10.41.10.254 - nameservers: - addresses: - - 10.41.10.254 - ``` + ```sh + network: + version: 2 + renderer: networkd + ethernets: + eth0: + dhcp4: no + addresses: + - 10.41.10.1/24 + routes: + - to: 0.0.0.0/0 + via: 10.41.10.254 + nameservers: + addresses: + - 10.41.10.254 + ``` - This gives the Jetson a static IP address on the Ethernet interface of `10.41.10.1` . + This gives the Jetson a static IP address on the Ethernet interface of `10.41.10.1` . 5. Apply the changes using the following command: - ```sh - sudo netplan apply - ``` + ```sh + sudo netplan apply + ``` The Pixhawk Ethernet address is set to `10.41.10.2` by default, which is on the same subnet. We can test our changes above by pinging the Pixhawk from within the Jetson terminal: diff --git a/docs/uk/companion_computer/holybro_pixhawk_rpi_cm4_baseboard.md b/docs/uk/companion_computer/holybro_pixhawk_rpi_cm4_baseboard.md index a9a506b734..7342bd079a 100644 --- a/docs/uk/companion_computer/holybro_pixhawk_rpi_cm4_baseboard.md +++ b/docs/uk/companion_computer/holybro_pixhawk_rpi_cm4_baseboard.md @@ -69,15 +69,15 @@ To install the RPi CM4 companion computer: 1. Disconnect the `FAN` wiring. - ![HB_Pixhawk_CM4_Fan](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/baseboard_fan.jpg) + ![HB_Pixhawk_CM4_Fan](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/baseboard_fan.jpg) 2. Видаліть ці 4 гвинти на задній стороні підлогової дошки. - ![Bottom of the board showing screws in corners holding the cover](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/baseboard_bottom.jpg) + ![Bottom of the board showing screws in corners holding the cover](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/baseboard_bottom.jpg) 3. Видаліть підставку корпусу, встановіть CM4 та використовуйте 4 гвинти для його кріплення (як показано): - ![HB_Pixhawk_CM4_Screws](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/baseboard_screws.jpg) + ![HB_Pixhawk_CM4_Screws](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/baseboard_screws.jpg) 4. Прикріпіть кришку знову. @@ -115,29 +115,29 @@ RPi CM4 та контролер польоту повинні бути живл 1. Switch Dip-Switch to `RPI`. - ![](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/cm4_dip_switch.png) + ![](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/cm4_dip_switch.png) 2. Підключіть комп'ютер до порту USB-C _CM4 Slave_, що використовується для живлення та прошивки RPi. - ![](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/cm4_usbc_slave_port.png) + ![](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/cm4_usbc_slave_port.png) 3. Отримайте `usbboot`, зберіть його та запустіть. - ```sh - sudo apt install libusb-1.0-0-dev - git clone --depth=1 https://github.com/raspberrypi/usbboot - cd usbboot - make - sudo ./rpiboot - ``` + ```sh + sudo apt install libusb-1.0-0-dev + git clone --depth=1 https://github.com/raspberrypi/usbboot + cd usbboot + make + sudo ./rpiboot + ``` 4. Тепер ви можете встановити свою перевагу Linux дистрибутив за допомогою `rpi-imager`. - Переконайтеся, що ви додали налаштування WiFi та SSH (приховані за символом шестерні / розширеним). + Переконайтеся, що ви додали налаштування WiFi та SSH (приховані за символом шестерні / розширеним). - ```sh - sudo apt install rpi-imager - rpi-imager - ``` + ```sh + sudo apt install rpi-imager + rpi-imager + ``` 5. Після завершення відключення USB-C CM4 Slave (це відмонтує томи та вимкне CM4). @@ -146,8 +146,8 @@ RPi CM4 та контролер польоту повинні бути живл 7. Увімкніть CM4, надаючи живлення через порт USB-C CM4 Slave. 8. Щоб перевірити, чи запускається/працює, ви можете або: - - Перевірте, чи є вихід HDMI - - Підключіться через SSH (якщо налаштовано в rpi-imager, і є доступ до WiFi). + - Перевірте, чи є вихід HDMI + - Підключіться через SSH (якщо налаштовано в rpi-imager, і є доступ до WiFi). ## Налаштуйте послідовне підключення PX4 до CM4 MAVLink @@ -167,13 +167,13 @@ FC повинен бути налаштований для підключенн 1. Підключіть комп'ютер, на якому працює QGroundControl, через порт USB Type C на базовій платі, позначеній як `FC` - ![Image of baseboard showing FC USB-C connector](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/baseboard_fc_usb_c.jpg) + ![Image of baseboard showing FC USB-C connector](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/baseboard_fc_usb_c.jpg) 2. [Встановіть параметри](../advanced_config/parameters.md): - - `MAV_1_CONFIG` = `102` - - `MAV_1_MODE = 2` - - `SER_TEL2_BAUD` = `921600` + - `MAV_1_CONFIG` = `102` + - `MAV_1_MODE = 2` + - `SER_TEL2_BAUD` = `921600` 3. Перезавантажте FC. @@ -185,13 +185,13 @@ FC повинен бути налаштований для підключенн 2. Увімкніть послідовний порт RPi, запустивши `RPi-config` - - Перейдіть до `3 Варіанти інтерфейсу`, потім `I6 Серійний порт`. - Потім введіть: - - `login shell accessible over serial → No` - - `serial port hardware enabled` → `Yes` + - Перейдіть до `3 Варіанти інтерфейсу`, потім `I6 Серійний порт`. + Потім введіть: + - `login shell accessible over serial → No` + - `serial port hardware enabled` → `Yes` 3. Завершіть і перезавантажте. - This will add `enable_uart=1` to `/boot/config.txt`, and remove `console=serial0,115200` from `/boot/cmdline.txt`. + This will add `enable_uart=1` to `/boot/config.txt`, and remove `console=serial0,115200` from `/boot/cmdline.txt`. 4. Тепер MAVLink-трафік повинен бути доступний на `/dev/serial0` з швидкістю передачі даних 921600. @@ -201,9 +201,9 @@ FC повинен бути налаштований для підключенн 2. Встановіть MAVSDK Python: - ```sh - python3 -m pip install mavsdk - ``` + ```sh + python3 -m pip install mavsdk + ``` 3. Скопіюйте приклад з [прикладів MAVSDK-Python](https://github.com/mavlink/MAVSDK-Python/tree/main/examples). diff --git a/docs/uk/companion_computer/pixhawk_rpi.md b/docs/uk/companion_computer/pixhawk_rpi.md index 0444585614..32efb5acce 100644 --- a/docs/uk/companion_computer/pixhawk_rpi.md +++ b/docs/uk/companion_computer/pixhawk_rpi.md @@ -132,50 +132,50 @@ make px4_fmu-v6c_default upload 1. Встановіть `raspi-config`: - ```sh - sudo apt update - sudo apt upgrade - sudo apt-get install raspi-config - ``` + ```sh + sudo apt update + sudo apt upgrade + sudo apt-get install raspi-config + ``` 2. Open `raspi-config`: - ```sh - sudo raspi-config - ``` + ```sh + sudo raspi-config + ``` 3. Перейдіть до **Варіанти інтерфейсу**, а потім клацніть **Серійний порт**. - - Виберіть **No**, щоб вимкнути послідовний вхід у оболонку. - - Виберіть **Так**, щоб увімкнути послідовний інтерфейс. - - Клацніть **Завершити** та перезапустіть RPi. + - Виберіть **No**, щоб вимкнути послідовний вхід у оболонку. + - Виберіть **Так**, щоб увімкнути послідовний інтерфейс. + - Клацніть **Завершити** та перезапустіть RPi. 4. Відкрийте файл конфігурації завантаження прошивки в редакторі `nano` на RaPi: - ```sh - sudo nano /boot/firmware/config.txt - ``` + ```sh + sudo nano /boot/firmware/config.txt + ``` 5. Додайте наступний текст в кінець файлу (після останнього рядка): - ```sh - enable_uart=1 - dtoverlay=disable-bt - ``` + ```sh + enable_uart=1 + dtoverlay=disable-bt + ``` 6. Далі збережіть файл і перезапустіть RPi. - - У `nano` ви можете зберегти файл за допомогою такої послідовності комбінацій клавіш: **ctrl+x**, **ctrl+y**, **Enter**. + - У `nano` ви можете зберегти файл за допомогою такої послідовності комбінацій клавіш: **ctrl+x**, **ctrl+y**, **Enter**. 7. Перевірте, чи доступний послідовний порт. - В даному випадку ми використовуємо наступні команди для перегляду серійних пристроїв: + В даному випадку ми використовуємо наступні команди для перегляду серійних пристроїв: - ```sh - cd / - ls /dev/ttyAMA0 - ``` + ```sh + cd / + ls /dev/ttyAMA0 + ``` - Результат команди повинен містити підключення RX/TX `/dev/ttyAMA0` (зверніть увагу, що цей послідовний порт також доступний як `/dev/serial0`). + Результат команди повинен містити підключення RX/TX `/dev/ttyAMA0` (зверніть увагу, що цей послідовний порт також доступний як `/dev/serial0`). RPi наразі налаштований для роботи з RPi та зв'язку за допомогою послідовного порту `/dev/ttyAMA0`. Зверніть увагу, що ми встановимо додаткове програмне забезпечення в наступних розділах для роботи з MAVLink та ROS 2. @@ -199,38 +199,38 @@ PX4 рекомендує використовувати [MAVSDK](https://mavsdk. 2. Відкрийте QGroundControl (повинно з'єднатися з транспортним засобом). 3. [Перевірте/змініть наступні параметри](../advanced_config/parameters.md) в QGroundControl: - ```ini - MAV_1_CONFIG = TELEM2 - UXRCE_DDS_CFG = 0 (Disabled) - SER_TEL2_BAUD = 57600 - ``` + ```ini + MAV_1_CONFIG = TELEM2 + UXRCE_DDS_CFG = 0 (Disabled) + SER_TEL2_BAUD = 57600 + ``` - Зверніть увагу, що параметри можуть вже бути налаштовані належним чином. - Для отримання інформації про те, як працюють послідовні порти та конфігурація MAVLink, див. [Конфігурація послідовного порту](../peripherals/serial_configuration.md) та [Периферійні пристрої MAVLink](../peripherals/mavlink_peripherals.md). + Зверніть увагу, що параметри можуть вже бути налаштовані належним чином. + Для отримання інформації про те, як працюють послідовні порти та конфігурація MAVLink, див. [Конфігурація послідовного порту](../peripherals/serial_configuration.md) та [Периферійні пристрої MAVLink](../peripherals/mavlink_peripherals.md). Потім встановіть налаштування MAVProxy на RPi за допомогою наступних термінальних команд: 1. Встановіть MAVProxy: - ```sh - sudo apt install python3-pip - sudo pip3 install mavproxy - sudo apt remove modemmanager - ``` + ```sh + sudo apt install python3-pip + sudo pip3 install mavproxy + sudo apt remove modemmanager + ``` 2. Запустіть MAVProxy, встановивши порт для підключення до `/dev/ttyAMA0` та швидкість передачі даних, щоб відповідати PX4: - ```sh - sudo mavproxy.py --master=/dev/serial0 --baudrate 57600 - ``` + ```sh + sudo mavproxy.py --master=/dev/serial0 --baudrate 57600 + ``` - Зверніть увагу, що вище ми використовували `/dev/serial0`, але ми могли б так само добре використовувати `/dev/ttyAMA0`. - Якщо ми підключалися через USB, тоді ми замість цього встановили порт як `/dev/ttyACM0`: + Зверніть увагу, що вище ми використовували `/dev/serial0`, але ми могли б так само добре використовувати `/dev/ttyAMA0`. + Якщо ми підключалися через USB, тоді ми замість цього встановили порт як `/dev/ttyACM0`: - ```sh - sudo chmod a+rw /dev/ttyACM0 - sudo mavproxy.py --master=/dev/ttyACM0 --baudrate 57600 - ``` + ```sh + sudo chmod a+rw /dev/ttyACM0 + sudo mavproxy.py --master=/dev/ttyACM0 --baudrate 57600 + ``` ::: @@ -258,26 +258,26 @@ The [ROS 2 Guide](../ros2/user_guide.md) and [uXRCE-DDS](../middleware/uxrce_dds 2. [Перевірте/змініть наступні параметри](../advanced_config/parameters.md) в QGroundControl: - ```ini - MAV_1_CONFIG = 0 (Disabled) - UXRCE_DDS_CFG = 102 (TELEM2) - SER_TEL2_BAUD = 921600 - ``` + ```ini + MAV_1_CONFIG = 0 (Disabled) + UXRCE_DDS_CFG = 102 (TELEM2) + SER_TEL2_BAUD = 921600 + ``` - [MAV_1_CONFIG=0](../advanced_config/parameter_reference.md#MAV_1_CONFIG) та [UXRCE_DDS_CFG=102](../advanced_config/parameter_reference.md#UXRCE_DDS_CFG) вимикають MAVLink на TELEM2 та увімкнюють клієнт uXRCE-DDS на TELEM2, відповідно. - Швидкість `SER_TEL2_BAUD` встановлює швидкість передачі даних зв'язку.\ - Ви так само можете налаштувати підключення до `TELEM1`, використовуючи або `MAV_1_CONFIG`, або `MAV_0_CONFIG`. + [MAV_1_CONFIG=0](../advanced_config/parameter_reference.md#MAV_1_CONFIG) та [UXRCE_DDS_CFG=102](../advanced_config/parameter_reference.md#UXRCE_DDS_CFG) вимикають MAVLink на TELEM2 та увімкнюють клієнт uXRCE-DDS на TELEM2, відповідно. + Швидкість `SER_TEL2_BAUD` встановлює швидкість передачі даних зв'язку.\ + Ви так само можете налаштувати підключення до `TELEM1`, використовуючи або `MAV_1_CONFIG`, або `MAV_0_CONFIG`. - Вам потрібно перезавантажити керування польотом, щоб застосувати будь-які зміни до цих параметрів. + Вам потрібно перезавантажити керування польотом, щоб застосувати будь-які зміни до цих параметрів. ::: 3. Перевірте, що модуль [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) зараз працює. - Ви можете це зробити, запустивши наступну команду в QGroundControl [MAVLink Console](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/analyze_view/mavlink_console.html): + Ви можете це зробити, запустивши наступну команду в QGroundControl [MAVLink Console](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/analyze_view/mavlink_console.html): - ```sh - uxrce_dds_client status - ``` + ```sh + uxrce_dds_client status + ``` :::info Якщо модуль клієнта не працює, ви можете запустити його вручну в консолі MAVLink: @@ -298,32 +298,32 @@ uxrce_dds_client start -t serial -d /dev/ttyS3 -b 921600 2. Встановіть git за допомогою терміналу RPi: - ```sh - sudo apt install git - ``` + ```sh + sudo apt install git + ``` 3. Встановіть агент uXRCE_DDS: - ```sh - git clone https://github.com/eProsima/Micro-XRCE-DDS-Agent.git - cd Micro-XRCE-DDS-Agent - mkdir build - cd build - cmake .. - make - sudo make install - sudo ldconfig /usr/local/lib/ - ``` + ```sh + git clone https://github.com/eProsima/Micro-XRCE-DDS-Agent.git + cd Micro-XRCE-DDS-Agent + mkdir build + cd build + cmake .. + make + sudo make install + sudo ldconfig /usr/local/lib/ + ``` - Див. [uXRCE-DDS > Встановлення агента Micro XRCE-DDS](../middleware/uxrce_dds.md#micro-xrce-dds-agent-installation) для альтернативних способів встановлення агента. + Див. [uXRCE-DDS > Встановлення агента Micro XRCE-DDS](../middleware/uxrce_dds.md#micro-xrce-dds-agent-installation) для альтернативних способів встановлення агента. 4. Запустіть агента в терміналі RPi: - ```sh - sudo MicroXRCEAgent serial --dev /dev/serial0 -b 921600 - ``` + ```sh + sudo MicroXRCEAgent serial --dev /dev/serial0 -b 921600 + ``` - Зверніть увагу, як ми використовуємо раніше налаштований послідовний порт і ту саму швидкість передачі даних, що й для PX4. + Зверніть увагу, як ми використовуємо раніше налаштований послідовний порт і ту саму швидкість передачі даних, що й для PX4. Тепер, коли обидва агент та клієнт працюють, ви повинні бачити активність як на консолі MAVLink, так і на терміналі RPi. Ви можете переглянути доступні теми за допомогою наступної команди на RPi: diff --git a/docs/uk/companion_computer/video_streaming_wfb_ng_wifi.md b/docs/uk/companion_computer/video_streaming_wfb_ng_wifi.md index 2b4fd1a73d..9abe46e1a4 100644 --- a/docs/uk/companion_computer/video_streaming_wfb_ng_wifi.md +++ b/docs/uk/companion_computer/video_streaming_wfb_ng_wifi.md @@ -80,18 +80,18 @@ Alpha AWUS036ACH - це карта середньої потужності, як 5. Налаштуйте камерний канал. Відкрийте `/etc/systemd/system/fpv-camera.service` і розкоментуйте конвеєр відповідно до вашої камери (камера PI або камера Logitech) 6. Відкрийте `/etc/wifibroadcast.cfg` і налаштуйте канал WiFi відповідно до налаштувань вашої антени (або використовуйте замовчуваний #165 для 5.8GHz) 7. Налаштуйте PX4 на вивід потоку телеметрії зі швидкістю 1500 Кбіт/с (інші швидкості UART не добре відповідають дільникам частоти RPI). - Підключіть UART Pixhawk до UART Raspberry PI. - У розділі `/etc/wifibroadcast.cfg` файлу розкоментуйте `peer = 'serial:ttyS0:1500000'` секцію. + Підключіть UART Pixhawk до UART Raspberry PI. + У розділі `/etc/wifibroadcast.cfg` файлу розкоментуйте `peer = 'serial:ttyS0:1500000'` секцію. ### Використання ноутбука Linux як GCS (важче, ніж використання RasPi) 1. На **наземному** Linux комп'ютері розробки: - ```sh - sudo apt install libpcap-dev libsodium-dev python3-all python3-twisted - git clone -b stable https://github.com/svpcom/wfb-ng.git - cd wfb-ng && make deb && sudo apt install ./deb_dist/wfb-ng*.deb - ``` + ```sh + sudo apt install libpcap-dev libsodium-dev python3-all python3-twisted + git clone -b stable https://github.com/svpcom/wfb-ng.git + cd wfb-ng && make deb && sudo apt install ./deb_dist/wfb-ng*.deb + ``` 2. Слідуйте інструкції з [Setup HOWTO](https://github.com/svpcom/wfb-ng/wiki/Setup-HOWTO) для завершення встановлення diff --git a/docs/uk/complete_vehicles_mc/amov_F410_drone.md b/docs/uk/complete_vehicles_mc/amov_F410_drone.md index 9f7a98d6d2..e6a906bb4c 100644 --- a/docs/uk/complete_vehicles_mc/amov_F410_drone.md +++ b/docs/uk/complete_vehicles_mc/amov_F410_drone.md @@ -22,7 +22,7 @@ It is pre-installed with PX4 v1.15.4 at time of writing (a more recent version m - Compatibility with many different components, providing platform for loading other user sensors, preparing for functional model development. - Abundant power supply making it perfect for installing additional sensors and onboard computers (including 5 external output voltages, 3 channels of 5V, 2 channels of 12V). - Pc-SDK support. - This is a PC-based Python SDK Library based on MAVSDK that significantly simplifies UAV development compared to other approaches, such as using ROS or using C++. All you need is a basic understanding of Python programming and some simple coordinate system principles! + This is a PC-based Python SDK Library based on MAVSDK that significantly simplifies UAV development compared to other approaches, such as using ROS or using C++. All you need is a basic understanding of Python programming and some simple coordinate system principles! - The [documentation](https://docs.amovlab.com/f450-v6c-wiki/#/en/) shows many of the options. 7. Quasi-smart battery. The battery has a hard housing design that makes easy to install and remove. It provides accurate power estimates, but does not have some more advanced "smart battery" features. diff --git a/docs/uk/complete_vehicles_mc/crazyflie2.md b/docs/uk/complete_vehicles_mc/crazyflie2.md index f30f6bdc0c..369edb5a70 100644 --- a/docs/uk/complete_vehicles_mc/crazyflie2.md +++ b/docs/uk/complete_vehicles_mc/crazyflie2.md @@ -51,54 +51,54 @@ _Crazyflie 2.0_ було [припинено/замінено](../flight_control 1. Завантажте вихідний код завантажувача PX4: - ```sh - git clone https://github.com/PX4/PX4-Bootloader.git - ``` + ```sh + git clone https://github.com/PX4/PX4-Bootloader.git + ``` 2. Перейдіть до верхньої директорії вихідного коду та скомпілюйте його за допомогою: - ```sh - make crazyflie_bl - ``` + ```sh + make crazyflie_bl + ``` 3. Поставте Crazyflie 2.0 у режим DFU, виконавши ці кроки: - - Спочатку переконайтеся, що він знеструмлений. - - Утримуйте кнопку скидання (див. малюнок нижче...). - ![Crazyflie2 Reset Button](../../assets/flight_controller/crazyflie/crazyflie_reset_button.jpg) - - Підключіть до USB-порту комп'ютера. - - Через секунду синій світлодіод повинен почати блимати, а через 5 секунд повинен почати блимати швидше. - - Відпустіть кнопку. + - Спочатку переконайтеся, що він знеструмлений. + - Утримуйте кнопку скидання (див. малюнок нижче...). + ![Crazyflie2 Reset Button](../../assets/flight_controller/crazyflie/crazyflie_reset_button.jpg) + - Підключіть до USB-порту комп'ютера. + - Через секунду синій світлодіод повинен почати блимати, а через 5 секунд повинен почати блимати швидше. + - Відпустіть кнопку. 4. Встановіть _dfu-util_: - ```sh - sudo apt-get update - sudo apt-get install dfu-util - ``` + ```sh + sudo apt-get update + sudo apt-get install dfu-util + ``` 5. Виконайте прошивку завантажувальника за допомогою _dfu-util_ та від'єднайте Crazyflie 2.0, коли це зроблено: - ```sh - sudo dfu-util -d 0483:df11 -a 0 -s 0x08000000 -D ./build/crazyflie_bl/crazyflie_bl.bin - ``` + ```sh + sudo dfu-util -d 0483:df11 -a 0 -s 0x08000000 -D ./build/crazyflie_bl/crazyflie_bl.bin + ``` - Коли увімкнено Crazyflie 2.0, жовтий світлодіод повинен мигати. + Коли увімкнено Crazyflie 2.0, жовтий світлодіод повинен мигати. 6. Завантажте вихідний код завантажувача автопілоту PX4: - ```sh - git clone https://github.com/PX4/PX4-Autopilot.git - ``` + ```sh + git clone https://github.com/PX4/PX4-Autopilot.git + ``` 7. Перейдіть до верхньої директорії вихідного коду та скомпілюйте його за допомогою: - ```sh - make bitcraze_crazyflie_default upload - ``` + ```sh + make bitcraze_crazyflie_default upload + ``` 8. Коли вас попросять підключити пристрій, підключіть Crazyflie 2.0. - Жовтий світлодіод повинен почати блимати, що вказує на режим завантажувача. - Потім червоний світлодіод повинен увімкнутися, що вказує на те, що процес мигання розпочався. + Жовтий світлодіод повинен почати блимати, що вказує на режим завантажувача. + Потім червоний світлодіод повинен увімкнутися, що вказує на те, що процес мигання розпочався. 9. Очікування завершення. diff --git a/docs/uk/complete_vehicles_mc/crazyflie21.md b/docs/uk/complete_vehicles_mc/crazyflie21.md index dc72e0b539..6b1e40dd18 100644 --- a/docs/uk/complete_vehicles_mc/crazyflie21.md +++ b/docs/uk/complete_vehicles_mc/crazyflie21.md @@ -64,56 +64,56 @@ An overview of the Crazyflie 2.1 can be [found here](https://www.bitcraze.io/pro 1. Завантажте вихідний код завантажувача PX4: - ```sh - git clone https://github.com/PX4/PX4-Bootloader.git --recurse-submodules - ``` + ```sh + git clone https://github.com/PX4/PX4-Bootloader.git --recurse-submodules + ``` 2. Перейдіть до верхньої директорії вихідного коду та скомпілюйте його за допомогою: - ```sh - make crazyflie21_bl - ``` + ```sh + make crazyflie21_bl + ``` 3. Поставте Crazyflie 2.1 у режим DFU, виконавши ці кроки: - - Спочатку переконайтеся, що він знеструмлений. - - Переконайтеся, що акумулятор від'єднаний. - - Утримуйте кнопку скидання (див. малюнок нижче...). - ![Crazyflie2 Reset Button](../../assets/flight_controller/crazyflie/crazyflie_reset_button.jpg) - - Підключіть до USB-порту комп'ютера. - - Через секунду синій світлодіод повинен почати блимати, а через 5 секунд повинен почати блимати швидше. - - Відпустіть кнопку. + - Спочатку переконайтеся, що він знеструмлений. + - Переконайтеся, що акумулятор від'єднаний. + - Утримуйте кнопку скидання (див. малюнок нижче...). + ![Crazyflie2 Reset Button](../../assets/flight_controller/crazyflie/crazyflie_reset_button.jpg) + - Підключіть до USB-порту комп'ютера. + - Через секунду синій світлодіод повинен почати блимати, а через 5 секунд повинен почати блимати швидше. + - Відпустіть кнопку. 4. Встановіть _dfu-util_: - ```sh - sudo apt-get update - sudo apt-get install dfu-util - ``` + ```sh + sudo apt-get update + sudo apt-get install dfu-util + ``` 5. Виконайте прошивку завантажувальника за допомогою _dfu-util_ та від'єднайте Crazyflie 2.1, коли це зроблено: - ```sh - sudo dfu-util -d 0483:df11 -a 0 -s 0x08000000 -D ./build/crazyflie21_bl/crazyflie21_bl.bin - ``` + ```sh + sudo dfu-util -d 0483:df11 -a 0 -s 0x08000000 -D ./build/crazyflie21_bl/crazyflie21_bl.bin + ``` - Коли увімкнено Crazyflie 2.1, жовтий світлодіод повинен мигати. + Коли увімкнено Crazyflie 2.1, жовтий світлодіод повинен мигати. 6. Завантажте вихідний код завантажувача автопілоту PX4: - ```sh - git clone https://github.com/PX4/PX4-Autopilot.git - ``` + ```sh + git clone https://github.com/PX4/PX4-Autopilot.git + ``` 7. Перейдіть до верхньої директорії вихідного коду та скомпілюйте його за допомогою: - ```sh - cd PX4-Autopilot/ - make bitcraze_crazyflie21_default upload - ``` + ```sh + cd PX4-Autopilot/ + make bitcraze_crazyflie21_default upload + ``` 8. Коли вас попросять підключити пристрій, підключіть Crazyflie 2.1. - Жовтий світлодіод повинен почати блимати, що вказує на режим завантажувача. - Потім червоний світлодіод повинен увімкнутися, що вказує на те, що процес мигання розпочався. + Жовтий світлодіод повинен почати блимати, що вказує на режим завантажувача. + Потім червоний світлодіод повинен увімкнутися, що вказує на те, що процес мигання розпочався. 9. Очікування завершення. @@ -124,20 +124,20 @@ An overview of the Crazyflie 2.1 can be [found here](https://www.bitcraze.io/pro 1. Завантажте останній [завантажувач Crazyflie 2.1](https://github.com/bitcraze/crazyflie2-stm-bootloader/releases) 2. Поставте Crazyflie 2.1 у режим DFU, виконавши ці кроки: - - Спочатку переконайтеся, що він знеструмлений. - - Переконайтеся, що акумулятор від'єднаний. - - Утримуйте кнопку скидання. - - Підключіть до USB-порту комп'ютера. - - Через секунду синій світлодіод повинен почати блимати, а через 5 секунд повинен почати блимати швидше. - - Відпустіть кнопку. + - Спочатку переконайтеся, що він знеструмлений. + - Переконайтеся, що акумулятор від'єднаний. + - Утримуйте кнопку скидання. + - Підключіть до USB-порту комп'ютера. + - Через секунду синій світлодіод повинен почати блимати, а через 5 секунд повинен почати блимати швидше. + - Відпустіть кнопку. 3. Виконайте прошивку завантажувальника за допомогою _dfu-util_ та від'єднайте Crazyflie 2.1, коли це зроблено: - ```sh - sudo dfu-util -d 0483:df11 -a 0 -s 0x08000000 -D cf2loader-1.0.bin - ``` + ```sh + sudo dfu-util -d 0483:df11 -a 0 -s 0x08000000 -D cf2loader-1.0.bin + ``` - Коли увімкнено Crazyflie 2.1, жовтий світлодіод повинен мигати. + Коли увімкнено Crazyflie 2.1, жовтий світлодіод повинен мигати. 4. Встановіть останнє програмне забезпечення для польоту Bitcraze Crazyflie 2.1, використовуючи [цей](https://www.bitcraze.io/documentation/tutorials/getting-started-with-crazyflie-2-x/#update-fw) посібник. diff --git a/docs/uk/complete_vehicles_mc/modalai_starling.md b/docs/uk/complete_vehicles_mc/modalai_starling.md index 4377709ef6..e3170acec4 100644 --- a/docs/uk/complete_vehicles_mc/modalai_starling.md +++ b/docs/uk/complete_vehicles_mc/modalai_starling.md @@ -84,26 +84,26 @@ The Starling features ModalAI's [open SDK](https://docs.modalai.com/voxl-develop #### Налаштування відображення 1. **Увімкніть приймач**: Як тільки ваш квадрокоптер увімкнено, ви помітите, що синій світлодіод приймача ELRS мигає. - Це свідчить про те, що отримувач увімкнений, але ще не встановив зв'язок з передавачем. + Це свідчить про те, що отримувач увімкнений, але ще не встановив зв'язок з передавачем. - ![Приймач Starling](../../assets/hardware/complete_vehicles/modalai_starling/starling-photo.png) + ![Приймач Starling](../../assets/hardware/complete_vehicles/modalai_starling/starling-photo.png) 2. **Увійдіть в режим зв'язку**: Для ініціювання зв'язку відкрийте термінал та виконайте команди `adb shell` та `voxl-elrs -bind`. - Ви побачите, що світлодіод приймача перемикається на миготливий в режимі миттєвого реагування, сигналізуючи, що тепер він у режимі зв'язку. + Ви побачите, що світлодіод приймача перемикається на миготливий в режимі миттєвого реагування, сигналізуючи, що тепер він у режимі зв'язку. - ![Boot Screenshot](../../assets/hardware/complete_vehicles/modalai_starling/screenshot-boot.png) + ![Boot Screenshot](../../assets/hardware/complete_vehicles/modalai_starling/screenshot-boot.png) #### Налаштування передавача 1. **Отримайте доступ до меню**: На вашому передавачі радіо Commando 8, включеному в комплект, натисніть ліву кнопку режиму, щоб відкрити систему меню. - ![Натисніть Меню на ПДУ](../../assets/hardware/complete_vehicles/modalai_starling/radio-1.png) + ![Натисніть Меню на ПДУ](../../assets/hardware/complete_vehicles/modalai_starling/radio-1.png) 2. **Перейдіть до ExpressLRS**: Використовуйте праву кнопку, щоб вибрати перший пункт меню, який повинен бути "ExpressLRS." 3. **Знайдіть опцію Bind**: Після вибору опції "ExpressLRS" прокрутіть вниз до нижньої частини меню, щоб знайти розділ "Bind". Це можна зробити, натиснувши праву кнопку донизу, поки ви не досягнете опцію "Прив'язка". - ![Press Binding on RC](../../assets/hardware/complete_vehicles/modalai_starling/radio-2.png) + ![Press Binding on RC](../../assets/hardware/complete_vehicles/modalai_starling/radio-2.png) 4. **Ініціювати Прив'язку**: Виберіть "Прив'язати", щоб перевести передавач у режим прив'язки. Ви будете знати, що процес був успішним, коли передавач видасть сигнал, вказуючи на успішне зв'язування. diff --git a/docs/uk/complete_vehicles_mc/px4_vision_kit.md b/docs/uk/complete_vehicles_mc/px4_vision_kit.md index 23e34ce1b9..45f56e1c9d 100644 --- a/docs/uk/complete_vehicles_mc/px4_vision_kit.md +++ b/docs/uk/complete_vehicles_mc/px4_vision_kit.md @@ -42,17 +42,17 @@ This kit is still highly recommended for developing and testing vision solutions ## Попередження та сповіщення 1. Комплект призначений для проєктів комп'ютерного зору, які використовують камеру, спрямовану вперед (він не має камер глибини, спрямованих вниз або назад). - Consequently it can't be used (without modification) for testing features that require a downward-facing camera. + Consequently it can't be used (without modification) for testing features that require a downward-facing camera. 2. Уникання перешкод у місіях можна тестувати лише за наявності сигналу GPS (місії використовують GPS-координати). - Запобігання зіткненням можна перевірити в режимі позиціювання за умови, що є стійке захоплення позиції, отримане або з GPS, або з оптичного потоку. + Запобігання зіткненням можна перевірити в режимі позиціювання за умови, що є стійке захоплення позиції, отримане або з GPS, або з оптичного потоку. 3. Порт, позначений `USB1`, може глушити GPS, якщо його використовувати з периферійним пристроєм _USB3_ (вимкніть GPS-залежні функції, зокрема місії). - Саме тому образ завантаження постачається на флешці _USB2.0_. + Саме тому образ завантаження постачається на флешці _USB2.0_. 4. PX4 Vision v1 з ECN 010 або вище (несуча плата RC05 і вище), _UP Core_ може живитися як від розетки постійного струму, так і від акумулятора. - ![RC Number](../../assets/hardware/px4_vision_devkit/rc.png) ![ECN Number](../../assets/hardware/px4_vision_devkit/serial_number_update.jpg) + ![RC Number](../../assets/hardware/px4_vision_devkit/rc.png) ![ECN Number](../../assets/hardware/px4_vision_devkit/serial_number_update.jpg) 5. Всі PX4 Vision v1.5 _UP Core_ можна живити як від мережі постійного струму, так і від батареї. @@ -132,37 +132,37 @@ PX4 Vision DevKit містить наступні компоненти: ## Перший запуск 1. Підключіть [сумісний RC приймач](../getting_started/rc_transmitter_receiver.md#connecting-receivers) до транспортного засобу (не постачається в комплекті): - - Видаліть/відкрутіть верхню пластину (де йде батарея) за допомогою інструменту з головками шестигранника H2.0. - - [Підключіть приймач до контролера польоту](../assembly/quick_start_pixhawk4.md#radio-control). - - Прикріпіть знову верхню пластину. - - Встановіть RC-приймач на плату кар'єра _UP Core_ на задній частині транспортного засобу (використовуйте зажими або двосторонній скотч). - - Переконайтеся, що антени вільні від будь-яких перешкод і електрично ізольовані від рами (наприклад, закріпіть їх під платою або до рук або ніг транспортного засобу). + - Видаліть/відкрутіть верхню пластину (де йде батарея) за допомогою інструменту з головками шестигранника H2.0. + - [Підключіть приймач до контролера польоту](../assembly/quick_start_pixhawk4.md#radio-control). + - Прикріпіть знову верхню пластину. + - Встановіть RC-приймач на плату кар'єра _UP Core_ на задній частині транспортного засобу (використовуйте зажими або двосторонній скотч). + - Переконайтеся, що антени вільні від будь-яких перешкод і електрично ізольовані від рами (наприклад, закріпіть їх під платою або до рук або ніг транспортного засобу). 2. [Прив'яжіть](../getting_started/rc_transmitter_receiver.md#binding) земельні та повітряні блоки керування RC (якщо ще не зроблено). - Процедура прив'язки залежить від конкретної радіосистеми, яку використовують (прочитайте посібник користувача приймача). + Процедура прив'язки залежить від конкретної радіосистеми, яку використовують (прочитайте посібник користувача приймача). 3. Підніміть стійку GPS до вертикального положення та вкрутіть кришку на тримач на базовій пластині. (Не потрібно для v1.5) - ![Підніміть мачту GPS](../../assets/hardware/px4_vision_devkit/raise_gps_mast.jpg) + ![Підніміть мачту GPS](../../assets/hardware/px4_vision_devkit/raise_gps_mast.jpg) 4. Уставте попередньо зображену USB2.0-ручку зі набору в порт _UP Core_, позначений як `USB1` (виділено нижче). - ![UP Core: Порт USB1 ](../../assets/hardware/px4_vision_devkit/upcore_port_usb1.png) + ![UP Core: Порт USB1 ](../../assets/hardware/px4_vision_devkit/upcore_port_usb1.png) 5. Запустіть транспортний засіб з повністю зарядженою батареєю. - :::info - Переконайтеся, що гвинти від'єднані перед підключенням батареї. + :::info + Переконайтеся, що гвинти від'єднані перед підключенням батареї. ::: 6. Підключіть земельну станцію до мережі WiFi транспортного засобу (через кілька секунд) за допомогою наступних типових облікових даних: - - **SSID:** pixhawk4 - - **Пароль:** px4vision + - **SSID:** pixhawk4 + - **Пароль:** px4vision - :::tip - Ім'я мережі WiFi, пароль та інші облікові дані можуть бути змінені після підключення (за бажанням), використовуючи веб-переглядач для відкриття URL-адреси: `http://192.168.4.1`. - Швидкість передачі даних (baud rate) не повинна змінюватися з 921600. + :::tip + Ім'я мережі WiFi, пароль та інші облікові дані можуть бути змінені після підключення (за бажанням), використовуючи веб-переглядач для відкриття URL-адреси: `http://192.168.4.1`. + Швидкість передачі даних (baud rate) не повинна змінюватися з 921600. ::: @@ -170,39 +170,39 @@ PX4 Vision DevKit містить наступні компоненти: 8. [Налаштувати/калібрувати](../config/index.md) транспортний засіб: - :::info - Транспортний засіб повинен прибути попередньо каліброваним (наприклад, з вбудованим програмним забезпеченням, конструкцією корпусу, батареєю та датчиками, всі встановлені). - Проте вам все одно потрібно калібрувати радіосистему (яку ви щойно підключили), і часто варто повторно виконати калібрування компаса. + :::info + Транспортний засіб повинен прибути попередньо каліброваним (наприклад, з вбудованим програмним забезпеченням, конструкцією корпусу, батареєю та датчиками, всі встановлені). + Проте вам все одно потрібно калібрувати радіосистему (яку ви щойно підключили), і часто варто повторно виконати калібрування компаса. ::: - - [Калібрування Радісистеми](../config/radio.md) - - [Калібрувати Компас](../config/compass.md) + - [Калібрування Радісистеми](../config/radio.md) + - [Калібрувати Компас](../config/compass.md) 9. (Опціонально) Налаштуйте перемикач режиму польоту на пульті дистанційного керування, скориставшись [вибором режиму польоту](../config/flight_mode.md). - :::info - Режими також можна змінити за допомогою _QGroundControl_ + :::info + Режими також можна змінити за допомогою _QGroundControl_ ::: - Ми рекомендуємо визначити RC контролери для перемикачів: + Ми рекомендуємо визначити RC контролери для перемикачів: - - [Режим позиції](../flight_modes_mc/position.md) - безпечний ручний режим польоту, який можна використовувати для тестування запобігання зіткнень. - - [Режим місії](../flight_modes_mc/mission.md) - виконуйте місії та тестуйте уникання перешкод. - - [Режим повернення](../flight_modes_mc/return.md) - повернення транспортного засобу безпечно до точки запуску та посадка. + - [Режим позиції](../flight_modes_mc/position.md) - безпечний ручний режим польоту, який можна використовувати для тестування запобігання зіткнень. + - [Режим місії](../flight_modes_mc/mission.md) - виконуйте місії та тестуйте уникання перешкод. + - [Режим повернення](../flight_modes_mc/return.md) - повернення транспортного засобу безпечно до точки запуску та посадка. 10. Прикріпіть гвинти з обертанням, як показано: - ![Motor Order Diagram](../../assets/hardware/px4_vision_devkit/motor_order_diagram.png) + ![Motor Order Diagram](../../assets/hardware/px4_vision_devkit/motor_order_diagram.png) - - Напрямки гвинтів можна визначити за мітками: _6045_ (звичайний, проти годинникової стрілки) та _6045_**R** (обернений, за годинниковою стрілкою). + - Напрямки гвинтів можна визначити за мітками: _6045_ (звичайний, проти годинникової стрілки) та _6045_**R** (обернений, за годинниковою стрілкою). - ![Ідентифікація гвинта](../../assets/hardware/px4_vision_devkit/propeller_directions.jpg) + ![Ідентифікація гвинта](../../assets/hardware/px4_vision_devkit/propeller_directions.jpg) - - Закрутіть тісно за допомогою наданих гайок пропелера: + - Закрутіть тісно за допомогою наданих гайок пропелера: - ![Гайки гвинтів](../../assets/hardware/px4_vision_devkit/propeller_nuts.png) + ![Гайки гвинтів](../../assets/hardware/px4_vision_devkit/propeller_nuts.png) ## Політ дроном з униканням @@ -212,30 +212,30 @@ PX4 Vision DevKit містить наступні компоненти: 2. Зачекайте, доки завершиться послідовність завантаження та система уникання розпочне роботу (транспортний засіб відхилить команди на озброєння під час завантаження). - :::tip - Процес завантаження/початку роботи триває близько 1 хвилини з постачаної USB-флешки (або 30 секунд з [внутрішньої пам'яті](#install_image_mission_computer)). + :::tip + Процес завантаження/початку роботи триває близько 1 хвилини з постачаної USB-флешки (або 30 секунд з [внутрішньої пам'яті](#install_image_mission_computer)). ::: 3. Перевірте, що система уникання почала працювати належним чином: - - Журнал сповіщень _QGroundControl_ відображає повідомлення: **Підключена система уникнення**. + - Журнал сповіщень _QGroundControl_ відображає повідомлення: **Підключена система уникнення**. - ![QGC Журнал показує, що система уникання почалася](../../assets/hardware/px4_vision_devkit/qgc_console_vision_system_started.jpg) + ![QGC Журнал показує, що система уникання почалася](../../assets/hardware/px4_vision_devkit/qgc_console_vision_system_started.jpg) - - Червоний лазер видно на передній частині камери _Structure Core_. + - Червоний лазер видно на передній частині камери _Structure Core_. 4. Зачекайте, доки світлодіод GPS не засвітиться зеленим кольором. - Це означає, що у транспортного засобу є GPS фіксація і він готовий до польоту! + Це означає, що у транспортного засобу є GPS фіксація і він готовий до польоту! 5. Підключіть наземну станцію до мережі WiFi транспортного засобу. 6. Знайдіть безпечне зовнішнє місце для польоту, ідеально з деревом або якою-небудь іншою зручною перешкодою для тестування PX4 Vision. 7. Для тестування [попередження про зіткнення](../computer_vision/collision_prevention.md), увімкніть [Режим Позиції](../flight_modes_mc/position.md) та літайте вручну до перешкоди. - Транспортний засіб повинен сповільнити і зупинитися протягом 6м від перешкоди (відстань може бути [змінена](../advanced_config/parameters.md) за допомогою параметра [CP_DIST](../advanced_config/parameter_reference.md#CP_DIST)). + Транспортний засіб повинен сповільнити і зупинитися протягом 6м від перешкоди (відстань може бути [змінена](../advanced_config/parameters.md) за допомогою параметра [CP_DIST](../advanced_config/parameter_reference.md#CP_DIST)). 8. To test obstacle avoidance, create a mission where the path is blocked by an obstacle. - Потім перейдіть до [Режиму Місії](../flight_modes_mc/mission.md), щоб запустити місію, і спостерігайте, як транспортний засіб рухається навколо перешкоди, а потім повертається на запланований курс. + Потім перейдіть до [Режиму Місії](../flight_modes_mc/mission.md), щоб запустити місію, і спостерігайте, як транспортний засіб рухається навколо перешкоди, а потім повертається на запланований курс. ## Розробка за допомогою комплекту @@ -280,22 +280,22 @@ PX4 та супутниковий комп'ютер обмінюються да 2. [Увійдіть в супровідний комп'ютер](#login_mission_computer) (як описано вище). 3. Відкрийте термінал та виконайте наступну команду, щоб скопіювати зображення на внутрішню пам'ять (eMMC). - Термінал буде пропонувати ввести кількість відповідей під час процесу прошивки. + Термінал буде пропонувати ввести кількість відповідей під час процесу прошивки. - ```sh - cd ~/catkin_ws/src/px4vision_ros/tools - sudo ./flash_emmc.sh - ``` + ```sh + cd ~/catkin_ws/src/px4vision_ros/tools + sudo ./flash_emmc.sh + ``` - :::info - Всю інформацію, збережену в комп'ютері _UP Core_, буде видалено при виконанні цього сценарію. + :::info + Всю інформацію, збережену в комп'ютері _UP Core_, буде видалено при виконанні цього сценарію. ::: 4. Витягніть USB-флешку. 5. Перезавантажте пристрій. - Тепер ком'ютер _UP Core_ буде завантажений з внутрішньої пам'яті (eMMC). + Тепер ком'ютер _UP Core_ буде завантажений з внутрішньої пам'яті (eMMC). ### Запустіть супутній комп'ютер @@ -319,23 +319,23 @@ PX4 та супутниковий комп'ютер обмінюються да 1. Підключіть клавіатуру та мишу до _UP Core_ через порт `USB2`: - ![UP Core: USB2](../../assets/hardware/px4_vision_devkit/upcore_port_usb2.png) + ![UP Core: USB2](../../assets/hardware/px4_vision_devkit/upcore_port_usb2.png) - - Використовуйте кабель USB-JST з комплекту, щоб отримати роз'єм USB A + - Використовуйте кабель USB-JST з комплекту, щоб отримати роз'єм USB A - ![USB to JST cable](../../assets/hardware/px4_vision_devkit/usb_jst_cable.jpg) + ![USB to JST cable](../../assets/hardware/px4_vision_devkit/usb_jst_cable.jpg) - - До кабелю можна підключити USB хаб, якщо клавіатура та миша мають окремі роз'єми. + - До кабелю можна підключити USB хаб, якщо клавіатура та миша мають окремі роз'єми. 2. Підключіть монітор до порту HDMI _UP Core_. - ![UP Core: Порт HDMI](../../assets/hardware/px4_vision_devkit/upcore_port_hdmi.png) + ![UP Core: Порт HDMI](../../assets/hardware/px4_vision_devkit/upcore_port_hdmi.png) - Екран входу в Ubuntu повинен з'явитися на моніторі. + Екран входу в Ubuntu повинен з'явитися на моніторі. 3. Увійдіть в _UP Core_ за допомогою облікових даних: - - **Username:** px4vision - - **Password:** px4vision + - **Username:** px4vision + - **Password:** px4vision ### Розробка / Розширення уникнення PX4 @@ -350,39 +350,39 @@ PX4 та супутниковий комп'ютер обмінюються да 1. Вимкніть процес уникання за допомогою наступної команди: - ```sh - systemctl stop avoidance.service - ``` + ```sh + systemctl stop avoidance.service + ``` - Ви можете просто перезавантажити машину, щоб перезапустити службу. + Ви можете просто перезавантажити машину, щоб перезапустити службу. - Інші корисні команди підтримуються: + Інші корисні команди підтримуються: - ```sh - # restart service - systemctl start avoidance.service + ```sh + # restart service + systemctl start avoidance.service - # disable service (stop service and do not restart after boot) - systemctl disable avoidance.service + # disable service (stop service and do not restart after boot) + systemctl disable avoidance.service - # enable service (start service and enable restart after boot) - systemctl enable avoidance.service - ``` + # enable service (start service and enable restart after boot) + systemctl enable avoidance.service + ``` 2. Вихідний код пакету уникання перешкод можна знайти за адресою https://github.com/PX4/PX4-Avoidance, який розташований в `~/catkin_ws/src/avoidance`. 3. Внесіть зміни до коду! Щоб отримати останній код уникання, витягніть код з репозиторію уникання: - ```sh - git pull origin - git checkout origin/master - ``` + ```sh + git pull origin + git checkout origin/master + ``` 4. Побудуйте пакет - ```sh - catkin build local_planner - ``` + ```sh + catkin build local_planner + ``` Робоче середовище ROS розміщене в `~/catkin_ws`. For reference on developing in ROS and using the catkin workspace, see the [ROS catkin tutorials](https://wiki.ros.org/catkin/Tutorials). diff --git a/docs/uk/complete_vehicles_rover/aion_r1.md b/docs/uk/complete_vehicles_rover/aion_r1.md index 45072c8fb8..1eac40e8fe 100644 --- a/docs/uk/complete_vehicles_rover/aion_r1.md +++ b/docs/uk/complete_vehicles_rover/aion_r1.md @@ -54,15 +54,15 @@ RoboClaw повинен бути підключений до відповідн Спочатку налаштуйте послідовне з'єднання: 1. Перейдіть до розділу [Параметри](../advanced_config/parameters.md) в QGroundControl. - - Встановіть параметр [RBCLW_SER_CFG](../advanced_config/parameter_reference.md#RBCLW_SER_CFG) на послідовний порт, до якого підключений RoboClaw (наприклад, `GPS2`). - - [RBCLW_COUNTS_REV](../advanced_config/parameter_reference.md#RBCLW_COUNTS_REV) визначає кількість лічильників енкодера, необхідних для одного оберту колеса. - Це значення повинно бути залишено на `1200` для протестованого `Контролера руху RoboClaw 2x15A`. - Відрегулюйте значення на основі вашого конкретного енкодера та налаштувань колеса. - - Контролери моторів RoboClaw повинні мати унікальну адресу на шині. - Стандартна адреса - 128, і вам не потрібно її змінювати (якщо ви це робите, оновіть параметр PX4 [RBCLW_ADDRESS](../advanced_config/parameter_reference.md#RBCLW_ADDRESS) відповідно). + - Встановіть параметр [RBCLW_SER_CFG](../advanced_config/parameter_reference.md#RBCLW_SER_CFG) на послідовний порт, до якого підключений RoboClaw (наприклад, `GPS2`). + - [RBCLW_COUNTS_REV](../advanced_config/parameter_reference.md#RBCLW_COUNTS_REV) визначає кількість лічильників енкодера, необхідних для одного оберту колеса. + Це значення повинно бути залишено на `1200` для протестованого `Контролера руху RoboClaw 2x15A`. + Відрегулюйте значення на основі вашого конкретного енкодера та налаштувань колеса. + - Контролери моторів RoboClaw повинні мати унікальну адресу на шині. + Стандартна адреса - 128, і вам не потрібно її змінювати (якщо ви це робите, оновіть параметр PX4 [RBCLW_ADDRESS](../advanced_config/parameter_reference.md#RBCLW_ADDRESS) відповідно). - :::info - PX4 не підтримує кілька контролерів моторів RoboClaw у тому ж транспортному засобі — кожен контролер повинен мати унікальну адресу на шині, і є лише один параметр для встановлення адреси в PX4 (`RBCLW_ADDRESS`). + :::info + PX4 не підтримує кілька контролерів моторів RoboClaw у тому ж транспортному засобі — кожен контролер повинен мати унікальну адресу на шині, і є лише один параметр для встановлення адреси в PX4 (`RBCLW_ADDRESS`). ::: @@ -71,12 +71,12 @@ RoboClaw повинен бути підключений до відповідн 1. Перейдіть до [Конфігурації та тестування приводів](../config/actuators.md) в QGroundControl. 2. Виберіть драйвер RoboClaw зі списку _Виводів приводів_. - Для призначень каналу, роззброю, мінімальних та максимальних значень, будь ласка, звертайтеся до зображення нижче. + Для призначень каналу, роззброю, мінімальних та максимальних значень, будь ласка, звертайтеся до зображення нижче. - ![RoboClaw QGC](../../assets/airframes/rover/aion_r1/roboclaw_actuator_config_qgc.png) + ![RoboClaw QGC](../../assets/airframes/rover/aion_r1/roboclaw_actuator_config_qgc.png) - Для систем з більш ніж двома двигунами можливо призначити одну й ту ж функцію кільком двигунам. - Причина нестандартних значень можна знайти в [Користувацькому посібнику RoboClaw](https://downloads.basicmicro.com/docs/roboclaw_user_manual.pdf) під `Командами сумісності` для `Пакетної послідовної передачі даних`: + Для систем з більш ніж двома двигунами можливо призначити одну й ту ж функцію кільком двигунам. + Причина нестандартних значень можна знайти в [Користувацькому посібнику RoboClaw](https://downloads.basicmicro.com/docs/roboclaw_user_manual.pdf) під `Командами сумісності` для `Пакетної послідовної передачі даних`: ```plain Приводити двигун вперед. Діапазон дійсних даних - від 0 до 127. Значення 127 = повна швидкість вперед, 64 = diff --git a/docs/uk/computer_vision/collision_prevention.md b/docs/uk/computer_vision/collision_prevention.md index 23f70960ff..ba066177f5 100644 --- a/docs/uk/computer_vision/collision_prevention.md +++ b/docs/uk/computer_vision/collision_prevention.md @@ -203,85 +203,85 @@ The Lua script works by extracting the `obstacle_distance_fused` data at each ti 2. Configure PX4 to publish obstacle distance data (so that it is available to PlotJuggler): - Add the [`obstacle_distance_fused`](../msg_docs/ObstacleDistance.md) UORB topic to your [`dds_topics.yaml`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) so that it is published by PX4: + Add the [`obstacle_distance_fused`](../msg_docs/ObstacleDistance.md) UORB topic to your [`dds_topics.yaml`](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) so that it is published by PX4: - ```sh - - topic: /fmu/out/obstacle_distance_fused - type: px4_msgs::msg::ObstacleDistance - ``` + ```sh + - topic: /fmu/out/obstacle_distance_fused + type: px4_msgs::msg::ObstacleDistance + ``` - For more information see [DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml) in [uXRCE-DDS](../middleware/uxrce_dds.md) (PX4-ROS 2/DDS Bridge)\_. + For more information see [DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml) in [uXRCE-DDS](../middleware/uxrce_dds.md) (PX4-ROS 2/DDS Bridge)\_. 3. Open PlotJuggler and navigate to the **Tools > Reactive Script Editor** section. - In the **Script Editor** tab, add following scripts in the appropriate sections: + In the **Script Editor** tab, add following scripts in the appropriate sections: - - **Global code, executed once:** + - **Global code, executed once:** - ```lua - obs_dist_fused_xy = ScatterXY.new("obstacle_distance_fused_xy") - obs_dist_min = Timeseries.new("obstacle_distance_minimum") - ``` + ```lua + obs_dist_fused_xy = ScatterXY.new("obstacle_distance_fused_xy") + obs_dist_min = Timeseries.new("obstacle_distance_minimum") + ``` - - **function(tracker_time)** + - **function(tracker_time)** - ```lua - obs_dist_fused_xy:clear() + ```lua + obs_dist_fused_xy:clear() - i = 0 - angle_offset = TimeseriesView.find("/fmu/out/obstacle_distance_fused/angle_offset") - increment = TimeseriesView.find("/fmu/out/obstacle_distance_fused/increment") - min_dist = 65535 + i = 0 + angle_offset = TimeseriesView.find("/fmu/out/obstacle_distance_fused/angle_offset") + increment = TimeseriesView.find("/fmu/out/obstacle_distance_fused/increment") + min_dist = 65535 - -- Cache increment and angle_offset values at tracker_time to avoid repeated calls - local angle_offset_value = angle_offset:atTime(tracker_time) - local increment_value = increment:atTime(tracker_time) + -- Cache increment and angle_offset values at tracker_time to avoid repeated calls + local angle_offset_value = angle_offset:atTime(tracker_time) + local increment_value = increment:atTime(tracker_time) - if increment_value == nil or increment_value <= 0 then - print("Invalid increment value: " .. tostring(increment_value)) - return - end + if increment_value == nil or increment_value <= 0 then + print("Invalid increment value: " .. tostring(increment_value)) + return + end - local max_steps = math.floor(360 / increment_value) + local max_steps = math.floor(360 / increment_value) - while i < max_steps do - local str = string.format("/fmu/out/obstacle_distance_fused/distances[%d]", i) - local distance = TimeseriesView.find(str) - if distance == nil then - print("No distance data for: " .. str) - break - end + while i < max_steps do + local str = string.format("/fmu/out/obstacle_distance_fused/distances[%d]", i) + local distance = TimeseriesView.find(str) + if distance == nil then + print("No distance data for: " .. str) + break + end - local dist = distance:atTime(tracker_time) - if dist ~= nil and dist < 65535 then - -- Calculate angle and Cartesian coordinates - local angle = angle_offset_value + i * increment_value - local y = dist * math.cos(math.rad(angle)) - local x = dist * math.sin(math.rad(angle)) + local dist = distance:atTime(tracker_time) + if dist ~= nil and dist < 65535 then + -- Calculate angle and Cartesian coordinates + local angle = angle_offset_value + i * increment_value + local y = dist * math.cos(math.rad(angle)) + local x = dist * math.sin(math.rad(angle)) - obs_dist_fused_xy:push_back(x, y) + obs_dist_fused_xy:push_back(x, y) - -- Update minimum distance - if dist < min_dist then - min_dist = dist - end - end + -- Update minimum distance + if dist < min_dist then + min_dist = dist + end + end - i = i + 1 - end + i = i + 1 + end - -- Push minimum distance once after the loop - if min_dist < 65535 then - obs_dist_min:push_back(tracker_time, min_dist) - else - print("No valid minimum distance found") - end - ``` + -- Push minimum distance once after the loop + if min_dist < 65535 then + obs_dist_min:push_back(tracker_time, min_dist) + else + print("No valid minimum distance found") + end + ``` 4. Enter a name for the script on the top right, and press **Save**. - Once saved, the script should appear in the _Active Scripts_ section. + Once saved, the script should appear in the _Active Scripts_ section. 5. Start streaming the data using the approach described in [Plotting uORB Topic Data in Real Time using PlotJuggler](../debug/plotting_realtime_uorb_data.md). - You should see the `obstacle_distance_fused_xy` and `obstacle_distance_minimum` timeseries on the left. + You should see the `obstacle_distance_fused_xy` and `obstacle_distance_minimum` timeseries on the left. Note that you have to press **Save** again to re-enable the scripts after loading a new log file or otherwise clearing data. diff --git a/docs/uk/computer_vision/visual_inertial_odometry.md b/docs/uk/computer_vision/visual_inertial_odometry.md index ba9156ba23..d2c2dfb0c5 100644 --- a/docs/uk/computer_vision/visual_inertial_odometry.md +++ b/docs/uk/computer_vision/visual_inertial_odometry.md @@ -125,15 +125,15 @@ For more detailed/additional information, see: [Using PX4's Navigation Filter (E Якщо ці кроки є послідовними, ви можете спробувати свій перший польот: 1. Покладіть літак на землю і почніть передавати зворотний зв'язок `ODOMETRY` (як вище). - Потягніть палицю газу вниз і зберметизуйте двигуни. + Потягніть палицю газу вниз і зберметизуйте двигуни. - На цьому етапі, зліва палиця на найнижчому положенні, перейдіть у режим позиціонного контролю. - Ви повинні побачити зелену лампочку. - Зелена лампочка свідчить про те, що доступний зворотний зв'язок позиції, і позиційний контроль активований. + На цьому етапі, зліва палиця на найнижчому положенні, перейдіть у режим позиціонного контролю. + Ви повинні побачити зелену лампочку. + Зелена лампочка свідчить про те, що доступний зворотний зв'язок позиції, і позиційний контроль активований. 2. Покладіть палицю газу в середину (мертву зону), щоб літак підтримував свою висоту. - Підняття палиці збільшить висоту посилки, тоді як зниження значення зменшить її. - Так само, інша палиця змінить положення над землею. + Підняття палиці збільшить висоту посилки, тоді як зниження значення зменшить її. + Так само, інша палиця змінить положення над землею. 3. Збільшуйте значення перемикача газу, і літак злетить. Відразу після цього поверніть його в середину. diff --git a/docs/uk/concept/flight_tasks.md b/docs/uk/concept/flight_tasks.md index 1752a20812..4753edcdd0 100644 --- a/docs/uk/concept/flight_tasks.md +++ b/docs/uk/concept/flight_tasks.md @@ -38,24 +38,24 @@ _Польотні завдання_ використовуються у [Реж - Оновіть відмітку про авторське право до поточного року - ```cmake - ############################################################################ - # - # Copyright (c) 2021 PX4 Development Team. All rights reserved. - # - ``` + ```cmake + ############################################################################ + # + # Copyright (c) 2021 PX4 Development Team. All rights reserved. + # + ``` - Модифікуйте код щоб він відповідав новому завданню, наприклад замініть `FlightTaskOrbit` на `FlightTaskMyTask`. - Код буде виглядати приблизно так: + Код буде виглядати приблизно так: - ```cmake - px4_add_library(FlightTaskMyTask - FlightTaskMyTask.cpp - ) + ```cmake + px4_add_library(FlightTaskMyTask + FlightTaskMyTask.cpp + ) - target_link_libraries(FlightTaskMyTask PUBLIC FlightTask) - target_include_directories(FlightTaskMyTask PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) - ``` + target_link_libraries(FlightTaskMyTask PUBLIC FlightTask) + target_include_directories(FlightTaskMyTask PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) + ``` 4. Оновіть файл заголовків (у цьому випадку **FlightTaskMyTask. pp**): Більшість завдань повторно реалізує віртуальні методи `activate()` і `update()`, в цьому прикладі ми також маємо приватну змінну. @@ -140,35 +140,35 @@ _Польотні завдання_ використовуються у [Реж - Оновіть `MPC_POS_MODE` ([multicopter_position_mode_params.](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mc_pos_control/multicopter_position_mode_params.c)), щоб додати варіант для вибору "MyTask", якщо параметр має раніше невикористане значення, наприклад 5: - ```c - ... - * @value 0 Direct velocity - * @value 3 Smoothed velocity - * @value 4 Acceleration based - * @value 5 My task - * @group Multicopter Position Control - */ - PARAM_DEFINE_INT32(MPC_POS_MODE, 5); - ``` + ```c + ... + * @value 0 Direct velocity + * @value 3 Smoothed velocity + * @value 4 Acceleration based + * @value 5 My task + * @group Multicopter Position Control + */ + PARAM_DEFINE_INT32(MPC_POS_MODE, 5); + ``` - Додайте мітку case для нового варіанту в операторі switch для параметра в [FlightModeManager.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/flight_mode_manager/FlightModeManager.cpp#L266-L285), щоб увімкнути завдання коли `_param_mpc_pos_mode` має відповідне значення. - ```cpp - ... - // manual position control - ... - switch (_param_mpc_pos_mode.get()) { - ... - case 3: - error = switchTask(FlightTaskIndex::ManualPositionSmoothVel); - break; - case 5: // Add case for new task: MyTask - error = switchTask(FlightTaskIndex::MyTask); - break; - case 4: - .... - ... - ``` + ```cpp + ... + // manual position control + ... + switch (_param_mpc_pos_mode.get()) { + ... + case 3: + error = switchTask(FlightTaskIndex::ManualPositionSmoothVel); + break; + case 5: // Add case for new task: MyTask + error = switchTask(FlightTaskIndex::MyTask); + break; + case 4: + .... + ... + ``` ## Перевірка нового польотного завдання diff --git a/docs/uk/concept/system_startup.md b/docs/uk/concept/system_startup.md index c4d74386af..e1cc0abd18 100644 --- a/docs/uk/concept/system_startup.md +++ b/docs/uk/concept/system_startup.md @@ -13,9 +13,9 @@ They are exported at build-time into an `airframes.xml` file which is parsed by Наступні секції розділені відповідно до операційної системи, на яких виконується PX4. -## Posix (Linux/MacOS) +## POSIX (Linux/MacOS) -На Posix системна оболонка використовується як інтерпретатор скриптів (наприклад, /bin/sh що є символьним посиланням на dash в Ubuntu). +On POSIX, the system shell is used as script interpreter (e.g. /bin/sh, being symlinked to dash on Ubuntu). Щоб це працювало потрібно кілька речей: - Модулі PX4 повинні виглядати для системи як окремі виконувані файли. @@ -59,7 +59,7 @@ cd /build/px4_sitl_default/bin ### Динамічні модулі Зазвичай всі модулі компілюються в єдиний виконуваний файл PX4. -Однак, на Posix системах, є можливість компіляції модуля в окремий файл, який можна завантажити в PX4 використовуючи команду `dyn`. +However, on POSIX, there's the option of compiling a module into a separate file, which can be loaded into PX4 using the `dyn` command. ```sh dyn ./test.px4mod @@ -95,7 +95,7 @@ NuttX має інтегрований інтерпретатор оболонк Найкращий спосіб змінити запуск системи - це ввести [нову конфігурацію планера](../dev_airframes/adding_a_new_frame.md). Файл конфігурації планеру може бути включений у прошивку або на SD карту. -#### Dynamic customization +#### Dynamic Customization Якщо вам потрібно "підлаштувати" конфігурацію що існує, наприклад запустити один або більше застосунків або встановити значення кількох параметрів, можна вказати це створивши два файли у директорії `/etc/` на SD картці: @@ -153,27 +153,36 @@ param set-default PWM_MAIN_MIN3 1120 mandatory_app start # Will abort boot if mandatory_app is unknown or fails ``` -#### Additional customization +#### Additional Init-File Customization -In rare cases where the desired setup cannot be achieved through frame configuration or dynamic customization, -you can add a script that will be contained in the binary. +In rare cases where the desired setup cannot be achieved through frame configuration or dynamic customization, you can add a script that will be compiled into the binary for a particular `make` target build variant. -**Note**: In almost all cases, you should use a frame configuration. This method should only be used for -edge-cases such as customizing `cannode` based boards. +:::warning +In almost all cases, you should use a frame configuration. +This method should only be used for edge-cases such as customizing `cannode` based boards. +::: + +Кроки наступні: + +- Add a new init script in `boards///init` that will run during board startup. + Наприклад: -- Add a new init script in `boards///init` that will run during board startup. Наприклад: ```sh # File: boards///init/rc.additional param set-default ``` -- Add a new board variant in `boards///.px4board` that includes the additional script. Наприклад: +- Add a new board variant in `boards///.px4board` that includes the additional script. + Наприклад: + ```sh # File: boards///var.px4board CONFIG_BOARD_ADDITIONAL_INIT="rc.additional" ``` -- Compile the firmware with your new variant by appending the variant name to the compile target. Наприклад: +- Compile the firmware with your new variant by appending the variant name to the compile target. + Наприклад: + ```sh make _var ``` diff --git a/docs/uk/config/_autotune.md b/docs/uk/config/_autotune.md index a372307923..f03800852a 100644 --- a/docs/uk/config/_autotune.md +++ b/docs/uk/config/_autotune.md @@ -43,13 +43,13 @@ The airframe must fly well enough to handle moderate disturbances, and should be 2. Take off and
hover at 1m above ground in [Altitude mode](../flight_modes_mc/altitude.md) or [Stabilized mode](../flight_modes_mc/manual_stabilized.md)
fly at cruise speed in [Position mode](../flight_modes_fw/position.md) or [Altitude mode](../flight_modes_fw/altitude.md)
. 3. Use the RC transmitter roll stick to perform the following maneuver, tilting the vehicle just a few degrees: _roll left > roll right > center_ (The whole maneuver should take about 3 seconds). - Транспортний засіб повинен стабілізуватися протягом 2 коливань. + Транспортний засіб повинен стабілізуватися протягом 2 коливань. 4. Повторіть маневр, нахиляючись з більшими амплітудами при кожної спроби. - Якщо транспортний засіб може стабілізуватися протягом 2 коливань під кутом близько 20 градусів, перейдіть до наступного кроку. + Якщо транспортний засіб може стабілізуватися протягом 2 коливань під кутом близько 20 градусів, перейдіть до наступного кроку. 5. Повторіть ті ж маніпуляції, але по осі поля. - Як вище, почніть з невеликих кутів і підтвердіть, що транспортний засіб може стабілізуватися самостійно протягом 2 коливань, перш ніж збільшувати нахил. + Як вище, почніть з невеликих кутів і підтвердіть, що транспортний засіб може стабілізуватися самостійно протягом 2 коливань, перш ніж збільшувати нахил. If the drone can stabilize itself within 2 oscillations it is ready for the [auto-tuning procedure](#auto-tuning-procedure). @@ -72,41 +72,41 @@ The RC sticks cannot be used during autotuning (moving the sticks will stop the 1. Perform the [pre-tuning test](#pre-tuning-test). 2. Takeoff using RC control
in [Altitude mode](../flight_modes_mc/altitude.md). - Hover the vehicle at a safe distance and at a few meters above ground (between 4 and 20m).
- Once flying at cruise speed, activate [Hold mode](../flight_modes_fw/hold.md). - This will guide the plane to fly in circle at constant altitude and speed.
+ Hover the vehicle at a safe distance and at a few meters above ground (between 4 and 20m).
+ Once flying at cruise speed, activate [Hold mode](../flight_modes_fw/hold.md). + This will guide the plane to fly in circle at constant altitude and speed.
3. Enable autotune. -
-

TIP

+
+

TIP

- If an [Enable/Disable Autotune Switch](#enable-disable-autotune-switch) is configured you can just toggle the switch to the "enabled" position. + If an [Enable/Disable Autotune Switch](#enable-disable-autotune-switch) is configured you can just toggle the switch to the "enabled" position. -
+
- 1. In QGroundControl, open the menu **Vehicle setup > PID Tuning**: + 1. In QGroundControl, open the menu **Vehicle setup > PID Tuning**: - ![Tuning Setup > Autotune Enabled](../../assets/qgc/setup/autotune/autotune.png) + ![Tuning Setup > Autotune Enabled](../../assets/qgc/setup/autotune/autotune.png) - 2. Select either the _Rate Controller_ or _Attitude Controller_ tabs. + 2. Select either the _Rate Controller_ or _Attitude Controller_ tabs. - 3. Ensure that the **Autotune enabled** button is enabled (this will display the **Autotune** button and remove the manual tuning selectors). + 3. Ensure that the **Autotune enabled** button is enabled (this will display the **Autotune** button and remove the manual tuning selectors). - 4. Read the warning popup and click on **OK** to start tuning. + 4. Read the warning popup and click on **OK** to start tuning. 4. Дрон спочатку почне виконувати швидкі рухи кочення, а потім рухи тангажу та рухи курсу. - The progress is shown in the progress bar, next to the _Autotune_ button. + The progress is shown in the progress bar, next to the _Autotune_ button.
5. Manually land and disarm to apply the new tuning parameters. - Takeoff carefully and manually test that the vehicle is stable. + Takeoff carefully and manually test that the vehicle is stable.
5. The tuning will be immediately/automatically be applied and tested in flight (by default). - PX4 will then run a 4 second test and revert the new tuning if a problem is detected. + PX4 will then run a 4 second test and revert the new tuning if a problem is detected.
diff --git a/docs/uk/config/actuators.md b/docs/uk/config/actuators.md index c11af3c04d..6bacb04fe6 100644 --- a/docs/uk/config/actuators.md +++ b/docs/uk/config/actuators.md @@ -448,9 +448,9 @@ QGC потім автоматично обере наступний двигун 4. One motor will start spinning (click **Spin Motor Again** if it stops spinning too quickly to note.) - Виберіть відповідний двигун в розділі геометрії. + Виберіть відповідний двигун в розділі геометрії. - ![Screenshot showing how to identify/assign motors](../../assets/config/actuators/identify_motors_in_progress.png) + ![Screenshot showing how to identify/assign motors](../../assets/config/actuators/identify_motors_in_progress.png) 5. Після призначення всіх двигунів інструмент встановить правильне відображення двигунів для виходів, а потім вийде. @@ -467,15 +467,15 @@ Actuator outputs for both motors and servos can be _manually_ assigned using sli 1. First assign functions to the outputs that you think are _likely_ to be correct in the _Actuator Outputs_ section. 2. Toggle the **Enable sliders** switch in _Actuator Testing_ section. 3. Перемістіть повзунок для приводу, який ви хочете перевірити: - - Двигуни повинні бути переведені в положення мінімального тяги. - - Сервоприводи повинні бути переміщені близько до середнього положення. + - Двигуни повинні бути переведені в положення мінімального тяги. + - Сервоприводи повинні бути переміщені близько до середнього положення. 4. Перевірте, який привод рухається на транспортному засобі. - This should match the actuator positions for your geometry (the [airframe reference](../airframes/airframe_reference.md) shows motor positions for a number of standard airframes). - - Якщо правильний привод рухається, перейдіть до наступного кроку. - - Якщо неправильний привод рухається, поміняйте призначення виводу. - - Якщо нічого не рухається, то збільште регулятор наполовину діапазону, потім вище, якщо потрібно. - Якщо після цього нічого не рухається, вихід може бути не підключений, можливо, двигун не живиться або вихід може бути неправильно налаштований. - Вам потрібно буде вирішити проблему (можливо, спробуйте інші виходи виконавчих пристроїв, щоб побачити, чи "щось" рухається). + This should match the actuator positions for your geometry (the [airframe reference](../airframes/airframe_reference.md) shows motor positions for a number of standard airframes). + - Якщо правильний привод рухається, перейдіть до наступного кроку. + - Якщо неправильний привод рухається, поміняйте призначення виводу. + - Якщо нічого не рухається, то збільште регулятор наполовину діапазону, потім вище, якщо потрібно. + Якщо після цього нічого не рухається, вихід може бути не підключений, можливо, двигун не живиться або вихід може бути неправильно налаштований. + Вам потрібно буде вирішити проблему (можливо, спробуйте інші виходи виконавчих пристроїв, щоб побачити, чи "щось" рухається). 5. Поверніть слайдер у положення "роззброєно" (донизу для двигунів, по центру для сервоприводів). 6. Повторити для всіх приводів @@ -501,32 +501,32 @@ Remove propellers! Для кожного двигуна: 1. Тягніть слайдер мотора вниз, щоб він защелкнувся унизу. - In this position the motor is set to the outputs `disarmed` value. - - Перевірте, що двигун не обертається в цьому положенні. - - If the motor spins, reduce the corresponding PWM `disarmed` value in the [Actuator Outputs](#actuator-outputs) section to below the level at which it still spins. + In this position the motor is set to the outputs `disarmed` value. + - Перевірте, що двигун не обертається в цьому положенні. + - If the motor spins, reduce the corresponding PWM `disarmed` value in the [Actuator Outputs](#actuator-outputs) section to below the level at which it still spins. 2. Slowly move the slider up until it snaps to the _minimum_ position. - In this position the motor is set to the outputs `minimum` value. - - Перевірте, чи двигун обертається дуже повільно в цьому положенні. - - If the motor is not spinning, or spinning too fast you will need to adjust the corresponding PWM `minimum` value in the [Actuator Outputs](#actuator-outputs) such that the motors barely spin. + In this position the motor is set to the outputs `minimum` value. + - Перевірте, чи двигун обертається дуже повільно в цьому положенні. + - If the motor is not spinning, or spinning too fast you will need to adjust the corresponding PWM `minimum` value in the [Actuator Outputs](#actuator-outputs) such that the motors barely spin. - ![PWM Minimum Output](../../assets/config/actuators/pwm_minimum_output.png) - ::: info - For DShot output, this is not required. + ![PWM Minimum Output](../../assets/config/actuators/pwm_minimum_output.png) + ::: info + For DShot output, this is not required. ::: 3. Збільште значення слайдера до рівня, на якому ви можете перевірити, що двигун обертається в правильному напрямку і що він надасть позитивний тяговий потік в очікуваному напрямку. - - Очікувана напрямок тяги може відрізнятися в залежності від типу транспортного засобу. - Наприклад, у багатороторних літаках тяга завжди повинна вказувати вгору, тоді як у повітряному судні з фіксованим крилом тяга буде тягти судно вперед. - - For VTOL, thrust should point upwards when the Tilt Servo is at 0 degrees as defined the [Tilt Servo Convention](#tilt-servo-coordinate-system). - Testing of the [Tilt Servo](#tilt-servo-setup) is covered below as well. - - If thrust is in the wrong direction, you may need to [reverse the motors](#reversing-motors). + - Очікувана напрямок тяги може відрізнятися в залежності від типу транспортного засобу. + Наприклад, у багатороторних літаках тяга завжди повинна вказувати вгору, тоді як у повітряному судні з фіксованим крилом тяга буде тягти судно вперед. + - For VTOL, thrust should point upwards when the Tilt Servo is at 0 degrees as defined the [Tilt Servo Convention](#tilt-servo-coordinate-system). + Testing of the [Tilt Servo](#tilt-servo-setup) is covered below as well. + - If thrust is in the wrong direction, you may need to [reverse the motors](#reversing-motors). 4. Збільште значення слайдера до максимального значення, щоб двигун швидко обертався. - Reduce the value of the PWM output's `maximum` value just below the default. - Прослухайте тон моторів, коли ви збільшуєте значення малими (25us) інкрементами. - "Оптимальне" максимальне значення - це значення, при якому ви востаннє почули зміну тона. + Reduce the value of the PWM output's `maximum` value just below the default. + Прослухайте тон моторів, коли ви збільшуєте значення малими (25us) інкрементами. + "Оптимальне" максимальне значення - це значення, при якому ви востаннє почули зміну тона. ### Налаштування поверхонь керування @@ -549,33 +549,33 @@ Control surfaces that move either direction around a neutral point include: aile To set these up: 1. Set the `Disarmed` value so that the surfaces will stay at neutral position when disarmed. - This is usually around `1500` for PWM servos (near the centre of the servo range). + This is usually around `1500` for PWM servos (near the centre of the servo range). - ![Control Surface Disarmed 1500 Setting](../../assets/config/actuators/control_surface_aileron_setup.png) + ![Control Surface Disarmed 1500 Setting](../../assets/config/actuators/control_surface_aileron_setup.png) 2. Move the slider for the surface upwards (positive command) and verify that it moves in the direction defined in the [Control Surface Convention](#control-surface-deflection-convention). - - Ailerons, elevons, V-Tails, A-Tails, and other horizontal surfaces should move up. - - Rudders and other "purely vertical" surfaces should move right. + - Ailerons, elevons, V-Tails, A-Tails, and other horizontal surfaces should move up. + - Rudders and other "purely vertical" surfaces should move right. - ::: tip - It is important that the slider movement matches the control surface convention, in order to normalize control for different servo mountings (moving the slider up may actually decrease the output value sent to the servo). + ::: tip + It is important that the slider movement matches the control surface convention, in order to normalize control for different servo mountings (moving the slider up may actually decrease the output value sent to the servo). ::: - If the control surface moves in the opposite direction, click on the `Rev Range` checkbox to reverse the range. + If the control surface moves in the opposite direction, click on the `Rev Range` checkbox to reverse the range. 3. Move the slider again to the middle and check if the Control Surfaces are aligned in the neutral position of the wing. - - If it is not aligned, you can set the **Trim** value for the control surface. + - If it is not aligned, you can set the **Trim** value for the control surface. - ::: info - This is done in the `Trim` setting of the Geometry panel, usually by "trial and error". - ![Control Surface Trimming](../../assets/config/actuators/control_surface_trim.png) + ::: info + This is done in the `Trim` setting of the Geometry panel, usually by "trial and error". + ![Control Surface Trimming](../../assets/config/actuators/control_surface_trim.png) ::: - - After setting the trim for a control surface, move its slider away from the centre, release, and then back into disarmed (middle) position. - Підтвердіть, що поверхня знаходиться в нейтральному положенні. + - After setting the trim for a control surface, move its slider away from the centre, release, and then back into disarmed (middle) position. + Підтвердіть, що поверхня знаходиться в нейтральному положенні. :::info Another way to test without using the sliders would be to set the [`COM_PREARM_MODE`](../advanced_config/parameter_reference.md#COM_PREARM_MODE) parameter to `Always`: @@ -597,13 +597,13 @@ One approach for setting these up is: 1. Set values `Disarmed` to `1500`, `Min` to `1200`, `Max` to `1700` so that the values are around the centre of the servo range. 2. Move the corresponding slider up and check the control moves and that it is extending (moving away from the disarmed position). - If not, click on the `Rev Range` checkbox to reverse the range. + If not, click on the `Rev Range` checkbox to reverse the range. 3. Enable slider in the disarmed position, them change the value of the `Disarmed` signal until the control is retracted/flush with wing. - This may require that the `Disarmed` value is increased or decreased: - - If the value was decreased towards `Min`, then set `Min` to match `Disarmed`. - - If the value was increased towards `Max`, then set `Max` to match `Disarmed`. + This may require that the `Disarmed` value is increased or decreased: + - If the value was decreased towards `Min`, then set `Min` to match `Disarmed`. + - If the value was increased towards `Max`, then set `Max` to match `Disarmed`. 4. The value that you did _not_ set to match `Disarmed` controls the maximum amount that the control surface can extend. - Set the slider to the top of the control, then change the value (`Max` or `Min`) so that the control surface is fully extended when the slider is at top. + Set the slider to the top of the control, then change the value (`Max` or `Min`) so that the control surface is fully extended when the slider is at top. :::info Special note for flaps In some vehicle builds, flaps may be configured such that both flaps are controlled from a single output. @@ -627,7 +627,7 @@ First set the _frame rate_ for the servos used in each group of outputs. 2. Position the slider for the servo in the lowest position, and verify that a positive value increase will point towards the `Angle at Min Tilt` (defined in the Geometry section). - ![Tilt Servo Geometry Setup](../../assets/config/actuators/tilt_servo_geometry_config.png) + ![Tilt Servo Geometry Setup](../../assets/config/actuators/tilt_servo_geometry_config.png) 3. Position the slider for the servo in the highest position, and verify that positive motor thrust will point towards the `Angle at Max Tilt` (as defined in the Geometry section). diff --git a/docs/uk/config/airspeed.md b/docs/uk/config/airspeed.md index 270887595f..cca0eff115 100644 --- a/docs/uk/config/airspeed.md +++ b/docs/uk/config/airspeed.md @@ -27,18 +27,18 @@ Before calibration they must be [enabled via the corresponding parameter](../adv 4. Click the **Airspeed** sensor button. - ![Airspeed calibration](../../assets/qgc/setup/sensor/sensor_airspeed.jpg) + ![Airspeed calibration](../../assets/qgc/setup/sensor/sensor_airspeed.jpg) 5. Захистіть сенсор від вітру (тобто закрийте його рукою). - Пильнуйте, щоб не заблокувати жодного з отворів. + Пильнуйте, щоб не заблокувати жодного з отворів. 6. Click **OK** to start the calibration. 7. Після запиту, дмухніть у кінець труби пітота, щоб сигналізувати про завершення калібрування. - :::tip - Blowing into the tube is also a basic check that the dynamic and static ports are installed correctly. - Якщо вони будуть поміняні місцями, то датчик буде відображати великий від'ємний перепад тиску, коли ви дмухаєте в трубку, і калібрування завершиться з помилкою. + :::tip + Blowing into the tube is also a basic check that the dynamic and static ports are installed correctly. + Якщо вони будуть поміняні місцями, то датчик буде відображати великий від'ємний перепад тиску, коли ви дмухаєте в трубку, і калібрування завершиться з помилкою. ::: diff --git a/docs/uk/config/compass.md b/docs/uk/config/compass.md index 081febdeba..dbcf9f28f2 100644 --- a/docs/uk/config/compass.md +++ b/docs/uk/config/compass.md @@ -23,9 +23,9 @@ If any external magnetometers are available, it then disables the internal magne Several types of compass calibration are available: 1. [Complete](#complete-calibration): This calibration is required after installing the autopilot on an airframe for the first time or when the configuration of the vehicle has changed significantly. - Воно компенсує впливи твердого та м'якого заліза, оцінюючи зміщення та коефіцієнт масштабу для кожної вісі. + Воно компенсує впливи твердого та м'якого заліза, оцінюючи зміщення та коефіцієнт масштабу для кожної вісі. 2. [Partial](#partial-quick-calibration): This calibration can be performed as a routine when preparing the vehicle for a flight, after changing the payload, or simply when the compass rose seems inaccurate. - Цей тип калібрування лише оцінює зміщення для компенсації ефекту твердого заліза. + Цей тип калібрування лише оцінює зміщення для компенсації ефекту твердого заліза. 3. [Large vehicle](#large-vehicle-calibration): This calibration can be performed when the vehicle is too large or heavy to perform a complete calibration. Цей тип калібрування лише оцінює зміщення для компенсації ефекту твердого заліза. ## Виконання калібрування @@ -35,13 +35,13 @@ Several types of compass calibration are available: Перед початком калібрування: 1. Виберіть місце подалеку від великих металевих об'єктів або магнітних полів. - :::tip - Metal is not always obvious! Уникайте калібрування на верхній частині офісного столу (часто містять металеві пластины) або поруч з транспортним засобом. - Калібрування може бути навіть уражено, якщо ви стоїте на бетонній плиті з нерівномірним розподілом арматури. + :::tip + Metal is not always obvious! Уникайте калібрування на верхній частині офісного столу (часто містять металеві пластины) або поруч з транспортним засобом. + Калібрування може бути навіть уражено, якщо ви стоїте на бетонній плиті з нерівномірним розподілом арматури. ::: 2. Підключайтесь за допомогою телеметричного радіо, а не через USB, якщо це взагалі можливо. - USB потенційно може викликати значне магнітне втручання. + USB потенційно може викликати значне магнітне втручання. 3. If using an external compass (or a combined GPS/compass module), make sure it is [mounted](../assembly/mount_gps_compass.md) as far as possible from other electronics in order to reduce magnetic interference, and in a _supported orientation_. ### Повне калібрування @@ -54,10 +54,10 @@ Several types of compass calibration are available: 3. Click the **Compass** sensor button. - ![Select Compass calibration PX4](../../assets/qgc/setup/sensor/sensor_compass_select_px4.png) + ![Select Compass calibration PX4](../../assets/qgc/setup/sensor/sensor_compass_select_px4.png) - ::: info - You should already have set the [Autopilot Orientation](../config/flight_controller_orientation.md). Якщо ні, ви також можете встановити це тут. + ::: info + You should already have set the [Autopilot Orientation](../config/flight_controller_orientation.md). Якщо ні, ви також можете встановити це тут. ::: @@ -65,7 +65,7 @@ Several types of compass calibration are available: 5. Розмістіть транспортний засіб у будь-якому з показаних червоних орієнтацій (неповний) та утримуйте його нерухомим. Після запиту (орієнтаційне зображення стає жовтим) обертайте транспортний засіб навколо вказаної вісі в одному або обох напрямках. Після завершення калібрування для поточного орієнтації пов'язане зображення на екрані стане зеленим. - ![Compass calibration steps on PX4](../../assets/qgc/setup/sensor/sensor_compass_calibrate_px4.png) + ![Compass calibration steps on PX4](../../assets/qgc/setup/sensor/sensor_compass_calibrate_px4.png) 6. Повторіть процес калібрування для всіх орієнтацій автомобіля. @@ -76,7 +76,7 @@ Once you've calibrated the vehicle in all the positions _QGroundControl_ will di Ця калібровка схожа на відому калібровку компасу у вигляді восьмірки, виконану на смартфоні: 1. Утримуйте транспортний засіб перед собою та випадковим чином виконуйте часткові обертання по всіх його осях. - 2-3 коливань на кут близько 30 градусів у кожному напрямку зазвичай достатньо. + 2-3 коливань на кут близько 30 градусів у кожному напрямку зазвичай достатньо. 2. Зачекайте, поки оцінка заголовку стабілізується, і перевірте, що компас вказує в правильному напрямку (це може зайняти кілька секунд). Примітки: @@ -94,12 +94,12 @@ This calibration process leverages external knowledge of vehicle's orientation a 1. Ensure GNSS Fix. This is required to find the expected Earth magnetic field in WMM tables. 2. Align the vehicle to face True North. - Be as accurate as possible for best results. + Be as accurate as possible for best results. 3. Open the [QGroundControl MAVLink Console](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/analyze_view/mavlink_console.html) and send the following command: - ```sh - commander calibrate mag quick - ``` + ```sh + commander calibrate mag quick + ``` Примітки: diff --git a/docs/uk/config/firmware.md b/docs/uk/config/firmware.md index 3eb6f56b85..bd2f64af2f 100644 --- a/docs/uk/config/firmware.md +++ b/docs/uk/config/firmware.md @@ -61,10 +61,10 @@ Next you will need to specify the [vehicle airframe](../config/airframe.md) (and 2. Check **Advanced settings** and select the version from the dropdown list: - **Standard Version (stable):** The default version (i.e. no need to use advanced settings to install this!) - **Beta Testing (beta):** A beta/candidate release. - Лише доступно, коли готується новий реліз. + Лише доступно, коли готується новий реліз. - **Developer Build (master):** The latest build of PX4/PX4-Autopilot _main_ branch. - **Custom Firmware file...:** A custom firmware file (e.g. [that you have built locally](../dev_setup/building_px4.md)). - Якщо ви виберете це, вам доведеться вибрати власну прошивку з файлової системи на наступному кроці. + Якщо ви виберете це, вам доведеться вибрати власну прошивку з файлової системи на наступному кроці. Оновлення прошивки потім продовжується, як і раніше. diff --git a/docs/uk/config/flight_mode.md b/docs/uk/config/flight_mode.md index 3960ed8133..4b8f9d0d42 100644 --- a/docs/uk/config/flight_mode.md +++ b/docs/uk/config/flight_mode.md @@ -40,24 +40,24 @@ PX4 дозволяє вам вказати канал "режиму" та виб 3. Select **"Q" icon > Vehicle Setup > Flight Modes** (sidebar) to open _Flight Modes Setup_. - ![Flight modes single-channel](../../assets/qgc/setup/flight_modes/flight_modes_single_channel.jpg) + ![Flight modes single-channel](../../assets/qgc/setup/flight_modes/flight_modes_single_channel.jpg) 4. Specify _Flight Mode Settings_: - - Select the **Mode channel** (above this shown as Channel 5, but this will depend on your transmitter configuration). - - Перемістіть перемикач передавача (або перемикачі), які ви налаштували для вибору режиму, через доступні позиції. - The mode slot matching your current switch position will be highlighted (above this is _Flight Mode 1_). - ::: info - While you can set flight modes in any of the 6 slots, only the channels that are mapped to switch positions will be highlighted/used. + - Select the **Mode channel** (above this shown as Channel 5, but this will depend on your transmitter configuration). + - Перемістіть перемикач передавача (або перемикачі), які ви налаштували для вибору режиму, через доступні позиції. + The mode slot matching your current switch position will be highlighted (above this is _Flight Mode 1_). + ::: info + While you can set flight modes in any of the 6 slots, only the channels that are mapped to switch positions will be highlighted/used. ::: - - Виберіть режим польоту, який ви хочете активувати для кожного положення перемикача. + - Виберіть режим польоту, який ви хочете активувати для кожного положення перемикача. 5. Specify _Switch Settings_: - - Select the channels that you want to map to specific actions - e.g.: _Return_ mode, _Kill switch_, _offboard_ mode, etc. (if you have spare switches and channels on your transmitter). + - Select the channels that you want to map to specific actions - e.g.: _Return_ mode, _Kill switch_, _offboard_ mode, etc. (if you have spare switches and channels on your transmitter). 6. Перевірте, що режими відображаються на правильні перемикачі передавача: - - Check the _Channel Monitor_ to confirm that the expected channel is changed by each switch. - - Select each mode switch on your transmitter in turn, and check that the desired flight mode is activated (the text turns yellow on _QGroundControl_ for the active mode). + - Check the _Channel Monitor_ to confirm that the expected channel is changed by each switch. + - Select each mode switch on your transmitter in turn, and check that the desired flight mode is activated (the text turns yellow on _QGroundControl_ for the active mode). Усі значення автоматично зберігаються після зміни. diff --git a/docs/uk/config/safety.md b/docs/uk/config/safety.md index 82b5b8e57c..850b7ab348 100644 --- a/docs/uk/config/safety.md +++ b/docs/uk/config/safety.md @@ -204,23 +204,13 @@ The relevant parameters shown below. ### Position Loss Failsafe Action -The failure action is controlled by [COM_POSCTL_NAVL](../advanced_config/parameter_reference.md#COM_POSCTL_NAVL), based on whether RC control is assumed to be available (and altitude information): - -- `0`: Remote control available. - Switch to _Altitude mode_ if a height estimate is available, otherwise _Stabilized mode_. -- `1`: Remote control _not_ available. - Switch to _Descend mode_ if a height estimate is available, otherwise enter flight termination. - _Descend mode_ is a landing mode that does not require a position estimate. +Multicopters will switch to [Altitude mode](../flight_modes_mc/altitude.md) if a height estimate is available, otherwise [Stabilized mode](../flight_modes_mc/manual_stabilized.md). Fixed-wing planes, and VTOLs not configured to land in hover ([NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT)), have a parameter ([FW_GPSF_LT](../advanced_config/parameter_reference.md#FW_GPSF_LT)) that defines how long they will loiter (circle with a constant roll angle ([FW_GPSF_R](../advanced_config/parameter_reference.md#FW_GPSF_R)) at the current altitude) after losing position before attempting to land. If VTOLs have are configured to switch to hover for landing ([NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT)) then they will first transition and then descend. Відповідні параметри для всіх транспортних засобів наведено нижче. -| Параметр | Опис | -| -------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [COM_POSCTL_NAVL](../advanced_config/parameter_reference.md#COM_POSCTL_NAVL) | Position control navigation loss response during mission. Values: `0` - assume use of RC, `1` - Assume no RC. | - Параметри, які впливають лише на повітряні судна з фіксованим крилом: | Параметр | Опис | diff --git a/docs/uk/config/safety_simulation.md b/docs/uk/config/safety_simulation.md index a58fe0928d..8905bb3f2c 100644 --- a/docs/uk/config/safety_simulation.md +++ b/docs/uk/config/safety_simulation.md @@ -14,7 +14,7 @@ Note that any delayed action (`COM_FAIL_ACT_T`) will also be delayed in the simu 2. Встановіть тип транспортного засобу 3. Set the other values in the **State** or any of the flags under **Conditions** - The **Intended Mode** corresponds to the commanded mode via RC or GCS (or external script). - Станова машина аварійного відновлення може перевизначити це у разі аварійного відновлення. + Станова машина аварійного відновлення може перевизначити це у разі аварійного відновлення. 4. Check the action under **Output** 5. Check what happens when changing mode or **Move the RC sticks** 6. Грайте з різними налаштуваннями та умовами! diff --git a/docs/uk/config_fw/trimming_guide_fixedwing.md b/docs/uk/config_fw/trimming_guide_fixedwing.md index bb46d70b28..89da7f115f 100644 --- a/docs/uk/config_fw/trimming_guide_fixedwing.md +++ b/docs/uk/config_fw/trimming_guide_fixedwing.md @@ -29,10 +29,10 @@ The [Advanced Trimming](#advanced-trimming) section introduces parameters that c 1. Trim the servos by physically adjusting the linkages lengths if possible and fine tune by trimming the PWM channels (use `PWM_MAIN/AUX_TRIMx`) on the bench to properly set the control surfaces to their theoretical position. 2. Fly in stabilized mode at cruise speed and set the pitch setpoint offset (`FW_PSP_OFF`) to desired angle of attack. - Необхідний кут атаки при крейсерській швидкості відповідає куту крена, який потрібно літаку летіти, щоб утримати постійну висоту під час польоту з вирівняним крилом. - If you are using an airspeed sensor, also set the correct cruise airspeed (`FW_AIRSPD_TRIM`). + Необхідний кут атаки при крейсерській швидкості відповідає куту крена, який потрібно літаку летіти, щоб утримати постійну висоту під час польоту з вирівняним крилом. + If you are using an airspeed sensor, also set the correct cruise airspeed (`FW_AIRSPD_TRIM`). 3. Look at the actuator controls in the log file (upload it to [Flight Review](https://logs.px4.io) and check the _Actuator Controls_ plot for example) and set the pitch trim (`TRIM_PITCH`). - Встановіть це значення на середнє зміщення сигналу тану під час польоту на рівні крила. + Встановіть це значення на середнє зміщення сигналу тану під час польоту на рівні крила. Крок 3 можна виконати перед кроком 2, якщо ви не хочете дивитися на журнал або якщо вам зручно керувати літаком вручну. You can then trim your remote (with the trim switches) and report the values to `TRIM_PITCH` (and remove the trims from your transmitter) or update `TRIM_PITCH` directly during flight via telemetry and QGC. diff --git a/docs/uk/config_heli/index.md b/docs/uk/config_heli/index.md index b61169f631..f98522d729 100644 --- a/docs/uk/config_heli/index.md +++ b/docs/uk/config_heli/index.md @@ -53,15 +53,15 @@ This section contains topics related to [helicopter](../frames_helicopter/index. Для кожного набору сервоприводів: - `Angle`: Clockwise angle in degree on the swash plate circle at which the servo arm is attached starting from `0` pointing forwards. - Приклад для типової настройки, де три сервопривода керують планкою рівномірно розподіленою по колу (360° / 3 =) по 120° кожен, що призводить до наступних кутів: + Приклад для типової настройки, де три сервопривода керують планкою рівномірно розподіленою по колу (360° / 3 =) по 120° кожен, що призводить до наступних кутів: - | # | Кут | - | ------- | ---- | - | Servo 1 | 60° | - | Servo 2 | 180° | - | Servo 3 | 300° | + | # | Кут | + | ------- | ---- | + | Servo 1 | 60° | + | Servo 2 | 180° | + | Servo 3 | 300° | - warning and requirement + warning and requirement - `Arm Length (relative to each other)`: Radius from the swash plate center (top view). Коротше плече означає, що та ж сама рух сервопривода зміщує плиту більше. Це дозволяє отримати компенсацію автопілоту. @@ -72,7 +72,7 @@ This section contains topics related to [helicopter](../frames_helicopter/index. - `Yaw compensation scale based on collective pitch`: How much yaw is feed forward compensated based on the current collective pitch. - `Main rotor turns counter-clockwise`: `Disabled` (clockwise rotation) | `Enabled` - `Throttle spoolup time`: Set value (in seconds) greater than the achievable minimum motor spool up time. - Більше значення може поліпшити зручність користувача. + Більше значення може поліпшити зручність користувача. 3. Видаліть лопаті ротора та пропелери diff --git a/docs/uk/config_mc/filter_tuning.md b/docs/uk/config_mc/filter_tuning.md index 716a307a0f..8bfb92fd79 100644 --- a/docs/uk/config_mc/filter_tuning.md +++ b/docs/uk/config_mc/filter_tuning.md @@ -166,11 +166,11 @@ In this case you might use the settings: [IMU_GYRO_NF0_FRQ=32](../advanced_confi ## Додаткові поради 1. Прийнятна затримка залежить від розміру транспортного засобу та очікувань. - FPV racers typically tune for the absolute minimal latency (as a ballpark `IMU_GYRO_CUTOFF` around 120, `IMU_DGYRO_CUTOFF` of 50 to 80). - For bigger vehicles latency is less critical and `IMU_GYRO_CUTOFF` of around 80 might be acceptable. + FPV racers typically tune for the absolute minimal latency (as a ballpark `IMU_GYRO_CUTOFF` around 120, `IMU_DGYRO_CUTOFF` of 50 to 80). + For bigger vehicles latency is less critical and `IMU_GYRO_CUTOFF` of around 80 might be acceptable. 2. You can start tuning at higher `IMU_GYRO_CUTOFF` values (e.g. 100Hz), which might be desirable because the default tuning of `IMU_GYRO_CUTOFF` is set very low (30Hz). - Однак вам потрібно бути обізнаними з ризиками: - - Не літайте більше 20-30 секунд - - Перевірте, що двигуни не нагріваються занадто сильно - - Слухайте дивні звуки та симптоми надмірного шуму, як обговорено вище. + Однак вам потрібно бути обізнаними з ризиками: + - Не літайте більше 20-30 секунд + - Перевірте, що двигуни не нагріваються занадто сильно + - Слухайте дивні звуки та симптоми надмірного шуму, як обговорено вище. diff --git a/docs/uk/config_mc/pid_tuning_guide_multicopter_basic.md b/docs/uk/config_mc/pid_tuning_guide_multicopter_basic.md index 93fe689ca8..4ccd6f0e3e 100644 --- a/docs/uk/config_mc/pid_tuning_guide_multicopter_basic.md +++ b/docs/uk/config_mc/pid_tuning_guide_multicopter_basic.md @@ -72,7 +72,7 @@ Make sure to have assigned a [Kill switch](../config/safety.md#emergency-switche 1. Arm the vehicle, takeoff, and hover (typically in [Position mode](../flight_modes_mc/position.md)). 2. Open _QGroundControl_ **Vehicle Setup > PID Tuning** - ![QGC Rate Controller Tuning UI](../../assets/mc_pid_tuning/qgc_mc_pid_tuning_rate_controller.png) + ![QGC Rate Controller Tuning UI](../../assets/mc_pid_tuning/qgc_mc_pid_tuning_rate_controller.png) 3. Select the **Rate Controller** tab. @@ -80,60 +80,60 @@ Make sure to have assigned a [Kill switch](../config/safety.md#emergency-switche 5. Set the _Thrust curve_ value to: 0.3 (PWM, power-based controllers) or 1 (RPM-based ESCs) - ::: info - For PWM, power-based and (some) UAVCAN speed controllers, the control signal to thrust relationship may not be linear. - Як результат, оптимальне налаштування при потужності утримання може бути не ідеальним, коли транспортний засіб працює на вищій потужності. + ::: info + For PWM, power-based and (some) UAVCAN speed controllers, the control signal to thrust relationship may not be linear. + Як результат, оптимальне налаштування при потужності утримання може бути не ідеальним, коли транспортний засіб працює на вищій потужності. - Значення кривої тяги може бути використане для компенсації цієї нелинійності: + Значення кривої тяги може бути використане для компенсації цієї нелинійності: - - For PWM controllers, 0.3 is a good default (which may benefit from [further tuning](../config_mc/pid_tuning_guide_multicopter.md#thrust-curve)). - - Для контролерів на основі RPM використовуйте 1 (додаткове налаштування не потрібно, оскільки вони мають квадратичну криву тяги). + - For PWM controllers, 0.3 is a good default (which may benefit from [further tuning](../config_mc/pid_tuning_guide_multicopter.md#thrust-curve)). + - Для контролерів на основі RPM використовуйте 1 (додаткове налаштування не потрібно, оскільки вони мають квадратичну криву тяги). - For more information see the [detailed PID tuning guide](../config_mc/pid_tuning_guide_multicopter.md#thrust-curve). + For more information see the [detailed PID tuning guide](../config_mc/pid_tuning_guide_multicopter.md#thrust-curve). ::: 6. Set the _Select Tuning_ radio button to: **Roll**. 7. (Optionally) Select the **Automatic Flight Mode Switching** checkbox. - This will _automatically_ switch from [Position mode](../flight_modes_mc/position.md) to [Stabilised mode](../flight_modes_mc/manual_stabilized.md) when you press the **Start** button + This will _automatically_ switch from [Position mode](../flight_modes_mc/position.md) to [Stabilised mode](../flight_modes_mc/manual_stabilized.md) when you press the **Start** button 8. For rate controller tuning switch to _Acro mode_, _Stabilized mode_ or _Altitude mode_ (unless automatic switching is enabled). 9. Select the **Start** button in order to start tracking the setpoint and response curves. 10. Rapidly move the _roll stick_ full range and observe the step response on the plots. - :::tip - Stop tracking to enable easier inspection of the plots. - Це відбувається автоматично, коли ви збільшуєте/панорамуєте. - Use the **Start** button to restart the plots, and **Clear** to reset them. + :::tip + Stop tracking to enable easier inspection of the plots. + Це відбувається автоматично, коли ви збільшуєте/панорамуєте. + Use the **Start** button to restart the plots, and **Clear** to reset them. ::: 11. Modify the three PID values using the sliders (for roll rate-tuning these affect `MC_ROLLRATE_K`, `MC_ROLLRATE_I`, `MC_ROLLRATE_D`) and observe the step response again. - Значення зберігаються на транспортний засіб, як тільки переміщуються слайдери. - ::: info - The goal is for the _Response_ curve to match the _Setpoint_ curve as closely as possible (i.e. a fast response without overshoots). + Значення зберігаються на транспортний засіб, як тільки переміщуються слайдери. + ::: info + The goal is for the _Response_ curve to match the _Setpoint_ curve as closely as possible (i.e. a fast response without overshoots). ::: - The PID values can be adjusted as follows: - - P (пропорційне) або К підсилення: - - збільште це для більшої реакції - - зменшити, якщо відповідь перевищує і / або коливається (до певної міри збільшення значення D також допомагає). - - D (похідне) надходження: - - це можна збільшити, щоб заглушити перевищення та коливання - - збільшуйте це лише настільки, наскільки це потрібно, оскільки це підсилює шум (і може призвести до нагрітих моторів) - - I (інтегральний) коефіцієнт отримання: - - використовується для зменшення поміченої похибки стану рівноваги - - якщо значення занадто низьке, відповідь може ніколи не досягти заданої точки (наприклад, у вітрових умовах) - - якщо занадто високий, можуть виникнути повільні коливання + The PID values can be adjusted as follows: + - P (пропорційне) або К підсилення: + - збільште це для більшої реакції + - зменшити, якщо відповідь перевищує і / або коливається (до певної міри збільшення значення D також допомагає). + - D (похідне) надходження: + - це можна збільшити, щоб заглушити перевищення та коливання + - збільшуйте це лише настільки, наскільки це потрібно, оскільки це підсилює шум (і може призвести до нагрітих моторів) + - I (інтегральний) коефіцієнт отримання: + - використовується для зменшення поміченої похибки стану рівноваги + - якщо значення занадто низьке, відповідь може ніколи не досягти заданої точки (наприклад, у вітрових умовах) + - якщо занадто високий, можуть виникнути повільні коливання 12. Повторіть процес налаштування вище для крена та курсу: - - Use _Select Tuning_ radio button to select the axis to tune - - Перемістіть відповідні палички (тобто паличку крена для крена, паличку риштування для риштування). - - Для налаштування крену почніть з тих самих значень, що й для крену. - :::tip - Use the **Save to Clipboard** and **Reset from Clipboard** buttons to copy the roll settings for initial pitch settings. + - Use _Select Tuning_ radio button to select the axis to tune + - Перемістіть відповідні палички (тобто паличку крена для крена, паличку риштування для риштування). + - Для налаштування крену почніть з тих самих значень, що й для крену. + :::tip + Use the **Save to Clipboard** and **Reset from Clipboard** buttons to copy the roll settings for initial pitch settings. ::: @@ -141,10 +141,10 @@ Make sure to have assigned a [Kill switch](../config/safety.md#emergency-switche 14. Повторіть процес налаштування контролерів швидкості та позицій (на всіх осях). - - Використовуйте режим позиції при налаштуванні цих контролерів - - Select the **Simple position control** option in the _Position control mode ..._ selector (this allows direct control for the generation of step inputs) + - Використовуйте режим позиції при налаштуванні цих контролерів + - Select the **Simple position control** option in the _Position control mode ..._ selector (this allows direct control for the generation of step inputs) - ![QGC PID tuning: Simple control selector](../../assets/mc_pid_tuning/qgc_mc_pid_tuning_simple_control.png) + ![QGC PID tuning: Simple control selector](../../assets/mc_pid_tuning/qgc_mc_pid_tuning_simple_control.png) Готово! Пам'ятайте увімкнути повітряний режим перед виходом з налаштувань. diff --git a/docs/uk/config_rover/basic_setup.md b/docs/uk/config_rover/basic_setup.md index a5fc9f1987..73340127eb 100644 --- a/docs/uk/config_rover/basic_setup.md +++ b/docs/uk/config_rover/basic_setup.md @@ -84,7 +84,7 @@ Navigate to [Parameters](../advanced_config/parameters.md) in QGroundControl and 2. (Optional) [RO_ACCEL_LIM](#RO_ACCEL_LIM) [m/s^2]: Maximum acceleration you want to allow for your rover. - + :::tip Your rover has a maximum possible acceleration which is determined by the maximum torque the motor can supply. @@ -128,15 +128,15 @@ $$ with: - - $\delta \in [-1, 1]=$ Normalized steering setpoint. - - $x \in [-1, 1]=$ Normalized stick input. - - $f=$ [RO_YAW_EXPO](#RO_YAW_EXPO): `0` Purely linear input curve, `1` Purely cubic input curve. - - $g=$ [RO_YAW_SUPEXPO](#RO_YAW_SUPEXPO): `0` Pure Expo function, `0.7` reasonable shape enhancement for intuitive stick feel, `0.95` very strong bent input curve only near maxima have effect. +- $\delta \in [-1, 1]=$ Normalized steering setpoint. +- $x \in [-1, 1]=$ Normalized stick input. +- $f=$ [RO_YAW_EXPO](#RO_YAW_EXPO): `0` Purely linear input curve, `1` Purely cubic input curve. +- $g=$ [RO_YAW_SUPEXPO](#RO_YAW_SUPEXPO): `0` Pure Expo function, `0.7` reasonable shape enhancement for intuitive stick feel, `0.95` very strong bent input curve only near maxima have effect. In [Manual mode](../flight_modes_rover/manual.md#manual-mode) we can additionally scale $\delta$ with an additional parameter $r$: - - Differential Rover: $r=$ [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN), which enables adjusting the slope of the input mapping. This leads to a normalized steering input $\hat{\delta} = \delta \cdot r \in$ [-[RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN), [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN)]. - - Mecanum Rover: $r=$ [RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN), which enables adjusting the slope of the input mapping. This leads to a normalized steering input $\hat{\delta} = \delta \cdot r \in$ [-[RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN), [RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN)]. +- Differential Rover: $r=$ [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN), which enables adjusting the slope of the input mapping. This leads to a normalized steering input $\hat{\delta} = \delta \cdot r \in$ [-[RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN), [RD_YAW_STK_GAIN](#RD_YAW_STK_GAIN)]. +- Mecanum Rover: $r=$ [RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN), which enables adjusting the slope of the input mapping. This leads to a normalized steering input $\hat{\delta} = \delta \cdot r \in$ [-[RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN), [RM_YAW_STK_GAIN](#RM_YAW_STK_GAIN)]. This scaling is useful to limit the normalized steering setpoint, if it is too aggresive for your rover in manual mode. diff --git a/docs/uk/config_rover/index.md b/docs/uk/config_rover/index.md index f085188225..82c7a91bf4 100644 --- a/docs/uk/config_rover/index.md +++ b/docs/uk/config_rover/index.md @@ -25,18 +25,18 @@ Rovers use a custom build that must be flashed onto your flight controller inste To build for rover with the `make` command, replace the `_default` suffix with `_rover`. For example, to build rover for px4_fmu-v6x boards, you would use the command: - ```sh - make px4_fmu-v6x_rover - ``` + ```sh + make px4_fmu-v6x_rover + ``` ::: info You can also enable the modules in default builds by adding these lines to your [board configuration](../hardware/porting_guide_config.md) (e.g. for fmu-v6x you might add them to [`main/boards/px4/fmu-v6x/default.px4board`](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/fmu-v6x/default.px4board)): - ```sh - CONFIG_MODULES_ROVER_ACKERMANN=y - CONFIG_MODULES_ROVER_DIFFERENTIAL=y - CONFIG_MODULES_ROVER_MECANUM=y - ``` + ```sh + CONFIG_MODULES_ROVER_ACKERMANN=y + CONFIG_MODULES_ROVER_DIFFERENTIAL=y + CONFIG_MODULES_ROVER_MECANUM=y + ``` Note that adding the rover modules may lead to flash overflow, in which case you will need to disable modules that you do not plan to use (such as those related to multicopter or fixed wing). diff --git a/docs/uk/config_rover/velocity_tuning.md b/docs/uk/config_rover/velocity_tuning.md index e171e07c34..5864698f4b 100644 --- a/docs/uk/config_rover/velocity_tuning.md +++ b/docs/uk/config_rover/velocity_tuning.md @@ -20,7 +20,7 @@ To tune the velocity controller configure the following [parameters](../advanced 2. [RO_MAX_THR_SPEED](#RO_MAX_THR_SPEED) [m/s]: This parameter is used to calculate the feed-forward term of the closed loop speed control which linearly maps desired speeds to normalized motor commands. As mentioned in the [Manual mode](../flight_modes_rover/manual.md#manual-mode) configuration , a good starting point is the observed ground speed when the rover drives at maximum throttle in [Manual mode](../flight_modes_rover/manual.md#manual-mode). - + ::: tip To further tune this parameter: diff --git a/docs/uk/config_vtol/vtol_quad_configuration.md b/docs/uk/config_vtol/vtol_quad_configuration.md index d089834fd1..0c8dc8c47a 100644 --- a/docs/uk/config_vtol/vtol_quad_configuration.md +++ b/docs/uk/config_vtol/vtol_quad_configuration.md @@ -11,7 +11,7 @@ For airframe specific documentation and build instructions see [VTOL Framebuilds 2. Flash the firmware for your current release or master (PX4 `main` branch build). 3. In the [Frame setup](../config/airframe.md) section select the appropriate VTOL airframe. - If your airframe is not listed select the [Generic Standard VTOL](../airframes/airframe_reference.md#vtol_standard_vtol_generic_standard_vtol) frame. + If your airframe is not listed select the [Generic Standard VTOL](../airframes/airframe_reference.md#vtol_standard_vtol_generic_standard_vtol) frame. ### Перемикач режимів польоту / переходу diff --git a/docs/uk/contribute/docs.md b/docs/uk/contribute/docs.md index 082b21ae0e..e4bd6005ec 100644 --- a/docs/uk/contribute/docs.md +++ b/docs/uk/contribute/docs.md @@ -63,33 +63,33 @@ If you already have a clone of the [PX4-Autopilot](https://github.com/PX4/PX4-Au 4. Клонуйте ваш форкнутий репозиторій на локальний комп'ютер: - ```sh - cd ~/wherever/ - git clone https://github.com//PX4-Autopilot.git - ``` + ```sh + cd ~/wherever/ + git clone https://github.com//PX4-Autopilot.git + ``` - For example, to clone PX4 source fork for a user with Github account "john_citizen": + For example, to clone PX4 source fork for a user with Github account "john_citizen": - ```sh - git clone https://github.com/john_citizen/PX4-Autopilot.git - ``` + ```sh + git clone https://github.com/john_citizen/PX4-Autopilot.git + ``` 5. Перейдіть до свого локального сховища: - ```sh - cd ~/wherever/PX4-Autopilot - ``` + ```sh + cd ~/wherever/PX4-Autopilot + ``` 6. Add a _remote_ called "upstream" to point to the "official" PX4 version of the library: - ```sh - git remote add upstream https://github.com/PX4/PX4-Autopilot.git - ``` + ```sh + git remote add upstream https://github.com/PX4/PX4-Autopilot.git + ``` - :::tip - A "remote" is a handle to a particular repository. - The remote named _origin_ is created by default when you clone the repository, and points to _your fork_ of the guide. - Above you create a new remote _upstream_ that points to the PX4 project version of the documents. + :::tip + A "remote" is a handle to a particular repository. + The remote named _origin_ is created by default when you clone the repository, and points to _your fork_ of the guide. + Above you create a new remote _upstream_ that points to the PX4 project version of the documents. ::: @@ -99,111 +99,111 @@ Within the repository you created above: 1. Bring your copy of the repository `main` branch up to date: - ```sh - git checkout main - git fetch upstream main - git pull upstream main - ``` + ```sh + git checkout main + git fetch upstream main + git pull upstream main + ``` 2. Create a new branch for your changes: - ```sh - git checkout -b - ``` + ```sh + git checkout -b + ``` - This creates a local branch on your computer named `your_feature_branch_name`. + This creates a local branch on your computer named `your_feature_branch_name`. 3. Внести зміни до документації за необхідною (загальний посібник по цьому в наступних розділах) 4. Коли ви будете задоволені своїми змінами, ви можете додати їх до вашої локальної гілки за допомогою "commit": - ```sh - git add - git commit -m "" - ``` + ```sh + git add + git commit -m "" + ``` - For a good commit message, please refer to the [Source Code Management](../contribute/code.md#commits-and-commit-messages) section. + For a good commit message, please refer to the [Source Code Management](../contribute/code.md#commits-and-commit-messages) section. 5. Натисніть "Push" вашу локальну гілку (включаючи додані до неї коміти) у вашу репозиторію-форк на Github. - ```sh - git push origin your_feature_branch_name - ``` + ```sh + git push origin your_feature_branch_name + ``` 6. Go to your forked repository on Github in a web browser, e.g.: `https://github.com//PX4-Autopilot.git`. - Там ви маєте побачити повідомлення, що нова гілка була відправлена у вашу репозиторію-форк. + Там ви маєте побачити повідомлення, що нова гілка була відправлена у вашу репозиторію-форк. 7. Створіть запит на витягнення (Pull Request, PR): - - On the right hand side of the "new branch message" (see one step before), you should see a green button saying "Compare & Create Pull Request". - Натисніть на неї. - - Буде створено шаблон запиту на витягнення. - Він буде перераховувати ваші коміти, і ви можете (маєте) додати значущий заголовок (у випадку одного коміту PR, це зазвичай повідомлення про коміт) та повідомлення (поясніть, що ви зробили і для якої причини. . - Check [other pull requests](https://github.com/PX4/PX4-Autopilot/pulls) for comparison). - - Add the "Documentation" label. + - On the right hand side of the "new branch message" (see one step before), you should see a green button saying "Compare & Create Pull Request". + Натисніть на неї. + - Буде створено шаблон запиту на витягнення. + Він буде перераховувати ваші коміти, і ви можете (маєте) додати значущий заголовок (у випадку одного коміту PR, це зазвичай повідомлення про коміт) та повідомлення (поясніть, що ви зробили і для якої причини. . + Check [other pull requests](https://github.com/PX4/PX4-Autopilot/pulls) for comparison). + - Add the "Documentation" label. 8. Готово! - Редактори PX4 User Guide зараз переглянуть вашу співпрацю і вирішать, чи хочуть вони інтегрувати її. - Періодично перевіряйте, чи є у них питання по вашим змінам. + Редактори PX4 User Guide зараз переглянуть вашу співпрацю і вирішать, чи хочуть вони інтегрувати її. + Періодично перевіряйте, чи є у них питання по вашим змінам. ### Побудова бібліотеки локально Побудуйте бібліотеку локально, щоб перевірити, що будь-які зміни, які ви внесли, відображені належним чином: 1. Install the [Vitepress prerequisites](https://vitepress.dev/guide/getting-started#prerequisites): - - [Nodejs 18+](https://nodejs.org/en) - - [Yarn classic](https://classic.yarnpkg.com/en/docs/install) + - [Nodejs 18+](https://nodejs.org/en) + - [Yarn classic](https://classic.yarnpkg.com/en/docs/install) 2. Navigate to your local repository and the `/docs` subdirectory: - ```sh - cd ~/wherever/PX4-Autopilot/docs - ``` + ```sh + cd ~/wherever/PX4-Autopilot/docs + ``` 3. Встановити залежності (включаючи Vuepress): - ```sh - yarn install - ``` + ```sh + yarn install + ``` 4. Попередній перегляд і обслуговування бібліотеки: - ```sh - yarn docs:dev - ``` + ```sh + yarn docs:dev + ``` - - Одного разу, коли сервер розробки / попереднього перегляду побудує бібліотеку (менше хвилини вперше), він покаже вам URL-адресу, за допомогою якої ви можете переглянути сайт. - This will be something like: `http://localhost:5173/px4_user_guide/`. - - Stop serving using **CTRL+C** in the terminal prompt. + - Одного разу, коли сервер розробки / попереднього перегляду побудує бібліотеку (менше хвилини вперше), він покаже вам URL-адресу, за допомогою якої ви можете переглянути сайт. + This will be something like: `http://localhost:5173/px4_user_guide/`. + - Stop serving using **CTRL+C** in the terminal prompt. 5. Open previewed pages in your local editor: - First specify a local text editor file using the `EDITOR` environment variable, before calling `yarn start` to preview the library. - For example, you can enable VSCode as your default editor by entering: + First specify a local text editor file using the `EDITOR` environment variable, before calling `yarn start` to preview the library. + For example, you can enable VSCode as your default editor by entering: - - Windows: + - Windows: - ```sh - set EDITOR=code - ``` + ```sh + set EDITOR=code + ``` - - Linux: + - Linux: - ```sh - export EDITOR=code - ``` + ```sh + export EDITOR=code + ``` - The **Open in your editor** link at the bottom of each page will then open the current page in the editor (this replaces the _Open in GitHub_ link). + The **Open in your editor** link at the bottom of each page will then open the current page in the editor (this replaces the _Open in GitHub_ link). 6. Побудуйте бібліотеку за допомогою: - ```sh - # Ubuntu - yarn docs:build + ```sh + # Ubuntu + yarn docs:build - # Windows - yarn docs:buildwin - ``` + # Windows + yarn docs:buildwin + ``` :::tip Use `yarn start` to preview changes _as you make them_ (documents are updated and served very quickly). @@ -256,38 +256,38 @@ When you add a new page you must also add it to `en/SUMMARY.md`! ## Інструкція зі стилістичного оформлення 1. Назви файлів/файлів - - Put new markdown files in an appropriate sub-folder of `/en/`, such as `/en/contribute/`. - Не створюйте додаткових вкладених папок. - - Put new image files in an appropriate nested sub-folder of `/assets/`. - Deeper nesting is allowed/encouraged. - - Use descriptive names for folders and files. - In particular, image filenames should describe what they contain (don't name as "image1.png") - - Use lower case filenames and separate words using underscores (`_`). + - Put new markdown files in an appropriate sub-folder of `/en/`, such as `/en/contribute/`. + Не створюйте додаткових вкладених папок. + - Put new image files in an appropriate nested sub-folder of `/assets/`. + Deeper nesting is allowed/encouraged. + - Use descriptive names for folders and files. + In particular, image filenames should describe what they contain (don't name as "image1.png") + - Use lower case filenames and separate words using underscores (`_`). 2. Зображення - - Використовуйте найменший розмір і найнижчу роздільну здатність, яка все ще робить зображення корисним (це зменшує вартість завантаження для користувачів із слабким інтернет-з'єднанням). - - New images should be created in a sub-folder of `/assets/` (so they can be shared between translations). - - SVG files are preferred for diagrams. - PNG files are preferred over JPG for screenshots. + - Використовуйте найменший розмір і найнижчу роздільну здатність, яка все ще робить зображення корисним (це зменшує вартість завантаження для користувачів із слабким інтернет-з'єднанням). + - New images should be created in a sub-folder of `/assets/` (so they can be shared between translations). + - SVG files are preferred for diagrams. + PNG files are preferred over JPG for screenshots. 3. Контент - - Use "style" (**bold**, _emphasis_, etc.) consistently and sparingly (as little as possible). - - **Bold** for button presses and menu definitions. - - _Emphasis_ for tool names such as _QGroundControl_ or _prettier_. - - `code` for file paths, and code, parameter names that aren't linked, using tools in a command line, such as `prettier`. - - Headings and page titles should use "First Letter Capitalisation". - - The page title should be a first level heading (`#`). - All other headings should be h2 (`##`) or lower. - - Не додавати ніяких стилів до заголовків. - - Don't translate the text indicating the name of an `info`, `tip` or `warning` declaration (e.g. `::: tip`) as this precise text is required to render the aside properly. - - Break lines on sentences by preference. - Don't break lines based on some arbitrary line length. - - Format using _prettier_ (_VSCode_ is a has extensions can be used for this). + - Use "style" (**bold**, _emphasis_, etc.) consistently and sparingly (as little as possible). + - **Bold** for button presses and menu definitions. + - _Emphasis_ for tool names such as _QGroundControl_ or _prettier_. + - `code` for file paths, and code, parameter names that aren't linked, using tools in a command line, such as `prettier`. + - Headings and page titles should use "First Letter Capitalisation". + - The page title should be a first level heading (`#`). + All other headings should be h2 (`##`) or lower. + - Не додавати ніяких стилів до заголовків. + - Don't translate the text indicating the name of an `info`, `tip` or `warning` declaration (e.g. `::: tip`) as this precise text is required to render the aside properly. + - Break lines on sentences by preference. + Don't break lines based on some arbitrary line length. + - Format using _prettier_ (_VSCode_ is a has extensions can be used for this). 4. Videos: - - Youtube videos can be added using the format `` (supported via the [https://www.npmjs.com/package/lite-youtube-embed](https://www.npmjs.com/package/lite-youtube-embed) custom element, which has other parameters you can pass). - - Use instructional videos sparingly as they date badly, and are hard to maintain. - - Cool videos of airframes in flight are always welcome. + - Youtube videos can be added using the format `` (supported via the [https://www.npmjs.com/package/lite-youtube-embed](https://www.npmjs.com/package/lite-youtube-embed) custom element, which has other parameters you can pass). + - Use instructional videos sparingly as they date badly, and are hard to maintain. + - Cool videos of airframes in flight are always welcome. ## Де я можу додати зміни? diff --git a/docs/uk/contribute/git_examples.md b/docs/uk/contribute/git_examples.md index 5fdd22d82f..37d211b180 100644 --- a/docs/uk/contribute/git_examples.md +++ b/docs/uk/contribute/git_examples.md @@ -109,23 +109,23 @@ We recommend using PX4 `make` commands to switch between source code branches. 1. Очистити поточну гілку, деініціалізувати підмодуль та видалити всі артефакти збірки: - ```sh - make clean - make distclean - ``` + ```sh + make clean + make distclean + ``` 2. Switch to a new branch or tag (here we first fetch the fictional branch "PR_test_branch" from the `upstream` remote): - ```sh - git fetch upstream PR_test_branch - git checkout PR_test_branch - ``` + ```sh + git fetch upstream PR_test_branch + git checkout PR_test_branch + ``` 3. Отримати підмодулі для нової гілки: - ```sh - make submodulesclean - ``` + ```sh + make submodulesclean + ``` @@ -138,35 +138,35 @@ To get the source code for a _specific older release_ (tag): 1. Clone the PX4-Autopilot repo and navigate into _PX4-Autopilot_ directory: - ```sh - git clone https://github.com/PX4/PX4-Autopilot.git - cd PX4-Autopilot - ``` + ```sh + git clone https://github.com/PX4/PX4-Autopilot.git + cd PX4-Autopilot + ``` - :::info + :::info - Ви можете повторно використовувати існуючий репозиторій, а не клонувати новий. - In this case clean the build environment (see [changing source trees](#changing-source-trees)): + Ви можете повторно використовувати існуючий репозиторій, а не клонувати новий. + In this case clean the build environment (see [changing source trees](#changing-source-trees)): - ```sh - make clean - make distclean - ``` + ```sh + make clean + make distclean + ``` ::: 2. Код оформлення замовлення для конкретного тегу (наприклад, для мітки v1.13.0-beta2) - ```sh - git checkout v1.13.0-beta2 - ``` + ```sh + git checkout v1.13.0-beta2 + ``` 3. Оновити підмодулі: - ```sh - make submodulesclean - ``` + ```sh + make submodulesclean + ``` ## Щоб отримати гілку релізу diff --git a/docs/uk/debug/eclipse_jlink.md b/docs/uk/debug/eclipse_jlink.md index 834c3f7954..060d2732a3 100644 --- a/docs/uk/debug/eclipse_jlink.md +++ b/docs/uk/debug/eclipse_jlink.md @@ -53,17 +53,17 @@ For more information, see: [https://gnu-mcu-eclipse.github.io/debug/jlink/instal 7. Пакети з оновленнями: - Click the small icon on the top right called _Open Perspective_ and open the _Packs_ perspective. - ![Eclipse: Workspace](../../assets/debug/eclipse_workspace_perspective.png) + ![Eclipse: Workspace](../../assets/debug/eclipse_workspace_perspective.png) - Click the **update all** button. - :::tip - This takes a VERY LONG TIME (10 minutes). - Ігноруйте всі помилки про відсутні пакети. + :::tip + This takes a VERY LONG TIME (10 minutes). + Ігноруйте всі помилки про відсутні пакети. ::: - ![Eclipse: Workspace Packs Perspective](../../assets/debug/eclipse_packs_perspective.jpg) + ![Eclipse: Workspace Packs Perspective](../../assets/debug/eclipse_packs_perspective.jpg) - The STM32Fxx devices are found in the Keil folder, install by right-clicking and then selecting **install** on the according device for F4 and F7. @@ -79,24 +79,24 @@ For more information, see: [https://gnu-mcu-eclipse.github.io/debug/jlink/instal ![Eclipse: Debug config](../../assets/debug/eclipse_settings_debug_config.png) 10. Then select _GDB SEGGER J-Link Debugging_ and then the **New config** button on the top left. - ![Eclipse: GDB Segger Debug config](../../assets/debug/eclipse_settings_debug_config_gdb_segger.png) + ![Eclipse: GDB Segger Debug config](../../assets/debug/eclipse_settings_debug_config_gdb_segger.png) 11. Налаштування конфігурації збірки: - - Give it a name and set the _C/C++ Application_ to the corresponding **.elf** file. - - Choose _Disable Auto build_ + - Give it a name and set the _C/C++ Application_ to the corresponding **.elf** file. + - Choose _Disable Auto build_ ::: info Remember that you must build the target from the command line before starting a debug session. ::: - ![Eclipse: GDB Segger Debug config](../../assets/debug/eclipse_settings_debug_config_gdb_segger_build_config.png) + ![Eclipse: GDB Segger Debug config](../../assets/debug/eclipse_settings_debug_config_gdb_segger_build_config.png) 12. The _Debugger_ and _Startup_ tabs shouldn’t need any modifications (just verify your settings with the screenshots below) - ![Eclipse: GDB Segger Debug config: debugger tab](../../assets/debug/eclipse_settings_debug_config_gdb_segger_build_config_debugger_tab.png) - ![Eclipse: GDB Segger Debug config: startup tab](../../assets/debug/eclipse_settings_debug_config_gdb_segger_build_config_startup_tab.png) + ![Eclipse: GDB Segger Debug config: debugger tab](../../assets/debug/eclipse_settings_debug_config_gdb_segger_build_config_debugger_tab.png) + ![Eclipse: GDB Segger Debug config: startup tab](../../assets/debug/eclipse_settings_debug_config_gdb_segger_build_config_startup_tab.png) ## Відлагодження з урахуванням завдань SEGGER @@ -109,16 +109,16 @@ Task-aware debugging (also known as [thread-aware debugging](https://www.segger. - Відкрийте термінал у кореневій теці вихідного коду PX4-Autopilot - In the terminal, open `menuconfig` using the appropriate make target for the build. - Це виглядатиме приблизно так: + Це виглядатиме приблизно так: - ```sh - make px4_fmu-v5_default boardguiconfig - ``` + ```sh + make px4_fmu-v5_default boardguiconfig + ``` - (See [PX4 Menuconfig Setup](../hardware/porting_guide_config.md#px4-menuconfig-setup) for more information) on using the config tools). + (See [PX4 Menuconfig Setup](../hardware/porting_guide_config.md#px4-menuconfig-setup) for more information) on using the config tools). - Ensure that the _Enable TCBinfo struct for debug_ is selected as shown: - ![NuttX: Menuconfig: CONFIG_DEBUG_TCBINFO](../../assets/debug/nuttx_tcb_task_aware.png) + ![NuttX: Menuconfig: CONFIG_DEBUG_TCBINFO](../../assets/debug/nuttx_tcb_task_aware.png) 2. Compile the **jlink-nuttx.so** library in the terminal by running the following command in the terminal: `make jlink-nuttx` diff --git a/docs/uk/debug/failure_injection.md b/docs/uk/debug/failure_injection.md index 2cfc45ccad..aaa939dc0c 100644 --- a/docs/uk/debug/failure_injection.md +++ b/docs/uk/debug/failure_injection.md @@ -68,13 +68,13 @@ failure [-i ] 1. Enable the parameter [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN). 2. Enter the following commands on the MAVLink console or SITL _pxh shell_: - ```sh - # Fail RC (turn publishing off) - failure rc_signal off + ```sh + # Fail RC (turn publishing off) + failure rc_signal off - # Restart RC publishing - failure rc_signal ok - ``` + # Restart RC publishing + failure rc_signal ok + ``` ## MAVSDK відлагоджувальний плагін diff --git a/docs/uk/dev_airframes/adding_a_new_frame.md b/docs/uk/dev_airframes/adding_a_new_frame.md index 5977914bb8..534f06bdc9 100644 --- a/docs/uk/dev_airframes/adding_a_new_frame.md +++ b/docs/uk/dev_airframes/adding_a_new_frame.md @@ -37,8 +37,8 @@ Alternatively you can just append the modified parameters to the startup configu Як додати конфігурацію до прошивки: 1. Create a new config file in the [init.d/airframes](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d/airframes) folder. - - Give it a short descriptive filename and prepend the filename with an unused autostart ID (for example, `1033092_superfast_vtol`). - - Оновіть файл з параметрами конфігурації та програмами (див. вище). + - Give it a short descriptive filename and prepend the filename with an unused autostart ID (for example, `1033092_superfast_vtol`). + - Оновіть файл з параметрами конфігурації та програмами (див. вище). 2. Add the name of the new frame config file to the [CMakeLists.txt](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt) in the relevant section for the type of vehicle. 3. [Build and upload](../dev_setup/building_px4.md) the software. @@ -292,37 +292,37 @@ If the airframe is for a **new group** you additionally need to: 2. Add a mapping between the new group name and image filename in the [srcparser.py](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/px4airframes/srcparser.py) method `GetImageName()` (follow the pattern below): - ```python - def GetImageName(self): - """ - Get parameter group image base name (w/o extension) - """ - if (self.name == "Standard Plane"): - return "Plane" - elif (self.name == "Flying Wing"): - return "FlyingWing" - ... - ... - return "AirframeUnknown" - ``` + ```python + def GetImageName(self): + """ + Get parameter group image base name (w/o extension) + """ + if (self.name == "Standard Plane"): + return "Plane" + elif (self.name == "Flying Wing"): + return "FlyingWing" + ... + ... + return "AirframeUnknown" + ``` 3. Update _QGroundControl_: - - Add the svg image for the group into: [src/AutopilotPlugins/Common/images](https://github.com/mavlink/qgroundcontrol/tree/master/src/AutoPilotPlugins/Common/Images) - - Add reference to the svg image into [qgcimages.qrc](https://github.com/mavlink/qgroundcontrol/blob/master/qgcimages.qrc), following the pattern below: + - Add the svg image for the group into: [src/AutopilotPlugins/Common/images](https://github.com/mavlink/qgroundcontrol/tree/master/src/AutoPilotPlugins/Common/Images) + - Add reference to the svg image into [qgcimages.qrc](https://github.com/mavlink/qgroundcontrol/blob/master/qgcimages.qrc), following the pattern below: - ```xml - - ... - src/AutoPilotPlugins/Common/Images/AirframeSimulation.svg - src/AutoPilotPlugins/Common/Images/AirframeUnknown.svg - src/AutoPilotPlugins/Common/Images/Boat.svg - src/AutoPilotPlugins/Common/Images/FlyingWing.svg - ... - ``` + ```xml + + ... + src/AutoPilotPlugins/Common/Images/AirframeSimulation.svg + src/AutoPilotPlugins/Common/Images/AirframeUnknown.svg + src/AutoPilotPlugins/Common/Images/Boat.svg + src/AutoPilotPlugins/Common/Images/FlyingWing.svg + ... + ``` - ::: info - The remaining airframe metadata should be automatically included in the firmware (once **srcparser.py** is updated). + ::: info + The remaining airframe metadata should be automatically included in the firmware (once **srcparser.py** is updated). ::: diff --git a/docs/uk/dev_log/log_encryption.md b/docs/uk/dev_log/log_encryption.md index a6f7f68b3c..82b519a857 100644 --- a/docs/uk/dev_log/log_encryption.md +++ b/docs/uk/dev_log/log_encryption.md @@ -30,7 +30,7 @@ If another algorithm is supported in future, the process is _likely_ to remain t The encryption process for each new ULog is: 1. A XChaCha20 symmetric key is generated and encrypted using an RSA2048 public key. - This wrapped (encrypted) key is stored on the SD card in the beginning of a file that has the suffix `.ulge` ("ulog encrypted"). + This wrapped (encrypted) key is stored on the SD card in the beginning of a file that has the suffix `.ulge` ("ulog encrypted"). 2. When a log is captured, the ULog data is encrypted with the unwrapped symmetric key and the resulting data is appended into the end of the `.ulge` file immediately after the wrapped key data. After the flight, the `.ulge` file containing both the wrapped symmetric key and the encrypted log data can be found on the SD card. @@ -356,26 +356,26 @@ This section explains how you might manually run the same steps as the script (s 2. Use OpenSSL to generate a RSA2048 private and public key: - ```sh - openssl genpkey -algorithm RSA -out private_key.pem -pkeyopt rsa_keygen_bits:2048 - ``` + ```sh + openssl genpkey -algorithm RSA -out private_key.pem -pkeyopt rsa_keygen_bits:2048 + ``` 3. Create a public key from this private key: - ```sh - # Convert private_key.pem to a DER file - openssl rsa -pubout -in private_key.pem -outform DER -out public_key.der - # From the DER file, generate a public key in hex format, separated by commas - xxd -p public_key.der | tr -d '\n' | sed 's/\(..\)/0x\1, /g' > public_key.pub - ``` + ```sh + # Convert private_key.pem to a DER file + openssl rsa -pubout -in private_key.pem -outform DER -out public_key.der + # From the DER file, generate a public key in hex format, separated by commas + xxd -p public_key.der | tr -d '\n' | sed 's/\(..\)/0x\1, /g' > public_key.pub + ``` 4. Copy the keys into the appropriate locations expected by the rest of the toolchain (as shown in previous section). 5. To use this key, modify your `.px4board` file to point `CONFIG_PUBLIC_KEY1` to the file location of `public_key.pub`. - ```sh - CONFIG_PUBLIC_KEY1="../../../keys/public/public_key.pub" - ``` + ```sh + CONFIG_PUBLIC_KEY1="../../../keys/public/public_key.pub" + ``` ## Flight Review & Encrypted logs @@ -397,10 +397,10 @@ This can use logs that you have downloaded and decrypted yourself, or you can in 3. Add this key location into the server config file: `flight_review/app/config_default.ini`. - The line to add should look something like this (for the file above): + The line to add should look something like this (for the file above): - ```sh - ulge_private_key = ../private_key/private_key.pem - ``` + ```sh + ulge_private_key = ../private_key/private_key.pem + ``` 4. Follow the Flight Review Instructions to start your server. diff --git a/docs/uk/dev_setup/dev_env_linux_ubuntu.md b/docs/uk/dev_setup/dev_env_linux_ubuntu.md index 7d8fd2f2a2..efe9dcce63 100644 --- a/docs/uk/dev_setup/dev_env_linux_ubuntu.md +++ b/docs/uk/dev_setup/dev_env_linux_ubuntu.md @@ -33,24 +33,24 @@ The script is intended to be run on _clean_ Ubuntu LTS installations, and may no 1. [Download PX4 Source Code](../dev_setup/building_px4.md): - ```sh - git clone https://github.com/PX4/PX4-Autopilot.git --recursive - ``` + ```sh + git clone https://github.com/PX4/PX4-Autopilot.git --recursive + ``` - ::: info - The environment setup scripts in the source usually work for recent PX4 releases. - If working with an older version of PX4 you may need to [get the source code specific to your release](../contribute/git_examples.md#get-a-specific-release). + ::: info + The environment setup scripts in the source usually work for recent PX4 releases. + If working with an older version of PX4 you may need to [get the source code specific to your release](../contribute/git_examples.md#get-a-specific-release). ::: 2. Run the **ubuntu.sh** with no arguments (in a bash shell) to install everything: - ```sh - bash ./PX4-Autopilot/Tools/setup/ubuntu.sh - ``` + ```sh + bash ./PX4-Autopilot/Tools/setup/ubuntu.sh + ``` - - При появі підказки по ходу виконання скрипту підтвердить вибір. - - You can use the `--no-nuttx` and `--no-sim-tools` options to omit the NuttX and/or simulation tools. + - При появі підказки по ходу виконання скрипту підтвердить вибір. + - You can use the `--no-nuttx` and `--no-sim-tools` options to omit the NuttX and/or simulation tools. 3. If you need Gazebo Classic (Ubuntu 22.04 only) then you can manually remove Gazebo and install it by following the instructions in [Gazebo Classic > Installation](../sim_gazebo_classic/index.md#installation). diff --git a/docs/uk/dev_setup/dev_env_mac.md b/docs/uk/dev_setup/dev_env_mac.md index 83af592c2e..65f1453411 100644 --- a/docs/uk/dev_setup/dev_env_mac.md +++ b/docs/uk/dev_setup/dev_env_mac.md @@ -38,21 +38,21 @@ If you have an Apple M1, M2 etc. Macbook, make sure to run the terminal as x86 b 1. Enable more open files by appending the following line to the `~/.zshenv` file (creating it if necessary): - ```sh - echo ulimit -S -n 2048 >> ~/.zshenv - ``` + ```sh + echo ulimit -S -n 2048 >> ~/.zshenv + ``` - ::: info - If you don't do this, the build toolchain may report the error: `"LD: too many open files"` + ::: info + If you don't do this, the build toolchain may report the error: `"LD: too many open files"` ::: 2. Enforce Python 3 by appending the following lines to `~/.zshenv` - ```sh - # Point pip3 to MacOS system python 3 pip - alias pip3=/usr/bin/pip3 - ``` + ```sh + # Point pip3 to MacOS system python 3 pip + alias pip3=/usr/bin/pip3 + ``` ### Загальні інструменти @@ -62,19 +62,19 @@ If you have an Apple M1, M2 etc. Macbook, make sure to run the terminal as x86 b 2. Виконайте ці команди в командній оболонці для встановлення загальних інструментів: - ```sh - brew tap PX4/px4 - brew install px4-dev - ``` + ```sh + brew tap PX4/px4 + brew install px4-dev + ``` 3. Встановіть необхідні пакети Python: - ```sh - # install required packages using pip3 - python3 -m pip install --user pyserial empty toml numpy pandas jinja2 pyyaml pyros-genmsg packaging kconfiglib future jsonschema - # if this fails with a permissions error, your Python install is in a system path - use this command instead: - sudo -H python3 -m pip install --user pyserial empty toml numpy pandas jinja2 pyyaml pyros-genmsg packaging kconfiglib future jsonschema - ``` + ```sh + # install required packages using pip3 + python3 -m pip install --user pyserial empty toml numpy pandas jinja2 pyyaml pyros-genmsg packaging kconfiglib future jsonschema + # if this fails with a permissions error, your Python install is in a system path - use this command instead: + sudo -H python3 -m pip install --user pyserial empty toml numpy pandas jinja2 pyyaml pyros-genmsg packaging kconfiglib future jsonschema + ``` ## Симуляція Gazebo Classic @@ -82,35 +82,35 @@ To setup the environment for [Gazebo Classic](../sim_gazebo_classic/index.md) si 1. Виконайте наступні команди в командній оболонці: - ```sh - brew unlink tbb - sed -i.bak '/disable! date:/s/^/ /; /disable! date:/s/./#/3' $(brew --prefix)/Library/Taps/homebrew/homebrew-core/Formula/tbb@2020.rb - brew install tbb@2020 - brew link tbb@2020 - ``` + ```sh + brew unlink tbb + sed -i.bak '/disable! date:/s/^/ /; /disable! date:/s/./#/3' $(brew --prefix)/Library/Taps/homebrew/homebrew-core/Formula/tbb@2020.rb + brew install tbb@2020 + brew link tbb@2020 + ``` - ::: info - September 2021: The commands above are a workaround to this bug: [PX4-Autopilot#17644](https://github.com/PX4/PX4-Autopilot/issues/17644). - Вони можуть бути видалені після того, як вона буде виправлена (разом з цією нотаткою). + ::: info + September 2021: The commands above are a workaround to this bug: [PX4-Autopilot#17644](https://github.com/PX4/PX4-Autopilot/issues/17644). + Вони можуть бути видалені після того, як вона буде виправлена (разом з цією нотаткою). ::: 2. Для встановлення симуляції SITL з Gazebo Classic: - ```sh - brew install --cask temurin - brew install --cask xquartz - brew install px4-sim-gazebo - ``` + ```sh + brew install --cask temurin + brew install --cask xquartz + brew install px4-sim-gazebo + ``` 3. Run the macOS setup script: `PX4-Autopilot/Tools/setup/macos.sh` - The easiest way to do this is to clone the PX4 source, and then run the script from the directory, as shown: + The easiest way to do this is to clone the PX4 source, and then run the script from the directory, as shown: - ```sh - git clone https://github.com/PX4/PX4-Autopilot.git --recursive - cd PX4-Autopilot/Tools/setup - sh macos.sh - ``` + ```sh + git clone https://github.com/PX4/PX4-Autopilot.git --recursive + cd PX4-Autopilot/Tools/setup + sh macos.sh + ``` ## Наступні кроки diff --git a/docs/uk/dev_setup/dev_env_windows_cygwin_packager_setup.md b/docs/uk/dev_setup/dev_env_windows_cygwin_packager_setup.md index b670ce7d51..c5c774c644 100644 --- a/docs/uk/dev_setup/dev_env_windows_cygwin_packager_setup.md +++ b/docs/uk/dev_setup/dev_env_windows_cygwin_packager_setup.md @@ -135,31 +135,31 @@ The toolchain gets maintained and hence these instructions might not cover every 10. Download [**Apache Ant**](https://ant.apache.org/bindownload.cgi) as zip archive of the binaries for Windows and unpack the content to the folder `C:\PX4\toolchain\apache-ant`. - :::tip - Make sure you don't have an additional folder layer from the folder which is inside the downloaded archive. + :::tip + Make sure you don't have an additional folder layer from the folder which is inside the downloaded archive. ::: - ::: info - This is what the toolchain does in: [apache-ant/install-apache-ant.bat](https://github.com/PX4/PX4-windows-toolchain/blob/master/toolchain/apache-ant/install-apache-ant.bat). + ::: info + This is what the toolchain does in: [apache-ant/install-apache-ant.bat](https://github.com/PX4/PX4-windows-toolchain/blob/master/toolchain/apache-ant/install-apache-ant.bat). ::: 11. Download, build and add _genromfs_ to the path: - - Clone the source code to the folder **C:\PX4\toolchain\genromfs\genromfs-src** with + - Clone the source code to the folder **C:\PX4\toolchain\genromfs\genromfs-src** with ```sh cd /c/toolchain/genromfs git clone https://github.com/chexum/genromfs.git genromfs-src ``` - - Скомпілюйте це: + - Скомпілюйте це: ```sh cd genromfs-src make all ``` - - Copy the resulting binary **genromfs.exe** one folder level out to: **C:\PX4\toolchain\genromfs** + - Copy the resulting binary **genromfs.exe** one folder level out to: **C:\PX4\toolchain\genromfs** 12. Make sure all the binary folders of all the installed components are correctly listed in the `PATH` variable configured by [**setup-environment.bat**](https://github.com/PX4/PX4-windows-toolchain/blob/master/toolchain/scripts/setup-environment.bat). diff --git a/docs/uk/dev_setup/dev_env_windows_vm.md b/docs/uk/dev_setup/dev_env_windows_vm.md index 26be70156b..93d09b3593 100644 --- a/docs/uk/dev_setup/dev_env_windows_vm.md +++ b/docs/uk/dev_setup/dev_env_windows_vm.md @@ -57,12 +57,12 @@ Allocate as many CPU cores and memory resources to the VM as possible. Запам'ятайте, всі налаштування потрібні тільки для використання у вашій основній операційній системі, тому можна вимкнути будь-який режим збереження екрана та функції безпеки локальні робочої станції, що не збільшують ризик мережевої атаки. 10. Once the new VM is booted up make sure you install _VMWare tools drivers and tools extension_ inside your guest system. - Це підвищить продуктивність та зручність користування віртуальною машиною: - - Значно поліпшена продуктивність графіки - - Належна підтримка використання апаратного забезпечення, наприклад розподілу портів USB (важливо для завантаження прошивок), прокручування коліщатком миші, підтримка звуку - - Адаптація роздільної здатності дисплею гостя до розміру вікна емулятора - - Спільний доступ до буфера обміну з основної ОС - - Спільний доступ до файлів з основної ОС + Це підвищить продуктивність та зручність користування віртуальною машиною: + - Значно поліпшена продуктивність графіки + - Належна підтримка використання апаратного забезпечення, наприклад розподілу портів USB (важливо для завантаження прошивок), прокручування коліщатком миші, підтримка звуку + - Адаптація роздільної здатності дисплею гостя до розміру вікна емулятора + - Спільний доступ до буфера обміну з основної ОС + - Спільний доступ до файлів з основної ОС 11. Continue with [PX4 environment setup for Linux](../dev_setup/dev_env_linux.md) @@ -96,11 +96,11 @@ One limitation of virtual machines is that you can't automatically connect to a 4. Add USB filters for the bootloader in VM: **VirtualBox > Settings > USB > Add new USB filter**. - Відкрийте меню і під'єднайте USB-кабель, підключений до автопілота. - Select the `...Bootloader` device when it appears in the UI. + Select the `...Bootloader` device when it appears in the UI. - ::: info - The bootloader device only appears for a few seconds after connecting USB. - Якщо він зникає до того як ви змогли обрати його, від'єднайте та повторно під'єднайте USB. + ::: info + The bootloader device only appears for a few seconds after connecting USB. + Якщо він зникає до того як ви змогли обрати його, від'єднайте та повторно під'єднайте USB. ::: diff --git a/docs/uk/dev_setup/dev_env_windows_wsl.md b/docs/uk/dev_setup/dev_env_windows_wsl.md index f11402c430..7d475f32f0 100644 --- a/docs/uk/dev_setup/dev_env_windows_wsl.md +++ b/docs/uk/dev_setup/dev_env_windows_wsl.md @@ -33,7 +33,7 @@ _QGroundControl for Windows_ is additionally required if you need to: Note that you can also use it to monitor a simulation, but you must manually [connect to the simulation running in WSL](#qgroundcontrol-on-windows). :::info -Connecting to an USB device from within WSL is not natively supported, however it can still be achieved by using the [USBIPD-WIN](https://learn.microsoft.com/en-us/windows/wsl/connect-usb) project. With this you can automatically upload firmware from the command line in WSL using the [`upload`](../dev_setup/building_px4.md#uploading-firmware-flashing-the-board) function. +Connecting to an USB device from within WSL is not natively supported, however it can still be achieved by using the [USBIPD-WIN](https://learn.microsoft.com/en-us/windows/wsl/connect-usb) project. With this you can automatically upload firmware from the command line in WSL using the [`upload`](../dev_setup/building_px4.md#uploading-firmware-flashing-the-board) function. ::: :::info @@ -48,38 +48,38 @@ The approach is similar to installing PX4 in your _own_ virtual machine, as desc Щоб встановити WSL2 з Ubuntu на новій установці Windows 10 або 11: 1. Переконайтеся, що функція віртуалізації увімкнена в BIOS вашого комп'ютера. - Зазвичай її називають "Virtualization Technology", "Intel VT-x" чи "AMD-V" відповідно. + Зазвичай її називають "Virtualization Technology", "Intel VT-x" чи "AMD-V" відповідно. 2. Open _cmd.exe_ as administrator. - This can be done by pressing the start key, typing `cmd`, right-clicking on the _Command prompt_ entry and selecting **Run as administrator**. + This can be done by pressing the start key, typing `cmd`, right-clicking on the _Command prompt_ entry and selecting **Run as administrator**. 3. Виконайте наступні команди для встановлення WSL2 та певної версії Ubuntu: - - Версія за замовчуванням (Ubuntu 22.04): + - Версія за замовчуванням (Ubuntu 22.04): - ```sh - wsl --install - ``` + ```sh + wsl --install + ``` - - Ubuntu 20.04 ([Gazebo-Classic Simulation](../sim_gazebo_classic/index.md)) + - Ubuntu 20.04 ([Gazebo-Classic Simulation](../sim_gazebo_classic/index.md)) - ```sh - wsl --install -d Ubuntu-20.04 - ``` + ```sh + wsl --install -d Ubuntu-20.04 + ``` - - Ubuntu 22.04 ([Gazebo Simulation](../sim_gazebo_gz/index.md)) + - Ubuntu 22.04 ([Gazebo Simulation](../sim_gazebo_gz/index.md)) - ```sh - wsl --install -d Ubuntu-22.04 - ``` + ```sh + wsl --install -d Ubuntu-22.04 + ``` - ::: info - You can also install[Ubuntu 20.04](https://www.microsoft.com/store/productId/9MTTCL66CPXJ) and [Ubuntu 22.04](https://www.microsoft.com/store/productId/9PN20MSR04DW) from the store, which allows you to delete the application using the normal Windows Add/Remove settings: + ::: info + You can also install[Ubuntu 20.04](https://www.microsoft.com/store/productId/9MTTCL66CPXJ) and [Ubuntu 22.04](https://www.microsoft.com/store/productId/9PN20MSR04DW) from the store, which allows you to delete the application using the normal Windows Add/Remove settings: ::: 4. WSL запитає про ім'я користувача та пароль для встановлення Ubuntu. - Запишіть ці облікові дані, оскільки вони знадобляться пізніше! + Запишіть ці облікові дані, оскільки вони знадобляться пізніше! Тепер командний рядок є терміналом в нововстановленому середовищі Ubuntu. @@ -94,26 +94,26 @@ If you're using [Windows Terminal](https://learn.microsoft.com/en-us/windows/ter Щоб відкрити оболонку WSL за допомогою командного рядка: 1. Відкрийте командний рядок: - - Press the Windows **Start** key. - - Type `cmd` and press **Enter** to open the prompt. + - Press the Windows **Start** key. + - Type `cmd` and press **Enter** to open the prompt. 2. Щоб запустити WSL і отримати доступ до WSL оболонки, виконайте команду: - ```sh - wsl -d - ``` + ```sh + wsl -d + ``` - Наприклад: + Наприклад: - ```sh - wsl -d Ubuntu - ``` + ```sh + wsl -d Ubuntu + ``` - ```sh - wsl -d Ubuntu-20.04 - ``` + ```sh + wsl -d Ubuntu-20.04 + ``` - If you only have one version of Ubuntu, you can just use `wsl`. + If you only have one version of Ubuntu, you can just use `wsl`. Введіть наступні команди, щоб спочатку закрити WSL оболонку, а потім завершити WSL: @@ -135,57 +135,57 @@ This will install the toolchain for Gazebo Classic simulation and Pixhawk/NuttX 2. Execute the command `cd ~` to switch to the home folder of WSL for the next steps. - :::warning - This is important! - Якщо ви працюєте за межами файлової системи WSL, то ви стикнетесь з такими проблемами, як дуже повільне виконання та помилки прав доступу/дозволів. + :::warning + This is important! + Якщо ви працюєте за межами файлової системи WSL, то ви стикнетесь з такими проблемами, як дуже повільне виконання та помилки прав доступу/дозволів. ::: 3. Download the PX4 source code using `git` (which is already installed in WSL2): - ```sh - git clone https://github.com/PX4/PX4-Autopilot.git --recursive - ``` + ```sh + git clone https://github.com/PX4/PX4-Autopilot.git --recursive + ``` - ::: info - The environment setup scripts in the source usually work for recent PX4 releases. - If working with an older version of PX4 you may need to [get the source code specific to your release](../contribute/git_examples.md#get-a-specific-release). + ::: info + The environment setup scripts in the source usually work for recent PX4 releases. + If working with an older version of PX4 you may need to [get the source code specific to your release](../contribute/git_examples.md#get-a-specific-release). ::: 4. Run the **ubuntu.sh** installer script and acknowledge any prompts as the script progresses: - ```sh - bash ./PX4-Autopilot/Tools/setup/ubuntu.sh - ``` + ```sh + bash ./PX4-Autopilot/Tools/setup/ubuntu.sh + ``` - ::: info - This installs tools to build PX4 for Pixhawk and either Gazebo or Gazebo Classic targets: + ::: info + This installs tools to build PX4 for Pixhawk and either Gazebo or Gazebo Classic targets: - - You can use the `--no-nuttx` and `--no-sim-tools` options to omit the NuttX and/or simulation tools. - - Other Linux build targets are untested (you can try these by entering the appropriate commands in [Ubuntu Development Environment](../dev_setup/dev_env_linux_ubuntu.md) into the WSL shell). + - You can use the `--no-nuttx` and `--no-sim-tools` options to omit the NuttX and/or simulation tools. + - Other Linux build targets are untested (you can try these by entering the appropriate commands in [Ubuntu Development Environment](../dev_setup/dev_env_linux_ubuntu.md) into the WSL shell). ::: 5. Перезапустіть "комп'ютер WSL" після завершення скрипту (вийти з оболонки, вимкнути WSL та перезапустити WSL): - ```sh - exit - wsl --shutdown - wsl - ``` + ```sh + exit + wsl --shutdown + wsl + ``` 6. Перейдіть в репозиторій PX4 в домашній директорії WSL: - ```sh - cd ~/PX4-Autopilot - ``` + ```sh + cd ~/PX4-Autopilot + ``` 7. Зберіть ціль PX4 SITL та перевірте середовище: - ```sh - make px4_sitl - ``` + ```sh + make px4_sitl + ``` For more build options see [Building PX4 Software](../dev_setup/building_px4.md). @@ -205,26 +205,26 @@ VS Code на Windows добре інтегрований з WSL. 5. У WSL оболонці перейдіть у директорію PX4: - ```sh - cd ~/PX4-Autopilot - ``` + ```sh + cd ~/PX4-Autopilot + ``` 6. В оболонці WSL запустіть VS Code: - ```sh - code . - ``` + ```sh + code . + ``` - Це відкриє IDE повністю інтегроване в WSL оболонку. + Це відкриє IDE повністю інтегроване в WSL оболонку. - Переконайтеся, що ви завжди відкриваєте PX4 репозиторій у режимі Remote WSL. + Переконайтеся, що ви завжди відкриваєте PX4 репозиторій у режимі Remote WSL. 7. Next time you want to develop WSL2 you can very easily open it again in Remote WSL mode by selecting **Open Recent** (as shown below). - Це запустить WSL. + Це запустить WSL. - ![](../../assets/toolchain/vscode/vscode_wsl.png) + ![](../../assets/toolchain/vscode/vscode_wsl.png) - Зверніть увагу, що IP-адреса віртуальної машини WSL буде змінена, так що ви не зможете контролювати симуляцію з QGC для Windows (ви все ще можете використовувати QGC для Linux) + Зверніть увагу, що IP-адреса віртуальної машини WSL буде змінена, так що ви не зможете контролювати симуляцію з QGC для Windows (ви все ще можете використовувати QGC для Linux) ## QGroundControl @@ -240,21 +240,21 @@ If you need to [flash a flight control board](#flash-a-flight-control-board) wit 1. In a web browser, navigate to the QGC [Ubuntu download section](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#ubuntu) 2. Right-click on the **QGroundControl.AppImage** link, and select "Copy link address". - This will be something like _https://d176td9ibe4jno.cloudfront.net/builds/master/QGroundControl.AppImage_ + This will be something like _https://d176td9ibe4jno.cloudfront.net/builds/master/QGroundControl.AppImage_ 3. [Open a WSL shell](#opening-a-wsl-shell) and enter the following commands to download the appimage and make it executable (replace the AppImage URL where indicated): - ```sh - cd ~ - wget - chmod +x QGroundControl.AppImage - ``` + ```sh + cd ~ + wget + chmod +x QGroundControl.AppImage + ``` 4. Запустіть QGroundControl: - ```sh - ./QGroundControl.AppImage - ``` + ```sh + ./QGroundControl.AppImage + ``` QGroundControl запуститься та автоматично приєднається до запущеної симуляції, що дозволить вам спостерігати та контролювати ваші рухомі засоби. @@ -270,15 +270,15 @@ Install [QGroundControl on Windows](https://docs.qgroundcontrol.com/master/en/qg 2. Check the IP address of the WSL virtual machine by running the command `ip addr | grep eth0`: - ```sh - $ ip addr | grep eth0 + ```sh + $ ip addr | grep eth0 - 6: eth0: mtu 1500 qdisc mq state UP group default qlen 1000 - inet 172.18.46.131/20 brd 172.18.47.255 scope global eth0 - ``` + 6: eth0: mtu 1500 qdisc mq state UP group default qlen 1000 + inet 172.18.46.131/20 brd 172.18.47.255 scope global eth0 + ``` - Copy the first part of the `eth0` interface `inet` address to the clipboard. - In this case: `172.18.46.131`. + Copy the first part of the `eth0` interface `inet` address to the clipboard. + In this case: `172.18.46.131`. 3. In QGC go to **Q > Application Settings > Comm Links** @@ -304,14 +304,14 @@ Instead you connect [QGroundControl for Windows](#qgroundcontrol-on-windows) to 1. If you haven't already built the binary in WSL e.g. with a [WSL shell](dev_env_windows_wsl.md#opening-a-wsl-shell) and by running: - ```sh - cd ~/PX4-Autopilot - make px4_fmu-v5 - ``` + ```sh + cd ~/PX4-Autopilot + make px4_fmu-v5 + ``` - ::: tip - Use the correct `make` target for your board. - `px4_fmu-v5` can be used for a Pixhawk 4 board. + ::: tip + Use the correct `make` target for your board. + `px4_fmu-v5` can be used for a Pixhawk 4 board. ::: @@ -325,12 +325,12 @@ Instead you connect [QGroundControl for Windows](#qgroundcontrol-on-windows) to 6. Continue and select the firmware binary you just built in WSL. - У відкритому діалозі знайдіть розташування "Linux" з іконкою пінгвіна на лівій панелі. - Зазвичай, вона в самому низу. - Choose the file in the path: `Ubuntu\home\{your WSL user name}\PX4-Autopilot\build\{your build target}\{your build target}.px4` + У відкритому діалозі знайдіть розташування "Linux" з іконкою пінгвіна на лівій панелі. + Зазвичай, вона в самому низу. + Choose the file in the path: `Ubuntu\home\{your WSL user name}\PX4-Autopilot\build\{your build target}\{your build target}.px4` - ::: info - You can add the folder to the favourites to access it quickly next time. + ::: info + You can add the folder to the favourites to access it quickly next time. ::: @@ -349,3 +349,9 @@ sudo add-apt-repository ppa:kisak/kisak-mesa sudo apt update sudo apt upgrade ``` + +### QGroundControl not connecting to PX4 SITL + +- The connection between PX4 SITL on WSL2 and QGroundControl on Windows requires [broadcasting](../simulation/index.md#enable-udp-broadcasting) or [streaming to a specific address](../simulation/index.md#enable-streaming-to-specific-address) to be enabled. + Streaming to a specific address should be enabled by default, but is something to check if a connection can't be established. +- Network traffic might be blocked by firewall or antivirus on you system. diff --git a/docs/uk/dev_setup/vscode.md b/docs/uk/dev_setup/vscode.md index 89cca6f8e7..99b6ba7618 100644 --- a/docs/uk/dev_setup/vscode.md +++ b/docs/uk/dev_setup/vscode.md @@ -27,10 +27,10 @@ You must already have installed the command line [PX4 developer environment](../ - Select _Open folder ..._ option on the welcome page (or using the menu: **File > Open Folder**): - ![Open Folder](../../assets/toolchain/vscode/welcome_open_folder.jpg) + ![Open Folder](../../assets/toolchain/vscode/welcome_open_folder.jpg) - З'явиться діалогове вікно вибору файлу. - Select the **PX4-Autopilot** directory and then press **OK**. + Select the **PX4-Autopilot** directory and then press **OK**. The project files and configuration will then load into _VSCode_. @@ -49,9 +49,9 @@ You must already have installed the command line [PX4 developer environment](../ ::: - If prompted to install a new version of _cmake_: - - Say **No** (the right version is installed with the [PX4 developer environment](../dev_setup/dev_env.md)). + - Say **No** (the right version is installed with the [PX4 developer environment](../dev_setup/dev_env.md)). - If prompted to sign into _github.com_ and add your credentials: - - Це ваш розсуд! Це забезпечує глибоку інтеграцію між Github та IDE, що може спростити ваш робочий процес. + - Це ваш розсуд! Це забезпечує глибоку інтеграцію між Github та IDE, що може спростити ваш робочий процес. - Інші підказки необов'язкові та можуть бути встановлені, якщо вважаються корисними. @@ -63,21 +63,21 @@ You must already have installed the command line [PX4 developer environment](../ 1. Оберіть свою ціль збірки ("cmake build config"): - The current _cmake build target_ is shown on the blue _config_ bar at the bottom (if this is already your desired target, skip to next step). - ![Select Cmake build target](../../assets/toolchain/vscode/cmake_build_config.jpg) + ![Select Cmake build target](../../assets/toolchain/vscode/cmake_build_config.jpg) - ::: info - The cmake target you select affects the targets offered for when [building/debugging](#debugging) (i.e. for hardware debugging you must select a hardware target like `px4_fmu-v6`). + ::: info + The cmake target you select affects the targets offered for when [building/debugging](#debugging) (i.e. for hardware debugging you must select a hardware target like `px4_fmu-v6`). ::: - Натисніть на ціль на панелі config, щоб показати інші параметри та вибрати ту, яка вам потрібна (це замінить обрану ціль). - _Cmake_ will then configure your project (see notification in bottom right). - ![Cmake config project](../../assets/toolchain/vscode/cmake_configuring_project.jpg) + ![Cmake config project](../../assets/toolchain/vscode/cmake_configuring_project.jpg) - Зачекайте, поки налаштування завершиться. - When this is done the notification will disappear and you'll be shown the build location: - ![Cmake config project](../../assets/toolchain/vscode/cmake_configuring_project_done.jpg). + When this is done the notification will disappear and you'll be shown the build location: + ![Cmake config project](../../assets/toolchain/vscode/cmake_configuring_project_done.jpg). 2. You can then kick off a build from the config bar (select either **Build** or **Debug**). ![Run debug or build](../../assets/toolchain/vscode/run_debug_build.jpg) diff --git a/docs/uk/dronecan/holybro_h_rtk_zed_f9p_gps.md b/docs/uk/dronecan/holybro_h_rtk_zed_f9p_gps.md index be65191b50..c164a5607a 100644 --- a/docs/uk/dronecan/holybro_h_rtk_zed_f9p_gps.md +++ b/docs/uk/dronecan/holybro_h_rtk_zed_f9p_gps.md @@ -64,10 +64,10 @@ To update the "AP Periph" firmware to the latest version: 1. [Download the latest binary](https://firmware.ardupilot.org/AP_Periph/latest/HolybroG4_GPS/). 2. Update the firmware using either of the following approaches: - - Using ArduPilot: - 1. Install _Ardupilot_ firmware on your flight controller and the Mission Planner GCS on your computer. - 2. Update the binary by following the instructions in the [DroneCAN FW Upgrade](https://docs.holybro.com/gps-and-rtk-system/zed-f9p-h-rtk-series/dronecan-fw-upgrade) guide. - - Use a serial-to-can converter (such as the [Zubax Babel](https://github.com/Zubax/canface_cf1?tab=readme-ov-file)) and the [DroneCAN GUI Tool](https://dronecan.github.io/Implementations/Libuavcan/Tutorials/11._Firmware_update/). + - Using ArduPilot: + 1. Install _Ardupilot_ firmware on your flight controller and the Mission Planner GCS on your computer. + 2. Update the binary by following the instructions in the [DroneCAN FW Upgrade](https://docs.holybro.com/gps-and-rtk-system/zed-f9p-h-rtk-series/dronecan-fw-upgrade) guide. + - Use a serial-to-can converter (such as the [Zubax Babel](https://github.com/Zubax/canface_cf1?tab=readme-ov-file)) and the [DroneCAN GUI Tool](https://dronecan.github.io/Implementations/Libuavcan/Tutorials/11._Firmware_update/). Remember to change the firmware on the flight controller back to PX4 afterwards. @@ -98,14 +98,14 @@ In order to use dual ZED-F9P GPS heading in PX4, follow these steps: 1. Open the QGroundControl parameters page. 2. On the left side next to the parameters list, double-click on the _System_ section (this hides the section). 3. Components should be visible on the left panel. - Click on the first `_Component_` that maps to the ZED-F9P DroneCAN node (below shown as _Component 124_). + Click on the first `_Component_` that maps to the ZED-F9P DroneCAN node (below shown as _Component 124_). 4. Click on the _GPS_ subsection and configure the parameters listed below: - - `GPS_TYPE`: Either set to `17` for moving baseline _base_, or set to `18` to be the moving baseline _rover_. - One F9P MUST be _rover_, and the other MUST be _base_. - - `GPS_AUTO_CONFIG`: set to 1 for both the rover and base - - `GPS_POS_X`, `GPS_POS_Y`, `GPS_POS_Z`: This is the antenna placement, which for the F9P is internal to the module. - This is the local offset (FRD) with respect to the autopilot. + - `GPS_TYPE`: Either set to `17` for moving baseline _base_, or set to `18` to be the moving baseline _rover_. + One F9P MUST be _rover_, and the other MUST be _base_. + - `GPS_AUTO_CONFIG`: set to 1 for both the rover and base + - `GPS_POS_X`, `GPS_POS_Y`, `GPS_POS_Z`: This is the antenna placement, which for the F9P is internal to the module. + This is the local offset (FRD) with respect to the autopilot. ![QGC Setup](../../assets/hardware/gps/holybro_h_rtk_zed_f9p_rover/holybro_f9p_gps_qgc_setup.png) diff --git a/docs/uk/dronecan/pomegranate_systems_pm.md b/docs/uk/dronecan/pomegranate_systems_pm.md index 9fb4005b6e..e0d75858ab 100644 --- a/docs/uk/dronecan/pomegranate_systems_pm.md +++ b/docs/uk/dronecan/pomegranate_systems_pm.md @@ -45,11 +45,11 @@ Source code and build instructions can be found on [the bitbucket](https://bitbu 1. Enable DroneCAN by setting the [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) parameter to `2` (Sensors Automatic Config) or `3`. 2. Enable DroneCAN battery monitoring by setting [UAVCAN_SUB_BAT](../advanced_config/parameter_reference.md#UAVCAN_SUB_BAT) to `1` or `2` ( depending on your battery). 3. Set the following module parameters using the [MAVLink console](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/analyze_view/mavlink_console.html): - - Battery capacity in mAh: `battery_capacity_mAh` - - Battery voltage when _full_: `battery_full_V`, - - Battery voltage when _empty_: `battery_empty_V` - - Turn on current integration: `enable_current_track` - - (optional) Turn Off CANbus termination resistor :`enable_can_term` + - Battery capacity in mAh: `battery_capacity_mAh` + - Battery voltage when _full_: `battery_full_V`, + - Battery voltage when _empty_: `battery_empty_V` + - Turn on current integration: `enable_current_track` + - (optional) Turn Off CANbus termination resistor :`enable_can_term` **Example:** A Power Module with UAVCAN node id `125` connected to a `3S` LiPo with capacity of `5000mAh` can be configured with the following commands: diff --git a/docs/uk/dronecan/raccoonlab_power.md b/docs/uk/dronecan/raccoonlab_power.md index dba00914ee..7e903d0809 100644 --- a/docs/uk/dronecan/raccoonlab_power.md +++ b/docs/uk/dronecan/raccoonlab_power.md @@ -7,9 +7,9 @@ CAN power connectors are designed for light unmanned aerial (UAV) and other vehi There are two types of devices: 1. `CAN-MUX` devices provide power from XT30 connector to CAN. - There are 2 variation of this type of the device with different number of connectors. + There are 2 variation of this type of the device with different number of connectors. 2. `Power connector node` is designed to pass current (up to 60A) to power load and CAN, measure voltage and current on load. - It behaves as Cyphal/DroneCAN node. + It behaves as Cyphal/DroneCAN node. Please refer to the RaccoonLab docs [CAN Power Connectors](https://docs.raccoonlab.co/guide/pmu/power/) page. diff --git a/docs/uk/flight_controller/accton-godwit_ga1.md b/docs/uk/flight_controller/accton-godwit_ga1.md new file mode 100644 index 0000000000..5b014c8452 --- /dev/null +++ b/docs/uk/flight_controller/accton-godwit_ga1.md @@ -0,0 +1,153 @@ +# Accton Godwit G-A1 + +:::warning +PX4 не розробляє цей (або будь-який інший) автопілот. +Contact the [manufacturer](https://cubepilot.org/#/home) for hardware support or compliance issues. +::: + +The G-A1 is a state-of-the-art flight controller developed derived from the [Pixhawk Autopilot v6X Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-012%20Pixhawk%20Autopilot%20v6X%20Standard.pdf). + +It includes an STM32H753 double-precision floating-point FMU processor and an STM32F103 IO coprocessor, multiple IMUs with 6-axis inertial sensors, two pressure/temperature sensors, and a geomagnetic sensor. +It also has independent buses and power supplies, and is designed for safety and rich expansion capabilities. + +With an integrated 10/100M Ethernet Physical Layer (PHY), the G-A1 can also communicate with a mission computer (airborne computer), high-end surveying and mapping cameras, and other UxV-mounted equipment for high-speed communications, meeting the needs of advanced UxV systems. + +:::tip +Visit [Accton-IoT Godwit](https://www.accton-iot.com/godwit/) for more information. +::: + +![AccGodwitGA1](../../assets/flight_controller/accton-godwit/ga1/outlook.png "Accton Godwit G-A1") + +![AccGodwitGA1 Top View](../../assets/flight_controller/accton-godwit/ga1/orientation.png "Accton Godwit G-A1 Top View") + +:::info +This flight controller is [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md). +::: + +## Характеристики + +### Процесор + +- STM32H753IIK (Arm® Cortex®-M7 480MHz) +- STM32F103 (Arm® Cortex®-M3, 72MHz) + +### Датчики + +- Bosch BMI088 (vibration isolated) +- TDK InvenSense ICM-42688-P x 2 (one vibration isolated) +- TDK Barometric Pressure and Temperature Sensor CP-20100 x 2 (one vibration isolated) +- PNI RM3100 Geomagnetic Sensor (vibration isolated) + +### Power + +- 4.6V to 5.7V + +### External ports + +- 2 CAN Buses (CAN1 and CAN2) +- 3 TELEM Ports (TELEM1, TELEM2 and TELEM3) +- 2 GPS Ports (GPS1 with safety switch, LED, buzzer, and GPS2) +- 1 PPM IN +- 1 SBUS OUT +- 2 USB Ports (1 TYPE-C and 1 JST GH1.25) +- 1 10/100Base-T Ethernet Port +- 1 DSM/SBUS RC +- 1 UART 4 +- 1 AD&IO Port +- 2 Debug Ports (1 IO Debug and 1 FMU Debug) +- 1 SPI6 Bus +- 4 Power Inputs (Power 1, Power 2, Power C1 and Power C2) +- 16 PWM Servo Outputs (A1-A8 from FMU and M1-M8 from IO) +- Micro SD Socket (supports SD 4.1 & SDIO 4.0 in two databus modes: 1 bit (default) and 4 bits) + +### Size and Dimensions + +- 92.2 (L) x 51.2 (W) x 28.3 (H) mm +- 77.6g (carrier board with IMU) + +## Де купити + +- [Accton-IoT Godwit](https://www.accton-iot.com/godwit/) +- [sales@accton-iot.com](sales@accton-iot.com) + +## Схема розташування виводів + +![G-A1 Pin definition](../../assets/flight_controller/accton-godwit/ga1/pin_definition.png "G-A1 Pin definition") + +## UART Mapping + +| Serial# | Протокол | Порт | Примітки | +| ------- | --------- | ------ | ---------- | +| SERIAL1 | Telem1 | UART7 | /dev/ttyS6 | +| SERIAL2 | Telem2 | UART5 | /dev/ttyS4 | +| SERIAL3 | GPS1 | USART1 | /dev/ttyS0 | +| SERIAL4 | GPS2 | UART8 | /dev/ttyS7 | +| SERIAL5 | Telem3 | USART2 | /dev/ttyS1 | +| SERIAL6 | UART4 | UART4 | /dev/ttyS3 | +| SERIAL7 | FMU Debug | USART3 | | +| SERIAL8 | OTG2 | USB | | + +## Wiring Diagram + +![G-A1 Wiring](../../assets/flight_controller/accton-godwit/ga1/wiring.png "G-A1 Wiring") + +## PWM Output + +PWM M1-M8 (IO Main PWM), A1-A8(FMU PWM). +All these 16 support normal PWM output formats. +FMU PWM A1-A6 can support DShot and B-Directional DShot. +A1-A8(FMU PWM) are grouped as: + +- Group 1: A1, A2, A3, A4 +- Group 2: A5, A6 +- Group 3: A7, A8 + +The motor and servo system should be connected to these ports according to the order outlined in the fuselage reference for your carrier. + +![G-A1 PWM Motor Servo](../../assets/flight_controller/accton-godwit/ga1/motor_servo.png "G-A1 PWM Motor Servo") + +## RC-вхід + +For DSM/SBUS receivers, connect them to the DSM/SBUS interface which provides dedicated 3.3V and 5V power pins respectively, and check above "Pinout" for detailed pin definition. +PPM receivers should be connected to the PPM interface. And other RC systems can be connected via other spare telemetry ports. + +![G-A1 Radio](../../assets/flight_controller/accton-godwit/ga1/radio.png "G-A1 Radio") + +## GPS/компас + +The Godwit G-A1 has a built-in compass +Due to potential interference, the autopilot is usually used with an external I2C compass as part of a GPS/Compass combination. + +![G-A1 GPS](../../assets/flight_controller/accton-godwit/ga1/gps.png "G-A1 GPS") + +## Power Connection and Battery Monitor + +This universal controller features a CAN PMU module that supports 3 to 14s lithium batteries. +To ensure proper connection, attach the module's 6-pin connector to the flight control Power C1 and/or Power C2 interface. + +This universal controller does not provide power to the servos. +To power them, an external BEC must be connected to the positive and negative terminals of any A1–A8 or M1–M8 port. + +![G-A1 Power](../../assets/flight_controller/accton-godwit/ga1/power.png "G-A1 Power") + +## SD-карта + +The SD card is NOT included in the package, you need to prepare the SD card and insert it into the slot. + +![G-A1 SD Card](../../assets/flight_controller/accton-godwit/ga1/sdcard.png "G-A1 SD Card") + +## Прошивка + +The autopilot is compatible with PX4 firmware. And G-A1 can be detected by QGroundControl automatically. Users can also build it with target "accton-godwit_ga1" + +To [build PX4](../dev_setup/building_px4.md) for this target, open up the terminal and enter: + +```sh +make accton-godwit_ga1 +``` + +## More Information and Support + +- [Accton-IoT Godwit](https://www.accton-iot.com/godwit/) +- [sales@accton-iot.com](sales@accton-iot.com) +- [support@accton-iot.com](mailto:support@accton-iot.com) diff --git a/docs/uk/flight_controller/autopilot_manufacturer_supported.md b/docs/uk/flight_controller/autopilot_manufacturer_supported.md index 189c41cb0e..6099c1fdf7 100644 --- a/docs/uk/flight_controller/autopilot_manufacturer_supported.md +++ b/docs/uk/flight_controller/autopilot_manufacturer_supported.md @@ -12,6 +12,7 @@ This category includes boards that are not fully compliant with the pixhawk stan Плати цієї категорії: +- [Accton Godwit GA1](../flight_controller/accton-godwit_ga1.md) - [AirMind MindPX](../flight_controller/mindpx.md) - [AirMind MindRacer](../flight_controller/mindracer.md) - [ARK Electronics ARKV6X](../flight_controller/ark_v6x.md) (and [ARK Electronics Pixhawk Autopilot Bus Carrier](../flight_controller/ark_pab.md)) diff --git a/docs/uk/flight_modes_fw/mission.md b/docs/uk/flight_modes_fw/mission.md index 31bb5be940..f8b6aacaea 100644 --- a/docs/uk/flight_modes_fw/mission.md +++ b/docs/uk/flight_modes_fw/mission.md @@ -29,32 +29,32 @@ _Режим місії_ змушує транспортний засіб вик 1. Якщо місія не збережена, або якщо PX4 завершив виконання всіх команд місії, або якщо [місія не є можливою](#mission-feasibility-checks): - - Якщо літає транспортний засіб, він буде марнувати час. - - Якщо посадять транспортний засіб, він буде "чекати". + - Якщо літає транспортний засіб, він буде марнувати час. + - Якщо посадять транспортний засіб, він буде "чекати". 2. Якщо місія збережена, а PX4 летить, вона виконає [місію / план польоту](../flying/missions.md) з поточного кроку. - - Пункт відправлення буде розглядатися як звичайна точка місії. + - Пункт відправлення буде розглядатися як звичайна точка місії. 3. Якщо місія збережена, а транспортний засіб приземлений, він злетить лише у випадку, якщо активна точка маршруту - це 'Зльот'. - Якщо налаштовано для запуску з катапульта, транспортний засіб також повинен бути запущений (див. [Зліт/посадка FW у місії](#mission-takeoff)). + Якщо налаштовано для запуску з катапульта, транспортний засіб також повинен бути запущений (див. [Зліт/посадка FW у місії](#mission-takeoff)). 4. Якщо жодне завдання не збережено, або якщо PX4 завершив виконання всіх команд місії: - - Якщо літає транспортний засіб, він буде марнувати час. - - Якщо посадять транспортний засіб, він буде "чекати". + - Якщо літає транспортний засіб, він буде марнувати час. + - Якщо посадять транспортний засіб, він буде "чекати". 5. Ви можете вручну змінити поточну команду місії, вибравши її в _QGroundControl_. - :::info - Якщо у вас є команда _Перейти до елементу_ в місії, переміщення до іншого елементу **не** скине лічильник циклу. - Однією з наслідків є те, що якщо ви зміните поточну команду місії на 1, це не призведе до "повного перезапуску" місії. + :::info + Якщо у вас є команда _Перейти до елементу_ в місії, переміщення до іншого елементу **не** скине лічильник циклу. + Однією з наслідків є те, що якщо ви зміните поточну команду місії на 1, це не призведе до "повного перезапуску" місії. ::: 6. Місія скине тільки тоді, коли транспортний засіб буде роззброєний або коли буде завантажена нова місія. - :::tip - Щоб автоматично роззброїти транспортний засіб після посадки, у _QGroundControl_ перейдіть до [Налаштування Транспортного Засобу > Безпека](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/safety.html), перейдіть до _Налаштувань Режиму Посадки_ та позначте прапорець _Роззброювати після_. - Введіть час очікування після посадки перед відброюванням транспортного засобу. + :::tip + Щоб автоматично роззброїти транспортний засіб після посадки, у _QGroundControl_ перейдіть до [Налаштування Транспортного Засобу > Безпека](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/safety.html), перейдіть до _Налаштувань Режиму Посадки_ та позначте прапорець _Роззброювати після_. + Введіть час очікування після посадки перед відброюванням транспортного засобу. ::: @@ -261,7 +261,7 @@ A fixed-wing mission requires a `Takeoff` mission item to takeoff; if however th 1. **Літайте до місця посадки**: Літак летить на поточній висоті до точки обертання. 2. **Опускаючись на орбіту для наближення до висоти**: При досягненні радіусу утримання точки шляху, транспортний засіб виконує опускаючу орбіту до досягнення "висоти наближення" (висота точки утримання). - Транспортний засіб продовжує обертатися на цій висоті до тих пір, поки він не матиме тангенціальну траєкторію до пункту наземної точки, після чого ініціюється посадковий захід. + Транспортний засіб продовжує обертатися на цій висоті до тих пір, поки він не матиме тангенціальну траєкторію до пункту наземної точки, після чого ініціюється посадковий захід. 3. **Приземлення**: Літак слідує нахилу під час приземлення до точки на землі до досягнення висоти флеру. 4. **Світло**: Транспортний засіб світиться, доки не сідає на землю. diff --git a/docs/uk/flight_modes_fw/takeoff.md b/docs/uk/flight_modes_fw/takeoff.md index aa6e3cd22e..5c339fc6fc 100644 --- a/docs/uk/flight_modes_fw/takeoff.md +++ b/docs/uk/flight_modes_fw/takeoff.md @@ -93,7 +93,7 @@ Once it reaches [MIS_TAKEOFF_ALT](#MIS_TAKEOFF_ALT) it will automatically switch 1. Увімкніть дрон 2. Put the vehicle into _Takeoff mode_ 3. Запустіть / киньте транспортний засіб (міцно) безпосередньо у вітер. - Ви також можете спершу потрясти транспортний засіб, зачекати, поки рушить двигун, а потім кинути його + Ви також можете спершу потрясти транспортний засіб, зачекати, поки рушить двигун, а потім кинути його ### Параметри (виявник запуску) diff --git a/docs/uk/flight_modes_mc/follow_me.md b/docs/uk/flight_modes_mc/follow_me.md index 9f770f7aa5..fae197203d 100644 --- a/docs/uk/flight_modes_mc/follow_me.md +++ b/docs/uk/flight_modes_mc/follow_me.md @@ -151,19 +151,19 @@ The follow-me behavior can be configured using the following parameters: 1. Set the [follow distance](#FLW_TGT_DST) to more than 12 meters (8 meters is a "recommended minimum"). - Існує вроджений вплив позиції (3 ~ 5 метрів) між цільовим об'єктом та GPS-датчиком дрона, що змушує дрон слідувати 'примарній цілі' десь поблизу фактичної цілі. - Це стає більш очевидним, коли відстань слідування дуже мала. - Ми рекомендуємо встановити достатньо велику відстань, щоб відхилення GPS не було значним. + Існує вроджений вплив позиції (3 ~ 5 метрів) між цільовим об'єктом та GPS-датчиком дрона, що змушує дрон слідувати 'примарній цілі' десь поблизу фактичної цілі. + Це стає більш очевидним, коли відстань слідування дуже мала. + Ми рекомендуємо встановити достатньо велику відстань, щоб відхилення GPS не було значним. 2. The speed at which you can change the follow angle depends on the [maximum tangential velocity](#FLW_TGT_MAX_VEL) setting. - Experimentation shows that values between `5 m/s` are `10 m/s` are usually suitable. + Experimentation shows that values between `5 m/s` are `10 m/s` are usually suitable. 3. Використовуючи коригування RC для висоти, відстані та кута, ви можете отримати деякі креативні знімки камери. - + - This video demonstrates a Google-Earth view perspective, by adjusting the height to around 50 meters (high), distance to 1 meter (close). Що дозволяє перспективу, як знято з супутника. + This video demonstrates a Google-Earth view perspective, by adjusting the height to around 50 meters (high), distance to 1 meter (close). Що дозволяє перспективу, як знято з супутника. ## Відомі проблеми diff --git a/docs/uk/flight_modes_mc/mission.md b/docs/uk/flight_modes_mc/mission.md index 0393ad7f2a..96cf5c7306 100644 --- a/docs/uk/flight_modes_mc/mission.md +++ b/docs/uk/flight_modes_mc/mission.md @@ -31,33 +31,33 @@ They may also be created by a MAVLink API such as [MAVSDK](../robotics/mavsdk.md 1. Якщо місія не збережена, або якщо PX4 завершив виконання всіх команд місії, або якщо [місія не є можливою](#mission-feasibility-checks): - - Якщо літає транспортний засіб, він буде утримувати. - - Якщо посадять транспортний засіб, він буде "чекати". + - Якщо літає транспортний засіб, він буде утримувати. + - Якщо посадять транспортний засіб, він буде "чекати". 2. Якщо місія збережена, а PX4 летить, вона виконає [місію / план польоту](../flying/missions.md) з поточного кроку. - - Пункт `TAKEOFF` трактується як звичайна точка місії. + - Пункт `TAKEOFF` трактується як звичайна точка місії. 3. Якщо місія збережена і PX4 приземлився: - - PX4 виконає [місію/план польоту](../flying/missions.md). - - Якщо місія не має пункту `TAKEOFF`, то PX4 підніме транспортний засіб на мінімальну висоту перед виконанням решти польотного плану з поточного кроку. + - PX4 виконає [місію/план польоту](../flying/missions.md). + - Якщо місія не має пункту `TAKEOFF`, то PX4 підніме транспортний засіб на мінімальну висоту перед виконанням решти польотного плану з поточного кроку. 4. Якщо жодне завдання не збережено, або якщо PX4 завершив виконання всіх команд місії: - - Якщо літає транспортний засіб, він буде утримувати. - - Якщо посадять транспортний засіб, він буде "чекати". + - Якщо літає транспортний засіб, він буде утримувати. + - Якщо посадять транспортний засіб, він буде "чекати". 5. Ви можете вручну змінити поточну команду місії, вибравши її в _QGroundControl_. - :::info - Якщо у вас є команда _Перейти до елементу_ в місії, переміщення до іншого елементу **не** скине лічильник циклу. - Однією з наслідків є те, що якщо ви зміните поточну команду місії на 1, це не призведе до "повного перезапуску" місії. + :::info + Якщо у вас є команда _Перейти до елементу_ в місії, переміщення до іншого елементу **не** скине лічильник циклу. + Однією з наслідків є те, що якщо ви зміните поточну команду місії на 1, це не призведе до "повного перезапуску" місії. ::: 6. Місія скине тільки тоді, коли транспортний засіб буде роззброєний або коли буде завантажена нова місія. - :::tip - Щоб автоматично роззброїти транспортний засіб після посадки, у _QGroundControl_ перейдіть до [Налаштування Транспортного Засобу > Безпека](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/safety.html), перейдіть до _Налаштувань Режиму Посадки_ та позначте прапорець _Роззброювати після_. - Введіть час очікування після посадки перед відброюванням транспортного засобу. + :::tip + Щоб автоматично роззброїти транспортний засіб після посадки, у _QGroundControl_ перейдіть до [Налаштування Транспортного Засобу > Безпека](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/safety.html), перейдіть до _Налаштувань Режиму Посадки_ та позначте прапорець _Роззброювати після_. + Введіть час очікування після посадки перед відброюванням транспортного засобу. ::: diff --git a/docs/uk/flight_modes_mc/throw_launch.md b/docs/uk/flight_modes_mc/throw_launch.md index 7e990f5db3..33477986ec 100644 --- a/docs/uk/flight_modes_mc/throw_launch.md +++ b/docs/uk/flight_modes_mc/throw_launch.md @@ -43,16 +43,16 @@ When throw launch is enabled, the vehicle is initially armed in a "lockdown" sta Окрім того: 1. Носіть засоби безпеки. - Захист для очей та рукавички для роботи рекомендовані. + Захист для очей та рукавички для роботи рекомендовані. 2. Маєте легкий доступний та протестований [вимикач вимкнення](../config/safety.md#kill-switch). - Нагадайте оператору бути уважним та використовувати вимикач аварійного вимкнення за потреби. - Пілоти часто забувають, що транспортні засоби можна замінити, але вони - ні! + Нагадайте оператору бути уважним та використовувати вимикач аварійного вимкнення за потреби. + Пілоти часто забувають, що транспортні засоби можна замінити, але вони - ні! 3. Тестуйте якомога більше без гвинтів. - Утримуйте інструменти для зняття гвинтів пропелерів поруч/легкодоступними. + Утримуйте інструменти для зняття гвинтів пропелерів поруч/легкодоступними. 4. Перевірте цю функцію з принаймні двома людьми — один керує літаком, інший — пультом дистанційного керування. 5. Пам'ятайте, що після кидка точна поведінка літака може бути важко передбачити, оскільки вона сильно залежить від способу кидка. - Іноді воно залишатиметься на місці ідеально, але іноді (наприклад, через великий кочення), воно може відхилятися в один бік під час стабілізації. - Дотримуйтеся безпечної відстані! + Іноді воно залишатиметься на місці ідеально, але іноді (наприклад, через великий кочення), воно може відхилятися в один бік під час стабілізації. + Дотримуйтеся безпечної відстані! Під час першого польоту нового транспортного засобу ми рекомендуємо виконати [Тест запуску без гвинтів (Throw Launch test without propellers)](#throw-launch-pretest) (див. нижче). @@ -65,13 +65,13 @@ When throw launch is enabled, the vehicle is initially armed in a "lockdown" sta 1. Демонтуйте пропелери. 2. Встановіть [COM_THROW_EN](../advanced_config/parameter_reference.md#COM_THROW_EN) на `Увімкнено`. 3. Озброїте літак. - Двигуни не повинні крутитися, але транспортний засіб повинен бути збройований і продовжувати відтворювати мелодію зброювання. + Двигуни не повинні крутитися, але транспортний засіб повинен бути збройований і продовжувати відтворювати мелодію зброювання. 4. Киньте літак приблизно на 2 м у повітря. - Якщо літак не буде кидати достатньо високо, двигуни не ввімкнуться. + Якщо літак не буде кидати достатньо високо, двигуни не ввімкнуться. 5. Двигуни повинні запуститися одразу після перетинання вершини. 6. Увімкніть вимикач вбивства (ідеально, щоб це робив друга особа, яка керує RC). 7. Спіймай дрон. - Не забувайте використовувати захисні рукавички! + Не забувайте використовувати захисні рукавички! ## Запуск з катапульти чи підкиданням @@ -79,12 +79,12 @@ When throw launch is enabled, the vehicle is initially armed in a "lockdown" sta 1. Встановіть [COM_THROW_EN](../advanced_config/parameter_reference.md#COM_THROW_EN) на `Увімкнено`. 2. Озброїте літак. - Пропелери не повинні обертатися, але транспортний засіб повинен бути збройований і продовжувати відтворювати мелодію зброювання. + Пропелери не повинні обертатися, але транспортний засіб повинен бути збройований і продовжувати відтворювати мелодію зброювання. 3. Викиньте літак від себе, вперед і вгору (рекомендується близько 2 м відстані та 2 м вгору). - - Транспортний засіб повинен досягти швидкості [COM_THROW_SPEED](../advanced_config/parameter_reference.md#COM_THROW_SPEED), щоб виявити запуск, яка за замовчуванням встановлена на 5 м/с. - Якщо цю швидкість не досягнуто, двигуни не запустяться, і літак впаде на землю. - - Спробуйте уникати надмірного обертання під час кидка, оскільки це може призвести до відмови дрона або непередбачуваної поведінки. - Точне значення "надмірного обертання" залежить від платформи: наприклад, [PX4Vision](../complete_vehicles_mc/px4_vision_kit.md), яка використовувалася для тестування, все ще вдалося відновитися після 2-3 повних обертань. + - Транспортний засіб повинен досягти швидкості [COM_THROW_SPEED](../advanced_config/parameter_reference.md#COM_THROW_SPEED), щоб виявити запуск, яка за замовчуванням встановлена на 5 м/с. + Якщо цю швидкість не досягнуто, двигуни не запустяться, і літак впаде на землю. + - Спробуйте уникати надмірного обертання під час кидка, оскільки це може призвести до відмови дрона або непередбачуваної поведінки. + Точне значення "надмірного обертання" залежить від платформи: наприклад, [PX4Vision](../complete_vehicles_mc/px4_vision_kit.md), яка використовувалася для тестування, все ще вдалося відновитися після 2-3 повних обертань. 4. Після виявлення швидкості вниз (транспортний засіб досягає свого апексу і починає падати), мотори повинні увімкнутися, і транспортний засіб почне летіти в поточному режимі. ## Параметри diff --git a/docs/uk/flying/geofence.md b/docs/uk/flying/geofence.md index cb3b8138cf..213f80f993 100644 --- a/docs/uk/flying/geofence.md +++ b/docs/uk/flying/geofence.md @@ -43,7 +43,7 @@ Geofence planning is fully documented in [Plan View > GeoFence](https://docs.qgr - Маркер центру зони може бути використаний для переміщення зони у правильне положення. - Маркер на межі кругової зони може бути використаний для зміни радіуса. - Маркери на кутах (вершинах) можуть бути використані для зміни геометрії полігону. - Додаткові вершини створюються шляхом натискання на середину ліній між наявними маркерами. + Додаткові вершини створюються шляхом натискання на середину ліній між наявними маркерами. 5. Use the _Geofence Editor_ to set a fence as an inclusion or exclusion, and to select a fence to edit (**Edit** radio button) or Delete (**Del** button). 6. Додайте стільки зон, скільки забажаєте. 7. Once finished, click on the **Upload** button (top right) to send the fence (along with rally points and mission) to the vehicle. diff --git a/docs/uk/flying/package_delivery_mission.md b/docs/uk/flying/package_delivery_mission.md index 3ff4a91c57..a5d2e0020f 100644 --- a/docs/uk/flying/package_delivery_mission.md +++ b/docs/uk/flying/package_delivery_mission.md @@ -37,9 +37,9 @@ Note that if landed, the next mission item after deployment should be another `W - Щоб скинути посилку під час польоту, установіть відповідну висоту для маршрутної точки (і переконайтеся, що маршрутна точка знаходиться в безпечному місці для скидання посилки). - If you'd like to land the vehicle to make the delivery you will need to change the `Waypoint` to a `Land` mission item. - Do this by selecting the mission item heading, then selecting `Land` in the popup dialog. + Do this by selecting the mission item heading, then selecting `Land` in the popup dialog. - ![Waypoint to Land mission item](../../assets/flying/package_delivery_land_waypoint.png) + ![Waypoint to Land mission item](../../assets/flying/package_delivery_land_waypoint.png) 3. Додайте маршрутну точку на карті (у будь-якому місці) для вивільнення захвату. To change this to a `Gripper Mechanism` select the "Waypoint" heading, and in the popup changing the group to "Advanced", then selecting `Gripper Mechanism`. diff --git a/docs/uk/frames_multicopter/dji_f450_cuav_5nano.md b/docs/uk/frames_multicopter/dji_f450_cuav_5nano.md index 6459c1d75a..f6311a3b29 100644 --- a/docs/uk/frames_multicopter/dji_f450_cuav_5nano.md +++ b/docs/uk/frames_multicopter/dji_f450_cuav_5nano.md @@ -106,52 +106,52 @@ This topic provides full instructions for building the kit and configuring PX4 u 1. Прикріпіть 4 ніжки до нижньої пластини за допомогою наданих гвинтів. - ![Arms to bottom plate](../../assets/airframes/multicopter/dji_f450_cuav_5nano/1_attach_arms_bottom_plate.jpg) + ![Arms to bottom plate](../../assets/airframes/multicopter/dji_f450_cuav_5nano/1_attach_arms_bottom_plate.jpg) 2. Припаяйте ЕСК (електронний регулятор швидкості) до плати, позитивний (червоний) та негативний (чорний). - ![Solder ESCs](../../assets/airframes/multicopter/dji_f450_cuav_5nano/2_solder_esc.jpg) + ![Solder ESCs](../../assets/airframes/multicopter/dji_f450_cuav_5nano/2_solder_esc.jpg) 3. Припаяйте модуль живлення, позитивний (червоний) та негативний (чорний). - ![Solder power module](../../assets/airframes/multicopter/dji_f450_cuav_5nano/3_solder_power_module.jpg) + ![Solder power module](../../assets/airframes/multicopter/dji_f450_cuav_5nano/3_solder_power_module.jpg) 4. Підключіть двигуни до ESC відповідно до їхніх позицій. - ![Plug in motors](../../assets/airframes/multicopter/dji_f450_cuav_5nano/4_plug_in_motors.jpg) + ![Plug in motors](../../assets/airframes/multicopter/dji_f450_cuav_5nano/4_plug_in_motors.jpg) 5. Прикріпіть двигуни до відповідних рук. - ![Attach motors to arms (white)](../../assets/airframes/multicopter/dji_f450_cuav_5nano/5a_attach_motors_to_arms.jpg) - ![Attach motors to arms (red)](../../assets/airframes/multicopter/dji_f450_cuav_5nano/5b_attach_motors_to_arms.jpg) + ![Attach motors to arms (white)](../../assets/airframes/multicopter/dji_f450_cuav_5nano/5a_attach_motors_to_arms.jpg) + ![Attach motors to arms (red)](../../assets/airframes/multicopter/dji_f450_cuav_5nano/5b_attach_motors_to_arms.jpg) 6. Додайте верхню дошку (прикрутіть до верхньої частини ніг). - ![Add top board](../../assets/airframes/multicopter/dji_f450_cuav_5nano/6_add_top_board.jpg) + ![Add top board](../../assets/airframes/multicopter/dji_f450_cuav_5nano/6_add_top_board.jpg) 7. Add damping foam to the _CUAV V5 nano_ flight controller. - ![Damping foam](../../assets/airframes/multicopter/dji_f450_cuav_5nano/7a_attach_cuav5nano.jpg) - ![Damping foam](../../assets/airframes/multicopter/dji_f450_cuav_5nano/7b_attach_cuav5nano.jpg) + ![Damping foam](../../assets/airframes/multicopter/dji_f450_cuav_5nano/7a_attach_cuav5nano.jpg) + ![Damping foam](../../assets/airframes/multicopter/dji_f450_cuav_5nano/7b_attach_cuav5nano.jpg) 8. Прикріпіть приймач FrSky до нижньої плати за допомогою двосторонньої стрічки. - ![Attach FrSky receiver with double-sided tape](../../assets/airframes/multicopter/dji_f450_cuav_5nano/8_attach_frsky.jpg) + ![Attach FrSky receiver with double-sided tape](../../assets/airframes/multicopter/dji_f450_cuav_5nano/8_attach_frsky.jpg) 9. Прикріпіть телеметричний модуль до нижньої плати транспортного засобу за допомогою двосторонньої стрічки. - ![Attach telemetry radio](../../assets/airframes/multicopter/dji_f450_cuav_5nano/9a_telemtry_radio.jpg) - ![Attach telemetry radio](../../assets/airframes/multicopter/dji_f450_cuav_5nano/9b_telemtry_radio.jpg) + ![Attach telemetry radio](../../assets/airframes/multicopter/dji_f450_cuav_5nano/9a_telemtry_radio.jpg) + ![Attach telemetry radio](../../assets/airframes/multicopter/dji_f450_cuav_5nano/9b_telemtry_radio.jpg) 10. Поставте алюмінієві опори на платформу кнопок і прикріпіть GPS. - ![Aluminium standoffs](../../assets/airframes/multicopter/dji_f450_cuav_5nano/10_aluminium_standoffs.jpg) + ![Aluminium standoffs](../../assets/airframes/multicopter/dji_f450_cuav_5nano/10_aluminium_standoffs.jpg) 11. Plug in Telemetry (`TELEM1`), GPS module (`GPS/SAFETY`), RC receiver (`RC`), all 4 ESC’s (`M1-M4`), and the power module (`Power1`) into the flight controller. - ![Attach peripherals to flight controller](../../assets/airframes/multicopter/dji_f450_cuav_5nano/12_fc_attach_periperhals.jpg) + ![Attach peripherals to flight controller](../../assets/airframes/multicopter/dji_f450_cuav_5nano/12_fc_attach_periperhals.jpg) - ::: info - The motor order is defined in the [Airframe Reference > Quadrotor x](../airframes/airframe_reference.md#quadrotor-x) + ::: info + The motor order is defined in the [Airframe Reference > Quadrotor x](../airframes/airframe_reference.md#quadrotor-x) ::: diff --git a/docs/uk/frames_multicopter/dji_f450_cuav_5plus.md b/docs/uk/frames_multicopter/dji_f450_cuav_5plus.md index 0e9d05a9cb..b29a2f70ea 100644 --- a/docs/uk/frames_multicopter/dji_f450_cuav_5plus.md +++ b/docs/uk/frames_multicopter/dji_f450_cuav_5plus.md @@ -108,53 +108,53 @@ This topic provides full instructions for building the kit and configuring PX4 u 1. Прикріпіть 4 ніжки до нижньої пластини за допомогою наданих гвинтів. - ![Arms to bottom plate](../../assets/airframes/multicopter/dji_f450_cuav_5plus/1_attach_arms_bottom_plate.jpg) + ![Arms to bottom plate](../../assets/airframes/multicopter/dji_f450_cuav_5plus/1_attach_arms_bottom_plate.jpg) 2. Припаяйте ЕСК (електронний регулятор швидкості) до плати, позитивний (червоний) та негативний (чорний). - ![Solder ESCs](../../assets/airframes/multicopter/dji_f450_cuav_5plus/2_solder_esc.jpg) + ![Solder ESCs](../../assets/airframes/multicopter/dji_f450_cuav_5plus/2_solder_esc.jpg) 3. Припаяйте модуль живлення, позитивний (червоний) та негативний (чорний). - ![Solder power module](../../assets/airframes/multicopter/dji_f450_cuav_5plus/3_solder_power_module.jpg) + ![Solder power module](../../assets/airframes/multicopter/dji_f450_cuav_5plus/3_solder_power_module.jpg) 4. Підключіть двигуни до ESC відповідно до їхніх позицій. - ![Plug in motors](../../assets/airframes/multicopter/dji_f450_cuav_5plus/4_plug_in_motors.jpg) + ![Plug in motors](../../assets/airframes/multicopter/dji_f450_cuav_5plus/4_plug_in_motors.jpg) 5. Прикріпіть двигуни до відповідних рук. - ![Attach motors to arms (white)](../../assets/airframes/multicopter/dji_f450_cuav_5plus/5a_attach_motors_to_arms.jpg) - ![Attach motors to arms (red)](../../assets/airframes/multicopter/dji_f450_cuav_5plus/5b_attach_motors_to_arms.jpg) + ![Attach motors to arms (white)](../../assets/airframes/multicopter/dji_f450_cuav_5plus/5a_attach_motors_to_arms.jpg) + ![Attach motors to arms (red)](../../assets/airframes/multicopter/dji_f450_cuav_5plus/5b_attach_motors_to_arms.jpg) 6. Додайте верхню дошку (прикрутіть до верхньої частини ніг). - ![Add top board](../../assets/airframes/multicopter/dji_f450_cuav_5plus/6_add_top_board.jpg) + ![Add top board](../../assets/airframes/multicopter/dji_f450_cuav_5plus/6_add_top_board.jpg) 7. Додайте двосторонній скотч (3M) до контролера польоту CUAV V5+ (він має внутрішнє гасіння вібрацій, тому використовувати піну не потрібно). - ![Tape CUAV v5+](../../assets/airframes/multicopter/dji_f450_cuav_5plus/7_attach_cuav5plus.jpg) + ![Tape CUAV v5+](../../assets/airframes/multicopter/dji_f450_cuav_5plus/7_attach_cuav5plus.jpg) 8. Прикріпіть приймач FrSky до нижньої плати за допомогою двосторонньої стрічки. - ![Attach FrSky receiver with double-sided tape](../../assets/airframes/multicopter/dji_f450_cuav_5plus/8_attach_frsky.jpg) + ![Attach FrSky receiver with double-sided tape](../../assets/airframes/multicopter/dji_f450_cuav_5plus/8_attach_frsky.jpg) 9. Прикріпіть телеметричний модуль до нижньої плати транспортного засобу за допомогою двосторонньої стрічки. - ![Attach telemetry radio](../../assets/airframes/multicopter/dji_f450_cuav_5plus/9a_telemtry_radio.jpg) - ![Attach telemetry radio](../../assets/airframes/multicopter/dji_f450_cuav_5plus/9b_telemtry_radio.jpg) + ![Attach telemetry radio](../../assets/airframes/multicopter/dji_f450_cuav_5plus/9a_telemtry_radio.jpg) + ![Attach telemetry radio](../../assets/airframes/multicopter/dji_f450_cuav_5plus/9b_telemtry_radio.jpg) 10. Поставте алюмінієві опори на платформу кнопок. 11. Plug in Telemetry (`TELEM1`) and GPS module (`GPS/SAFETY`) to the flight controller. - ![Attach GPS](../../assets/airframes/multicopter/dji_f450_cuav_5plus/11a_gps.jpg) - ![Attach GPS](../../assets/airframes/multicopter/dji_f450_cuav_5plus/11b_gps.jpg) + ![Attach GPS](../../assets/airframes/multicopter/dji_f450_cuav_5plus/11a_gps.jpg) + ![Attach GPS](../../assets/airframes/multicopter/dji_f450_cuav_5plus/11b_gps.jpg) 12. Plug in the RC receiver (`RC`), all 4 ESC’s (`M1-M4`), and the power module (`Power1`) into the flight controller. - ![Attach peripherals to flight controller](../../assets/airframes/multicopter/dji_f450_cuav_5plus/12_fc_attach_periperhals.jpg) + ![Attach peripherals to flight controller](../../assets/airframes/multicopter/dji_f450_cuav_5plus/12_fc_attach_periperhals.jpg) - ::: info - The motor order is defined in the [Airframe Reference > Quadrotor x](../airframes/airframe_reference.md#quadrotor-x) + ::: info + The motor order is defined in the [Airframe Reference > Quadrotor x](../airframes/airframe_reference.md#quadrotor-x) ::: diff --git a/docs/uk/frames_multicopter/holybro_qav250_pixhawk4_mini.md b/docs/uk/frames_multicopter/holybro_qav250_pixhawk4_mini.md index 7b7b54ed99..37a4d5bcd7 100644 --- a/docs/uk/frames_multicopter/holybro_qav250_pixhawk4_mini.md +++ b/docs/uk/frames_multicopter/holybro_qav250_pixhawk4_mini.md @@ -103,78 +103,78 @@ Estimated time to assemble frame is 2 hours and 1.5 hours installing the autopil 1. Прикріпіть руки до плати кнопки за допомогою гвинтів довжиною 15 мм, як показано: - ![QAV250 Add arms to button plate](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/1_button_plate_add_arms.jpg) + ![QAV250 Add arms to button plate](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/1_button_plate_add_arms.jpg) 2. Покладіть коротку пластину над руками - ![QAV250 Add short plate over arms](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/2_short_plate_over_arms.jpg) + ![QAV250 Add short plate over arms](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/2_short_plate_over_arms.jpg) 3. Покладіть гайки на відносно 15 мм гвинти (показано в наступному кроці) 4. Insert the plastic screws into the indicated holes (note that this part of the frame faces down when the vehicle is complete). - ![QAV250 Add nuts to 15mm screws and put plastic nuts in holes](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/3_nuts_screws_holes.jpg) + ![QAV250 Add nuts to 15mm screws and put plastic nuts in holes](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/3_nuts_screws_holes.jpg) 5. Add the plastic nuts to the screws (turn over, as shown) - ![QAV250 Plastic nuts onto screws](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/4_plastic_nuts_on_screws.jpg) + ![QAV250 Plastic nuts onto screws](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/4_plastic_nuts_on_screws.jpg) 6. Lower the power module over the plastic screws and then add the plastics standoffs - ![QAV250 Add power module and standoffs](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/5_power_module_on_screws.jpg) + ![QAV250 Add power module and standoffs](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/5_power_module_on_screws.jpg) 7. Put the flight controller plate on the standoffs (over the power module) - ![QAV250 Add flight controller plate](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/6_flight_controller_plate.jpg) + ![QAV250 Add flight controller plate](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/6_flight_controller_plate.jpg) 8. Підключіть двигуни. Двигуни мають стрілку, що показує напрямок обертання. - ![QAV250 Add motors](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/7_motors.jpg) + ![QAV250 Add motors](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/7_motors.jpg) 9. Use double sided tape from kit to attach the _Pixhawk 4 Mini_ to the flight controller plate. - ![QAV250 Add doublesided tape](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/8_double_sided_tape_controller.jpg) + ![QAV250 Add doublesided tape](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/8_double_sided_tape_controller.jpg) 10. Connect the power module's "power" cable to _Pixhawk 4 mini_. - ![QAV250 Power Pixhawk](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/9_power_module_power_pixhawk.jpg) + ![QAV250 Power Pixhawk](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/9_power_module_power_pixhawk.jpg) 11. Attach the aluminium standoffs to the button plate - ![QAV250 Aluminium standoffs](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/10_aluminium_standoffs.jpg) + ![QAV250 Aluminium standoffs](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/10_aluminium_standoffs.jpg) 12. Підключіть ESC з моторами та утримуйте. На цьому зображенні показаний порядок розташування двигунів та напрямок обертання. - ![QAV250 Connect ESCs](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/11_escs.jpg) + ![QAV250 Connect ESCs](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/11_escs.jpg) - Підключіть двигуни на ESC, переконайтеся, що двигуни обертаються у правильному напрямку, якщо двигун обертається у протилежний бік, змініть кабель A на плату C та C на плату A ESC. + Підключіть двигуни на ESC, переконайтеся, що двигуни обертаються у правильному напрямку, якщо двигун обертається у протилежний бік, змініть кабель A на плату C та C на плату A ESC. - :::warning - Test motor directions with propellers removed. + :::warning + Test motor directions with propellers removed. ::: - ![QAV250 Connect ESCs to Power](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/11b_escs.jpg) + ![QAV250 Connect ESCs to Power](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/11b_escs.jpg) 13. Підключіть кабелі сигналу ESC до виходів PWM Pixhawk у правильному порядку (див. попереднє зображення) - ![QAV250 Connect ESCs to Pixhawk PWM](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/12_escs_pixhawk.jpg) + ![QAV250 Connect ESCs to Pixhawk PWM](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/12_escs_pixhawk.jpg) 14. Підключіть приймач. - - Якщо використовуєте приймач PPM, підключіть його до порту PPM. + - Якщо використовуєте приймач PPM, підключіть його до порту PPM. - ![QAV250 Connect Receiver PPM](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/13_rc_receiver_ppm.jpg) + ![QAV250 Connect Receiver PPM](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/13_rc_receiver_ppm.jpg) - - Якщо використовується приймач SBUS, підключіть його до порту RC IN + - Якщо використовується приймач SBUS, підключіть його до порту RC IN - ![QAV250 Connect Receiver SBUS](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/13_rc_receiver_sbus.jpg) + ![QAV250 Connect Receiver SBUS](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/13_rc_receiver_sbus.jpg) 15. Підключіть модуль телеметрії. Вставте модуль за допомогою двостворчастої стрічки та підключіть його до порту телеметрії. - ![QAV250 Telemetry module](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/14_telemetry.jpg) + ![QAV250 Telemetry module](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/14_telemetry.jpg) 16. Підключіть модуль GPS - ![QAV250 Connect GPS](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/15a_connect_gps.jpg) + ![QAV250 Connect GPS](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/15a_connect_gps.jpg) - Прикріпіть модуль на верхню плату (використовуючи наданий стрічку 3M, або пастою). Потім покладіть верхню плиту на стойки, як показано + Прикріпіть модуль на верхню плату (використовуючи наданий стрічку 3M, або пастою). Потім покладіть верхню плиту на стойки, як показано - ![QAV250 Connect GPS](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/15b_attach_gps.jpg) + ![QAV250 Connect GPS](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/15b_attach_gps.jpg) 17. Останнім "обов'язковим" кроком зборки є додавання липучки для утримання батареї - ![QAV250 Velcro battery strap](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/16_velcro_strap.jpg) + ![QAV250 Velcro battery strap](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/16_velcro_strap.jpg) The "basic" frame build is now complete (though if you need them, you can find more information about connecting components in the [Pixhawk 4 Wiring Quickstart](../assembly/quick_start_pixhawk4.md)). @@ -189,17 +189,17 @@ If you have the "basic" version of the kit, you can now jump ahead to instructio Кроки для встановлення комплекту: 1. Install the camera bracket on the frame - ![Camera Connection](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_camera_bracket.jpg) + ![Camera Connection](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_camera_bracket.jpg) 2. Install the camera on the bracket - ![Camera on Bracket](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_camera_on_bracket.jpg) + ![Camera on Bracket](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_camera_on_bracket.jpg) 3. The power module on the complete kit comes with wiring ready to connect the Video Transmitter and Camera: - ![Connecting FPV](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_connection_board.jpg) - - Attach the camera connector - ![Camera Connection](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_camera_connection.jpg) - The wires are: blue=voltage sensor, yellow=video out, black=ground, red=+voltage. - - Connect the Video Transmitter (VTX) connector - ![Video Transmitter Connection](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_video_transmitter_connection.jpg) - The wires are: yellow=video out, black=ground, red=+voltage. + ![Connecting FPV](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_connection_board.jpg) + - Attach the camera connector + ![Camera Connection](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_camera_connection.jpg) + The wires are: blue=voltage sensor, yellow=video out, black=ground, red=+voltage. + - Connect the Video Transmitter (VTX) connector + ![Video Transmitter Connection](../../assets/airframes/multicopter/qav250_holybro_pixhawk4_mini/fpv_video_transmitter_connection.jpg) + The wires are: yellow=video out, black=ground, red=+voltage. 4. Закріпіть відеопередавач і плату OSD на рамку за допомогою стрічки. :::info diff --git a/docs/uk/frames_multicopter/holybro_s500_v2_pixhawk4.md b/docs/uk/frames_multicopter/holybro_s500_v2_pixhawk4.md index 22cf0615c3..f649cb2b4e 100644 --- a/docs/uk/frames_multicopter/holybro_s500_v2_pixhawk4.md +++ b/docs/uk/frames_multicopter/holybro_s500_v2_pixhawk4.md @@ -115,11 +115,11 @@ No LiPo battery is included. Оцінкований час для збирання - 90 хвилин, близько 45 хвилин на збірку рами та 45 хвилин на встановлення та налаштування автопілота в QGroundControl. 1. Збірка шасі. - Ми збираємося почати зі складання шасі на вертикальний стовп. Відкрутіть гвинти стійки посадки та вставте вертикальний стовп, як показано нижче. + Ми збираємося почати зі складання шасі на вертикальний стовп. Відкрутіть гвинти стійки посадки та вставте вертикальний стовп, як показано нижче. - ![Figure 1](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig1.jpg) + ![Figure 1](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig1.jpg) - ![Figure 2](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig2.jpg) + ![Figure 2](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig2.jpg) 2. Зібрати плату управління живленням до стільникового шасі. Закрутіть шасі з вертикальним полем на повністю зібрану плату управління живленням. @@ -132,132 +132,132 @@ No LiPo battery is included. ![Figure 4](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig4.jpg) 1. Зберігайте зброю на плату керування живленням. - Прикріпіть руку до плати управління живленням. + Прикріпіть руку до плати управління живленням. - ![Figure 6](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig7.jpg) + ![Figure 6](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig7.jpg) - ![Figure 7](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig8.jpg) + ![Figure 7](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig8.jpg) - Використовуйте гвинти M2 5X6 по 2 штуки в кожній руці. - Вставте гвинти знизу пластини. + Використовуйте гвинти M2 5X6 по 2 штуки в кожній руці. + Вставте гвинти знизу пластини. - ![Figure 8](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig9.jpg) + ![Figure 8](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig9.jpg) - Переконайтеся, що кабелі ESC прокладені через середину руки. + Переконайтеся, що кабелі ESC прокладені через середину руки. - ![Figure 9](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig91.jpg) + ![Figure 9](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig91.jpg) 2. Assemble the 8_3 2.54mm pitch Horizontal Pin to the 10 to 10 pin cable (PWM) to the Power Management Board. - Connect the 10 to 10 pin cable (PWM) to the 8_3 2.54mm pitch Horizontal Pin. + Connect the 10 to 10 pin cable (PWM) to the 8_3 2.54mm pitch Horizontal Pin. - ![Figure 10](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig10.jpg) + ![Figure 10](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig10.jpg) - Виріжте шматок стрічки 3M та прикріпіть його до нижньої частини горизонтального штиря: + Виріжте шматок стрічки 3M та прикріпіть його до нижньої частини горизонтального штиря: - ![Figure 11](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig11.jpg) + ![Figure 11](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig11.jpg) - Stick the Horizontal Pin to the Power Management Board: + Stick the Horizontal Pin to the Power Management Board: - ![Figure 12](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig12.jpg) + ![Figure 12](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig12.jpg) - ![Figure 13](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig13.jpg) + ![Figure 13](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig13.jpg) 3. Зберіть двигуни на руки. Для цього нам знадобляться 16 шурупів M3X7, 4 мотори та 4 руки. - Встановіть двигуни в кожну руку, пропустіть гвинт через дно руки: + Встановіть двигуни в кожну руку, пропустіть гвинт через дно руки: - ![Figure 14](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig14.jpg) + ![Figure 14](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig14.jpg) - ![Figure 15](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig15.jpg) + ![Figure 15](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig15.jpg) - Після того, як 4 мотори встановлені на руку, візьміть кабелі (червоний, синій, чорний) і пропустіть їх через різьбу руки. - 3 кабелі, які мають колірну маркування, підключаються до ESC. + Після того, як 4 мотори встановлені на руку, візьміть кабелі (червоний, синій, чорний) і пропустіть їх через різьбу руки. + 3 кабелі, які мають колірну маркування, підключаються до ESC. - ![Figure 16](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig16.jpg) + ![Figure 16](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig16.jpg) - ![Figure 17](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig17.jpg) + ![Figure 17](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig17.jpg) 4. Монтаж GPS на рамці. - Для цього нам знадобиться GPS Pixhawk 4 та монтажна плита. + Для цього нам знадобиться GPS Pixhawk 4 та монтажна плита. - ![GPS Parts](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_gpskit.png) + ![GPS Parts](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_gpskit.png) - Встановіть мачту GPS на задню частину дошки, використовуйте 4 гвинти: + Встановіть мачту GPS на задню частину дошки, використовуйте 4 гвинти: - ![Figure 18](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig18.jpg) + ![Figure 18](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig18.jpg) - ![Figure 19](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig19.jpg) + ![Figure 19](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig19.jpg) - Використовуйте стрічку та приклейте GPS на верх мачти GPS: + Використовуйте стрічку та приклейте GPS на верх мачти GPS: - ![Figure 20](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig20.jpg) + ![Figure 20](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig20.jpg) 5. Вставте FrSky на дошку. Наклейте FrSky за допомогою двосторонньої стрічки (3M) на нижню плату. - Прикріпіть FrSky до рами: + Прикріпіть FrSky до рами: - ![Figure 21](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig21.jpg) + ![Figure 21](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig21.jpg) - ![Figure 22](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig22.jpg) + ![Figure 22](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig22.jpg) 6. Прикріпіть телеметрію до рами. - Наступним кроком є взяти телеметричне радіо Holybro та прикріпити його до рами, використовуйте стрічку 3M. + Наступним кроком є взяти телеметричне радіо Holybro та прикріпити його до рами, використовуйте стрічку 3M. - ![Figure 23](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig23.jpg) + ![Figure 23](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig23.jpg) - ![Figure 24](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig24.jpg) + ![Figure 24](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig24.jpg) - Цей збірний вузол прикріплений всередину рами, спрямований на зовнішню сторону вперед автомобіля. - На нижче наведеному зображенні показано радіо, яке знаходиться всередині нижньої частини рами. + Цей збірний вузол прикріплений всередину рами, спрямований на зовнішню сторону вперед автомобіля. + На нижче наведеному зображенні показано радіо, яке знаходиться всередині нижньої частини рами. - ![Figure 25](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig25.jpg) + ![Figure 25](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig25.jpg) 7. Монтаж Pixhawk 4 на плату. - Використовуйте двосторонній скотч для кріплення Pixhawk 4 до центральної пластини: + Використовуйте двосторонній скотч для кріплення Pixhawk 4 до центральної пластини: - ![Figure 26](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig26.jpg) + ![Figure 26](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig26.jpg) - ![Figure 27](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig27.jpg) + ![Figure 27](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig27.jpg) - ![Figure 28](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig28.jpg) + ![Figure 28](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig28.jpg) - Наступним кроком є монтаж Pixhawk 4 на плату до рами. - Для цього нам знадобляться винти M2 5X6. - Вирівняйте пластину з рамою та вставте гвинти. - Перед тим як встановлювати плату, ми рекомендуємо накласти стрічку на модуль живлення (таким чином він буде щільно фіксуватися). + Наступним кроком є монтаж Pixhawk 4 на плату до рами. + Для цього нам знадобляться винти M2 5X6. + Вирівняйте пластину з рамою та вставте гвинти. + Перед тим як встановлювати плату, ми рекомендуємо накласти стрічку на модуль живлення (таким чином він буде щільно фіксуватися). - ![Figure 29](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig29.jpg) + ![Figure 29](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig29.jpg) - ![Figure 30](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig30.jpg) + ![Figure 30](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig30.jpg) 8. Збирання кронштейну батареї до рами. - Для цього нам знадобляться винти M2 5X6 та кріплення батареї: + Для цього нам знадобляться винти M2 5X6 та кріплення батареї: - ![Figure 31](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig31.jpg) + ![Figure 31](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig31.jpg) - Вставте довгі важі в маленькі кільця: + Вставте довгі важі в маленькі кільця: - ![Figure 32](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig32.png) + ![Figure 32](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig32.png) - ![Figure 33](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig33.png) + ![Figure 33](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig33.png) - Додайте це до рами, переконайтеся, що всі чотири сторони вирівняні для вставки гвинтів: + Додайте це до рами, переконайтеся, що всі чотири сторони вирівняні для вставки гвинтів: - ![Figure 34](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig34.jpg) + ![Figure 34](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig34.jpg) - Зберіть маленьку пластину до ніг та відкрутіть по всіх чотирьох сторонах. + Зберіть маленьку пластину до ніг та відкрутіть по всіх чотирьох сторонах. - ![Figure 35](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig35.jpg) + ![Figure 35](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig35.jpg) - Останнім кроком є закріплення плати: + Останнім кроком є закріплення плати: - ![Figure 36](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig36.jpg) + ![Figure 36](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig36.jpg) 9. Підключення Pixhawk 4. Pixhawk 4, який має кілька різних дротів та з'єднань з ним. - Нижче наведено зображення кожного дроту, який потрібен з Pixhawk, і його вигляд підключення. + Нижче наведено зображення кожного дроту, який потрібен з Pixhawk, і його вигляд підключення. 10. Підключіть модуль телеметрії та GPS до контролера польоту, як показано на рисунку 37; підключіть RC приймач, всі 4 ESC до контролера польоту, а також модуль живлення. - ![Figure 37](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig37.png) + ![Figure 37](../../assets/airframes/multicopter/s500_holybro_pixhawk4/s500_fig37.png) Після повної збірки комплект виглядає як показано нижче: diff --git a/docs/uk/frames_multicopter/holybro_x500V2_pixhawk5x.md b/docs/uk/frames_multicopter/holybro_x500V2_pixhawk5x.md index d0156e13bb..4a822bd2ff 100644 --- a/docs/uk/frames_multicopter/holybro_x500V2_pixhawk5x.md +++ b/docs/uk/frames_multicopter/holybro_x500V2_pixhawk5x.md @@ -93,92 +93,92 @@ _Figure 1_: X500 V2 ARF Kit what's inside Орієнтовний час збірки - 55 хвилин (25 хвилин на раму, 30 хвилин на встановлення/налаштування автопілота) 1. Start by assembling the payload & battery holder. - Втисніть гумки в захоплювачі (не використовуйте гострі предмети, щоб їх втиснути в них!). - Далі пропустіть тримачі через планки тримача з основами тримача батарей, як показано на рисунку 3. + Втисніть гумки в захоплювачі (не використовуйте гострі предмети, щоб їх втиснути в них!). + Далі пропустіть тримачі через планки тримача з основами тримача батарей, як показано на рисунку 3. - ![Landing Figure 1: Components](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/payload_holder_required_stuff.png) + ![Landing Figure 1: Components](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/payload_holder_required_stuff.png) - _Figure 2_: Payload holder components + _Figure 2_: Payload holder components - ![Landing Figure 2: Assembled](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/payload_holder_assembled.png) + ![Landing Figure 2: Assembled](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/payload_holder_assembled.png) - _Figure 3_: Payload holder assembled + _Figure 3_: Payload holder assembled 2. Наступним кроком буде прикріплення нижньої пластини до тримача вантажу. - Вам знадобляться деталі, як показано на рисунку 4. - Потім встановіть основу для розподільної плати живлення, використовуючи нейлонові гайки, як зображено на Рис. 5. - Нарешті, використовуючи 8 шестигранних гвинтів, ви можете приєднати нижню пластину до тримача навантаження (Рисунок 7) + Вам знадобляться деталі, як показано на рисунку 4. + Потім встановіть основу для розподільної плати живлення, використовуючи нейлонові гайки, як зображено на Рис. 5. + Нарешті, використовуючи 8 шестигранних гвинтів, ви можете приєднати нижню пластину до тримача навантаження (Рисунок 7) - ![Materials to attach bottom plate](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/topplate_holder_stuff.png) + ![Materials to attach bottom plate](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/topplate_holder_stuff.png) - _Figure 4_: Needed Materials + _Figure 4_: Needed Materials - ![PDB mountbase](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/powerboard-mountbase.png) + ![PDB mountbase](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/powerboard-mountbase.png) - _Figure 5_: PDB mount base + _Figure 5_: PDB mount base - ![PDB attachment](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/pdb_bottom_plate.png) + ![PDB attachment](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/pdb_bottom_plate.png) - _Figure 6_: Mounted pdb with nylon nuts + _Figure 6_: Mounted pdb with nylon nuts - ![Bottom plate Final](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/bottom_plate_holder_final.png) + ![Bottom plate Final](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/bottom_plate_holder_final.png) - _Figure 7_: Mounted Plate on payload holder + _Figure 7_: Mounted Plate on payload holder 3. Давайте зберемо речі, необхідні для монтажу посадкового шасі, як на рисунку 8. - Використовуйте гвинти, щоб приєднати посадкові шасі до нижньої пластини. - Також потрібно відкрити три шестигранних гвинти на кожній з ніжок, щоб ви могли вставити їх у вуглецеві труби. - Не забудьте знову їх затягнути. + Використовуйте гвинти, щоб приєднати посадкові шасі до нижньої пластини. + Також потрібно відкрити три шестигранних гвинти на кожній з ніжок, щоб ви могли вставити їх у вуглецеві труби. + Не забудьте знову їх затягнути. - ![Attach Landing Gear Stuff](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/landing_gear_materials.png) + ![Attach Landing Gear Stuff](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/landing_gear_materials.png) - _Figure 8_: Required parts for landing gear attachment + _Figure 8_: Required parts for landing gear attachment - ![Lanfing great to bottom plate](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/attached_landing_gear.png) + ![Lanfing great to bottom plate](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/attached_landing_gear.png) - _Figure 9_: Landing gear attachment to the body + _Figure 9_: Landing gear attachment to the body 4. Зараз ми зберемо все оснащення, щоб встановити верхню пластину. - Прошу звернути увагу, що номери моторів на кронштейнах відповідають тим, що згадані на верхній платі. - На щастя, мотори встановлені, а ESCs були з'єднані заздалегідь. - Почніть, проходячи через всі гвинти, так як ви зафіксували кронштейни на їхніх власних місцях (Вони мають направляючий елемент, як показано на рисунку 11, щоб переконатися, що вони на місці), і трохи підтягніть всі нейлонові гайки. - Потім ви зможете підключити роз'єми живлення XT30 до плати живлення. - Пам'ятайте, що дроти сигналу повинні бути проведені через верхню пластину так, що ми зможемо пізніше їх підключити до Pixhawk. + Прошу звернути увагу, що номери моторів на кронштейнах відповідають тим, що згадані на верхній платі. + На щастя, мотори встановлені, а ESCs були з'єднані заздалегідь. + Почніть, проходячи через всі гвинти, так як ви зафіксували кронштейни на їхніх власних місцях (Вони мають направляючий елемент, як показано на рисунку 11, щоб переконатися, що вони на місці), і трохи підтягніть всі нейлонові гайки. + Потім ви зможете підключити роз'єми живлення XT30 до плати живлення. + Пам'ятайте, що дроти сигналу повинні бути проведені через верхню пластину так, що ми зможемо пізніше їх підключити до Pixhawk. - + - _Figure 10_: Connecting arms needed materials. + _Figure 10_: Connecting arms needed materials. - + - _Figure 11_: Guide for the arms mount + _Figure 11_: Guide for the arms mount 5. Для затягування всіх 16 гвинтів і гайок використовуйте як шестигранний ключ, так і гайковий ключ. - ![Top plae mounted](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/finalized_top_plate.png) + ![Top plae mounted](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/finalized_top_plate.png) - _Figure 12_: Mounted top plate + _Figure 12_: Mounted top plate 6. Наступним кроком ви можете закріпити свій pixhawk на верхній плиті, використовуючи наклейки. - Рекомендується мати напрямок стрілки вашого Pixhawk таким же, як зазначено на верхній плиті. + Рекомендується мати напрямок стрілки вашого Pixhawk таким же, як зазначено на верхній плиті. - ![Flight controller mounting stickers](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/pixhawk5x_stickertapes.png) + ![Flight controller mounting stickers](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk5x/pixhawk5x_stickertapes.png) - _Figure 13_: Sticker tapes on Pixhawk + _Figure 13_: Sticker tapes on Pixhawk 7. Якщо ви хочете встановити GPS на плату компаньйона-комп'ютера, тепер ви можете закріпити кріплення GPS на ній за допомогою 4 гвинтів і гайок. - + - _Figure 14_: Secure GPS mount onto companion plate + _Figure 14_: Secure GPS mount onto companion plate 8. За допомогою скотча приклейте GPS до верхньої частини GPS-щогли і встановіть її на щоглу. - Переконайтеся, що стрілка на gps вказує вперед (зображення 15). + Переконайтеся, що стрілка на gps вказує вперед (зображення 15). - + - _Figure 15_: GPS and mast + _Figure 15_: GPS and mast 9. Наразі ви можете підключити інтерфейси Pixhawk, такі як телеметрійне радіо до 'TELEM1' та відповідно кабелі сигналів для моторів. diff --git a/docs/uk/frames_multicopter/holybro_x500_pixhawk4.md b/docs/uk/frames_multicopter/holybro_x500_pixhawk4.md index 60ab2730a5..3cf16c139d 100644 --- a/docs/uk/frames_multicopter/holybro_x500_pixhawk4.md +++ b/docs/uk/frames_multicopter/holybro_x500_pixhawk4.md @@ -81,125 +81,125 @@ Additionally you will need a battery and receiver ([compatible radio system](../ Час збірки (приблизно): 3.75 години (180 хвилин на раму, 45 хвилин на встановлення/налаштування автопілота) 1. Почніть зі збирання шасі. - Відкрутіть гвинти шасі і вставте вертикальну стійку (зобр. 1 і 2). + Відкрутіть гвинти шасі і вставте вертикальну стійку (зобр. 1 і 2). - ![Landing Figure 1: Components](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_step_1_fig1.jpg) + ![Landing Figure 1: Components](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_step_1_fig1.jpg) - _Figure 2_: Landing gear components + _Figure 2_: Landing gear components - ![Landing Figure 2: Assembled](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_step_1_fig2.jpg) + ![Landing Figure 2: Assembled](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_step_1_fig2.jpg) - _Figure 2_: Landing gear assembled + _Figure 2_: Landing gear assembled 2. Потім просуньте 4 кронштейни через 4 основи двигуна, як показано на малюнку 3. - Переконайтеся, що штанги злегка виступають з основи і є однаковими на всіх 4-х плечах, а також переконайтеся, що дроти електродвигуна спрямовані назовні. + Переконайтеся, що штанги злегка виступають з основи і є однаковими на всіх 4-х плечах, а також переконайтеся, що дроти електродвигуна спрямовані назовні. - ![Attach arms to motor bases](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_step_2_fig3.png) + ![Attach arms to motor bases](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_step_2_fig3.png) - _Figure 3_: Attach arms to motor bases + _Figure 3_: Attach arms to motor bases 3. Вставте 4 нейлонові гвинти та нейлонові стійки і прикріпіть модуль живлення PM07 до нижньої панелі за допомогою 4 нейлонових гайок, як показано на зображенні 4. - ![Attach power module](../../assets/airframes/multicopter/x500_holybro_pixhawk4/power_module.jpg) + ![Attach power module](../../assets/airframes/multicopter/x500_holybro_pixhawk4/power_module.jpg) - _Figure 4_: Attach power module + _Figure 4_: Attach power module 4. Протягніть 4 двигуни ESC через кожне з кронштейнів і підключіть трижильні дроти до двигунів, як показано на зображенні 5. - + - _Figure 5_: Connect motors + _Figure 5_: Connect motors 5. Connect the ESCs power wires onto the power module PM07, black->black and red->red, ESC PWM signal wires goes to "FMU-PWM-Out". - Переконайтеся, що ви підключили дроти ШІМ ESC двигуна в правильному порядку. - Номер двигуна повітряного корпусу дивіться на зображенні 7 і підключіть його до відповідного номера на платі PM07. + Переконайтеся, що ви підключили дроти ШІМ ESC двигуна в правильному порядку. + Номер двигуна повітряного корпусу дивіться на зображенні 7 і підключіть його до відповідного номера на платі PM07. - ![ESC power module and signal wiring](../../assets/airframes/multicopter/x500_holybro_pixhawk4/pm07_pwm.jpg) - _Figure 7_: ESC power module and signal wiring + ![ESC power module and signal wiring](../../assets/airframes/multicopter/x500_holybro_pixhawk4/pm07_pwm.jpg) + _Figure 7_: ESC power module and signal wiring - Колір на верхній частині двигуна вказує на напрямок обертання (зображення 7-1), чорний кінчик - за годинниковою стрілкою, а білий - проти годинникової стрілки. - Переконайтеся, що при виборі напрямку двигуна ви дотримуєтесь орієнтира px4 quadrotor x airframe (зображення 7-2). + Колір на верхній частині двигуна вказує на напрямок обертання (зображення 7-1), чорний кінчик - за годинниковою стрілкою, а білий - проти годинникової стрілки. + Переконайтеся, що при виборі напрямку двигуна ви дотримуєтесь орієнтира px4 quadrotor x airframe (зображення 7-2). - + - _Figure 7_: Motor order/direction diagram + _Figure 7_: Motor order/direction diagram - + - _Figure 7-1_: Motor direction + _Figure 7-1_: Motor direction 6. Підключіть 10-контактні кабелі до FMU-PWM-in, а 6-контактні - до PWR1 на модулі живлення PM07. - ![Flight controller/Power module PWM and Power connections](../../assets/airframes/multicopter/x500_holybro_pixhawk4/pm07_cable.jpg) + ![Flight controller/Power module PWM and Power connections](../../assets/airframes/multicopter/x500_holybro_pixhawk4/pm07_cable.jpg) - _Figure 8_: Power module PWM and power wiring + _Figure 8_: Power module PWM and power wiring 7. Якщо ви хочете встановити GPS на верхній панелі, то тепер ви можете закріпити кріплення GPS на верхній панелі за допомогою 4 гвинтів і гайок. - + - _Figure 9_: Secure GPS mount onto top plate + _Figure 9_: Secure GPS mount onto top plate 8. Протягніть кабелі PM07 через верхню пластину. - З'єднайте верхню і нижню пластини за допомогою 4 U-подібних нейлонових ременів, гвинтів і гайок з кожного боку, переконайтеся, що кабелі ESC двигуна знаходяться всередині U-подібних нейлонових ременів, як показано на зображенні 10, гайки не затягуйте. + З'єднайте верхню і нижню пластини за допомогою 4 U-подібних нейлонових ременів, гвинтів і гайок з кожного боку, переконайтеся, що кабелі ESC двигуна знаходяться всередині U-подібних нейлонових ременів, як показано на зображенні 10, гайки не затягуйте. - + - _Figure 10-1_: Feed power module cables through top plate + _Figure 10-1_: Feed power module cables through top plate - + - _Figure 10-2_: Connecting top and bottom plate + _Figure 10-2_: Connecting top and bottom plate 9. Трохи всуньте трубки кронштейнів у раму і переконайтеся, що величина виступу (червоний квадрат на зображенні 11) є однаковою на всіх 4-х кронштейнах. - Переконайтеся, що всі двигуни спрямовані прямо вгору, а потім затягніть усі гайки та гвинти. + Переконайтеся, що всі двигуни спрямовані прямо вгору, а потім затягніть усі гайки та гвинти. - ![Arms 3](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_fig16.jpg) + ![Arms 3](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_fig16.jpg) 10. Вставте прокладки для підвісів у 4 підвіси та закріпіть їх на нижній пластині за допомогою 8 шестигранних гвинтів (Зображення 11). - Отвори для гвинтів позначені білою стрілкою на зображенні 12. - Ми рекомендуємо нахилити дрон убік, щоб полегшити встановлення. + Отвори для гвинтів позначені білою стрілкою на зображенні 12. + Ми рекомендуємо нахилити дрон убік, щоб полегшити встановлення. - + - _Figure 11_: Hanger gaskets + _Figure 11_: Hanger gaskets - ![Battery Mount 4](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_fig10.jpg) + ![Battery Mount 4](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_fig10.jpg) - _Figure 12_: Screw holes + _Figure 12_: Screw holes 11. Вставте направляючі планки на кільця кріплення (зображення 13). - Зберіть кріплення для батареї та плату платформи і встановіть їх на направляючі, як показано на зображенні 14. + Зберіть кріплення для батареї та плату платформи і встановіть їх на направляючі, як показано на зображенні 14. - ![Battery Mount 2: Slide bars](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_fig8.png) + ![Battery Mount 2: Slide bars](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_fig8.png) - _Figure 13_: Slide bars + _Figure 13_: Slide bars - + - _Figure 14_: Battery mount on slide bars + _Figure 14_: Battery mount on slide bars 12. Встановіть шасі на нижню пластину. - Ми рекомендуємо нахилити дрон убік, щоб полегшити встановлення. + Ми рекомендуємо нахилити дрон убік, щоб полегшити встановлення. - ![Landing Gear](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_fig5.jpg) + ![Landing Gear](../../assets/airframes/multicopter/x500_holybro_pixhawk4/x500_fig5.jpg) - _Figure 15_: Landing Gear + _Figure 15_: Landing Gear 13. За допомогою скотча приклейте GPS до верхньої частини GPS-щогли і встановіть її на щоглу. - Переконайтеся, що стрілка на gps вказує вперед (зображення 16). + Переконайтеся, що стрілка на gps вказує вперед (зображення 16). - + - _Figure 16_: GPS and mast + _Figure 16_: GPS and mast 14. Встановіть телеметричну радіостанцію на верхню пластину. - Plug the telemetry cable into `TELEM1` port and GPS module to `GPS MODULE` port on the flight controller. - Plug the cable from PM07 `FMU-PWM-in` to `I/O-PWM-out`on the FC and PM07 `PWR1` to `POWER1` on the FC, as shown in Figure 17. + Plug the telemetry cable into `TELEM1` port and GPS module to `GPS MODULE` port on the flight controller. + Plug the cable from PM07 `FMU-PWM-in` to `I/O-PWM-out`on the FC and PM07 `PWR1` to `POWER1` on the FC, as shown in Figure 17. - ![Pixhawk 4 wiring 1](../../assets/airframes/multicopter/x500_holybro_pixhawk4/fc_connections.jpg) + ![Pixhawk 4 wiring 1](../../assets/airframes/multicopter/x500_holybro_pixhawk4/fc_connections.jpg) - _Figure 17_: Mount telemetry radio/plug in PWM and Power cables to Flight controller. + _Figure 17_: Mount telemetry radio/plug in PWM and Power cables to Flight controller. Please refer to [Pixhawk 4 Quick Start](../assembly/quick_start_pixhawk4.md) for more information. diff --git a/docs/uk/frames_multicopter/holybro_x500v2_pixhawk6c.md b/docs/uk/frames_multicopter/holybro_x500v2_pixhawk6c.md index da28900651..8e20beecd5 100644 --- a/docs/uk/frames_multicopter/holybro_x500v2_pixhawk6c.md +++ b/docs/uk/frames_multicopter/holybro_x500v2_pixhawk6c.md @@ -18,21 +18,21 @@ This topic provides full instructions for building the [Holybro X500 V2 ARF Kit] **Screw**- Sunk Screw M2.5\*6 12pcs 1. Вставте резинове кільце підвіски-висувки в кожну з їхніх відповідних підвісок. - Не використовуйте гострi предмети для натискання резинок всередині. + Не використовуйте гострi предмети для натискання резинок всередині. - [![Assembly1](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly1.png)](https://www.youtube.com/watch?v=4Tid-FCP_aI) + [![Assembly1](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly1.png)](https://www.youtube.com/watch?v=4Tid-FCP_aI) 2. Take the battery mounting board and screw it with the slide bar clip using the Sunk Screw M2.5\*6. - [![Assembly2](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly2.png)](https://youtu.be/9E-rld6tPWQ) + [![Assembly2](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly2.png)](https://youtu.be/9E-rld6tPWQ) 3. Screw 4 hangers to the Platform Board using Sunk Screw M2.5\*6. - [![Assembly3](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly3.png)](https://youtu.be/4qIBABc9KsY)) + [![Assembly3](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly3.png)](https://youtu.be/4qIBABc9KsY)) 4. Візьміть зациклювальну планку та вставте 4 вісця, щоб прикрутити до нижньої плати пізніше. - [![Assembly4](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly4.png)](https://youtu.be/CFx6Ct7FCIc)) + [![Assembly4](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly4.png)](https://youtu.be/CFx6Ct7FCIc)) 5. Now insert the battery holder and payload holders assembled in step 2 & 3 @@ -44,11 +44,11 @@ This topic provides full instructions for building the [Holybro X500 V2 ARF Kit] 1. Take the bottom plate and insert 4 M3\*14 screws and fasten the nylon standoffs on the same. - [![Assembly6](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly6.png)](https://youtu.be/IfsMXTr3Uy4) + [![Assembly6](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly6.png)](https://youtu.be/IfsMXTr3Uy4) 2. Розмістіть Планку розподілу живлення та використовуйте гайки-самостопорювачі для їх збирання. Модуль живлення PM02 (для Pixhawk 6C) буде живити цю плату - [![Assembly7](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly7.png)](https://youtu.be/Qjs6pqarRIY) + [![Assembly7](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly7.png)](https://youtu.be/Qjs6pqarRIY) 3. Use Socket Cap Screws M2.5\*6 and screw the bottom plate on the 4 hangers (that we inserted in the 2 bars on the 3rd step of the payload holder assembly) @@ -56,15 +56,15 @@ This topic provides full instructions for building the [Holybro X500 V2 ARF Kit] 1. Для збирання станції шасі відкрутіть заздалегідь складені винти шасі - перекрестна стрічка та вставте шасі - вертикальний стовп і затягніть той же. - [![Assembly8](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly8.png)](https://youtu.be/mU4vm4zyjcY) + [![Assembly8](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly8.png)](https://youtu.be/mU4vm4zyjcY) - [![Assembly9](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly9.png)](https://youtu.be/7REaF3YAqLg) + [![Assembly9](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly9.png)](https://youtu.be/7REaF3YAqLg) 2. Use the Socket Cap Screw M3\*8 to screw the landing gears to the bottom plate - [![Assembly11](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly11.png)](https://youtu.be/iDxzWeyCN54) + [![Assembly11](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly11.png)](https://youtu.be/iDxzWeyCN54) - [![Assembly12](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly12.png)](https://youtu.be/3fNJQraCJx0) + [![Assembly12](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly12.png)](https://youtu.be/3fNJQraCJx0) Оскільки важко вставити проводи після того, як верхня плита складена, зробіть проводку заздалегідь. Хоча дизайн добре спроектований таким чином, що ви зможете зробити це пізніше також. @@ -92,28 +92,28 @@ Pixhawk 6C запитується за допомогою плати живле 1. Поставити руки досить просто, оскільки двигуни поставляються вже зібраними. - - Переконайтесь, що у вас є правильна пронумерована рука з мотором на відповідному боці. + - Переконайтесь, що у вас є правильна пронумерована рука з мотором на відповідному боці. - [![Assembly15](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly15.png)](https://youtu.be/45KCey3WiJ4) + [![Assembly15](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly15.png)](https://youtu.be/45KCey3WiJ4) - :::tip - Use your allen keys/ any elongated item and insert it on the opposite side of the bolt that you're trying to fasten. + :::tip + Use your allen keys/ any elongated item and insert it on the opposite side of the bolt that you're trying to fasten. ::: 2. Возьміть одну руку та вставте прямокутний виступ всередину прямокутного порожнини на нижній плиті. - [![Assembly16](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly16.png)](https://youtu.be/GOTqmjq9_3s) + [![Assembly16](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly16.png)](https://youtu.be/GOTqmjq9_3s) 3. While inserting the top plate on top of this the 3 piece assembly (bottom plate, top plate & arms) have to screwed using Socket Cap Screw M3\*38 and Flange Locknut M3. 4. Утримуйте одну сторону, використовуючи міні-гайковий ключ, який надається у розробницькому комплекті. - [![Assembly17](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly17.png)](https://youtu.be/2rcNVekJQd0) + [![Assembly17](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly17.png)](https://youtu.be/2rcNVekJQd0) 5. Не зав'язуйте жодних болтів, поки всі 3 мотори не будуть на місці, оскільки це може зробити складним збирання 3-го та 4-го моторів. - [![Assembly18](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly18.png)](https://youtu.be/SlKRuNoE_AY) + [![Assembly18](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly18.png)](https://youtu.be/SlKRuNoE_AY) ### Пропелери @@ -132,13 +132,13 @@ Pixhawk 6C запитується за допомогою плати живле 1. Зберіть GPS, дотримуючись відео. - [![Assembly20](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly20.png)](https://youtu.be/aiFxVJFjlos) + [![Assembly20](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly20.png)](https://youtu.be/aiFxVJFjlos) - У цьому посібнику використовується місце кріплення GPS, запропоноване в посібнику Holybro. + У цьому посібнику використовується місце кріплення GPS, запропоноване в посібнику Holybro. 2. Screw the GPS mount’s bottom end on the payload holder side using Locknut M3 & Screw M3\*10 - [![Assembly21](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly21.png)](https://youtu.be/uG5UKy3FrIc) + [![Assembly21](../../assets/airframes/multicopter/x500_v2_holybro_pixhawk6c/assembly21.png)](https://youtu.be/uG5UKy3FrIc) ### Pixhawk 6C diff --git a/docs/uk/frames_vtol/vtol_quadplane_falcon_vertigo_hybrid_rtf_dropix.md b/docs/uk/frames_vtol/vtol_quadplane_falcon_vertigo_hybrid_rtf_dropix.md index 60d91fbff4..e21f612731 100644 --- a/docs/uk/frames_vtol/vtol_quadplane_falcon_vertigo_hybrid_rtf_dropix.md +++ b/docs/uk/frames_vtol/vtol_quadplane_falcon_vertigo_hybrid_rtf_dropix.md @@ -67,45 +67,45 @@ The _Falcon Vertigo Hybrid VTOL_ is a quadplane VTOL aircraft that has been desi 1. Нанесіть клей Gorilla всередину кронштейнів крила, як показано. - ![Add glue on wing brackets](../../assets/airframes/vtol/falcon_vertigo/wing_brackets_glue.jpg) + ![Add glue on wing brackets](../../assets/airframes/vtol/falcon_vertigo/wing_brackets_glue.jpg) 2. Вкріпіть карбонову трубку в держаки. Для вирівнювання піддона та трубки слід використовувати білу позначку (як показано на зображенні). - ::: info - This is very important because the white mark indicates the center of gravity. + ::: info + This is very important because the white mark indicates the center of gravity. ::: - + 3. Наступні зображення показують вирівнювання стержнів з інших точок зору: - ![quad motor frame rod alignment from bottom](../../assets/airframes/vtol/falcon_vertigo/falcon_vertigo_9_bottom_view_rod_alignment.jpg) - ![quad motor frame rod alignment schematic](../../assets/airframes/vtol/falcon_vertigo/falcon_vertigo_11_rod_alignment_schamatic.jpg) + ![quad motor frame rod alignment from bottom](../../assets/airframes/vtol/falcon_vertigo/falcon_vertigo_9_bottom_view_rod_alignment.jpg) + ![quad motor frame rod alignment schematic](../../assets/airframes/vtol/falcon_vertigo/falcon_vertigo_11_rod_alignment_schamatic.jpg) ### Крок 2: Прикріпіть крила 1. Вставте обидві вуглецеві труби в фюзеляж. - + 2. Нанесіть клей gorilla між двома білими позначками на кожну трубку (вказано червоними стрілками). Білий знак по центру (синя стрілка) буде розміщений в центрі фюзеляжу, а інші знаки - по боках. - + 3. Після того, як вуглецеві трубки знаходяться всередині фюзеляжу, розподіліть клей gorilla на решту трубки та прикріпіть крила. 4. Фюзеляж має два отвори для кабелів двигуна та сервоприводів. Пропустіть кабелі через отвори, а потім приєднайте крила до фюзеляжу. - + 5. Усередині фюзеляжу під'єднайте сигнальні кабелі, які ви щойно прокинули з крил до регулятора ESC, використовуючи надані роз'єми. Регулятори швидкості ESC вже підключені до двигунів і налаштовані на обертання в правильному порядку (вам потрібно буде підключити ESC PDB до модуля живлення на пізнішому етапі). - + 6. Так само, як і з ESC, сервопристосування вже встановлені. Підключіть сигнальний кабель з крила (проходить через фюзеляж) до контролера польоту. - + 7. Повторіть ці кроки для іньшого крила. @@ -123,11 +123,11 @@ General information about connecting Dropix can be found in [Dropix Flight Contr 1. Підключіть ЕСС до модуля живлення за допомогою роз'єму XT60 - + 2. Передайте кабелі сигналів до контролера польоту - + #### Підключення двигуна @@ -162,7 +162,7 @@ The geometry and output assignment can be configured in the [Actuators Configura 3. Підключіть кабель сигналу двигуна дроселя від ESC до відповідного допоміжного порту контролера польоту. Підключіть ESC до регулятора газу. - + 4. Підключіть приймач (RC IN). @@ -176,7 +176,7 @@ The geometry and output assignment can be configured in the [Actuators Configura 1. Підключіть телеметрію, датчик швидкості, GPS, гудок та безпечний перемикач, як показано. - + #### Контролер польоту: Підключіть модуль живлення та зовнішній USB @@ -184,7 +184,7 @@ The geometry and output assignment can be configured in the [Actuators Configura 1. Підключіть живлення та USB, як показано - + :::tip The external USB is optional. @@ -201,27 +201,27 @@ It is important that nothing obstructs airflow to the Pitot tube. Це крит 1. Встановіть трубку Піто у передній частині літака - + 2. Зафіксуйте з'єднуючі трубки та переконайтеся, що вони не зігнуті / пом'яті. - + 3. Підключіть трубки до датчика швидкості. - + #### Встановлення/підключення приймача та модуля телеметрії 1. Вставте приймач та телеметричний модуль на зовнішню сторону рами транспортного засобу. - + 2. Connect the receiver to the RC IN port on the _back_ of the dropix, as shown above (also see the [flight controller instructions](#dropix_back)). 3. Connect the telemetry module to the _front_ of the flight controller as shown below (see the [flight controller instructions](#dropix_front) for more detail on the pins). - + @@ -237,7 +237,7 @@ It is important that nothing obstructs airflow to the Pitot tube. Це крит 1. Встановіть орієнтацію вашого політ контролеру на 270 градусів. - + 2. Закріпіть контролер на місці за допомогою піни для поглинання вібрації. @@ -247,21 +247,21 @@ It is important that nothing obstructs airflow to the Pitot tube. Це крит 1. Перевірте, що двигуни обертаються у правильних напрямках (як у діаграмі QuadX нижче). - + - ::: info - If necessary the servo direction can be reversed using the `Rev Range (for servos)` checkbox associated with each servo output in the QGroundControl [Actuator Output](../config/actuators.md#actuator-outputs) configuration (for servos only) (this sets the [PWM_AUX_REV](../advanced_config/parameter_reference.md#PWM_AUX_REV) or [PWM_AUX_MAIN](../advanced_config/parameter_reference.md#PWM_MAIN_REV) parameter). + ::: info + If necessary the servo direction can be reversed using the `Rev Range (for servos)` checkbox associated with each servo output in the QGroundControl [Actuator Output](../config/actuators.md#actuator-outputs) configuration (for servos only) (this sets the [PWM_AUX_REV](../advanced_config/parameter_reference.md#PWM_AUX_REV) or [PWM_AUX_MAIN](../advanced_config/parameter_reference.md#PWM_MAIN_REV) parameter). ::: 2. Перевірте, чи транспортний засіб збалансований навколо очікуваного центру мас - - Утримуйте транспортний засіб пальцями у центрі ваги та переконайтеся, що транспортний засіб залишається стабільним. + - Утримуйте транспортний засіб пальцями у центрі ваги та переконайтеся, що транспортний засіб залишається стабільним. - ![Level Centre of Gravity](../../assets/airframes/vtol/falcon_vertigo/falcon_vertigo_57_level_centre_of_gravity.jpg) + ![Level Centre of Gravity](../../assets/airframes/vtol/falcon_vertigo/falcon_vertigo_57_level_centre_of_gravity.jpg) - - Якщо транспортний засіб нахиляється вперед або назад, перемістіть двигуни, щоб утримати рівновагу. + - Якщо транспортний засіб нахиляється вперед або назад, перемістіть двигуни, щоб утримати рівновагу. - ![Level Motors](../../assets/airframes/vtol/falcon_vertigo/falcon_vertigo_55_level_motors.jpg) + ![Level Motors](../../assets/airframes/vtol/falcon_vertigo/falcon_vertigo_55_level_motors.jpg) ## Налаштування @@ -271,7 +271,7 @@ Perform the normal [Basic Configuration](../config/index.md). 1. For [Airframe](../config/airframe.md) select the vehicle group/type as _Standard VTOL_ and the specific vehicle as [Generic Standard VTOL](../airframes/airframe_reference.md#vtol_standard_vtol_generic_standard_vtol) as shown below. - ![QCG - Select Generic Standard VTOL](../../assets/qgc/setup/airframe/px4_frame_generic_standard_vtol.png) + ![QCG - Select Generic Standard VTOL](../../assets/qgc/setup/airframe/px4_frame_generic_standard_vtol.png) 2. Set the [Autopilot Orientation](../config/flight_controller_orientation.md) to `ROTATION_YAW_270` as the autopilot is mounted [sideways](#flight_controller_orientation) with respect to the front of the vehicle. The compass is oriented forward, so you can leave that at the default (`ROTATION_NONE`). diff --git a/docs/uk/frames_vtol/vtol_quadplane_foxtech_loong_2160.md b/docs/uk/frames_vtol/vtol_quadplane_foxtech_loong_2160.md index aa5f8a1af4..8bd9b58c2d 100644 --- a/docs/uk/frames_vtol/vtol_quadplane_foxtech_loong_2160.md +++ b/docs/uk/frames_vtol/vtol_quadplane_foxtech_loong_2160.md @@ -99,33 +99,33 @@ Foxtech Loong 2160 VTOL - це легкий у монтажі майже гот 1. Вставте 10x різьбових вкладок M3 в піддон, як показано на малюнку: - ![Основна плита з різбленими вставками](../../assets/airframes/vtol/foxtech_loong_2160/03-baseplate.jpg) + ![Основна плита з різбленими вставками](../../assets/airframes/vtol/foxtech_loong_2160/03-baseplate.jpg) 2. Вставте 2x різьбові вставки M3 в пристрій для накладання, як показано на зображенні нижче: - ![Фіксатор стекла з нарізними вкладками](../../assets/airframes/vtol/foxtech_loong_2160/04-stack-fixture.jpg) + ![Фіксатор стекла з нарізними вкладками](../../assets/airframes/vtol/foxtech_loong_2160/04-stack-fixture.jpg) 3. Вставте 2x різьбові вкладки M4 в кріплення вентилятора та кріплення радіо, як показано на малюнку нижче. - ![Кріплення радіо](../../assets/airframes/vtol/foxtech_loong_2160/05-radio-mount.jpg) + ![Кріплення радіо](../../assets/airframes/vtol/foxtech_loong_2160/05-radio-mount.jpg) - Якщо ви хочете додати 40-мм вентилятор з напругою 5 В на кріплення вентилятора, вставте 4x вставки M3. + Якщо ви хочете додати 40-мм вентилятор з напругою 5 В на кріплення вентилятора, вставте 4x вставки M3. - ![Fan-mount](../../assets/airframes/vtol/foxtech_loong_2160/06-fan-mount.jpg) + ![Fan-mount](../../assets/airframes/vtol/foxtech_loong_2160/06-fan-mount.jpg) 4. Змініть кабельний роз'єм на роз'єм для сервоприводу, щоб його можна було вставити в шину сервоприводу для живлення. - ::: info - Можливо знадобиться вентилятор, якщо використовується потужне радіо. + ::: info + Можливо знадобиться вентилятор, якщо використовується потужне радіо. ::: - ![Кріплення вентилятора](../../assets/airframes/vtol/foxtech_loong_2160/07-fan-mount.jpg) + ![Кріплення вентилятора](../../assets/airframes/vtol/foxtech_loong_2160/07-fan-mount.jpg) 5. Вилучіть оригінальну кронштейнну пластину з автомобіля. - Приклейте кабелі до зовнішньої частини фюзеляжу. + Приклейте кабелі до зовнішньої частини фюзеляжу. - ![Порожнє фюзеляж](../../assets/airframes/vtol/foxtech_loong_2160/08-preparations.jpg) + ![Порожнє фюзеляж](../../assets/airframes/vtol/foxtech_loong_2160/08-preparations.jpg) 6. Перемістіть підставку в транспортний засіб. @@ -142,9 +142,9 @@ Foxtech Loong 2160 VTOL - це легкий у монтажі майже гот 1. Вилучіть корпус з 40A PM. 2. Зафіксуйте ПМ з 2x M2x6mm до нижньої пластини. 3. Створіть кабель для подовження роз'єму XT60 до XT30, який закріплений на базовій платі. - З цим, живлення від акумулятора 6S може бути підключено безпосередньо до роз'єму XT30 за допомогою попередньо налаштованого кабелю, що поставляється з транспортним засобом. + З цим, живлення від акумулятора 6S може бути підключено безпосередньо до роз'єму XT30 за допомогою попередньо налаштованого кабелю, що поставляється з транспортним засобом. - ![Встановлення модуля живлення 40A](../../assets/airframes/vtol/foxtech_loong_2160/10-40a-power-module.jpg) + ![Встановлення модуля живлення 40A](../../assets/airframes/vtol/foxtech_loong_2160/10-40a-power-module.jpg) Якщо потрібно, вихід 10V з радіопорту на PM також може бути викладений через XT30, який може бути встановлений поруч зі входом батареї 6S XT60. @@ -153,17 +153,17 @@ Foxtech Loong 2160 VTOL - це легкий у монтажі майже гот #### Трубка Піто 1. Датчик може бути встановлений за допомогою 2x винтів M3x16мм в передньому правому куті підставки. - Піклуйтесь, щоб конектор був звернутий у бік центру фюзеляжу. + Піклуйтесь, щоб конектор був звернутий у бік центру фюзеляжу. - ![Встановлений датчик швидкості повітря](../../assets/airframes/vtol/foxtech_loong_2160/11-airspeed-sensor.jpg) + ![Встановлений датчик швидкості повітря](../../assets/airframes/vtol/foxtech_loong_2160/11-airspeed-sensor.jpg) - Лише передню трубу (не так, як показано на картинці) використовується; іншу трубу можна видалити, оскільки наш досвід показав, що тиск всередині фюзеляжу достатній як статичний тиск. + Лише передню трубу (не так, як показано на картинці) використовується; іншу трубу можна видалити, оскільки наш досвід показав, що тиск всередині фюзеляжу достатній як статичний тиск. 2. Коли стек встановлено всередині фюзеляжу, труба, що йде з крила, та труба, що йде з датчика швидкості повітря, повинні бути з'єднані разом. - Використовуйте трохи слини (це найлегший спосіб) щоб з'єднати їх разом, а потім використовуйте термоусадочну трубку, щоб посилити з'єднання. + Використовуйте трохи слини (це найлегший спосіб) щоб з'єднати їх разом, а потім використовуйте термоусадочну трубку, щоб посилити з'єднання. - :::warning - Використовуйте джерело тепла обережно, оскільки піна починаєтся танути при високих температурах. + :::warning + Використовуйте джерело тепла обережно, оскільки піна починаєтся танути при високих температурах. ::: @@ -175,22 +175,22 @@ Foxtech Loong 2160 VTOL - це легкий у монтажі майже гот ::: 1. Позначте місце для встановлення лідару за допомогою скотчу або ручки. - Виріжте отвір всередині оболонки з ПВХ та піни, щоб лідар вміщувався на місце. + Виріжте отвір всередині оболонки з ПВХ та піни, щоб лідар вміщувався на місце. - ![Підготоване отвір лідару](../../assets/airframes/vtol/foxtech_loong_2160/12-lidar-01.jpg) + ![Підготоване отвір лідару](../../assets/airframes/vtol/foxtech_loong_2160/12-lidar-01.jpg) 2. Закріпіть лідар з гарячим клеєм. - ![Встановлений лідар](../../assets/airframes/vtol/foxtech_loong_2160/13-lidar-02.jpg) + ![Встановлений лідар](../../assets/airframes/vtol/foxtech_loong_2160/13-lidar-02.jpg) #### GPS/компас 1. Використовуйте двосторонній скотч для кріплення GPS на задній частині транспортного засобу під задньою засувкою. - ![Встановлений GPS](../../assets/airframes//vtol/foxtech_loong_2160/14-gps.jpg) + ![Встановлений GPS](../../assets/airframes//vtol/foxtech_loong_2160/14-gps.jpg) - Стрілка на GPS для орієнтації може бути проігнорована. - Орієнтацію буде визначено під час калібрування автопілота. + Стрілка на GPS для орієнтації може бути проігнорована. + Орієнтацію буде визначено під час калібрування автопілота. ### Політний контролер @@ -203,15 +203,15 @@ Foxtech Loong 2160 VTOL - це легкий у монтажі майже гот #### Skynode 1. Використовуйте 4x гвинти M3x8 для кріплення Skynode до підстави. - Переконайтеся, що верхня частина "A" спрямована вперед транспортного засобу. + Переконайтеся, що верхня частина "A" спрямована вперед транспортного засобу. 2. Вставте 40-амперний модуль живлення в верхній з двох роз'ємів живлення. 3. Вставте один (або якщо потрібно, два) USB адаптери в 4-контактні роз'єми JST-GH на задній частині Skynode та прокладіть їх до передньої панелі. - Виправте кабелі за допомогою хомутів-ґудзиків на місці. + Виправте кабелі за допомогою хомутів-ґудзиків на місці. 4. Приклейте розгалужувач I2C до правої передньої сторони підставки (Розгалужувач може бути використаний для підключення пристроїв ETH, таких як радіозв'язок.) 5. Підключіть розгалужувач I2C до порту ETH на задній панелі Skynode. 6. Вставте два 40-контактних кабелі у передню частину Skynode. 7. Підключіть USB-C кабель подовження та згинайте його впереду. - Згин повинен бути дуже тугим, щоб пластина влізла в дрон. + Згин повинен бути дуже тугим, щоб пластина влізла в дрон. ![Встановлений Skynode](../../assets/airframes/vtol/foxtech_loong_2160/15-skynode.jpg) @@ -223,17 +223,17 @@ Foxtech Loong 2160 VTOL - це легкий у монтажі майже гот 1. Приклейте антени Skynode LTE до боку фюзеляжу, як показано на зображенні: - ![Антени LTE](../../assets/airframes/vtol/foxtech_loong_2160/16-lte-antennas.jpg) + ![Антени LTE](../../assets/airframes/vtol/foxtech_loong_2160/16-lte-antennas.jpg) 2. Якщо ви використовуєте модуль радіотелеметрії, ви можете встановити антени на верх фюзеляжу. - Зверху ви можете прямо встановити кабель подовження антени. + Зверху ви можете прямо встановити кабель подовження антени. - ![WIFI-Антени-Фронтальні](../../assets/airframes/vtol/foxtech_loong_2160/17-antenna-front.jpg) + ![WIFI-Антени-Фронтальні](../../assets/airframes/vtol/foxtech_loong_2160/17-antenna-front.jpg) - На задній частині ви можете використовувати адаптер антени з використанням технології 3D-друку. - Адаптер можна склеювати на місці гарячим клеєм. + На задній частині ви можете використовувати адаптер антени з використанням технології 3D-друку. + Адаптер можна склеювати на місці гарячим клеєм. - ![Задня WIFI антена](../../assets/airframes/vtol/foxtech_loong_2160/19-rear-antenna.jpg) + ![Задня WIFI антена](../../assets/airframes/vtol/foxtech_loong_2160/19-rear-antenna.jpg) ### Модуль потужності 12S diff --git a/docs/uk/frames_vtol/vtol_tiltrotor_omp_hobby_zmo_fpv.md b/docs/uk/frames_vtol/vtol_tiltrotor_omp_hobby_zmo_fpv.md index 5fc3ce782c..3ceb129558 100644 --- a/docs/uk/frames_vtol/vtol_tiltrotor_omp_hobby_zmo_fpv.md +++ b/docs/uk/frames_vtol/vtol_tiltrotor_omp_hobby_zmo_fpv.md @@ -93,7 +93,7 @@ ZMO FPV в його початковому стані. ### ESC регулятори швидкості 1. Відпаяйте сигнальні контакти PWM та контакти заземлення ESC регулятора швидкості та припаяйте до контактів подовжувач сервоприводу. - Кабель повинен бути достатньо довгим, щоб підключити дріт до контактів FMU плати керування польотом. + Кабель повинен бути достатньо довгим, щоб підключити дріт до контактів FMU плати керування польотом. 2. Розпаяйте 3 роз’єми «банан» заднього двигуна (може не знадобитися для інтеграції Pixhawk 6). @@ -103,17 +103,17 @@ ZMO FPV в його початковому стані. 5. Припаяйте сигнальні та GND-дроти до входу PWM ESC регулятора швидкості. - ![ESC 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/esc-01.jpg) + ![ESC 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/esc-01.jpg) 6. Зніміть гніздову вилку на ESC. - Це надасть вам більше місця для встановлення польотного контролера. + Це надасть вам більше місця для встановлення польотного контролера. - ![ESC 02](../../assets/airframes/vtol/omp_hobby_zmo_fpv/esc-02.jpg) + ![ESC 02](../../assets/airframes/vtol/omp_hobby_zmo_fpv/esc-02.jpg) 7. Припаяйте проводи заднього двигуна до ESC регулятора швидкості. - Переконайтеся, що підключаєте так, щоб двигун обертався у правильному напрямку. + Переконайтеся, що підключаєте так, щоб двигун обертався у правильному напрямку. - ![ESC 03](../../assets/airframes/vtol/omp_hobby_zmo_fpv/esc-03.jpg) + ![ESC 03](../../assets/airframes/vtol/omp_hobby_zmo_fpv/esc-03.jpg) ### З'єднувач крила @@ -122,9 +122,9 @@ ZMO FPV в його початковому стані. 1. Приклейте з'єднувачі крила до деталі, надрукованої на 3D-принтері, гарячим клеєм або 5 хвилинною епоксидною смолою. 2. Приклейте 3D-друковану частину разом із з'єднувачем у фюзеляж. - Переконайтеся, що правильно вирівняли з'єднувач, поки клей сохне. + Переконайтеся, що правильно вирівняли з'єднувач, поки клей сохне. - Найпростіший спосіб вирівняти роз'єм - встановити крило, поки клей застигає, але переконайтеся, що клей не потрапив між фюзеляжем і крилом, інакше крило може застрягти. + Найпростіший спосіб вирівняти роз'єм - встановити крило, поки клей застигає, але переконайтеся, що клей не потрапив між фюзеляжем і крилом, інакше крило може застрягти. Роз'єм, вклеєний у 3D-друковану частину @@ -137,58 +137,58 @@ ZMO FPV в його початковому стані. ### Плати адаптерів Pixhawk та BEC 1. Виріжте пінопласт, як показано на малюнках, щоб створити простір для кріплення адаптерних плат Pixhawk і BEC двостороннім скотчем. - Плата FMU розміщується зліва (у напрямку польоту) від фюзеляжу. - Зпаяйте серво конектор та кабель для напруги батареї до BEC. + Плата FMU розміщується зліва (у напрямку польоту) від фюзеляжу. + Зпаяйте серво конектор та кабель для напруги батареї до BEC. - ![Foam cutout 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/foam-cut-01.png) - ![Pixhawk adapter board mount 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/pixhawk-adapter-01.jpg) + ![Foam cutout 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/foam-cut-01.png) + ![Pixhawk adapter board mount 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/pixhawk-adapter-01.jpg) 2. Підготуйте BEC для підключення до IO плати та батареї. - BEC також можна припаяти безпосередньо до акумуляторних колодок ESC. + BEC також можна припаяти безпосередньо до акумуляторних колодок ESC. - ![BEC preparation](../../assets/airframes/vtol/omp_hobby_zmo_fpv/bec-01.jpg) + ![BEC preparation](../../assets/airframes/vtol/omp_hobby_zmo_fpv/bec-01.jpg) 3. Закріпіть BEC двостороннім скотчем. - ![BEC mounting](../../assets/airframes/vtol/omp_hobby_zmo_fpv/bec-02.jpg) + ![BEC mounting](../../assets/airframes/vtol/omp_hobby_zmo_fpv/bec-02.jpg) ### Кабелі 1. Відріжте роз’єми від сервоприводів і припаяйте подовжувачі сервоприводів до кабелів. - Переконайтеся, що кабелі достатньо довгі, щоб дістатися до адаптерної плати Pixhawk. - Якщо у вас є обтискний інструмент, ви також можете безпосередньо додати роз’єми без пайки. + Переконайтеся, що кабелі достатньо довгі, щоб дістатися до адаптерної плати Pixhawk. + Якщо у вас є обтискний інструмент, ви також можете безпосередньо додати роз’єми без пайки. 2. Під'єднайте кабелі сервоприводу до IO плати адаптера в такому порядку: - - 1 - Aileron left - - 2 - Aileron right - - 3 - V-Tail left - - 4 - V-Tail right - - 5 - Tilt left - - 6 - Tilt right + - 1 - Aileron left + - 2 - Aileron right + - 3 - V-Tail left + - 4 - V-Tail right + - 5 - Tilt left + - 6 - Tilt right 3. Під'єднайте сигнальні кабелі мотора до адаптерної плати FMU у такому порядку: - - 1 - Передній лівий - - 2 - Передній правий - - 3 - Задній + - 1 - Передній лівий + - 2 - Передній правий + - 3 - Задній ### Датчики #### Трубка Піто 1. Спочатку перевірте, чи трубка Піто влазить у кріплення, надруковане на 3D-принтері. - Якщо це так, то приклейте трубку Піто на місце у кріплення. + Якщо це так, то приклейте трубку Піто на місце у кріплення. - Щоб вирівняти трубку пропустіть її через другий отвір праворуч від передньої пластини FPV. - Кріплення дозволить вам вдавити трубку назад у фюзеляж, щоб захистити її під час транспортування та обробки. - Датчик може бути встановлений зверху на кріпленні, надрукованому на 3D-принтері, за допомогою двостороннього скотчу. + Щоб вирівняти трубку пропустіть її через другий отвір праворуч від передньої пластини FPV. + Кріплення дозволить вам вдавити трубку назад у фюзеляж, щоб захистити її під час транспортування та обробки. + Датчик може бути встановлений зверху на кріпленні, надрукованому на 3D-принтері, за допомогою двостороннього скотчу. 2. Приклейте кріплення, надруковане на 3D-принтері, на місце. - ![Pitot tube 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/pitot-tube-01.png) + ![Pitot tube 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/pitot-tube-01.png) 3. Датчик може бути встановлений зверху на кріпленні, надрукованому на 3D-принтері. - ![Pitot tube 02](../../assets/airframes/vtol/omp_hobby_zmo_fpv/pitot-tube-02.png) + ![Pitot tube 02](../../assets/airframes/vtol/omp_hobby_zmo_fpv/pitot-tube-02.png) #### Лідар @@ -209,9 +209,9 @@ ZMO FPV в його початковому стані. 2. Вийміть GPS із пластикового корпусу та від’єднайте роз’єм. 3. Протягніть кабель через вуглецевий лонжерон. 4. Glue the 3D-Printed part with 5 min epoxy in place. - ![Glue the GPS mount into place](../../assets/airframes/vtol/omp_hobby_zmo_fpv/gps-01.jpg) + ![Glue the GPS mount into place](../../assets/airframes/vtol/omp_hobby_zmo_fpv/gps-01.jpg) 5. After the glue has cured, screw the GPS with 4x M2.5x10 screws to the plate. - ![Screw the GPS to the mount2](../../assets/airframes/vtol/omp_hobby_zmo_fpv/gps-02.jpg) + ![Screw the GPS to the mount2](../../assets/airframes/vtol/omp_hobby_zmo_fpv/gps-02.jpg) #### USB Камера @@ -219,9 +219,9 @@ ZMO FPV в його початковому стані. 2. Відріжте кабель USB-адаптера на 25 см і спаяйте два кабелі між собою. 3. Для встановлення камери потрібно вирізати отвір у пінопласті перегородки. - ![USB Camera 01: Hole to feed the USB cable through the wall.](../../assets/airframes/vtol/omp_hobby_zmo_fpv/camera-01.jpg) + ![USB Camera 01: Hole to feed the USB cable through the wall.](../../assets/airframes/vtol/omp_hobby_zmo_fpv/camera-01.jpg) - Потім ви можете закріпити камеру на перегородці за допомогою двостороннього скотча. + Потім ви можете закріпити камеру на перегородці за допомогою двостороннього скотча. ### Політний контролер @@ -237,7 +237,7 @@ ZMO FPV в його початковому стані. 1. Помістіть його на верхню частину ESC і позначте 2 задніх місця кріплення на литій пластиковій частині ZMO. 2. Remove the Skynode from the vehicle and drill 2 holes with a 2.8 mm drill bit into the plastic part. - ![Mounting holes for the Skynode in the back](../../assets/airframes/vtol/omp_hobby_zmo_fpv/flight-controller-01.jpg) + ![Mounting holes for the Skynode in the back](../../assets/airframes/vtol/omp_hobby_zmo_fpv/flight-controller-01.jpg) 3. Встановіть Skynode на місце і прикрутіть його 2-ма гвинтами M3x10. Інший варіант - додати в отвори різьбові вставки. @@ -245,9 +245,9 @@ ZMO FPV в його початковому стані. 1. Прикрутіть переднє кріплення Skynode 2-ма гвинтами M3x10 до Skynode. 2. Потім додайте трохи епоксидного клею на 5 хвилин в нижню частину кріплення і покладіть вантаж зверху на Skynode, поки клей не затвердіє. - Щоб отримати доступ до 2 кріпильних гвинтів спереду, проткніть 2 отвори зверху через пінопласт. + Щоб отримати доступ до 2 кріпильних гвинтів спереду, проткніть 2 отвори зверху через пінопласт. - ![Skynode mount in the front](../../assets/airframes/vtol/omp_hobby_zmo_fpv/flight-controller-02.jpg) + ![Skynode mount in the front](../../assets/airframes/vtol/omp_hobby_zmo_fpv/flight-controller-02.jpg) ### Антени та RC приймач @@ -258,14 +258,14 @@ An inexpensive example would be a [SiK Telemetry Radio](../telemetry/sik_radio.m ::: 1. Одна антена LTE може бути встановлена в нижній частині транспортного засобу. - Для цього ви можете протягнути дріт антени через отвір для радіатора ESC. + Для цього ви можете протягнути дріт антени через отвір для радіатора ESC. - ![LTE antenna 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/lte-antenna-01.jpg) + ![LTE antenna 01](../../assets/airframes/vtol/omp_hobby_zmo_fpv/lte-antenna-01.jpg) 2. Другу антену можна встановити всередині транспортного засобу з лівого боку акумуляторного відсіку. - Пульт дистанційного керування також можна розмістити з лівого боку батарейного відсіку. + Пульт дистанційного керування також можна розмістити з лівого боку батарейного відсіку. - ![LTE antenna 2 and RC receiver](../../assets/airframes/vtol/omp_hobby_zmo_fpv/lte-antenna-02.jpg) + ![LTE antenna 2 and RC receiver](../../assets/airframes/vtol/omp_hobby_zmo_fpv/lte-antenna-02.jpg) ## Налаштування програмного забезпечення @@ -332,9 +332,9 @@ The airspeed sensor can be enabled in the [Parameters](../advanced_config/parame 1. Switch the vehicle into manual mode (either via the flight mode switch or type `commander mode manual` into the MAVLink shell). 2. Перевірте, чи двигуни спрямовані вгору. - Якщо двигуни спрямовані вперед, то пов'язані з ними сервоприводи нахилу потрібно змінити на протилежні (встановіть прапорець біля кожного сервоприводу). + Якщо двигуни спрямовані вперед, то пов'язані з ними сервоприводи нахилу потрібно змінити на протилежні (встановіть прапорець біля кожного сервоприводу). - ![Tilt Servo adjustment](../../assets/airframes/vtol/omp_hobby_zmo_fpv/tilt-limits-01.jpg) + ![Tilt Servo adjustment](../../assets/airframes/vtol/omp_hobby_zmo_fpv/tilt-limits-01.jpg) 3. Adjust the minimum (or, if revesed: maximum) value such that the rotor thrust can point backward (needed for proper yaw allocation in Multicopter mode). diff --git a/docs/uk/gps_compass/index.md b/docs/uk/gps_compass/index.md index e1c2339a67..96ab9ae8a4 100644 --- a/docs/uk/gps_compass/index.md +++ b/docs/uk/gps_compass/index.md @@ -145,21 +145,21 @@ To ensure the port is set up correctly perform a [Serial Port Configuration](../ The following steps show how to configure a secondary GPS on the `GPS 2` port in _QGroundControl_: 1. [Find and set](../advanced_config/parameters.md) the parameter [GPS_2_CONFIG](../advanced_config/parameter_reference.md#GPS_2_CONFIG) to **GPS 2**. - - Open _QGroundControl_ and navigate to the **Vehicle Setup > Parameters** section. - - Select the **GPS** tab, then open the [GPS_2_CONFIG](../advanced_config/parameter_reference.md#GPS_2_CONFIG) parameter and select `GPS 2` from the dropdown list. + - Open _QGroundControl_ and navigate to the **Vehicle Setup > Parameters** section. + - Select the **GPS** tab, then open the [GPS_2_CONFIG](../advanced_config/parameter_reference.md#GPS_2_CONFIG) parameter and select `GPS 2` from the dropdown list. - ![QGC Serial Example](../../assets/peripherals/qgc_serial_config_example.png) + ![QGC Serial Example](../../assets/peripherals/qgc_serial_config_example.png) 2. Перезавантажте апарат, щоб побачити інші параметри. 3. Select the **Serial** tab, and open the [SER_GPS2_BAUD](../advanced_config/parameter_reference.md#SER_GPS2_BAUD) parameter (`GPS 2` port baud rate): set it to _Auto_ (or 115200 for the Trimble). - ![QGC Serial Baudrate Example](../../assets/peripherals/qgc_serial_baudrate_example.png) + ![QGC Serial Baudrate Example](../../assets/peripherals/qgc_serial_baudrate_example.png) Після налаштування другого GPS-порту: 1. Налаштуйте обчислювач ECL/EKF2, щоб об'єднати дані з обох GPS-систем. - For detailed instructions see: [Using the ECL EKF > Dual Receivers](../advanced_config/tuning_the_ecl_ekf.md#dual-receivers). + For detailed instructions see: [Using the ECL EKF > Dual Receivers](../advanced_config/tuning_the_ecl_ekf.md#dual-receivers). ### DroneCAN GNSS Configuration diff --git a/docs/uk/gps_compass/rtk_gps.md b/docs/uk/gps_compass/rtk_gps.md index ff709d76a0..1e8f3c158e 100644 --- a/docs/uk/gps_compass/rtk_gps.md +++ b/docs/uk/gps_compass/rtk_gps.md @@ -122,35 +122,35 @@ This should be set by default, but if not, follow the [MAVLink2 configuration in Підключення RTK GPS насправді просте: 1. Start _QGroundControl_ and attach the base RTK GPS via USB to the ground station. - Пристрій визнається автоматично. + Пристрій визнається автоматично. 2. Start the vehicle and make sure it is connected to _QGroundControl_. - :::tip - _QGroundControl_ displays an RTK GPS status icon in the top icon bar while an RTK GPS device is connected (in addition to the normal GPS status icon). - Іконка червона, поки налаштовується RTK, а потім змінюється на білу, коли RTK GPS активний. - Ви можете натиснути на піктограму, щоб побачити поточний стан та точність RTK. + :::tip + _QGroundControl_ displays an RTK GPS status icon in the top icon bar while an RTK GPS device is connected (in addition to the normal GPS status icon). + Іконка червона, поки налаштовується RTK, а потім змінюється на білу, коли RTK GPS активний. + Ви можете натиснути на піктограму, щоб побачити поточний стан та точність RTK. ::: 3. _QGroundControl_ then starts the RTK setup process (known as "Survey-In"). - Survey-In - це процедура запуску для отримання точної оцінки положення базової станції. - The process typically takes several minutes (it ends after reaching the minimum time and accuracy specified in the [RTK settings](#rtk-gps-settings)). + Survey-In - це процедура запуску для отримання точної оцінки положення базової станції. + The process typically takes several minutes (it ends after reaching the minimum time and accuracy specified in the [RTK settings](#rtk-gps-settings)). - Ви можете відстежити прогрес, натиснувши на піктограму стану RTK GPS. + Ви можете відстежити прогрес, натиснувши на піктограму стану RTK GPS. - ![survey-in](../../assets/qgc/setup/rtk/qgc_rtk_survey-in.png) + ![survey-in](../../assets/qgc/setup/rtk/qgc_rtk_survey-in.png) 4. Після завершення опитування: - - The RTK GPS icon changes to white and _QGroundControl_ starts to stream position data to the vehicle: + - The RTK GPS icon changes to white and _QGroundControl_ starts to stream position data to the vehicle: - ![RTK streaming](../../assets/qgc/setup/rtk/qgc_rtk_streaming.png) + ![RTK streaming](../../assets/qgc/setup/rtk/qgc_rtk_streaming.png) - - Транспортний GPS переходить у режим RTK. - The new mode is displayed in the _normal_ GPS status icon (`3D RTK GPS Lock`): + - Транспортний GPS переходить у режим RTK. + The new mode is displayed in the _normal_ GPS status icon (`3D RTK GPS Lock`): - ![RTK GPS Status](../../assets/qgc/setup/rtk/qgc_rtk_gps_status.png) + ![RTK GPS Status](../../assets/qgc/setup/rtk/qgc_rtk_gps_status.png) ### Налаштування GPS як Джерело розділення/Курсування diff --git a/docs/uk/hardware/board_support_guide.md b/docs/uk/hardware/board_support_guide.md index b1b0aeb4a5..9d1f1854db 100644 --- a/docs/uk/hardware/board_support_guide.md +++ b/docs/uk/hardware/board_support_guide.md @@ -33,8 +33,8 @@ Boards that are not compliant with the requirements are [unsupported](#unsupport 6. Достатня документація, яка включає, але не обмежується: - Повний підключення, яке стало доступним для громадськості, яке відображає PX4 визначення контактів на: - 1. Піни мікроконтролера - 2. Фізичні зовнішні роз'ємники + 1. Піни мікроконтролера + 2. Фізичні зовнішні роз'ємники - A block diagram or full schematic of the main components (sensors, power supply, etc.) that allows to infer software requirements and boot order - Посібник з використання готового продукту diff --git a/docs/uk/hardware/porting_guide_nuttx.md b/docs/uk/hardware/porting_guide_nuttx.md index 38b250b741..ab4a1afa0e 100644 --- a/docs/uk/hardware/porting_guide_nuttx.md +++ b/docs/uk/hardware/porting_guide_nuttx.md @@ -62,30 +62,30 @@ To run `qconfig` you may need to install additional Qt dependencies. 2. Завантажте вихідний код і переконайтеся, що ви можете зібрати існуючу ціль: - ```sh - git clone --recursive https://github.com/PX4/PX4-Autopilot.git - cd PX4-Autopilot - make px4_fmu-v5 - ``` + ```sh + git clone --recursive https://github.com/PX4/PX4-Autopilot.git + cd PX4-Autopilot + make px4_fmu-v5 + ``` 3. Знаходьте існуючу ціль, яка використовує той самий (або тісно пов'язаний) тип ЦП, і скопіюйте її. - Наприклад для STM32F7: + Наприклад для STM32F7: - ```sh - mkdir boards/manufacturer - cp -r boards/px4/fmu-v5 boards/manufacturer/my-target-v1 - ``` + ```sh + mkdir boards/manufacturer + cp -r boards/px4/fmu-v5 boards/manufacturer/my-target-v1 + ``` - Change **manufacturer** to the manufacturer name and **my-target-v1** to your board name. + Change **manufacturer** to the manufacturer name and **my-target-v1** to your board name. Next you need to go through all files under **boards/manufacturer/my-target-v1** and update them according to your board. 1. **firmware.prototype**: update the board ID and name 2. **default.px4board**: update the **VENDOR** and **MODEL** to match the directory names (**my-target-v1**). - Налаштування послідовних портів. + Налаштування послідовних портів. 3. Configure NuttX (**defconfig**) via `make manufacturer_my-target-v1 menuconfig`: Adjust the CPU and chip, configure the peripherals (UART's, SPI, I2C, ADC). 4. **nuttx-config/include/board.h**: Configure the NuttX pins. - Для всіх зовнішніх пристроїв з кількома варіантами контактів, NuttX повинен знати контакт. - They are defined in the chip-specific pinmap header file, for example [stm32f74xx75xx_pinmap.h](https://github.com/PX4/NuttX/blob/px4_firmware_nuttx-8.2/arch/arm/src/stm32f7/hardware/stm32f74xx75xx_pinmap.h). + Для всіх зовнішніх пристроїв з кількома варіантами контактів, NuttX повинен знати контакт. + They are defined in the chip-specific pinmap header file, for example [stm32f74xx75xx_pinmap.h](https://github.com/PX4/NuttX/blob/px4_firmware_nuttx-8.2/arch/arm/src/stm32f7/hardware/stm32f74xx75xx_pinmap.h). 5. **src**: go through all files under **src** and update them as needed, in particular **board_config.h**. 6. **init/rc.board_sensors**: start the sensors that are attached to the board. diff --git a/docs/uk/middleware/uxrce_dds.md b/docs/uk/middleware/uxrce_dds.md index dc42bc881f..613bb93f41 100644 --- a/docs/uk/middleware/uxrce_dds.md +++ b/docs/uk/middleware/uxrce_dds.md @@ -118,78 +118,78 @@ This considerably speeds up the build process but requires that the Agent depend 1. Створіть директорію робочого простору для агента: - ```sh - mkdir -p ~/px4_ros_uxrce_dds_ws/src - ``` + ```sh + mkdir -p ~/px4_ros_uxrce_dds_ws/src + ``` 2. Clone the source code for the eProsima [Micro-XRCE-DDS-Agent](https://github.com/eProsima/Micro-XRCE-DDS-Agent) to the `/src` directory (the `main` branch is cloned by default): - ```sh - cd ~/px4_ros_uxrce_dds_ws/src - git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git - ``` + ```sh + cd ~/px4_ros_uxrce_dds_ws/src + git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git + ``` 3. Source the ROS 2 development environment, and compile the workspace using `colcon`: - :::: tabs + :::: tabs - ::: tab humble + ::: tab humble - ```sh - source /opt/ros/humble/setup.bash - colcon build - ``` + ```sh + source /opt/ros/humble/setup.bash + colcon build + ``` ::: - ::: tab foxy + ::: tab foxy - ```sh - source /opt/ros/foxy/setup.bash - colcon build - ``` + ```sh + source /opt/ros/foxy/setup.bash + colcon build + ``` ::: - :::: + :::: - This builds all the folders under `/src` using the sourced toolchain. + This builds all the folders under `/src` using the sourced toolchain. Для запуску агента micro XRCE-DDS в робочому просторі: 1. Source the `local_setup.bash` to make the executables available in the terminal (also `setup.bash` if using a new terminal). - :::: tabs + :::: tabs - ::: tab humble + ::: tab humble - ```sh - source /opt/ros/humble/setup.bash - source install/local_setup.bash - ``` + ```sh + source /opt/ros/humble/setup.bash + source install/local_setup.bash + ``` ::: - ::: tab foxy + ::: tab foxy - ```sh - source /opt/ros/foxy/setup.bash - source install/local_setup.bash - ``` + ```sh + source /opt/ros/foxy/setup.bash + source install/local_setup.bash + ``` ::: - :::: + :::: 1) Запустіть агента з налаштуваннями для підключення до клієнта uXRCE-DDS, який працює на симуляторі: - ```sh - MicroXRCEAgent udp4 -p 8888 - ``` + ```sh + MicroXRCEAgent udp4 -p 8888 + ``` ## Запуск агента та клієнта @@ -466,15 +466,15 @@ Each (`topic`,`type`) pairs defines: 1. A new `publication`, `subscription`, or `subscriptions_multi`, depending on the list to which it is added. 2. The topic _base name_, which **must** coincide with the desired uORB topic name that you want to publish/subscribe. - It is identified by the last token in `topic:` that starts with `/` and does not contains any `/` in it. - `vehicle_odometry`, `vehicle_status` and `offboard_control_mode` are examples of base names. + It is identified by the last token in `topic:` that starts with `/` and does not contains any `/` in it. + `vehicle_odometry`, `vehicle_status` and `offboard_control_mode` are examples of base names. 3. The topic [namespace](https://design.ros2.org/articles/topic_and_service_names.html#namespaces). - By default it is set to: - - `/fmu/out/` for topics that are _published_ by PX4. - - `/fmu/in/` for topics that are _subscribed_ by PX4. + By default it is set to: + - `/fmu/out/` for topics that are _published_ by PX4. + - `/fmu/in/` for topics that are _subscribed_ by PX4. 4. The message type (`VehicleOdometry`, `VehicleStatus`, `OffboardControlMode`, etc.) and the ROS 2 package (`px4_msgs`) that is expected to provide the message definition. 5. **(Optional)**: An additional `rate_limit` field (only for publication entries), which specifies the maximum rate (Hz) at which messages will be published on this topic by PX4 to ROS 2. - If left unspecified, the maximum publication rate limit is set to 100 Hz. + If left unspecified, the maximum publication rate limit is set to 100 Hz. `subscriptions` and `subscriptions_multi` allow us to choose the uORB topic instance that ROS 2 topics are routed to: either a shared instance that may also be getting updates from internal PX4 uORB publishers, or a separate instance that is reserved for ROS2 publications, respectively. Without this mechanism all ROS 2 messages would be routed to the _same_ uORB topic instance (because ROS 2 does not have the concept of [multiple topic instances](../middleware/uorb.md#multi-instance)), and it would not be possible for PX4 subscribers to differentiate between streams from ROS 2 or PX4 publishers. diff --git a/docs/uk/modules/hello_sky.md b/docs/uk/modules/hello_sky.md index 93be69de26..80a2ad2685 100644 --- a/docs/uk/modules/hello_sky.md +++ b/docs/uk/modules/hello_sky.md @@ -28,151 +28,151 @@ This consists of a single _C_ file and a _cmake_ definition (which tells the too 1. Create a new directory **PX4-Autopilot/src/examples/px4_simple_app**. 2. Create a new C file in that directory named **px4_simple_app.c**: - - Скопіюйте заголовок за замовчуванням у верхній частині сторінки. - Це повинно бути присутнім у всіх розміщених файлах! + - Скопіюйте заголовок за замовчуванням у верхній частині сторінки. + Це повинно бути присутнім у всіх розміщених файлах! - ```c - /**************************************************************************** - * - * Copyright (c) 2012-2022 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - ``` + ```c + /**************************************************************************** + * + * Copyright (c) 2012-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + ``` - - Скопіюйте наступний код під заголовком за замовчуванням. - Це повинно бути присутнім у всіх розміщених файлах! + - Скопіюйте наступний код під заголовком за замовчуванням. + Це повинно бути присутнім у всіх розміщених файлах! - ```c - /** - * @file px4_simple_app.c - * Minimal application example for PX4 autopilot - * - * @author Example User - */ + ```c + /** + * @file px4_simple_app.c + * Minimal application example for PX4 autopilot + * + * @author Example User + */ - #include + #include - __EXPORT int px4_simple_app_main(int argc, char *argv[]); + __EXPORT int px4_simple_app_main(int argc, char *argv[]); - int px4_simple_app_main(int argc, char *argv[]) - { - PX4_INFO("Hello Sky!"); - return OK; - } - ``` + int px4_simple_app_main(int argc, char *argv[]) + { + PX4_INFO("Hello Sky!"); + return OK; + } + ``` - :::tip - The main function must be named `_main` and exported from the module as shown. + :::tip + The main function must be named `_main` and exported from the module as shown. ::: - :::tip - `PX4_INFO` is the equivalent of `printf` for the PX4 shell (included from **px4_platform_common/log.h**). - There are different log levels: `PX4_INFO`, `PX4_WARN`, `PX4_ERR`, `PX4_DEBUG`. - Warnings and errors are additionally added to the [ULog](../dev_log/ulog_file_format.md) and shown on [Flight Review](https://logs.px4.io/). + :::tip + `PX4_INFO` is the equivalent of `printf` for the PX4 shell (included from **px4_platform_common/log.h**). + There are different log levels: `PX4_INFO`, `PX4_WARN`, `PX4_ERR`, `PX4_DEBUG`. + Warnings and errors are additionally added to the [ULog](../dev_log/ulog_file_format.md) and shown on [Flight Review](https://logs.px4.io/). ::: 3. Create and open a new _cmake_ definition file named **CMakeLists.txt**. - Скопіюйте текст нижче: + Скопіюйте текст нижче: - ```cmake - ############################################################################ - # - # Copyright (c) 2015 PX4 Development Team. All rights reserved. - # - # Redistribution and use in source and binary forms, with or without - # modification, are permitted provided that the following conditions - # are met: - # - # 1. Redistributions of source code must retain the above copyright - # notice, this list of conditions and the following disclaimer. - # 2. Redistributions in binary form must reproduce the above copyright - # notice, this list of conditions and the following disclaimer in - # the documentation and/or other materials provided with the - # distribution. - # 3. Neither the name PX4 nor the names of its contributors may be - # used to endorse or promote products derived from this software - # without specific prior written permission. - # - # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - # OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - # AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - # POSSIBILITY OF SUCH DAMAGE. - # - ############################################################################ - px4_add_module( - MODULE examples__px4_simple_app - MAIN px4_simple_app - STACK_MAIN 2000 - SRCS - px4_simple_app.c - DEPENDS - ) - ``` + ```cmake + ############################################################################ + # + # Copyright (c) 2015 PX4 Development Team. All rights reserved. + # + # Redistribution and use in source and binary forms, with or without + # modification, are permitted provided that the following conditions + # are met: + # + # 1. Redistributions of source code must retain the above copyright + # notice, this list of conditions and the following disclaimer. + # 2. Redistributions in binary form must reproduce the above copyright + # notice, this list of conditions and the following disclaimer in + # the documentation and/or other materials provided with the + # distribution. + # 3. Neither the name PX4 nor the names of its contributors may be + # used to endorse or promote products derived from this software + # without specific prior written permission. + # + # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + # OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + # AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + # POSSIBILITY OF SUCH DAMAGE. + # + ############################################################################ + px4_add_module( + MODULE examples__px4_simple_app + MAIN px4_simple_app + STACK_MAIN 2000 + SRCS + px4_simple_app.c + DEPENDS + ) + ``` - The `px4_add_module()` method builds a static library from a module description. + The `px4_add_module()` method builds a static library from a module description. - - The `MODULE` block is the Firmware-unique name of the module (by convention the module name is prefixed by parent directories back to `src`). - - The `MAIN` block lists the entry point of the module, which registers the command with NuttX so that it can be called from the PX4 shell or SITL console. + - The `MODULE` block is the Firmware-unique name of the module (by convention the module name is prefixed by parent directories back to `src`). + - The `MAIN` block lists the entry point of the module, which registers the command with NuttX so that it can be called from the PX4 shell or SITL console. - :::tip - The `px4_add_module()` format is documented in [PX4-Autopilot/cmake/px4_add_module.cmake](https://github.com/PX4/PX4-Autopilot/blob/main/cmake/px4_add_module.cmake). + :::tip + The `px4_add_module()` format is documented in [PX4-Autopilot/cmake/px4_add_module.cmake](https://github.com/PX4/PX4-Autopilot/blob/main/cmake/px4_add_module.cmake). ::: - ::: info - If you specify `DYNAMIC` as an option to `px4_add_module`, a _shared library_ is created instead of a static library on POSIX platforms (these can be loaded without having to recompile PX4, and shared to others as binaries rather than source code). - Your app will not become a builtin command, but ends up in a separate file called `examples__px4_simple_app.px4mod`. - You can then run your command by loading the file at runtime using the `dyn` command: `dyn ./examples__px4_simple_app.px4mod` + ::: info + If you specify `DYNAMIC` as an option to `px4_add_module`, a _shared library_ is created instead of a static library on POSIX platforms (these can be loaded without having to recompile PX4, and shared to others as binaries rather than source code). + Your app will not become a builtin command, but ends up in a separate file called `examples__px4_simple_app.px4mod`. + You can then run your command by loading the file at runtime using the `dyn` command: `dyn ./examples__px4_simple_app.px4mod` ::: 4. Create and open a new _Kconfig_ definition file named **Kconfig** and define your symbol for naming (see [Kconfig naming convention](../hardware/porting_guide_config.md#px4-kconfig-symbol-naming-convention)). - Скопіюйте текст нижче: + Скопіюйте текст нижче: - ``` - menuconfig EXAMPLES_PX4_SIMPLE_APP - bool "px4_simple_app" - default n - ---help--- - Enable support for px4_simple_app - ``` + ``` + menuconfig EXAMPLES_PX4_SIMPLE_APP + bool "px4_simple_app" + default n + ---help--- + Enable support for px4_simple_app + ``` ## Побудуйте Програму/прошивку diff --git a/docs/uk/modules/module_template.md b/docs/uk/modules/module_template.md index c2cb88599f..93ed9e86de 100644 --- a/docs/uk/modules/module_template.md +++ b/docs/uk/modules/module_template.md @@ -22,27 +22,27 @@ PX4-Autopilot contains a template for writing a new application (module) that ru Підсумовуючи: 1. Specify the dependency on the work queue library in the cmake definition file ([CMakeLists.txt](https://github.com/PX4/PX4-Autopilot/blob/main/src/examples/work_item/CMakeLists.txt)): - ``` - ... - DEPENDS - px4_work_queue - ``` + ``` + ... + DEPENDS + px4_work_queue + ``` 2. In addition to `ModuleBase`, the task should also derive from `ScheduledWorkItem` (included from [ScheduledWorkItem.hpp](https://github.com/PX4/PX4-Autopilot/blob/main/platforms/common/include/px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp)) 3. Вкажіть чергу, до якої додати завдання у конструкторі ініціалізації. - The [work_item](https://github.com/PX4/PX4-Autopilot/blob/main/src/examples/work_item/WorkItemExample.cpp#L42) example adds itself to the `wq_configurations::test1` work queue as shown below: + The [work_item](https://github.com/PX4/PX4-Autopilot/blob/main/src/examples/work_item/WorkItemExample.cpp#L42) example adds itself to the `wq_configurations::test1` work queue as shown below: - ```cpp - WorkItemExample::WorkItemExample() : - ModuleParams(nullptr), - ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::test1) - { - } - ``` + ```cpp + WorkItemExample::WorkItemExample() : + ModuleParams(nullptr), + ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::test1) + { + } + ``` - ::: info - The available work queues (`wq_configurations`) are listed in [WorkQueueManager.hpp](https://github.com/PX4/PX4-Autopilot/blob/main/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp#L49). + ::: info + The available work queues (`wq_configurations`) are listed in [WorkQueueManager.hpp](https://github.com/PX4/PX4-Autopilot/blob/main/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp#L49). ::: diff --git a/docs/uk/modules/modules_driver_ins.md b/docs/uk/modules/modules_driver_ins.md index d0a35f7acb..c48ae1db0f 100644 --- a/docs/uk/modules/modules_driver_ins.md +++ b/docs/uk/modules/modules_driver_ins.md @@ -45,6 +45,41 @@ MicroStrain [arguments...] status Driver status ``` +## eulernav_bahrs + +Source: [drivers/ins/eulernav_bahrs](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/eulernav_bahrs) + +### Опис + +Serial bus driver for the EULER-NAV Baro-Inertial AHRS. + +### Приклади + +Attempt to start driver on a specified serial device. + +``` +eulernav_bahrs start -d /dev/ttyS1 +``` + +Stop driver + +``` +eulernav_bahrs stop +``` + +### Usage {#eulernav_bahrs_usage} + +``` +eulernav_bahrs [arguments...] + Commands: + start Start driver + -d Serial device + + status Print driver status + + stop Stop driver +``` + ## ilabs Source: [drivers/ins/ilabs](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/ilabs) diff --git a/docs/uk/msg_docs/ActionRequest.md b/docs/uk/msg_docs/ActionRequest.md index b18cf24d07..584b06d718 100644 --- a/docs/uk/msg_docs/ActionRequest.md +++ b/docs/uk/msg_docs/ActionRequest.md @@ -15,25 +15,25 @@ Request are published by `manual_control` and subscribed by the `commander` and # It allows mapping triggers from various external interfaces like RC channels or MAVLink to cause an action. # Request are published by `manual_control` and subscribed by the `commander` and `vtol_att_control` modules. -uint64 timestamp # [us] Time since system start +uint64 timestamp # [us] Time since system start -uint8 action # [@enum ACTION] Requested action -uint8 ACTION_DISARM = 0 # Disarm vehicle -uint8 ACTION_ARM = 1 # Arm vehicle -uint8 ACTION_TOGGLE_ARMING = 2 # Toggle arming -uint8 ACTION_UNKILL = 3 # Revert a kill action -uint8 ACTION_KILL = 4 # Kill vehicle (instantly stop the motors) -uint8 ACTION_SWITCH_MODE = 5 # Switch mode. The target mode is set in the `mode` field. -uint8 ACTION_VTOL_TRANSITION_TO_MULTICOPTER = 6 # Transition to hover flight -uint8 ACTION_VTOL_TRANSITION_TO_FIXEDWING = 7 # Transition to fast forward flight -uint8 ACTION_TERMINATION = 8 # Irreversably output failsafe values on all outputs, trigger parachute +uint8 action # [@enum ACTION] Requested action +uint8 ACTION_DISARM = 0 # Disarm vehicle +uint8 ACTION_ARM = 1 # Arm vehicle +uint8 ACTION_TOGGLE_ARMING = 2 # Toggle arming +uint8 ACTION_UNKILL = 3 # Revert a kill action +uint8 ACTION_KILL = 4 # Kill vehicle (instantly stop the motors) +uint8 ACTION_SWITCH_MODE = 5 # Switch mode. The target mode is set in the `mode` field. +uint8 ACTION_VTOL_TRANSITION_TO_MULTICOPTER = 6 # Transition to hover flight +uint8 ACTION_VTOL_TRANSITION_TO_FIXEDWING = 7 # Transition to fast forward flight +uint8 ACTION_TERMINATION = 8 # Irreversibly output failsafe values on all outputs, trigger parachute -uint8 source # [@enum SOURCE] Request trigger type, such as a switch, button or gesture -uint8 SOURCE_STICK_GESTURE = 0 # Triggered by holding the sticks in a certain position -uint8 SOURCE_RC_SWITCH = 1 # Triggered by an RC switch moving into a certain position -uint8 SOURCE_RC_BUTTON = 2 # Triggered by a momentary button on the RC being pressed or held -uint8 SOURCE_RC_MODE_SLOT = 3 # Mode change through the RC mode selection mechanism +uint8 source # [@enum SOURCE] Request trigger type, such as a switch, button or gesture +uint8 SOURCE_STICK_GESTURE = 0 # Triggered by holding the sticks in a certain position +uint8 SOURCE_RC_SWITCH = 1 # Triggered by an RC switch moving into a certain position +uint8 SOURCE_RC_BUTTON = 2 # Triggered by a momentary button on the RC being pressed or held +uint8 SOURCE_RC_MODE_SLOT = 3 # Mode change through the RC mode selection mechanism -uint8 mode # Requested mode. Only applies when `action` is `ACTION_SWITCH_MODE`. Values for this field are defined by the `vehicle_status_s::NAVIGATION_STATE_*` enumeration. +uint8 mode # Requested mode. Only applies when `action` is `ACTION_SWITCH_MODE`. Values for this field are defined by the `vehicle_status_s::NAVIGATION_STATE_*` enumeration. ``` diff --git a/docs/uk/msg_docs/ActuatorMotors.md b/docs/uk/msg_docs/ActuatorMotors.md index dfce383e9c..f35f523185 100644 --- a/docs/uk/msg_docs/ActuatorMotors.md +++ b/docs/uk/msg_docs/ActuatorMotors.md @@ -15,14 +15,14 @@ Published by the vehicle's allocation and consumed by the ESC protocol drivers e uint32 MESSAGE_VERSION = 0 -uint64 timestamp # [us] Time since system start -uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on -uint16 reversible_flags # Bitset indicating which motors are configured to be reversible +uint16 reversible_flags # Bitset indicating which motors are configured to be reversible -uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 +uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 # -uint8 NUM_CONTROLS = 12 -float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) +uint8 NUM_CONTROLS = 12 # +float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) ``` diff --git a/docs/uk/msg_docs/ActuatorServos.md b/docs/uk/msg_docs/ActuatorServos.md index fcbb45d0b1..530331c16b 100644 --- a/docs/uk/msg_docs/ActuatorServos.md +++ b/docs/uk/msg_docs/ActuatorServos.md @@ -15,10 +15,10 @@ Published by the vehicle's allocation and consumed by the actuator output driver uint32 MESSAGE_VERSION = 0 -uint64 timestamp # [us] Time since system start -uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on -uint8 NUM_CONTROLS = 8 -float32[8] control # [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. +uint8 NUM_CONTROLS = 8 # +float32[8] control # [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. ``` diff --git a/docs/uk/msg_docs/Airspeed.md b/docs/uk/msg_docs/Airspeed.md index 3748e60b12..8717f30d78 100644 --- a/docs/uk/msg_docs/Airspeed.md +++ b/docs/uk/msg_docs/Airspeed.md @@ -13,10 +13,10 @@ It is subscribed by the airspeed selector module, which validates the data from # This is published by airspeed sensor drivers, CAN airspeed sensors, simulators. # It is subscribed by the airspeed selector module, which validates the data from multiple sensors and passes on a single estimation to the EKF, controllers and telemetry providers. -uint64 timestamp # [us] Time since system start -uint64 timestamp_sample # [us] Timestamp of the raw data -float32 indicated_airspeed_m_s # [m/s] Indicated airspeed -float32 true_airspeed_m_s # [m/s] True airspeed -float32 confidence # [@range 0,1] Confidence value for this sensor +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Timestamp of the raw data +float32 indicated_airspeed_m_s # [m/s] Indicated airspeed +float32 true_airspeed_m_s # [m/s] True airspeed +float32 confidence # [@range 0,1] Confidence value for this sensor ``` diff --git a/docs/uk/msg_docs/ArmingCheckReply.md b/docs/uk/msg_docs/ArmingCheckReply.md index c6d4ff02b7..97347eaa8d 100644 --- a/docs/uk/msg_docs/ArmingCheckReply.md +++ b/docs/uk/msg_docs/ArmingCheckReply.md @@ -21,39 +21,39 @@ The message is not used by internal/FMU components, as their mode requirements a # Note that the external component is identified by its registration_id, which is allocated to the component during registration (arming_check_id in RegisterExtComponentReply). # The message is not used by internal/FMU components, as their mode requirements are known at compile time. -uint32 MESSAGE_VERSION = 1 +uint32 MESSAGE_VERSION = 1 uint64 timestamp # [us] Time since system start. -uint8 request_id # Id of ArmingCheckRequest for which this is a response. -uint8 registration_id # Id of external component emitting this response. +uint8 request_id # Id of ArmingCheckRequest for which this is a response. +uint8 registration_id # Id of external component emitting this response. -uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies. +uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies. -uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX] -bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json). +uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX] +bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json). +bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json). +bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json). -bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed. +bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed. -uint8 num_events # Number of queued failure messages (Event) in the events field. +uint8 num_events # Number of queued failure messages (Event) in the events field. -Event[5] events # Arming failure reasons (Queue of events to report to GCS). +Event[5] events # Arming failure reasons (Queue of events to report to GCS). # Mode requirements -bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope). -bool mode_req_attitude # Requires an attitude estimate. -bool mode_req_local_alt # Requires a local altitude estimate. -bool mode_req_local_position # Requires a local position estimate. -bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate. -bool mode_req_global_position # Requires a global position estimate. -bool mode_req_global_position_relaxed # Requires a relaxed global position estimate. -bool mode_req_mission # Requires an uploaded mission. -bool mode_req_home_position # Requires a home position (such as RTL/Return mode). -bool mode_req_prevent_arming # Prevent arming (such as in Land mode). -bool mode_req_manual_control # Requires a manual controller +bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope). +bool mode_req_attitude # Requires an attitude estimate. +bool mode_req_local_alt # Requires a local altitude estimate. +bool mode_req_local_position # Requires a local position estimate. +bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate. +bool mode_req_global_position # Requires a global position estimate. +bool mode_req_global_position_relaxed # Requires a relaxed global position estimate. +bool mode_req_mission # Requires an uploaded mission. +bool mode_req_home_position # Requires a home position (such as RTL/Return mode). +bool mode_req_prevent_arming # Prevent arming (such as in Land mode). +bool mode_req_manual_control # Requires a manual controller -uint8 ORB_QUEUE_LENGTH = 4 # +uint8 ORB_QUEUE_LENGTH = 4 ``` diff --git a/docs/uk/msg_docs/ArmingCheckRequest.md b/docs/uk/msg_docs/ArmingCheckRequest.md index 07ab3706a3..a919ec405a 100644 --- a/docs/uk/msg_docs/ArmingCheckRequest.md +++ b/docs/uk/msg_docs/ArmingCheckRequest.md @@ -21,10 +21,12 @@ The reply will also include the registration_id for each external component, pro # The reply will include the published request_id, allowing correlation of all arming check information for a particular request. # The reply will also include the registration_id for each external component, provided to it during the registration process (RegisterExtComponentReply). -uint32 MESSAGE_VERSION = 0 +uint32 MESSAGE_VERSION = 1 -uint64 timestamp # [us] Time since system start. +uint64 timestamp # [us] Time since system start. -uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. +uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. + +uint32 valid_registrations_mask # Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) ``` diff --git a/docs/uk/msg_docs/ArmingCheckRequestV0.md b/docs/uk/msg_docs/ArmingCheckRequestV0.md new file mode 100644 index 0000000000..f5680c11f2 --- /dev/null +++ b/docs/uk/msg_docs/ArmingCheckRequestV0.md @@ -0,0 +1,30 @@ +# ArmingCheckRequestV0 (UORB message) + +Arming check request. + +Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. +All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. +The request is sent regularly, even while armed, so that the FMU always knows the current arming state for external modes, and can forward it to ground stations. + +The reply will include the published request_id, allowing correlation of all arming check information for a particular request. +The reply will also include the registration_id for each external component, provided to it during the registration process (RegisterExtComponentReply). + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/ArmingCheckRequestV0.msg) + +```c +# Arming check request. +# +# Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. +# All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. +# The request is sent regularly, even while armed, so that the FMU always knows the current arming state for external modes, and can forward it to ground stations. +# +# The reply will include the published request_id, allowing correlation of all arming check information for a particular request. +# The reply will also include the registration_id for each external component, provided to it during the registration process (RegisterExtComponentReply). + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # [us] Time since system start. + +uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. + +``` diff --git a/docs/uk/msg_docs/CellularStatus.md b/docs/uk/msg_docs/CellularStatus.md index 1bf03491d9..9ba5a00378 100644 --- a/docs/uk/msg_docs/CellularStatus.md +++ b/docs/uk/msg_docs/CellularStatus.md @@ -11,39 +11,39 @@ This is currently used only for logging cell status from MAVLink. # # This is currently used only for logging cell status from MAVLink. -uint64 timestamp # [us] Time since system start +uint64 timestamp # [us] Time since system start -uint16 status # [@enum STATUS_FLAG] Status bitmap -uint16 STATUS_FLAG_UNKNOWN = 1 # State unknown or not reportable -uint16 STATUS_FLAG_FAILED = 2 # Modem is unusable -uint16 STATUS_FLAG_INITIALIZING = 4 # Modem is being initialized -uint16 STATUS_FLAG_LOCKED = 8 # Modem is locked -uint16 STATUS_FLAG_DISABLED = 16 # Modem is not enabled and is powered down -uint16 STATUS_FLAG_DISABLING = 32 # Modem is currently transitioning to the STATUS_FLAG_DISABLED state -uint16 STATUS_FLAG_ENABLING = 64 # Modem is currently transitioning to the STATUS_FLAG_ENABLED state -uint16 STATUS_FLAG_ENABLED = 128 # Modem is enabled and powered on but not registered with a network provider and not available for data connections -uint16 STATUS_FLAG_SEARCHING = 256 # Modem is searching for a network provider to register -uint16 STATUS_FLAG_REGISTERED = 512 # Modem is registered with a network provider, and data connections and messaging may be available for use -uint16 STATUS_FLAG_DISCONNECTING = 1024 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated -uint16 STATUS_FLAG_CONNECTING = 2048 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered -uint16 STATUS_FLAG_CONNECTED = 4096 # One or more packet data bearers is active and connected +uint16 status # [@enum STATUS_FLAG] Status bitmap +uint16 STATUS_FLAG_UNKNOWN = 1 # State unknown or not reportable +uint16 STATUS_FLAG_FAILED = 2 # Modem is unusable +uint16 STATUS_FLAG_INITIALIZING = 4 # Modem is being initialized +uint16 STATUS_FLAG_LOCKED = 8 # Modem is locked +uint16 STATUS_FLAG_DISABLED = 16 # Modem is not enabled and is powered down +uint16 STATUS_FLAG_DISABLING = 32 # Modem is currently transitioning to the STATUS_FLAG_DISABLED state +uint16 STATUS_FLAG_ENABLING = 64 # Modem is currently transitioning to the STATUS_FLAG_ENABLED state +uint16 STATUS_FLAG_ENABLED = 128 # Modem is enabled and powered on but not registered with a network provider and not available for data connections +uint16 STATUS_FLAG_SEARCHING = 256 # Modem is searching for a network provider to register +uint16 STATUS_FLAG_REGISTERED = 512 # Modem is registered with a network provider, and data connections and messaging may be available for use +uint16 STATUS_FLAG_DISCONNECTING = 1024 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated +uint16 STATUS_FLAG_CONNECTING = 2048 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered +uint16 STATUS_FLAG_CONNECTED = 4096 # One or more packet data bearers is active and connected -uint8 failure_reason # [@enum FAILURE_REASON] Failure reason -uint8 FAILURE_REASON_NONE = 0 # No error -uint8 FAILURE_REASON_UNKNOWN = 1 # Error state is unknown -uint8 FAILURE_REASON_SIM_MISSING = 2 # SIM is required for the modem but missing -uint8 FAILURE_REASON_SIM_ERROR = 3 # SIM is available, but not usable for connection +uint8 failure_reason # [@enum FAILURE_REASON] Failure reason +uint8 FAILURE_REASON_NONE = 0 # No error +uint8 FAILURE_REASON_UNKNOWN = 1 # Error state is unknown +uint8 FAILURE_REASON_SIM_MISSING = 2 # SIM is required for the modem but missing +uint8 FAILURE_REASON_SIM_ERROR = 3 # SIM is available, but not usable for connection -uint8 type # [@enum CELLULAR_NETWORK_RADIO_TYPE] Cellular network radio type -uint8 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0 # None -uint8 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1 # GSM -uint8 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2 # CDMA -uint8 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3 # WCDMA -uint8 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4 # LTE +uint8 type # [@enum CELLULAR_NETWORK_RADIO_TYPE] Cellular network radio type +uint8 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0 # None +uint8 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1 # GSM +uint8 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2 # CDMA +uint8 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3 # WCDMA +uint8 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4 # LTE -uint8 quality # [dBm] Cellular network RSSI/RSRP, absolute value -uint16 mcc # [@invalid UINT16_MAX] Mobile country code -uint16 mnc # [@invalid UINT16_MAX] Mobile network code -uint16 lac # [@invalid 0] Location area code +uint8 quality # [dBm] Cellular network RSSI/RSRP, absolute value +uint16 mcc # [@invalid UINT16_MAX] Mobile country code +uint16 mnc # [@invalid UINT16_MAX] Mobile network code +uint16 lac # [@invalid 0] Location area code ``` diff --git a/docs/uk/msg_docs/RoverSpeedSetpoint.md b/docs/uk/msg_docs/RoverSpeedSetpoint.md new file mode 100644 index 0000000000..9eea46e60f --- /dev/null +++ b/docs/uk/msg_docs/RoverSpeedSetpoint.md @@ -0,0 +1,14 @@ +# RoverSpeedSetpoint (UORB message) + +Rover Speed Setpoint + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverSpeedSetpoint.msg) + +```c +# Rover Speed Setpoint + +uint64 timestamp # [us] Time since system start +float32 speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction +float32 speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction + +``` diff --git a/docs/uk/msg_docs/RoverSpeedStatus.md b/docs/uk/msg_docs/RoverSpeedStatus.md new file mode 100644 index 0000000000..8c212e2b0f --- /dev/null +++ b/docs/uk/msg_docs/RoverSpeedStatus.md @@ -0,0 +1,18 @@ +# RoverSpeedStatus (UORB message) + +Rover Velocity Status + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverSpeedStatus.msg) + +```c +# Rover Velocity Status + +uint64 timestamp # [us] Time since system start +float32 measured_speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Measured speed in body x direction +float32 adjusted_speed_body_x_setpoint # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction that is being tracked (Applied slew rates) +float32 pid_throttle_body_x_integral # [] [@range -1, 1] Integral of the PID for the closed loop controller of the speed in body x direction +float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction +float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates) +float32 pid_throttle_body_y_integral # [] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction + +``` diff --git a/docs/uk/msg_docs/VehicleAirData.md b/docs/uk/msg_docs/VehicleAirData.md index add8c771a8..738f52402e 100644 --- a/docs/uk/msg_docs/VehicleAirData.md +++ b/docs/uk/msg_docs/VehicleAirData.md @@ -1,22 +1,26 @@ # VehicleAirData (повідомлення UORB) +Vehicle air data + +Data from the currently selected barometer (plus ambient temperature from the source specified in temperature_source). +Includes calculated data such as barometric altitude and air density. + [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleAirData.msg) ```c +# Vehicle air data +# +# Data from the currently selected barometer (plus ambient temperature from the source specified in temperature_source). +# Includes calculated data such as barometric altitude and air density. -uint64 timestamp # time since system start (microseconds) - -uint64 timestamp_sample # the timestamp of the raw data (microseconds) - -uint32 baro_device_id # unique device ID for the selected barometer - -float32 baro_alt_meter # Altitude above MSL calculated from temperature compensated baro sensor data using an ISA corrected for sea level pressure SENS_BARO_QNH. -float32 baro_pressure_pa # Absolute pressure in Pascals -float32 ambient_temperature # Abient temperature in degrees Celsius -uint8 temperature_source # Source of temperature data: 0: Default Temperature (15°C), 1: External Baro, 2: Airspeed - -float32 rho # air density - -uint8 calibration_count # Calibration changed counter. Monotonically increases whenever calibration changes. +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Timestamp of the raw data +uint32 baro_device_id # Unique device ID for the selected barometer +float32 baro_alt_meter # [m] [@frame MSL] Altitude above MSL calculated from temperature compensated baro sensor data using an ISA corrected for sea level pressure SENS_BARO_QNH +float32 baro_pressure_pa # [Pa] Absolute pressure +float32 ambient_temperature # [degC] Ambient temperature +uint8 temperature_source # Source of temperature data: 0: Default Temperature (15°C), 1: External Baro, 2: Airspeed +float32 rho # [kg/m^3] Air density +uint8 calibration_count # Calibration changed counter. Monotonically increases whenever calibration changes. ``` diff --git a/docs/uk/msg_docs/index.md b/docs/uk/msg_docs/index.md index 3d2a4443c1..b4f0082888 100644 --- a/docs/uk/msg_docs/index.md +++ b/docs/uk/msg_docs/index.md @@ -229,10 +229,10 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [RoverPositionSetpoint](RoverPositionSetpoint.md) — Rover Position Setpoint - [RoverRateSetpoint](RoverRateSetpoint.md) — Rover Rate setpoint - [RoverRateStatus](RoverRateStatus.md) — Rover Rate Status +- [RoverSpeedSetpoint](RoverSpeedSetpoint.md) — Rover Speed Setpoint +- [RoverSpeedStatus](RoverSpeedStatus.md) — Rover Velocity Status - [RoverSteeringSetpoint](RoverSteeringSetpoint.md) — Rover Steering setpoint - [RoverThrottleSetpoint](RoverThrottleSetpoint.md) — Rover Throttle setpoint -- [RoverVelocitySetpoint](RoverVelocitySetpoint.md) — Rover Velocity Setpoint -- [RoverVelocityStatus](RoverVelocityStatus.md) — Rover Velocity Status - [Rpm](Rpm.md) - [RtlStatus](RtlStatus.md) - [RtlTimeEstimate](RtlTimeEstimate.md) @@ -281,7 +281,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [UlogStreamAck](UlogStreamAck.md) — Ack a previously sent ulog_stream message that had the NEED_ACK flag set - [VehicleAcceleration](VehicleAcceleration.md) -- [VehicleAirData](VehicleAirData.md) +- [VehicleAirData](VehicleAirData.md) — Vehicle air data - [VehicleAngularAccelerationSetpoint](VehicleAngularAccelerationSetpoint.md) - [VehicleConstraints](VehicleConstraints.md) — Local setpoint constraints in NED frame setting something to NaN means that no limit is provided @@ -301,6 +301,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [YawEstimatorStatus](YawEstimatorStatus.md) - [AirspeedValidatedV0](AirspeedValidatedV0.md) - [ArmingCheckReplyV0](ArmingCheckReplyV0.md) +- [ArmingCheckRequestV0](ArmingCheckRequestV0.md) — Arming check request. - [BatteryStatusV0](BatteryStatusV0.md) — Battery status - [EventV0](EventV0.md) — this message is required here in the msg_old folder because other msg are depending on it Events interface diff --git a/docs/uk/payloads/generic_actuator_control.md b/docs/uk/payloads/generic_actuator_control.md index 17f9c27b0c..4d1f9c6e66 100644 --- a/docs/uk/payloads/generic_actuator_control.md +++ b/docs/uk/payloads/generic_actuator_control.md @@ -60,7 +60,7 @@ - Виберіть заголовок у редакторі маршрутної точки місії, щоб відкрити редактор **Select Mission Command**. - Виберіть категорію **Advanced**, а потім пункт **Set actuator** (якщо елемента немає, спробуйте новішу версію _QGroundControl_ або щоденну збірку). - Це змінить тип елемента місії на «Set actuator». + Це змінить тип елемента місії на «Set actuator». 3. Виберіть підключені приводи та встановіть їхні значення (вони нормалізовані між -1 і 1). diff --git a/docs/uk/peripherals/gripper.md b/docs/uk/peripherals/gripper.md index 0982b2f9fb..26c3d3bc35 100644 --- a/docs/uk/peripherals/gripper.md +++ b/docs/uk/peripherals/gripper.md @@ -75,13 +75,13 @@ For grippers that do not provide sensor-based feedback of their state, which is - Run the `payload_deliverer` test in the QGC [MAVLink Shell](../debug/mavlink_shell.md): - ```sh - > payload_deliverer gripper_test - ``` + ```sh + > payload_deliverer gripper_test + ``` - ::: info - If you get an error message like "[payload_deliverer] not running", repeat the setup procedures above. - You might also run the `payload_deliverer start` command in the Nuttx shell. + ::: info + If you get an error message like "[payload_deliverer] not running", repeat the setup procedures above. + You might also run the `payload_deliverer start` command in the Nuttx shell. ::: diff --git a/docs/uk/peripherals/remote_id.md b/docs/uk/peripherals/remote_id.md index dd5714d51a..c2673dae23 100644 --- a/docs/uk/peripherals/remote_id.md +++ b/docs/uk/peripherals/remote_id.md @@ -245,11 +245,11 @@ If the Remote ID CAN node is present and the messages are not being received, th 2. Navigate to the [Application settings](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/settings_view/general.html): **Application Settings > General > Miscellaneous**. 3. Select `Enable Remote ID`. - The Remote ID tab should appear. + The Remote ID tab should appear. - ::: info - If this option is not present you may be in a very recent version of QGC. - In that case, open the view at: **Application Settings > Remote ID**. + ::: info + If this option is not present you may be in a very recent version of QGC. + In that case, open the view at: **Application Settings > Remote ID**. ::: diff --git a/docs/uk/releases/1.14.md b/docs/uk/releases/1.14.md index 8bcf3d1dff..0118ab0be6 100644 --- a/docs/uk/releases/1.14.md +++ b/docs/uk/releases/1.14.md @@ -72,18 +72,18 @@ For users upgrading from previous versions, please take a moment to review the f 1. Для змін актуатора необхідно перевірити геометрію автомобіля та зв'язки моторів/сервоприводів з вашим автомобілем. In QGC, find the [Actuator Configuration Dashboard](../config/actuators.md), and make sure to confirm the airframe geometry matches actuals from your vehicle, as well as update motor and ensure motors and servos are mapped to outputs as they are wired to the frame and with the correct ESC type specified. Примітка: скористайтеся повзунками в користувацькому інтерфейсі. Вони можуть бути використані для підтвердження з'єднання моторів. - We highly recommend running an [ESC Calibration](../advanced_config/esc_calibration.md) if using PWM ESC motors and then setting appropriate disarmed minimum and maximum values for the motors (in the actuator UI). + We highly recommend running an [ESC Calibration](../advanced_config/esc_calibration.md) if using PWM ESC motors and then setting appropriate disarmed minimum and maximum values for the motors (in the actuator UI). - Калібрування є критичним, якщо ви використовуєте власний файл змішувача або повітряну конструкцію, яку ви призначили в попередній версії, немає в PX4 v1.14. + Калібрування є критичним, якщо ви використовуєте власний файл змішувача або повітряну конструкцію, яку ви призначили в попередній версії, немає в PX4 v1.14. - However, an ESC Calibration is still recommended **even if** you are using an airframe that precisely matches a specific vehicle in the [Airframe Reference](../airframes/airframe_reference.md) (such as the [Holybro X500 V2](../airframes/airframe_reference.md#copter_quadrotor_x_holybro_x500_v2)) as your wiring and ESCs calibration may not match the defaults. + However, an ESC Calibration is still recommended **even if** you are using an airframe that precisely matches a specific vehicle in the [Airframe Reference](../airframes/airframe_reference.md) (such as the [Holybro X500 V2](../airframes/airframe_reference.md#copter_quadrotor_x_holybro_x500_v2)) as your wiring and ESCs calibration may not match the defaults. 2. Змінено значення вимкненого PWM за замовчуванням з 900 мкс на 1000 мкс. - Перевірте, чи ви раніше використовували значення роззброєння PWM за замовчуванням і якщо зміни впливають на вашу настройку. - For details, you can find related information in the [step 7 of ESC calibration](../advanced_config/esc_calibration.md#steps) document. + Перевірте, чи ви раніше використовували значення роззброєння PWM за замовчуванням і якщо зміни впливають на вашу настройку. + For details, you can find related information in the [step 7 of ESC calibration](../advanced_config/esc_calibration.md#steps) document. 3. Користувачам Fast-RTPS потрібно перенести свій код на новий інтерфейс uXRCE-DDS. - Код програми повинен вимагати лише незначних модифікацій. Це включає (мінімально): + Код програми повинен вимагати лише незначних модифікацій. Це включає (мінімально): Modifying topic names to match the new naming pattern, which changed from `fmu//out` to `fmu/out/`, and [Adusting the QoS settings](../ros2/user_guide.md#ros-2-subscriber-qos-settings). diff --git a/docs/uk/releases/main.md b/docs/uk/releases/main.md index a3472a434f..b2e252a05d 100644 --- a/docs/uk/releases/main.md +++ b/docs/uk/releases/main.md @@ -52,7 +52,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Датчики -- Уточнюється +- Add [sbgECom INS driver](../sensor/sbgecom.md) ([PX4-Autopilot#24137](https://github.com/PX4/PX4-Autopilot/pull/24137)) ### Симуляція diff --git a/docs/uk/ros/mavros_custom_messages.md b/docs/uk/ros/mavros_custom_messages.md index 253bffbb45..23fb6960f1 100644 --- a/docs/uk/ros/mavros_custom_messages.md +++ b/docs/uk/ros/mavros_custom_messages.md @@ -110,7 +110,7 @@ Follow _Source Installation_ instructions from [mavlink/mavros](https://github.c - `PX4-Autopilot/src/modules/mavlink/mavlink/message_definitions/v1.0` - `workspace/src/mavlink/message_definitions/v1.0` - are exactly the same. + are exactly the same. ::: diff --git a/docs/uk/ros/mavros_installation.md b/docs/uk/ros/mavros_installation.md index 840d1a8102..b486ce151e 100644 --- a/docs/uk/ros/mavros_installation.md +++ b/docs/uk/ros/mavros_installation.md @@ -148,21 +148,21 @@ $ wstool init ~/catkin_ws/src 2. Встановити MAVROS з джерела, використовуючи як випущену, так і останню версію: - Випущений реліз/стабільний - ```sh - rosinstall_generator --upstream mavros | tee -a /tmp/mavros.rosinstall - ``` + ```sh + rosinstall_generator --upstream mavros | tee -a /tmp/mavros.rosinstall + ``` - Найновіше джерело - ```sh - rosinstall_generator --upstream-development mavros | tee -a /tmp/mavros.rosinstall - ``` + ```sh + rosinstall_generator --upstream-development mavros | tee -a /tmp/mavros.rosinstall + ``` - ```sh - # For fetching all the dependencies into your catkin_ws, - # just add '--deps' to the above scripts, E.g.: - # rosinstall_generator --upstream mavros --deps | tee -a /tmp/mavros.rosinstall - ``` + ```sh + # For fetching all the dependencies into your catkin_ws, + # just add '--deps' to the above scripts, E.g.: + # rosinstall_generator --upstream mavros --deps | tee -a /tmp/mavros.rosinstall + ``` 3. Create workspace & deps diff --git a/docs/uk/ros/offboard_control.md b/docs/uk/ros/offboard_control.md index aead2313e2..4908421e29 100644 --- a/docs/uk/ros/offboard_control.md +++ b/docs/uk/ros/offboard_control.md @@ -38,9 +38,9 @@ Enable MAVLink on the serial port that you connect to the companion computer (se 1. Один підключений до UART порту автопілота 2. Один підключений до наземної станції - Приклад радіомодулів включає: + Приклад радіомодулів включає: - - [Digi International XBee Pro](https://www.digi.com/products/embedded-systems/digi-xbee/rf-modules/sub-1-ghz-rf-modules) + - [Digi International XBee Pro](https://www.digi.com/products/embedded-systems/digi-xbee/rf-modules/sub-1-ghz-rf-modules) [![Mermaid graph: mavlink channel](https://mermaid.ink/img/eyJjb2RlIjoiZ3JhcGggVEQ7XG4gIGduZFtHcm91bmQgU3RhdGlvbl0gLS1NQVZMaW5rLS0-IHJhZDFbR3JvdW5kIFJhZGlvXTtcbiAgcmFkMSAtLVJhZGlvUHJvdG9jb2wtLT4gcmFkMltWZWhpY2xlIFJhZGlvXTtcbiAgcmFkMiAtLU1BVkxpbmstLT4gYVtBdXRvcGlsb3RdOyIsIm1lcm1haWQiOnsidGhlbWUiOiJkZWZhdWx0In0sInVwZGF0ZUVkaXRvciI6ZmFsc2V9)](https://mermaid-js.github.io/mermaid-live-editor/#/edit/eyJjb2RlIjoiZ3JhcGggVEQ7XG4gIGduZFtHcm91bmQgU3RhdGlvbl0gLS1NQVZMaW5rLS0-IHJhZDFbR3JvdW5kIFJhZGlvXTtcbiAgcmFkMSAtLVJhZGlvUHJvdG9jb2wtLT4gcmFkMltWZWhpY2xlIFJhZGlvXTtcbiAgcmFkMiAtLU1BVkxpbmstLT4gYVtBdXRvcGlsb3RdOyIsIm1lcm1haWQiOnsidGhlbWUiOiJkZWZhdWx0In0sInVwZGF0ZUVkaXRvciI6ZmFsc2V9) diff --git a/docs/uk/ros2/px4_ros2_control_interface.md b/docs/uk/ros2/px4_ros2_control_interface.md index 8c3fb9e5f6..3eb6178220 100644 --- a/docs/uk/ros2/px4_ros2_control_interface.md +++ b/docs/uk/ros2/px4_ros2_control_interface.md @@ -109,92 +109,92 @@ Unless the mode is safety-critical, requires strict timing or very high update r 2. Клонуйте репозиторій в робочий простір: - ```sh - cd $ros_workspace/src - git clone --recursive https://github.com/Auterion/px4-ros2-interface-lib - ``` + ```sh + cd $ros_workspace/src + git clone --recursive https://github.com/Auterion/px4-ros2-interface-lib + ``` - :::info - Для забезпечення сумісності, використовуйте останні _main_ гілки для PX4, _px4_msgs_ та бібліотеки. - Дивіться також [here](https://github.com/Auterion/px4-ros2-interface-lib#compatibility-with-px4). + :::info + Для забезпечення сумісності, використовуйте останні _main_ гілки для PX4, _px4_msgs_ та бібліотеки. + Дивіться також [here](https://github.com/Auterion/px4-ros2-interface-lib#compatibility-with-px4). ::: 3. Побудуйте робочий простір: - ```sh - cd .. - colcon build - source install/setup.bash - ``` + ```sh + cd .. + colcon build + source install/setup.bash + ``` 4. У іншій оболонці запустіть PX4 SITL: - ```sh - cd $px4-autopilot - make px4_sitl gazebo-classic - ``` + ```sh + cd $px4-autopilot + make px4_sitl gazebo-classic + ``` - (тут ми використовуємо Gazebo-Classic, але ви можете використовувати будь-яку модель або симулятор) + (тут ми використовуємо Gazebo-Classic, але ви можете використовувати будь-яку модель або симулятор) 5. Запустіть агента micro XRCE в новій оболонці (після цього ви можете залишити його запущеним): - ```sh - MicroXRCEAgent udp4 -p 8888 - ``` + ```sh + MicroXRCEAgent udp4 -p 8888 + ``` 6. Запустіть QGroundControl. - :::info - Використовуйте QGroundControl Daily, яка підтримує динамічне оновлення списку режимів. + :::info + Використовуйте QGroundControl Daily, яка підтримує динамічне оновлення списку режимів. ::: 7. Повернутись до терміналу 2 ROS, запустити один із прикладів: - ```sh - ros2 run example_mode_manual_cpp example_mode_manual - ``` + ```sh + ros2 run example_mode_manual_cpp example_mode_manual + ``` - Ви повинні отримати на виході режим 'Мій ручний режим' зареєстрований: + Ви повинні отримати на виході режим 'Мій ручний режим' зареєстрований: - ```sh - [DEBUG] [example_mode_manual]: Checking message compatibility... - [DEBUG] [example_mode_manual]: Subscriber found, continuing - [DEBUG] [example_mode_manual]: Publisher found, continuing - [DEBUG] [example_mode_manual]: Registering 'My Manual Mode' (arming check: 1, mode: 1, mode executor: 0) - [DEBUG] [example_mode_manual]: Subscriber found, continuing - [DEBUG] [example_mode_manual]: Publisher found, continuing - [DEBUG] [example_mode_manual]: Got RegisterExtComponentReply - [DEBUG] [example_mode_manual]: Arming check request (id=1, only printed once) - ``` + ```sh + [DEBUG] [example_mode_manual]: Checking message compatibility... + [DEBUG] [example_mode_manual]: Subscriber found, continuing + [DEBUG] [example_mode_manual]: Publisher found, continuing + [DEBUG] [example_mode_manual]: Registering 'My Manual Mode' (arming check: 1, mode: 1, mode executor: 0) + [DEBUG] [example_mode_manual]: Subscriber found, continuing + [DEBUG] [example_mode_manual]: Publisher found, continuing + [DEBUG] [example_mode_manual]: Got RegisterExtComponentReply + [DEBUG] [example_mode_manual]: Arming check request (id=1, only printed once) + ``` 8. На PX4 оболонці ви можете перевірити, що PX4 зареєстрував новий режим: - ```sh - commander status - ``` + ```sh + commander status + ``` - Вихід має містити: + Вихід має містити: - ```plain - INFO [commander] Disarmed - INFO [commander] navigation mode: Position - INFO [commander] user intended navigation mode: Position - INFO [commander] in failsafe: no - INFO [commander] External Mode 1: nav_state: 23, name: My Manual Mode - ``` + ```plain + INFO [commander] Disarmed + INFO [commander] navigation mode: Position + INFO [commander] user intended navigation mode: Position + INFO [commander] in failsafe: no + INFO [commander] External Mode 1: nav_state: 23, name: My Manual Mode + ``` 9. У цій точці ви також повинні побачити режим в QGroundControl : 10. Виберіть режим, переконайтеся, що у вас є ручне джерело управління (фізичний або віртуальний джойстик), та озброєння транспорту. - Тоді режим активується, і він має вивести наступний вивід: + Тоді режим активується, і він має вивести наступний вивід: - ```sh - [DEBUG] [example_mode_manual]: Mode 'My Manual Mode' activated - ``` + ```sh + [DEBUG] [example_mode_manual]: Mode 'My Manual Mode' activated + ``` 11. Тепер ви готові створити свій власний режим. @@ -420,7 +420,7 @@ This setpoint is streamed to the PX4 [_FwLateralLongitudinalControl_ module](../ To control the vehicle, at least one lateral **and** one longitudinal setpoint must be provided: 1. Of the longitudinal inputs: either `altitude` or `height_rate` must be finite to control vertical motion. - If both are set to `NAN`, the vehicle will maintain its current altitude. + If both are set to `NAN`, the vehicle will maintain its current altitude. 2. Of the lateral inputs: at least one of `course`, `airspeed_direction`, or `lateral_acceleration` must be finite. For a detailed description of the controllable parameters, please refer to message definitions ([FixedWingLateralSetpoint](../msg_docs/FixedWingLateralSetpoint.md) and [FixedWingLongitudinalSetpoint](../msg_docs/FixedWingLongitudinalSetpoint.md)). @@ -569,24 +569,24 @@ Commanding transitions externally makes the user partially responsible for ensur 3. To command a transition, you can use the `toMulticopter()` or `toFixedwing()` methods on your VTOL object to set the desired state. 4. During transition, send the following combination of setpoints: - ```cpp - // Assuming the instance of the px4_ros2::VTOL object is called vtol + ```cpp + // Assuming the instance of the px4_ros2::VTOL object is called vtol - // Send TrajectorySetpointType as follows: - Eigen::Vector3f acceleration_sp = vtol.computeAccelerationSetpointDuringTransition(); - Eigen::Vector3f velocity_sp{NAN, NAN, 0.f}; + // Send TrajectorySetpointType as follows: + Eigen::Vector3f acceleration_sp = vtol.computeAccelerationSetpointDuringTransition(); + Eigen::Vector3f velocity_sp{NAN, NAN, 0.f}; - _trajectory_setpoint->update(velocity_sp, acceleration_sp); + _trajectory_setpoint->update(velocity_sp, acceleration_sp); - // Send FwLateralLongitudinalSetpointType with lateral input to realign vehicle as desired + // Send FwLateralLongitudinalSetpointType with lateral input to realign vehicle as desired - float course_sp = 0.F; // North + float course_sp = 0.F; // North - _fw_lateral_longitudinal_setpoint->updateWithAltitude(NAN, course_sp) - ``` + _fw_lateral_longitudinal_setpoint->updateWithAltitude(NAN, course_sp) + ``` - This will ensure that the transition is handled properly within PX4. - You can optionally pass a deceleration setpoint to `computeAccelerationSetpointDuringTransition()` to be used during back-transitions. + This will ensure that the transition is handled properly within PX4. + You can optionally pass a deceleration setpoint to `computeAccelerationSetpointDuringTransition()` to be used during back-transitions. To check the current state of the vehicle, use the `getCurrentState()` method on your `px4_ros2::VTOL` object. @@ -599,7 +599,7 @@ See [this external flight mode implementation](https://github.com/Auterion/px4-r 1. [Configure the output](../payloads/generic_actuator_control.md#generic-actuator-control-with-mavlink). 2. Створіть екземпляр px4_ros2::PeripheralActuatorControls у конструкторі вашого режиму. 3. Викличте метод set(), щоб керувати клапаном(-ами). - Це може бути зроблено незалежно від будь-яких активних встановлень. + Це може бути зроблено незалежно від будь-яких активних встановлень. ### Телеметрія diff --git a/docs/uk/ros2/px4_ros2_msg_translation_node.md b/docs/uk/ros2/px4_ros2_msg_translation_node.md index 7ad1c15295..5407586db8 100644 --- a/docs/uk/ros2/px4_ros2_msg_translation_node.md +++ b/docs/uk/ros2/px4_ros2_msg_translation_node.md @@ -27,36 +27,36 @@ The following steps describe how to install and run the translation node on your 1. (Optional) Create a new ROS 2 workspace in which to build the message translation node and its dependencies: - ```sh - mkdir -p /path/to/ros_ws/src - ``` + ```sh + mkdir -p /path/to/ros_ws/src + ``` 2. Run the following helper script to copy the message definitions and translation node into your ROS workspace directory. - ```sh - cd /path/to/ros_ws - /path/to/PX4-Autopilot/Tools/copy_to_ros_ws.sh . - ``` + ```sh + cd /path/to/ros_ws + /path/to/PX4-Autopilot/Tools/copy_to_ros_ws.sh . + ``` 3. Build and source the workspace. - ```sh - colcon build - source /path/to/ros_ws/install/setup.bash - ``` + ```sh + colcon build + source /path/to/ros_ws/install/setup.bash + ``` 4. Finally, run the translation node. - ```sh - ros2 run translation_node translation_node_bin - ``` + ```sh + ros2 run translation_node translation_node_bin + ``` - You should see an output similar to: + You should see an output similar to: - ```sh - [INFO] [1734525720.729530513] [translation_node]: Registered pub/sub topics and versions: - [INFO] [1734525720.729594413] [translation_node]: Registered services and versions: - ``` + ```sh + [INFO] [1734525720.729530513] [translation_node]: Registered pub/sub topics and versions: + [INFO] [1734525720.729594413] [translation_node]: Registered services and versions: + ``` With the translation node running, any simultaneously running ROS 2 application designed to communicate with PX4 can do so, as long as it uses message versions recognized by the node. The translation node will print a warning if it encounters an unknown topic version. @@ -295,111 +295,111 @@ The example describes the process of updating the `VehicleAttitude` message defi 1. **Create an Archived Definition of the Current Versioned Message** - Copy the versioned `.msg` topic message file (or `.srv` service message file) to `px4_msgs_old/msg/` (or `px4_msgs_old/srv/`), and append its message version to the file name. + Copy the versioned `.msg` topic message file (or `.srv` service message file) to `px4_msgs_old/msg/` (or `px4_msgs_old/srv/`), and append its message version to the file name. - For example:
- Copy `msg/versioned/VehicleAttitude.msg` → `msg/versioned/px4_msgs_old/msg/VehicleAttitudeV3.msg` + For example:
+ Copy `msg/versioned/VehicleAttitude.msg` → `msg/versioned/px4_msgs_old/msg/VehicleAttitudeV3.msg` 2. **Update Translation References to the Archived Definition** - Update the existing translations header files `msg/translation_node/translations/*.h` to reference the newly archived message definition. + Update the existing translations header files `msg/translation_node/translations/*.h` to reference the newly archived message definition. - For example, update references in those files:
+ For example, update references in those files:
- - Replace `px4_msgs::msg::VehicleAttitude` → `px4_msgs_old::msg::VehicleAttitudeV3` - - Replace `#include ` → `#include ` + - Replace `px4_msgs::msg::VehicleAttitude` → `px4_msgs_old::msg::VehicleAttitudeV3` + - Replace `#include ` → `#include ` 3. **Update the Versioned Definition** - Update the versioned `.msg` topic message file (or `.srv` service message file) with required changes. + Update the versioned `.msg` topic message file (or `.srv` service message file) with required changes. - First increment the `MESSAGE_VERSION` field. - Then update the message fields that prompted the version change. + First increment the `MESSAGE_VERSION` field. + Then update the message fields that prompted the version change. - For example, update `msg/versioned/VehicleAttitude.msg` from: + For example, update `msg/versioned/VehicleAttitude.msg` from: - ```txt - uint32 MESSAGE_VERSION = 3 - uint64 timestamp - ... - ``` + ```txt + uint32 MESSAGE_VERSION = 3 + uint64 timestamp + ... + ``` - to + to - ```txt - uint32 MESSAGE_VERSION = 4 # Increment - uint64 timestamp - float32 new_field # Make definition changes - ... - ``` + ```txt + uint32 MESSAGE_VERSION = 4 # Increment + uint64 timestamp + float32 new_field # Make definition changes + ... + ``` 4. **Add a New Translation Header** - Add a new version translation to bridge the archived version and the updated current version, by creating a new translation header. + Add a new version translation to bridge the archived version and the updated current version, by creating a new translation header. - For example, create a direct translation header `translation_node/translations/translation_vehicle_attitude_v4.h`: + For example, create a direct translation header `translation_node/translations/translation_vehicle_attitude_v4.h`: - ```c++ - // Translate VehicleAttitude v3 <--> v4 - #include - #include + ```c++ + // Translate VehicleAttitude v3 <--> v4 + #include + #include - class VehicleAttitudeV4Translation { - public: - using MessageOlder = px4_msgs_old::msg::VehicleAttitudeV3; - static_assert(MessageOlder::MESSAGE_VERSION == 3); + class VehicleAttitudeV4Translation { + public: + using MessageOlder = px4_msgs_old::msg::VehicleAttitudeV3; + static_assert(MessageOlder::MESSAGE_VERSION == 3); - using MessageNewer = px4_msgs::msg::VehicleAttitude; - static_assert(MessageNewer::MESSAGE_VERSION == 4); + using MessageNewer = px4_msgs::msg::VehicleAttitude; + static_assert(MessageNewer::MESSAGE_VERSION == 4); - static constexpr const char* kTopic = "fmu/out/vehicle_attitude"; + static constexpr const char* kTopic = "fmu/out/vehicle_attitude"; - static void fromOlder(const MessageOlder &msg_older, MessageNewer &msg_newer) { - msg_newer.timestamp = msg_older.timestamp; - msg_newer.timestamp_sample = msg_older.timestamp_sample; - msg_newer.q[0] = msg_older.q[0]; - msg_newer.q[1] = msg_older.q[1]; - msg_newer.q[2] = msg_older.q[2]; - msg_newer.q[3] = msg_older.q[3]; - msg_newer.delta_q_reset = msg_older.delta_q_reset; - msg_newer.quat_reset_counter = msg_older.quat_reset_counter; + static void fromOlder(const MessageOlder &msg_older, MessageNewer &msg_newer) { + msg_newer.timestamp = msg_older.timestamp; + msg_newer.timestamp_sample = msg_older.timestamp_sample; + msg_newer.q[0] = msg_older.q[0]; + msg_newer.q[1] = msg_older.q[1]; + msg_newer.q[2] = msg_older.q[2]; + msg_newer.q[3] = msg_older.q[3]; + msg_newer.delta_q_reset = msg_older.delta_q_reset; + msg_newer.quat_reset_counter = msg_older.quat_reset_counter; - // Populate `new_field` with some value - msg_newer.new_field = -1; - } + // Populate `new_field` with some value + msg_newer.new_field = -1; + } - static void toOlder(const MessageNewer &msg_newer, MessageOlder &msg_older) { - msg_older.timestamp = msg_newer.timestamp; - msg_older.timestamp_sample = msg_newer.timestamp_sample; - msg_older.q[0] = msg_newer.q[0]; - msg_older.q[1] = msg_newer.q[1]; - msg_older.q[2] = msg_newer.q[2]; - msg_older.q[3] = msg_newer.q[3]; - msg_older.delta_q_reset = msg_newer.delta_q_reset; - msg_older.quat_reset_counter = msg_newer.quat_reset_counter; + static void toOlder(const MessageNewer &msg_newer, MessageOlder &msg_older) { + msg_older.timestamp = msg_newer.timestamp; + msg_older.timestamp_sample = msg_newer.timestamp_sample; + msg_older.q[0] = msg_newer.q[0]; + msg_older.q[1] = msg_newer.q[1]; + msg_older.q[2] = msg_newer.q[2]; + msg_older.q[3] = msg_newer.q[3]; + msg_older.delta_q_reset = msg_newer.delta_q_reset; + msg_older.quat_reset_counter = msg_newer.quat_reset_counter; - // Discards `new_field` from MessageNewer - } - }; + // Discards `new_field` from MessageNewer + } + }; - REGISTER_TOPIC_TRANSLATION_DIRECT(VehicleAttitudeV4Translation); - ``` + REGISTER_TOPIC_TRANSLATION_DIRECT(VehicleAttitudeV4Translation); + ``` - Version translation templates are provided here: + Version translation templates are provided here: - - [Direct Topic Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_direct_v1.h) - - [Generic Topic Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_multi_v2.h) - - [Direct Service Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_service_v1.h) + - [Direct Topic Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_direct_v1.h) + - [Generic Topic Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_multi_v2.h) + - [Direct Service Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_service_v1.h) 5. **Include New Headers in `all_translations.h`** - Add all newly created headers to [`translations/all_translations.h`](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/all_translations.h) so that the translation node can find them. + Add all newly created headers to [`translations/all_translations.h`](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/all_translations.h) so that the translation node can find them. - For example, append the following line to `all_translation.h`: + For example, append the following line to `all_translation.h`: - ```c++ - #include "translation_vehicle_attitude_v4.h" - ``` + ```c++ + #include "translation_vehicle_attitude_v4.h" + ``` Note that in the example above and in most cases, step 4 only requires the developer to create a direct translation for the definition change. This is because the changes only involved a single message. diff --git a/docs/uk/ros2/px4_ros2_navigation_interface.md b/docs/uk/ros2/px4_ros2_navigation_interface.md index 003cf8c43a..a946973966 100644 --- a/docs/uk/ros2/px4_ros2_navigation_interface.md +++ b/docs/uk/ros2/px4_ros2_navigation_interface.md @@ -22,80 +22,80 @@ 2. Клонуйте репозиторій в робочий простір: - ```sh - cd $ros_workspace/src - git clone --recursive https://github.com/Auterion/px4-ros2-interface-lib - ``` + ```sh + cd $ros_workspace/src + git clone --recursive https://github.com/Auterion/px4-ros2-interface-lib + ``` - :::info - Для забезпечення сумісності, використовуйте останні _main_ гілки для PX4, _px4_msgs_ та бібліотеки. - Дивіться також [here](https://github.com/Auterion/px4-ros2-interface-lib#compatibility-with-px4). + :::info + Для забезпечення сумісності, використовуйте останні _main_ гілки для PX4, _px4_msgs_ та бібліотеки. + Дивіться також [here](https://github.com/Auterion/px4-ros2-interface-lib#compatibility-with-px4). ::: 3. Побудуйте робочий простір: - ```sh - cd .. - colcon build - ``` + ```sh + cd .. + colcon build + ``` 4. У іншій оболонці запустіть PX4 SITL: - ```sh - cd $px4-autopilot - make px4_sitl gazebo-classic - ``` + ```sh + cd $px4-autopilot + make px4_sitl gazebo-classic + ``` - (тут ми використовуємо Gazebo-Classic, але ви можете використовувати будь-яку модель або симулятор) + (тут ми використовуємо Gazebo-Classic, але ви можете використовувати будь-яку модель або симулятор) 5. У іншій оболонці запустіть агента micro XRCE (ви можете залишити його запущеним після цього): - ```sh - MicroXRCEAgent udp4 -p 8888 - ``` + ```sh + MicroXRCEAgent udp4 -p 8888 + ``` 6. Поверніться до терміналу ROS 2, створіть робочу область, яку ви щойно створили (у кроці 3), і запустіть приклад [global_navigation](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/navigation/global_navigation), який періодично надсилає фіктивні оновлення глобальної позиції: - ```sh - source install/setup.bash - ros2 run example_global_navigation_cpp example_global_navigation - ``` + ```sh + source install/setup.bash + ros2 run example_global_navigation_cpp example_global_navigation + ``` - Ви повинні отримати вивід, подібний до цього, що показує, що глобальний інтерфейс успішно надсилає оновлення позиції: + Ви повинні отримати вивід, подібний до цього, що показує, що глобальний інтерфейс успішно надсилає оновлення позиції: - ```sh - [INFO] [1702030701.836897756] [example_global_navigation_node]: example_global_navigation_node running! - [DEBUG] [1702030702.837279784] [example_global_navigation_node]: Successfully sent position update to navigation interface. - [DEBUG] [1702030703.837223884] [example_global_navigation_node]: Successfully sent position update to navigation interface. - ``` + ```sh + [INFO] [1702030701.836897756] [example_global_navigation_node]: example_global_navigation_node running! + [DEBUG] [1702030702.837279784] [example_global_navigation_node]: Successfully sent position update to navigation interface. + [DEBUG] [1702030703.837223884] [example_global_navigation_node]: Successfully sent position update to navigation interface. + ``` 7. У PX4 оболонці можна перевірити, що PX4 отримує глобальні оновлення позиції: - ```sh - listener aux_global_position - ``` + ```sh + listener aux_global_position + ``` - Вихід має містити: + Вихід має містити: - ```sh - TOPIC: aux_global_position - aux_global_position - timestamp: 46916000 (0.528000 seconds ago) - timestamp_sample: 46916000 (0 us before timestamp) - lat: 12.343210 - lon: 23.454320 - alt: 12.40000 - alt_ellipsoid: 0.00000 - delta_alt: 0.00000 - eph: 0.31623 - epv: 0.44721 - terrain_alt: 0.00000 - lat_lon_reset_counter: 0 - alt_reset_counter: 0 - terrain_alt_valid: False - dead_reckoning: False - ``` + ```sh + TOPIC: aux_global_position + aux_global_position + timestamp: 46916000 (0.528000 seconds ago) + timestamp_sample: 46916000 (0 us before timestamp) + lat: 12.343210 + lon: 23.454320 + alt: 12.40000 + alt_ellipsoid: 0.00000 + delta_alt: 0.00000 + eph: 0.31623 + epv: 0.44721 + terrain_alt: 0.00000 + lat_lon_reset_counter: 0 + alt_reset_counter: 0 + terrain_alt_valid: False + dead_reckoning: False + ``` 8. Тепер ви готові використовувати навігаційний інтерфейс для надсилання своїх оновлень. diff --git a/docs/uk/ros2/user_guide.md b/docs/uk/ros2/user_guide.md index 47683eb4ec..b09de1bf84 100644 --- a/docs/uk/ros2/user_guide.md +++ b/docs/uk/ros2/user_guide.md @@ -97,48 +97,48 @@ To install ROS 2 and its dependencies: 1. Встановлення ROS 2. - :::: tabs + :::: tabs - ::: tab humble - To install ROS 2 "Humble" on Ubuntu 22.04: + ::: tab humble + To install ROS 2 "Humble" on Ubuntu 22.04: - ```sh - sudo apt update && sudo apt install locales - sudo locale-gen en_US en_US.UTF-8 - sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 - export LANG=en_US.UTF-8 - sudo apt install software-properties-common - sudo add-apt-repository universe - sudo apt update && sudo apt install curl -y - sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg - echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null - sudo apt update && sudo apt upgrade -y - sudo apt install ros-humble-desktop - sudo apt install ros-dev-tools - source /opt/ros/humble/setup.bash && echo "source /opt/ros/humble/setup.bash" >> .bashrc - ``` + ```sh + sudo apt update && sudo apt install locales + sudo locale-gen en_US en_US.UTF-8 + sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 + export LANG=en_US.UTF-8 + sudo apt install software-properties-common + sudo add-apt-repository universe + sudo apt update && sudo apt install curl -y + sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg + echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null + sudo apt update && sudo apt upgrade -y + sudo apt install ros-humble-desktop + sudo apt install ros-dev-tools + source /opt/ros/humble/setup.bash && echo "source /opt/ros/humble/setup.bash" >> .bashrc + ``` - The instructions above are reproduced from the official installation guide: [Install ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html). - You can install _either_ the desktop (`ros-humble-desktop`) _or_ bare-bones versions (`ros-humble-ros-base`), _and_ the development tools (`ros-dev-tools`). + The instructions above are reproduced from the official installation guide: [Install ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html). + You can install _either_ the desktop (`ros-humble-desktop`) _or_ bare-bones versions (`ros-humble-ros-base`), _and_ the development tools (`ros-dev-tools`). ::: - ::: tab foxy - To install ROS 2 "Foxy" on Ubuntu 20.04: + ::: tab foxy + To install ROS 2 "Foxy" on Ubuntu 20.04: - - Follow the official installation guide: [Install ROS 2 Foxy](https://docs.ros.org/en/foxy/Installation/Ubuntu-Install-Debians.html). + - Follow the official installation guide: [Install ROS 2 Foxy](https://docs.ros.org/en/foxy/Installation/Ubuntu-Install-Debians.html). - You can install _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), _and_ the development tools (`ros-dev-tools`). + You can install _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), _and_ the development tools (`ros-dev-tools`). ::: - :::: + :::: 2. Some Python dependencies must also be installed (using **`pip`** or **`apt`**): - ```sh - pip install --user -U empy==3.3.4 pyros-genmsg setuptools - ``` + ```sh + pip install --user -U empy==3.3.4 pyros-genmsg setuptools + ``` ### Setup Micro XRCE-DDS Agent & Client @@ -155,22 +155,22 @@ To setup and start the agent: 2. Введіть наступні команди для витягування та побудови агента з вихідного коду: - ```sh - git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git - cd Micro-XRCE-DDS-Agent - mkdir build - cd build - cmake .. - make - sudo make install - sudo ldconfig /usr/local/lib/ - ``` + ```sh + git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git + cd Micro-XRCE-DDS-Agent + mkdir build + cd build + cmake .. + make + sudo make install + sudo ldconfig /usr/local/lib/ + ``` 3. Запустіть агента з налаштуваннями для підключення до клієнта uXRCE-DDS, який працює на симуляторі: - ```sh - MicroXRCEAgent udp4 -p 8888 - ``` + ```sh + MicroXRCEAgent udp4 -p 8888 + ``` The agent is now running, but you won't see much until we start PX4 (in the next step). @@ -187,31 +187,31 @@ To start the simulator (and client): 1. Open a new terminal in the root of the **PX4 Autopilot** repo that was installed above. - :::: tabs + :::: tabs - ::: tab humble + ::: tab humble - - Start a PX4 [Gazebo](../sim_gazebo_gz/index.md) simulation using: + - Start a PX4 [Gazebo](../sim_gazebo_gz/index.md) simulation using: - ```sh - make px4_sitl gz_x500 - ``` + ```sh + make px4_sitl gz_x500 + ``` ::: - ::: tab foxy + ::: tab foxy - - Start a PX4 [Gazebo Classic](../sim_gazebo_classic/index.md) simulation using: + - Start a PX4 [Gazebo Classic](../sim_gazebo_classic/index.md) simulation using: - ```sh - make px4_sitl gazebo-classic - ``` + ```sh + make px4_sitl gazebo-classic + ``` ::: - :::: + :::: The agent and client are now running they should connect. @@ -261,52 +261,52 @@ To create and build the workspace: 2. Створіть новий каталог робочого простору та перейдіть до нього за допомогою: - ```sh - mkdir -p ~/ws_sensor_combined/src/ - cd ~/ws_sensor_combined/src/ - ``` + ```sh + mkdir -p ~/ws_sensor_combined/src/ + cd ~/ws_sensor_combined/src/ + ``` - ::: info - A naming convention for workspace folders can make it easier to manage workspaces. + ::: info + A naming convention for workspace folders can make it easier to manage workspaces. ::: 3. Clone the example repository and [px4_msgs](https://github.com/PX4/px4_msgs) to the `/src` directory (the `main` branch is cloned by default, which corresponds to the version of PX4 we are running): - ```sh - git clone https://github.com/PX4/px4_msgs.git - git clone https://github.com/PX4/px4_ros_com.git - ``` + ```sh + git clone https://github.com/PX4/px4_msgs.git + git clone https://github.com/PX4/px4_ros_com.git + ``` 4. Source the ROS 2 development environment into the current terminal and compile the workspace using `colcon`: - :::: tabs + :::: tabs - ::: tab humble + ::: tab humble - ```sh - cd .. - source /opt/ros/humble/setup.bash - colcon build - ``` + ```sh + cd .. + source /opt/ros/humble/setup.bash + colcon build + ``` ::: - ::: tab foxy + ::: tab foxy - ```sh - cd .. - source /opt/ros/foxy/setup.bash - colcon build - ``` + ```sh + cd .. + source /opt/ros/foxy/setup.bash + colcon build + ``` ::: - :::: + :::: - This builds all the folders under `/src` using the sourced toolchain. + This builds all the folders under `/src` using the sourced toolchain. #### Запуск прикладу @@ -322,42 +322,42 @@ In a new terminal: 1. Перейдіть на верхній рівень каталогу вашого робочого простору та джерело середовища ROS 2 (у цьому випадку "Humble"): - :::: tabs + :::: tabs - ::: tab humble + ::: tab humble - ```sh - cd ~/ws_sensor_combined/ - source /opt/ros/humble/setup.bash - ``` + ```sh + cd ~/ws_sensor_combined/ + source /opt/ros/humble/setup.bash + ``` ::: - ::: tab foxy + ::: tab foxy - ```sh - cd ~/ws_sensor_combined/ - source /opt/ros/foxy/setup.bash - ``` + ```sh + cd ~/ws_sensor_combined/ + source /opt/ros/foxy/setup.bash + ``` ::: - :::: + :::: 2. Source the `local_setup.bash`. - ```sh - source install/local_setup.bash - ``` + ```sh + source install/local_setup.bash + ``` 3. Тепер запустіть приклад. - Note here that we use `ros2 launch`, which is described below. + Note here that we use `ros2 launch`, which is described below. - ```sh - ros2 launch px4_ros_com sensor_combined_listener.launch.py - ``` + ```sh + ros2 launch px4_ros_com sensor_combined_listener.launch.py + ``` If this is working you should see data being printed on the terminal/console where you launched the ROS listener: @@ -385,18 +385,18 @@ If you were to use incompatible [message versions](../middleware/uorb.md#message 1. Include the [Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) into the example workspace or a separate workspace by running the following script: - ```sh - cd /path/to/ros_ws - /path/to/PX4-Autopilot/Tools/copy_to_ros_ws.sh . - ``` + ```sh + cd /path/to/ros_ws + /path/to/PX4-Autopilot/Tools/copy_to_ros_ws.sh . + ``` 2. Build and run the translation node: - ```sh - colcon build - source install/local_setup.bash - ros2 run translation_node translation_node_bin - ``` + ```sh + colcon build + source install/local_setup.bash + ros2 run translation_node translation_node_bin + ``` ## Керування Транспортним Засобом diff --git a/docs/uk/sensor/accelerometer.md b/docs/uk/sensor/accelerometer.md index 285e121abd..92c15ba7c8 100644 --- a/docs/uk/sensor/accelerometer.md +++ b/docs/uk/sensor/accelerometer.md @@ -5,7 +5,7 @@ PX4 використовує дані акселерометра для оцін Вам не потрібно прикріплювати акселерометр як окремий зовнішній пристрій: - Більшість польотних контролерів, таких, як в [Pixhawk Series](/flight_controller/pixhawk_series.md), включають в себе акселерометр як частину польот контролеру [Inertial Motion (IMU)](https://en.wikipedia.org/wiki/Inertial_measurement_unit). -- Гіроскопи присутні як частина зовнішньої системи інерціальної навігації, ARHS або системи підвищеної точності глобальної навігації INS (../sensor/inertial_navigation_systems.md). +- Gyroscopes are present as part of an [external INS, AHRS or INS-enhanced GNSS system](../sensor/inertial_navigation_systems.md). Потрібно відкалібрувати акселерометр перед першим використанням безпілотника: diff --git a/docs/uk/sensor/inertial_navigation_systems.md b/docs/uk/sensor/inertial_navigation_systems.md index e0d36d29ef..0f01d9b58e 100644 --- a/docs/uk/sensor/inertial_navigation_systems.md +++ b/docs/uk/sensor/inertial_navigation_systems.md @@ -9,6 +9,7 @@ However PX4 can also use some INS devices as either sources of raw data, or as a INS systems that can be used as a replacement for EKF2 in PX4: - [InertialLabs](../sensor/inertiallabs.md) +- [SBG Systems](../sensor/sbgecom.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data. - [VectorNav](../sensor/vectornav.md): ІВП/AHRS, ССН/INS, Dual GNSS/INS системи, котрі можуть бути використані як зовнішній INS, або джерело вхідної інформації датчиків. ## PX4 Firmware diff --git a/docs/uk/sensor/inertiallabs.md b/docs/uk/sensor/inertiallabs.md index d5dcdd0b53..e7e3c6e4b3 100644 --- a/docs/uk/sensor/inertiallabs.md +++ b/docs/uk/sensor/inertiallabs.md @@ -57,11 +57,11 @@ To use the Inertial Labs driver: - For external INS, set [ILABS_MODE](../advanced_config/parameter_reference.md#ILABS_MODE) to `INS`. - For raw inertial sensors, set [ILABS_MODE](../advanced_config/parameter_reference.md#ILABS_MODE) to `Sensors Only`. - You can then prioritize inertial labs sensors using [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO), [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO), [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO), [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO), where `n` is the instance number of the IMU component (0, 1, etc.). + You can then prioritize inertial labs sensors using [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO), [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO), [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO), [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO), where `n` is the instance number of the IMU component (0, 1, etc.). - ::: tip - In most cases the external IMU is the highest-numbered. - Ви можете отримати список доступних компонентів IMU, використовуючи [`uorb top -1`](../middleware/uorb.md#uorb-top-command), ви можете відрізняти їх за допомогою команди [`listener`](../modules/modules_command.md#listener) та розглядаючи дані чи просто швидкості. + ::: tip + In most cases the external IMU is the highest-numbered. + Ви можете отримати список доступних компонентів IMU, використовуючи [`uorb top -1`](../middleware/uorb.md#uorb-top-command), ви можете відрізняти їх за допомогою команди [`listener`](../modules/modules_command.md#listener) та розглядаючи дані чи просто швидкості. ::: diff --git a/docs/uk/sensor/rangefinders.md b/docs/uk/sensor/rangefinders.md index a25b799444..17d480acd9 100644 --- a/docs/uk/sensor/rangefinders.md +++ b/docs/uk/sensor/rangefinders.md @@ -146,11 +146,11 @@ To view the rangefinder output: 1. Open the menu **Q > Select Tool > Analyze Tools**: - ![Menu for QGC Analyze Tool](../../assets/qgc/analyze/menu_analyze_tool.png) + ![Menu for QGC Analyze Tool](../../assets/qgc/analyze/menu_analyze_tool.png) 2. Select the message `DISTANCE_SENSOR`, and then check the plot checkbox against `current_distance`. - The tool will then plot the result: - ![QGC Analyze DISTANCE_SENSOR value](../../assets/qgc/analyze/qgc_analyze_tool_distance_sensor.png) + The tool will then plot the result: + ![QGC Analyze DISTANCE_SENSOR value](../../assets/qgc/analyze/qgc_analyze_tool_distance_sensor.png) ### QGroundControl MAVLink Console diff --git a/docs/uk/sensor/sbgecom.md b/docs/uk/sensor/sbgecom.md new file mode 100644 index 0000000000..f02ce87683 --- /dev/null +++ b/docs/uk/sensor/sbgecom.md @@ -0,0 +1,159 @@ +# SBG Systems INS/AHRS (Pulse, Ellipse, etc.) + +[SBG-Systems](https://www.sbg-systems.com/) designs, manufactures, and support an extensive range of state-of-the-art inertial sensors such as Inertial Measurement Units (IMU), Attitude and Heading Reference Systems (AHRS), Inertial Navigation Systems with embedded GNSS (INS/GNSS), and so on. + +PX4 supports [all SBG Systems products](https://www.sbg-systems.com/products/) and can use these as an [external INS](../sensor/inertial_navigation_systems.md) (bypassing/replacing the EKF2 estimator), or as a source of raw sensor data provided to the navigation estimator. + +![Ellipse](../../assets/hardware/sensors/inertial/ellipse-inertial-navigation-system.png) + +## Загальний огляд + +SBG Systems products provide a range of benefits to PX4 users and can be integrated for: + +- Вища точність оцінки напрямку, крену та кочення +- Більш надійна геоприв'язка GNSS +- Покращена точність позиціонування та установки під час конфлікту супутникового зв'язку +- Продуктивність при динамічних умовах (наприклад, запуски катапультою, операції VTOL, високі g або високі операції з великою кутовою швидкістю) + +The sbgECom PX4 driver is streamlined to provide a simple plug-and-play architecture, removing engineering obstacles and allowing the acceleration of the design, development, and launch of platforms to keep pace with the rapid rate of innovation. + +The driver supports [all SBG Systems products](https://www.sbg-systems.com/products/). +Зокрема, рекомендуємо наступні системи: + +- **Pulse:** Recommended for fixed-wing systems without hovering, where static heading is not necessary. +- **Ellipse:** Recommended for multicopter systems where hovering and low dynamics requires the use of static heading. + +## Де купити + +SBG Systems solutions are available directly from [MySBG](https://my.sbg-systems.com) (FR) or through their Global Sales Representatives. For more information on their solutions or for international orders, please contact contact@sbg-systems.com. + +## Налаштування програмного забезпечення + +### Підключення + +Connect any unused flight controller serial interface, such as a spare `GPS` or `TELEM` port, to the SBG Systems product MAIN port (required by PX4). + +### Встановлення + +The SBG Systems product sensor can be mounted in any orientation, in any position on the vehicle, without regard to center of gravity. +All SBG Systems product sensors default to a coordinate system of x-forward, y-right, and z-down, making the default mounting as connector-back, base down. +This can be changed to any rigid rotation using the sbgECom Reference Frame Rotation register. + +Якщо використовується продукт з підтримкою GNSS, антена GNSS повинна бути жорстко монтуватися щодо інерційного датчика та мати необмежений вид на небо. If using a dual-GNSS-enabled product (Ellipse-D), the secondary antenna must be mounted rigidly with respect to the primary antenna and the inertial sensor with an unobstructed sky view. + +For more mounting and configuration requirements and recommendations, see the relevant [SBG SUPPORT CENTER](https://support.sbg-systems.com/sc). + +## Конфігурація прошивки + +### Конфігурація PX4 + +To use the sbgECom driver: + +1. Include the module in firmware in the [kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) by setting the kconfig variables: `CONFIG_DRIVERS_INS_SBGECOM` or `CONFIG_COMMON_INS`. + +2. [Set the parameter](../advanced_config/parameters.md) [SENS_SBG_CFG](../advanced_config/parameter_reference.md#SENS_SBG_CFG) to the hardware port connected to the SBG Systems product (for more information see [Serial Port Configuration](../peripherals/serial_configuration.md)). + + ::: warning + Disable or change port of other sensors that are using the same one, for example [GPS_1_CONFIG](../advanced_config/parameter_reference.md#GPS_1_CONFIG) if using GPS1 port. + +::: + +3. Set [SBG_BAUDRATE](../advanced_config/parameter_reference.md#SBG_BAUDRATE) to the desired default baudrate value. + +4. Allow the sbgECom driver to initialize by restarting PX4. + +5. Configure driver to provide IMU data, GNSS data and INS : + + 1. Set [SBG_MODE](../advanced_config/parameter_reference.md#SBG_MODE) to the desired mode. + 2. Make sensor module select sensors by enabling [SENS_IMU_MODE](../advanced_config/parameter_reference.md#SENS_IMU_MODE). + 3. Prioritize SBG Systems sensors using [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO), [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO), [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO), [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO), where _n_ is the instance number of the IMU component (0, 1, etc.). + + ::: tip + In most cases the external IMU (SBG) is the highest-numbered. + Ви можете отримати список доступних компонентів IMU, використовуючи [`uorb top -1`](../middleware/uorb.md#uorb-top-command), ви можете відрізняти їх за допомогою команди [`listener`](../modules/modules_command.md#listener) та розглядаючи дані чи просто швидкості. + + За потреби ви можете перевірити [CAL_GYROn_ID](../advanced_config/parameter_reference.md#CAL_GYRO0_ID), щоб побачити ідентифікатор пристрою. + Пріоритет становить 0-255, де 0 абсолютно вимкнено, а 255 - найвищий пріоритет. + +::: + + ::: warning + When configuring both SBG Systems and Pixhawk sensors to have non-zero priority, if the selected sensor is errored (timeout), it can change during operation without being notified. + In this case, MAVLink messages will be updated with the newly selected sensor. + + If you don't want to have this fallback mechanism, you must disable unwanted sensors. + +::: + + 4. If using the sbgECom as an INS, disable EKF2 using [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN). + +6. Перезавантажте PX4. + +Після активації модуль буде виявлено при завантаженні. +IMU data should be published at 200Hz. + +## SBG Systems Configuration + +All High Performance and Ellipse 3.0 and higher SBG Systems INS can be configured directly from PX4 firmware: + +1. Enable [SBG_CONFIGURATION_EN](../advanced_config/parameter_reference.md#SBG_CONFIGURATION_EN) + +2. Provide a JSON file `sbg_settings.json` containing SBG Systems INS settings to be applied in your PX4 board `extras` directory (ex: `boards/px4/fmu-v5/extras`). The settings JSON file will be installed in `/etc/extras/sbg_settings.json` on the board. + + ::: tip + The settings can be retrieved using [sbgEComAPI](https://github.com/SBG-Systems/sbgECom/tree/main/tools/sbgEComApi) or [sbgInsRestApi](https://developer.sbg-systems.com/sbgInsRestApi/1.3/#tag/Settings) and then modified as a JSON file. + +::: + + ::: tip + The settings file can be provided in the SD card in q`/fs/microsd/etc/extras/sbg_settings.json` to avoid rebuilding a new firmware to change JSON settings file. + +::: + +3. For testing purpose, it's also possible to modify SBG Systems INS settings on the fly: + + - By passing a JSON file path as argument when starting sbgecom driver (ex: `sbgecom start -f /fs/microsd/new_sbg_settings.json`) + - By passing a JSON string as argument when starting sbgecom driver: (ex: `sbgecom start -s {"output":{"comA":{"messages":{"airData":"onChange"}}}}`) + +For older Ellipse SBG Systems INS or to configure any SBG Systems INS directly, all commands and registers can be found in the [SBG SUPPORT CENTER](https://support.sbg-systems.com/sc). + +:::warning +If the baudrate of the serial port on the INS product (used to communicate with PX4) is changed, the parameter [SBG_BAUDRATE](../advanced_config/parameter_reference.md#SBG_BAUDRATE) must be changed to match. +::: + +## Опубліковані дані + +При ініціалізації водій повинен надрукувати наступну інформацію до консолі (надруковано за допомогою `PX4_INFO`) + +- Номер моделі блока +- Версія апаратної одиниці +- Номер серійного номеру блока +- Номер прошивки одиниці + +Цей текст має бути доступний за допомогою команди [`dmesg`](../modules/modules_system.md#dmesg). + +The sbgECom driver always publishes the unit's data to the following uORB topics: + +- [sensor_accel](../msg_docs/SensorAccel.md) +- [датчик_гіроскопа](../msg_docs/SensorGyro.md) +- [sensor_mag](../msg_docs/SensorMag.md) + +if configured as a GNSS, publishes: + +- [sensor_gps](../msg_docs/SensorGps.md) + +and, if configured as an INS, publishes: + +- [estimator_status](../msg_docs/EstimatorStatus.md) +- [vehicle_local_position](../msg_docs/VehicleLocalPosition.md) +- [vehicle_global_positon](../msg_docs/VehicleGlobalPosition.md) +- [vehicle_attitude](../msg_docs/VehicleAttitude.md) + +:::tip +Опубліковані теми можна переглянути за допомогою команди `listener`. +::: + +## Характеристики обладнання + +- [Product Briefs](https://www.sbg-systems.com/products/) +- [Datasheets](https://www.sbg-systems.com/contact/#products) diff --git a/docs/uk/sensor/vectornav.md b/docs/uk/sensor/vectornav.md index 0cf39e2905..6fd363bed1 100644 --- a/docs/uk/sensor/vectornav.md +++ b/docs/uk/sensor/vectornav.md @@ -61,18 +61,18 @@ PX4 може використовувати це як [зовнішній INS] ( 5. Налаштуйте водія як зовнішній INS або надайте сирові дані: - Якщо використовувати VectorNav як зовнішній INS, встановіть [VN_MODE](../advanced_config/parameter_reference.md#VN_MODE) на `INS`. - Це вимикає EKF2. + Це вимикає EKF2. - Якщо використовувати VectorNav як зовнішні інерційні сенсори: - 1. Встановіть [VN_MODE](../advanced_config/parameter_reference.md#VN_MODE) на `Sensors Only` - 2. Якщо внутрішні датчики увімкнені, пріоритетом є датчики VectorNav за допомогою [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO), [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO), [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO), [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO), де _n_ - це номер екземпляра компонента ІМП (0, 1 і т.д.). + 1. Встановіть [VN_MODE](../advanced_config/parameter_reference.md#VN_MODE) на `Sensors Only` + 2. Якщо внутрішні датчики увімкнені, пріоритетом є датчики VectorNav за допомогою [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO), [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO), [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO), [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO), де _n_ - це номер екземпляра компонента ІМП (0, 1 і т.д.). - :::tip - У більшості випадків зовнішній IMU (VN) має найвищий номер. - Ви можете отримати список доступних компонентів IMU, використовуючи [`uorb top -1`](../middleware/uorb.md#uorb-top-command), ви можете відрізняти їх за допомогою команди [`listener`](../modules/modules_command.md#listener) та розглядаючи дані чи просто швидкості. + :::tip + У більшості випадків зовнішній IMU (VN) має найвищий номер. + Ви можете отримати список доступних компонентів IMU, використовуючи [`uorb top -1`](../middleware/uorb.md#uorb-top-command), ви можете відрізняти їх за допомогою команди [`listener`](../modules/modules_command.md#listener) та розглядаючи дані чи просто швидкості. - За потреби ви можете перевірити [CAL_GYROn_ID](../advanced_config/parameter_reference.md#CAL_GYRO0_ID), щоб побачити ідентифікатор пристрою. - Пріоритет становить 0-255, де 0 абсолютно вимкнено, а 255 - найвищий пріоритет. + За потреби ви можете перевірити [CAL_GYROn_ID](../advanced_config/parameter_reference.md#CAL_GYRO0_ID), щоб побачити ідентифікатор пристрою. + Пріоритет становить 0-255, де 0 абсолютно вимкнено, а 255 - найвищий пріоритет. ::: diff --git a/docs/uk/sim_flightgear/index.md b/docs/uk/sim_flightgear/index.md index 98998fa199..f637d8ad8b 100644 --- a/docs/uk/sim_flightgear/index.md +++ b/docs/uk/sim_flightgear/index.md @@ -40,33 +40,33 @@ These instructions were tested on Ubuntu 18.04 2. Встановити FlightGear: - ```sh - sudo add-apt-repository ppa:saiarcot895/flightgear - sudo apt update - sudo apt install flightgear - ``` + ```sh + sudo add-apt-repository ppa:saiarcot895/flightgear + sudo apt update + sudo apt install flightgear + ``` - Це встановить останню стабільну версію FlightGear зі сховища PAA разом із пакетом FGdata. + Це встановить останню стабільну версію FlightGear зі сховища PAA разом із пакетом FGdata. - :::tip - For some models (e.g. those with electric engines) the daily build with the newest features may be necessary. - Install this using the [daily build PPA](https://launchpad.net/~saiarcot895/+archive/ubuntu/flightgear-edge). + :::tip + For some models (e.g. those with electric engines) the daily build with the newest features may be necessary. + Install this using the [daily build PPA](https://launchpad.net/~saiarcot895/+archive/ubuntu/flightgear-edge). ::: 3. Перевірте, що ви можете запустити FlightGear: - ```sh - fgfs --launcher - ``` + ```sh + fgfs --launcher + ``` 4. Set write permissions to the **Protocols** folder in the FlightGear installation directory: - ```sh - sudo chmod a+w /usr/share/games/flightgear/Protocol - ``` + ```sh + sudo chmod a+w /usr/share/games/flightgear/Protocol + ``` - Налаштування дозволів потрібне, оскільки PX4-FlightGear-Bridge розміщує тут файл визначення зв’язку. + Налаштування дозволів потрібне, оскільки PX4-FlightGear-Bridge розміщує тут файл визначення зв’язку. Additional installation instructions can be found on [FlightGear wiki](https://wiki.flightgear.org/Howto:Install_Flightgear_from_a_PPA). diff --git a/docs/uk/sim_gazebo_classic/index.md b/docs/uk/sim_gazebo_classic/index.md index 37b64ee8ce..d4a131c6ae 100644 --- a/docs/uk/sim_gazebo_classic/index.md +++ b/docs/uk/sim_gazebo_classic/index.md @@ -249,14 +249,14 @@ It is enabled by default in many vehicle SDF files: **solo.sdf**, **iris.sdf**, To enable/disable GPS noise: 1. Build any gazebo target in order to generate SDF files (for all vehicles). - Наприклад: + Наприклад: - ```sh - make px4_sitl gazebo-classic_iris - ``` + ```sh + make px4_sitl gazebo-classic_iris + ``` - :::tip - The SDF files are not overwritten on subsequent builds. + :::tip + The SDF files are not overwritten on subsequent builds. ::: @@ -264,17 +264,17 @@ To enable/disable GPS noise: 3. Search for the `gpsNoise` element: - ```xml - - - true - - ``` + ```xml + + + true + + ``` - - If it is present, GPS is enabled. - You can disable it by deleting the line: `true` - - If it is not present, GPS is disabled. - You can enable it by adding the `gpsNoise` element to the `gps_plugin` section (as shown above). + - If it is present, GPS is enabled. + You can disable it by deleting the line: `true` + - If it is not present, GPS is disabled. + You can enable it by adding the `gpsNoise` element to the `gps_plugin` section (as shown above). The next time you build/restart Gazebo Classic it will use the new GPS noise setting. diff --git a/docs/uk/sim_gazebo_classic/multi_vehicle_simulation.md b/docs/uk/sim_gazebo_classic/multi_vehicle_simulation.md index a198f4a006..db344edaae 100644 --- a/docs/uk/sim_gazebo_classic/multi_vehicle_simulation.md +++ b/docs/uk/sim_gazebo_classic/multi_vehicle_simulation.md @@ -68,36 +68,36 @@ For more information see: [ROS 2 User Guide (PX4-ROS 2 Bridge)](../ros2/user_gui 1. Клонуйте код PX4/Прошивки і зберіть код SITL: - ```sh - cd Firmware_clone - git submodule update --init --recursive - DONT_RUN=1 make px4_sitl gazebo-classic - ``` + ```sh + cd Firmware_clone + git submodule update --init --recursive + DONT_RUN=1 make px4_sitl gazebo-classic + ``` 2. Build the `micro xrce-dds agent` and the interface package following the [instructions here](../ros2/user_guide.md). 3. Run `Tools/simulation/gazebo-classic/sitl_multiple_run.sh`. - Наприклад, для відтворення 4 рухомих засобів виконайте: + Наприклад, для відтворення 4 рухомих засобів виконайте: - ```sh - ./Tools/simulation/gazebo-classic/sitl_multiple_run.sh -m iris -n 4 - ``` + ```sh + ./Tools/simulation/gazebo-classic/sitl_multiple_run.sh -m iris -n 4 + ``` - ::: info - Each vehicle instance is allocated a unique MAVLink system id (2, 3, 4, etc.). - Системний ідентифікатор MAVLink 1 пропускається. + ::: info + Each vehicle instance is allocated a unique MAVLink system id (2, 3, 4, etc.). + Системний ідентифікатор MAVLink 1 пропускається. ::: 4. Run `MicroXRCEAgent`. - Він автоматично під'єднається до усіх чотирьох рухомих засобів: + Він автоматично під'єднається до усіх чотирьох рухомих засобів: - ```sh - MicroXRCEAgent udp4 -p 8888 - ``` + ```sh + MicroXRCEAgent udp4 -p 8888 + ``` - ::: info - The simulator startup script automatically assigns a [unique namespace](../ros2/multi_vehicle.md) to each vehicle. + ::: info + The simulator startup script automatically assigns a [unique namespace](../ros2/multi_vehicle.md) to each vehicle. ::: @@ -117,27 +117,27 @@ You can then control the vehicles with _QGroundControl_ and MAVROS in a similar 1. Клонуйте код PX4/PX4-Autopilot і зберіть код SITL - ```sh - cd Firmware_clone - git submodule update --init --recursive - DONT_RUN=1 make px4_sitl_default gazebo-classic - ``` + ```sh + cd Firmware_clone + git submodule update --init --recursive + DONT_RUN=1 make px4_sitl_default gazebo-classic + ``` 2. Виконайте команду source у вашому середовищі: - ```sh - source Tools/simulation/gazebo-classic/setup_gazebo.bash $(pwd) $(pwd)/build/px4_sitl_default - export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:$(pwd):$(pwd)/Tools/simulation/gazebo-classic/sitl_gazebo - ``` + ```sh + source Tools/simulation/gazebo-classic/setup_gazebo.bash $(pwd) $(pwd)/build/px4_sitl_default + export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:$(pwd):$(pwd)/Tools/simulation/gazebo-classic/sitl_gazebo + ``` 3. Виконайте файл запуску: - ```sh - roslaunch px4 multi_uav_mavros_sitl.launch - ``` + ```sh + roslaunch px4 multi_uav_mavros_sitl.launch + ``` - ::: info - You can specify `gui:=false` in the above _roslaunch_ to launch Gazebo Classic without its UI. + ::: info + You can specify `gui:=false` in the above _roslaunch_ to launch Gazebo Classic without its UI. ::: @@ -253,45 +253,45 @@ The launch file `multi_uav_mavros_sitl.launch`does the following, 1. Install _xmlstarlet_ from your Linux terminal: - ```sh - sudo apt install xmlstarlet - ``` + ```sh + sudo apt install xmlstarlet + ``` 2. Use _roslaunch_ with the **multi_uav_mavros_sitl_sdf.launch** launch file: - ````sh - roslaunch multi_uav_mavros_sitl_sdf.launch vehicle:= - ``` + ````sh + roslaunch multi_uav_mavros_sitl_sdf.launch vehicle:= + ``` - ::: info - Note that the vehicle model file name argument is optional (`vehicle:=`); if omitted the [plane model](https://github.com/PX4/PX4-SITL_gazebo-classic/tree/master/models/plane) will be used by default. + ::: info + Note that the vehicle model file name argument is optional (`vehicle:=`); if omitted the [plane model](https://github.com/PX4/PX4-SITL_gazebo-classic/tree/master/models/plane) will be used by default. ::: - ```` + ```` This method is similar to using the xacro except that the SITL/Gazebo Classic port number is automatically inserted by _xmstarlet_ for each spawned vehicle, and does not need to be specified in the SDF file. Щоб додати новий рухомий засіб, вам потрібно переконатися, що модель можна знайти (для відтворення у Gazebo Classic) та PX4 повинен мати відповідний скрипт запуску. 1. Можна обрати зробити щось одне з: - - modify the **single_vehicle_spawn_sdf.launch** file to point to the location of your model by changing the line below to point to your model: + - modify the **single_vehicle_spawn_sdf.launch** file to point to the location of your model by changing the line below to point to your model: - ```sh - $(find px4)/Tools/simulation/gazebo/sitl_gazebo-classic/models/$(arg vehicle)/$(arg vehicle).sdf - ``` + ```sh + $(find px4)/Tools/simulation/gazebo/sitl_gazebo-classic/models/$(arg vehicle)/$(arg vehicle).sdf + ``` - ::: info - Ensure you set the `vehicle` argument even if you hardcode the path to your model. + ::: info + Ensure you set the `vehicle` argument even if you hardcode the path to your model. ::: - - скопіювати свою модель в директорію, позначену вище (дотримуючись тих же правил шляху). + - скопіювати свою модель в директорію, позначену вище (дотримуючись тих же правил шляху). 2. The `vehicle` argument is used to set the `PX4_SIM_MODEL` environment variable, which is used by the default rcS (startup script) to find the corresponding startup settings file for the model. - Within PX4 these startup files can be found in the **PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/** directory. - For example, here is the plane model's [startup script](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/1030_gazebo-classic_plane). - For this to work, the PX4 node in the launch file is passed arguments that specify the _rcS_ file (**etc/init.d/rcS**) and the location of the rootfs etc directory (`$(find px4)/build_px4_sitl_default/etc`). - For simplicity, it is suggested that the startup file for the model be placed alongside PX4's in **PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/**. + Within PX4 these startup files can be found in the **PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/** directory. + For example, here is the plane model's [startup script](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/1030_gazebo-classic_plane). + For this to work, the PX4 node in the launch file is passed arguments that specify the _rcS_ file (**etc/init.d/rcS**) and the location of the rootfs etc directory (`$(find px4)/build_px4_sitl_default/etc`). + For simplicity, it is suggested that the startup file for the model be placed alongside PX4's in **PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/**. ## Додаткові ресурси diff --git a/docs/uk/sim_gazebo_gz/gazebo_models.md b/docs/uk/sim_gazebo_gz/gazebo_models.md index f55f30ba24..0bbaa35775 100644 --- a/docs/uk/sim_gazebo_gz/gazebo_models.md +++ b/docs/uk/sim_gazebo_gz/gazebo_models.md @@ -101,15 +101,15 @@ python simulation-gazebo --overwrite 1. В одному терміналі запустіть - ```sh - PX4_GZ_STANDALONE=1 PX4_SYS_AUTOSTART=4001 PX4_SIM_MODEL=gz_x500 PX4_GZ_WORLD=windy ./build/px4_sitl_default/bin/px4 - ``` + ```sh + PX4_GZ_STANDALONE=1 PX4_SYS_AUTOSTART=4001 PX4_SIM_MODEL=gz_x500 PX4_GZ_WORLD=windy ./build/px4_sitl_default/bin/px4 + ``` 2. У вікні другого терміналу запустіть: - ```sh - python3 /path/to/simulation-gazebo --world windy - ``` + ```sh + python3 /path/to/simulation-gazebo --world windy + ``` Не потрібно передавати додаткових параметрів скрипту simulation-gazebo щоб цей приклад працював, оскільки усі вузли Gazebo виконуються на одному комп'ютері. Дивіться приклад складнішого сценарію з різними комп'ютерами нижче. diff --git a/docs/uk/sim_gazebo_gz/index.md b/docs/uk/sim_gazebo_gz/index.md index 8b9c17d00f..01fbe74cbe 100644 --- a/docs/uk/sim_gazebo_gz/index.md +++ b/docs/uk/sim_gazebo_gz/index.md @@ -316,33 +316,33 @@ The PX4 Gazebo worlds and and models databases [can be found on GitHub here](htt 1. **Start simulator + default world + spawn vehicle at default pose** - ```sh - PX4_SYS_AUTOSTART=4001 PX4_SIM_MODEL=gz_x500 ./build/px4_sitl_default/bin/px4 - ``` + ```sh + PX4_SYS_AUTOSTART=4001 PX4_SIM_MODEL=gz_x500 ./build/px4_sitl_default/bin/px4 + ``` 2. **Start simulator + default world + spawn vehicle at custom pose (y=2m)** - ```sh - PX4_SYS_AUTOSTART=4001 PX4_GZ_MODEL_POSE="0,2" PX4_SIM_MODEL=gz_x500 ./build/px4_sitl_default/bin/px4 - ``` + ```sh + PX4_SYS_AUTOSTART=4001 PX4_GZ_MODEL_POSE="0,2" PX4_SIM_MODEL=gz_x500 ./build/px4_sitl_default/bin/px4 + ``` 3. **Start simulator + default world + link to existing vehicle** - ```sh - PX4_SYS_AUTOSTART=4001 PX4_GZ_MODEL_NAME=x500 ./build/px4_sitl_default/bin/px4 - ``` + ```sh + PX4_SYS_AUTOSTART=4001 PX4_GZ_MODEL_NAME=x500 ./build/px4_sitl_default/bin/px4 + ``` 4. **Start simulator in standalone mode + connect to Gazebo instance running default world** - ```sh - PX4_GZ_STANDALONE=1 PX4_SYS_AUTOSTART=4001 PX4_SIM_MODEL=gz_x500 ./build/px4_sitl_default/bin/px4 - ``` + ```sh + PX4_GZ_STANDALONE=1 PX4_SYS_AUTOSTART=4001 PX4_SIM_MODEL=gz_x500 ./build/px4_sitl_default/bin/px4 + ``` - В окремому терміналі запустіть: + В окремому терміналі запустіть: - ```sh - python /path/to/simulation-gazebo - ``` + ```sh + python /path/to/simulation-gazebo + ``` ## Додавання нових світів та моделей @@ -358,38 +358,38 @@ SDF files, mesh files, textures and anything else to do with the functionality a 2. Define the default parameters for Gazebo in the airframe configuration file (this example is from [x500 quadcopter](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/4001_gz_x500)): - ```ini - PX4_SIMULATOR=${PX4_SIMULATOR:=gz} - PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} - PX4_SIM_MODEL=${PX4_SIM_MODEL:=} - ``` + ```ini + PX4_SIMULATOR=${PX4_SIMULATOR:=gz} + PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} + PX4_SIM_MODEL=${PX4_SIM_MODEL:=} + ``` - - `PX4_SIMULATOR=${PX4_SIMULATOR:=gz}` sets the default simulator (Gz) for that specific airframe. + - `PX4_SIMULATOR=${PX4_SIMULATOR:=gz}` sets the default simulator (Gz) for that specific airframe. - - `PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}` sets the [default world](https://github.com/PX4/PX4-gazebo-models/blob/main/worlds/default.sdf) for that specific airframe. + - `PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}` sets the [default world](https://github.com/PX4/PX4-gazebo-models/blob/main/worlds/default.sdf) for that specific airframe. - - Setting the default value of `PX4_SIM_MODEL` lets you start the simulation with just: + - Setting the default value of `PX4_SIM_MODEL` lets you start the simulation with just: - ```sh - PX4_SYS_AUTOSTART= ./build/px4_sitl_default/bin/px4 - ``` + ```sh + PX4_SYS_AUTOSTART= ./build/px4_sitl_default/bin/px4 + ``` 3. Add CMake Target for the [airframe](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt). - - If you plan to use "regular" mode, add your model SDF to `Tools/simulation/gz/models/`. - - If you plan to use _standalone_ mode, add your model SDF to `~/.simulation-gazebo/models/` + - If you plan to use "regular" mode, add your model SDF to `Tools/simulation/gz/models/`. + - If you plan to use _standalone_ mode, add your model SDF to `~/.simulation-gazebo/models/` - Ви звичайно також можете використовувати обидва варіанти. + Ви звичайно також можете використовувати обидва варіанти. ### Додавання світу Щоб додати новий світ: 1. Add your world to the list of worlds found in the [`CMakeLists.txt` here](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/gz_bridge/CMakeLists.txt). - This is required in order to allow `CMake` to generate correct targets. + This is required in order to allow `CMake` to generate correct targets. - - If you plan to use "normal" mode, add your world sdf to `Tools/simulation/gz/worlds/`. - - If you plan to use _standalone_ mode, add your world SDF to `~/.simulation-gazebo/worlds/` + - If you plan to use "normal" mode, add your world sdf to `Tools/simulation/gz/worlds/`. + - If you plan to use _standalone_ mode, add your world SDF to `~/.simulation-gazebo/worlds/` :::info As long as the world file and the model file are in the Gazebo search path (`GZ_SIM_RESOURCE_PATH`) it is not necessary to add them to the PX4 world and model directories. diff --git a/docs/uk/sim_gazebo_gz/plugins.md b/docs/uk/sim_gazebo_gz/plugins.md index 9723f44177..0f48c53db8 100644 --- a/docs/uk/sim_gazebo_gz/plugins.md +++ b/docs/uk/sim_gazebo_gz/plugins.md @@ -43,8 +43,8 @@ When developing new plugins: 1. **Follow the plugin architecture** - Implement desired interfaces. - You can start by copying the [Template plugin](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/template_plugin) which is a simple example that only implements `ISystemPreUpdate` and `ISystemPostUpdate`. - The interfaces are specified in the official [Gazebo documentation](https://gazebosim.org/api/sim/9/createsystemplugins.html). + You can start by copying the [Template plugin](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/gz_plugins/template_plugin) which is a simple example that only implements `ISystemPreUpdate` and `ISystemPostUpdate`. + The interfaces are specified in the official [Gazebo documentation](https://gazebosim.org/api/sim/9/createsystemplugins.html). 2. **Register your plugin** - Add it to [server.config](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/gz_bridge/server.config) for discovery. diff --git a/docs/uk/sim_gazebo_gz/tools_avl_automation.md b/docs/uk/sim_gazebo_gz/tools_avl_automation.md index ced2df2610..80e32b4bb8 100644 --- a/docs/uk/sim_gazebo_gz/tools_avl_automation.md +++ b/docs/uk/sim_gazebo_gz/tools_avl_automation.md @@ -11,26 +11,26 @@ Щоб налаштувати інструмент: 1. Завантажте AVL 3.36 з . - Файл AVL для версії 3.36 можна знайти приблизно посередині сторінки. + Файл AVL для версії 3.36 можна знайти приблизно посередині сторінки. 2. Після завантаження розпакуйте AVL та перемістіть його в домашню директорію за допомогою: - ```sh - sudo tar -xf avl3.36.tgz - mv ./Avl /home/ - ``` + ```sh + sudo tar -xf avl3.36.tgz + mv ./Avl /home/ + ``` 3. Дотримуйтесь **index.md**, що знаходиться у `./Avl` щоб завершити процес встановлення AVL (вимагає встановлення бібліотек `plotlib` та `eispack`). - Ми рекомендуємо використовувати варіант компіляції "gfortran", який може далі вимагати, щоб ви встановили "gfortran". - На Ubuntu це можна зробити виконавши: + Ми рекомендуємо використовувати варіант компіляції "gfortran", який може далі вимагати, щоб ви встановили "gfortran". + На Ubuntu це можна зробити виконавши: - ```sh - sudo apt update - sudo apt install gfortran - ``` + ```sh + sudo apt update + sudo apt install gfortran + ``` - При запуску Makefile для AVL, ви можливо зіткнетесь з повідомленням `Error 1`, яке стверджує що відсутня якась директорія. - Це не завадить AVL працювати для нашої мети. + При запуску Makefile для AVL, ви можливо зіткнетесь з повідомленням `Error 1`, яке стверджує що відсутня якась директорія. + Це не завадить AVL працювати для нашої мети. Як тільки процес, описаний в AVL README буде завершений, AVL готовий до використання. Зі сторони AVL та інструменту більше ніяких налаштувань не потрібно. @@ -49,16 +49,16 @@ 2. Запустіть інструмент на вашому yml-файлі: - ```sh - python input_avl.py .yml - ``` + ```sh + python input_avl.py .yml + ``` - Зверніть увагу, що пакети `yaml` та `argparse` повинні бути присутні в середовищі Python. + Зверніть увагу, що пакети `yaml` та `argparse` повинні бути присутні в середовищі Python. 3. Інструмент очікує діапазон певних параметрів рухомого засобу, які потрібні щоб вказати геометрію та фізичні властивості літака. - Ви можете або: - - обрати попередньо визначений шаблон моделі (наприклад Cessna або ВЗІП), який має відому кількість поверхонь керування і просто змінити деяки фізичні властивості, або - - визначити повністю довільну модель + Ви можете або: + - обрати попередньо визначений шаблон моделі (наприклад Cessna або ВЗІП), який має відому кількість поверхонь керування і просто змінити деяки фізичні властивості, або + - визначити повністю довільну модель Після виконання скрипту, згенеровані файли `.avl`, `.sdf` та креслення пропонованих поверхонь керування можна знайти у директорії ``. Файл sdf - це згенерований плагін Advanced Lift Drag який може бути скопійовано і вставлено у файл model.sdf, який потім можна запустити у Gazebo. diff --git a/docs/uk/sim_jmavsim/index.md b/docs/uk/sim_jmavsim/index.md index 92d65c2f9c..2b92535f04 100644 --- a/docs/uk/sim_jmavsim/index.md +++ b/docs/uk/sim_jmavsim/index.md @@ -30,23 +30,23 @@ Follow the instructions below to install jMAVSim on macOS. To setup the environment for [jMAVSim](../sim_jmavsim/index.md) simulation: 1. Install a recent version of Java (e.g. Java 15). - You can download [Java 15 (or later) from Oracle](https://www.oracle.com/java/technologies/downloads/?er=221886) or use [Eclipse Temurin](https://adoptium.net): + You can download [Java 15 (or later) from Oracle](https://www.oracle.com/java/technologies/downloads/?er=221886) or use [Eclipse Temurin](https://adoptium.net): - ```sh - brew install --cask temurin - ``` + ```sh + brew install --cask temurin + ``` 2. Install jMAVSim: - ```sh - brew install px4-sim-jmavsim - ``` + ```sh + brew install px4-sim-jmavsim + ``` - :::warning - PX4 v1.11 and beyond require at least JDK 15 for jMAVSim simulation. + :::warning + PX4 v1.11 and beyond require at least JDK 15 for jMAVSim simulation. - For earlier versions, macOS users might see the error `Exception in thread "main" java.lang.UnsupportedClassVersionError:`. - You can find the fix in the [jMAVSim with SITL > Troubleshooting](../sim_jmavsim/index.md#troubleshooting)). + For earlier versions, macOS users might see the error `Exception in thread "main" java.lang.UnsupportedClassVersionError:`. + You can find the fix in the [jMAVSim with SITL > Troubleshooting](../sim_jmavsim/index.md#troubleshooting)). ::: diff --git a/docs/uk/simulation/index.md b/docs/uk/simulation/index.md index e9a85d3c41..2f0e51f38f 100644 --- a/docs/uk/simulation/index.md +++ b/docs/uk/simulation/index.md @@ -217,20 +217,20 @@ The simulated camera is a gazebo classic plugin that implements the [MAVLink Cam PX4 connects/integrates with this camera in _exactly the same way_ as it would with any other MAVLink camera: 1. [TRIG_INTERFACE](../advanced_config/parameter_reference.md#TRIG_INTERFACE) must be set to `3` to configure the camera trigger driver for use with a MAVLink camera - :::tip - In this mode the driver just sends a [CAMERA_TRIGGER](https://mavlink.io/en/messages/common.html#CAMERA_TRIGGER) message whenever an image capture is requested. - For more information see [Cameras Connected to Flight Controller Outputs](../camera/fc_connected_camera.md). + :::tip + In this mode the driver just sends a [CAMERA_TRIGGER](https://mavlink.io/en/messages/common.html#CAMERA_TRIGGER) message whenever an image capture is requested. + For more information see [Cameras Connected to Flight Controller Outputs](../camera/fc_connected_camera.md). ::: 2. PX4 повинен перенаправляти всі команди камери між GCS і (симулятором) MAVLink Camera. - You can do this by starting [MAVLink](../modules/modules_communication.md#mavlink) with the `-f` flag as shown, specifying the UDP ports for the new connection. + You can do this by starting [MAVLink](../modules/modules_communication.md#mavlink) with the `-f` flag as shown, specifying the UDP ports for the new connection. - ```sh - mavlink start -u 14558 -o 14530 -r 4000 -f -m camera - ``` + ```sh + mavlink start -u 14558 -o 14530 -r 4000 -f -m camera + ``` - ::: info - More than just the camera MAVLink messages will be forwarded, but the camera will ignore those that it doesn't consider relevant. + ::: info + More than just the camera MAVLink messages will be forwarded, but the camera will ignore those that it doesn't consider relevant. ::: diff --git a/docs/uk/telemetry/crsf_telemetry.md b/docs/uk/telemetry/crsf_telemetry.md index 484f0f04f0..8cef4b1675 100644 --- a/docs/uk/telemetry/crsf_telemetry.md +++ b/docs/uk/telemetry/crsf_telemetry.md @@ -77,36 +77,36 @@ To use this feature you must build and upload custom firmware that includes [crs 1. [Setup a development environment](../dev_setup/dev_env.md) for building PX4. - As part of this process you will have used `git` to fetch source code into the **PX4-Autopilot** directory. + As part of this process you will have used `git` to fetch source code into the **PX4-Autopilot** directory. 2. Open a terminal and `cd` into the `PX4-Autopilot` directory. - ```sh - cd PX4-Autopilot - ``` + ```sh + cd PX4-Autopilot + ``` 3. Launch the [PX4 board config tool (`menuconfig`)](../hardware/porting_guide_config.md#px4-menuconfig-setup) for your `make` target using the `boardconfig` option (here the target is the [ARK Electronics ARKV6X](../flight_controller/ark_v6x.md) flight controller): - ```sh - make ark_fmu-v6x_default boardconfig - ``` + ```sh + make ark_fmu-v6x_default boardconfig + ``` 4. У інструменті конфігурації плати PX4: - - Disable the default `rc_input` module - 1. Navigate to the `drivers` submenu, then scroll down to highlight `rc_input`. - 2. Use the enter key to remove the `*` from `rc_input` checkbox. - - Enable the `crsf_rc` module - 1. Scroll to highlight the `RC` submenu, then press enter to open it. - 2. Scroll to highlight `crsf_rc` and press enter to enable it. + - Disable the default `rc_input` module + 1. Navigate to the `drivers` submenu, then scroll down to highlight `rc_input`. + 2. Use the enter key to remove the `*` from `rc_input` checkbox. + - Enable the `crsf_rc` module + 1. Scroll to highlight the `RC` submenu, then press enter to open it. + 2. Scroll to highlight `crsf_rc` and press enter to enable it. - Збережіть і вийдіть з інструменту конфігурації плати PX4. + Збережіть і вийдіть з інструменту конфігурації плати PX4. 5. [Build the PX4 source code](../dev_setup/building_px4.md) with your changes (again assuming you are using ARKV6X): - ```sh - make ark_fmu-v6x_default - ``` + ```sh + make ark_fmu-v6x_default + ``` Це побудує вашу власну прошивку, яку зараз потрібно завантажити на ваш контролер польоту. @@ -128,11 +128,11 @@ Alternatively you can use QGroundControl to install the firmware, as described i 1. [RC_CRSF_PRT_CFG](../advanced_config/parameter_reference.md#RC_CRSF_PRT_CFG) — Set to the port that is connected to the CRSF receiver (such as `TELEM1`). - This [configures the serial port](../peripherals/serial_configuration.md) to use the CRSF protocol. - Note that some serial ports may already have a [default serial port mapping](../peripherals/serial_configuration.md#default-serial-port-configuration) or [default MAVLink serial port mapping](../peripherals/mavlink_peripherals.md#default-mavlink-ports) that you will have to un-map before you can assign the port to CRSF. - For example, if you want to use `TELEM1` or `TELEM2` you first need to modify [MAV_0_CONFIG](../advanced_config/parameter_reference.md#MAV_0_CONFIG) or [MAV_1_CONFIG](../advanced_config/parameter_reference.md#MAV_1_CONFIG) to stop setting those ports. + This [configures the serial port](../peripherals/serial_configuration.md) to use the CRSF protocol. + Note that some serial ports may already have a [default serial port mapping](../peripherals/serial_configuration.md#default-serial-port-configuration) or [default MAVLink serial port mapping](../peripherals/mavlink_peripherals.md#default-mavlink-ports) that you will have to un-map before you can assign the port to CRSF. + For example, if you want to use `TELEM1` or `TELEM2` you first need to modify [MAV_0_CONFIG](../advanced_config/parameter_reference.md#MAV_0_CONFIG) or [MAV_1_CONFIG](../advanced_config/parameter_reference.md#MAV_1_CONFIG) to stop setting those ports. - Немає потреби встановлювати швидкість передачі для порту, оскільки це налаштовано драйвером. + Немає потреби встановлювати швидкість передачі для порту, оскільки це налаштовано драйвером. 2. [RC_CRSF_TEL_EN](../advanced_config/parameter_reference.md#RC_CRSF_TEL_EN) — Enable to activate Crossfire telemetry. diff --git a/docs/uk/telemetry/jfi_telemetry.md b/docs/uk/telemetry/jfi_telemetry.md index decce61a0d..d6ec2f083c 100644 --- a/docs/uk/telemetry/jfi_telemetry.md +++ b/docs/uk/telemetry/jfi_telemetry.md @@ -111,9 +111,9 @@ However if you change the baud rate from 57600 you will need to create and use a 1. Disable SiK Radio in QGC (**Application Settings → General → AutoConnect**). 2. Create a new link configuration: - - Go to **Application Settings → Comms Links**. - - Click **Add**. - - Set **Type** to **Serial**, configure the **Serial Port** and **Baud Rate** to match the J.Fi device. + - Go to **Application Settings → Comms Links**. + - Click **Add**. + - Set **Type** to **Serial**, configure the **Serial Port** and **Baud Rate** to match the J.Fi device. 3. Select **Connect** to connect with the new configuration. ## J.Fi Configuration diff --git a/docs/uk/test_and_ci/fuzz_tests.md b/docs/uk/test_and_ci/fuzz_tests.md index 8215c18d8c..94db42eb4b 100644 --- a/docs/uk/test_and_ci/fuzz_tests.md +++ b/docs/uk/test_and_ci/fuzz_tests.md @@ -15,14 +15,14 @@ To write a fuzz test: 1. Start by writing a "normal" [functional test](../test_and_ci/unit_tests.md#functional-test). 2. Make sure the file name contains `fuzz` (lower case). - For example `my_driver_fuzz_tests.cpp`. + For example `my_driver_fuzz_tests.cpp`. 3. Add one or more fuzz tests to the file. - Наприклад: + Наприклад: ```cpp #include #include - + void myDriverNeverCrashes(const std::string& s) { MyDriver driver; driver.handleInput(s); diff --git a/docs/uk/test_and_ci/index.md b/docs/uk/test_and_ci/index.md index 570eeedba5..57cd0ba411 100644 --- a/docs/uk/test_and_ci/index.md +++ b/docs/uk/test_and_ci/index.md @@ -9,8 +9,8 @@ PX4 широко протестовано за допомогою модульн - [Unit Tests](../test_and_ci/unit_tests.md) - [Continuous Integration (CI)](../test_and_ci/continous_integration.md) - [Integration Testing](../test_and_ci/integration_testing.md) - - [MAVSDK Integration Testing](../test_and_ci/integration_testing_mavsdk.md) - - [PX4 ROS2 Interface Library Integration Testing](../test_and_ci/integration_testing_px4_ros2_interface.md) - - [ROS 1 Integration Testing](../test_and_ci/integration_testing_ros1_mavros.md) (Deprecated) + - [MAVSDK Integration Testing](../test_and_ci/integration_testing_mavsdk.md) + - [PX4 ROS2 Interface Library Integration Testing](../test_and_ci/integration_testing_px4_ros2_interface.md) + - [ROS 1 Integration Testing](../test_and_ci/integration_testing_ros1_mavros.md) (Deprecated) - [Docker](../test_and_ci/docker.md) - [Maintenance](../test_and_ci/maintenance.md) diff --git a/docs/uk/test_and_ci/integration_testing_ros1_mavros.md b/docs/uk/test_and_ci/integration_testing_ros1_mavros.md index 8a1272c79c..4ca05494ec 100644 --- a/docs/uk/test_and_ci/integration_testing_ros1_mavros.md +++ b/docs/uk/test_and_ci/integration_testing_ros1_mavros.md @@ -65,73 +65,73 @@ To write a new test: 1. Create a new test script by copying the empty test skeleton below: - ```python - #!/usr/bin/env python - # [... LICENSE ...] - - # - # @author Example Author - # - PKG = 'px4' - - import unittest - import rospy - import rosbag - - from sensor_msgs.msg import NavSatFix - - class MavrosNewTest(unittest.TestCase): - """ - Test description - """ - - def setUp(self): - rospy.init_node('test_node', anonymous=True) - rospy.wait_for_service('mavros/cmd/arming', 30) - - rospy.Subscriber("mavros/global_position/global", NavSatFix, self.global_position_callback) - self.rate = rospy.Rate(10) # 10hz - self.has_global_pos = False - - def tearDown(self): - pass - - # - # General callback functions used in tests - # - def global_position_callback(self, data): - self.has_global_pos = True - - def test_method(self): - """Test method description""" - - # FIXME: hack to wait for simulation to be ready - while not self.has_global_pos: - self.rate.sleep() - - # TODO: execute test - - if __name__ == '__main__': - import rostest - rostest.rosrun(PKG, 'mavros_new_test', MavrosNewTest) - ``` + ```python + #!/usr/bin/env python + # [... LICENSE ...] + + # + # @author Example Author + # + PKG = 'px4' + + import unittest + import rospy + import rosbag + + from sensor_msgs.msg import NavSatFix + + class MavrosNewTest(unittest.TestCase): + """ + Test description + """ + + def setUp(self): + rospy.init_node('test_node', anonymous=True) + rospy.wait_for_service('mavros/cmd/arming', 30) + + rospy.Subscriber("mavros/global_position/global", NavSatFix, self.global_position_callback) + self.rate = rospy.Rate(10) # 10hz + self.has_global_pos = False + + def tearDown(self): + pass + + # + # General callback functions used in tests + # + def global_position_callback(self, data): + self.has_global_pos = True + + def test_method(self): + """Test method description""" + + # FIXME: hack to wait for simulation to be ready + while not self.has_global_pos: + self.rate.sleep() + + # TODO: execute test + + if __name__ == '__main__': + import rostest + rostest.rosrun(PKG, 'mavros_new_test', MavrosNewTest) + ``` 2. Run the new test only - Start the simulator: - ```sh - cd - source Tools/simulation/gazebo/setup_gazebo.bash - roslaunch launch/mavros_posix_sitl.launch - ``` + ```sh + cd + source Tools/simulation/gazebo/setup_gazebo.bash + roslaunch launch/mavros_posix_sitl.launch + ``` - Run test (in a new shell): - ```sh - cd - source Tools/simulation/gazebo/setup_gazebo.bash - rosrun px4 mavros_new_test.py - ``` + ```sh + cd + source Tools/simulation/gazebo/setup_gazebo.bash + rosrun px4 mavros_new_test.py + ``` 3. Add new test node to a launch file - In `test/` create a new `.test` ROS launch file. @@ -145,9 +145,9 @@ To write a new test: Наприклад: - ```sh - tests_: rostest - @"$(SRC_DIR)"/test/rostest_px4_run.sh mavros_posix_tests_.test - ``` + ```sh + tests_: rostest + @"$(SRC_DIR)"/test/rostest_px4_run.sh mavros_posix_tests_.test + ``` Run the tests as described above. diff --git a/docs/uk/test_and_ci/unit_tests.md b/docs/uk/test_and_ci/unit_tests.md index e06d7f0b8a..f72444d986 100644 --- a/docs/uk/test_and_ci/unit_tests.md +++ b/docs/uk/test_and_ci/unit_tests.md @@ -126,34 +126,34 @@ It can be run directly in a debugger, however be careful to only run one test pe 10. Within [tests_main.h](https://github.com/PX4/PX4-Autopilot/blob/main/src/systemcmds/tests/tests_main.h) define the new test: - ```cpp - extern int test_[description](int argc, char *argv[]); - ``` + ```cpp + extern int test_[description](int argc, char *argv[]); + ``` 11. Within [tests_main.c](https://github.com/PX4/PX4-Autopilot/blob/main/src/systemcmds/tests/tests_main.c) add description name, test function and option: - ```cpp - ... - } tests[] = { - {... - {"[description]", test_[description], OPTION}, - ... - } - ``` + ```cpp + ... + } tests[] = { + {... + {"[description]", test_[description], OPTION}, + ... + } + ``` - `OPTION` can be `OPT_NOALLTEST`,`OPT_NOJIGTEST` or `0` and is considered if within px4 shell one of the two commands are called: + `OPTION` can be `OPT_NOALLTEST`,`OPT_NOJIGTEST` or `0` and is considered if within px4 shell one of the two commands are called: - ```sh - pxh> tests all - ``` + ```sh + pxh> tests all + ``` - або + або - ```sh - pxh> tests jig - ``` + ```sh + pxh> tests jig + ``` - If a test has option `OPT_NOALLTEST`, then that test will be excluded when calling `tests all`. The same is true for `OPT_NOJITEST` when command `test jig` is called. Option `0` means that the test is never excluded, which is what most developer want to use. + If a test has option `OPT_NOALLTEST`, then that test will be excluded when calling `tests all`. The same is true for `OPT_NOJITEST` when command `test jig` is called. Option `0` means that the test is never excluded, which is what most developer want to use. 12. Add the test `test_[description].cpp` to the [CMakeLists.txt](https://github.com/PX4/PX4-Autopilot/blob/main/src/systemcmds/tests/CMakeLists.txt). diff --git a/docs/uk/test_cards/mc_04_failsafe_testing.md b/docs/uk/test_cards/mc_04_failsafe_testing.md index d22a331772..e21b52750b 100644 --- a/docs/uk/test_cards/mc_04_failsafe_testing.md +++ b/docs/uk/test_cards/mc_04_failsafe_testing.md @@ -9,10 +9,10 @@ Test RC loss, data link loss, and low battery failsafes. - Verify RC Loss action is Return to Land - Verify Data Link Loss action is Return to Land and the timeout is 10 seconds - Verify Battery failsafe - - Action is Return to Land - - Battery Warn Level is 25% - - Battery Failsafe Level is 20% - - Battery Emergency Level is 15% + - Action is Return to Land + - Battery Warn Level is 25% + - Battery Failsafe Level is 20% + - Battery Emergency Level is 15% ## Flight Tests diff --git a/docs/uk/uart/user_configurable_serial_driver.md b/docs/uk/uart/user_configurable_serial_driver.md index 812f3561b0..4164dfbf84 100644 --- a/docs/uk/uart/user_configurable_serial_driver.md +++ b/docs/uk/uart/user_configurable_serial_driver.md @@ -26,33 +26,33 @@ 1. Створіть конфігураційний файл модуля YAML: - - Add a new file in the driver's source directory named **module.yaml** - - Вставте наступний текст і підлаштуйте за потреби: + - Add a new file in the driver's source directory named **module.yaml** + - Вставте наступний текст і підлаштуйте за потреби: - ```cmake - module_name: uLanding Radar - serial_config: - - command: ulanding_radar start -d ${SERIAL_DEV} -b p:${BAUD_PARAM} - port_config_param: - name: SENS_ULAND_CFG - group: Sensors - ``` + ```cmake + module_name: uLanding Radar + serial_config: + - command: ulanding_radar start -d ${SERIAL_DEV} -b p:${BAUD_PARAM} + port_config_param: + name: SENS_ULAND_CFG + group: Sensors + ``` - ::: info - The full documentation of the module configuration file can be found in the [validation/module_schema.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/validation/module_schema.yaml) file. - Це також використовується для перевірки всіх файлів конфігурації в CI. + ::: info + The full documentation of the module configuration file can be found in the [validation/module_schema.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/validation/module_schema.yaml) file. + Це також використовується для перевірки всіх файлів конфігурації в CI. ::: 2. Add the module configuration to the **CMakeLists.txt** file for the driver module: - ```cmake - px4_add_module( - MODULE drivers__ulanding - MAIN ulanding_radar - SRCS - ulanding.cpp - MODULE_CONFIG - module.yaml - ) - ``` + ```cmake + px4_add_module( + MODULE drivers__ulanding + MAIN ulanding_radar + SRCS + ulanding.cpp + MODULE_CONFIG + module.yaml + ) + ``` From a14cd9ad7917a2d6e431c3d5c351f89166bda72c Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Tue, 16 Sep 2025 08:57:44 +1000 Subject: [PATCH 034/812] New Crowdin translations - ko (#25557) Co-authored-by: Crowdin Bot --- docs/ko/SUMMARY.md | 5 + docs/ko/airframes/airframe_reference.md | 13 +- docs/ko/assembly/_assembly.md | 2 +- docs/ko/concept/system_startup.md | 31 ++- docs/ko/config/safety.md | 12 +- docs/ko/dev_setup/dev_env_windows_wsl.md | 200 +++++++++--------- .../ko/flight_controller/accton-godwit_ga1.md | 153 ++++++++++++++ .../autopilot_manufacturer_supported.md | 1 + docs/ko/modules/modules_driver_ins.md | 35 +++ docs/ko/msg_docs/ActionRequest.md | 34 +-- docs/ko/msg_docs/ActuatorMotors.md | 12 +- docs/ko/msg_docs/ActuatorServos.md | 8 +- docs/ko/msg_docs/Airspeed.md | 10 +- docs/ko/msg_docs/ArmingCheckReply.md | 46 ++-- docs/ko/msg_docs/ArmingCheckRequest.md | 8 +- docs/ko/msg_docs/ArmingCheckRequestV0.md | 30 +++ docs/ko/msg_docs/CellularStatus.md | 60 +++--- docs/ko/msg_docs/RoverSpeedSetpoint.md | 14 ++ docs/ko/msg_docs/RoverSpeedStatus.md | 18 ++ docs/ko/msg_docs/VehicleAirData.md | 32 +-- docs/ko/msg_docs/index.md | 7 +- docs/ko/releases/main.md | 2 +- docs/ko/sensor/accelerometer.md | 2 +- docs/ko/sensor/inertial_navigation_systems.md | 1 + docs/ko/sensor/sbgecom.md | 159 ++++++++++++++ 25 files changed, 666 insertions(+), 229 deletions(-) create mode 100644 docs/ko/flight_controller/accton-godwit_ga1.md create mode 100644 docs/ko/msg_docs/ArmingCheckRequestV0.md create mode 100644 docs/ko/msg_docs/RoverSpeedSetpoint.md create mode 100644 docs/ko/msg_docs/RoverSpeedStatus.md create mode 100644 docs/ko/sensor/sbgecom.md diff --git a/docs/ko/SUMMARY.md b/docs/ko/SUMMARY.md index 8542513eec..e0bc2578cc 100644 --- a/docs/ko/SUMMARY.md +++ b/docs/ko/SUMMARY.md @@ -157,6 +157,7 @@ - [mRo (3DR) Pixhawk 배선 퀵 스타트](assembly/quick_start_pixhawk.md) - [Holybro Pixhawk Mini (FMUv3) - Discontinued](flight_controller/pixhawk_mini.md) - [Manufacturer-Supported Autopilots](flight_controller/autopilot_manufacturer_supported.md) + - [Accton Godwit GA1](flight_controller/accton-godwit_ga1.md) - [AirMind MindPX](flight_controller/mindpx.md) - [AirMind MindRacer](flight_controller/mindracer.md) - [ARK Electronics ARKV6X](flight_controller/ark_v6x.md) @@ -283,6 +284,7 @@ - [CubePilot Here+ (Discontined)](gps_compass/rtk_gps_hex_hereplus.md) - [INS (Inertial Navigation/GNSS)](sensor/inertial_navigation_systems.md) - [InertialLabs](sensor/inertiallabs.md) + - [sbgECom](sensor/sbgecom.md) - [VectorNav](sensor/vectornav.md) - [광류 센서](sensor/optical_flow.md) - [ARK Flow](dronecan/ark_flow.md) @@ -679,6 +681,8 @@ - [RoverPositionSetpoint](msg_docs/RoverPositionSetpoint.md) - [RoverRateSetpoint](msg_docs/RoverRateSetpoint.md) - [RoverRateStatus](msg_docs/RoverRateStatus.md) + - [RoverSpeedSetpoint](msg_docs/RoverSpeedSetpoint.md) + - [RoverSpeedStatus](msg_docs/RoverSpeedStatus.md) - [RoverSteeringSetpoint](msg_docs/RoverSteeringSetpoint.md) - [RoverThrottleSetpoint](msg_docs/RoverThrottleSetpoint.md) - [RoverVelocitySetpoint](msg_docs/RoverVelocitySetpoint.md) @@ -739,6 +743,7 @@ - [YawEstimatorStatus](msg_docs/YawEstimatorStatus.md) - [AirspeedValidatedV0](msg_docs/AirspeedValidatedV0.md) - [ArmingCheckReplyV0](msg_docs/ArmingCheckReplyV0.md) + - [ArmingCheckRequestV0](msg_docs/ArmingCheckRequestV0.md) - [BatteryStatusV0](msg_docs/BatteryStatusV0.md) - [EventV0](msg_docs/EventV0.md) - [HomePositionV0](msg_docs/HomePositionV0.md) diff --git a/docs/ko/airframes/airframe_reference.md b/docs/ko/airframes/airframe_reference.md index 4ee1518c4a..06c9517842 100644 --- a/docs/ko/airframes/airframe_reference.md +++ b/docs/ko/airframes/airframe_reference.md @@ -631,7 +631,16 @@ div.frame_variant td, div.frame_variant th { ### Free-Flyer
- + + + + + + + + + +
공통 출력
  • Motor1: back left thruster, +x thrust
  • Motor2: front left thruster, -x thrust
  • Motor3: back right thruster, +x thrust
  • Motor4: front right thruster, -x thrust
  • Motor5: front left thruster, +y thrust
  • Motor6: front right thruster, -y thrust
  • Motor7: back left thruster, +y thrust
  • Motor8: back right thruster, -y thrust
@@ -641,7 +650,7 @@ div.frame_variant td, div.frame_variant th { - KTH-ATMOS + KTH-ATMOS Maintainer: DISCOWER

SYS_AUTOSTART = 70000

diff --git a/docs/ko/assembly/_assembly.md b/docs/ko/assembly/_assembly.md index 29e71c2760..496741776c 100644 --- a/docs/ko/assembly/_assembly.md +++ b/docs/ko/assembly/_assembly.md @@ -291,7 +291,7 @@ If you're using [DroneCAN ESC](../peripherals/esc_motors.md#dronecan) the contro ### Flight Controller Power Pixhawk FCs require a regulated power supply that can supply at around 5V/3A continuous (check your specific FC)! -This is sufficient to power the controller itself and a few low-power peripherals, such as a GNSS module, RC transmitter, and low power telemetry radio, but not for motors, actuators, and other peripherals. +This is sufficient to power the controller itself and a few low-power peripherals, such as a GNSS module, RC receiver, and low power telemetry radio, but not for motors, actuators, and other peripherals. [Power modules](../power_module/index.md) are commonly used to "split off" this regulated power supply for the FC and also to provide measurements of the battery voltage and total current to the whole system — which PX4 can use to estimate power levels. The power module is connected to the FC power port, which is normally labeled `POWER` (or `POWER 1` or `POWER 2` for FCs that have redundant power supply). diff --git a/docs/ko/concept/system_startup.md b/docs/ko/concept/system_startup.md index 5dc6d5b985..79fd6cb79b 100644 --- a/docs/ko/concept/system_startup.md +++ b/docs/ko/concept/system_startup.md @@ -15,7 +15,7 @@ The first executed file is the [init.d/rcS](https://github.com/PX4/PX4-Autopilot ## POSIX (Linux/MacOS) -Posix에서 시스템 셸은 스크립트 인터프리터로 사용됩니다(예: /bin/sh, Ubuntu에서 dash에 심볼릭 링크됨). +On POSIX, the system shell is used as script interpreter (e.g. /bin/sh, being symlinked to dash on Ubuntu). 동작하기 위한 몇가지 조건이 있습니다. - PX4 모듈은 시스템에서 개별적으로 실행할 수 있어야합니다. @@ -59,7 +59,7 @@ cd /build/px4_sitl_default/bin ### Dynamic Modules 일반적으로 모든 모듈은 단일 PX4 실행 파일로 컴파일됩니다. -However, on Posix, there's the option of compiling a module into a separate file, which can be loaded into PX4 using the `dyn` command. +However, on POSIX, there's the option of compiling a module into a separate file, which can be loaded into PX4 using the `dyn` command. ```sh dyn ./test.px4mod @@ -95,7 +95,7 @@ This is documented below. The best way to customize the system startup is to introduce a [new frame configuration](../dev_airframes/adding_a_new_frame.md). The frame configuration file can be included in the firmware or on an SD Card. -#### Dynamic customization +#### Dynamic Customization If you only need to "tweak" the existing configuration, such as starting one more application or setting the value of a few parameters, you can specify these by creating two files in the `/etc/` directory of the SD Card: @@ -153,27 +153,36 @@ Calling an unknown command in system boot files may result in boot failure. mandatory_app start # Will abort boot if mandatory_app is unknown or fails ``` -#### Additional customization +#### Additional Init-File Customization -In rare cases where the desired setup cannot be achieved through frame configuration or dynamic customization, -you can add a script that will be contained in the binary. +In rare cases where the desired setup cannot be achieved through frame configuration or dynamic customization, you can add a script that will be compiled into the binary for a particular `make` target build variant. -**Note**: In almost all cases, you should use a frame configuration. This method should only be used for -edge-cases such as customizing `cannode` based boards. +:::warning +In almost all cases, you should use a frame configuration. +This method should only be used for edge-cases such as customizing `cannode` based boards. +::: + +단계는 다음과 같습니다: + +- Add a new init script in `boards///init` that will run during board startup. + 예: -- Add a new init script in `boards///init` that will run during board startup. 예: ```sh # File: boards///init/rc.additional param set-default ``` -- Add a new board variant in `boards///.px4board` that includes the additional script. 예: +- Add a new board variant in `boards///.px4board` that includes the additional script. + 예: + ```sh # File: boards///var.px4board CONFIG_BOARD_ADDITIONAL_INIT="rc.additional" ``` -- Compile the firmware with your new variant by appending the variant name to the compile target. 예: +- Compile the firmware with your new variant by appending the variant name to the compile target. + 예: + ```sh make _var ``` diff --git a/docs/ko/config/safety.md b/docs/ko/config/safety.md index 3323b03aaa..d819eb304b 100644 --- a/docs/ko/config/safety.md +++ b/docs/ko/config/safety.md @@ -206,23 +206,13 @@ The relevant parameters shown below. ### Position Loss Failsafe Action -The failure action is controlled by [COM_POSCTL_NAVL](../advanced_config/parameter_reference.md#COM_POSCTL_NAVL), based on whether RC control is assumed to be available (and altitude information): - -- `0`: Remote control available. - Switch to _Altitude mode_ if a height estimate is available, otherwise _Stabilized mode_. -- `1`: Remote control _not_ available. - Switch to _Descend mode_ if a height estimate is available, otherwise enter flight termination. - _Descend mode_ is a landing mode that does not require a position estimate. +Multicopters will switch to [Altitude mode](../flight_modes_mc/altitude.md) if a height estimate is available, otherwise [Stabilized mode](../flight_modes_mc/manual_stabilized.md). Fixed-wing planes, and VTOLs not configured to land in hover ([NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT)), have a parameter ([FW_GPSF_LT](../advanced_config/parameter_reference.md#FW_GPSF_LT)) that defines how long they will loiter (circle with a constant roll angle ([FW_GPSF_R](../advanced_config/parameter_reference.md#FW_GPSF_R)) at the current altitude) after losing position before attempting to land. If VTOLs have are configured to switch to hover for landing ([NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT)) then they will first transition and then descend. The relevant parameters for all vehicles shown below. -| 매개변수 | 설명 | -| -------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [COM_POSCTL_NAVL](../advanced_config/parameter_reference.md#COM_POSCTL_NAVL) | Position control navigation loss response during mission. Values: `0` - assume use of RC, `1` - Assume no RC. | - Parameters that only affect Fixed-wing vehicles: | 매개변수 | 설명 | diff --git a/docs/ko/dev_setup/dev_env_windows_wsl.md b/docs/ko/dev_setup/dev_env_windows_wsl.md index 0db75b34e0..fe782c5baa 100644 --- a/docs/ko/dev_setup/dev_env_windows_wsl.md +++ b/docs/ko/dev_setup/dev_env_windows_wsl.md @@ -33,7 +33,7 @@ _QGroundControl for Windows_ is additionally required if you need to: Note that you can also use it to monitor a simulation, but you must manually [connect to the simulation running in WSL](#qgroundcontrol-on-windows). :::info -Connecting to an USB device from within WSL is not natively supported, however it can still be achieved by using the [USBIPD-WIN](https://learn.microsoft.com/en-us/windows/wsl/connect-usb) project. With this you can automatically upload firmware from the command line in WSL using the [`upload`](../dev_setup/building_px4.md#uploading-firmware-flashing-the-board) function. +Connecting to an USB device from within WSL is not natively supported, however it can still be achieved by using the [USBIPD-WIN](https://learn.microsoft.com/en-us/windows/wsl/connect-usb) project. With this you can automatically upload firmware from the command line in WSL using the [`upload`](../dev_setup/building_px4.md#uploading-firmware-flashing-the-board) function. ::: :::info @@ -48,38 +48,38 @@ The benefit of WSL2 is that its virtual machine is deeply integrated into Window To install WSL2 with Ubuntu on a new installation of Windows 10 or 11: 1. Make sure your computer your computer's virtualization feature is enabled in the BIOS. - It's usually referred as "Virtualization Technology", "Intel VT-x" or "AMD-V" respectively + It's usually referred as "Virtualization Technology", "Intel VT-x" or "AMD-V" respectively 2. Open _cmd.exe_ as administrator. - This can be done by pressing the start key, typing `cmd`, right-clicking on the _Command prompt_ entry and selecting **Run as administrator**. + This can be done by pressing the start key, typing `cmd`, right-clicking on the _Command prompt_ entry and selecting **Run as administrator**. 3. Execute the following commands to install WSL2 and a particular Ubuntu version: - - Default version (Ubuntu 22.04): + - Default version (Ubuntu 22.04): - ```sh - wsl --install - ``` + ```sh + wsl --install + ``` - - Ubuntu 20.04 ([Gazebo-Classic Simulation](../sim_gazebo_classic/index.md)) + - Ubuntu 20.04 ([Gazebo-Classic Simulation](../sim_gazebo_classic/index.md)) - ```sh - wsl --install -d Ubuntu-20.04 - ``` + ```sh + wsl --install -d Ubuntu-20.04 + ``` - - Ubuntu 22.04 ([Gazebo Simulation](../sim_gazebo_gz/index.md)) + - Ubuntu 22.04 ([Gazebo Simulation](../sim_gazebo_gz/index.md)) - ```sh - wsl --install -d Ubuntu-22.04 - ``` + ```sh + wsl --install -d Ubuntu-22.04 + ``` - ::: info - You can also install[Ubuntu 20.04](https://www.microsoft.com/store/productId/9MTTCL66CPXJ) and [Ubuntu 22.04](https://www.microsoft.com/store/productId/9PN20MSR04DW) from the store, which allows you to delete the application using the normal Windows Add/Remove settings: + ::: info + You can also install[Ubuntu 20.04](https://www.microsoft.com/store/productId/9MTTCL66CPXJ) and [Ubuntu 22.04](https://www.microsoft.com/store/productId/9PN20MSR04DW) from the store, which allows you to delete the application using the normal Windows Add/Remove settings: ::: 4. WSL will prompt you for a user name and password for the Ubuntu installation. - Record these credentials as you will need them later on! + Record these credentials as you will need them later on! The command prompt is now a terminal within the newly installed Ubuntu environment. @@ -94,26 +94,26 @@ If you're using [Windows Terminal](https://learn.microsoft.com/en-us/windows/ter To open a WSL shell using a command prompt: 1. Open a command prompt: - - Press the Windows **Start** key. - - Type `cmd` and press **Enter** to open the prompt. + - Press the Windows **Start** key. + - Type `cmd` and press **Enter** to open the prompt. 2. To start WSL and access the WSL shell, execute the command: - ```sh - wsl -d - ``` + ```sh + wsl -d + ``` - 예: + 예: - ```sh - wsl -d Ubuntu - ``` + ```sh + wsl -d Ubuntu + ``` - ```sh - wsl -d Ubuntu-20.04 - ``` + ```sh + wsl -d Ubuntu-20.04 + ``` - If you only have one version of Ubuntu, you can just use `wsl`. + If you only have one version of Ubuntu, you can just use `wsl`. Enter the following commands to first close the WSL shell, and then shut down WSL: @@ -135,57 +135,57 @@ To install the development toolchain: 2. Execute the command `cd ~` to switch to the home folder of WSL for the next steps. - :::warning - This is important! - If you work from a location outside of the WSL file system you'll run into issues such as very slow execution and access right/permission errors. + :::warning + This is important! + If you work from a location outside of the WSL file system you'll run into issues such as very slow execution and access right/permission errors. ::: 3. Download the PX4 source code using `git` (which is already installed in WSL2): - ```sh - git clone https://github.com/PX4/PX4-Autopilot.git --recursive - ``` + ```sh + git clone https://github.com/PX4/PX4-Autopilot.git --recursive + ``` - ::: info - The environment setup scripts in the source usually work for recent PX4 releases. - If working with an older version of PX4 you may need to [get the source code specific to your release](../contribute/git_examples.md#get-a-specific-release). + ::: info + The environment setup scripts in the source usually work for recent PX4 releases. + If working with an older version of PX4 you may need to [get the source code specific to your release](../contribute/git_examples.md#get-a-specific-release). ::: 4. Run the **ubuntu.sh** installer script and acknowledge any prompts as the script progresses: - ```sh - bash ./PX4-Autopilot/Tools/setup/ubuntu.sh - ``` + ```sh + bash ./PX4-Autopilot/Tools/setup/ubuntu.sh + ``` - ::: info - This installs tools to build PX4 for Pixhawk and either Gazebo or Gazebo Classic targets: + ::: info + This installs tools to build PX4 for Pixhawk and either Gazebo or Gazebo Classic targets: - - You can use the `--no-nuttx` and `--no-sim-tools` options to omit the NuttX and/or simulation tools. - - Other Linux build targets are untested (you can try these by entering the appropriate commands in [Ubuntu Development Environment](../dev_setup/dev_env_linux_ubuntu.md) into the WSL shell). + - You can use the `--no-nuttx` and `--no-sim-tools` options to omit the NuttX and/or simulation tools. + - Other Linux build targets are untested (you can try these by entering the appropriate commands in [Ubuntu Development Environment](../dev_setup/dev_env_linux_ubuntu.md) into the WSL shell). ::: 5. Restart the "WSL computer" after the script completes (exit the shell, shutdown WSL, and restart WSL): - ```sh - exit - wsl --shutdown - wsl - ``` + ```sh + exit + wsl --shutdown + wsl + ``` 6. Switch to the PX4 repository in the WSL home folder: - ```sh - cd ~/PX4-Autopilot - ``` + ```sh + cd ~/PX4-Autopilot + ``` 7. Build the PX4 SITL target and test your environment: - ```sh - make px4_sitl - ``` + ```sh + make px4_sitl + ``` For more build options see [Building PX4 Software](../dev_setup/building_px4.md). @@ -205,26 +205,26 @@ To set up the integration: 5. In the WSL shell, switch to the PX4 folder: - ```sh - cd ~/PX4-Autopilot - ``` + ```sh + cd ~/PX4-Autopilot + ``` 6. In the WSL shell, start VS Code: - ```sh - code . - ``` + ```sh + code . + ``` - This will open the IDE fully integrated with the WSL shell. + This will open the IDE fully integrated with the WSL shell. - Make sure you always open the PX4 repository in the Remote WSL mode. + Make sure you always open the PX4 repository in the Remote WSL mode. 7. Next time you want to develop WSL2 you can very easily open it again in Remote WSL mode by selecting **Open Recent** (as shown below). - This will start WSL for you. + This will start WSL for you. - ![](../../assets/toolchain/vscode/vscode_wsl.png) + ![](../../assets/toolchain/vscode/vscode_wsl.png) - Note however that the IP address of the WSL virtual machine will have changed, so you won't be able to monitor simulation from QGC for Windows (you can still monitor using QGC for Linux) + Note however that the IP address of the WSL virtual machine will have changed, so you won't be able to monitor simulation from QGC for Windows (you can still monitor using QGC for Linux) ## QGroundControl @@ -240,21 +240,21 @@ You can do this from within the WSL shell. 1. In a web browser, navigate to the QGC [Ubuntu download section](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html#ubuntu) 2. Right-click on the **QGroundControl.AppImage** link, and select "Copy link address". - This will be something like _https://d176td9ibe4jno.cloudfront.net/builds/master/QGroundControl.AppImage_ + This will be something like _https://d176td9ibe4jno.cloudfront.net/builds/master/QGroundControl.AppImage_ 3. [Open a WSL shell](#opening-a-wsl-shell) and enter the following commands to download the appimage and make it executable (replace the AppImage URL where indicated): - ```sh - cd ~ - wget - chmod +x QGroundControl.AppImage - ``` + ```sh + cd ~ + wget + chmod +x QGroundControl.AppImage + ``` 4. Run QGroundControl: - ```sh - ./QGroundControl.AppImage - ``` + ```sh + ./QGroundControl.AppImage + ``` QGroundControl will launch and automatically connect to a running simulation and allow you to monitor and control your vehicle(s). @@ -270,15 +270,15 @@ These steps describe how you can connect to the simulation running in the WSL: 2. Check the IP address of the WSL virtual machine by running the command `ip addr | grep eth0`: - ```sh - $ ip addr | grep eth0 + ```sh + $ ip addr | grep eth0 - 6: eth0: mtu 1500 qdisc mq state UP group default qlen 1000 - inet 172.18.46.131/20 brd 172.18.47.255 scope global eth0 - ``` + 6: eth0: mtu 1500 qdisc mq state UP group default qlen 1000 + inet 172.18.46.131/20 brd 172.18.47.255 scope global eth0 + ``` - Copy the first part of the `eth0` interface `inet` address to the clipboard. - In this case: `172.18.46.131`. + Copy the first part of the `eth0` interface `inet` address to the clipboard. + In this case: `172.18.46.131`. 3. In QGC go to **Q > Application Settings > Comm Links** @@ -304,14 +304,14 @@ Do the following steps to flash your custom binary built in WSL: 1. If you haven't already built the binary in WSL e.g. with a [WSL shell](dev_env_windows_wsl.md#opening-a-wsl-shell) and by running: - ```sh - cd ~/PX4-Autopilot - make px4_fmu-v5 - ``` + ```sh + cd ~/PX4-Autopilot + make px4_fmu-v5 + ``` - ::: tip - Use the correct `make` target for your board. - `px4_fmu-v5` can be used for a Pixhawk 4 board. + ::: tip + Use the correct `make` target for your board. + `px4_fmu-v5` can be used for a Pixhawk 4 board. ::: @@ -325,12 +325,12 @@ Do the following steps to flash your custom binary built in WSL: 6. Continue and select the firmware binary you just built in WSL. - In the open dialog look for the "Linux" location with the penguin icon in the left pane. - It's usually all the way at the bottom. - Choose the file in the path: `Ubuntu\home\{your WSL user name}\PX4-Autopilot\build\{your build target}\{your build target}.px4` + In the open dialog look for the "Linux" location with the penguin icon in the left pane. + It's usually all the way at the bottom. + Choose the file in the path: `Ubuntu\home\{your WSL user name}\PX4-Autopilot\build\{your build target}\{your build target}.px4` - ::: info - You can add the folder to the favourites to access it quickly next time. + ::: info + You can add the folder to the favourites to access it quickly next time. ::: @@ -349,3 +349,9 @@ sudo add-apt-repository ppa:kisak/kisak-mesa sudo apt update sudo apt upgrade ``` + +### QGroundControl not connecting to PX4 SITL + +- The connection between PX4 SITL on WSL2 and QGroundControl on Windows requires [broadcasting](../simulation/index.md#enable-udp-broadcasting) or [streaming to a specific address](../simulation/index.md#enable-streaming-to-specific-address) to be enabled. + Streaming to a specific address should be enabled by default, but is something to check if a connection can't be established. +- Network traffic might be blocked by firewall or antivirus on you system. diff --git a/docs/ko/flight_controller/accton-godwit_ga1.md b/docs/ko/flight_controller/accton-godwit_ga1.md new file mode 100644 index 0000000000..bd968f852e --- /dev/null +++ b/docs/ko/flight_controller/accton-godwit_ga1.md @@ -0,0 +1,153 @@ +# Accton Godwit G-A1 + +:::warning +PX4 does not manufacture this (or any) autopilot. +Contact the [manufacturer](https://cubepilot.org/#/home) for hardware support or compliance issues. +::: + +The G-A1 is a state-of-the-art flight controller developed derived from the [Pixhawk Autopilot v6X Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-012%20Pixhawk%20Autopilot%20v6X%20Standard.pdf). + +It includes an STM32H753 double-precision floating-point FMU processor and an STM32F103 IO coprocessor, multiple IMUs with 6-axis inertial sensors, two pressure/temperature sensors, and a geomagnetic sensor. +It also has independent buses and power supplies, and is designed for safety and rich expansion capabilities. + +With an integrated 10/100M Ethernet Physical Layer (PHY), the G-A1 can also communicate with a mission computer (airborne computer), high-end surveying and mapping cameras, and other UxV-mounted equipment for high-speed communications, meeting the needs of advanced UxV systems. + +:::tip +Visit [Accton-IoT Godwit](https://www.accton-iot.com/godwit/) for more information. +::: + +![AccGodwitGA1](../../assets/flight_controller/accton-godwit/ga1/outlook.png "Accton Godwit G-A1") + +![AccGodwitGA1 Top View](../../assets/flight_controller/accton-godwit/ga1/orientation.png "Accton Godwit G-A1 Top View") + +:::info +This flight controller is [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md). +::: + +## 사양 + +### 프로세서 + +- STM32H753IIK (Arm® Cortex®-M7 480MHz) +- STM32F103 (Arm® Cortex®-M3, 72MHz) + +### 센서 + +- Bosch BMI088 (vibration isolated) +- TDK InvenSense ICM-42688-P x 2 (one vibration isolated) +- TDK Barometric Pressure and Temperature Sensor CP-20100 x 2 (one vibration isolated) +- PNI RM3100 Geomagnetic Sensor (vibration isolated) + +### 전원 + +- 4.6V to 5.7V + +### External ports + +- 2 CAN Buses (CAN1 and CAN2) +- 3 TELEM Ports (TELEM1, TELEM2 and TELEM3) +- 2 GPS Ports (GPS1 with safety switch, LED, buzzer, and GPS2) +- 1 PPM IN +- 1 SBUS OUT +- 2 USB Ports (1 TYPE-C and 1 JST GH1.25) +- 1 10/100Base-T Ethernet Port +- 1 DSM/SBUS RC +- 1 UART 4 +- 1 AD&IO Port +- 2 Debug Ports (1 IO Debug and 1 FMU Debug) +- 1 SPI6 Bus +- 4 Power Inputs (Power 1, Power 2, Power C1 and Power C2) +- 16 PWM Servo Outputs (A1-A8 from FMU and M1-M8 from IO) +- Micro SD Socket (supports SD 4.1 & SDIO 4.0 in two databus modes: 1 bit (default) and 4 bits) + +### Size and Dimensions + +- 92.2 (L) x 51.2 (W) x 28.3 (H) mm +- 77.6g (carrier board with IMU) + +## 구매처 + +- [Accton-IoT Godwit](https://www.accton-iot.com/godwit/) +- [sales@accton-iot.com](sales@accton-iot.com) + +## 핀배열 + +![G-A1 Pin definition](../../assets/flight_controller/accton-godwit/ga1/pin_definition.png "G-A1 Pin definition") + +## UART Mapping + +| Serial# | Protocol | 포트 | 참고 | +| ------- | --------- | ------ | ---------- | +| SERIAL1 | Telem1 | UART7 | /dev/ttyS6 | +| SERIAL2 | Telem2 | UART5 | /dev/ttyS4 | +| SERIAL3 | GPS1 | USART1 | /dev/ttyS0 | +| SERIAL4 | GPS2 | UART8 | /dev/ttyS7 | +| SERIAL5 | Telem3 | USART2 | /dev/ttyS1 | +| SERIAL6 | UART4 | UART4 | /dev/ttyS3 | +| SERIAL7 | FMU Debug | USART3 | | +| SERIAL8 | OTG2 | USB | | + +## Wiring Diagram + +![G-A1 Wiring](../../assets/flight_controller/accton-godwit/ga1/wiring.png "G-A1 Wiring") + +## PWM Output + +PWM M1-M8 (IO Main PWM), A1-A8(FMU PWM). +All these 16 support normal PWM output formats. +FMU PWM A1-A6 can support DShot and B-Directional DShot. +A1-A8(FMU PWM) are grouped as: + +- Group 1: A1, A2, A3, A4 +- Group 2: A5, A6 +- Group 3: A7, A8 + +The motor and servo system should be connected to these ports according to the order outlined in the fuselage reference for your carrier. + +![G-A1 PWM Motor Servo](../../assets/flight_controller/accton-godwit/ga1/motor_servo.png "G-A1 PWM Motor Servo") + +## RC Input + +For DSM/SBUS receivers, connect them to the DSM/SBUS interface which provides dedicated 3.3V and 5V power pins respectively, and check above "Pinout" for detailed pin definition. +PPM receivers should be connected to the PPM interface. And other RC systems can be connected via other spare telemetry ports. + +![G-A1 Radio](../../assets/flight_controller/accton-godwit/ga1/radio.png "G-A1 Radio") + +## GPS/나침반 + +The Godwit G-A1 has a built-in compass +Due to potential interference, the autopilot is usually used with an external I2C compass as part of a GPS/Compass combination. + +![G-A1 GPS](../../assets/flight_controller/accton-godwit/ga1/gps.png "G-A1 GPS") + +## Power Connection and Battery Monitor + +This universal controller features a CAN PMU module that supports 3 to 14s lithium batteries. +To ensure proper connection, attach the module's 6-pin connector to the flight control Power C1 and/or Power C2 interface. + +This universal controller does not provide power to the servos. +To power them, an external BEC must be connected to the positive and negative terminals of any A1–A8 or M1–M8 port. + +![G-A1 Power](../../assets/flight_controller/accton-godwit/ga1/power.png "G-A1 Power") + +## SD 카드 + +The SD card is NOT included in the package, you need to prepare the SD card and insert it into the slot. + +![G-A1 SD Card](../../assets/flight_controller/accton-godwit/ga1/sdcard.png "G-A1 SD Card") + +## 펌웨어 + +The autopilot is compatible with PX4 firmware. And G-A1 can be detected by QGroundControl automatically. Users can also build it with target "accton-godwit_ga1" + +To [build PX4](../dev_setup/building_px4.md) for this target, open up the terminal and enter: + +```sh +make accton-godwit_ga1 +``` + +## More Information and Support + +- [Accton-IoT Godwit](https://www.accton-iot.com/godwit/) +- [sales@accton-iot.com](sales@accton-iot.com) +- [support@accton-iot.com](mailto:support@accton-iot.com) diff --git a/docs/ko/flight_controller/autopilot_manufacturer_supported.md b/docs/ko/flight_controller/autopilot_manufacturer_supported.md index 45c768b388..02ab0e7724 100644 --- a/docs/ko/flight_controller/autopilot_manufacturer_supported.md +++ b/docs/ko/flight_controller/autopilot_manufacturer_supported.md @@ -12,6 +12,7 @@ This category includes boards that are not fully compliant with the pixhawk stan 이 카테고리의 보드는 다음과 같습니다. +- [Accton Godwit GA1](../flight_controller/accton-godwit_ga1.md) - [AirMind MindPX](../flight_controller/mindpx.md) - [AirMind MindRacer](../flight_controller/mindracer.md) - [ARK Electronics ARKV6X](../flight_controller/ark_v6x.md) (and [ARK Electronics Pixhawk Autopilot Bus Carrier](../flight_controller/ark_pab.md)) diff --git a/docs/ko/modules/modules_driver_ins.md b/docs/ko/modules/modules_driver_ins.md index 6b5c8f46ef..93b8af3e7a 100644 --- a/docs/ko/modules/modules_driver_ins.md +++ b/docs/ko/modules/modules_driver_ins.md @@ -45,6 +45,41 @@ MicroStrain [arguments...] status Driver status ``` +## eulernav_bahrs + +Source: [drivers/ins/eulernav_bahrs](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/eulernav_bahrs) + +### 설명 + +Serial bus driver for the EULER-NAV Baro-Inertial AHRS. + +### 예 + +Attempt to start driver on a specified serial device. + +``` +eulernav_bahrs start -d /dev/ttyS1 +``` + +Stop driver + +``` +eulernav_bahrs stop +``` + +### Usage {#eulernav_bahrs_usage} + +``` +eulernav_bahrs [arguments...] + Commands: + start Start driver + -d Serial device + + status Print driver status + + stop Stop driver +``` + ## ilabs Source: [drivers/ins/ilabs](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/ilabs) diff --git a/docs/ko/msg_docs/ActionRequest.md b/docs/ko/msg_docs/ActionRequest.md index 3579870754..1c724dabb7 100644 --- a/docs/ko/msg_docs/ActionRequest.md +++ b/docs/ko/msg_docs/ActionRequest.md @@ -15,25 +15,25 @@ Request are published by `manual_control` and subscribed by the `commander` and # It allows mapping triggers from various external interfaces like RC channels or MAVLink to cause an action. # Request are published by `manual_control` and subscribed by the `commander` and `vtol_att_control` modules. -uint64 timestamp # [us] Time since system start +uint64 timestamp # [us] Time since system start -uint8 action # [@enum ACTION] Requested action -uint8 ACTION_DISARM = 0 # Disarm vehicle -uint8 ACTION_ARM = 1 # Arm vehicle -uint8 ACTION_TOGGLE_ARMING = 2 # Toggle arming -uint8 ACTION_UNKILL = 3 # Revert a kill action -uint8 ACTION_KILL = 4 # Kill vehicle (instantly stop the motors) -uint8 ACTION_SWITCH_MODE = 5 # Switch mode. The target mode is set in the `mode` field. -uint8 ACTION_VTOL_TRANSITION_TO_MULTICOPTER = 6 # Transition to hover flight -uint8 ACTION_VTOL_TRANSITION_TO_FIXEDWING = 7 # Transition to fast forward flight -uint8 ACTION_TERMINATION = 8 # Irreversably output failsafe values on all outputs, trigger parachute +uint8 action # [@enum ACTION] Requested action +uint8 ACTION_DISARM = 0 # Disarm vehicle +uint8 ACTION_ARM = 1 # Arm vehicle +uint8 ACTION_TOGGLE_ARMING = 2 # Toggle arming +uint8 ACTION_UNKILL = 3 # Revert a kill action +uint8 ACTION_KILL = 4 # Kill vehicle (instantly stop the motors) +uint8 ACTION_SWITCH_MODE = 5 # Switch mode. The target mode is set in the `mode` field. +uint8 ACTION_VTOL_TRANSITION_TO_MULTICOPTER = 6 # Transition to hover flight +uint8 ACTION_VTOL_TRANSITION_TO_FIXEDWING = 7 # Transition to fast forward flight +uint8 ACTION_TERMINATION = 8 # Irreversibly output failsafe values on all outputs, trigger parachute -uint8 source # [@enum SOURCE] Request trigger type, such as a switch, button or gesture -uint8 SOURCE_STICK_GESTURE = 0 # Triggered by holding the sticks in a certain position -uint8 SOURCE_RC_SWITCH = 1 # Triggered by an RC switch moving into a certain position -uint8 SOURCE_RC_BUTTON = 2 # Triggered by a momentary button on the RC being pressed or held -uint8 SOURCE_RC_MODE_SLOT = 3 # Mode change through the RC mode selection mechanism +uint8 source # [@enum SOURCE] Request trigger type, such as a switch, button or gesture +uint8 SOURCE_STICK_GESTURE = 0 # Triggered by holding the sticks in a certain position +uint8 SOURCE_RC_SWITCH = 1 # Triggered by an RC switch moving into a certain position +uint8 SOURCE_RC_BUTTON = 2 # Triggered by a momentary button on the RC being pressed or held +uint8 SOURCE_RC_MODE_SLOT = 3 # Mode change through the RC mode selection mechanism -uint8 mode # Requested mode. Only applies when `action` is `ACTION_SWITCH_MODE`. Values for this field are defined by the `vehicle_status_s::NAVIGATION_STATE_*` enumeration. +uint8 mode # Requested mode. Only applies when `action` is `ACTION_SWITCH_MODE`. Values for this field are defined by the `vehicle_status_s::NAVIGATION_STATE_*` enumeration. ``` diff --git a/docs/ko/msg_docs/ActuatorMotors.md b/docs/ko/msg_docs/ActuatorMotors.md index 06fbd1b908..ca739f6c22 100644 --- a/docs/ko/msg_docs/ActuatorMotors.md +++ b/docs/ko/msg_docs/ActuatorMotors.md @@ -15,14 +15,14 @@ Published by the vehicle's allocation and consumed by the ESC protocol drivers e uint32 MESSAGE_VERSION = 0 -uint64 timestamp # [us] Time since system start -uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on -uint16 reversible_flags # Bitset indicating which motors are configured to be reversible +uint16 reversible_flags # Bitset indicating which motors are configured to be reversible -uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 +uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 # -uint8 NUM_CONTROLS = 12 -float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) +uint8 NUM_CONTROLS = 12 # +float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) ``` diff --git a/docs/ko/msg_docs/ActuatorServos.md b/docs/ko/msg_docs/ActuatorServos.md index ffe01e2f49..6f0a677dbf 100644 --- a/docs/ko/msg_docs/ActuatorServos.md +++ b/docs/ko/msg_docs/ActuatorServos.md @@ -15,10 +15,10 @@ Published by the vehicle's allocation and consumed by the actuator output driver uint32 MESSAGE_VERSION = 0 -uint64 timestamp # [us] Time since system start -uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on -uint8 NUM_CONTROLS = 8 -float32[8] control # [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. +uint8 NUM_CONTROLS = 8 # +float32[8] control # [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. ``` diff --git a/docs/ko/msg_docs/Airspeed.md b/docs/ko/msg_docs/Airspeed.md index 7309747f66..949af8d5e7 100644 --- a/docs/ko/msg_docs/Airspeed.md +++ b/docs/ko/msg_docs/Airspeed.md @@ -13,10 +13,10 @@ It is subscribed by the airspeed selector module, which validates the data from # This is published by airspeed sensor drivers, CAN airspeed sensors, simulators. # It is subscribed by the airspeed selector module, which validates the data from multiple sensors and passes on a single estimation to the EKF, controllers and telemetry providers. -uint64 timestamp # [us] Time since system start -uint64 timestamp_sample # [us] Timestamp of the raw data -float32 indicated_airspeed_m_s # [m/s] Indicated airspeed -float32 true_airspeed_m_s # [m/s] True airspeed -float32 confidence # [@range 0,1] Confidence value for this sensor +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Timestamp of the raw data +float32 indicated_airspeed_m_s # [m/s] Indicated airspeed +float32 true_airspeed_m_s # [m/s] True airspeed +float32 confidence # [@range 0,1] Confidence value for this sensor ``` diff --git a/docs/ko/msg_docs/ArmingCheckReply.md b/docs/ko/msg_docs/ArmingCheckReply.md index d5e3322506..8d619f5aaf 100644 --- a/docs/ko/msg_docs/ArmingCheckReply.md +++ b/docs/ko/msg_docs/ArmingCheckReply.md @@ -21,39 +21,39 @@ The message is not used by internal/FMU components, as their mode requirements a # Note that the external component is identified by its registration_id, which is allocated to the component during registration (arming_check_id in RegisterExtComponentReply). # The message is not used by internal/FMU components, as their mode requirements are known at compile time. -uint32 MESSAGE_VERSION = 1 +uint32 MESSAGE_VERSION = 1 uint64 timestamp # [us] Time since system start. -uint8 request_id # Id of ArmingCheckRequest for which this is a response. -uint8 registration_id # Id of external component emitting this response. +uint8 request_id # Id of ArmingCheckRequest for which this is a response. +uint8 registration_id # Id of external component emitting this response. -uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies. +uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies. -uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX] -bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json). +uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX] +bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json). +bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json). +bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json). -bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed. +bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed. -uint8 num_events # Number of queued failure messages (Event) in the events field. +uint8 num_events # Number of queued failure messages (Event) in the events field. -Event[5] events # Arming failure reasons (Queue of events to report to GCS). +Event[5] events # Arming failure reasons (Queue of events to report to GCS). # Mode requirements -bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope). -bool mode_req_attitude # Requires an attitude estimate. -bool mode_req_local_alt # Requires a local altitude estimate. -bool mode_req_local_position # Requires a local position estimate. -bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate. -bool mode_req_global_position # Requires a global position estimate. -bool mode_req_global_position_relaxed # Requires a relaxed global position estimate. -bool mode_req_mission # Requires an uploaded mission. -bool mode_req_home_position # Requires a home position (such as RTL/Return mode). -bool mode_req_prevent_arming # Prevent arming (such as in Land mode). -bool mode_req_manual_control # Requires a manual controller +bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope). +bool mode_req_attitude # Requires an attitude estimate. +bool mode_req_local_alt # Requires a local altitude estimate. +bool mode_req_local_position # Requires a local position estimate. +bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate. +bool mode_req_global_position # Requires a global position estimate. +bool mode_req_global_position_relaxed # Requires a relaxed global position estimate. +bool mode_req_mission # Requires an uploaded mission. +bool mode_req_home_position # Requires a home position (such as RTL/Return mode). +bool mode_req_prevent_arming # Prevent arming (such as in Land mode). +bool mode_req_manual_control # Requires a manual controller -uint8 ORB_QUEUE_LENGTH = 4 # +uint8 ORB_QUEUE_LENGTH = 4 ``` diff --git a/docs/ko/msg_docs/ArmingCheckRequest.md b/docs/ko/msg_docs/ArmingCheckRequest.md index cfa4b52c23..653d58d2d2 100644 --- a/docs/ko/msg_docs/ArmingCheckRequest.md +++ b/docs/ko/msg_docs/ArmingCheckRequest.md @@ -21,10 +21,12 @@ The reply will also include the registration_id for each external component, pro # The reply will include the published request_id, allowing correlation of all arming check information for a particular request. # The reply will also include the registration_id for each external component, provided to it during the registration process (RegisterExtComponentReply). -uint32 MESSAGE_VERSION = 0 +uint32 MESSAGE_VERSION = 1 -uint64 timestamp # [us] Time since system start. +uint64 timestamp # [us] Time since system start. -uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. +uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. + +uint32 valid_registrations_mask # Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) ``` diff --git a/docs/ko/msg_docs/ArmingCheckRequestV0.md b/docs/ko/msg_docs/ArmingCheckRequestV0.md new file mode 100644 index 0000000000..f5680c11f2 --- /dev/null +++ b/docs/ko/msg_docs/ArmingCheckRequestV0.md @@ -0,0 +1,30 @@ +# ArmingCheckRequestV0 (UORB message) + +Arming check request. + +Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. +All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. +The request is sent regularly, even while armed, so that the FMU always knows the current arming state for external modes, and can forward it to ground stations. + +The reply will include the published request_id, allowing correlation of all arming check information for a particular request. +The reply will also include the registration_id for each external component, provided to it during the registration process (RegisterExtComponentReply). + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/ArmingCheckRequestV0.msg) + +```c +# Arming check request. +# +# Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. +# All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. +# The request is sent regularly, even while armed, so that the FMU always knows the current arming state for external modes, and can forward it to ground stations. +# +# The reply will include the published request_id, allowing correlation of all arming check information for a particular request. +# The reply will also include the registration_id for each external component, provided to it during the registration process (RegisterExtComponentReply). + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # [us] Time since system start. + +uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. + +``` diff --git a/docs/ko/msg_docs/CellularStatus.md b/docs/ko/msg_docs/CellularStatus.md index 6579d3fe85..04ca0a65dc 100644 --- a/docs/ko/msg_docs/CellularStatus.md +++ b/docs/ko/msg_docs/CellularStatus.md @@ -11,39 +11,39 @@ This is currently used only for logging cell status from MAVLink. # # This is currently used only for logging cell status from MAVLink. -uint64 timestamp # [us] Time since system start +uint64 timestamp # [us] Time since system start -uint16 status # [@enum STATUS_FLAG] Status bitmap -uint16 STATUS_FLAG_UNKNOWN = 1 # State unknown or not reportable -uint16 STATUS_FLAG_FAILED = 2 # Modem is unusable -uint16 STATUS_FLAG_INITIALIZING = 4 # Modem is being initialized -uint16 STATUS_FLAG_LOCKED = 8 # Modem is locked -uint16 STATUS_FLAG_DISABLED = 16 # Modem is not enabled and is powered down -uint16 STATUS_FLAG_DISABLING = 32 # Modem is currently transitioning to the STATUS_FLAG_DISABLED state -uint16 STATUS_FLAG_ENABLING = 64 # Modem is currently transitioning to the STATUS_FLAG_ENABLED state -uint16 STATUS_FLAG_ENABLED = 128 # Modem is enabled and powered on but not registered with a network provider and not available for data connections -uint16 STATUS_FLAG_SEARCHING = 256 # Modem is searching for a network provider to register -uint16 STATUS_FLAG_REGISTERED = 512 # Modem is registered with a network provider, and data connections and messaging may be available for use -uint16 STATUS_FLAG_DISCONNECTING = 1024 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated -uint16 STATUS_FLAG_CONNECTING = 2048 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered -uint16 STATUS_FLAG_CONNECTED = 4096 # One or more packet data bearers is active and connected +uint16 status # [@enum STATUS_FLAG] Status bitmap +uint16 STATUS_FLAG_UNKNOWN = 1 # State unknown or not reportable +uint16 STATUS_FLAG_FAILED = 2 # Modem is unusable +uint16 STATUS_FLAG_INITIALIZING = 4 # Modem is being initialized +uint16 STATUS_FLAG_LOCKED = 8 # Modem is locked +uint16 STATUS_FLAG_DISABLED = 16 # Modem is not enabled and is powered down +uint16 STATUS_FLAG_DISABLING = 32 # Modem is currently transitioning to the STATUS_FLAG_DISABLED state +uint16 STATUS_FLAG_ENABLING = 64 # Modem is currently transitioning to the STATUS_FLAG_ENABLED state +uint16 STATUS_FLAG_ENABLED = 128 # Modem is enabled and powered on but not registered with a network provider and not available for data connections +uint16 STATUS_FLAG_SEARCHING = 256 # Modem is searching for a network provider to register +uint16 STATUS_FLAG_REGISTERED = 512 # Modem is registered with a network provider, and data connections and messaging may be available for use +uint16 STATUS_FLAG_DISCONNECTING = 1024 # Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated +uint16 STATUS_FLAG_CONNECTING = 2048 # Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered +uint16 STATUS_FLAG_CONNECTED = 4096 # One or more packet data bearers is active and connected -uint8 failure_reason # [@enum FAILURE_REASON] Failure reason -uint8 FAILURE_REASON_NONE = 0 # No error -uint8 FAILURE_REASON_UNKNOWN = 1 # Error state is unknown -uint8 FAILURE_REASON_SIM_MISSING = 2 # SIM is required for the modem but missing -uint8 FAILURE_REASON_SIM_ERROR = 3 # SIM is available, but not usable for connection +uint8 failure_reason # [@enum FAILURE_REASON] Failure reason +uint8 FAILURE_REASON_NONE = 0 # No error +uint8 FAILURE_REASON_UNKNOWN = 1 # Error state is unknown +uint8 FAILURE_REASON_SIM_MISSING = 2 # SIM is required for the modem but missing +uint8 FAILURE_REASON_SIM_ERROR = 3 # SIM is available, but not usable for connection -uint8 type # [@enum CELLULAR_NETWORK_RADIO_TYPE] Cellular network radio type -uint8 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0 # None -uint8 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1 # GSM -uint8 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2 # CDMA -uint8 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3 # WCDMA -uint8 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4 # LTE +uint8 type # [@enum CELLULAR_NETWORK_RADIO_TYPE] Cellular network radio type +uint8 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0 # None +uint8 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1 # GSM +uint8 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2 # CDMA +uint8 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3 # WCDMA +uint8 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4 # LTE -uint8 quality # [dBm] Cellular network RSSI/RSRP, absolute value -uint16 mcc # [@invalid UINT16_MAX] Mobile country code -uint16 mnc # [@invalid UINT16_MAX] Mobile network code -uint16 lac # [@invalid 0] Location area code +uint8 quality # [dBm] Cellular network RSSI/RSRP, absolute value +uint16 mcc # [@invalid UINT16_MAX] Mobile country code +uint16 mnc # [@invalid UINT16_MAX] Mobile network code +uint16 lac # [@invalid 0] Location area code ``` diff --git a/docs/ko/msg_docs/RoverSpeedSetpoint.md b/docs/ko/msg_docs/RoverSpeedSetpoint.md new file mode 100644 index 0000000000..9eea46e60f --- /dev/null +++ b/docs/ko/msg_docs/RoverSpeedSetpoint.md @@ -0,0 +1,14 @@ +# RoverSpeedSetpoint (UORB message) + +Rover Speed Setpoint + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverSpeedSetpoint.msg) + +```c +# Rover Speed Setpoint + +uint64 timestamp # [us] Time since system start +float32 speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction +float32 speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction + +``` diff --git a/docs/ko/msg_docs/RoverSpeedStatus.md b/docs/ko/msg_docs/RoverSpeedStatus.md new file mode 100644 index 0000000000..8c212e2b0f --- /dev/null +++ b/docs/ko/msg_docs/RoverSpeedStatus.md @@ -0,0 +1,18 @@ +# RoverSpeedStatus (UORB message) + +Rover Velocity Status + +[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverSpeedStatus.msg) + +```c +# Rover Velocity Status + +uint64 timestamp # [us] Time since system start +float32 measured_speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Measured speed in body x direction +float32 adjusted_speed_body_x_setpoint # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction that is being tracked (Applied slew rates) +float32 pid_throttle_body_x_integral # [] [@range -1, 1] Integral of the PID for the closed loop controller of the speed in body x direction +float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction +float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates) +float32 pid_throttle_body_y_integral # [] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction + +``` diff --git a/docs/ko/msg_docs/VehicleAirData.md b/docs/ko/msg_docs/VehicleAirData.md index 75363b8571..dccfefc095 100644 --- a/docs/ko/msg_docs/VehicleAirData.md +++ b/docs/ko/msg_docs/VehicleAirData.md @@ -1,22 +1,26 @@ # VehicleAirData (UORB message) +Vehicle air data + +Data from the currently selected barometer (plus ambient temperature from the source specified in temperature_source). +Includes calculated data such as barometric altitude and air density. + [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleAirData.msg) ```c +# Vehicle air data +# +# Data from the currently selected barometer (plus ambient temperature from the source specified in temperature_source). +# Includes calculated data such as barometric altitude and air density. -uint64 timestamp # time since system start (microseconds) - -uint64 timestamp_sample # the timestamp of the raw data (microseconds) - -uint32 baro_device_id # unique device ID for the selected barometer - -float32 baro_alt_meter # Altitude above MSL calculated from temperature compensated baro sensor data using an ISA corrected for sea level pressure SENS_BARO_QNH. -float32 baro_pressure_pa # Absolute pressure in Pascals -float32 ambient_temperature # Abient temperature in degrees Celsius -uint8 temperature_source # Source of temperature data: 0: Default Temperature (15°C), 1: External Baro, 2: Airspeed - -float32 rho # air density - -uint8 calibration_count # Calibration changed counter. Monotonically increases whenever calibration changes. +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Timestamp of the raw data +uint32 baro_device_id # Unique device ID for the selected barometer +float32 baro_alt_meter # [m] [@frame MSL] Altitude above MSL calculated from temperature compensated baro sensor data using an ISA corrected for sea level pressure SENS_BARO_QNH +float32 baro_pressure_pa # [Pa] Absolute pressure +float32 ambient_temperature # [degC] Ambient temperature +uint8 temperature_source # Source of temperature data: 0: Default Temperature (15°C), 1: External Baro, 2: Airspeed +float32 rho # [kg/m^3] Air density +uint8 calibration_count # Calibration changed counter. Monotonically increases whenever calibration changes. ``` diff --git a/docs/ko/msg_docs/index.md b/docs/ko/msg_docs/index.md index cb1c447eb4..3699e70936 100644 --- a/docs/ko/msg_docs/index.md +++ b/docs/ko/msg_docs/index.md @@ -229,10 +229,10 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [RoverPositionSetpoint](RoverPositionSetpoint.md) — Rover Position Setpoint - [RoverRateSetpoint](RoverRateSetpoint.md) — Rover Rate setpoint - [RoverRateStatus](RoverRateStatus.md) — Rover Rate Status +- [RoverSpeedSetpoint](RoverSpeedSetpoint.md) — Rover Speed Setpoint +- [RoverSpeedStatus](RoverSpeedStatus.md) — Rover Velocity Status - [RoverSteeringSetpoint](RoverSteeringSetpoint.md) — Rover Steering setpoint - [RoverThrottleSetpoint](RoverThrottleSetpoint.md) — Rover Throttle setpoint -- [RoverVelocitySetpoint](RoverVelocitySetpoint.md) — Rover Velocity Setpoint -- [RoverVelocityStatus](RoverVelocityStatus.md) — Rover Velocity Status - [Rpm](Rpm.md) - [RtlStatus](RtlStatus.md) - [RtlTimeEstimate](RtlTimeEstimate.md) @@ -281,7 +281,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [UlogStreamAck](UlogStreamAck.md) — Ack a previously sent ulog_stream message that had the NEED_ACK flag set - [VehicleAcceleration](VehicleAcceleration.md) -- [VehicleAirData](VehicleAirData.md) +- [VehicleAirData](VehicleAirData.md) — Vehicle air data - [VehicleAngularAccelerationSetpoint](VehicleAngularAccelerationSetpoint.md) - [VehicleConstraints](VehicleConstraints.md) — Local setpoint constraints in NED frame setting something to NaN means that no limit is provided @@ -301,6 +301,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [YawEstimatorStatus](YawEstimatorStatus.md) - [AirspeedValidatedV0](AirspeedValidatedV0.md) - [ArmingCheckReplyV0](ArmingCheckReplyV0.md) +- [ArmingCheckRequestV0](ArmingCheckRequestV0.md) — Arming check request. - [BatteryStatusV0](BatteryStatusV0.md) — Battery status - [EventV0](EventV0.md) — this message is required here in the msg_old folder because other msg are depending on it Events interface diff --git a/docs/ko/releases/main.md b/docs/ko/releases/main.md index ba15118e44..e94a31e199 100644 --- a/docs/ko/releases/main.md +++ b/docs/ko/releases/main.md @@ -52,7 +52,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### 센서 -- TBD +- Add [sbgECom INS driver](../sensor/sbgecom.md) ([PX4-Autopilot#24137](https://github.com/PX4/PX4-Autopilot/pull/24137)) ### 시뮬레이션 diff --git a/docs/ko/sensor/accelerometer.md b/docs/ko/sensor/accelerometer.md index da249b1934..6de3d5bd21 100644 --- a/docs/ko/sensor/accelerometer.md +++ b/docs/ko/sensor/accelerometer.md @@ -5,7 +5,7 @@ PX4 uses accelerometer data for velocity estimation. You should not need to attach an accelometer as a stand-alone external device: - Most flight controllers, such as those in the [Pixhawk Series](../flight_controller/pixhawk_series.md), include an accelerometer as part of the flight controller's [Inertial Motion Unit (IMU)](https://en.wikipedia.org/wiki/Inertial_measurement_unit). -- Gyroscopes are present as part of an [external INS, ARHS or INS-enhanced GNSS system](../sensor/inertial_navigation_systems.md). +- Gyroscopes are present as part of an [external INS, AHRS or INS-enhanced GNSS system](../sensor/inertial_navigation_systems.md). The accelerometer must be calibrated before first use of the vehicle: diff --git a/docs/ko/sensor/inertial_navigation_systems.md b/docs/ko/sensor/inertial_navigation_systems.md index 9c329a2b24..ca354d569e 100644 --- a/docs/ko/sensor/inertial_navigation_systems.md +++ b/docs/ko/sensor/inertial_navigation_systems.md @@ -9,6 +9,7 @@ However PX4 can also use some INS devices as either sources of raw data, or as a INS systems that can be used as a replacement for EKF2 in PX4: - [InertialLabs](../sensor/inertiallabs.md) +- [SBG Systems](../sensor/sbgecom.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data. - [VectorNav](../sensor/vectornav.md): IMU/AHRS, GNSS/INS, Dual GNSS/INS systems that can be used as an external INS or as a source of raw sensor data. ## PX4 Firmware diff --git a/docs/ko/sensor/sbgecom.md b/docs/ko/sensor/sbgecom.md new file mode 100644 index 0000000000..6d9a292d53 --- /dev/null +++ b/docs/ko/sensor/sbgecom.md @@ -0,0 +1,159 @@ +# SBG Systems INS/AHRS (Pulse, Ellipse, etc.) + +[SBG-Systems](https://www.sbg-systems.com/) designs, manufactures, and support an extensive range of state-of-the-art inertial sensors such as Inertial Measurement Units (IMU), Attitude and Heading Reference Systems (AHRS), Inertial Navigation Systems with embedded GNSS (INS/GNSS), and so on. + +PX4 supports [all SBG Systems products](https://www.sbg-systems.com/products/) and can use these as an [external INS](../sensor/inertial_navigation_systems.md) (bypassing/replacing the EKF2 estimator), or as a source of raw sensor data provided to the navigation estimator. + +![Ellipse](../../assets/hardware/sensors/inertial/ellipse-inertial-navigation-system.png) + +## 개요 + +SBG Systems products provide a range of benefits to PX4 users and can be integrated for: + +- Higher accuracy heading, pitch, and roll estimates +- More robust and reliable GNSS positioning +- Improved positioning and attitude performance in GNSS-contested environments +- Performance under challenging dynamic conditions (e.g. catapult launches, VTOL operations, high-g or high angular rate operations) + +The sbgECom PX4 driver is streamlined to provide a simple plug-and-play architecture, removing engineering obstacles and allowing the acceleration of the design, development, and launch of platforms to keep pace with the rapid rate of innovation. + +The driver supports [all SBG Systems products](https://www.sbg-systems.com/products/). +In particular the following systems are recommended: + +- **Pulse:** Recommended for fixed-wing systems without hovering, where static heading is not necessary. +- **Ellipse:** Recommended for multicopter systems where hovering and low dynamics requires the use of static heading. + +## 구매처 + +SBG Systems solutions are available directly from [MySBG](https://my.sbg-systems.com) (FR) or through their Global Sales Representatives. For more information on their solutions or for international orders, please contact contact@sbg-systems.com. + +## 하드웨어 설정 + +### 배선 + +Connect any unused flight controller serial interface, such as a spare `GPS` or `TELEM` port, to the SBG Systems product MAIN port (required by PX4). + +### 장착 + +The SBG Systems product sensor can be mounted in any orientation, in any position on the vehicle, without regard to center of gravity. +All SBG Systems product sensors default to a coordinate system of x-forward, y-right, and z-down, making the default mounting as connector-back, base down. +This can be changed to any rigid rotation using the sbgECom Reference Frame Rotation register. + +If using a GNSS-enabled product, the GNSS antenna must be mounted rigidly with respect to the inertial sensor and with an unobstructed sky view. If using a dual-GNSS-enabled product (Ellipse-D), the secondary antenna must be mounted rigidly with respect to the primary antenna and the inertial sensor with an unobstructed sky view. + +For more mounting and configuration requirements and recommendations, see the relevant [SBG SUPPORT CENTER](https://support.sbg-systems.com/sc). + +## 펌웨어 설정 + +### PX4 설정 + +To use the sbgECom driver: + +1. Include the module in firmware in the [kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) by setting the kconfig variables: `CONFIG_DRIVERS_INS_SBGECOM` or `CONFIG_COMMON_INS`. + +2. [Set the parameter](../advanced_config/parameters.md) [SENS_SBG_CFG](../advanced_config/parameter_reference.md#SENS_SBG_CFG) to the hardware port connected to the SBG Systems product (for more information see [Serial Port Configuration](../peripherals/serial_configuration.md)). + + ::: warning + Disable or change port of other sensors that are using the same one, for example [GPS_1_CONFIG](../advanced_config/parameter_reference.md#GPS_1_CONFIG) if using GPS1 port. + +::: + +3. Set [SBG_BAUDRATE](../advanced_config/parameter_reference.md#SBG_BAUDRATE) to the desired default baudrate value. + +4. Allow the sbgECom driver to initialize by restarting PX4. + +5. Configure driver to provide IMU data, GNSS data and INS : + + 1. Set [SBG_MODE](../advanced_config/parameter_reference.md#SBG_MODE) to the desired mode. + 2. Make sensor module select sensors by enabling [SENS_IMU_MODE](../advanced_config/parameter_reference.md#SENS_IMU_MODE). + 3. Prioritize SBG Systems sensors using [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO), [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO), [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO), [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO), where _n_ is the instance number of the IMU component (0, 1, etc.). + + ::: tip + In most cases the external IMU (SBG) is the highest-numbered. + You can get a list of the IMU components available using [`uorb top -1`](../middleware/uorb.md#uorb-top-command), you can differentiate between them using the [`listener`](../modules/modules_command.md#listener) command and looking through the data, or just the rates. + + Alternatively, you can check [CAL_GYROn_ID](../advanced_config/parameter_reference.md#CAL_GYRO0_ID) to see the device id. + The priority is 0-255, where 0 is entirely disabled and 255 is highest priority. + +::: + + ::: warning + When configuring both SBG Systems and Pixhawk sensors to have non-zero priority, if the selected sensor is errored (timeout), it can change during operation without being notified. + In this case, MAVLink messages will be updated with the newly selected sensor. + + If you don't want to have this fallback mechanism, you must disable unwanted sensors. + +::: + + 4. If using the sbgECom as an INS, disable EKF2 using [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN). + +6. Restart PX4. + +Once enabled, the module will be detected on boot. +IMU data should be published at 200Hz. + +## SBG Systems Configuration + +All High Performance and Ellipse 3.0 and higher SBG Systems INS can be configured directly from PX4 firmware: + +1. Enable [SBG_CONFIGURATION_EN](../advanced_config/parameter_reference.md#SBG_CONFIGURATION_EN) + +2. Provide a JSON file `sbg_settings.json` containing SBG Systems INS settings to be applied in your PX4 board `extras` directory (ex: `boards/px4/fmu-v5/extras`). The settings JSON file will be installed in `/etc/extras/sbg_settings.json` on the board. + + ::: tip + The settings can be retrieved using [sbgEComAPI](https://github.com/SBG-Systems/sbgECom/tree/main/tools/sbgEComApi) or [sbgInsRestApi](https://developer.sbg-systems.com/sbgInsRestApi/1.3/#tag/Settings) and then modified as a JSON file. + +::: + + ::: tip + The settings file can be provided in the SD card in q`/fs/microsd/etc/extras/sbg_settings.json` to avoid rebuilding a new firmware to change JSON settings file. + +::: + +3. For testing purpose, it's also possible to modify SBG Systems INS settings on the fly: + + - By passing a JSON file path as argument when starting sbgecom driver (ex: `sbgecom start -f /fs/microsd/new_sbg_settings.json`) + - By passing a JSON string as argument when starting sbgecom driver: (ex: `sbgecom start -s {"output":{"comA":{"messages":{"airData":"onChange"}}}}`) + +For older Ellipse SBG Systems INS or to configure any SBG Systems INS directly, all commands and registers can be found in the [SBG SUPPORT CENTER](https://support.sbg-systems.com/sc). + +:::warning +If the baudrate of the serial port on the INS product (used to communicate with PX4) is changed, the parameter [SBG_BAUDRATE](../advanced_config/parameter_reference.md#SBG_BAUDRATE) must be changed to match. +::: + +## Published Data + +Upon initialization, the driver should print the following information to console (printed using `PX4_INFO`) + +- Unit model number +- Unit hardware version +- Unit serial number +- Unit firmware number + +This should be accessible using the [`dmesg`](../modules/modules_system.md#dmesg) command. + +The sbgECom driver always publishes the unit's data to the following uORB topics: + +- [sensor_accel](../msg_docs/SensorAccel.md) +- [sensor_gyro](../msg_docs/SensorGyro.md) +- [sensor_mag](../msg_docs/SensorMag.md) + +if configured as a GNSS, publishes: + +- [sensor_gps](../msg_docs/SensorGps.md) + +and, if configured as an INS, publishes: + +- [estimator_status](../msg_docs/EstimatorStatus.md) +- [vehicle_local_position](../msg_docs/VehicleLocalPosition.md) +- [vehicle_global_positon](../msg_docs/VehicleGlobalPosition.md) +- [vehicle_attitude](../msg_docs/VehicleAttitude.md) + +:::tip +Published topics can be viewed using the `listener` command. +::: + +## Hardware Specifications + +- [Product Briefs](https://www.sbg-systems.com/products/) +- [Datasheets](https://www.sbg-systems.com/contact/#products) From 41d3403ec776778dfff0c8d8a278f4c8fca98ede Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 15 Sep 2025 19:18:45 -0400 Subject: [PATCH 035/812] drivers/gps: prioritize non-blocking reads over injection (#25535) --- src/drivers/gps/gps.cpp | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index eae1732f0a..af6508f8cf 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -469,10 +469,16 @@ int GPS::pollOrRead(uint8_t *buf, size_t buf_length, int timeout) const int max_timeout = 50; int timeout_adjusted = math::min(max_timeout, timeout); - handleInjectDataTopic(); - if (_interface == GPSHelper::Interface::UART) { - ret = _uart.readAtLeast(buf, buf_length, math::min(character_count, buf_length), timeout_adjusted); + + const ssize_t read_at_least = math::min(character_count, buf_length); + + // handle injection data before read if caught up + if (_uart.bytesAvailable() < read_at_least) { + handleInjectDataTopic(); + } + + ret = _uart.readAtLeast(buf, buf_length, read_at_least, timeout_adjusted); if (ret > 0) { _num_bytes_read += ret; @@ -483,6 +489,8 @@ int GPS::pollOrRead(uint8_t *buf, size_t buf_length, int timeout) } else if ((_interface == GPSHelper::Interface::SPI) && (_spi_fd >= 0)) { + handleInjectDataTopic(); + //Poll only for the SPI data. In the same thread we also need to handle orb messages, //so ideally we would poll on both, the SPI fd and orb subscription. Unfortunately the //two pollings use different underlying mechanisms (at least under posix), which makes this From d3f912ad2571bad4dd843e9f55a3e7a1fb9fd44a Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 15 Sep 2025 19:22:49 -0400 Subject: [PATCH 036/812] platforms: Serial new dedicated writeBlocking method (#25537) * platforms: Serial new dedicated writeBlocking method * finish writeBlocking() * add back fsync * updated posix, added string constant for port not open error * format * fix build * remove fsync * actually remove fsync * remove fsync from write * review feedback --------- Co-authored-by: Jacob Dahl Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> --- platforms/common/Serial.cpp | 5 ++ .../include/px4_platform_common/Serial.hpp | 1 + platforms/nuttx/src/px4/common/SerialImpl.cpp | 61 +++++++++++++++++- .../src/px4/common/include/SerialImpl.hpp | 1 + platforms/posix/include/SerialImpl.hpp | 1 + platforms/posix/src/px4/common/SerialImpl.cpp | 62 ++++++++++++++++++- platforms/qurt/include/SerialImpl.hpp | 1 + platforms/qurt/src/px4/SerialImpl.cpp | 17 +++++ 8 files changed, 144 insertions(+), 5 deletions(-) diff --git a/platforms/common/Serial.cpp b/platforms/common/Serial.cpp index 88a29667c8..748dcba9b2 100644 --- a/platforms/common/Serial.cpp +++ b/platforms/common/Serial.cpp @@ -89,6 +89,11 @@ ssize_t Serial::write(const void *buffer, size_t buffer_size) return _impl.write(buffer, buffer_size); } +ssize_t Serial::writeBlocking(const void *buffer, size_t buffer_size, uint32_t timeout_ms) +{ + return _impl.writeBlocking(buffer, buffer_size, timeout_ms); +} + void Serial::flush() { return _impl.flush(); diff --git a/platforms/common/include/px4_platform_common/Serial.hpp b/platforms/common/include/px4_platform_common/Serial.hpp index cad568d134..983834ccf6 100644 --- a/platforms/common/include/px4_platform_common/Serial.hpp +++ b/platforms/common/include/px4_platform_common/Serial.hpp @@ -66,6 +66,7 @@ public: ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_ms = 0); ssize_t write(const void *buffer, size_t buffer_size); + ssize_t writeBlocking(const void *buffer, size_t buffer_size, uint32_t timeout_ms = 0); void flush(); diff --git a/platforms/nuttx/src/px4/common/SerialImpl.cpp b/platforms/nuttx/src/px4/common/SerialImpl.cpp index f3a9f2389b..9bb84dd902 100644 --- a/platforms/nuttx/src/px4/common/SerialImpl.cpp +++ b/platforms/nuttx/src/px4/common/SerialImpl.cpp @@ -362,11 +362,68 @@ ssize_t SerialImpl::write(const void *buffer, size_t buffer_size) } } - ::fsync(_serial_fd); - return written; } +ssize_t SerialImpl::writeBlocking(const void *buffer, size_t buffer_size, uint32_t timeout_ms) +{ + if (!_open) { + PX4_ERR("Cannot writeBlocking to serial device until it has been opened"); + return -1; + } + + const uint8_t *data = static_cast(buffer); + size_t total_written = 0; + const hrt_abstime start_time_us = hrt_absolute_time(); + const hrt_abstime timeout_us = timeout_ms * 1000; + + while (total_written < buffer_size) { + if (hrt_elapsed_time(&start_time_us) > timeout_us) { + PX4_WARN("Write timeout, sent %zu", total_written); + break; + } + + pollfd fds[1]; + fds[0].fd = _serial_fd; + fds[0].events = POLLOUT; + + hrt_abstime elapsed_us = hrt_elapsed_time(&start_time_us); + int remaining_timeout_ms = (timeout_us - elapsed_us) / 1000; + + if (remaining_timeout_ms <= 0) { + break; + } + + int result = ::poll(fds, 1, remaining_timeout_ms); + + if (result < 0) { + PX4_ERR("poll error %d", errno); + return -1; + } + + if (fds[0].revents & POLLOUT) { + // Write as much as we can + ssize_t written = ::write(_serial_fd, data + total_written, buffer_size - total_written); + + if (written < 0) { + if (errno == EAGAIN) { + // Buffer full, wait a bit and try again + px4_usleep(1000); + continue; + } + + PX4_ERR("Write error: %d", errno); + return -1; + + } else if (written > 0) { + total_written += written; + } + } + } + + return total_written; +} + void SerialImpl::flush() { if (_open) { diff --git a/platforms/nuttx/src/px4/common/include/SerialImpl.hpp b/platforms/nuttx/src/px4/common/include/SerialImpl.hpp index c7fb1ede81..82e4ddd29d 100644 --- a/platforms/nuttx/src/px4/common/include/SerialImpl.hpp +++ b/platforms/nuttx/src/px4/common/include/SerialImpl.hpp @@ -64,6 +64,7 @@ public: ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0); ssize_t write(const void *buffer, size_t buffer_size); + ssize_t writeBlocking(const void *buffer, size_t buffer_size, uint32_t timeout_us = 0); void flush(); diff --git a/platforms/posix/include/SerialImpl.hpp b/platforms/posix/include/SerialImpl.hpp index c7fb1ede81..82e4ddd29d 100644 --- a/platforms/posix/include/SerialImpl.hpp +++ b/platforms/posix/include/SerialImpl.hpp @@ -64,6 +64,7 @@ public: ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0); ssize_t write(const void *buffer, size_t buffer_size); + ssize_t writeBlocking(const void *buffer, size_t buffer_size, uint32_t timeout_us = 0); void flush(); diff --git a/platforms/posix/src/px4/common/SerialImpl.cpp b/platforms/posix/src/px4/common/SerialImpl.cpp index 9ad8d62567..0c23b050e0 100644 --- a/platforms/posix/src/px4/common/SerialImpl.cpp +++ b/platforms/posix/src/px4/common/SerialImpl.cpp @@ -274,7 +274,6 @@ ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size) if (ret < 0) { PX4_DEBUG("%s read error %d", _port, ret); - } return ret; @@ -344,11 +343,68 @@ ssize_t SerialImpl::write(const void *buffer, size_t buffer_size) } } - ::fsync(_serial_fd); - return written; } +ssize_t SerialImpl::writeBlocking(const void *buffer, size_t buffer_size, uint32_t timeout_ms) +{ + if (!_open) { + PX4_ERR("Cannot writeBlocking to serial device until it has been opened"); + return -1; + } + + const uint8_t *data = static_cast(buffer); + size_t total_written = 0; + const hrt_abstime start_time_us = hrt_absolute_time(); + const hrt_abstime timeout_us = timeout_ms * 1000; + + while (total_written < buffer_size) { + if (hrt_elapsed_time(&start_time_us) > timeout_us) { + PX4_WARN("Write timeout, sent %zu", total_written); + break; + } + + pollfd fds[1]; + fds[0].fd = _serial_fd; + fds[0].events = POLLOUT; + + hrt_abstime elapsed_us = hrt_elapsed_time(&start_time_us); + int remaining_timeout_ms = (timeout_us - elapsed_us) / 1000; + + if (remaining_timeout_ms <= 0) { + break; + } + + int result = ::poll(fds, 1, remaining_timeout_ms); + + if (result < 0) { + PX4_ERR("poll error %d", errno); + return -1; + } + + if (fds[0].revents & POLLOUT) { + // Write as much as we can + ssize_t written = ::write(_serial_fd, data + total_written, buffer_size - total_written); + + if (written < 0) { + if (errno == EAGAIN) { + // Buffer full, wait a bit and try again + px4_usleep(1000); + continue; + } + + PX4_ERR("Write error: %d", errno); + return -1; + + } else if (written > 0) { + total_written += written; + } + } + } + + return total_written; +} + void SerialImpl::flush() { if (_open) { diff --git a/platforms/qurt/include/SerialImpl.hpp b/platforms/qurt/include/SerialImpl.hpp index 469bd6db97..c7739429ef 100644 --- a/platforms/qurt/include/SerialImpl.hpp +++ b/platforms/qurt/include/SerialImpl.hpp @@ -63,6 +63,7 @@ public: ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0); ssize_t write(const void *buffer, size_t buffer_size); + ssize_t writeBlocking(const void *buffer, size_t buffer_size, uint32_t timeout_us = 0); void flush(); diff --git a/platforms/qurt/src/px4/SerialImpl.cpp b/platforms/qurt/src/px4/SerialImpl.cpp index c2c88e43b9..a019244cee 100644 --- a/platforms/qurt/src/px4/SerialImpl.cpp +++ b/platforms/qurt/src/px4/SerialImpl.cpp @@ -276,6 +276,23 @@ ssize_t SerialImpl::write(const void *buffer, size_t buffer_size) return ret_write; } +ssize_t SerialImpl::writeBlocking(const void *buffer, size_t buffer_size, uint32_t timeout_ms) +{ + if (!_open) { + PX4_ERR("Cannot write to serial device until it has been opened"); + return -1; + } + + int ret_write = qurt_uart_write(_serial_fd, (const char *) buffer, buffer_size); + + if (ret_write < 0) { + PX4_ERR("%s write error %d", _port, ret_write); + + } + + return ret_write; +} + void SerialImpl::flush() { if (_open) { From d205d11c3d15b3c8c92b2770966dcf8d77498ab6 Mon Sep 17 00:00:00 2001 From: Rowan Dempster Date: Mon, 15 Sep 2025 20:18:26 -0400 Subject: [PATCH 037/812] Recovering UTC timestamps from ULog without sensor_gps (#25534) * Added overloaded get_log_time util for fractional seconds * Added write_info implementation for double info types * Save boot time to .ulg via info message key boot_time_utc * Changed time type from double to uint64_t, formatted * Fixing get_log_time function doc --- src/modules/logger/logger.cpp | 11 +++++++++++ src/modules/logger/logger.h | 1 + src/modules/logger/util.cpp | 25 ++++++++++++++++--------- src/modules/logger/util.h | 10 ++++++++++ 4 files changed, 38 insertions(+), 9 deletions(-) diff --git a/src/modules/logger/logger.cpp b/src/modules/logger/logger.cpp index 99ec75898c..00ffc2fbd2 100644 --- a/src/modules/logger/logger.cpp +++ b/src/modules/logger/logger.cpp @@ -1990,6 +1990,11 @@ void Logger::write_info(LogType type, const char *name, uint32_t value) write_info_template(type, name, value, "uint32_t"); } +void Logger::write_info(LogType type, const char *name, uint64_t value) +{ + write_info_template(type, name, value, "uint64_t"); +} + template void Logger::write_info_template(LogType type, const char *name, T value, const char *type_str) @@ -2122,6 +2127,12 @@ void Logger::write_version(LogType type) write_info(type, "time_ref_utc", _param_sdlog_utc_offset.get() * 60); + uint64_t boot_time_utc_us; + + if (util::get_log_time(boot_time_utc_us, _param_sdlog_utc_offset.get() * 60, true)) { + write_info(type, "boot_time_utc_us", boot_time_utc_us); + } + if (_replay_file_name) { write_info(type, "replay", _replay_file_name); } diff --git a/src/modules/logger/logger.h b/src/modules/logger/logger.h index 44499c71b5..a24debd79e 100644 --- a/src/modules/logger/logger.h +++ b/src/modules/logger/logger.h @@ -267,6 +267,7 @@ private: void write_info_multiple(LogType type, const char *name, int fd); void write_info(LogType type, const char *name, int32_t value); void write_info(LogType type, const char *name, uint32_t value); + void write_info(LogType type, const char *name, uint64_t value); /** generic common template method for write_info variants */ template diff --git a/src/modules/logger/util.cpp b/src/modules/logger/util.cpp index efff34af6a..5fdd576bcf 100644 --- a/src/modules/logger/util.cpp +++ b/src/modules/logger/util.cpp @@ -72,20 +72,19 @@ bool file_exist(const char *filename) return stat(filename, &buffer) == 0; } -bool get_log_time(struct tm *tt, int utc_offset_sec, bool boot_time) +bool get_log_time(uint64_t &utc_time_usec, int utc_offset_sec, bool boot_time) { uORB::Subscription vehicle_gps_position_sub{ORB_ID(vehicle_gps_position)}; - time_t utc_time_sec; bool use_clock_time = true; /* Get the latest GPS publication */ sensor_gps_s gps_pos; if (vehicle_gps_position_sub.copy(&gps_pos)) { - utc_time_sec = gps_pos.time_utc_usec / 1e6; + utc_time_usec = gps_pos.time_utc_usec; - if (gps_pos.fix_type >= 2 && utc_time_sec >= GPS_EPOCH_SECS) { + if (gps_pos.fix_type >= 2 && utc_time_usec >= (uint64_t) GPS_EPOCH_SECS * 1000000ULL) { use_clock_time = false; } } @@ -94,22 +93,30 @@ bool get_log_time(struct tm *tt, int utc_offset_sec, bool boot_time) /* take clock time if there's no fix (yet) */ struct timespec ts = {}; px4_clock_gettime(CLOCK_REALTIME, &ts); - utc_time_sec = ts.tv_sec + (ts.tv_nsec / 1e9); + utc_time_usec = ts.tv_sec * 1000000ULL + ts.tv_nsec / 1000ULL; - if (utc_time_sec < GPS_EPOCH_SECS) { + if (utc_time_usec < (uint64_t) GPS_EPOCH_SECS * 1000000ULL) { return false; } } /* strip the time elapsed since boot */ if (boot_time) { - utc_time_sec -= hrt_absolute_time() / 1e6; + utc_time_usec -= hrt_absolute_time(); } /* apply utc offset */ - utc_time_sec += utc_offset_sec; + utc_time_usec += (int64_t) utc_offset_sec * 1000000LL; - return gmtime_r(&utc_time_sec, tt) != nullptr; + return true; +} + +bool get_log_time(struct tm *tt, int utc_offset_sec, bool boot_time) +{ + uint64_t utc_time_usec; + bool result = get_log_time(utc_time_usec, utc_offset_sec, boot_time); + time_t utc_time_sec = static_cast(utc_time_usec / 1000000ULL); + return result && gmtime_r(&utc_time_sec, tt) != nullptr; } int check_free_space(const char *log_root_dir, int32_t max_log_dirs_to_keep, orb_advert_t &mavlink_log_pub, diff --git a/src/modules/logger/util.h b/src/modules/logger/util.h index 535815c7fb..f2939b0794 100644 --- a/src/modules/logger/util.h +++ b/src/modules/logger/util.h @@ -75,6 +75,16 @@ bool file_exist(const char *filename); int check_free_space(const char *log_root_dir, int32_t max_log_dirs_to_keep, orb_advert_t &mavlink_log_pub, int &sess_dir_index); + +/** + * Utility for fetching UTC time in microseconds from sensor_gps or CLOCK_REALTIME + * @param utc_time_usec returned microseconds + * @param utc_offset_sec UTC time offset [s] + * @param boot_time use time when booted instead of current time + * @return true on success, false otherwise (eg. if no gps) + */ +bool get_log_time(uint64_t &utc_time_usec, int utc_offset_sec, bool boot_time); + /** * Get the time for log file name * @param tt returned time From 0c8f5ebc32bd561162c2a5e99009d3c3c2c60a22 Mon Sep 17 00:00:00 2001 From: Pernilla Date: Tue, 16 Sep 2025 10:38:47 +0200 Subject: [PATCH 038/812] Navigator: delay neutral gimbal command (#25551) * Set gimbal neutral after delay --- src/modules/navigator/land.cpp | 6 +----- src/modules/navigator/mission_base.cpp | 11 +++++------ src/modules/navigator/navigator.h | 10 ++++++++++ src/modules/navigator/navigator_main.cpp | 23 +++++++++++++++++++++++ src/modules/navigator/rtl.cpp | 5 +---- 5 files changed, 40 insertions(+), 15 deletions(-) diff --git a/src/modules/navigator/land.cpp b/src/modules/navigator/land.cpp index 55116c78e3..b51999ac55 100644 --- a/src/modules/navigator/land.cpp +++ b/src/modules/navigator/land.cpp @@ -72,11 +72,7 @@ Land::on_activation() // reset cruising speed to default _navigator->reset_cruising_speed(); - // set gimbal to neutral position (level with horizon) to reduce change of damage on landing - _navigator->acquire_gimbal_control(); - _navigator->set_gimbal_neutral(); - _navigator->release_gimbal_control(); - + _navigator->activate_set_gimbal_neutral_timer(hrt_absolute_time()); } void diff --git a/src/modules/navigator/mission_base.cpp b/src/modules/navigator/mission_base.cpp index 052968ed7e..d95e0cea15 100644 --- a/src/modules/navigator/mission_base.cpp +++ b/src/modules/navigator/mission_base.cpp @@ -180,8 +180,10 @@ MissionBase::on_inactivation() _navigator->disable_camera_trigger(); _navigator->stop_capturing_images(); - _navigator->set_gimbal_neutral(); // point forward - _navigator->release_gimbal_control(); + + if (!_navigator->get_land_detected()->landed) { + _navigator->activate_set_gimbal_neutral_timer(hrt_absolute_time()); + } if (_navigator->get_precland()->is_activated()) { _navigator->get_precland()->on_inactivation(); @@ -698,10 +700,7 @@ void MissionBase::handleLanding(WorkItemType &new_work_item_type, mission_item_s // if the vehicle drifted off the path during back-transition it should just go straight to the landing point _navigator->reset_position_setpoint(pos_sp_triplet->previous); - // set gimbal to neutral position (level with horizon) to reduce change of damage on landing - _navigator->acquire_gimbal_control(); - _navigator->set_gimbal_neutral(); - _navigator->release_gimbal_control(); + _navigator->activate_set_gimbal_neutral_timer(hrt_absolute_time()); } else { diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h index cdabb9d36e..d70c7bd69b 100644 --- a/src/modules/navigator/navigator.h +++ b/src/modules/navigator/navigator.h @@ -282,6 +282,13 @@ public: void release_gimbal_control(); void set_gimbal_neutral(); + /* Set gimbal to neutral position (level with horizon) to reduce risk of damage on landing. + The commands are executed after time delay. */ + void neutralize_gimbal_if_control_activated(); + /* Accepts a new timestamp only if the current timestamp is UINT64_MAX, preventing the + timer from resetting during an ongoing neutral command. */ + void activate_set_gimbal_neutral_timer(const hrt_abstime timestamp); + void preproject_stop_point(double &lat, double &lon); void stop_capturing_images(); @@ -391,6 +398,9 @@ private: bool _is_capturing_images{false}; // keep track if we need to stop capturing images + // timer to trigger a delayed set gimbal neutral command + hrt_abstime _gimbal_neutral_activation_time{UINT64_MAX}; + // update subscriptions void params_update(); diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index c3c2fb3656..7ee9bcaabe 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -904,6 +904,8 @@ void Navigator::run() publish_mission_result(); } + neutralize_gimbal_if_control_activated(); + publish_navigator_status(); publish_distance_sensor_mode_request(); @@ -1629,6 +1631,27 @@ void Navigator::set_gimbal_neutral() publish_vehicle_command(vehicle_command); } +void Navigator::activate_set_gimbal_neutral_timer(const hrt_abstime timestamp) +{ + if (_gimbal_neutral_activation_time == UINT64_MAX) { + _gimbal_neutral_activation_time = timestamp; + } +} + +void Navigator::neutralize_gimbal_if_control_activated() +{ + const hrt_abstime now{hrt_absolute_time()}; + + // The time delay must be sufficiently long to allow flight tasks to complete its + // destruction and release gimbal control before the navigator takes control of the gimbal. + if (_gimbal_neutral_activation_time != UINT64_MAX && now > _gimbal_neutral_activation_time + 250_ms) { + acquire_gimbal_control(); + set_gimbal_neutral(); + release_gimbal_control(); + _gimbal_neutral_activation_time = UINT64_MAX; + } +} + void Navigator::sendWarningDescentStoppedDueToTerrain() { mavlink_log_critical(&_mavlink_log_pub, "Terrain collision risk, descent is stopped\t"); diff --git a/src/modules/navigator/rtl.cpp b/src/modules/navigator/rtl.cpp index b2898be415..8d551e87bd 100644 --- a/src/modules/navigator/rtl.cpp +++ b/src/modules/navigator/rtl.cpp @@ -237,10 +237,7 @@ void RTL::on_activation() break; } - // set gimbal to neutral position (level with horizon) to reduce change of damage on landing - _navigator->acquire_gimbal_control(); - _navigator->set_gimbal_neutral(); - _navigator->release_gimbal_control(); + _navigator->activate_set_gimbal_neutral_timer(hrt_absolute_time()); } void RTL::on_active() From e72ffa3b1f6dd7ddc13db105076c1171cf528c4b Mon Sep 17 00:00:00 2001 From: Eric Katzfey <53063038+katzfey@users.noreply.github.com> Date: Tue, 16 Sep 2025 11:40:19 -0700 Subject: [PATCH 039/812] QURT: Changed the non-blocking UART write to use the blocking write with a comment that Qurt (#25573) still needs a non-blocking write implemented. --- platforms/qurt/src/px4/SerialImpl.cpp | 16 ++-------------- 1 file changed, 2 insertions(+), 14 deletions(-) diff --git a/platforms/qurt/src/px4/SerialImpl.cpp b/platforms/qurt/src/px4/SerialImpl.cpp index a019244cee..312c830041 100644 --- a/platforms/qurt/src/px4/SerialImpl.cpp +++ b/platforms/qurt/src/px4/SerialImpl.cpp @@ -260,20 +260,8 @@ ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t char ssize_t SerialImpl::write(const void *buffer, size_t buffer_size) { - if (!_open) { - PX4_ERR("Cannot write to serial device until it has been opened"); - return -1; - } - - int ret_write = qurt_uart_write(_serial_fd, (const char *) buffer, buffer_size); - - if (ret_write < 0) { - if (errno != EAGAIN) { - PX4_ERR("%s write error %d", _port, ret_write); - } - } - - return ret_write; + // TODO: Implement a non-blocking write in Qurt + return writeBlocking(buffer, buffer_size, 0); } ssize_t SerialImpl::writeBlocking(const void *buffer, size_t buffer_size, uint32_t timeout_ms) From 2cc64c438f94ae8424d18d5fa4c8120de212cd15 Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Tue, 16 Sep 2025 15:53:00 -0800 Subject: [PATCH 040/812] docs: UAVCAN_ESC_IFACE (#25560) * dronecan: esc: change UAVCAN_ESC_IFACE to 2 to default to only outputting on CAN2 * revert param default and update docs * Subedit --------- Co-authored-by: Hamish Willee --- docs/en/dronecan/escs.md | 15 +++++++++++++++ docs/en/dronecan/index.md | 8 +++++++- 2 files changed, 22 insertions(+), 1 deletion(-) diff --git a/docs/en/dronecan/escs.md b/docs/en/dronecan/escs.md index 9742e3739e..d65b854877 100644 --- a/docs/en/dronecan/escs.md +++ b/docs/en/dronecan/escs.md @@ -9,3 +9,18 @@ For more information, see the following articles for specific hardware/firmware: - [Vertiq](../peripherals/vertiq.md) (larger modules) - [VESC Project](../peripherals/vesc.md) - [RaccoonLab Cyphal and DroneCAN PWM nodes](raccoonlab_nodes.md) + +## Hardware Configuration + +General DroneCAN hardware configuration is covered in [DroneCAN > Hardware Setup](../dronecan/index.md#hardware-setup). + +DroneCAN ESCs should be on their own dedicated CAN interface(s) because ESC messages can saturate the bus and starve other nodes of bandwidth. + +## PX4 Configuration + +DroneCAN peripherals are configured by following the procedure outlined in [DroneCAN](../dronecan/index.md). + +In addition to the general setup, such as setting `UAVCAN_ENABLE` to `3`: + +- Select the specific CAN interface(s) used for ESC data output using the [UAVCAN_ESC_IFACE](../advanced_config/parameter_reference.md#UAVCAN_ESC_IFACE) parameter (all that all interfaces are selected by default). +- Configure the [motor order and servo outputs](../config/actuators.md). diff --git a/docs/en/dronecan/index.md b/docs/en/dronecan/index.md index 75a211b927..c76f18ce8f 100644 --- a/docs/en/dronecan/index.md +++ b/docs/en/dronecan/index.md @@ -270,6 +270,9 @@ PX4 DroneCAN parameters: [DroneCAN ESCs and servos](../dronecan/escs.md) require the [motor order and servo outputs](../config/actuators.md) to be configured. +Select the specific CAN interface(s) used for ESC data output using the [UAVCAN_ESC_IFACE](../advanced_config/parameter_reference.md#UAVCAN_ESC_IFACE) parameter (all that all interfaces are selected by default). +Note that DroneCAN ESCs should be on their own dedicated CAN interface(s) because ESC messages can saturate the bus and starve other nodes of bandwidth. + ## QGC CANNODE Parameter Configuration QGroundControl can inspect and modify parameters belonging to CAN devices attached to the flight controller, provided the device are connected to the flight controller before QGC is started. @@ -307,7 +310,10 @@ If successful, the firmware binary will be removed from the root directory and t **Q**: The motors aren't spinning when armed. -**A**: Make sure `UAVCAN_ENABLE` is set to `3` to enable DroneCAN ESC output. +**A**: + +- Make sure `UAVCAN_ENABLE` is set to `3` to enable DroneCAN ESC output. +- Make sure `UAVCAN_ESC_IFACE` is set to enable the CAN interface(s) used for ESCs. --- From 78d602e68aee29a31bc8e5af244e1eac20bb114f Mon Sep 17 00:00:00 2001 From: Alex Espinoza Date: Tue, 16 Sep 2025 18:57:32 -0700 Subject: [PATCH 041/812] switched instructions for cloning Micro-XRCE-DDS from v2.4.2 to v2.4.3 (#25525) * switched instructions for clodning Micro-XRCE-DDS from v2.4.2 to v2.4.3 since v2.4.2 references a bad fast-dds tag that doesnt build * reverted uxrce instructions changes from docs/ko docs/uk and docs/zh sin ce they are generated automatically and should not be changed manually --- docs/en/middleware/uxrce_dds.md | 4 ++-- docs/en/ros2/user_guide.md | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/docs/en/middleware/uxrce_dds.md b/docs/en/middleware/uxrce_dds.md index dcd9e3dbda..5ab96699cf 100644 --- a/docs/en/middleware/uxrce_dds.md +++ b/docs/en/middleware/uxrce_dds.md @@ -65,7 +65,7 @@ PX4 Micro XRCE-DDS Client is based on version `v2.x` which is not compatible wit On Ubuntu you can build from source and install the Agent standalone using the following commands: ```sh -git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git +git clone -b v2.4.3 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git cd Micro-XRCE-DDS-Agent mkdir build cd build @@ -126,7 +126,7 @@ To build the agent within ROS: ```sh cd ~/px4_ros_uxrce_dds_ws/src - git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git + git clone -b v2.4.3 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git ``` 1. Source the ROS 2 development environment, and compile the workspace using `colcon`: diff --git a/docs/en/ros2/user_guide.md b/docs/en/ros2/user_guide.md index 4fb40695f5..332c9b00dd 100644 --- a/docs/en/ros2/user_guide.md +++ b/docs/en/ros2/user_guide.md @@ -152,7 +152,7 @@ To setup and start the agent: 1. Enter the following commands to fetch and build the agent from source: ```sh - git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git + git clone -b v2.4.3 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git cd Micro-XRCE-DDS-Agent mkdir build cd build From 0303d36e6094f9a31cbd19f8b9688a7207b72902 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 18 Sep 2025 15:59:54 +1000 Subject: [PATCH 042/812] RoverAttitudeSetpoint et al - whitespace (#25545) * RoverAttitudeSetpoint - whitespace * Format RoverAttitudeStatus.msg for consistency * Format RoverPositionSetpoint.msg for consistency * Format msg/RoverRateSetpoint.msg for consistency * Format msg/RoverRateStatus.msg for consistency * Format msg/RoverSpeedSetpoint.msg for consistency * Reformat RoverSpeedStatus.msg for consistency * Fix formatting of pid_yaw_rate_integral field * Fix formatting in RoverSteeringSetpoint.msg * Fix formatting in RoverThrottleSetpoint.msg * Apply suggestions from code review --- msg/RoverAttitudeSetpoint.msg | 4 ++-- msg/RoverAttitudeStatus.msg | 6 +++--- msg/RoverPositionSetpoint.msg | 12 ++++++------ msg/RoverRateSetpoint.msg | 4 ++-- msg/RoverRateStatus.msg | 8 ++++---- msg/RoverSpeedSetpoint.msg | 6 +++--- msg/RoverSpeedStatus.msg | 14 +++++++------- msg/RoverSteeringSetpoint.msg | 4 ++-- msg/RoverThrottleSetpoint.msg | 6 +++--- 9 files changed, 32 insertions(+), 32 deletions(-) diff --git a/msg/RoverAttitudeSetpoint.msg b/msg/RoverAttitudeSetpoint.msg index 05b5d15086..2b8315016c 100644 --- a/msg/RoverAttitudeSetpoint.msg +++ b/msg/RoverAttitudeSetpoint.msg @@ -1,4 +1,4 @@ # Rover Attitude Setpoint -uint64 timestamp # [us] Time since system start -float32 yaw_setpoint # [rad] [@range -inf, inf] [@frame NED] Yaw setpoint +uint64 timestamp # [us] Time since system start +float32 yaw_setpoint # [rad] [@range -inf, inf] [@frame NED] Yaw setpoint diff --git a/msg/RoverAttitudeStatus.msg b/msg/RoverAttitudeStatus.msg index 6b8afc192a..9d4bd2a949 100644 --- a/msg/RoverAttitudeStatus.msg +++ b/msg/RoverAttitudeStatus.msg @@ -1,5 +1,5 @@ # Rover Attitude Status -uint64 timestamp # [us] Time since system start -float32 measured_yaw # [rad] [@range -pi, pi] [@frame NED]Measured yaw -float32 adjusted_yaw_setpoint # [rad] [@range -pi, pi] [@frame NED] Yaw setpoint that is being tracked (Applied slew rates) +uint64 timestamp # [us] Time since system start +float32 measured_yaw # [rad] [@range -pi, pi] [@frame NED]Measured yaw +float32 adjusted_yaw_setpoint # [rad] [@range -pi, pi] [@frame NED] Yaw setpoint that is being tracked (Applied slew rates) diff --git a/msg/RoverPositionSetpoint.msg b/msg/RoverPositionSetpoint.msg index bc711d2d29..e55dcd4737 100644 --- a/msg/RoverPositionSetpoint.msg +++ b/msg/RoverPositionSetpoint.msg @@ -1,8 +1,8 @@ # Rover Position Setpoint -uint64 timestamp # [us] Time since system start -float32[2] position_ned # [m] [@range -inf, inf] [@frame NED] Target position -float32[2] start_ned # [m] [@range -inf, inf] [@frame NED] [@invalid NaN Defaults to vehicle position] Start position which specifies a line for the rover to track -float32 cruising_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to maximum speed] Cruising speed -float32 arrival_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to 0] Speed the rover should arrive at the target with -float32 yaw # [rad] [@range -pi,pi] [@frame NED] [@invalid NaN Defaults to vehicle yaw] Mecanum only: Specify vehicle yaw during travel +uint64 timestamp # [us] Time since system start +float32[2] position_ned # [m] [@range -inf, inf] [@frame NED] Target position +float32[2] start_ned # [m] [@range -inf, inf] [@frame NED] [@invalid NaN Defaults to vehicle position] Start position which specifies a line for the rover to track +float32 cruising_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to maximum speed] Cruising speed +float32 arrival_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to 0] Speed the rover should arrive at the target with +float32 yaw # [rad] [@range -pi,pi] [@frame NED] [@invalid NaN Defaults to vehicle yaw] Mecanum only: Specify vehicle yaw during travel diff --git a/msg/RoverRateSetpoint.msg b/msg/RoverRateSetpoint.msg index 1a3c3b89f1..06752f285d 100644 --- a/msg/RoverRateSetpoint.msg +++ b/msg/RoverRateSetpoint.msg @@ -1,4 +1,4 @@ # Rover Rate setpoint -uint64 timestamp # [us] Time since system start -float32 yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint +uint64 timestamp # [us] Time since system start +float32 yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint diff --git a/msg/RoverRateStatus.msg b/msg/RoverRateStatus.msg index fd6c0b7f3c..cde9200ea7 100644 --- a/msg/RoverRateStatus.msg +++ b/msg/RoverRateStatus.msg @@ -1,6 +1,6 @@ # Rover Rate Status -uint64 timestamp # [us] Time since system start -float32 measured_yaw_rate # [rad/s] [@range -inf, inf] [@frame NED] Measured yaw rate -float32 adjusted_yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint that is being tracked (Applied slew rates) -float32 pid_yaw_rate_integral # [] [@range -1, 1] Integral of the PID for the closed loop yaw rate controller +uint64 timestamp # [us] Time since system start +float32 measured_yaw_rate # [rad/s] [@range -inf, inf] [@frame NED] Measured yaw rate +float32 adjusted_yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint that is being tracked (Applied slew rates) +float32 pid_yaw_rate_integral # [-] [@range -1, 1] Integral of the PID for the closed loop yaw rate controller diff --git a/msg/RoverSpeedSetpoint.msg b/msg/RoverSpeedSetpoint.msg index ac7787f6c9..9933c1157d 100644 --- a/msg/RoverSpeedSetpoint.msg +++ b/msg/RoverSpeedSetpoint.msg @@ -1,5 +1,5 @@ # Rover Speed Setpoint -uint64 timestamp # [us] Time since system start -float32 speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction -float32 speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction +uint64 timestamp # [us] Time since system start +float32 speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction +float32 speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction diff --git a/msg/RoverSpeedStatus.msg b/msg/RoverSpeedStatus.msg index 71cacd0e77..a005bb64c8 100644 --- a/msg/RoverSpeedStatus.msg +++ b/msg/RoverSpeedStatus.msg @@ -1,9 +1,9 @@ # Rover Velocity Status -uint64 timestamp # [us] Time since system start -float32 measured_speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Measured speed in body x direction -float32 adjusted_speed_body_x_setpoint # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction that is being tracked (Applied slew rates) -float32 pid_throttle_body_x_integral # [] [@range -1, 1] Integral of the PID for the closed loop controller of the speed in body x direction -float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction -float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates) -float32 pid_throttle_body_y_integral # [] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction +uint64 timestamp # [us] Time since system start +float32 measured_speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Measured speed in body x direction +float32 adjusted_speed_body_x_setpoint # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction that is being tracked (Applied slew rates) +float32 pid_throttle_body_x_integral # [-] [@range -1, 1] Integral of the PID for the closed loop controller of the speed in body x direction +float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction +float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates) +float32 pid_throttle_body_y_integral # [-] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction diff --git a/msg/RoverSteeringSetpoint.msg b/msg/RoverSteeringSetpoint.msg index f2daa967f9..eb6c2787f6 100644 --- a/msg/RoverSteeringSetpoint.msg +++ b/msg/RoverSteeringSetpoint.msg @@ -1,4 +1,4 @@ # Rover Steering setpoint -uint64 timestamp # [us] Time since system start -float32 normalized_steering_setpoint # [@range -1 (Left), 1 (Right)] [@frame Body] Ackermann: Normalized steering angle, Differential/Mecanum: Normalized speed difference between the left and right wheels +uint64 timestamp # [us] Time since system start +float32 normalized_steering_setpoint # [-] [@range -1 (Left), 1 (Right)] [@frame Body] Ackermann: Normalized steering angle, Differential/Mecanum: Normalized speed difference between the left and right wheels diff --git a/msg/RoverThrottleSetpoint.msg b/msg/RoverThrottleSetpoint.msg index 333ebee5c3..104e228d15 100644 --- a/msg/RoverThrottleSetpoint.msg +++ b/msg/RoverThrottleSetpoint.msg @@ -1,5 +1,5 @@ # Rover Throttle setpoint -uint64 timestamp # [us] Time since system start -float32 throttle_body_x # [] [@range -1 (Backwards), 1 (Forwards)] [@frame Body] Throttle setpoint along body X axis -float32 throttle_body_y # [] [@range -1 (Left), 1 (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Throttle setpoint along body Y axis +uint64 timestamp # [us] Time since system start +float32 throttle_body_x # [-] [@range -1 (Backwards), 1 (Forwards)] [@frame Body] Throttle setpoint along body X axis +float32 throttle_body_y # [-] [@range -1 (Left), 1 (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Throttle setpoint along body Y axis From dd65380bf334e92579ef39bf5a8f77d103f91d6d Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 18 Sep 2025 16:58:56 +1000 Subject: [PATCH 043/812] Ark GNSS CAN - link to the DroneCAN docs for fixed base (#25382) * Ark GNSS CAN - link to the DroneCAN docs for fixed base * Update docs/en/dronecan/ark_rtk_gps.md --- docs/en/dronecan/ark_rtk_gps.md | 24 ++++++++++++++++++++++-- 1 file changed, 22 insertions(+), 2 deletions(-) diff --git a/docs/en/dronecan/ark_rtk_gps.md b/docs/en/dronecan/ark_rtk_gps.md index b3f5637474..ec7840c132 100644 --- a/docs/en/dronecan/ark_rtk_gps.md +++ b/docs/en/dronecan/ark_rtk_gps.md @@ -27,7 +27,7 @@ Order this module from: - Safety Button - Buzzer - Two Pixhawk Standard CAN Connectors (4 Pin JST GH) -- F9P “UART 2” Connector +- F9P `UART 2` Connector - 3 Pin JST GH - TX, RX, GND - Pixhawk Standard Debug Connector (6 Pin JST SH) @@ -87,6 +87,25 @@ You need to set necessary [DroneCAN](index.md) parameters and define offsets if - The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK RTK GPS from the vehicles centre of gravity. - Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` on the GPS if this it that last node on the CAN bus. +### Setting Up Rover and Fixed Base + +Position of the rover is established using RTCM messages from the RTK base module (the base module is connected to QGC, which sends the RTCM information to PX4 via MAVLink). + +PX4 DroneCAN parameters: + +- [UAVCAN_PUB_RTCM](../advanced_config/parameter_reference.md#UAVCAN_PUB_RTCM): + - Makes PX4 publish RTCM messages ([RTCMStream](https://dronecan.github.io/Specification/7._List_of_standard_data_types/#rtcmstream)) to the bus (which it gets from the RTK base module via QGC). + +Rover module parameters (also [set using QGC](../dronecan/index.md#qgc-cannode-parameter-configuration)): + +- [CANNODE_SUB_RTCM](../advanced_config/parameter_reference.md#CANNODE_SUB_RTCM) tells the rover that it should subscribe to [RTCMStream](https://dronecan.github.io/Specification/7._List_of_standard_data_types/#rtcmstream) RTCM messages on the bus (from the moving base). + +::: info +Use [UAVCAN_PUB_MBD](../advanced_config/parameter_reference.md#UAVCAN_PUB_MBD) and [CANNODE_SUB_MBD](../advanced_config/parameter_reference.md#CANNODE_SUB_MBD) instead if you want to implement moving base (see below) at the same time. +::: + +For more information see [Rover and Fixed Base](../dronecan/index.md#rover-and-fixed-base) in the DroneCAN guide. + ### Setting Up Moving Baseline & GPS Heading The simplest way to set up moving baseline and GPS heading with two ARK RTK GPS modules is via CAN, though it can be done via UART to reduce traffic on the CAN bus if desired. @@ -127,10 +146,11 @@ Setup via UART: - On the _Moving Base_, set the following: - [GPS_UBX_MODE](../advanced_config/parameter_reference.md#GPS_UBX_MODE) to `2`. +For more information see [Rover and Moving Base](../dronecan/index.md#rover-and-moving-base) in the DroneCAN guide. + ## LED Meanings - The GPS status lights are located to the right of the connectors - - Blinking green is GPS fix - Blinking blue is received corrections and RTK Float - Solid blue is RTK Fixed From e8ccb23dc8477f92ef68af63e97020206b3923eb Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 18 Sep 2025 17:33:36 +1000 Subject: [PATCH 044/812] PurePursuitStatus.msg - whitespace indentation (#25544) --- msg/PurePursuitStatus.msg | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/msg/PurePursuitStatus.msg b/msg/PurePursuitStatus.msg index ef17246be5..bf1bb88b24 100644 --- a/msg/PurePursuitStatus.msg +++ b/msg/PurePursuitStatus.msg @@ -1,8 +1,8 @@ # Pure pursuit status -uint64 timestamp # [us] Time since system start -float32 lookahead_distance # [m] [@range 0, inf] Lookahead distance of pure the pursuit controller -float32 target_bearing # [rad] [@range -pi, pi] [@frame NED] Target bearing calculated by the pure pursuit controller -float32 crosstrack_error # [m] [@range -inf (Left of the path), inf (Right of the path)] Shortest distance from the vehicle to the path -float32 distance_to_waypoint # [m] [@range -inf, inf]Distance from the vehicle to the current waypoint -float32 bearing_to_waypoint # [rad] [@range -pi, pi] [@frame NED]Bearing towards current waypoint +uint64 timestamp # [us] Time since system start +float32 lookahead_distance # [m] [@range 0, inf] Lookahead distance of pure the pursuit controller +float32 target_bearing # [rad] [@range -pi, pi] [@frame NED] Target bearing calculated by the pure pursuit controller +float32 crosstrack_error # [m] [@range -inf (Left of the path), inf (Right of the path)] Shortest distance from the vehicle to the path +float32 distance_to_waypoint # [m] [@range -inf, inf]Distance from the vehicle to the current waypoint +float32 bearing_to_waypoint # [rad] [@range -pi, pi] [@frame NED]Bearing towards current waypoint From 2cb97e79b901eae446edf62996d2d7015a8e8e0c Mon Sep 17 00:00:00 2001 From: Pernilla Date: Thu, 18 Sep 2025 11:09:09 +0200 Subject: [PATCH 045/812] FlightTaskManualAccelerationSlow: Acquire gimbal control until expected IDs are reported (#25565) * Acquire control until expected id s are reported * require an updated message and allow release in case early exit of FlightTask * FlightTask Gimbal: acquiring logic simplification suggestion * formatting --------- Co-authored-by: Matthias Grob --- .../tasks/Utility/Gimbal.cpp | 40 +++++++++++-------- .../tasks/Utility/Gimbal.hpp | 5 ++- 2 files changed, 26 insertions(+), 19 deletions(-) diff --git a/src/modules/flight_mode_manager/tasks/Utility/Gimbal.cpp b/src/modules/flight_mode_manager/tasks/Utility/Gimbal.cpp index 21e97f5fc3..f56ee48804 100644 --- a/src/modules/flight_mode_manager/tasks/Utility/Gimbal.cpp +++ b/src/modules/flight_mode_manager/tasks/Utility/Gimbal.cpp @@ -63,29 +63,35 @@ bool Gimbal::checkForTelemetry(const hrt_abstime now) void Gimbal::acquireGimbalControlIfNeeded() { - if (!_have_gimbal_control) { - _have_gimbal_control = true; + gimbal_manager_status_s gimbal_manager_status; - vehicle_command_s vehicle_command{}; - vehicle_command.command = vehicle_command_s::VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE; - vehicle_command.param1 = _param_mav_sys_id.get(); - vehicle_command.param2 = _param_mav_comp_id.get(); - vehicle_command.param3 = -1.0f; // Leave unchanged. - vehicle_command.param4 = -1.0f; // Leave unchanged. - vehicle_command.timestamp = hrt_absolute_time(); - vehicle_command.source_system = _param_mav_sys_id.get(); - vehicle_command.source_component = _param_mav_comp_id.get(); - vehicle_command.target_system = _param_mav_sys_id.get(); - vehicle_command.target_component = _param_mav_sys_id.get(); - vehicle_command.from_external = false; - _vehicle_command_pub.publish(vehicle_command); + if (_gimbal_manager_status_sub.updated()) { + _gimbal_manager_status_sub.copy(&gimbal_manager_status); + + if (gimbal_manager_status.primary_control_compid != _param_mav_comp_id.get() || + gimbal_manager_status.primary_control_sysid != _param_mav_sys_id.get()) { + _tried_to_have_gimbal_control = true; + vehicle_command_s vehicle_command{}; + vehicle_command.command = vehicle_command_s::VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE; + vehicle_command.param1 = _param_mav_sys_id.get(); + vehicle_command.param2 = _param_mav_comp_id.get(); + vehicle_command.param3 = -1.0f; // Leave unchanged. + vehicle_command.param4 = -1.0f; // Leave unchanged. + vehicle_command.timestamp = hrt_absolute_time(); + vehicle_command.source_system = _param_mav_sys_id.get(); + vehicle_command.source_component = _param_mav_comp_id.get(); + vehicle_command.target_system = _param_mav_sys_id.get(); + vehicle_command.target_component = _param_mav_sys_id.get(); + vehicle_command.from_external = false; + _vehicle_command_pub.publish(vehicle_command); + } } } void Gimbal::releaseGimbalControlIfNeeded() { - if (_have_gimbal_control) { - _have_gimbal_control = false; + if (_tried_to_have_gimbal_control) { + _tried_to_have_gimbal_control = false; // Restore default flags, setting rate setpoints to NAN lead to unexpected behavior publishGimbalManagerSetAttitude(FLAGS_ROLL_PITCH_LOCKED, diff --git a/src/modules/flight_mode_manager/tasks/Utility/Gimbal.hpp b/src/modules/flight_mode_manager/tasks/Utility/Gimbal.hpp index 938ef32aa2..627979fa23 100644 --- a/src/modules/flight_mode_manager/tasks/Utility/Gimbal.hpp +++ b/src/modules/flight_mode_manager/tasks/Utility/Gimbal.hpp @@ -45,6 +45,7 @@ #include #include #include +#include #include #include "Sticks.hpp" @@ -73,9 +74,9 @@ public: | gimbal_manager_set_attitude_s::GIMBAL_MANAGER_FLAGS_PITCH_LOCK; private: - bool _have_gimbal_control{false}; - + bool _tried_to_have_gimbal_control{false}; uORB::Subscription _gimbal_device_attitude_status_sub{ORB_ID(gimbal_device_attitude_status)}; + uORB::Subscription _gimbal_manager_status_sub{ORB_ID(gimbal_manager_status)}; hrt_abstime _telemtry_timestamp{}; uint16_t _telemetry_flags{}; float _telemetry_yaw{}; From a514289a68c7566f8b7eb607026387c29a9394df Mon Sep 17 00:00:00 2001 From: mahima-yoga Date: Thu, 21 Aug 2025 10:59:05 +0200 Subject: [PATCH 046/812] Move Stick class into a globally available library --- src/lib/CMakeLists.txt | 1 + src/lib/sticks/CMakeLists.txt | 37 +++++++++++++++++++ .../tasks/Utility => lib/sticks}/Sticks.cpp | 0 .../tasks/Utility => lib/sticks}/Sticks.hpp | 0 .../tasks/Auto/CMakeLists.txt | 2 +- .../tasks/Auto/FlightTaskAuto.hpp | 2 +- .../FlightTaskAutoFollowTarget.hpp | 2 +- .../tasks/Descend/CMakeLists.txt | 2 +- .../tasks/Descend/FlightTaskDescend.hpp | 2 +- .../tasks/ManualAltitude/CMakeLists.txt | 2 +- .../FlightTaskManualAltitude.hpp | 2 +- .../tasks/Utility/CMakeLists.txt | 3 +- .../tasks/Utility/Gimbal.hpp | 3 +- .../tasks/Utility/StickAccelerationXY.cpp | 2 +- .../tasks/Utility/StickTiltXY.cpp | 2 +- 15 files changed, 50 insertions(+), 12 deletions(-) create mode 100644 src/lib/sticks/CMakeLists.txt rename src/{modules/flight_mode_manager/tasks/Utility => lib/sticks}/Sticks.cpp (100%) rename src/{modules/flight_mode_manager/tasks/Utility => lib/sticks}/Sticks.hpp (100%) diff --git a/src/lib/CMakeLists.txt b/src/lib/CMakeLists.txt index 8afa75fd58..22e377402e 100644 --- a/src/lib/CMakeLists.txt +++ b/src/lib/CMakeLists.txt @@ -71,6 +71,7 @@ add_subdirectory(rover_control EXCLUDE_FROM_ALL) add_subdirectory(rtl EXCLUDE_FROM_ALL) add_subdirectory(sensor_calibration EXCLUDE_FROM_ALL) add_subdirectory(slew_rate EXCLUDE_FROM_ALL) +add_subdirectory(sticks EXCLUDE_FROM_ALL) add_subdirectory(stick_yaw EXCLUDE_FROM_ALL) add_subdirectory(systemlib EXCLUDE_FROM_ALL) add_subdirectory(system_identification EXCLUDE_FROM_ALL) diff --git a/src/lib/sticks/CMakeLists.txt b/src/lib/sticks/CMakeLists.txt new file mode 100644 index 0000000000..3d17b2a140 --- /dev/null +++ b/src/lib/sticks/CMakeLists.txt @@ -0,0 +1,37 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +px4_add_library(Sticks + Sticks.cpp +) +target_include_directories(Sticks PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/flight_mode_manager/tasks/Utility/Sticks.cpp b/src/lib/sticks/Sticks.cpp similarity index 100% rename from src/modules/flight_mode_manager/tasks/Utility/Sticks.cpp rename to src/lib/sticks/Sticks.cpp diff --git a/src/modules/flight_mode_manager/tasks/Utility/Sticks.hpp b/src/lib/sticks/Sticks.hpp similarity index 100% rename from src/modules/flight_mode_manager/tasks/Utility/Sticks.hpp rename to src/lib/sticks/Sticks.hpp diff --git a/src/modules/flight_mode_manager/tasks/Auto/CMakeLists.txt b/src/modules/flight_mode_manager/tasks/Auto/CMakeLists.txt index fc43d98d27..3c9022f909 100644 --- a/src/modules/flight_mode_manager/tasks/Auto/CMakeLists.txt +++ b/src/modules/flight_mode_manager/tasks/Auto/CMakeLists.txt @@ -35,5 +35,5 @@ px4_add_library(FlightTaskAuto FlightTaskAuto.cpp ) -target_link_libraries(FlightTaskAuto PUBLIC FlightTask FlightTaskUtility StickYaw WeatherVane) +target_link_libraries(FlightTaskAuto PUBLIC FlightTask FlightTaskUtility Sticks StickYaw WeatherVane) target_include_directories(FlightTaskAuto PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp index 00610d910c..89dfc494c1 100644 --- a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp +++ b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.hpp @@ -49,9 +49,9 @@ #include #include #include +#include #include #include -#include "Sticks.hpp" #include "StickAccelerationXY.hpp" /** diff --git a/src/modules/flight_mode_manager/tasks/AutoFollowTarget/FlightTaskAutoFollowTarget.hpp b/src/modules/flight_mode_manager/tasks/AutoFollowTarget/FlightTaskAutoFollowTarget.hpp index 7e7b97b589..bc3d5e9506 100644 --- a/src/modules/flight_mode_manager/tasks/AutoFollowTarget/FlightTaskAutoFollowTarget.hpp +++ b/src/modules/flight_mode_manager/tasks/AutoFollowTarget/FlightTaskAutoFollowTarget.hpp @@ -44,7 +44,6 @@ #include "FlightTaskAuto.hpp" #include "follow_target_estimator/TargetEstimator.hpp" -#include "Sticks.hpp" #include #include @@ -57,6 +56,7 @@ #include #include +#include #include // << Follow Target Behavior related constants >> diff --git a/src/modules/flight_mode_manager/tasks/Descend/CMakeLists.txt b/src/modules/flight_mode_manager/tasks/Descend/CMakeLists.txt index eada0139e0..aaaceefd72 100644 --- a/src/modules/flight_mode_manager/tasks/Descend/CMakeLists.txt +++ b/src/modules/flight_mode_manager/tasks/Descend/CMakeLists.txt @@ -35,5 +35,5 @@ px4_add_library(FlightTaskDescend FlightTaskDescend.cpp ) -target_link_libraries(FlightTaskDescend PUBLIC FlightTask FlightTaskUtility StickYaw) +target_link_libraries(FlightTaskDescend PUBLIC FlightTask FlightTaskUtility Sticks StickYaw) target_include_directories(FlightTaskDescend PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/flight_mode_manager/tasks/Descend/FlightTaskDescend.hpp b/src/modules/flight_mode_manager/tasks/Descend/FlightTaskDescend.hpp index 6792e8fd12..46ae7543d1 100644 --- a/src/modules/flight_mode_manager/tasks/Descend/FlightTaskDescend.hpp +++ b/src/modules/flight_mode_manager/tasks/Descend/FlightTaskDescend.hpp @@ -37,9 +37,9 @@ #pragma once +#include #include #include "FlightTask.hpp" -#include "Sticks.hpp" #include "StickTiltXY.hpp" class FlightTaskDescend : public FlightTask diff --git a/src/modules/flight_mode_manager/tasks/ManualAltitude/CMakeLists.txt b/src/modules/flight_mode_manager/tasks/ManualAltitude/CMakeLists.txt index 65abdf871c..59b51435e1 100644 --- a/src/modules/flight_mode_manager/tasks/ManualAltitude/CMakeLists.txt +++ b/src/modules/flight_mode_manager/tasks/ManualAltitude/CMakeLists.txt @@ -35,5 +35,5 @@ px4_add_library(FlightTaskManualAltitude FlightTaskManualAltitude.cpp ) -target_link_libraries(FlightTaskManualAltitude PUBLIC FlightTask FlightTaskUtility StickYaw) +target_link_libraries(FlightTaskManualAltitude PUBLIC FlightTask FlightTaskUtility Sticks StickYaw) target_include_directories(FlightTaskManualAltitude PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.hpp b/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.hpp index 8386dfedad..6c04d7388a 100644 --- a/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.hpp +++ b/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.hpp @@ -40,8 +40,8 @@ #pragma once #include +#include #include "FlightTask.hpp" -#include "Sticks.hpp" #include "StickTiltXY.hpp" #include diff --git a/src/modules/flight_mode_manager/tasks/Utility/CMakeLists.txt b/src/modules/flight_mode_manager/tasks/Utility/CMakeLists.txt index f81a994452..c12356658b 100644 --- a/src/modules/flight_mode_manager/tasks/Utility/CMakeLists.txt +++ b/src/modules/flight_mode_manager/tasks/Utility/CMakeLists.txt @@ -32,13 +32,12 @@ ############################################################################ px4_add_library(FlightTaskUtility - Sticks.cpp StickAccelerationXY.cpp StickTiltXY.cpp Gimbal.cpp ) -target_link_libraries(FlightTaskUtility PUBLIC FlightTask hysteresis SlewRate motion_planning mathlib) +target_link_libraries(FlightTaskUtility PUBLIC FlightTask hysteresis SlewRate Sticks motion_planning mathlib) target_include_directories(FlightTaskUtility PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) px4_add_functional_gtest(SRC StickTiltXYTest.cpp LINKLIBS FlightTaskUtility) diff --git a/src/modules/flight_mode_manager/tasks/Utility/Gimbal.hpp b/src/modules/flight_mode_manager/tasks/Utility/Gimbal.hpp index 627979fa23..01a324b4a9 100644 --- a/src/modules/flight_mode_manager/tasks/Utility/Gimbal.hpp +++ b/src/modules/flight_mode_manager/tasks/Utility/Gimbal.hpp @@ -48,7 +48,8 @@ #include #include -#include "Sticks.hpp" +#include + class Gimbal : public ModuleParams diff --git a/src/modules/flight_mode_manager/tasks/Utility/StickAccelerationXY.cpp b/src/modules/flight_mode_manager/tasks/Utility/StickAccelerationXY.cpp index 686db33a88..3eeb56bd86 100644 --- a/src/modules/flight_mode_manager/tasks/Utility/StickAccelerationXY.cpp +++ b/src/modules/flight_mode_manager/tasks/Utility/StickAccelerationXY.cpp @@ -34,7 +34,7 @@ #include "StickAccelerationXY.hpp" #include -#include "Sticks.hpp" +#include using namespace matrix; diff --git a/src/modules/flight_mode_manager/tasks/Utility/StickTiltXY.cpp b/src/modules/flight_mode_manager/tasks/Utility/StickTiltXY.cpp index 642c4ef8a1..32ad13bdf8 100644 --- a/src/modules/flight_mode_manager/tasks/Utility/StickTiltXY.cpp +++ b/src/modules/flight_mode_manager/tasks/Utility/StickTiltXY.cpp @@ -34,7 +34,7 @@ #include "StickTiltXY.hpp" #include -#include "Sticks.hpp" +#include using namespace matrix; From a9720cf1ef28bf2dc1f584c7244e55937cc00ba2 Mon Sep 17 00:00:00 2001 From: mahima-yoga Date: Thu, 21 Aug 2025 14:07:32 +0200 Subject: [PATCH 047/812] FixedWingModeManager: use Sticks library --- src/modules/fw_mode_manager/CMakeLists.txt | 3 +- .../fw_mode_manager/FixedWingModeManager.cpp | 41 ++++++++----------- .../fw_mode_manager/FixedWingModeManager.hpp | 7 ++-- 3 files changed, 24 insertions(+), 27 deletions(-) diff --git a/src/modules/fw_mode_manager/CMakeLists.txt b/src/modules/fw_mode_manager/CMakeLists.txt index 3e21a51ee1..dec814aebc 100644 --- a/src/modules/fw_mode_manager/CMakeLists.txt +++ b/src/modules/fw_mode_manager/CMakeLists.txt @@ -41,7 +41,8 @@ set(POSCONTROL_DEPENDENCIES SlewRate tecs motion_planning - performance_model + performance_model + Sticks ) if(CONFIG_FIGURE_OF_EIGHT) diff --git a/src/modules/fw_mode_manager/FixedWingModeManager.cpp b/src/modules/fw_mode_manager/FixedWingModeManager.cpp index 84767f0368..b5e6d758c1 100644 --- a/src/modules/fw_mode_manager/FixedWingModeManager.cpp +++ b/src/modules/fw_mode_manager/FixedWingModeManager.cpp @@ -207,23 +207,18 @@ FixedWingModeManager::wind_poll(const hrt_abstime now) void FixedWingModeManager::manual_control_setpoint_poll() { - _manual_control_setpoint_sub.update(&_manual_control_setpoint); + _sticks.checkAndUpdateStickInputs(); - _manual_control_setpoint_for_height_rate = _manual_control_setpoint.pitch; - _manual_control_setpoint_for_airspeed = _manual_control_setpoint.throttle; + _manual_control_setpoint_for_height_rate = _sticks.getPitch(); + _manual_control_setpoint_for_airspeed = _sticks.getThrottleZeroCentered(); if (_param_fw_pos_stk_conf.get() & STICK_CONFIG_SWAP_STICKS_BIT) { /* Alternate stick allocation (similar concept as for multirotor systems: * demanding up/down with the throttle stick, and move faster/break with the pitch one. */ - _manual_control_setpoint_for_height_rate = -_manual_control_setpoint.throttle; - _manual_control_setpoint_for_airspeed = _manual_control_setpoint.pitch; - } - // send neutral setpoints if no update for 1 s - if (hrt_elapsed_time(&_manual_control_setpoint.timestamp) > 1_s) { - _manual_control_setpoint_for_height_rate = 0.f; - _manual_control_setpoint_for_airspeed = 0.f; + _manual_control_setpoint_for_height_rate = -_sticks.getThrottleZeroCentered(); + _manual_control_setpoint_for_airspeed = _sticks.getPitch(); } } @@ -1156,7 +1151,7 @@ FixedWingModeManager::control_auto_takeoff(const hrt_abstime &now, const float c fixed_wing_runway_control_s fw_runway_control{}; fw_runway_control.timestamp = now; fw_runway_control.wheel_steering_enabled = true; - fw_runway_control.wheel_steering_nudging_rate = _param_rwto_nudge.get() ? _manual_control_setpoint.yaw : 0.f; + fw_runway_control.wheel_steering_nudging_rate = _param_rwto_nudge.get() ? _sticks.getYaw() : 0.f; _fixed_wing_runway_control_pub.publish(fw_runway_control); @@ -1329,7 +1324,7 @@ FixedWingModeManager::control_auto_takeoff_no_nav(const hrt_abstime &now, const fixed_wing_runway_control_s fw_runway_control{}; fw_runway_control.timestamp = now; fw_runway_control.wheel_steering_enabled = true; - fw_runway_control.wheel_steering_nudging_rate = _param_rwto_nudge.get() ? _manual_control_setpoint.yaw : 0.f; + fw_runway_control.wheel_steering_nudging_rate = _param_rwto_nudge.get() ? _sticks.getYaw() : 0.f; _fixed_wing_runway_control_pub.publish(fw_runway_control); @@ -1578,7 +1573,7 @@ FixedWingModeManager::control_auto_landing_straight(const hrt_abstime &now, cons fw_runway_control.timestamp = now; fw_runway_control.wheel_steering_enabled = true; fw_runway_control.wheel_steering_nudging_rate = _param_fw_lnd_nudge.get() > LandingNudgingOption::kNudgingDisabled ? - _manual_control_setpoint.yaw : 0.f; + _sticks.getYaw() : 0.f; _fixed_wing_runway_control_pub.publish(fw_runway_control); @@ -1743,7 +1738,7 @@ FixedWingModeManager::control_auto_landing_circular(const hrt_abstime &now, cons fw_runway_control.timestamp = now; fw_runway_control.wheel_steering_enabled = true; fw_runway_control.wheel_steering_nudging_rate = _param_fw_lnd_nudge.get() > LandingNudgingOption::kNudgingDisabled ? - _manual_control_setpoint.yaw : 0.f; + _sticks.getYaw() : 0.f; _fixed_wing_runway_control_pub.publish(fw_runway_control); @@ -1795,7 +1790,7 @@ FixedWingModeManager::control_manual_altitude(const float control_interval, cons _ctrl_configuration_handler.setPitchMin(min_pitch); _ctrl_configuration_handler.setThrottleMax(throttle_max); - const float roll_body = _manual_control_setpoint.roll * radians(_param_fw_r_lim.get()); + const float roll_body = _sticks.getRoll() * radians(_param_fw_r_lim.get()); const DirectionalGuidanceOutput sp = {.course_setpoint = NAN, .lateral_acceleration_feedforward = rollAngleToLateralAccel(roll_body)}; fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint}; fw_lateral_ctrl_sp.timestamp = hrt_absolute_time(); @@ -1831,8 +1826,8 @@ FixedWingModeManager::control_manual_position(const hrt_abstime now, const float /* heading control */ // TODO: either make it course hold (easier) or a real heading hold (minus all the complexity here) - if (fabsf(_manual_control_setpoint.roll) < HDG_HOLD_MAN_INPUT_THRESH && - fabsf(_manual_control_setpoint.yaw) < HDG_HOLD_MAN_INPUT_THRESH) { + if (fabsf(_sticks.getRoll()) < HDG_HOLD_MAN_INPUT_THRESH && + fabsf(_sticks.getYaw()) < HDG_HOLD_MAN_INPUT_THRESH) { /* heading / roll is zero, lock onto current heading */ if (fabsf(_yawrate) < HDG_HOLD_YAWRATE_THRESH && !_yaw_lock_engaged) { @@ -1891,13 +1886,13 @@ FixedWingModeManager::control_manual_position(const hrt_abstime now, const float _ctrl_configuration_handler.setPitchMin(min_pitch); _ctrl_configuration_handler.setThrottleMax(throttle_max); - if (!_yaw_lock_engaged || fabsf(_manual_control_setpoint.roll) >= HDG_HOLD_MAN_INPUT_THRESH || - fabsf(_manual_control_setpoint.yaw) >= HDG_HOLD_MAN_INPUT_THRESH) { + if (!_yaw_lock_engaged || fabsf(_sticks.getRoll()) >= HDG_HOLD_MAN_INPUT_THRESH || + fabsf(_sticks.getYaw()) >= HDG_HOLD_MAN_INPUT_THRESH) { _hdg_hold_enabled = false; _yaw_lock_engaged = false; - const float roll_body = _manual_control_setpoint.roll * radians(_param_fw_r_lim.get()); + const float roll_body = _sticks.getRoll() * radians(_param_fw_r_lim.get()); fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint}; fw_lateral_ctrl_sp.timestamp = hrt_absolute_time(); fw_lateral_ctrl_sp.lateral_acceleration = rollAngleToLateralAccel(roll_body); @@ -2385,14 +2380,14 @@ FixedWingModeManager::initializeAutoLanding(const hrt_abstime &now, const positi Vector2f FixedWingModeManager::calculateTouchdownPosition(const float control_interval, const Vector2f &local_land_position) { - if (fabsf(_manual_control_setpoint.yaw) > MANUAL_TOUCHDOWN_NUDGE_INPUT_DEADZONE + if (fabsf(_sticks.getYaw()) > MANUAL_TOUCHDOWN_NUDGE_INPUT_DEADZONE && _param_fw_lnd_nudge.get() > LandingNudgingOption::kNudgingDisabled && !_flare_states.flaring) { // laterally nudge touchdown location with yaw stick // positive is defined in the direction of a right hand turn starting from the approach vector direction const float signed_deadzone_threshold = MANUAL_TOUCHDOWN_NUDGE_INPUT_DEADZONE * math::signNoZero( - _manual_control_setpoint.yaw); - _lateral_touchdown_position_offset += (_manual_control_setpoint.yaw - signed_deadzone_threshold) * + _sticks.getYaw()); + _lateral_touchdown_position_offset += (_sticks.getYaw() - signed_deadzone_threshold) * MAX_TOUCHDOWN_POSITION_NUDGE_RATE * control_interval; _lateral_touchdown_position_offset = math::constrain(_lateral_touchdown_position_offset, -_param_fw_lnd_td_off.get(), _param_fw_lnd_td_off.get()); diff --git a/src/modules/fw_mode_manager/FixedWingModeManager.hpp b/src/modules/fw_mode_manager/FixedWingModeManager.hpp index b02e29678c..71fe564de7 100644 --- a/src/modules/fw_mode_manager/FixedWingModeManager.hpp +++ b/src/modules/fw_mode_manager/FixedWingModeManager.hpp @@ -52,6 +52,7 @@ #include #include #include +#include #include #include #include @@ -71,7 +72,6 @@ #include #include #include -#include #include #include #include @@ -180,7 +180,6 @@ private: uORB::Subscription _wind_sub{ORB_ID(wind)}; uORB::Subscription _control_mode_sub{ORB_ID(vehicle_control_mode)}; uORB::Subscription _global_pos_sub{ORB_ID(vehicle_global_position)}; - uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; uORB::Subscription _pos_sp_triplet_sub{ORB_ID(position_setpoint_triplet)}; uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)}; uORB::Subscription _vehicle_angular_velocity_sub{ORB_ID(vehicle_angular_velocity)}; @@ -201,7 +200,6 @@ private: uORB::Publication _fixed_wing_lateral_guidance_status_pub{ORB_ID(fixed_wing_lateral_guidance_status)}; uORB::Publication _fixed_wing_runway_control_pub{ORB_ID(fixed_wing_runway_control)}; - manual_control_setpoint_s _manual_control_setpoint{}; position_setpoint_triplet_s _pos_sp_triplet{}; vehicle_control_mode_s _control_mode{}; vehicle_local_position_s _local_pos{}; @@ -243,6 +241,9 @@ private: STICK_CONFIG_ENABLE_AIRSPEED_SP_MANUAL_BIT = (1 << 1) }; + + Sticks _sticks{this}; + // VEHICLE STATES uint8_t _nav_state; From 2bf9fce57724068abf7275ddc36d0428285258a5 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 4 Sep 2025 14:56:34 +0200 Subject: [PATCH 048/812] Sticks: globalize MPC_HOLD_DZ to MAN_DEADZONE --- .../amovlabf410_drone_v1.15.4.params | 1 - docs/en/flight_modes_mc/position.md | 12 ++++++------ src/lib/sticks/Sticks.cpp | 8 ++++---- src/lib/sticks/Sticks.hpp | 2 +- .../manual_control/manual_control_params.c | 17 +++++++++++++++++ src/modules/mc_att_control/mc_att_control.hpp | 2 +- .../mc_att_control/mc_att_control_main.cpp | 2 +- .../multicopter_position_mode_params.c | 13 ------------- 8 files changed, 30 insertions(+), 27 deletions(-) diff --git a/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params b/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params index 0d16ea9f01..d742b0fc3e 100644 --- a/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params +++ b/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params @@ -645,7 +645,6 @@ 1 1 MPC_ACC_HOR_MAX 5.000000000000000000 9 1 1 MPC_ACC_UP_MAX 4.000000000000000000 9 1 1 MPC_ALT_MODE 2 6 -1 1 MPC_HOLD_DZ 0.100000001490116119 9 1 1 MPC_HOLD_MAX_XY 0.800000011920928955 9 1 1 MPC_HOLD_MAX_Z 0.600000023841857910 9 1 1 MPC_JERK_AUTO 4.000000000000000000 9 diff --git a/docs/en/flight_modes_mc/position.md b/docs/en/flight_modes_mc/position.md index cb85fc53ac..746a1baaac 100644 --- a/docs/en/flight_modes_mc/position.md +++ b/docs/en/flight_modes_mc/position.md @@ -43,7 +43,7 @@ While very rare on a well calibrated vehicle, sometimes there may be problems wi RC mode where roll, pitch, throttle (RPT) sticks control movement in corresponding axes/directions. Centered sticks level vehicle and hold it to fixed altitude and position against wind. -- Centered roll, pitch, throttle sticks (within RC deadzone [MPC_HOLD_DZ](../advanced_config/parameter_reference.md#MPC_HOLD_DZ)) hold x, y, z position steady against any disturbance like wind. +- Centered roll, pitch, throttle sticks (within RC deadzone [MAN_DEADZONE](../advanced_config/parameter_reference.md#MAN_DEADZONE)) hold x, y, z position steady against any disturbance like wind. - Outside center: - Roll/Pitch sticks control horizontal acceleration over ground in the vehicle's left-right and forward-back directions (respectively). - Throttle stick controls speed of ascent-descent. @@ -51,10 +51,10 @@ Centered sticks level vehicle and hold it to fixed altitude and position against - Takeoff: - When landed, the vehicle will take off if the throttle stick is raised above 62.5% percent (of the full range from bottom). - Global position estimate is required. -- Manual control input is required (such as RC control, joystick). - - Roll, Pitch, Throttle: Assistance from autopilot to hold position against wind. - - Yaw: Assistance from autopilot to stabilize the attitude rate. - Position of RC stick maps to the rate of rotation of vehicle in that orientation. +- Manual control input is required (such as RC control, joystick). + - Roll, Pitch, Throttle: Assistance from autopilot to hold position against wind. + - Yaw: Assistance from autopilot to stabilize the attitude rate. + Position of RC stick maps to the rate of rotation of vehicle in that orientation. ### Parameters @@ -62,7 +62,7 @@ All the parameters in the [Multicopter Position Control](../advanced_config/para | Parameter | Description | | ----------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -| [MPC_HOLD_DZ](../advanced_config/parameter_reference.md#MPC_HOLD_DZ) | Deadzone of sticks where position hold is enabled. Default: 0.1 (10% of full stick range). | +| [MAN_DEADZONE](../advanced_config/parameter_reference.md#MAN_DEADZONE) | Deadzone of sticks where position hold is enabled. Default: 0.1 (10% of full stick range). | | [MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | Maximum vertical ascent velocity. Default: 3 m/s. | | [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | Maximum vertical descent velocity. Default: 1 m/s. | | [MPC_LAND_ALT1](../advanced_config/parameter_reference.md#MPC_LAND_ALT1) | Altitude for triggering first phase of slow landing. Below this altitude descending velocity gets limited to a value between [MPC_Z_VEL_MAX_DN](#MPC_Z_VEL_MAX_DN) (or `MPC_Z_V_AUTO_DN`) and [MPC_LAND_SPEED](#MPC_LAND_SPEED). Value needs to be higher than [MPC_LAND_ALT2](#MPC_LAND_ALT2). Default 10m. | diff --git a/src/lib/sticks/Sticks.cpp b/src/lib/sticks/Sticks.cpp index fb5bc40673..0150e4af2f 100644 --- a/src/lib/sticks/Sticks.cpp +++ b/src/lib/sticks/Sticks.cpp @@ -57,10 +57,10 @@ bool Sticks::checkAndUpdateStickInputs() _positions(3) = manual_control_setpoint.yaw; // Exponential scale - _positions_expo(0) = math::expo_deadzone(_positions(0), _param_mpc_xy_man_expo.get(), _param_mpc_hold_dz.get()); - _positions_expo(1) = math::expo_deadzone(_positions(1), _param_mpc_xy_man_expo.get(), _param_mpc_hold_dz.get()); - _positions_expo(2) = math::expo_deadzone(_positions(2), _param_mpc_z_man_expo.get(), _param_mpc_hold_dz.get()); - _positions_expo(3) = math::expo_deadzone(_positions(3), _param_mpc_yaw_expo.get(), _param_mpc_hold_dz.get()); + _positions_expo(0) = math::expo_deadzone(_positions(0), _param_mpc_xy_man_expo.get(), _param_man_deadzone.get()); + _positions_expo(1) = math::expo_deadzone(_positions(1), _param_mpc_xy_man_expo.get(), _param_man_deadzone.get()); + _positions_expo(2) = math::expo_deadzone(_positions(2), _param_mpc_z_man_expo.get(), _param_man_deadzone.get()); + _positions_expo(3) = math::expo_deadzone(_positions(3), _param_mpc_yaw_expo.get(), _param_man_deadzone.get()); _aux_positions(0) = manual_control_setpoint.aux1; _aux_positions(1) = manual_control_setpoint.aux2; diff --git a/src/lib/sticks/Sticks.hpp b/src/lib/sticks/Sticks.hpp index 3ab13368e8..a169549b01 100644 --- a/src/lib/sticks/Sticks.hpp +++ b/src/lib/sticks/Sticks.hpp @@ -101,7 +101,7 @@ private: uORB::Subscription _failsafe_flags_sub{ORB_ID(failsafe_flags)}; DEFINE_PARAMETERS( - (ParamFloat) _param_mpc_hold_dz, + (ParamFloat) _param_man_deadzone, (ParamFloat) _param_mpc_xy_man_expo, (ParamFloat) _param_mpc_z_man_expo, (ParamFloat) _param_mpc_yaw_expo diff --git a/src/modules/manual_control/manual_control_params.c b/src/modules/manual_control/manual_control_params.c index 7fde0d6dd3..30bfa35b4c 100644 --- a/src/modules/manual_control/manual_control_params.c +++ b/src/modules/manual_control/manual_control_params.c @@ -58,3 +58,20 @@ PARAM_DEFINE_INT32(MAN_ARM_GESTURE, 1); * @max 15 */ PARAM_DEFINE_FLOAT(MAN_KILL_GEST_T, -1.f); + +/** + * Deadzone for sticks (only specific use cases) + * + * Range around stick center ignored to prevent + * vehicle drift from stick hardware inaccuracy. + * + * Does not apply to any precise constant input like + * throttle and attitude or rate piloting. + * + * @min 0 + * @max 1 + * @decimal 2 + * @increment 0.01 + * @group Manual Control + */ +PARAM_DEFINE_FLOAT(MAN_DEADZONE, 0.1f); diff --git a/src/modules/mc_att_control/mc_att_control.hpp b/src/modules/mc_att_control/mc_att_control.hpp index 4743d1936d..c3b67bc47d 100644 --- a/src/modules/mc_att_control/mc_att_control.hpp +++ b/src/modules/mc_att_control/mc_att_control.hpp @@ -161,7 +161,7 @@ private: (ParamFloat) _param_mc_yawrate_max, /* Stabilized mode params */ - (ParamFloat) _param_mpc_hold_dz, + (ParamFloat) _param_man_deadzone, (ParamFloat) _param_mpc_man_tilt_max, (ParamFloat) _param_mpc_manthr_min, (ParamFloat) _param_mpc_thr_max, diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index f79e8ff911..6e7b8ee44a 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -147,7 +147,7 @@ MulticopterAttitudeControl::generate_attitude_setpoint(const Quatf &q, float dt) const float yaw = Eulerf(q).psi(); const float yaw_stick_input = math::expo_deadzone(_manual_control_setpoint.yaw, _param_mpc_yaw_expo.get(), - _param_mpc_hold_dz.get()); + _param_man_deadzone.get()); _stick_yaw.generateYawSetpoint(attitude_setpoint.yaw_sp_move_rate, _yaw_setpoint_stabilized, yaw_stick_input, yaw, dt, _unaided_heading); diff --git a/src/modules/mc_pos_control/multicopter_position_mode_params.c b/src/modules/mc_pos_control/multicopter_position_mode_params.c index b70bb95a3e..0df673350e 100644 --- a/src/modules/mc_pos_control/multicopter_position_mode_params.c +++ b/src/modules/mc_pos_control/multicopter_position_mode_params.c @@ -130,19 +130,6 @@ PARAM_DEFINE_FLOAT(MPC_ACC_HOR_MAX, 5.f); */ PARAM_DEFINE_FLOAT(MPC_JERK_MAX, 8.f); -/** - * Deadzone for sticks in manual piloted modes - * - * Does not apply to manual throttle and direct attitude piloting by stick. - * - * @min 0 - * @max 1 - * @decimal 2 - * @increment 0.01 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_HOLD_DZ, 0.1f); - /** * Manual position control stick exponential curve sensitivity * From 2e910fe18587566a9210f4caddfc610ac45f8463 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 4 Sep 2025 15:16:34 +0200 Subject: [PATCH 049/812] FlightTask{Altitude+Orbit}: use getter for specific stick value instead of entire array --- .../tasks/ManualAltitude/FlightTaskManualAltitude.cpp | 8 ++++---- .../flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp | 8 ++++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.cpp b/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.cpp index 2f27fd1aed..1d049b344a 100644 --- a/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.cpp +++ b/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.cpp @@ -91,8 +91,8 @@ void FlightTaskManualAltitude::_scaleSticks() // Use sticks input with deadzone and exponential curve for vertical velocity const float vel_max_up = fminf(_param_mpc_z_vel_max_up.get(), _velocity_constraint_up); const float vel_max_down = fminf(_param_mpc_z_vel_max_dn.get(), _velocity_constraint_down); - const float vel_max_z = (_sticks.getPosition()(2) > 0.0f) ? vel_max_down : vel_max_up; - _velocity_setpoint(2) = vel_max_z * _sticks.getPositionExpo()(2); + const float vel_max_z = (_sticks.getThrottleZeroCentered() < 0.f) ? vel_max_down : vel_max_up; + _velocity_setpoint(2) = vel_max_z * -_sticks.getThrottleZeroCenteredExpo(); } void FlightTaskManualAltitude::_updateAltitudeLock() @@ -101,7 +101,7 @@ void FlightTaskManualAltitude::_updateAltitudeLock() // If not locked, altitude setpoint is set to NAN. // Check if user wants to break - const bool apply_brake = fabsf(_sticks.getPositionExpo()(2)) <= FLT_EPSILON; + const bool apply_brake = fabsf(_sticks.getThrottleZeroCenteredExpo()) <= FLT_EPSILON; // Check if vehicle has stopped const bool stopped = (_param_mpc_hold_max_z.get() < FLT_EPSILON || fabsf(_velocity(2)) < _param_mpc_hold_max_z.get()); @@ -284,7 +284,7 @@ void FlightTaskManualAltitude::_updateSetpoints() bool FlightTaskManualAltitude::_checkTakeoff() { // stick is deflected above 65% throttle (throttle stick is in the range [-1,1]) - return _sticks.getPosition()(2) < -0.3f; + return _sticks.getThrottleZeroCentered() > 0.3f; } bool FlightTaskManualAltitude::update() diff --git a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp index c8a79a7b0c..d8b68b0db3 100644 --- a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp +++ b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp @@ -292,8 +292,8 @@ void FlightTaskOrbit::_adjustParametersByStick() switch (_yaw_behaviour) { case orbit_status_s::ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE: - radius -= signFromBool(_started_clockwise) * _sticks.getPositionExpo()(1) * _deltatime * _param_mpc_xy_cruise.get(); - velocity += signFromBool(_started_clockwise) * _sticks.getPositionExpo()(0) * _deltatime * _param_mpc_acc_hor.get(); + radius -= signFromBool(_started_clockwise) * _sticks.getRollExpo() * _deltatime * _param_mpc_xy_cruise.get(); + velocity += signFromBool(_started_clockwise) * _sticks.getPitchExpo() * _deltatime * _param_mpc_acc_hor.get(); break; case orbit_status_s::ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING: @@ -302,8 +302,8 @@ void FlightTaskOrbit::_adjustParametersByStick() case orbit_status_s::ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER: default: // stick input adjusts parameters within a fixed time frame - radius -= _sticks.getPositionExpo()(0) * _deltatime * _param_mpc_xy_cruise.get(); - velocity -= _sticks.getPositionExpo()(1) * _deltatime * _param_mpc_acc_hor.get(); + radius -= _sticks.getPitchExpo() * _deltatime * _param_mpc_xy_cruise.get(); + velocity -= _sticks.getRollExpo() * _deltatime * _param_mpc_acc_hor.get(); break; } From 234e4688b069c0d1b02fb775a15aa1e1d5d60720 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 4 Sep 2025 15:17:29 +0200 Subject: [PATCH 050/812] Sticks: calculate expo only upon getter call --- src/lib/sticks/Sticks.cpp | 8 -------- src/lib/sticks/Sticks.hpp | 15 +++++---------- 2 files changed, 5 insertions(+), 18 deletions(-) diff --git a/src/lib/sticks/Sticks.cpp b/src/lib/sticks/Sticks.cpp index 0150e4af2f..31d06421f3 100644 --- a/src/lib/sticks/Sticks.cpp +++ b/src/lib/sticks/Sticks.cpp @@ -50,18 +50,11 @@ bool Sticks::checkAndUpdateStickInputs() manual_control_setpoint_s manual_control_setpoint; if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) { - // Linear scale _positions(0) = manual_control_setpoint.pitch; _positions(1) = manual_control_setpoint.roll; _positions(2) = -manual_control_setpoint.throttle; _positions(3) = manual_control_setpoint.yaw; - // Exponential scale - _positions_expo(0) = math::expo_deadzone(_positions(0), _param_mpc_xy_man_expo.get(), _param_man_deadzone.get()); - _positions_expo(1) = math::expo_deadzone(_positions(1), _param_mpc_xy_man_expo.get(), _param_man_deadzone.get()); - _positions_expo(2) = math::expo_deadzone(_positions(2), _param_mpc_z_man_expo.get(), _param_man_deadzone.get()); - _positions_expo(3) = math::expo_deadzone(_positions(3), _param_mpc_yaw_expo.get(), _param_man_deadzone.get()); - _aux_positions(0) = manual_control_setpoint.aux1; _aux_positions(1) = manual_control_setpoint.aux2; _aux_positions(2) = manual_control_setpoint.aux3; @@ -85,7 +78,6 @@ bool Sticks::checkAndUpdateStickInputs() if (!_input_available) { // Timeout: set all sticks to zero _positions.zero(); - _positions_expo.zero(); } return _input_available; diff --git a/src/lib/sticks/Sticks.hpp b/src/lib/sticks/Sticks.hpp index a169549b01..56d6016386 100644 --- a/src/lib/sticks/Sticks.hpp +++ b/src/lib/sticks/Sticks.hpp @@ -58,21 +58,17 @@ public: bool isAvailable() { return _input_available; }; - // Position : 0 : pitch, 1 : roll, 2 : throttle, 3 : yaw - const matrix::Vector4f &getPosition() { return _positions; }; // Raw stick position, no deadzone - const matrix::Vector4f &getPositionExpo() { return _positions_expo; }; // Deadzone and expo applied - // Helper functions to get stick values more intuitively float getRoll() const { return _positions(1); } - float getRollExpo() const { return _positions_expo(1); } + float getRollExpo() const { return math::expo_deadzone(_positions(1), _param_mpc_xy_man_expo.get(), _param_man_deadzone.get()); } float getPitch() const { return _positions(0); } - float getPitchExpo() const { return _positions_expo(0); } + float getPitchExpo() const { return math::expo_deadzone(_positions(0), _param_mpc_xy_man_expo.get(), _param_man_deadzone.get()); } float getYaw() const { return _positions(3); } - float getYawExpo() const { return _positions_expo(3); } + float getYawExpo() const { return math::expo_deadzone(_positions(3), _param_mpc_yaw_expo.get(), _param_man_deadzone.get()); } float getThrottleZeroCentered() const { return -_positions(2); } // Convert Z-axis(down) command to Up-axis frame - float getThrottleZeroCenteredExpo() const { return -_positions_expo(2); } + float getThrottleZeroCenteredExpo() const { return -math::expo_deadzone(_positions(2), _param_mpc_z_man_expo.get(), _param_man_deadzone.get()); } const matrix::Vector2f getPitchRoll() { return _positions.slice<2, 1>(0, 0); } - const matrix::Vector2f getPitchRollExpo() { return _positions_expo.slice<2, 1>(0, 0); } + const matrix::Vector2f getPitchRollExpo() { return {getPitchExpo(), getRollExpo()}; } const matrix::Vector &getAux() const { return _aux_positions; } @@ -93,7 +89,6 @@ public: private: bool _input_available{false}; matrix::Vector4f _positions; ///< unmodified manual stick inputs that usually move vehicle in x, y, z and yaw direction - matrix::Vector4f _positions_expo; ///< modified manual sticks using expo function matrix::Vector _aux_positions; From 5b9455731014de491ca77f59ed6e25afbdf59656 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 4 Sep 2025 15:27:38 +0200 Subject: [PATCH 051/812] Sticks: change internal order and sign of stick positions --- src/lib/sticks/Sticks.cpp | 8 ++++---- src/lib/sticks/Sticks.hpp | 22 ++++++++++++---------- 2 files changed, 16 insertions(+), 14 deletions(-) diff --git a/src/lib/sticks/Sticks.cpp b/src/lib/sticks/Sticks.cpp index 31d06421f3..26a66cf271 100644 --- a/src/lib/sticks/Sticks.cpp +++ b/src/lib/sticks/Sticks.cpp @@ -50,10 +50,10 @@ bool Sticks::checkAndUpdateStickInputs() manual_control_setpoint_s manual_control_setpoint; if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) { - _positions(0) = manual_control_setpoint.pitch; - _positions(1) = manual_control_setpoint.roll; - _positions(2) = -manual_control_setpoint.throttle; - _positions(3) = manual_control_setpoint.yaw; + _positions(0) = manual_control_setpoint.roll; + _positions(1) = manual_control_setpoint.pitch; + _positions(2) = manual_control_setpoint.yaw; + _positions(3) = manual_control_setpoint.throttle; _aux_positions(0) = manual_control_setpoint.aux1; _aux_positions(1) = manual_control_setpoint.aux2; diff --git a/src/lib/sticks/Sticks.hpp b/src/lib/sticks/Sticks.hpp index 56d6016386..1620fb90ce 100644 --- a/src/lib/sticks/Sticks.hpp +++ b/src/lib/sticks/Sticks.hpp @@ -59,15 +59,17 @@ public: bool isAvailable() { return _input_available; }; // Helper functions to get stick values more intuitively - float getRoll() const { return _positions(1); } - float getRollExpo() const { return math::expo_deadzone(_positions(1), _param_mpc_xy_man_expo.get(), _param_man_deadzone.get()); } - float getPitch() const { return _positions(0); } - float getPitchExpo() const { return math::expo_deadzone(_positions(0), _param_mpc_xy_man_expo.get(), _param_man_deadzone.get()); } - float getYaw() const { return _positions(3); } - float getYawExpo() const { return math::expo_deadzone(_positions(3), _param_mpc_yaw_expo.get(), _param_man_deadzone.get()); } - float getThrottleZeroCentered() const { return -_positions(2); } // Convert Z-axis(down) command to Up-axis frame - float getThrottleZeroCenteredExpo() const { return -math::expo_deadzone(_positions(2), _param_mpc_z_man_expo.get(), _param_man_deadzone.get()); } - const matrix::Vector2f getPitchRoll() { return _positions.slice<2, 1>(0, 0); } + float getRoll() const { return _positions(0); } + float getPitch() const { return _positions(1); } + float getYaw() const { return _positions(2); } + float getThrottleZeroCentered() const { return _positions(3); } + + float getRollExpo() const { return math::expo_deadzone(getRoll(), _param_mpc_xy_man_expo.get(), _param_man_deadzone.get()); } + float getPitchExpo() const { return math::expo_deadzone(getPitch(), _param_mpc_xy_man_expo.get(), _param_man_deadzone.get()); } + float getYawExpo() const { return math::expo_deadzone(getYaw(), _param_mpc_yaw_expo.get(), _param_man_deadzone.get()); } + float getThrottleZeroCenteredExpo() const { return math::expo_deadzone(getThrottleZeroCentered(), _param_mpc_z_man_expo.get(), _param_man_deadzone.get()); } + + const matrix::Vector2f getPitchRoll() { return {getPitch(), getRoll()}; } const matrix::Vector2f getPitchRollExpo() { return {getPitchExpo(), getRollExpo()}; } const matrix::Vector &getAux() const { return _aux_positions; } @@ -88,7 +90,7 @@ public: private: bool _input_available{false}; - matrix::Vector4f _positions; ///< unmodified manual stick inputs that usually move vehicle in x, y, z and yaw direction + matrix::Vector4f _positions; ///< unmodified manual stick inputs roll, pitch, yaw ,throttle matrix::Vector _aux_positions; From 5c5bf0b83db96e8c556a44e48746fab99f6c3513 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 4 Sep 2025 15:40:01 +0200 Subject: [PATCH 052/812] Remove parameters MPC_{XY/Z/YAW}_MAN_EXPO and use default value instead --- .../amovlabf410_drone_v1.15.4.params | 3 -- src/lib/sticks/Sticks.hpp | 13 ++--- src/modules/mc_att_control/mc_att_control.hpp | 1 - .../mc_att_control/mc_att_control_main.cpp | 3 +- .../multicopter_position_mode_params.c | 51 ------------------- 5 files changed, 6 insertions(+), 65 deletions(-) diff --git a/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params b/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params index d742b0fc3e..2b611958b9 100644 --- a/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params +++ b/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params @@ -677,7 +677,6 @@ 1 1 MPC_VEL_MAN_SIDE -1.000000000000000000 9 1 1 MPC_XY_CRUISE 5.000000000000000000 9 1 1 MPC_XY_ERR_MAX 2.000000000000000000 9 -1 1 MPC_XY_MAN_EXPO 0.600000023841857910 9 1 1 MPC_XY_P 0.949999988079071045 9 1 1 MPC_XY_TRAJ_P 0.500000000000000000 9 1 1 MPC_XY_VEL_ALL -10.000000000000000000 9 @@ -687,9 +686,7 @@ 1 1 MPC_XY_VEL_P_ACC 1.799999952316284180 9 1 1 MPC_YAWRAUTO_ACC 60.000000000000000000 9 1 1 MPC_YAWRAUTO_MAX 45.000000000000000000 9 -1 1 MPC_YAW_EXPO 0.600000023841857910 9 1 1 MPC_YAW_MODE 0 6 -1 1 MPC_Z_MAN_EXPO 0.600000023841857910 9 1 1 MPC_Z_P 1.000000000000000000 9 1 1 MPC_Z_VEL_ALL -3.000000000000000000 9 1 1 MPC_Z_VEL_D_ACC 0.000000000000000000 9 diff --git a/src/lib/sticks/Sticks.hpp b/src/lib/sticks/Sticks.hpp index 1620fb90ce..1da031a283 100644 --- a/src/lib/sticks/Sticks.hpp +++ b/src/lib/sticks/Sticks.hpp @@ -64,10 +64,10 @@ public: float getYaw() const { return _positions(2); } float getThrottleZeroCentered() const { return _positions(3); } - float getRollExpo() const { return math::expo_deadzone(getRoll(), _param_mpc_xy_man_expo.get(), _param_man_deadzone.get()); } - float getPitchExpo() const { return math::expo_deadzone(getPitch(), _param_mpc_xy_man_expo.get(), _param_man_deadzone.get()); } - float getYawExpo() const { return math::expo_deadzone(getYaw(), _param_mpc_yaw_expo.get(), _param_man_deadzone.get()); } - float getThrottleZeroCenteredExpo() const { return math::expo_deadzone(getThrottleZeroCentered(), _param_mpc_z_man_expo.get(), _param_man_deadzone.get()); } + float getRollExpo(float expo = .6f) const { return math::expo_deadzone(getRoll(), expo, _param_man_deadzone.get()); } + float getPitchExpo(float expo = .6f) const { return math::expo_deadzone(getPitch(), expo, _param_man_deadzone.get()); } + float getYawExpo(float expo = .6f) const { return math::expo_deadzone(getYaw(), expo, _param_man_deadzone.get()); } + float getThrottleZeroCenteredExpo(float expo = .6f) const { return math::expo_deadzone(getThrottleZeroCentered(), expo, _param_man_deadzone.get()); } const matrix::Vector2f getPitchRoll() { return {getPitch(), getRoll()}; } const matrix::Vector2f getPitchRollExpo() { return {getPitchExpo(), getRollExpo()}; } @@ -98,9 +98,6 @@ private: uORB::Subscription _failsafe_flags_sub{ORB_ID(failsafe_flags)}; DEFINE_PARAMETERS( - (ParamFloat) _param_man_deadzone, - (ParamFloat) _param_mpc_xy_man_expo, - (ParamFloat) _param_mpc_z_man_expo, - (ParamFloat) _param_mpc_yaw_expo + (ParamFloat) _param_man_deadzone ) }; diff --git a/src/modules/mc_att_control/mc_att_control.hpp b/src/modules/mc_att_control/mc_att_control.hpp index c3b67bc47d..d9bdddabdd 100644 --- a/src/modules/mc_att_control/mc_att_control.hpp +++ b/src/modules/mc_att_control/mc_att_control.hpp @@ -167,7 +167,6 @@ private: (ParamFloat) _param_mpc_thr_max, (ParamFloat) _param_mpc_thr_hover, (ParamInt) _param_mpc_thr_curve, - (ParamFloat) _param_mpc_yaw_expo, (ParamFloat) _param_com_spoolup_time ) diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 6e7b8ee44a..0b8f9c8198 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -146,8 +146,7 @@ MulticopterAttitudeControl::generate_attitude_setpoint(const Quatf &q, float dt) } const float yaw = Eulerf(q).psi(); - const float yaw_stick_input = math::expo_deadzone(_manual_control_setpoint.yaw, _param_mpc_yaw_expo.get(), - _param_man_deadzone.get()); + const float yaw_stick_input = math::expo_deadzone(_manual_control_setpoint.yaw, .6f, _param_man_deadzone.get()); _stick_yaw.generateYawSetpoint(attitude_setpoint.yaw_sp_move_rate, _yaw_setpoint_stabilized, yaw_stick_input, yaw, dt, _unaided_heading); diff --git a/src/modules/mc_pos_control/multicopter_position_mode_params.c b/src/modules/mc_pos_control/multicopter_position_mode_params.c index 0df673350e..97c905f819 100644 --- a/src/modules/mc_pos_control/multicopter_position_mode_params.c +++ b/src/modules/mc_pos_control/multicopter_position_mode_params.c @@ -129,54 +129,3 @@ PARAM_DEFINE_FLOAT(MPC_ACC_HOR_MAX, 5.f); * @group Multicopter Position Control */ PARAM_DEFINE_FLOAT(MPC_JERK_MAX, 8.f); - -/** - * Manual position control stick exponential curve sensitivity - * - * The higher the value the less sensitivity the stick has around zero - * while still reaching the maximum value with full stick deflection. - * - * 0 Purely linear input curve - * 1 Purely cubic input curve - * - * @min 0 - * @max 1 - * @decimal 2 - * @increment 0.01 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_XY_MAN_EXPO, 0.6f); - -/** - * Manual control stick vertical exponential curve - * - * The higher the value the less sensitivity the stick has around zero - * while still reaching the maximum value with full stick deflection. - * - * 0 Purely linear input curve - * 1 Purely cubic input curve - * - * @min 0 - * @max 1 - * @decimal 2 - * @increment 0.01 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_Z_MAN_EXPO, 0.6f); - -/** - * Manual control stick yaw rotation exponential curve - * - * The higher the value the less sensitivity the stick has around zero - * while still reaching the maximum value with full stick deflection. - * - * 0 Purely linear input curve - * 1 Purely cubic input curve - * - * @min 0 - * @max 1 - * @decimal 2 - * @increment 0.01 - * @group Multicopter Position Control - */ -PARAM_DEFINE_FLOAT(MPC_YAW_EXPO, 0.6f); From d2e4d85bce42bad2f9575efde17f617c861c4f34 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 15 Aug 2025 16:41:38 +0200 Subject: [PATCH 053/812] Add Altitude Cruise mode -add new NAVIGATION_STATE_ALTITUDE_VOYAGER -this mode does require manual control to enter -but you can disable the manual control loss failsafe to continue flying in case of manual control loss -for MC: in throttle and yaw are controlled like in Altitude mode, the tilt is controlled via integrated rate input (similar to Acro, but with tilt limit) Signed-off-by: Silvan Fuhrer --- docs/en/SUMMARY.md | 1 + docs/en/flight_modes_fw/index.md | 2 + docs/en/flight_modes_mc/altitude.md | 2 +- docs/en/flight_modes_mc/altitude_cruise.md | 45 +++++++++++++++++++ docs/en/flight_modes_mc/index.md | 4 +- docs/en/flight_modes_mc/manual_stabilized.md | 2 +- docs/en/releases/main.md | 7 ++- msg/versioned/VehicleStatus.msg | 2 +- src/drivers/osd/atxxxx/atxxxx.cpp | 4 ++ src/drivers/rc/crsf_rc/CrsfRc.cpp | 4 ++ src/drivers/rc_input/crsf_telemetry.cpp | 4 ++ src/lib/events/enums.json | 4 ++ src/lib/modes/ui.hpp | 5 ++- src/modules/commander/Commander.cpp | 8 +++- .../commander/ModeUtil/control_mode.cpp | 1 + .../commander/ModeUtil/conversions.hpp | 2 + .../commander/ModeUtil/mode_requirements.cpp | 7 +++ src/modules/commander/commander_params.c | 3 +- src/modules/commander/failsafe/failsafe.cpp | 5 ++- src/modules/commander/failsafe/failsafe.h | 3 +- src/modules/commander/module.yaml | 1 + src/modules/commander/px4_custom_mode.h | 7 ++- .../flight_mode_manager/CMakeLists.txt | 1 + .../flight_mode_manager/FlightModeManager.cpp | 11 +++++ .../tasks/AltitudeCruise/CMakeLists.txt | 6 +++ .../FlightTaskAltitudeCruise.cpp | 19 ++++++++ .../FlightTaskAltitudeCruise.hpp | 15 +++++++ .../FlightTaskManualAltitude.cpp | 18 ++++++-- .../FlightTaskManualAltitude.hpp | 2 + .../tasks/Utility/StickTiltXY.cpp | 23 ++++++++++ .../tasks/Utility/StickTiltXY.hpp | 6 +++ src/modules/fw_mode_manager/CMakeLists.txt | 2 +- .../fw_mode_manager/FixedWingModeManager.cpp | 11 ++--- .../fw_mode_manager/FixedWingModeManager.hpp | 2 - src/modules/manual_control/ManualControl.cpp | 1 + .../multicopter_stabilized_mode_params.c | 2 +- src/modules/navigator/navigator_main.cpp | 1 + 37 files changed, 216 insertions(+), 27 deletions(-) create mode 100644 docs/en/flight_modes_mc/altitude_cruise.md create mode 100644 src/modules/flight_mode_manager/tasks/AltitudeCruise/CMakeLists.txt create mode 100644 src/modules/flight_mode_manager/tasks/AltitudeCruise/FlightTaskAltitudeCruise.cpp create mode 100644 src/modules/flight_mode_manager/tasks/AltitudeCruise/FlightTaskAltitudeCruise.hpp diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index feb8bf2ecc..a5d0c37f6b 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -7,6 +7,7 @@ - [Position Mode (MC)](flight_modes_mc/position.md) - [Position Slow Mode (MC)](flight_modes_mc/position_slow.md) - [Altitude Mode (MC)](flight_modes_mc/altitude.md) + - [Altitude Cruise Mode (MC)](flight_modes_mc/altitude_cruise.md) - [Stabilized Mode (MC)](flight_modes_mc/manual_stabilized.md) - [Acro Mode (MC)](flight_modes_mc/acro.md) - [Orbit Mode (MC)](flight_modes_mc/orbit.md) diff --git a/docs/en/flight_modes_fw/index.md b/docs/en/flight_modes_fw/index.md index 8bd9e4b062..052bfe7dd3 100644 --- a/docs/en/flight_modes_fw/index.md +++ b/docs/en/flight_modes_fw/index.md @@ -17,6 +17,8 @@ Manual-Easy: Airspeed is actively controlled if an airspeed sensor is installed. - [Altitude](../flight_modes_fw/altitude.md) — Easiest and safest _non-GPS_ manual mode. The only difference compared to _Position mode_ is that the pilot always directly controls the roll angle of the plane and there is no automatic course holding. +- Altitude Cruise mode — It behaves exactly like _Altitude mode_, with the only difference being that the manual control failsafe can be disabled. This is done by setting the corresponding flag in [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT). In that case the current altitude, airspeed and heading (by leveling out the roll angle) are kept until the manual control link is regained or the mode is exited. +It is highly recommended to only disable the manual control loss failsafe for this mode if there is a stable data link connection to the vehicle at all times, or to enable the data link loss failsafe through [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT). - [Stabilized mode](../flight_modes_fw/stabilized.md) — The pilot directly commands the roll and pitch angle and the vehicle keeps the setpoint until the sticks are moved again. Thrust is directly set by the pilot. Turn coordination is still handled by the controller. diff --git a/docs/en/flight_modes_mc/altitude.md b/docs/en/flight_modes_mc/altitude.md index 13d54b9148..fda7dde9bb 100644 --- a/docs/en/flight_modes_mc/altitude.md +++ b/docs/en/flight_modes_mc/altitude.md @@ -21,7 +21,7 @@ The diagram below shows the mode behaviour visually (for a [mode 2 transmitter]( RC/manual mode like [Stabilized mode](../flight_modes_mc/manual_stabilized.md) but with _altitude stabilization_ (centred sticks level vehicle and hold it to fixed altitude). The horizontal position of the vehicle can move due to wind (or pre-existing momentum). -- Centered sticks (inside deadband): +- Centered sticks: - RPY sticks levels vehicle. - Throttle (~50%) holds current altitude steady against wind. - Outside center: diff --git a/docs/en/flight_modes_mc/altitude_cruise.md b/docs/en/flight_modes_mc/altitude_cruise.md new file mode 100644 index 0000000000..87728cc311 --- /dev/null +++ b/docs/en/flight_modes_mc/altitude_cruise.md @@ -0,0 +1,45 @@ +# Altitude Cruise Mode (Multicopter) + +   + +_Altitude Cruise mode_ is a _relatively_ easy-to-fly manual control mode in which roll and pitch sticks control vehicle movement in the left-right and forward-back directions (relative to the "front" of the vehicle), yaw stick controls rate of rotation over the horizontal plane, and throttle controls speed of ascent-descent. + +When the sticks are released/centered the vehicle will keep the current tilt and heading angle and maintain the current _altitude_. +If moving in the horizontal plane the vehicle will accelerate until the wind resistance equals the acceleration caused by the set tilt angle. +The vehicle will then continue to move with a constant velocity (unlike for Altitude mode, in which the vehicle will eventually slow down and stop). +If the wind blows the aircraft will drift in the direction of the wind even if flying perfectly level. + +:::tip +_Altitude Cruise mode_ is intended for long distance flights where the same tilt angle is kept for a long period of time. It is just like [Altitude](../flight_modes_mc/altitude.md) mode but does not go back to level tilt when the sticks are released. +::: + +The diagram below shows the mode behaviour visually (for a [mode 2 transmitter](../getting_started/rc_transmitter_receiver.md#transmitter_modes)). + +![Altitude Control MC - Mode2 RC Controller](../../assets/flight_modes/altitude_mc.png) + +## Technical Summary + +A manual mode that is similar to [Altitude mode](../flight_modes_mc/altitude.md) but with different interpretation of roll and pitch sticks. + +- Centered sticks: + - Roll/Pitch sticks: the current tilt is kept. + - Yaw: the current heading is kept. + - Throttle (~50%) holds current altitude. +- Outside center: + - Roll/Pitch sticks control the rate of change of the tilt angle, resulting in corresponding left-right and forward-back movement. A maximum stick deflection results in a tilting rate setpoint to go from level to max tilt within 0.5 seconds. + - Yaw stick deflection rotates the tilt angle either left or right, causing the vehicle to change course. It is _not_ causing a direct rotation around the body yaw axis like in [Acro mode](../flight_modes_mc/acro.md). + - Throttle stick controls up/down speed with a predetermined maximum rate (and movement speed in other axes). +- Takeoff: + - When landed, the vehicle will take off if the throttle stick is raised above 62.5% percent (of the full range from bottom). +- Manual control input is required (such as RC control, joystick) to enter this mode. Other than in all other manual modes, it's though possible to disable the manual control loss failsafe by setting the corresponding flag in [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT). In that case the current altitude, tilt and heading are kept until the manual control link is regained or the mode is exited. + It is highly recommended to only disable the manual control loss failsafe for this mode if there is a stable data link connection to the vehicle at all times, and to enable the data link loss failsafe through [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT). + +## Parameters + +Most of the relevant parameters are already covered in the corresponding section in the [Altitude mode](../flight_modes_mc/altitude.md). Here a list of parameters of particular importance for Altitude Cruise. + +| Parameter | Description | +| ----------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------- | +| [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | The manual control failsafe can be disabled for Altitude Cruise by setting the corresponding bit in this parameter. | +| [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT) | Data link lost failsafe action. Recommended to set if the manual control failsafe is disabled to avoid fly-aways. | +| [MPC_MAN_TILT_MAX](../advanced_config/parameter_reference.md#MPC_MAN_TILT_MAX) | The maximum tilt angle the vehicle will go to. At max stick deflection, it will take 0.5 seconds from level flight to this tilt angle. | diff --git a/docs/en/flight_modes_mc/index.md b/docs/en/flight_modes_mc/index.md index c0fe5405f2..bbab81b23d 100644 --- a/docs/en/flight_modes_mc/index.md +++ b/docs/en/flight_modes_mc/index.md @@ -21,10 +21,12 @@ Manual-Easy: - [Stabilized mode](../flight_modes_mc/manual_stabilized.md) — Releasing the sticks levels and maintains the vehicle horizontal posture (but not altitude or position). The vehicle will continue to move with momentum, and both altitude and horizontal position may be affected by wind. This mode is also used if "Manual mode" is selected in a ground station. +- [Altitude Cruise mode](../flight_modes_mc/altitude_cruise.md) — Very similar to _Altitude mode_, with the difference that when the roll and pitch sticks are released the vehicle does not level out but keeps the tilt until further inputs are given. + Additionally it is possible to disable the manual control failsafe for this mode, having the vehicle continue on it's set path even if there are no new control inputs. Manual-Acrobatic -- [Acro](../flight_modes_mc/acro.md) — Manual mode for performing acrobatic maneuvers, such as rolls and loops. +- [Acro](../flight_modes_mc/acro.md) — Manual mode for performing acrobatic manoeuvrers, such as rolls and loops. Releasing the sticks stops the vehicle rotating in the roll, pitch, yaw axes, but does not otherwise stabilise the vehicle. Autonomous: diff --git a/docs/en/flight_modes_mc/manual_stabilized.md b/docs/en/flight_modes_mc/manual_stabilized.md index 9d3f29112d..36a9ae345f 100644 --- a/docs/en/flight_modes_mc/manual_stabilized.md +++ b/docs/en/flight_modes_mc/manual_stabilized.md @@ -31,7 +31,7 @@ Throttle is rescaled (see [below](#params)) and passed directly to control alloc The autopilot controls the attitude, meaning it regulates the roll and pitch angles to zero when the RC sticks are centered inside the controller deadzone (consequently leveling-out the attitude). The autopilot does not compensate for drift due to wind (or other sources). -- Centered sticks (inside deadband): +- Centered sticks: - Roll/Pitch sticks level vehicle. - Outside center: - Roll/Pitch sticks control tilt angle in those orientations, resulting in corresponding left-right and forward-back movement. diff --git a/docs/en/releases/main.md b/docs/en/releases/main.md index 84fb901659..5bbc07873a 100644 --- a/docs/en/releases/main.md +++ b/docs/en/releases/main.md @@ -44,7 +44,9 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Control -- TBD +- Added new flight mode(s): [Altitude Cruise (MC)](../flight_modes_mc/altitude_cruise.md), Altitude Cruise (FW). + For fixed-wing the mode behaves the same as Altitude mode but you can disable the manual control loss failsafe. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise + ](https://github.com/PX4/PX4-Autopilot/pull/25435)). ### Estimation @@ -72,7 +74,8 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Multi-Rotor -- TBD +- Removed parameters `MPC_{XY/Z/YAW}_MAN_EXPO` and use default value instead, as they were not deemed necessary anymore. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)). +- Renamed `MPC_HOLD_DZ` to `MAN_DEADZONE` to have it globally available in modes that allow for a dead zone. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)). ### VTOL diff --git a/msg/versioned/VehicleStatus.msg b/msg/versioned/VehicleStatus.msg index f433d564e9..0dffdc2c92 100644 --- a/msg/versioned/VehicleStatus.msg +++ b/msg/versioned/VehicleStatus.msg @@ -41,7 +41,7 @@ uint8 NAVIGATION_STATE_AUTO_LOITER = 4 # Auto loiter mode uint8 NAVIGATION_STATE_AUTO_RTL = 5 # Auto return to launch mode uint8 NAVIGATION_STATE_POSITION_SLOW = 6 uint8 NAVIGATION_STATE_FREE5 = 7 -uint8 NAVIGATION_STATE_FREE4 = 8 +uint8 NAVIGATION_STATE_ALTITUDE_CRUISE = 8 # Altitude with Cruise mode uint8 NAVIGATION_STATE_FREE3 = 9 uint8 NAVIGATION_STATE_ACRO = 10 # Acro mode uint8 NAVIGATION_STATE_FREE2 = 11 diff --git a/src/drivers/osd/atxxxx/atxxxx.cpp b/src/drivers/osd/atxxxx/atxxxx.cpp index a5acabd391..6f85fcd383 100644 --- a/src/drivers/osd/atxxxx/atxxxx.cpp +++ b/src/drivers/osd/atxxxx/atxxxx.cpp @@ -387,6 +387,10 @@ OSDatxxxx::get_flight_mode(uint8_t nav_state) flight_mode = "ALTITUDE"; break; + case vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE: + flight_mode = "CRUISE"; + break; + case vehicle_status_s::NAVIGATION_STATE_POSCTL: flight_mode = "POSITION"; break; diff --git a/src/drivers/rc/crsf_rc/CrsfRc.cpp b/src/drivers/rc/crsf_rc/CrsfRc.cpp index 9db8911636..9e311da18e 100644 --- a/src/drivers/rc/crsf_rc/CrsfRc.cpp +++ b/src/drivers/rc/crsf_rc/CrsfRc.cpp @@ -281,6 +281,10 @@ void CrsfRc::Run() flight_mode = "Altitude"; break; + case vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE: + flight_mode = "Altitude Cruise"; + break; + case vehicle_status_s::NAVIGATION_STATE_POSCTL: flight_mode = "Position"; break; diff --git a/src/drivers/rc_input/crsf_telemetry.cpp b/src/drivers/rc_input/crsf_telemetry.cpp index 60286e0f40..fb557f8497 100644 --- a/src/drivers/rc_input/crsf_telemetry.cpp +++ b/src/drivers/rc_input/crsf_telemetry.cpp @@ -141,6 +141,10 @@ bool CRSFTelemetry::send_flight_mode() flight_mode = "Altitude"; break; + case vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE: + flight_mode = "Altitude Cruise"; + break; + case vehicle_status_s::NAVIGATION_STATE_POSCTL: flight_mode = "Position"; break; diff --git a/src/lib/events/enums.json b/src/lib/events/enums.json index 3b73cff62c..c3cbc2578a 100644 --- a/src/lib/events/enums.json +++ b/src/lib/events/enums.json @@ -604,6 +604,10 @@ "name": "external8", "description": "External 8" }, + "24": { + "name": "altitude_cruise", + "description": "Altitude Cruise" + }, "255": { "name": "unknown", "description": "[Unknown]" diff --git a/src/lib/modes/ui.hpp b/src/lib/modes/ui.hpp index 9e4156ae00..e81a3609ad 100644 --- a/src/lib/modes/ui.hpp +++ b/src/lib/modes/ui.hpp @@ -47,6 +47,7 @@ static inline uint32_t getValidNavStates() { return (1u << vehicle_status_s::NAVIGATION_STATE_MANUAL) | (1u << vehicle_status_s::NAVIGATION_STATE_ALTCTL) | + (1u << vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE) | (1u << vehicle_status_s::NAVIGATION_STATE_POSCTL) | (1u << vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION) | (1u << vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER) | @@ -75,7 +76,7 @@ const char *const nav_state_names[vehicle_status_s::NAVIGATION_STATE_MAX] = { "Return", "Position Slow", "7: unallocated", - "8: unallocated", + "Altitude Cruise", "9: unallocated", "Acro", "11: UNUSED", @@ -108,6 +109,8 @@ static inline bool isAdvanced(uint8_t nav_state) switch (nav_state) { case vehicle_status_s::NAVIGATION_STATE_ALTCTL: return false; + case vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE: return false; + case vehicle_status_s::NAVIGATION_STATE_POSCTL: return false; case vehicle_status_s::NAVIGATION_STATE_EXTERNAL1: return false; diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 0e2c50ec4f..169cc34587 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -380,6 +380,9 @@ int Commander::custom_command(int argc, char *argv[]) send_vehicle_command(vehicle_command_s::VEHICLE_CMD_DO_SET_MODE, 1, PX4_CUSTOM_MAIN_MODE_POSCTL, PX4_CUSTOM_SUB_MODE_POSCTL_SLOW); + } else if (!strcmp(argv[1], "altitude_cruise")) { + send_vehicle_command(vehicle_command_s::VEHICLE_CMD_DO_SET_MODE, 1, PX4_CUSTOM_MAIN_MODE_ALTITUDE_CRUISE); + } else if (!strcmp(argv[1], "auto:mission")) { send_vehicle_command(vehicle_command_s::VEHICLE_CMD_DO_SET_MODE, 1, PX4_CUSTOM_MAIN_MODE_AUTO, PX4_CUSTOM_SUB_MODE_AUTO_MISSION); @@ -794,6 +797,9 @@ Commander::handle_command(const vehicle_command_s &cmd) } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ALTCTL) { desired_nav_state = vehicle_status_s::NAVIGATION_STATE_ALTCTL; + } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ALTITUDE_CRUISE) { + desired_nav_state = vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE; + } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_POSCTL) { switch (custom_sub_mode) { default: @@ -3026,7 +3032,7 @@ The commander module contains the state machine for mode switching and failsafe PRINT_MODULE_USAGE_COMMAND("land"); PRINT_MODULE_USAGE_COMMAND_DESCR("transition", "VTOL transition"); PRINT_MODULE_USAGE_COMMAND_DESCR("mode", "Change flight mode"); - PRINT_MODULE_USAGE_ARG("manual|acro|offboard|stabilized|altctl|posctl|position:slow|auto:mission|auto:loiter|auto:rtl|auto:takeoff|auto:land|auto:precland|ext1", + PRINT_MODULE_USAGE_ARG("manual|acro|offboard|stabilized|altctl|posctl|altitude_cruise|position:slow|auto:mission|auto:loiter|auto:rtl|auto:takeoff|auto:land|auto:precland|ext1", "Flight mode", false); PRINT_MODULE_USAGE_COMMAND("pair"); PRINT_MODULE_USAGE_COMMAND("termination"); diff --git a/src/modules/commander/ModeUtil/control_mode.cpp b/src/modules/commander/ModeUtil/control_mode.cpp index fbebc7b93d..59858a51e8 100644 --- a/src/modules/commander/ModeUtil/control_mode.cpp +++ b/src/modules/commander/ModeUtil/control_mode.cpp @@ -63,6 +63,7 @@ void getVehicleControlMode(uint8_t nav_state, uint8_t vehicle_type, break; case vehicle_status_s::NAVIGATION_STATE_ALTCTL: + case vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE: vehicle_control_mode.flag_control_manual_enabled = true; vehicle_control_mode.flag_control_altitude_enabled = true; vehicle_control_mode.flag_control_climb_rate_enabled = true; diff --git a/src/modules/commander/ModeUtil/conversions.hpp b/src/modules/commander/ModeUtil/conversions.hpp index 045db4570f..e6bb4e2102 100644 --- a/src/modules/commander/ModeUtil/conversions.hpp +++ b/src/modules/commander/ModeUtil/conversions.hpp @@ -50,6 +50,8 @@ static inline navigation_mode_t navigation_mode(uint8_t nav_state) case vehicle_status_s::NAVIGATION_STATE_ALTCTL: return navigation_mode_t::altctl; + case vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE: return navigation_mode_t::altitude_cruise; + case vehicle_status_s::NAVIGATION_STATE_POSCTL: return navigation_mode_t::posctl; case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION: return navigation_mode_t::auto_mission; diff --git a/src/modules/commander/ModeUtil/mode_requirements.cpp b/src/modules/commander/ModeUtil/mode_requirements.cpp index 9e64c529f2..850a0cf6e9 100644 --- a/src/modules/commander/ModeUtil/mode_requirements.cpp +++ b/src/modules/commander/ModeUtil/mode_requirements.cpp @@ -69,6 +69,13 @@ void getModeRequirements(uint8_t vehicle_type, failsafe_flags_s &flags) setRequirement(vehicle_status_s::NAVIGATION_STATE_ALTCTL, flags.mode_req_local_alt); setRequirement(vehicle_status_s::NAVIGATION_STATE_ALTCTL, flags.mode_req_manual_control); + // NAVIGATION_STATE_ALTITUDE_CRUISE + setRequirement(vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE, flags.mode_req_angular_velocity); + setRequirement(vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE, flags.mode_req_attitude); + setRequirement(vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE, flags.mode_req_local_alt); + setRequirement(vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE, + flags.mode_req_manual_control); // COM_RCL_EXCEPT can override this + // NAVIGATION_STATE_POSCTL setRequirement(vehicle_status_s::NAVIGATION_STATE_POSCTL, flags.mode_req_angular_velocity); setRequirement(vehicle_status_s::NAVIGATION_STATE_POSCTL, flags.mode_req_attitude); diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index 1e194ac5df..45da253f11 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -613,11 +613,12 @@ PARAM_DEFINE_INT32(NAV_RCL_ACT, 2); * External modes requiring stick input will still failsafe. * * @min 0 - * @max 15 + * @max 31 * @bit 0 Mission * @bit 1 Hold * @bit 2 Offboard * @bit 3 External Mode + * @bit 4 Altitude Cruise * @group Commander */ PARAM_DEFINE_INT32(COM_RCL_EXCEPT, 0); diff --git a/src/modules/commander/failsafe/failsafe.cpp b/src/modules/commander/failsafe/failsafe.cpp index cdc770190c..d86e672d7e 100644 --- a/src/modules/commander/failsafe/failsafe.cpp +++ b/src/modules/commander/failsafe/failsafe.cpp @@ -471,6 +471,9 @@ void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state, const bool rc_loss_ignored_takeoff = (state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF || state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF) && (_param_com_rcl_except.get() & (int)ManualControlLossExceptionBits::Hold); + const bool rc_loss_ignored_altitude_cruise = (state.user_intended_mode == + vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE + && (_param_com_rcl_except.get() & (int)ManualControlLossExceptionBits::AltitudeCruise)); const bool rc_loss_ignored_external_mode = (state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_EXTERNAL1 || @@ -485,7 +488,7 @@ void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state, const bool rc_loss_ignored = rc_loss_ignored_mission || rc_loss_ignored_loiter || rc_loss_ignored_offboard || rc_loss_ignored_takeoff || rc_loss_ignored_external_mode || ignore_any_link_loss_vtol_takeoff_fixedwing - || _manual_control_lost_at_arming; + || _manual_control_lost_at_arming || rc_loss_ignored_altitude_cruise; if (_param_com_rc_in_mode.get() != int32_t(RcInMode::StickInputDisabled) && !rc_loss_ignored) { CHECK_FAILSAFE(status_flags, manual_control_signal_lost, diff --git a/src/modules/commander/failsafe/failsafe.h b/src/modules/commander/failsafe/failsafe.h index f9382e0428..e3849bf8b1 100644 --- a/src/modules/commander/failsafe/failsafe.h +++ b/src/modules/commander/failsafe/failsafe.h @@ -57,7 +57,8 @@ private: Mission = (1 << 0), Hold = (1 << 1), Offboard = (1 << 2), - ExternalMode = (1 << 3) + ExternalMode = (1 << 3), + AltitudeCruise = (1 << 4) }; enum class DatalinkLossExceptionBits : int32_t { diff --git a/src/modules/commander/module.yaml b/src/modules/commander/module.yaml index d2113d9359..67f97e3a7e 100644 --- a/src/modules/commander/module.yaml +++ b/src/modules/commander/module.yaml @@ -38,6 +38,7 @@ parameters: 8: Stabilized 12: Follow Me 13: Precision Land + 16: Altitude Cruise 100: External Mode 1 101: External Mode 2 102: External Mode 3 diff --git a/src/modules/commander/px4_custom_mode.h b/src/modules/commander/px4_custom_mode.h index e4936982ff..fc901d1492 100644 --- a/src/modules/commander/px4_custom_mode.h +++ b/src/modules/commander/px4_custom_mode.h @@ -51,7 +51,8 @@ enum PX4_CUSTOM_MAIN_MODE { PX4_CUSTOM_MAIN_MODE_STABILIZED, PX4_CUSTOM_MAIN_MODE_RATTITUDE_LEGACY, PX4_CUSTOM_MAIN_MODE_SIMPLE, /* unused, but reserved for future use */ - PX4_CUSTOM_MAIN_MODE_TERMINATION + PX4_CUSTOM_MAIN_MODE_TERMINATION, + PX4_CUSTOM_MAIN_MODE_ALTITUDE_CRUISE }; enum PX4_CUSTOM_SUB_MODE_AUTO { @@ -112,6 +113,10 @@ static inline union px4_custom_mode get_px4_custom_mode(uint8_t nav_state) custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ALTCTL; break; + case vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE: + custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ALTITUDE_CRUISE; + break; + case vehicle_status_s::NAVIGATION_STATE_POSCTL: custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_POSCTL; break; diff --git a/src/modules/flight_mode_manager/CMakeLists.txt b/src/modules/flight_mode_manager/CMakeLists.txt index 84ccba6ac0..efd7d9a261 100644 --- a/src/modules/flight_mode_manager/CMakeLists.txt +++ b/src/modules/flight_mode_manager/CMakeLists.txt @@ -48,6 +48,7 @@ list(APPEND flight_tasks_all ManualAltitudeSmoothVel ManualPosition Transition + AltitudeCruise ) if(NOT px4_constrained_flash_build) diff --git a/src/modules/flight_mode_manager/FlightModeManager.cpp b/src/modules/flight_mode_manager/FlightModeManager.cpp index f17e00aa96..d69ca84c25 100644 --- a/src/modules/flight_mode_manager/FlightModeManager.cpp +++ b/src/modules/flight_mode_manager/FlightModeManager.cpp @@ -249,6 +249,17 @@ void FlightModeManager::start_flight_task() matching_task_running = matching_task_running && !task_failure; } + // Altitude cruise + if (_vehicle_status_sub.get().nav_state == vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE) { + found_some_task = true; + FlightTaskError error = FlightTaskError::NoError; + + error = switchTask(FlightTaskIndex::AltitudeCruise); + + task_failure = (error != FlightTaskError::NoError); + matching_task_running = matching_task_running && !task_failure; + } + // Emergency descend if (nav_state_descend || task_failure) { found_some_task = true; diff --git a/src/modules/flight_mode_manager/tasks/AltitudeCruise/CMakeLists.txt b/src/modules/flight_mode_manager/tasks/AltitudeCruise/CMakeLists.txt new file mode 100644 index 0000000000..238b5bbd0f --- /dev/null +++ b/src/modules/flight_mode_manager/tasks/AltitudeCruise/CMakeLists.txt @@ -0,0 +1,6 @@ +px4_add_library(FlightTaskAltitudeCruise + FlightTaskAltitudeCruise.cpp +) + +target_link_libraries(FlightTaskAltitudeCruise PUBLIC FlightTaskManualAltitudeSmoothVel) +target_include_directories(FlightTaskAltitudeCruise PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/flight_mode_manager/tasks/AltitudeCruise/FlightTaskAltitudeCruise.cpp b/src/modules/flight_mode_manager/tasks/AltitudeCruise/FlightTaskAltitudeCruise.cpp new file mode 100644 index 0000000000..3e42cdf2c4 --- /dev/null +++ b/src/modules/flight_mode_manager/tasks/AltitudeCruise/FlightTaskAltitudeCruise.cpp @@ -0,0 +1,19 @@ +#include "FlightTaskAltitudeCruise.hpp" + +FlightTaskAltitudeCruise::FlightTaskAltitudeCruise() +{ + _sticks_data_required = false; // disable stick requirement to not report flight task failure when they're lost +} + +void FlightTaskAltitudeCruise::reActivate() +{ + FlightTaskManualAltitudeSmoothVel::reActivate(); + _stick_tilt_xy.reset(); +} + +void FlightTaskAltitudeCruise::_updateXYSetpoint() +{ + _acceleration_setpoint.xy() = + _stick_tilt_xy.generateAccelerationSetpointsForAltitudeCruise( + _sticks.getPitchRoll(), _deltatime, _yaw, _yaw_setpoint); +} diff --git a/src/modules/flight_mode_manager/tasks/AltitudeCruise/FlightTaskAltitudeCruise.hpp b/src/modules/flight_mode_manager/tasks/AltitudeCruise/FlightTaskAltitudeCruise.hpp new file mode 100644 index 0000000000..1915b20304 --- /dev/null +++ b/src/modules/flight_mode_manager/tasks/AltitudeCruise/FlightTaskAltitudeCruise.hpp @@ -0,0 +1,15 @@ +#pragma once + +#include "FlightTaskManualAltitudeSmoothVel.hpp" + +class FlightTaskAltitudeCruise : public FlightTaskManualAltitudeSmoothVel +{ +public: + FlightTaskAltitudeCruise(); + virtual ~FlightTaskAltitudeCruise() = default; + + void reActivate() override; + +protected: + void _updateXYSetpoint() override; +}; diff --git a/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.cpp b/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.cpp index 1d049b344a..778cea55f2 100644 --- a/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.cpp +++ b/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.cpp @@ -274,13 +274,25 @@ void FlightTaskManualAltitude::_ekfResetHandlerHagl(float delta_hagl) void FlightTaskManualAltitude::_updateSetpoints() { - _stick_yaw.generateYawSetpoint(_yawspeed_setpoint, _yaw_setpoint, _sticks.getYawExpo(), _yaw, _deltatime, _unaided_yaw); - _acceleration_setpoint.xy() = _stick_tilt_xy.generateAccelerationSetpoints(_sticks.getPitchRoll(), _deltatime, _yaw, - _yaw_setpoint); + _updateYawSetpoint(); + _updateXYSetpoint(); _updateAltitudeLock(); _respectGroundSlowdown(); } +void FlightTaskManualAltitude::_updateYawSetpoint() +{ + _stick_yaw.generateYawSetpoint(_yawspeed_setpoint, _yaw_setpoint, + _sticks.getYawExpo(), _yaw, _deltatime, + _unaided_yaw); +} + +void FlightTaskManualAltitude::_updateXYSetpoint() +{ + _acceleration_setpoint.xy() = _stick_tilt_xy.generateAccelerationSetpoints( + _sticks.getPitchRoll(), _deltatime, _yaw, _yaw_setpoint); +} + bool FlightTaskManualAltitude::_checkTakeoff() { // stick is deflected above 65% throttle (throttle stick is in the range [-1,1]) diff --git a/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.hpp b/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.hpp index 6c04d7388a..92648daf7c 100644 --- a/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.hpp +++ b/src/modules/flight_mode_manager/tasks/ManualAltitude/FlightTaskManualAltitude.hpp @@ -60,6 +60,8 @@ protected: void _ekfResetHandlerHagl(float delta_hagl) override; virtual void _updateSetpoints(); /**< updates all setpoints */ + virtual void _updateYawSetpoint(); + virtual void _updateXYSetpoint(); virtual void _scaleSticks(); /**< scales sticks to velocity in z */ bool _checkTakeoff() override; void _updateConstraintsFromEstimator(); diff --git a/src/modules/flight_mode_manager/tasks/Utility/StickTiltXY.cpp b/src/modules/flight_mode_manager/tasks/Utility/StickTiltXY.cpp index 32ad13bdf8..6148bb985d 100644 --- a/src/modules/flight_mode_manager/tasks/Utility/StickTiltXY.cpp +++ b/src/modules/flight_mode_manager/tasks/Utility/StickTiltXY.cpp @@ -44,6 +44,11 @@ StickTiltXY::StickTiltXY(ModuleParams *parent) : updateParams(); } +void StickTiltXY::reset() +{ + _altitude_cruise_acceleration.setZero(); +} + void StickTiltXY::updateParams() { ModuleParams::updateParams(); @@ -62,3 +67,21 @@ Vector2f StickTiltXY::generateAccelerationSetpoints(Vector2f stick_xy, const flo Sticks::rotateIntoHeadingFrameXY(stick_xy, yaw, yaw_setpoint); return stick_xy * _maximum_acceleration; } + +Vector2f StickTiltXY::generateAccelerationSetpointsForAltitudeCruise(Vector2f stick_xy, const float dt, const float yaw, + const float yaw_setpoint) +{ + Sticks::limitStickUnitLengthXY(stick_xy); + const Vector2f increment = stick_xy; + // at full stick deflection it takes 1s from -tilt_max to tilt_max + _altitude_cruise_acceleration += increment * _maximum_acceleration * 2.f * dt; + + if (_altitude_cruise_acceleration.longerThan(_maximum_acceleration)) { + _altitude_cruise_acceleration = + _altitude_cruise_acceleration.unit_or_zero() * _maximum_acceleration; + } + + Vector2f global_altitude_cruise_acceleration = _altitude_cruise_acceleration; + Sticks::rotateIntoHeadingFrameXY(global_altitude_cruise_acceleration, yaw, yaw_setpoint); + return global_altitude_cruise_acceleration; +} diff --git a/src/modules/flight_mode_manager/tasks/Utility/StickTiltXY.hpp b/src/modules/flight_mode_manager/tasks/Utility/StickTiltXY.hpp index f5caea8550..992c975224 100644 --- a/src/modules/flight_mode_manager/tasks/Utility/StickTiltXY.hpp +++ b/src/modules/flight_mode_manager/tasks/Utility/StickTiltXY.hpp @@ -62,11 +62,17 @@ public: */ matrix::Vector2f generateAccelerationSetpoints(matrix::Vector2f stick_xy, const float dt, const float yaw, const float yaw_setpoint); + + matrix::Vector2f generateAccelerationSetpointsForAltitudeCruise(matrix::Vector2f stick_xy, const float dt, + const float yaw, const float yaw_setpoint); + + void reset(); private: void updateParams() override; float _maximum_acceleration{0.f}; AlphaFilter _man_input_filter; + matrix::Vector2f _altitude_cruise_acceleration{}; DEFINE_PARAMETERS( (ParamFloat) _param_mpc_man_tilt_max, ///< maximum tilt allowed for manual flight diff --git a/src/modules/fw_mode_manager/CMakeLists.txt b/src/modules/fw_mode_manager/CMakeLists.txt index dec814aebc..dc32389580 100644 --- a/src/modules/fw_mode_manager/CMakeLists.txt +++ b/src/modules/fw_mode_manager/CMakeLists.txt @@ -41,7 +41,7 @@ set(POSCONTROL_DEPENDENCIES SlewRate tecs motion_planning - performance_model + performance_model Sticks ) diff --git a/src/modules/fw_mode_manager/FixedWingModeManager.cpp b/src/modules/fw_mode_manager/FixedWingModeManager.cpp index b5e6d758c1..9d43e1f637 100644 --- a/src/modules/fw_mode_manager/FixedWingModeManager.cpp +++ b/src/modules/fw_mode_manager/FixedWingModeManager.cpp @@ -1953,17 +1953,12 @@ FixedWingModeManager::Run() perf_begin(_loop_perf); - if (_vehicle_status_sub.updated()) { - - if (_vehicle_status_sub.update(&_vehicle_status)) { - _nav_state = _vehicle_status.nav_state; - } - } + _vehicle_status_sub.update(&_vehicle_status); /* only run controller if position changed and we are not running an external mode*/ - const bool is_external_nav_state = (_nav_state >= vehicle_status_s::NAVIGATION_STATE_EXTERNAL1) - && (_nav_state <= vehicle_status_s::NAVIGATION_STATE_EXTERNAL8); + const bool is_external_nav_state = (_vehicle_status.nav_state >= vehicle_status_s::NAVIGATION_STATE_EXTERNAL1) + && (_vehicle_status.nav_state <= vehicle_status_s::NAVIGATION_STATE_EXTERNAL8); if (is_external_nav_state) { // this will cause the configuration handler to publish immediately the next time an internal flight diff --git a/src/modules/fw_mode_manager/FixedWingModeManager.hpp b/src/modules/fw_mode_manager/FixedWingModeManager.hpp index 71fe564de7..fcc6270a22 100644 --- a/src/modules/fw_mode_manager/FixedWingModeManager.hpp +++ b/src/modules/fw_mode_manager/FixedWingModeManager.hpp @@ -246,8 +246,6 @@ private: // VEHICLE STATES - uint8_t _nav_state; - double _current_latitude{0}; double _current_longitude{0}; float _current_altitude{0.f}; diff --git a/src/modules/manual_control/ManualControl.cpp b/src/modules/manual_control/ManualControl.cpp index 082b2ccaa3..517639100c 100644 --- a/src/modules/manual_control/ManualControl.cpp +++ b/src/modules/manual_control/ManualControl.cpp @@ -590,6 +590,7 @@ int8_t ManualControl::navStateFromParam(int32_t param_value) case 13: return vehicle_status_s::NAVIGATION_STATE_AUTO_PRECLAND; case 14: return vehicle_status_s::NAVIGATION_STATE_ORBIT; case 15: return vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF; + case 16: return vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE; case 100: return vehicle_status_s::NAVIGATION_STATE_EXTERNAL1; case 101: return vehicle_status_s::NAVIGATION_STATE_EXTERNAL2; diff --git a/src/modules/mc_pos_control/multicopter_stabilized_mode_params.c b/src/modules/mc_pos_control/multicopter_stabilized_mode_params.c index 6229b18bc5..c804a034bb 100644 --- a/src/modules/mc_pos_control/multicopter_stabilized_mode_params.c +++ b/src/modules/mc_pos_control/multicopter_stabilized_mode_params.c @@ -32,7 +32,7 @@ ****************************************************************************/ /** - * Maximal tilt angle in Stabilized or Altitude mode + * Maximal tilt angle in Stabilized, Altitude and Altitude Cruise mode * * @unit deg * @min 1 diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 7ee9bcaabe..69ca9896d4 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -823,6 +823,7 @@ void Navigator::run() case vehicle_status_s::NAVIGATION_STATE_MANUAL: case vehicle_status_s::NAVIGATION_STATE_ACRO: case vehicle_status_s::NAVIGATION_STATE_ALTCTL: + case vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE: case vehicle_status_s::NAVIGATION_STATE_POSCTL: case vehicle_status_s::NAVIGATION_STATE_DESCEND: case vehicle_status_s::NAVIGATION_STATE_TERMINATION: From 361d66bb44b7adebe82606c616d56bd663e9d14b Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 15 Sep 2025 16:30:27 +0200 Subject: [PATCH 054/812] ekf2: add reporting of gnss_vel status flag --- msg/EstimatorStatus.msg | 3 ++- msg/EstimatorStatusFlags.msg | 1 + src/modules/ekf2/EKF2.cpp | 1 + 3 files changed, 4 insertions(+), 1 deletion(-) diff --git a/msg/EstimatorStatus.msg b/msg/EstimatorStatus.msg index 3de2bfd722..b7933afdec 100644 --- a/msg/EstimatorStatus.msg +++ b/msg/EstimatorStatus.msg @@ -47,7 +47,8 @@ uint8 CS_SYNTHETIC_MAG_Z = 25 # 25 - true when we are using a synthesized measur uint8 CS_VEHICLE_AT_REST = 26 # 26 - true when the vehicle is at rest uint8 CS_GPS_YAW_FAULT = 27 # 27 - true when the GNSS heading has been declared faulty and is no longer being used uint8 CS_RNG_FAULT = 28 # 28 - true when the range finder has been declared faulty and is no longer being used -uint8 CS_GNSS_VEL = 44 # 44 - true if GNSS velocity measurements are being fused +uint8 CS_GNSS_VEL = 44 # 44 - true if GNSS velocity measurement fusion is intended +uint8 CS_GNSS_FAULT = 45 # 45 - true if GNSS measurements have been declared faulty and are no longer used uint32 filter_fault_flags # Bitmask to indicate EKF internal faults # 0 - true if the fusion of the magnetometer X-axis has encountered a numerical error diff --git a/msg/EstimatorStatusFlags.msg b/msg/EstimatorStatusFlags.msg index 8ab5b3d3e4..f22e2b727c 100644 --- a/msg/EstimatorStatusFlags.msg +++ b/msg/EstimatorStatusFlags.msg @@ -49,6 +49,7 @@ bool cs_valid_fake_pos # 41 - true if a valid constant position is bein bool cs_constant_pos # 42 - true if the vehicle is at a constant position bool cs_baro_fault # 43 - true when the current baro has been declared faulty and is no longer being used bool cs_gnss_vel # 44 - true if GNSS velocity measurement fusion is intended +bool cs_gnss_fault # 45 - true if GNSS measurements have been declared faulty and are no longer used # fault status uint32 fault_status_changes # number of filter fault status (fs) changes diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 40b642c9b0..b40601bdd0 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1935,6 +1935,7 @@ void EKF2::PublishStatusFlags(const hrt_abstime ×tamp) status_flags.cs_constant_pos = _ekf.control_status_flags().constant_pos; status_flags.cs_baro_fault = _ekf.control_status_flags().baro_fault; status_flags.cs_gnss_vel = _ekf.control_status_flags().gnss_vel; + status_flags.cs_gnss_fault = _ekf.control_status_flags().gnss_fault; status_flags.fault_status_changes = _filter_fault_status_changes; status_flags.fs_bad_mag_x = _ekf.fault_status_flags().bad_mag_x; From eba0b999502f416f5e7fdbf0635dbaa1826f2c57 Mon Sep 17 00:00:00 2001 From: bresch Date: Tue, 2 Sep 2025 13:14:20 +0200 Subject: [PATCH 055/812] ekf2: remove unnecessary code The delta angles are now correctly accumulated in case multiple resets are triggered during the same epoch --- src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp | 8 -------- .../ekf2/EKF/aid_sources/magnetometer/mag_control.cpp | 2 -- 2 files changed, 10 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp index d265a0bc26..76936556a4 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp @@ -522,14 +522,6 @@ bool Ekf::resetYawToEKFGSF() return false; } - // don't allow reset if there's just been a yaw reset - const bool yaw_alignment_changed = (_control_status_prev.flags.yaw_align != _control_status.flags.yaw_align); - const bool quat_reset = (_state_reset_status.reset_count.quat != _state_reset_count_prev.quat); - - if (yaw_alignment_changed || quat_reset) { - return false; - } - ECL_INFO("yaw estimator reset heading %.3f -> %.3f rad", (double)getEulerYaw(_R_to_earth), (double)_yawEstimator.getYaw()); diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp index 991f7bc75f..d178bd8ebf 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -593,8 +593,6 @@ void Ekf::resetMagHeading(const Vector3f &mag) // update quaternion states and corresponding covarainces resetQuatStateYaw(yaw_new, yaw_new_variance); - _time_last_heading_fuse = _time_delayed_us; - _mag_heading_innov_lpf.reset(0.f); _control_status.flags.mag_heading_consistent = true; } From 82308da18d5e17c4acc83874f00f6b1f254d251d Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 3 Sep 2025 10:36:13 +0200 Subject: [PATCH 056/812] ekf2: support heading external update from MAV_CMD_EXTERNAL_ATTITUDE_ESTIMATE --- docs/zh/msg_docs/EstimatorStatusFlags.md | 1 + msg/EstimatorStatus.msg | 1 + msg/EstimatorStatusFlags.msg | 1 + msg/versioned/VehicleCommand.msg | 1 + src/modules/commander/Commander.cpp | 19 +++++++ .../aid_sources/magnetometer/mag_control.cpp | 8 +-- src/modules/ekf2/EKF/common.h | 1 + src/modules/ekf2/EKF/ekf.h | 22 ++++++++- src/modules/ekf2/EKF/yaw_fusion.cpp | 49 ++++++++++++++----- src/modules/ekf2/EKF2.cpp | 19 +++++++ 10 files changed, 106 insertions(+), 16 deletions(-) diff --git a/docs/zh/msg_docs/EstimatorStatusFlags.md b/docs/zh/msg_docs/EstimatorStatusFlags.md index 19a6a00d23..e3e33c6a39 100644 --- a/docs/zh/msg_docs/EstimatorStatusFlags.md +++ b/docs/zh/msg_docs/EstimatorStatusFlags.md @@ -54,6 +54,7 @@ bool cs_valid_fake_pos # 41 - true if a valid constant position is bein bool cs_constant_pos # 42 - true if the vehicle is at a constant position bool cs_baro_fault # 43 - true when the current baro has been declared faulty and is no longer being used bool cs_gnss_vel # 44 - true if GNSS velocity measurement fusion is intended +bool cs_yaw_manual # 45 - true if yaw has been set manually # fault status uint32 fault_status_changes # number of filter fault status (fs) changes diff --git a/msg/EstimatorStatus.msg b/msg/EstimatorStatus.msg index b7933afdec..cf565e02d3 100644 --- a/msg/EstimatorStatus.msg +++ b/msg/EstimatorStatus.msg @@ -49,6 +49,7 @@ uint8 CS_GPS_YAW_FAULT = 27 # 27 - true when the GNSS heading has been declared uint8 CS_RNG_FAULT = 28 # 28 - true when the range finder has been declared faulty and is no longer being used uint8 CS_GNSS_VEL = 44 # 44 - true if GNSS velocity measurement fusion is intended uint8 CS_GNSS_FAULT = 45 # 45 - true if GNSS measurements have been declared faulty and are no longer used +uint8 CS_YAW_MANUAL = 46 # 46 - true if yaw has been set manually uint32 filter_fault_flags # Bitmask to indicate EKF internal faults # 0 - true if the fusion of the magnetometer X-axis has encountered a numerical error diff --git a/msg/EstimatorStatusFlags.msg b/msg/EstimatorStatusFlags.msg index f22e2b727c..ef85dbaf7c 100644 --- a/msg/EstimatorStatusFlags.msg +++ b/msg/EstimatorStatusFlags.msg @@ -50,6 +50,7 @@ bool cs_constant_pos # 42 - true if the vehicle is at a constant posi bool cs_baro_fault # 43 - true when the current baro has been declared faulty and is no longer being used bool cs_gnss_vel # 44 - true if GNSS velocity measurement fusion is intended bool cs_gnss_fault # 45 - true if GNSS measurements have been declared faulty and are no longer used +bool cs_yaw_manual # 46 - true if yaw has been set manually # fault status uint32 fault_status_changes # number of filter fault status (fs) changes diff --git a/msg/versioned/VehicleCommand.msg b/msg/versioned/VehicleCommand.msg index 669a4b8af9..8f20ec2d85 100644 --- a/msg/versioned/VehicleCommand.msg +++ b/msg/versioned/VehicleCommand.msg @@ -88,6 +88,7 @@ uint16 VEHICLE_CMD_REQUEST_CAMERA_INFORMATION = 521 # Request camera information uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.). uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom. uint16 VEHICLE_CMD_SET_CAMERA_FOCUS = 532 +uint16 VEHICLE_CMD_EXTERNAL_ATTITUDE_ESTIMATE = 620 # Set an external estimate of vehicle attitude in degrees. uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw. uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control. uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence. diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 169cc34587..cb5e87ff05 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -462,6 +462,22 @@ int Commander::custom_command(int argc, char *argv[]) } } + if (!strcmp(argv[0], "set_heading")) { + if (argc > 1) { + const float heading = atof(argv[1]); + const float heading_accuracy = NAN; + + bool ret = send_vehicle_command(vehicle_command_s::VEHICLE_CMD_EXTERNAL_ATTITUDE_ESTIMATE, + 0.f, 0.f, heading, 0.f, 0.f, 0.f, heading_accuracy); + return (ret ? 0 : 1); + + } else { + PX4_ERR("missing argument"); + return 0; + } + } + + if (!strcmp(argv[0], "poweroff")) { bool ret = send_vehicle_command(vehicle_command_s::VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN, @@ -1521,6 +1537,7 @@ Commander::handle_command(const vehicle_command_s &cmd) case vehicle_command_s::VEHICLE_CMD_DO_GRIPPER: case vehicle_command_s::VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE: case vehicle_command_s::VEHICLE_CMD_REQUEST_CAMERA_INFORMATION: + case vehicle_command_s::VEHICLE_CMD_EXTERNAL_ATTITUDE_ESTIMATE: /* ignore commands that are handled by other parts of the system */ break; @@ -3040,6 +3057,8 @@ The commander module contains the state machine for mode switching and failsafe PRINT_MODULE_USAGE_COMMAND("set_ekf_origin"); PRINT_MODULE_USAGE_ARG("lat, lon, alt", "Origin Latitude, Longitude, Altitude", false); PRINT_MODULE_USAGE_COMMAND_DESCR("lat|lon|alt", "Origin latitude longitude altitude"); + PRINT_MODULE_USAGE_COMMAND_DESCR("set_heading", "Set current heading"); + PRINT_MODULE_USAGE_ARG("heading", "degrees from True North [0 360]", false); PRINT_MODULE_USAGE_COMMAND_DESCR("poweroff", "Power off board (if supported)"); #endif PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp index d178bd8ebf..d03229f7c2 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -181,7 +181,8 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) && !_control_status.flags.mag_fault && !_control_status.flags.mag_field_disturbed && !_control_status.flags.ev_yaw - && !_control_status.flags.gnss_yaw; + && !_control_status.flags.gnss_yaw + && (!_control_status.flags.yaw_manual || _control_status.flags.mag_aligned_in_flight); _control_status.flags.mag_3D = common_conditions_passing && (_params.ekf2_mag_type == MagFuseType::AUTO) @@ -210,7 +211,8 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) if (continuing_conditions_passing && _control_status.flags.yaw_align) { - if ((checkHaglYawResetReq() && (_control_status.flags.mag_hdg || _control_status.flags.mag_3D)) + if ((checkHaglYawResetReq() && (_control_status.flags.mag_hdg || _control_status.flags.mag_3D + || _control_status.flags.yaw_manual)) || (wmm_updated && no_ne_aiding_or_not_moving)) { ECL_INFO("reset to %s", AID_SRC_NAME); const bool reset_heading = _control_status.flags.mag_hdg || _control_status.flags.mag_3D; @@ -448,7 +450,7 @@ void Ekf::resetMagStates(const Vector3f &mag, bool reset_heading) } // record the start time for the magnetic field alignment - if (_control_status.flags.in_air && reset_heading) { + if (_control_status.flags.in_air && (reset_heading || _control_status.flags.yaw_manual)) { _control_status.flags.mag_aligned_in_flight = true; _flt_mag_align_start_time = _time_delayed_us; } diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index de4eb07ad6..63655750f5 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -608,6 +608,7 @@ uint64_t mag_heading_consistent : uint64_t gnss_vel : 1; ///< 44 - true if GNSS velocity measurement fusion is intended uint64_t gnss_fault : 1; ///< 45 - true if GNSS measurements have been declared faulty and are no longer used + uint64_t yaw_manual : 1; ///< 46 - true if yaw has been reset manually } flags; uint64_t value; }; diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index b421bcb889..bbabed8bc0 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -416,6 +416,22 @@ public: bool resetGlobalPosToExternalObservation(double latitude, double longitude, float altitude, float eph, float epv, uint64_t timestamp_observation); + void resetHeadingToExternalObservation(float heading, float heading_accuracy) + { + if (_control_status.flags.yaw_align) { + resetYawByFusion(heading, heading_accuracy); + + } else { + resetQuatStateYaw(heading, heading_accuracy); + _control_status.flags.yaw_align = true; + } + + // Force the mag consistency check to pass again since an external heading reset is often done to + // counter mag disturbances. + _control_status.flags.mag_heading_consistent = false; + _control_status.flags.yaw_manual = true; + } + void updateParameters(); friend class AuxGlobalPosition; @@ -647,8 +663,8 @@ private: bool initialiseAltitudeTo(float altitude, float vpos_var = NAN); // update quaternion states and covariances using an innovation, observation variance and Jacobian vector - bool fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H_YAW); - void computeYawInnovVarAndH(float variance, float &innovation_variance, VectorState &H_YAW) const; + bool fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H_YAW, const bool reset = false); + void computeYawInnovVarAndH(float observation_variance, float &innovation_variance, VectorState &H_YAW) const; void updateIMUBiasInhibit(const imuSample &imu_delayed); @@ -999,6 +1015,8 @@ private: // yaw : Euler yaw angle (rad) // yaw_variance : yaw error variance (rad^2) void resetQuatStateYaw(float yaw, float yaw_variance); + void propagateQuatReset(const Quatf &quat_before_reset); + void resetYawByFusion(float yaw, float yaw_variance); HeightSensor _height_sensor_ref{HeightSensor::UNKNOWN}; PositionSensor _position_sensor_ref{PositionSensor::GNSS}; diff --git a/src/modules/ekf2/EKF/yaw_fusion.cpp b/src/modules/ekf2/EKF/yaw_fusion.cpp index 9560d8110f..fd723613dd 100644 --- a/src/modules/ekf2/EKF/yaw_fusion.cpp +++ b/src/modules/ekf2/EKF/yaw_fusion.cpp @@ -37,7 +37,7 @@ #include -bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H_YAW) +bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H_YAW, bool reset) { // check if the innovation variance calculation is badly conditioned if (aid_src_status.innovation_variance >= aid_src_status.observation_variance) { @@ -68,6 +68,11 @@ bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H Kfusion(row) *= heading_innov_var_inv; } + if (reset && fabsf(H_YAW(State::quat_nominal.idx + 2)) > FLT_EPSILON) { + // Reset the yaw estimate by forcing the measurement into the state + Kfusion(State::quat_nominal.idx + 2) = 1.f / H_YAW(State::quat_nominal.idx + 2); + } + // set the heading unhealthy if the test fails if (aid_src_status.innovation_rejected) { _innov_check_fail_status.flags.reject_yaw = true; @@ -110,12 +115,12 @@ bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H return true; } -void Ekf::computeYawInnovVarAndH(float variance, float &innovation_variance, VectorState &H_YAW) const +void Ekf::computeYawInnovVarAndH(float observation_variance, float &innovation_variance, VectorState &H_YAW) const { - sym::ComputeYawInnovVarAndH(_state.vector(), P, variance, &innovation_variance, &H_YAW); + sym::ComputeYawInnovVarAndH(_state.vector(), P, observation_variance, &innovation_variance, &H_YAW); } -void Ekf::resetQuatStateYaw(float yaw, float yaw_variance) +void Ekf::resetQuatStateYaw(const float yaw, const float yaw_variance) { // save a copy of the quaternion state for later use in calculating the amount of reset change const Quatf quat_before_reset = _state.quat_nominal; @@ -129,12 +134,17 @@ void Ekf::resetQuatStateYaw(float yaw, float yaw_variance) // update the rotation matrix using the new yaw value _R_to_earth = updateYawInRotMat(yaw, Dcmf(_state.quat_nominal)); - // calculate the amount that the quaternion has changed by - const Quatf quat_after_reset(_R_to_earth); - const Quatf q_error((quat_after_reset * quat_before_reset.inversed()).normalized()); - // update quaternion states - _state.quat_nominal = quat_after_reset; + _state.quat_nominal = Quatf(_R_to_earth); + + _time_last_heading_fuse = _time_delayed_us; + + propagateQuatReset(quat_before_reset); +} + +void Ekf::propagateQuatReset(const Quatf &quat_before_reset) +{ + const Quatf q_error((_state.quat_nominal * quat_before_reset.inversed()).normalized()); // add the reset amount to the output observer buffered data _output_predictor.resetQuaternion(q_error); @@ -160,6 +170,23 @@ void Ekf::resetQuatStateYaw(float yaw, float yaw_variance) } _state_reset_status.reset_count.quat++; - - _time_last_heading_fuse = _time_delayed_us; +} + +void Ekf::resetYawByFusion(const float yaw, const float yaw_variance) +{ + const Quatf quat_before_reset = _state.quat_nominal; + + estimator_aid_source1d_s aid_src_status{}; + aid_src_status.observation = yaw; + aid_src_status.observation_variance = yaw_variance; + aid_src_status.innovation = wrap_pi(getEulerYaw(_state.quat_nominal) - yaw); + + VectorState H_YAW; + + computeYawInnovVarAndH(aid_src_status.observation_variance, aid_src_status.innovation_variance, H_YAW); + + const bool reset_yaw = true; + fuseYaw(aid_src_status, H_YAW, reset_yaw); + + propagateQuatReset(quat_before_reset); } diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index b40601bdd0..c409a3ef47 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -580,6 +580,24 @@ void EKF2::Run() command_ack.timestamp = hrt_absolute_time(); _vehicle_command_ack_pub.publish(command_ack); } + + if (vehicle_command.command == vehicle_command_s::VEHICLE_CMD_EXTERNAL_ATTITUDE_ESTIMATE) { + if (PX4_ISFINITE(vehicle_command.param3)) { + const float heading = wrap_pi(math::radians(vehicle_command.param3)); + static constexpr float kDefaultHeadingAccuracyDeg = 20.f; + const float heading_accuracy = math::radians(PX4_ISFINITE(vehicle_command.param7) + ? vehicle_command.param7 + : kDefaultHeadingAccuracyDeg); + _ekf.resetHeadingToExternalObservation(heading, heading_accuracy); + command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED; + + } else { + command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED; + } + + command_ack.timestamp = hrt_absolute_time(); + _vehicle_command_ack_pub.publish(command_ack); + } } } @@ -1936,6 +1954,7 @@ void EKF2::PublishStatusFlags(const hrt_abstime ×tamp) status_flags.cs_baro_fault = _ekf.control_status_flags().baro_fault; status_flags.cs_gnss_vel = _ekf.control_status_flags().gnss_vel; status_flags.cs_gnss_fault = _ekf.control_status_flags().gnss_fault; + status_flags.cs_yaw_manual = _ekf.control_status_flags().yaw_manual; status_flags.fault_status_changes = _filter_fault_status_changes; status_flags.fs_bad_mag_x = _ekf.fault_status_flags().bad_mag_x; From c06ba93175782e5a90a83017fb2f92bb69da58f8 Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 3 Sep 2025 14:36:51 +0200 Subject: [PATCH 057/812] mc-auto: handle EKF heading reset --- src/lib/motion_planning/HeadingSmoothing.cpp | 5 ++++- src/lib/motion_planning/HeadingSmoothing.hpp | 2 +- .../flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp | 9 +++++---- 3 files changed, 10 insertions(+), 6 deletions(-) diff --git a/src/lib/motion_planning/HeadingSmoothing.cpp b/src/lib/motion_planning/HeadingSmoothing.cpp index b8094dff08..e28c4d87ce 100644 --- a/src/lib/motion_planning/HeadingSmoothing.cpp +++ b/src/lib/motion_planning/HeadingSmoothing.cpp @@ -42,7 +42,10 @@ void HeadingSmoothing::reset(const float heading, const float heading_rate) { const float wrapped_heading = matrix::wrap_pi(heading); _velocity_smoothing.setCurrentVelocity(wrapped_heading); - _velocity_smoothing.setCurrentAcceleration(heading_rate); + + if (PX4_ISFINITE(heading_rate)) { + _velocity_smoothing.setCurrentAcceleration(heading_rate); + } } void HeadingSmoothing::update(const float heading_setpoint, const float time_elapsed) diff --git a/src/lib/motion_planning/HeadingSmoothing.hpp b/src/lib/motion_planning/HeadingSmoothing.hpp index 5fdb4dde36..0aeccdbac2 100644 --- a/src/lib/motion_planning/HeadingSmoothing.hpp +++ b/src/lib/motion_planning/HeadingSmoothing.hpp @@ -69,7 +69,7 @@ public: * @param heading [rad] [-pi,pi] * @param heading_rate [rad/s] */ - void reset(const float heading, const float heading_rate); + void reset(const float heading, const float heading_rate = NAN); /** * @brief updates the heading setpoint, re-calculates trajectory, and takes an integration step diff --git a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp index dbbf2533f9..2eceae9353 100644 --- a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp +++ b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp @@ -707,19 +707,20 @@ void FlightTaskAuto::_ekfResetHandlerVelocityXY(const matrix::Vector2f &delta_vx _position_smoothing.forceSetVelocity({_velocity(0), _velocity(1), NAN}); } -void FlightTaskAuto::_ekfResetHandlerPositionZ(float delta_z) +void FlightTaskAuto::_ekfResetHandlerPositionZ(const float delta_z) { _position_smoothing.forceSetPosition({NAN, NAN, _position(2)}); } -void FlightTaskAuto::_ekfResetHandlerVelocityZ(float delta_vz) +void FlightTaskAuto::_ekfResetHandlerVelocityZ(const float delta_vz) { _position_smoothing.forceSetVelocity({NAN, NAN, _velocity(2)}); } -void FlightTaskAuto::_ekfResetHandlerHeading(float delta_psi) +void FlightTaskAuto::_ekfResetHandlerHeading(const float delta_psi) { - _yaw_setpoint_previous += delta_psi; + _yaw_setpoint_previous = wrap_pi(_yaw_setpoint_previous + delta_psi); + _heading_smoothing.reset(wrap_pi(_heading_smoothing.getSmoothedHeading() + delta_psi)); } void FlightTaskAuto::_checkEmergencyBraking() From 799f910ca9a4fd2cf6a415970850c919ada712ee Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Fri, 19 Sep 2025 09:06:01 +1000 Subject: [PATCH 058/812] uORB message layout fixes (#25581) * uORB message layout fixes * Apply suggestions from code review --------- Co-authored-by: PX4BuildBot --- msg/versioned/ActuatorMotors.msg | 4 +- msg/versioned/ActuatorServos.msg | 2 +- msg/versioned/ArmingCheckReply.msg | 40 ++++----- msg/versioned/ArmingCheckRequest.msg | 8 +- msg/versioned/BatteryStatus.msg | 121 ++++++++++++++------------- 5 files changed, 88 insertions(+), 87 deletions(-) diff --git a/msg/versioned/ActuatorMotors.msg b/msg/versioned/ActuatorMotors.msg index 04b8ebbb4e..d165c5c1cb 100644 --- a/msg/versioned/ActuatorMotors.msg +++ b/msg/versioned/ActuatorMotors.msg @@ -8,9 +8,9 @@ uint32 MESSAGE_VERSION = 0 uint64 timestamp # [us] Time since system start uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on -uint16 reversible_flags # Bitset indicating which motors are configured to be reversible +uint16 reversible_flags # [-] Bitset indicating which motors are configured to be reversible uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 # uint8 NUM_CONTROLS = 12 # -float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) +float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) diff --git a/msg/versioned/ActuatorServos.msg b/msg/versioned/ActuatorServos.msg index 30b1b359b9..c547998d1c 100644 --- a/msg/versioned/ActuatorServos.msg +++ b/msg/versioned/ActuatorServos.msg @@ -9,4 +9,4 @@ uint64 timestamp # [us] Time since system start uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on uint8 NUM_CONTROLS = 8 # -float32[8] control # [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. +float32[8] control # [-] [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. diff --git a/msg/versioned/ArmingCheckReply.msg b/msg/versioned/ArmingCheckReply.msg index 7ba4ad7bf3..b39649641f 100644 --- a/msg/versioned/ArmingCheckReply.msg +++ b/msg/versioned/ArmingCheckReply.msg @@ -1,4 +1,4 @@ -# Arming check reply. +# Arming check reply # # This is a response to an ArmingCheckRequest message sent by the FMU to an external component, such as a ROS 2 navigation mode. # The response contains the current set of external mode requirements, and a queue of events indicating recent failures to set the mode (which the FMU may then forward to a ground station). @@ -11,33 +11,33 @@ uint32 MESSAGE_VERSION = 1 uint64 timestamp # [us] Time since system start. -uint8 request_id # Id of ArmingCheckRequest for which this is a response. -uint8 registration_id # Id of external component emitting this response. +uint8 request_id # [-] Id of ArmingCheckRequest for which this is a response +uint8 registration_id # [-] Id of external component emitting this response -uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies. +uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX] -bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json). +bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json) +bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json) +bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json) -bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed. +bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed -uint8 num_events # Number of queued failure messages (Event) in the events field. +uint8 num_events # Number of queued failure messages (Event) in the events field -Event[5] events # Arming failure reasons (Queue of events to report to GCS). +Event[5] events # Arming failure reasons (Queue of events to report to GCS) # Mode requirements -bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope). -bool mode_req_attitude # Requires an attitude estimate. -bool mode_req_local_alt # Requires a local altitude estimate. -bool mode_req_local_position # Requires a local position estimate. -bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate. -bool mode_req_global_position # Requires a global position estimate. -bool mode_req_global_position_relaxed # Requires a relaxed global position estimate. -bool mode_req_mission # Requires an uploaded mission. -bool mode_req_home_position # Requires a home position (such as RTL/Return mode). -bool mode_req_prevent_arming # Prevent arming (such as in Land mode). +bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope) +bool mode_req_attitude # Requires an attitude estimate +bool mode_req_local_alt # Requires a local altitude estimate +bool mode_req_local_position # Requires a local position estimate +bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate +bool mode_req_global_position # Requires a global position estimate +bool mode_req_global_position_relaxed # Requires a relaxed global position estimate +bool mode_req_mission # Requires an uploaded mission +bool mode_req_home_position # Requires a home position (such as RTL/Return mode) +bool mode_req_prevent_arming # Prevent arming (such as in Land mode) bool mode_req_manual_control # Requires a manual controller uint8 ORB_QUEUE_LENGTH = 4 diff --git a/msg/versioned/ArmingCheckRequest.msg b/msg/versioned/ArmingCheckRequest.msg index 42d56bdf51..df12a79d35 100644 --- a/msg/versioned/ArmingCheckRequest.msg +++ b/msg/versioned/ArmingCheckRequest.msg @@ -1,4 +1,4 @@ -# Arming check request. +# Arming check request # # Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. # All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. @@ -9,8 +9,8 @@ uint32 MESSAGE_VERSION = 1 -uint64 timestamp # [us] Time since system start. +uint64 timestamp # [us] Time since system start -uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. +uint8 request_id # [-] Id of this request. Allows correlation with associated ArmingCheckReply messages. -uint32 valid_registrations_mask # Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) +uint32 valid_registrations_mask # [-] Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) diff --git a/msg/versioned/BatteryStatus.msg b/msg/versioned/BatteryStatus.msg index 39f75ed611..94926ac3a2 100644 --- a/msg/versioned/BatteryStatus.msg +++ b/msg/versioned/BatteryStatus.msg @@ -7,72 +7,73 @@ uint32 MESSAGE_VERSION = 1 uint8 MAX_INSTANCES = 4 -uint64 timestamp # [us] Time since system start -bool connected # Whether or not a battery is connected. For power modules this is based on a voltage threshold. -float32 voltage_v # [V] [@invalid 0] Battery voltage -float32 current_a # [A] [@invalid -1] Battery current -float32 current_average_a # [A] [@invalid -1] Battery current average (for FW average in level flight) -float32 discharged_mah # [mAh] [@invalid -1] Discharged amount -float32 remaining # [@range 0,1] [@invalid -1] Remaining capacity -float32 scale # [@range 1,] [@invalid -1] Scaling factor to compensate for lower actuation power caused by voltage sag -float32 time_remaining_s # [s] [@invalid NaN] Predicted time remaining until battery is empty under previous averaged load -float32 temperature # [°C] [@invalid NaN] Temperature of the battery -uint8 cell_count # [@invalid 0] Number of cells +uint64 timestamp # [us] Time since system start + +bool connected # Whether or not a battery is connected. For power modules this is based on a voltage threshold. +float32 voltage_v # [V] [@invalid 0] Battery voltage +float32 current_a # [A] [@invalid -1] Battery current +float32 current_average_a # [A] [@invalid -1] Battery current average (for FW average in level flight) +float32 discharged_mah # [mAh] [@invalid -1] Discharged amount +float32 remaining # [@range 0,1] [@invalid -1] Remaining capacity +float32 scale # [-] [@range 1,] [@invalid -1] Scaling factor to compensate for lower actuation power caused by voltage sag +float32 time_remaining_s # [s] [@invalid NaN] Predicted time remaining until battery is empty under previous averaged load +float32 temperature # [°C] [@invalid NaN] Temperature of the battery +uint8 cell_count # [-] [@invalid 0] Number of cells -uint8 source # [@enum SOURCE] Battery source -uint8 SOURCE_POWER_MODULE = 0 # Power module -uint8 SOURCE_EXTERNAL = 1 # External -uint8 SOURCE_ESCS = 2 # ESCs +uint8 source # [@enum SOURCE] Battery source +uint8 SOURCE_POWER_MODULE = 0 # Power module +uint8 SOURCE_EXTERNAL = 1 # External +uint8 SOURCE_ESCS = 2 # ESCs -uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 -uint16 capacity # [mAh] Capacity of the battery when fully charged -uint16 cycle_count # Number of discharge cycles the battery has experienced -uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge -uint16 manufacture_date # Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 -uint16 state_of_health # [%] [@range 0, 100] State of health. FullChargeCapacity/DesignCapacity -uint16 max_error # [%] [@range 1, 100] Max error, expected margin of error in the state-of-charge calculation -uint8 id # ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed -uint16 interface_error # Interface error counter +uint8 priority # [-] Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 +uint16 capacity # [mAh] Capacity of the battery when fully charged +uint16 cycle_count # [-] Number of discharge cycles the battery has experienced +uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge +uint16 manufacture_date # [-] Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 +uint16 state_of_health # [%] [@range 0, 100] State of health. FullChargeCapacity/DesignCapacity +uint16 max_error # [%] [@range 1, 100] Max error, expected margin of error in the state-of-charge calculation +uint8 id # [-] ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed +uint16 interface_error # [-] Interface error counter -float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages -float32 max_cell_voltage_delta # Max difference between individual cell voltages +float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages +float32 max_cell_voltage_delta # [V] Max difference between individual cell voltages -bool is_powering_off # Power off event imminent indication, false if unknown -bool is_required # Set if the battery is explicitly required before arming +bool is_powering_off # Power off event imminent indication, false if unknown +bool is_required # Set if the battery is explicitly required before arming -uint8 warning # [@enum WARNING STATE] Current battery warning -uint8 WARNING_NONE = 0 # No battery low voltage warning active -uint8 WARNING_LOW = 1 # Low voltage warning -uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately -uint8 WARNING_EMERGENCY = 3 # Immediate landing required -uint8 WARNING_FAILED = 4 # Battery has failed completely -uint8 STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field -uint8 STATE_CHARGING = 7 # Battery is charging +uint8 warning # [@enum WARNING STATE] Current battery warning +uint8 WARNING_NONE = 0 # No battery low voltage warning active +uint8 WARNING_LOW = 1 # Low voltage warning +uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately +uint8 WARNING_EMERGENCY = 3 # Immediate landing required +uint8 WARNING_FAILED = 4 # Battery has failed completely +uint8 STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field +uint8 STATE_CHARGING = 7 # Battery is charging -uint16 faults # [@enum FAULT] Smart battery supply status/fault flags (bitmask) for health indication -uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged -uint8 FAULT_SPIKES = 1 # Voltage spikes -uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed -uint8 FAULT_OVER_CURRENT = 3 # Over-current -uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature -uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault -uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage) -uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware -uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system -uint8 FAULT_HARDWARE_FAILURE = 9 # Hardware problem -uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming -uint8 FAULT_COUNT = 11 # Counter. Keep this as last element +uint16 faults # [@enum FAULT] Smart battery supply status/fault flags (bitmask) for health indication +uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged +uint8 FAULT_SPIKES = 1 # Voltage spikes +uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed +uint8 FAULT_OVER_CURRENT = 3 # Over-current +uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature +uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault +uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage) +uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware +uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system +uint8 FAULT_HARDWARE_FAILURE = 9 # Hardware problem +uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming +uint8 FAULT_COUNT = 11 # Counter. Keep this as last element -float32 full_charge_capacity_wh # [Wh] Compensated battery capacity -float32 remaining_capacity_wh # [Wh] Compensated battery capacity remaining -uint16 over_discharge_count # Number of battery overdischarge -float32 nominal_voltage # [V] Nominal voltage of the battery pack +float32 full_charge_capacity_wh # [Wh] Compensated battery capacity +float32 remaining_capacity_wh # [Wh] Compensated battery capacity remaining +uint16 over_discharge_count # [-] Number of battery overdischarge +float32 nominal_voltage # [V] Nominal voltage of the battery pack -float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate -float32 ocv_estimate # [V] Open circuit voltage estimate -float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate -float32 volt_based_soc_estimate # [@range 0, 1] Normalized volt based state of charge estimate -float32 voltage_prediction # [V] Predicted voltage -float32 prediction_error # [V] Prediction error -float32 estimation_covariance_norm # Norm of the covariance matrix +float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate +float32 ocv_estimate # [V] Open circuit voltage estimate +float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate +float32 volt_based_soc_estimate # [-] [@range 0, 1] Normalized volt based state of charge estimate +float32 voltage_prediction # [V] Predicted voltage +float32 prediction_error # [V] Prediction error +float32 estimation_covariance_norm # [-] Norm of the covariance matrix From 91fa0f469333dc1518b15e430b6841d489cc02e0 Mon Sep 17 00:00:00 2001 From: Alex Klimaj Date: Fri, 19 Sep 2025 12:06:03 -0600 Subject: [PATCH 059/812] boards: ark x20 and f9p gps (#25149) * boards: ark x20 gps * update startup * fix cmake variants * boards: ark f9p gps * ark x20 gps add serial dma hrt call * update gps submodule with x20 support * update default constellations * fix mag rotation --- .vscode/cmake-variants.yaml | 20 ++ boards/ark/f9p-gps/canbootloader.px4board | 5 + boards/ark/f9p-gps/default.px4board | 37 ++++ boards/ark/f9p-gps/firmware.prototype | 13 ++ boards/ark/f9p-gps/init/rc.board_defaults | 13 ++ boards/ark/f9p-gps/init/rc.board_sensors | 11 + .../nuttx-config/canbootloader/defconfig | 57 ++++++ .../ark/f9p-gps/nuttx-config/include/board.h | 152 ++++++++++++++ .../nuttx-config/include/board_dma_map.h | 46 +++++ boards/ark/f9p-gps/nuttx-config/nsh/defconfig | 153 ++++++++++++++ .../scripts/canbootloader_script.ld | 134 +++++++++++++ .../f9p-gps/nuttx-config/scripts/script.ld | 146 ++++++++++++++ boards/ark/f9p-gps/src/CMakeLists.txt | 66 ++++++ boards/ark/f9p-gps/src/board_config.h | 125 ++++++++++++ boards/ark/f9p-gps/src/boot.c | 188 ++++++++++++++++++ boards/ark/f9p-gps/src/boot_config.h | 130 ++++++++++++ boards/ark/f9p-gps/src/can.c | 130 ++++++++++++ boards/ark/f9p-gps/src/i2c.cpp | 39 ++++ boards/ark/f9p-gps/src/init.c | 168 ++++++++++++++++ boards/ark/f9p-gps/src/led.c | 124 ++++++++++++ boards/ark/f9p-gps/src/led.h | 37 ++++ boards/ark/f9p-gps/src/spi.cpp | 44 ++++ boards/ark/f9p-gps/uavcan_board_identity | 17 ++ boards/ark/x20-gps/canbootloader.px4board | 5 + boards/ark/x20-gps/default.px4board | 37 ++++ boards/ark/x20-gps/firmware.prototype | 13 ++ boards/ark/x20-gps/init/rc.board_defaults | 13 ++ boards/ark/x20-gps/init/rc.board_sensors | 11 + .../nuttx-config/canbootloader/defconfig | 57 ++++++ .../ark/x20-gps/nuttx-config/include/board.h | 152 ++++++++++++++ .../nuttx-config/include/board_dma_map.h | 46 +++++ boards/ark/x20-gps/nuttx-config/nsh/defconfig | 153 ++++++++++++++ .../scripts/canbootloader_script.ld | 134 +++++++++++++ .../x20-gps/nuttx-config/scripts/script.ld | 146 ++++++++++++++ boards/ark/x20-gps/src/CMakeLists.txt | 66 ++++++ boards/ark/x20-gps/src/board_config.h | 125 ++++++++++++ boards/ark/x20-gps/src/boot.c | 188 ++++++++++++++++++ boards/ark/x20-gps/src/boot_config.h | 130 ++++++++++++ boards/ark/x20-gps/src/can.c | 130 ++++++++++++ boards/ark/x20-gps/src/i2c.cpp | 39 ++++ boards/ark/x20-gps/src/init.c | 168 ++++++++++++++++ boards/ark/x20-gps/src/led.c | 124 ++++++++++++ boards/ark/x20-gps/src/led.h | 37 ++++ boards/ark/x20-gps/src/spi.cpp | 44 ++++ boards/ark/x20-gps/uavcan_board_identity | 17 ++ src/drivers/drv_sensor.h | 2 + src/drivers/gps/gps.cpp | 8 + 47 files changed, 3700 insertions(+) create mode 100644 boards/ark/f9p-gps/canbootloader.px4board create mode 100644 boards/ark/f9p-gps/default.px4board create mode 100644 boards/ark/f9p-gps/firmware.prototype create mode 100644 boards/ark/f9p-gps/init/rc.board_defaults create mode 100644 boards/ark/f9p-gps/init/rc.board_sensors create mode 100644 boards/ark/f9p-gps/nuttx-config/canbootloader/defconfig create mode 100644 boards/ark/f9p-gps/nuttx-config/include/board.h create mode 100644 boards/ark/f9p-gps/nuttx-config/include/board_dma_map.h create mode 100644 boards/ark/f9p-gps/nuttx-config/nsh/defconfig create mode 100644 boards/ark/f9p-gps/nuttx-config/scripts/canbootloader_script.ld create mode 100644 boards/ark/f9p-gps/nuttx-config/scripts/script.ld create mode 100644 boards/ark/f9p-gps/src/CMakeLists.txt create mode 100644 boards/ark/f9p-gps/src/board_config.h create mode 100644 boards/ark/f9p-gps/src/boot.c create mode 100644 boards/ark/f9p-gps/src/boot_config.h create mode 100644 boards/ark/f9p-gps/src/can.c create mode 100644 boards/ark/f9p-gps/src/i2c.cpp create mode 100644 boards/ark/f9p-gps/src/init.c create mode 100644 boards/ark/f9p-gps/src/led.c create mode 100644 boards/ark/f9p-gps/src/led.h create mode 100644 boards/ark/f9p-gps/src/spi.cpp create mode 100644 boards/ark/f9p-gps/uavcan_board_identity create mode 100644 boards/ark/x20-gps/canbootloader.px4board create mode 100644 boards/ark/x20-gps/default.px4board create mode 100644 boards/ark/x20-gps/firmware.prototype create mode 100644 boards/ark/x20-gps/init/rc.board_defaults create mode 100644 boards/ark/x20-gps/init/rc.board_sensors create mode 100644 boards/ark/x20-gps/nuttx-config/canbootloader/defconfig create mode 100644 boards/ark/x20-gps/nuttx-config/include/board.h create mode 100644 boards/ark/x20-gps/nuttx-config/include/board_dma_map.h create mode 100644 boards/ark/x20-gps/nuttx-config/nsh/defconfig create mode 100644 boards/ark/x20-gps/nuttx-config/scripts/canbootloader_script.ld create mode 100644 boards/ark/x20-gps/nuttx-config/scripts/script.ld create mode 100644 boards/ark/x20-gps/src/CMakeLists.txt create mode 100644 boards/ark/x20-gps/src/board_config.h create mode 100644 boards/ark/x20-gps/src/boot.c create mode 100644 boards/ark/x20-gps/src/boot_config.h create mode 100644 boards/ark/x20-gps/src/can.c create mode 100644 boards/ark/x20-gps/src/i2c.cpp create mode 100644 boards/ark/x20-gps/src/init.c create mode 100644 boards/ark/x20-gps/src/led.c create mode 100644 boards/ark/x20-gps/src/led.h create mode 100644 boards/ark/x20-gps/src/spi.cpp create mode 100644 boards/ark/x20-gps/uavcan_board_identity diff --git a/.vscode/cmake-variants.yaml b/.vscode/cmake-variants.yaml index 30eddc8e56..ec8822e01c 100644 --- a/.vscode/cmake-variants.yaml +++ b/.vscode/cmake-variants.yaml @@ -206,6 +206,16 @@ CONFIG: buildType: MinSizeRel settings: CONFIG: ark_dist_canbootloader + ark_f9p-gps_default: + short: ark_f9p-gps_default + buildType: MinSizeRel + settings: + CONFIG: ark_f9p-gps_default + ark_f9p-gps_canbootloader: + short: ark_f9p-gps_canbootloader + buildType: MinSizeRel + settings: + CONFIG: ark_f9p-gps_canbootloader ark_fmu-v6x_bootloader: short: ark_fmu-v6x_bootloader buildType: MinSizeRel @@ -236,6 +246,16 @@ CONFIG: buildType: MinSizeRel settings: CONFIG: ark_pi6x_default + ark_x20-gps_default: + short: ark_x20-gps_default + buildType: MinSizeRel + settings: + CONFIG: ark_x20-gps_default + ark_x20-gps_canbootloader: + short: ark_x20-gps_canbootloader + buildType: MinSizeRel + settings: + CONFIG: ark_x20-gps_canbootloader atl_mantis-edu_default: short: atl_mantis-edu buildType: MinSizeRel diff --git a/boards/ark/f9p-gps/canbootloader.px4board b/boards/ark/f9p-gps/canbootloader.px4board new file mode 100644 index 0000000000..46917280f6 --- /dev/null +++ b/boards/ark/f9p-gps/canbootloader.px4board @@ -0,0 +1,5 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m4" +CONFIG_BOARD_ROMFSROOT="" +CONFIG_BOARD_CONSTRAINED_MEMORY=y +CONFIG_DRIVERS_BOOTLOADERS=y diff --git a/boards/ark/f9p-gps/default.px4board b/boards/ark/f9p-gps/default.px4board new file mode 100644 index 0000000000..6c79012be7 --- /dev/null +++ b/boards/ark/f9p-gps/default.px4board @@ -0,0 +1,37 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m4" +CONFIG_BOARD_ROMFSROOT="cannode" +CONFIG_BOARD_CONSTRAINED_MEMORY=y +CONFIG_DRIVERS_BAROMETER_BMP388=y +CONFIG_DRIVERS_BOOTLOADERS=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_DRIVERS_MAGNETOMETER_ST_IIS2MDC=y +CONFIG_DRIVERS_SAFETY_BUTTON=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_BOARD_UAVCAN_INTERFACES=1 +CONFIG_DRIVERS_UAVCANNODE=y +CONFIG_UAVCANNODE_BEEP_COMMAND=y +CONFIG_UAVCANNODE_GNSS_FIX=y +CONFIG_UAVCANNODE_LIGHTS_COMMAND=y +CONFIG_UAVCANNODE_MAGNETIC_FIELD_STRENGTH=y +CONFIG_UAVCANNODE_RTK_DATA=y +CONFIG_UAVCANNODE_RAW_IMU=y +CONFIG_UAVCANNODE_SAFETY_BUTTON=y +CONFIG_UAVCANNODE_STATIC_PRESSURE=y +CONFIG_UAVCANNODE_STATIC_TEMPERATURE=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_SENSORS=y +# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set +# CONFIG_SENSORS_VEHICLE_AIR_DATA is not set +# CONFIG_SENSORS_VEHICLE_GPS_POSITION is not set +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/ark/f9p-gps/firmware.prototype b/boards/ark/f9p-gps/firmware.prototype new file mode 100644 index 0000000000..b23ef47ca3 --- /dev/null +++ b/boards/ark/f9p-gps/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 90, + "magic": "PX4FWv1", + "description": "Firmware for the ARK F9P GPS", + "image": "", + "build_time": 0, + "summary": "ARKF9PGPS", + "version": "0.1", + "image_size": 0, + "image_maxsize": 2080768, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/ark/f9p-gps/init/rc.board_defaults b/boards/ark/f9p-gps/init/rc.board_defaults new file mode 100644 index 0000000000..ca7fc7b3ef --- /dev/null +++ b/boards/ark/f9p-gps/init/rc.board_defaults @@ -0,0 +1,13 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ + +param set-default CBRK_IO_SAFETY 0 +param set-default CANNODE_SUB_MBD 1 +param set-default CANNODE_SUB_RTCM 1 +param set-default GPS_1_GNSS 63 +param set-default SENS_IMU_CLPNOTI 0 + +safety_button start +tone_alarm start diff --git a/boards/ark/f9p-gps/init/rc.board_sensors b/boards/ark/f9p-gps/init/rc.board_sensors new file mode 100644 index 0000000000..25bb268272 --- /dev/null +++ b/boards/ark/f9p-gps/init/rc.board_sensors @@ -0,0 +1,11 @@ +#!/bin/sh +# +# board sensors init +#------------------------------------------------------------------------------ +gps start -d /dev/ttyS0 -p ubx + +icm42688p -R 0 -s start + +bmp388 -I -b 1 start + +iis2mdc -R 2 -I -b 1 start diff --git a/boards/ark/f9p-gps/nuttx-config/canbootloader/defconfig b/boards/ark/f9p-gps/nuttx-config/canbootloader/defconfig new file mode 100644 index 0000000000..eff9943964 --- /dev/null +++ b/boards/ark/f9p-gps/nuttx-config/canbootloader/defconfig @@ -0,0 +1,57 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/f9p-gps/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F412CE=y +CONFIG_ARCH_INTERRUPTSTACK=4096 +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BINFMT_DISABLE=y +CONFIG_BOARDCTL=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DISABLE_MOUNTPOINT=y +CONFIG_EXPERIMENTAL=y +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=4096 +CONFIG_INIT_STACKSIZE=4096 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MM_REGIONS=2 +CONFIG_NAME_MAX=0 +CONFIG_NUNGET_CHARS=0 +CONFIG_PREALLOC_TIMERS=0 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=262144 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_DISABLE_BUFFERING=y +CONFIG_STM32_FLASH_CONFIG_G=y +CONFIG_STM32_NOEXT_VECTORS=y +CONFIG_STM32_TIM8=y +CONFIG_TASK_NAME_SIZE=0 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/ark/f9p-gps/nuttx-config/include/board.h b/boards/ark/f9p-gps/nuttx-config/include/board.h new file mode 100644 index 0000000000..526392b92b --- /dev/null +++ b/boards/ark/f9p-gps/nuttx-config/include/board.h @@ -0,0 +1,152 @@ +/************************************************************************************ + * configs/px4fmu/include/board.h + * include/arch/board/board.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ +#include "board_dma_map.h" + +#ifndef __ARCH_BOARD_BOARD_H +#define __ARCH_BOARD_BOARD_H + +#include +#ifndef __ASSEMBLY__ +# include +#endif + +#include + +/* HSI - 8 MHz RC factory-trimmed + * LSI - 32 KHz RC + * HSE - 8 MHz Crystal + * LSE - not installed + */ +#define STM32_BOARD_USEHSE 1 +#define STM32_BOARD_XTAL 8000000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 + +/* Main PLL Configuration */ +#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8) +#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(384) +#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_4 +#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(8) +#define STM32_PLLCFG_PLLR RCC_PLLCFG_PLLR(2) + +#define STM32_RCC_PLLI2SCFGR_PLLI2SM RCC_PLLI2SCFGR_PLLI2SM(16) +#define STM32_RCC_PLLI2SCFGR_PLLI2SN RCC_PLLI2SCFGR_PLLI2SN(192) +#define STM32_RCC_PLLI2SCFGR_PLLI2SQ RCC_PLLI2SCFGR_PLLI2SQ(2) +#define STM32_RCC_PLLI2SCFGR_PLLI2SR RCC_PLLI2SCFGR_PLLI2SR(2) +#define STM32_RCC_PLLI2SCFGR_PLLI2SSRC RCC_PLLI2SCFGR_PLLI2SSRC(0) /* HSE or HSI depending on PLLSRC of PLLCFGR*/ + +#define STM32_RCC_DCKCFGR2_CK48MSEL RCC_DCKCFGR2_CK48MSEL_PLL +#define STM32_RCC_DCKCFGR2_FMPI2C1SEL RCC_DCKCFGR2_FMPI2C1SEL_APB +#define STM32_RCC_DCKCFGR2_SDIOSEL RCC_DCKCFGR2_SDIOSEL_48MHZ + +#define STM32_SYSCLK_FREQUENCY 96000000ul + +/* AHB clock (HCLK) is SYSCLK (96MHz) */ +#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* Same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (48MHz) */ +#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timers driven from APB1 will be twice PCLK1 (see page 112 of reference manual) */ +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* APB2 clock (PCLK2) is HCLK (96MHz) */ +#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK /* PCLK2 = HCLK */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY) + +/* Timers driven from APB2 will be PCLK2 since no prescale division */ +#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM9_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM10_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM11_CLKIN (STM32_PCLK2_FREQUENCY) + +/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx otherwise frequency is 2xAPBx. */ +#define BOARD_TIM2_FREQUENCY (2 * STM32_PCLK1_FREQUENCY) +#define BOARD_TIM3_FREQUENCY (2 * STM32_PCLK1_FREQUENCY) +#define BOARD_TIM4_FREQUENCY (2 * STM32_PCLK1_FREQUENCY) +#define BOARD_TIM5_FREQUENCY (2 * STM32_PCLK1_FREQUENCY) +#define BOARD_TIM6_FREQUENCY (2 * STM32_PCLK1_FREQUENCY) +#define BOARD_TIM7_FREQUENCY (2 * STM32_PCLK1_FREQUENCY) +#define BOARD_TIM8_FREQUENCY (2 * STM32_PCLK2_FREQUENCY) + +/* Alternate function pin selections ************************************************/ + +/* UARTs */ +#define GPIO_USART1_RX GPIO_USART1_RX_2 +#define GPIO_USART1_TX GPIO_USART1_TX_3 + +#define GPIO_USART2_RX GPIO_USART2_RX_1 +#define GPIO_USART2_TX GPIO_USART2_TX_1 + +/* CAN */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_1 +#define GPIO_CAN1_TX GPIO_CAN1_TX_1 + +/* I2C */ + +#define GPIO_MCU_I2C1_SCL +#define GPIO_MCU_I2C1_SDA + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1 +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 + +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN6) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_4 + +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10) + +/* SPI */ +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 + +#endif /* __ARCH_BOARD_BOARD_H */ diff --git a/boards/ark/f9p-gps/nuttx-config/include/board_dma_map.h b/boards/ark/f9p-gps/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..efa3d824b2 --- /dev/null +++ b/boards/ark/f9p-gps/nuttx-config/include/board_dma_map.h @@ -0,0 +1,46 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// DMA1 Channel/Stream Selections +//--------------------------------------------//---------------------------//---------------- + + +// DMA2 Channel/Stream Selections +//--------------------------------------------//---------------------------//---------------- +#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_1 // DMA2, Stream 0, Channel 3 +#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_1 // DMA2, Stream 3, Channel 3 +#define DMACHAN_USART1_RX DMAMAP_USART1_RX_1 // DMA2, Stream 2, Channel 4 +#define DMAMAP_USART1_RX DMAMAP_USART1_RX_1 +//#define DMACHAN_USART1_TX DMAMAP_USART1_TX // DMA2, Stream 7, Channel 4 diff --git a/boards/ark/f9p-gps/nuttx-config/nsh/defconfig b/boards/ark/f9p-gps/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..bde9d7318c --- /dev/null +++ b/boards/ark/f9p-gps/nuttx-config/nsh/defconfig @@ -0,0 +1,153 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/f9p-gps/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F412CE=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_CROMFS=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=2624 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MM_REGIONS=2 +CONFIG_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_VARS=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=262144 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_WAITPID=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STM32_ADC1=y +CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y +CONFIG_STM32_DMA1=y +CONFIG_STM32_DMA2=y +CONFIG_STM32_FLASH_CONFIG_G=y +CONFIG_STM32_FLASH_PREFETCH=y +CONFIG_STM32_FLOWCONTROL_BROKEN=y +CONFIG_STM32_I2C1=y +CONFIG_STM32_I2C2=y +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_SPI1_DMA=y +CONFIG_STM32_SPI1_DMA_BUFFER=1024 +CONFIG_STM32_TIM8=y +CONFIG_STM32_USART1=y +CONFIG_STM32_USART2=y +CONFIG_STM32_USART_BREAKS=y +CONFIG_STM32_WWDG=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=2000 +CONFIG_USART1_RXDMA=y +CONFIG_USART1_TXBUFSIZE=2000 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=1100 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/ark/f9p-gps/nuttx-config/scripts/canbootloader_script.ld b/boards/ark/f9p-gps/nuttx-config/scripts/canbootloader_script.ld new file mode 100644 index 0000000000..6be5cffcd8 --- /dev/null +++ b/boards/ark/f9p-gps/nuttx-config/scripts/canbootloader_script.ld @@ -0,0 +1,134 @@ +/**************************************************************************** + * nuttx-config/scripts/canbootloader_script.ld + * + * Copyright (c) 2025 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The STM32F412 has 1M of FLASH beginning at address 0x0800:0000 and + * 256Kb of SRAM. SRAM is split up into three blocks: + * + * 1) 112Kb of SRAM beginning at address 0x2000:0000 + * 2) 16Kb of SRAM beginning at address 0x2001:c000 + * 3) 64Kb of SRAM beginning at address 0x2002:0000 + * 4) 64Kb of TCM SRAM beginning at address 0x1000:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The first 0x10000 of flash is reserved for the bootloader. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08000000, LENGTH = 32K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K +} + +OUTPUT_ARCH(arm) + +ENTRY(__start) /* treat __start as the anchor for dead code stripping */ +EXTERN(_vectors) /* force the vectors to be included in the output */ + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/ark/f9p-gps/nuttx-config/scripts/script.ld b/boards/ark/f9p-gps/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..2f4769b8f5 --- /dev/null +++ b/boards/ark/f9p-gps/nuttx-config/scripts/script.ld @@ -0,0 +1,146 @@ +/**************************************************************************** + * scripts/ld.script + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The STM32F412 has 1M of FLASH beginning at address 0x0800:0000 and + * 256Kb of SRAM. SRAM is split up into three blocks: + * + * 1) 112Kb of SRAM beginning at address 0x2000:0000 + * 2) 16Kb of SRAM beginning at address 0x2001:c000 + * 3) 64Kb of SRAM beginning at address 0x2002:0000 + * 4) 64Kb of TCM SRAM beginning at address 0x1000:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The first 0x10000 of flash is reserved for the bootloader. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08010000, LENGTH = 928K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K +} + +OUTPUT_ARCH(arm) + +ENTRY(__start) /* treat __start as the anchor for dead code stripping */ +EXTERN(_vectors) /* force the vectors to be included in the output */ + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(8); + /* + * This section positions the app_descriptor_t used + * by the make_can_boot_descriptor.py tool to set + * the application image's descriptor so that the + * uavcan bootloader has the ability to validate the + * image crc, size etc + */ + KEEP(*(.app_descriptor)) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/ark/f9p-gps/src/CMakeLists.txt b/boards/ark/f9p-gps/src/CMakeLists.txt new file mode 100644 index 0000000000..7f8a23a27e --- /dev/null +++ b/boards/ark/f9p-gps/src/CMakeLists.txt @@ -0,0 +1,66 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +if("${PX4_BOARD_LABEL}" STREQUAL "canbootloader") + + add_library(drivers_board + boot_config.h + boot.c + led.c + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch + nuttx_drivers + canbootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/canbootloader) + +else() + add_library(drivers_board + can.c + i2c.cpp + init.c + led.c + spi.cpp + ) + + target_link_libraries(drivers_board + PRIVATE + arch_spi + drivers__led # drv_led_start + nuttx_arch + nuttx_drivers + px4_layer + ) +endif() diff --git a/boards/ark/f9p-gps/src/board_config.h b/boards/ark/f9p-gps/src/board_config.h new file mode 100644 index 0000000000..2d5f582075 --- /dev/null +++ b/boards/ark/f9p-gps/src/board_config.h @@ -0,0 +1,125 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * board internal definitions + */ + +#pragma once + +#include +#include +#include + +/* BUTTON */ +#define GPIO_BTN_SAFETY /* PB15 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTB|GPIO_PIN15) + +/* Safety LED */ +#define GPIO_LED_SAFETY /* PA1 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN1) + +/* Tone alarm output. */ +#define TONE_ALARM_TIMER 2 /* timer 2 */ +#define TONE_ALARM_CHANNEL 1 /* channel 1 */ +#define GPIO_TONE_ALARM_IDLE /* PA0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TONE_ALARM /* PA0 */ (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0) + +/* CAN Silent mode control */ +#define GPIO_CAN1_SILENT_S0 /* PB12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN12) + +/* CAN termination software control */ +#define GPIO_CAN1_TERMINATION /* PB13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN13) +#define GPIO_CAN_TERM GPIO_CAN1_TERMINATION + +/* ICM42688p FSYNC */ +#define GPIO_42688P_FSYNC /* PB8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8) + +/* Boot config */ +#define GPIO_BOOT_CONFIG /* PC15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN15|GPIO_EXTI) + +/* LEDs are driven with open drain to support Anode to 5V or 3.3V */ +#define GPIO_TIM1_CH1 /* PA8 */ (GPIO_TIM1_CH1_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz) +#define GPIO_TIM1_CH2 /* PA9 */ (GPIO_TIM1_CH2_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz) +#define GPIO_TIM1_CH3 /* PA10 */ (GPIO_TIM1_CH3_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz) + +#define GPIO_I2C1_SCL_RESET /* PB6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN6) +#define GPIO_I2C1_SDA_RESET /* PB7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN7) + +#define GPIO_I2C2_SCL_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10) +#define GPIO_I2C2_SDA_RESET /* PB9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9) + +#define GPIO_I2C2_SCL_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10) +#define GPIO_I2C2_SDA_RESET /* PB9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9) + +#define GPIO_USART1_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN3) +#define GPIO_USART1_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN15) + +#define GPIO_USART2_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN3) +#define GPIO_USART2_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN2) + +#define FLASH_BASED_PARAMS + +/* High-resolution timer */ +#define HRT_TIMER 3 /* use timer 3 for the HRT */ +#define HRT_TIMER_CHANNEL 4 /* use capture/compare channel 4 */ + +#define PX4_GPIO_INIT_LIST { \ + GPIO_BTN_SAFETY, \ + GPIO_LED_SAFETY, \ + GPIO_I2C1_SCL_RESET, \ + GPIO_I2C1_SDA_RESET, \ + GPIO_I2C2_SCL_RESET, \ + GPIO_I2C2_SDA_RESET, \ + GPIO_42688P_FSYNC, \ + GPIO_BOOT_CONFIG, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN1_SILENT_S0, \ + GPIO_CAN1_TERMINATION, \ + } + +__BEGIN_DECLS + +#define BOARD_HAS_N_S_RGB_LED 1 +#define BOARD_MAX_LEDS BOARD_HAS_N_S_RGB_LED + +#ifndef __ASSEMBLY__ + +extern void stm32_spiinitialize(void); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/ark/f9p-gps/src/boot.c b/boards/ark/f9p-gps/src/boot.c new file mode 100644 index 0000000000..3efdba508c --- /dev/null +++ b/boards/ark/f9p-gps/src/boot.c @@ -0,0 +1,188 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * Author: Ben Dyer + * Pavel Kirienko + * David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include "boot_config.h" +#include "board.h" + +#include +#include +#include + +#include +#include "led.h" + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +__EXPORT void stm32_boardinitialize(void) +{ + putreg32(getreg32(STM32_RCC_APB1ENR) | RCC_APB1ENR_CAN1EN, STM32_RCC_APB1ENR); + stm32_configgpio(GPIO_CAN1_RX); + stm32_configgpio(GPIO_CAN1_TX); + stm32_configgpio(GPIO_CAN1_SILENT_S0); + stm32_configgpio(GPIO_CAN1_TERMINATION); + putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR); + putreg32(getreg32(STM32_RCC_APB1RSTR) & ~RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR); + +#if defined(OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO) + stm32_configgpio(GPIO_GETNODEINFO_JUMPER); +#endif + +} + +/************************************************************************************ + * Name: board_deinitialize + * + * Description: + * This function is called by the bootloader code prior to booting + * the application. Is should place the HW into an benign initialized state. + * + ************************************************************************************/ + +void board_deinitialize(void) +{ + putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR); +} + +/**************************************************************************** + * Name: board_get_product_name + * + * Description: + * Called to retrieve the product name. The returned value is a assumed + * to be written to a pascal style string that will be length prefixed + * and not null terminated + * + * Input Parameters: + * product_name - A pointer to a buffer to write the name. + * maxlen - The maximum number of charter that can be written + * + * Returned Value: + * The length of characters written to the buffer. + * + ****************************************************************************/ + +uint8_t board_get_product_name(uint8_t *product_name, size_t maxlen) +{ + DEBUGASSERT(maxlen > UAVCAN_STRLEN(HW_UAVCAN_NAME)); + memcpy(product_name, HW_UAVCAN_NAME, UAVCAN_STRLEN(HW_UAVCAN_NAME)); + return UAVCAN_STRLEN(HW_UAVCAN_NAME); +} + +/**************************************************************************** + * Name: board_get_hardware_version + * + * Description: + * Called to retrieve the hardware version information. The function + * will first initialize the the callers struct to all zeros. + * + * Input Parameters: + * hw_version - A pointer to a uavcan_hardwareversion_t. + * + * Returned Value: + * Length of the unique_id + * + ****************************************************************************/ + +size_t board_get_hardware_version(uavcan_HardwareVersion_t *hw_version) +{ + memset(hw_version, 0, sizeof(uavcan_HardwareVersion_t)); + + hw_version->major = HW_VERSION_MAJOR; + hw_version->minor = HW_VERSION_MINOR; + + return board_get_mfguid(*(mfguid_t *) hw_version->unique_id); +} + +/**************************************************************************** + * Name: board_indicate + * + * Description: + * Provides User feedback to indicate the state of the bootloader + * on board specific hardware. + * + * Input Parameters: + * indication - A member of the uiindication_t + * + * Returned Value: + * None + * + ****************************************************************************/ +#define led(n, code, r , g , b, h) {.red = (r),.green = (g), .blue = (b),.hz = (h)} + +typedef begin_packed_struct struct led_t { + uint8_t red; + uint8_t green; + uint8_t blue; + uint8_t hz; +} end_packed_struct led_t; + +static const led_t i2l[] = { + + led(0, off, 0, 0, 0, 0), + led(1, reset, 128, 128, 128, 30), + led(2, autobaud_start, 0, 128, 0, 1), + led(3, autobaud_end, 0, 128, 0, 2), + led(4, allocation_start, 0, 0, 64, 2), + led(5, allocation_end, 0, 128, 64, 3), + led(6, fw_update_start, 32, 128, 64, 3), + led(7, fw_update_erase_fail, 32, 128, 32, 3), + led(8, fw_update_invalid_response, 64, 0, 0, 1), + led(9, fw_update_timeout, 64, 0, 0, 2), + led(a, fw_update_invalid_crc, 64, 0, 0, 4), + led(b, jump_to_app, 0, 128, 0, 10), + +}; + +void board_indicate(uiindication_t indication) +{ + rgb_led(i2l[indication].red, + i2l[indication].green, + i2l[indication].blue, + i2l[indication].hz); +} diff --git a/boards/ark/f9p-gps/src/boot_config.h b/boards/ark/f9p-gps/src/boot_config.h new file mode 100644 index 0000000000..7da61bb2bb --- /dev/null +++ b/boards/ark/f9p-gps/src/boot_config.h @@ -0,0 +1,130 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* + * @file boot_config.h + * + * bootloader definitions that configures the behavior and options + * of the Boot loader + * This file is relies on the parent folder's boot_config.h file and defines + * different usages of the hardware for bootloading + */ + +#pragma once + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +/* Bring in the board_config.h definitions + * todo:make this be pulled in from a targed's build + * files in nuttx*/ + +#include "board_config.h" +#include "uavcan.h" +#include + +#include + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define OPT_PREFERRED_NODE_ID ANY_NODE_ID + +//todo:wrap OPT_x in in ifdefs for command line definitions +#define OPT_TBOOT_MS 3000 +#define OPT_NODE_STATUS_RATE_MS 800 +#define OPT_NODE_INFO_RATE_MS 50 +#define OPT_BL_NUMBER_TIMERS 7 + +/* + * This Option set is set to 1 ensure a provider of firmware has an + * opportunity update the node's firmware. + * This Option is the default policy and can be overridden by + * a jumper + * When this Policy is set, the node will ignore tboot and + * wait indefinitely for a GetNodeInfo request before booting. + * + * OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT is used to allow + * the polarity of the jumper to be True Active + * + * wait OPT_WAIT_FOR_GETNODEINFO OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO + * Jumper + * yes 1 0 x + * yes 1 1 Active + * no 1 1 Not Active + * no 0 0 X + * yes 0 1 Active + * no 0 1 Not Active + * + */ +#define OPT_WAIT_FOR_GETNODEINFO 0 +#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO 1 +#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 1 + +#define OPT_ENABLE_WD 1 + +#define OPT_RESTART_TIMEOUT_MS 20000 + +/* Reserved for the Booloader */ +#define OPT_BOOTLOADER_SIZE_IN_K (1024*64) + +/* Reserved for the application out of the total + * system flash minus the BOOTLOADER_SIZE_IN_K + */ +#define OPT_APPLICATION_RESERVER_IN_K 0 + +#define OPT_APPLICATION_IMAGE_OFFSET OPT_BOOTLOADER_SIZE_IN_K +#define OPT_APPLICATION_IMAGE_LENGTH (FLASH_SIZE-(OPT_BOOTLOADER_SIZE_IN_K+OPT_APPLICATION_RESERVER_IN_K)) + + +#define FLASH_BASE STM32_FLASH_BASE +#define FLASH_SIZE STM32_FLASH_SIZE + +#define APPLICATION_LOAD_ADDRESS (FLASH_BASE + OPT_APPLICATION_IMAGE_OFFSET) +#define APPLICATION_SIZE (FLASH_SIZE-OPT_APPLICATION_IMAGE_OFFSET) +#define APPLICATION_LAST_8BIT_ADDRRESS ((uint8_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint8_t))) +#define APPLICATION_LAST_32BIT_ADDRRESS ((uint32_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint32_t))) +#define APPLICATION_LAST_64BIT_ADDRRESS ((uint64_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint64_t))) + +/* If this board uses big flash that have large sectors */ + +#define OPT_USE_YIELD + +/* Bootloader Option***************************************************************** + * + */ +#define GPIO_GETNODEINFO_JUMPER (GPIO_BOOT_CONFIG & ~GPIO_EXTI) diff --git a/boards/ark/f9p-gps/src/can.c b/boards/ark/f9p-gps/src/can.c new file mode 100644 index 0000000000..bb1a7025e8 --- /dev/null +++ b/boards/ark/f9p-gps/src/can.c @@ -0,0 +1,130 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file can.c + * + * Board-specific CAN functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_internal.h" + +#include "stm32.h" +#include "stm32_can.h" +#include "board_config.h" + +#ifdef CONFIG_CAN + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) +# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." +# undef CONFIG_STM32_CAN2 +#endif + +#ifdef CONFIG_STM32_CAN1 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int can_devinit(void); + +/************************************************************************************ + * Name: can_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/can. + * + ************************************************************************************/ + +int can_devinit(void) +{ + static bool initialized = false; + struct can_dev_s *can; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) { + /* Call stm32_caninitialize() to get an instance of the CAN interface */ + + can = stm32_caninitialize(CAN_PORT); + + if (can == NULL) { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + + if (ret < 0) { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} + +#endif diff --git a/boards/ark/f9p-gps/src/i2c.cpp b/boards/ark/f9p-gps/src/i2c.cpp new file mode 100644 index 0000000000..6700d8c8f2 --- /dev/null +++ b/boards/ark/f9p-gps/src/i2c.cpp @@ -0,0 +1,39 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusInternal(1), + initI2CBusExternal(2), +}; diff --git a/boards/ark/f9p-gps/src/init.c b/boards/ark/f9p-gps/src/init.c new file mode 100644 index 0000000000..c036e72f56 --- /dev/null +++ b/boards/ark/f9p-gps/src/init.c @@ -0,0 +1,168 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * board specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialization. + */ + +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include "board_config.h" +#include "led.h" +#include + +#include + +#include +#include +#include + +#include + +#include +#include + +# if defined(FLASH_BASED_PARAMS) +# include +#endif + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +__EXPORT void stm32_boardinitialize(void) +{ + watchdog_init(); + + /* configure pins */ + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + // Configure SPI all interfaces GPIO & enable power. + stm32_spiinitialize(); + + // Check if button is held. If so go into gps passthrough mode + if (stm32_gpioread(GPIO_BTN_SAFETY)) { + rgb_led(128, 128, 128, 10); + stm32_configgpio(GPIO_USART1_TX_GPIO); + stm32_configgpio(GPIO_USART1_RX_GPIO); + stm32_configgpio(GPIO_USART2_TX_GPIO); + stm32_configgpio(GPIO_USART2_RX_GPIO); + + while (1) { + watchdog_pet(); + stm32_gpiowrite(GPIO_USART2_TX_GPIO, stm32_gpioread(GPIO_USART1_RX_GPIO)); + stm32_gpiowrite(GPIO_USART1_TX_GPIO, stm32_gpioread(GPIO_USART2_RX_GPIO)); + } + } +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + px4_platform_init(); + +#if defined(SERIAL_HAVE_RXDMA) + // set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event. + static struct hrt_call serial_dma_call; + hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL); +#endif + +#if defined(FLASH_BASED_PARAMS) + static sector_descriptor_t params_sector_map[] = { + {2, 16 * 1024, 0x08008000}, + {3, 16 * 1024, 0x0800C000}, + {0, 0, 0}, + }; + + /* Initialize the flashfs layer to use heap allocated memory */ + int result = parameter_flashfs_init(params_sector_map, NULL, 0); + + if (result != OK) { + syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result); + } + +#endif // FLASH_BASED_PARAMS + + /* Configure the HW based on the manifest */ + //px4_platform_configure(); + + return OK; +} diff --git a/boards/ark/f9p-gps/src/led.c b/boards/ark/f9p-gps/src/led.c new file mode 100644 index 0000000000..d2a2126d33 --- /dev/null +++ b/boards/ark/f9p-gps/src/led.c @@ -0,0 +1,124 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +#include "led.h" + +#define TMR_BASE STM32_TIM1_BASE +#define TMR_FREQUENCY STM32_APB2_TIM1_CLKIN +#define TMR_REG(o) (TMR_BASE+(o)) + +void rgb_led(int r, int g, int b, int freqs) +{ + + long fosc = TMR_FREQUENCY; + long prescale = 2048; + long p1s = fosc / prescale; + long p0p5s = p1s / 2; + uint16_t val; + static bool once = 0; + + if (!once) { + once = 1; + + /* Enabel Clock to Block */ + modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_TIM1EN); + + /* Reload */ + + val = getreg16(TMR_REG(STM32_BTIM_EGR_OFFSET)); + val |= ATIM_EGR_UG; + putreg16(val, TMR_REG(STM32_BTIM_EGR_OFFSET)); + + /* Set Prescaler STM32_TIM_SETCLOCK */ + + putreg16(prescale, TMR_REG(STM32_BTIM_PSC_OFFSET)); + + /* Enable STM32_TIM_SETMODE*/ + + putreg16(ATIM_CR1_CEN | ATIM_CR1_ARPE, TMR_REG(STM32_BTIM_CR1_OFFSET)); + + + putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC1M_SHIFT) | ATIM_CCMR1_OC1PE | + (ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC2M_SHIFT) | ATIM_CCMR1_OC2PE, TMR_REG(STM32_GTIM_CCMR1_OFFSET)); + putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC3M_SHIFT) | ATIM_CCMR2_OC3PE, TMR_REG(STM32_GTIM_CCMR2_OFFSET)); + putreg16(ATIM_CCER_CC3E | ATIM_CCER_CC3P | + ATIM_CCER_CC2E | ATIM_CCER_CC2P | + ATIM_CCER_CC1E | ATIM_CCER_CC1P, TMR_REG(STM32_GTIM_CCER_OFFSET)); + + + stm32_configgpio(GPIO_TIM1_CH1); + stm32_configgpio(GPIO_TIM1_CH2); + stm32_configgpio(GPIO_TIM1_CH3); + + /* master output enable = on */ + putreg16(ATIM_BDTR_MOE, (TMR_REG(STM32_ATIM_BDTR_OFFSET))); + } + + long p = freqs == 0 ? p1s : p1s / freqs; + putreg32(p, TMR_REG(STM32_BTIM_ARR_OFFSET)); + + p = freqs == 0 ? p1s + 1 : p0p5s / freqs; + + putreg32((r * p) / 255, TMR_REG(STM32_GTIM_CCR1_OFFSET)); + putreg32((g * p) / 255, TMR_REG(STM32_GTIM_CCR2_OFFSET)); + putreg32((b * p) / 255, TMR_REG(STM32_GTIM_CCR3_OFFSET)); + + val = getreg16(TMR_REG(STM32_BTIM_CR1_OFFSET)); + + if (freqs == 0) { + val &= ~ATIM_CR1_CEN; + + } else { + val |= ATIM_CR1_CEN; + } + + putreg16(val, TMR_REG(STM32_BTIM_CR1_OFFSET)); + +} diff --git a/boards/ark/f9p-gps/src/led.h b/boards/ark/f9p-gps/src/led.h new file mode 100644 index 0000000000..0d71157cc8 --- /dev/null +++ b/boards/ark/f9p-gps/src/led.h @@ -0,0 +1,37 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * Author: David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +__BEGIN_DECLS +void rgb_led(int r, int g, int b, int freqs); +__END_DECLS diff --git a/boards/ark/f9p-gps/src/spi.cpp b/boards/ark/f9p-gps/src/spi.cpp new file mode 100644 index 0000000000..baafb0354c --- /dev/null +++ b/boards/ark/f9p-gps/src/spi.cpp @@ -0,0 +1,44 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortB, GPIO::Pin0}, SPI::DRDY{GPIO::PortB, GPIO::Pin1}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/ark/f9p-gps/uavcan_board_identity b/boards/ark/f9p-gps/uavcan_board_identity new file mode 100644 index 0000000000..59ef104022 --- /dev/null +++ b/boards/ark/f9p-gps/uavcan_board_identity @@ -0,0 +1,17 @@ +# UAVCAN boot loadable Module ID +set(uavcanblid_sw_version_major ${PX4_VERSION_MAJOR}) +set(uavcanblid_sw_version_minor ${PX4_VERSION_MINOR}) +add_definitions( + -DAPP_VERSION_MAJOR=${uavcanblid_sw_version_major} + -DAPP_VERSION_MINOR=${uavcanblid_sw_version_minor} +) + +set(uavcanblid_hw_version_major 0) +set(uavcanblid_hw_version_minor 90) +set(uavcanblid_name "\"org.ark.f9p-gps\"") + +add_definitions( + -DHW_UAVCAN_NAME=${uavcanblid_name} + -DHW_VERSION_MAJOR=${uavcanblid_hw_version_major} + -DHW_VERSION_MINOR=${uavcanblid_hw_version_minor} +) diff --git a/boards/ark/x20-gps/canbootloader.px4board b/boards/ark/x20-gps/canbootloader.px4board new file mode 100644 index 0000000000..46917280f6 --- /dev/null +++ b/boards/ark/x20-gps/canbootloader.px4board @@ -0,0 +1,5 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m4" +CONFIG_BOARD_ROMFSROOT="" +CONFIG_BOARD_CONSTRAINED_MEMORY=y +CONFIG_DRIVERS_BOOTLOADERS=y diff --git a/boards/ark/x20-gps/default.px4board b/boards/ark/x20-gps/default.px4board new file mode 100644 index 0000000000..6c79012be7 --- /dev/null +++ b/boards/ark/x20-gps/default.px4board @@ -0,0 +1,37 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m4" +CONFIG_BOARD_ROMFSROOT="cannode" +CONFIG_BOARD_CONSTRAINED_MEMORY=y +CONFIG_DRIVERS_BAROMETER_BMP388=y +CONFIG_DRIVERS_BOOTLOADERS=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_DRIVERS_MAGNETOMETER_ST_IIS2MDC=y +CONFIG_DRIVERS_SAFETY_BUTTON=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_BOARD_UAVCAN_INTERFACES=1 +CONFIG_DRIVERS_UAVCANNODE=y +CONFIG_UAVCANNODE_BEEP_COMMAND=y +CONFIG_UAVCANNODE_GNSS_FIX=y +CONFIG_UAVCANNODE_LIGHTS_COMMAND=y +CONFIG_UAVCANNODE_MAGNETIC_FIELD_STRENGTH=y +CONFIG_UAVCANNODE_RTK_DATA=y +CONFIG_UAVCANNODE_RAW_IMU=y +CONFIG_UAVCANNODE_SAFETY_BUTTON=y +CONFIG_UAVCANNODE_STATIC_PRESSURE=y +CONFIG_UAVCANNODE_STATIC_TEMPERATURE=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_SENSORS=y +# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set +# CONFIG_SENSORS_VEHICLE_AIR_DATA is not set +# CONFIG_SENSORS_VEHICLE_GPS_POSITION is not set +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/ark/x20-gps/firmware.prototype b/boards/ark/x20-gps/firmware.prototype new file mode 100644 index 0000000000..d63aa2d618 --- /dev/null +++ b/boards/ark/x20-gps/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 89, + "magic": "PX4FWv1", + "description": "Firmware for the ARK X20 GPS", + "image": "", + "build_time": 0, + "summary": "ARKX20GPS", + "version": "0.1", + "image_size": 0, + "image_maxsize": 2080768, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/ark/x20-gps/init/rc.board_defaults b/boards/ark/x20-gps/init/rc.board_defaults new file mode 100644 index 0000000000..63f479fe53 --- /dev/null +++ b/boards/ark/x20-gps/init/rc.board_defaults @@ -0,0 +1,13 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ + +param set-default CBRK_IO_SAFETY 0 +param set-default CANNODE_SUB_MBD 1 +param set-default CANNODE_SUB_RTCM 1 +param set-default GPS_1_GNSS 47 +param set-default SENS_IMU_CLPNOTI 0 + +safety_button start +tone_alarm start diff --git a/boards/ark/x20-gps/init/rc.board_sensors b/boards/ark/x20-gps/init/rc.board_sensors new file mode 100644 index 0000000000..25bb268272 --- /dev/null +++ b/boards/ark/x20-gps/init/rc.board_sensors @@ -0,0 +1,11 @@ +#!/bin/sh +# +# board sensors init +#------------------------------------------------------------------------------ +gps start -d /dev/ttyS0 -p ubx + +icm42688p -R 0 -s start + +bmp388 -I -b 1 start + +iis2mdc -R 2 -I -b 1 start diff --git a/boards/ark/x20-gps/nuttx-config/canbootloader/defconfig b/boards/ark/x20-gps/nuttx-config/canbootloader/defconfig new file mode 100644 index 0000000000..d50bae4a9b --- /dev/null +++ b/boards/ark/x20-gps/nuttx-config/canbootloader/defconfig @@ -0,0 +1,57 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/x20-gps/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F412CE=y +CONFIG_ARCH_INTERRUPTSTACK=4096 +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BINFMT_DISABLE=y +CONFIG_BOARDCTL=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DISABLE_MOUNTPOINT=y +CONFIG_EXPERIMENTAL=y +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=4096 +CONFIG_INIT_STACKSIZE=4096 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MM_REGIONS=2 +CONFIG_NAME_MAX=0 +CONFIG_NUNGET_CHARS=0 +CONFIG_PREALLOC_TIMERS=0 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=262144 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_DISABLE_BUFFERING=y +CONFIG_STM32_FLASH_CONFIG_G=y +CONFIG_STM32_NOEXT_VECTORS=y +CONFIG_STM32_TIM8=y +CONFIG_TASK_NAME_SIZE=0 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/ark/x20-gps/nuttx-config/include/board.h b/boards/ark/x20-gps/nuttx-config/include/board.h new file mode 100644 index 0000000000..526392b92b --- /dev/null +++ b/boards/ark/x20-gps/nuttx-config/include/board.h @@ -0,0 +1,152 @@ +/************************************************************************************ + * configs/px4fmu/include/board.h + * include/arch/board/board.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ +#include "board_dma_map.h" + +#ifndef __ARCH_BOARD_BOARD_H +#define __ARCH_BOARD_BOARD_H + +#include +#ifndef __ASSEMBLY__ +# include +#endif + +#include + +/* HSI - 8 MHz RC factory-trimmed + * LSI - 32 KHz RC + * HSE - 8 MHz Crystal + * LSE - not installed + */ +#define STM32_BOARD_USEHSE 1 +#define STM32_BOARD_XTAL 8000000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 + +/* Main PLL Configuration */ +#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8) +#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(384) +#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_4 +#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(8) +#define STM32_PLLCFG_PLLR RCC_PLLCFG_PLLR(2) + +#define STM32_RCC_PLLI2SCFGR_PLLI2SM RCC_PLLI2SCFGR_PLLI2SM(16) +#define STM32_RCC_PLLI2SCFGR_PLLI2SN RCC_PLLI2SCFGR_PLLI2SN(192) +#define STM32_RCC_PLLI2SCFGR_PLLI2SQ RCC_PLLI2SCFGR_PLLI2SQ(2) +#define STM32_RCC_PLLI2SCFGR_PLLI2SR RCC_PLLI2SCFGR_PLLI2SR(2) +#define STM32_RCC_PLLI2SCFGR_PLLI2SSRC RCC_PLLI2SCFGR_PLLI2SSRC(0) /* HSE or HSI depending on PLLSRC of PLLCFGR*/ + +#define STM32_RCC_DCKCFGR2_CK48MSEL RCC_DCKCFGR2_CK48MSEL_PLL +#define STM32_RCC_DCKCFGR2_FMPI2C1SEL RCC_DCKCFGR2_FMPI2C1SEL_APB +#define STM32_RCC_DCKCFGR2_SDIOSEL RCC_DCKCFGR2_SDIOSEL_48MHZ + +#define STM32_SYSCLK_FREQUENCY 96000000ul + +/* AHB clock (HCLK) is SYSCLK (96MHz) */ +#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* Same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (48MHz) */ +#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timers driven from APB1 will be twice PCLK1 (see page 112 of reference manual) */ +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* APB2 clock (PCLK2) is HCLK (96MHz) */ +#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK /* PCLK2 = HCLK */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY) + +/* Timers driven from APB2 will be PCLK2 since no prescale division */ +#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM9_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM10_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM11_CLKIN (STM32_PCLK2_FREQUENCY) + +/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx otherwise frequency is 2xAPBx. */ +#define BOARD_TIM2_FREQUENCY (2 * STM32_PCLK1_FREQUENCY) +#define BOARD_TIM3_FREQUENCY (2 * STM32_PCLK1_FREQUENCY) +#define BOARD_TIM4_FREQUENCY (2 * STM32_PCLK1_FREQUENCY) +#define BOARD_TIM5_FREQUENCY (2 * STM32_PCLK1_FREQUENCY) +#define BOARD_TIM6_FREQUENCY (2 * STM32_PCLK1_FREQUENCY) +#define BOARD_TIM7_FREQUENCY (2 * STM32_PCLK1_FREQUENCY) +#define BOARD_TIM8_FREQUENCY (2 * STM32_PCLK2_FREQUENCY) + +/* Alternate function pin selections ************************************************/ + +/* UARTs */ +#define GPIO_USART1_RX GPIO_USART1_RX_2 +#define GPIO_USART1_TX GPIO_USART1_TX_3 + +#define GPIO_USART2_RX GPIO_USART2_RX_1 +#define GPIO_USART2_TX GPIO_USART2_TX_1 + +/* CAN */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_1 +#define GPIO_CAN1_TX GPIO_CAN1_TX_1 + +/* I2C */ + +#define GPIO_MCU_I2C1_SCL +#define GPIO_MCU_I2C1_SDA + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_1 +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_1 + +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN6) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN7) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_4 + +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10) + +/* SPI */ +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 + +#endif /* __ARCH_BOARD_BOARD_H */ diff --git a/boards/ark/x20-gps/nuttx-config/include/board_dma_map.h b/boards/ark/x20-gps/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..efa3d824b2 --- /dev/null +++ b/boards/ark/x20-gps/nuttx-config/include/board_dma_map.h @@ -0,0 +1,46 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// DMA1 Channel/Stream Selections +//--------------------------------------------//---------------------------//---------------- + + +// DMA2 Channel/Stream Selections +//--------------------------------------------//---------------------------//---------------- +#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_1 // DMA2, Stream 0, Channel 3 +#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_1 // DMA2, Stream 3, Channel 3 +#define DMACHAN_USART1_RX DMAMAP_USART1_RX_1 // DMA2, Stream 2, Channel 4 +#define DMAMAP_USART1_RX DMAMAP_USART1_RX_1 +//#define DMACHAN_USART1_TX DMAMAP_USART1_TX // DMA2, Stream 7, Channel 4 diff --git a/boards/ark/x20-gps/nuttx-config/nsh/defconfig b/boards/ark/x20-gps/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..d7550e73bf --- /dev/null +++ b/boards/ark/x20-gps/nuttx-config/nsh/defconfig @@ -0,0 +1,153 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/x20-gps/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F412CE=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_CROMFS=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=2624 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MM_REGIONS=2 +CONFIG_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_VARS=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=262144 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_WAITPID=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STM32_ADC1=y +CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y +CONFIG_STM32_DMA1=y +CONFIG_STM32_DMA2=y +CONFIG_STM32_FLASH_CONFIG_G=y +CONFIG_STM32_FLASH_PREFETCH=y +CONFIG_STM32_FLOWCONTROL_BROKEN=y +CONFIG_STM32_I2C1=y +CONFIG_STM32_I2C2=y +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32_SPI1=y +CONFIG_STM32_SPI1_DMA=y +CONFIG_STM32_SPI1_DMA_BUFFER=1024 +CONFIG_STM32_TIM8=y +CONFIG_STM32_USART1=y +CONFIG_STM32_USART2=y +CONFIG_STM32_USART_BREAKS=y +CONFIG_STM32_WWDG=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=2000 +CONFIG_USART1_RXDMA=y +CONFIG_USART1_TXBUFSIZE=2000 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=1100 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/ark/x20-gps/nuttx-config/scripts/canbootloader_script.ld b/boards/ark/x20-gps/nuttx-config/scripts/canbootloader_script.ld new file mode 100644 index 0000000000..6be5cffcd8 --- /dev/null +++ b/boards/ark/x20-gps/nuttx-config/scripts/canbootloader_script.ld @@ -0,0 +1,134 @@ +/**************************************************************************** + * nuttx-config/scripts/canbootloader_script.ld + * + * Copyright (c) 2025 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The STM32F412 has 1M of FLASH beginning at address 0x0800:0000 and + * 256Kb of SRAM. SRAM is split up into three blocks: + * + * 1) 112Kb of SRAM beginning at address 0x2000:0000 + * 2) 16Kb of SRAM beginning at address 0x2001:c000 + * 3) 64Kb of SRAM beginning at address 0x2002:0000 + * 4) 64Kb of TCM SRAM beginning at address 0x1000:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The first 0x10000 of flash is reserved for the bootloader. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08000000, LENGTH = 32K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K +} + +OUTPUT_ARCH(arm) + +ENTRY(__start) /* treat __start as the anchor for dead code stripping */ +EXTERN(_vectors) /* force the vectors to be included in the output */ + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/ark/x20-gps/nuttx-config/scripts/script.ld b/boards/ark/x20-gps/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..2f4769b8f5 --- /dev/null +++ b/boards/ark/x20-gps/nuttx-config/scripts/script.ld @@ -0,0 +1,146 @@ +/**************************************************************************** + * scripts/ld.script + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The STM32F412 has 1M of FLASH beginning at address 0x0800:0000 and + * 256Kb of SRAM. SRAM is split up into three blocks: + * + * 1) 112Kb of SRAM beginning at address 0x2000:0000 + * 2) 16Kb of SRAM beginning at address 0x2001:c000 + * 3) 64Kb of SRAM beginning at address 0x2002:0000 + * 4) 64Kb of TCM SRAM beginning at address 0x1000:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The first 0x10000 of flash is reserved for the bootloader. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08010000, LENGTH = 928K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K +} + +OUTPUT_ARCH(arm) + +ENTRY(__start) /* treat __start as the anchor for dead code stripping */ +EXTERN(_vectors) /* force the vectors to be included in the output */ + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(8); + /* + * This section positions the app_descriptor_t used + * by the make_can_boot_descriptor.py tool to set + * the application image's descriptor so that the + * uavcan bootloader has the ability to validate the + * image crc, size etc + */ + KEEP(*(.app_descriptor)) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/ark/x20-gps/src/CMakeLists.txt b/boards/ark/x20-gps/src/CMakeLists.txt new file mode 100644 index 0000000000..7f8a23a27e --- /dev/null +++ b/boards/ark/x20-gps/src/CMakeLists.txt @@ -0,0 +1,66 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +if("${PX4_BOARD_LABEL}" STREQUAL "canbootloader") + + add_library(drivers_board + boot_config.h + boot.c + led.c + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch + nuttx_drivers + canbootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/canbootloader) + +else() + add_library(drivers_board + can.c + i2c.cpp + init.c + led.c + spi.cpp + ) + + target_link_libraries(drivers_board + PRIVATE + arch_spi + drivers__led # drv_led_start + nuttx_arch + nuttx_drivers + px4_layer + ) +endif() diff --git a/boards/ark/x20-gps/src/board_config.h b/boards/ark/x20-gps/src/board_config.h new file mode 100644 index 0000000000..2d5f582075 --- /dev/null +++ b/boards/ark/x20-gps/src/board_config.h @@ -0,0 +1,125 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * board internal definitions + */ + +#pragma once + +#include +#include +#include + +/* BUTTON */ +#define GPIO_BTN_SAFETY /* PB15 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTB|GPIO_PIN15) + +/* Safety LED */ +#define GPIO_LED_SAFETY /* PA1 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN1) + +/* Tone alarm output. */ +#define TONE_ALARM_TIMER 2 /* timer 2 */ +#define TONE_ALARM_CHANNEL 1 /* channel 1 */ +#define GPIO_TONE_ALARM_IDLE /* PA0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0) +#define GPIO_TONE_ALARM /* PA0 */ (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0) + +/* CAN Silent mode control */ +#define GPIO_CAN1_SILENT_S0 /* PB12 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN12) + +/* CAN termination software control */ +#define GPIO_CAN1_TERMINATION /* PB13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN13) +#define GPIO_CAN_TERM GPIO_CAN1_TERMINATION + +/* ICM42688p FSYNC */ +#define GPIO_42688P_FSYNC /* PB8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8) + +/* Boot config */ +#define GPIO_BOOT_CONFIG /* PC15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN15|GPIO_EXTI) + +/* LEDs are driven with open drain to support Anode to 5V or 3.3V */ +#define GPIO_TIM1_CH1 /* PA8 */ (GPIO_TIM1_CH1_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz) +#define GPIO_TIM1_CH2 /* PA9 */ (GPIO_TIM1_CH2_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz) +#define GPIO_TIM1_CH3 /* PA10 */ (GPIO_TIM1_CH3_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz) + +#define GPIO_I2C1_SCL_RESET /* PB6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN6) +#define GPIO_I2C1_SDA_RESET /* PB7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN7) + +#define GPIO_I2C2_SCL_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10) +#define GPIO_I2C2_SDA_RESET /* PB9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9) + +#define GPIO_I2C2_SCL_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10) +#define GPIO_I2C2_SDA_RESET /* PB9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9) + +#define GPIO_USART1_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN3) +#define GPIO_USART1_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN15) + +#define GPIO_USART2_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN3) +#define GPIO_USART2_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN2) + +#define FLASH_BASED_PARAMS + +/* High-resolution timer */ +#define HRT_TIMER 3 /* use timer 3 for the HRT */ +#define HRT_TIMER_CHANNEL 4 /* use capture/compare channel 4 */ + +#define PX4_GPIO_INIT_LIST { \ + GPIO_BTN_SAFETY, \ + GPIO_LED_SAFETY, \ + GPIO_I2C1_SCL_RESET, \ + GPIO_I2C1_SDA_RESET, \ + GPIO_I2C2_SCL_RESET, \ + GPIO_I2C2_SDA_RESET, \ + GPIO_42688P_FSYNC, \ + GPIO_BOOT_CONFIG, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN1_SILENT_S0, \ + GPIO_CAN1_TERMINATION, \ + } + +__BEGIN_DECLS + +#define BOARD_HAS_N_S_RGB_LED 1 +#define BOARD_MAX_LEDS BOARD_HAS_N_S_RGB_LED + +#ifndef __ASSEMBLY__ + +extern void stm32_spiinitialize(void); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/ark/x20-gps/src/boot.c b/boards/ark/x20-gps/src/boot.c new file mode 100644 index 0000000000..3efdba508c --- /dev/null +++ b/boards/ark/x20-gps/src/boot.c @@ -0,0 +1,188 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * Author: Ben Dyer + * Pavel Kirienko + * David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include "boot_config.h" +#include "board.h" + +#include +#include +#include + +#include +#include "led.h" + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +__EXPORT void stm32_boardinitialize(void) +{ + putreg32(getreg32(STM32_RCC_APB1ENR) | RCC_APB1ENR_CAN1EN, STM32_RCC_APB1ENR); + stm32_configgpio(GPIO_CAN1_RX); + stm32_configgpio(GPIO_CAN1_TX); + stm32_configgpio(GPIO_CAN1_SILENT_S0); + stm32_configgpio(GPIO_CAN1_TERMINATION); + putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR); + putreg32(getreg32(STM32_RCC_APB1RSTR) & ~RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR); + +#if defined(OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO) + stm32_configgpio(GPIO_GETNODEINFO_JUMPER); +#endif + +} + +/************************************************************************************ + * Name: board_deinitialize + * + * Description: + * This function is called by the bootloader code prior to booting + * the application. Is should place the HW into an benign initialized state. + * + ************************************************************************************/ + +void board_deinitialize(void) +{ + putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR); +} + +/**************************************************************************** + * Name: board_get_product_name + * + * Description: + * Called to retrieve the product name. The returned value is a assumed + * to be written to a pascal style string that will be length prefixed + * and not null terminated + * + * Input Parameters: + * product_name - A pointer to a buffer to write the name. + * maxlen - The maximum number of charter that can be written + * + * Returned Value: + * The length of characters written to the buffer. + * + ****************************************************************************/ + +uint8_t board_get_product_name(uint8_t *product_name, size_t maxlen) +{ + DEBUGASSERT(maxlen > UAVCAN_STRLEN(HW_UAVCAN_NAME)); + memcpy(product_name, HW_UAVCAN_NAME, UAVCAN_STRLEN(HW_UAVCAN_NAME)); + return UAVCAN_STRLEN(HW_UAVCAN_NAME); +} + +/**************************************************************************** + * Name: board_get_hardware_version + * + * Description: + * Called to retrieve the hardware version information. The function + * will first initialize the the callers struct to all zeros. + * + * Input Parameters: + * hw_version - A pointer to a uavcan_hardwareversion_t. + * + * Returned Value: + * Length of the unique_id + * + ****************************************************************************/ + +size_t board_get_hardware_version(uavcan_HardwareVersion_t *hw_version) +{ + memset(hw_version, 0, sizeof(uavcan_HardwareVersion_t)); + + hw_version->major = HW_VERSION_MAJOR; + hw_version->minor = HW_VERSION_MINOR; + + return board_get_mfguid(*(mfguid_t *) hw_version->unique_id); +} + +/**************************************************************************** + * Name: board_indicate + * + * Description: + * Provides User feedback to indicate the state of the bootloader + * on board specific hardware. + * + * Input Parameters: + * indication - A member of the uiindication_t + * + * Returned Value: + * None + * + ****************************************************************************/ +#define led(n, code, r , g , b, h) {.red = (r),.green = (g), .blue = (b),.hz = (h)} + +typedef begin_packed_struct struct led_t { + uint8_t red; + uint8_t green; + uint8_t blue; + uint8_t hz; +} end_packed_struct led_t; + +static const led_t i2l[] = { + + led(0, off, 0, 0, 0, 0), + led(1, reset, 128, 128, 128, 30), + led(2, autobaud_start, 0, 128, 0, 1), + led(3, autobaud_end, 0, 128, 0, 2), + led(4, allocation_start, 0, 0, 64, 2), + led(5, allocation_end, 0, 128, 64, 3), + led(6, fw_update_start, 32, 128, 64, 3), + led(7, fw_update_erase_fail, 32, 128, 32, 3), + led(8, fw_update_invalid_response, 64, 0, 0, 1), + led(9, fw_update_timeout, 64, 0, 0, 2), + led(a, fw_update_invalid_crc, 64, 0, 0, 4), + led(b, jump_to_app, 0, 128, 0, 10), + +}; + +void board_indicate(uiindication_t indication) +{ + rgb_led(i2l[indication].red, + i2l[indication].green, + i2l[indication].blue, + i2l[indication].hz); +} diff --git a/boards/ark/x20-gps/src/boot_config.h b/boards/ark/x20-gps/src/boot_config.h new file mode 100644 index 0000000000..7da61bb2bb --- /dev/null +++ b/boards/ark/x20-gps/src/boot_config.h @@ -0,0 +1,130 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* + * @file boot_config.h + * + * bootloader definitions that configures the behavior and options + * of the Boot loader + * This file is relies on the parent folder's boot_config.h file and defines + * different usages of the hardware for bootloading + */ + +#pragma once + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +/* Bring in the board_config.h definitions + * todo:make this be pulled in from a targed's build + * files in nuttx*/ + +#include "board_config.h" +#include "uavcan.h" +#include + +#include + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define OPT_PREFERRED_NODE_ID ANY_NODE_ID + +//todo:wrap OPT_x in in ifdefs for command line definitions +#define OPT_TBOOT_MS 3000 +#define OPT_NODE_STATUS_RATE_MS 800 +#define OPT_NODE_INFO_RATE_MS 50 +#define OPT_BL_NUMBER_TIMERS 7 + +/* + * This Option set is set to 1 ensure a provider of firmware has an + * opportunity update the node's firmware. + * This Option is the default policy and can be overridden by + * a jumper + * When this Policy is set, the node will ignore tboot and + * wait indefinitely for a GetNodeInfo request before booting. + * + * OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT is used to allow + * the polarity of the jumper to be True Active + * + * wait OPT_WAIT_FOR_GETNODEINFO OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO + * Jumper + * yes 1 0 x + * yes 1 1 Active + * no 1 1 Not Active + * no 0 0 X + * yes 0 1 Active + * no 0 1 Not Active + * + */ +#define OPT_WAIT_FOR_GETNODEINFO 0 +#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO 1 +#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 1 + +#define OPT_ENABLE_WD 1 + +#define OPT_RESTART_TIMEOUT_MS 20000 + +/* Reserved for the Booloader */ +#define OPT_BOOTLOADER_SIZE_IN_K (1024*64) + +/* Reserved for the application out of the total + * system flash minus the BOOTLOADER_SIZE_IN_K + */ +#define OPT_APPLICATION_RESERVER_IN_K 0 + +#define OPT_APPLICATION_IMAGE_OFFSET OPT_BOOTLOADER_SIZE_IN_K +#define OPT_APPLICATION_IMAGE_LENGTH (FLASH_SIZE-(OPT_BOOTLOADER_SIZE_IN_K+OPT_APPLICATION_RESERVER_IN_K)) + + +#define FLASH_BASE STM32_FLASH_BASE +#define FLASH_SIZE STM32_FLASH_SIZE + +#define APPLICATION_LOAD_ADDRESS (FLASH_BASE + OPT_APPLICATION_IMAGE_OFFSET) +#define APPLICATION_SIZE (FLASH_SIZE-OPT_APPLICATION_IMAGE_OFFSET) +#define APPLICATION_LAST_8BIT_ADDRRESS ((uint8_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint8_t))) +#define APPLICATION_LAST_32BIT_ADDRRESS ((uint32_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint32_t))) +#define APPLICATION_LAST_64BIT_ADDRRESS ((uint64_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint64_t))) + +/* If this board uses big flash that have large sectors */ + +#define OPT_USE_YIELD + +/* Bootloader Option***************************************************************** + * + */ +#define GPIO_GETNODEINFO_JUMPER (GPIO_BOOT_CONFIG & ~GPIO_EXTI) diff --git a/boards/ark/x20-gps/src/can.c b/boards/ark/x20-gps/src/can.c new file mode 100644 index 0000000000..bb1a7025e8 --- /dev/null +++ b/boards/ark/x20-gps/src/can.c @@ -0,0 +1,130 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file can.c + * + * Board-specific CAN functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_internal.h" + +#include "stm32.h" +#include "stm32_can.h" +#include "board_config.h" + +#ifdef CONFIG_CAN + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) +# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." +# undef CONFIG_STM32_CAN2 +#endif + +#ifdef CONFIG_STM32_CAN1 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int can_devinit(void); + +/************************************************************************************ + * Name: can_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/can. + * + ************************************************************************************/ + +int can_devinit(void) +{ + static bool initialized = false; + struct can_dev_s *can; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) { + /* Call stm32_caninitialize() to get an instance of the CAN interface */ + + can = stm32_caninitialize(CAN_PORT); + + if (can == NULL) { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + + if (ret < 0) { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} + +#endif diff --git a/boards/ark/x20-gps/src/i2c.cpp b/boards/ark/x20-gps/src/i2c.cpp new file mode 100644 index 0000000000..6700d8c8f2 --- /dev/null +++ b/boards/ark/x20-gps/src/i2c.cpp @@ -0,0 +1,39 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusInternal(1), + initI2CBusExternal(2), +}; diff --git a/boards/ark/x20-gps/src/init.c b/boards/ark/x20-gps/src/init.c new file mode 100644 index 0000000000..c036e72f56 --- /dev/null +++ b/boards/ark/x20-gps/src/init.c @@ -0,0 +1,168 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * board specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialization. + */ + +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include "board_config.h" +#include "led.h" +#include + +#include + +#include +#include +#include + +#include + +#include +#include + +# if defined(FLASH_BASED_PARAMS) +# include +#endif + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +__EXPORT void stm32_boardinitialize(void) +{ + watchdog_init(); + + /* configure pins */ + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + // Configure SPI all interfaces GPIO & enable power. + stm32_spiinitialize(); + + // Check if button is held. If so go into gps passthrough mode + if (stm32_gpioread(GPIO_BTN_SAFETY)) { + rgb_led(128, 128, 128, 10); + stm32_configgpio(GPIO_USART1_TX_GPIO); + stm32_configgpio(GPIO_USART1_RX_GPIO); + stm32_configgpio(GPIO_USART2_TX_GPIO); + stm32_configgpio(GPIO_USART2_RX_GPIO); + + while (1) { + watchdog_pet(); + stm32_gpiowrite(GPIO_USART2_TX_GPIO, stm32_gpioread(GPIO_USART1_RX_GPIO)); + stm32_gpiowrite(GPIO_USART1_TX_GPIO, stm32_gpioread(GPIO_USART2_RX_GPIO)); + } + } +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + px4_platform_init(); + +#if defined(SERIAL_HAVE_RXDMA) + // set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event. + static struct hrt_call serial_dma_call; + hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL); +#endif + +#if defined(FLASH_BASED_PARAMS) + static sector_descriptor_t params_sector_map[] = { + {2, 16 * 1024, 0x08008000}, + {3, 16 * 1024, 0x0800C000}, + {0, 0, 0}, + }; + + /* Initialize the flashfs layer to use heap allocated memory */ + int result = parameter_flashfs_init(params_sector_map, NULL, 0); + + if (result != OK) { + syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result); + } + +#endif // FLASH_BASED_PARAMS + + /* Configure the HW based on the manifest */ + //px4_platform_configure(); + + return OK; +} diff --git a/boards/ark/x20-gps/src/led.c b/boards/ark/x20-gps/src/led.c new file mode 100644 index 0000000000..d2a2126d33 --- /dev/null +++ b/boards/ark/x20-gps/src/led.c @@ -0,0 +1,124 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +#include "led.h" + +#define TMR_BASE STM32_TIM1_BASE +#define TMR_FREQUENCY STM32_APB2_TIM1_CLKIN +#define TMR_REG(o) (TMR_BASE+(o)) + +void rgb_led(int r, int g, int b, int freqs) +{ + + long fosc = TMR_FREQUENCY; + long prescale = 2048; + long p1s = fosc / prescale; + long p0p5s = p1s / 2; + uint16_t val; + static bool once = 0; + + if (!once) { + once = 1; + + /* Enabel Clock to Block */ + modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_TIM1EN); + + /* Reload */ + + val = getreg16(TMR_REG(STM32_BTIM_EGR_OFFSET)); + val |= ATIM_EGR_UG; + putreg16(val, TMR_REG(STM32_BTIM_EGR_OFFSET)); + + /* Set Prescaler STM32_TIM_SETCLOCK */ + + putreg16(prescale, TMR_REG(STM32_BTIM_PSC_OFFSET)); + + /* Enable STM32_TIM_SETMODE*/ + + putreg16(ATIM_CR1_CEN | ATIM_CR1_ARPE, TMR_REG(STM32_BTIM_CR1_OFFSET)); + + + putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC1M_SHIFT) | ATIM_CCMR1_OC1PE | + (ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC2M_SHIFT) | ATIM_CCMR1_OC2PE, TMR_REG(STM32_GTIM_CCMR1_OFFSET)); + putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC3M_SHIFT) | ATIM_CCMR2_OC3PE, TMR_REG(STM32_GTIM_CCMR2_OFFSET)); + putreg16(ATIM_CCER_CC3E | ATIM_CCER_CC3P | + ATIM_CCER_CC2E | ATIM_CCER_CC2P | + ATIM_CCER_CC1E | ATIM_CCER_CC1P, TMR_REG(STM32_GTIM_CCER_OFFSET)); + + + stm32_configgpio(GPIO_TIM1_CH1); + stm32_configgpio(GPIO_TIM1_CH2); + stm32_configgpio(GPIO_TIM1_CH3); + + /* master output enable = on */ + putreg16(ATIM_BDTR_MOE, (TMR_REG(STM32_ATIM_BDTR_OFFSET))); + } + + long p = freqs == 0 ? p1s : p1s / freqs; + putreg32(p, TMR_REG(STM32_BTIM_ARR_OFFSET)); + + p = freqs == 0 ? p1s + 1 : p0p5s / freqs; + + putreg32((r * p) / 255, TMR_REG(STM32_GTIM_CCR1_OFFSET)); + putreg32((g * p) / 255, TMR_REG(STM32_GTIM_CCR2_OFFSET)); + putreg32((b * p) / 255, TMR_REG(STM32_GTIM_CCR3_OFFSET)); + + val = getreg16(TMR_REG(STM32_BTIM_CR1_OFFSET)); + + if (freqs == 0) { + val &= ~ATIM_CR1_CEN; + + } else { + val |= ATIM_CR1_CEN; + } + + putreg16(val, TMR_REG(STM32_BTIM_CR1_OFFSET)); + +} diff --git a/boards/ark/x20-gps/src/led.h b/boards/ark/x20-gps/src/led.h new file mode 100644 index 0000000000..0d71157cc8 --- /dev/null +++ b/boards/ark/x20-gps/src/led.h @@ -0,0 +1,37 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * Author: David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +__BEGIN_DECLS +void rgb_led(int r, int g, int b, int freqs); +__END_DECLS diff --git a/boards/ark/x20-gps/src/spi.cpp b/boards/ark/x20-gps/src/spi.cpp new file mode 100644 index 0000000000..baafb0354c --- /dev/null +++ b/boards/ark/x20-gps/src/spi.cpp @@ -0,0 +1,44 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortB, GPIO::Pin0}, SPI::DRDY{GPIO::PortB, GPIO::Pin1}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/ark/x20-gps/uavcan_board_identity b/boards/ark/x20-gps/uavcan_board_identity new file mode 100644 index 0000000000..c84cc61d2b --- /dev/null +++ b/boards/ark/x20-gps/uavcan_board_identity @@ -0,0 +1,17 @@ +# UAVCAN boot loadable Module ID +set(uavcanblid_sw_version_major ${PX4_VERSION_MAJOR}) +set(uavcanblid_sw_version_minor ${PX4_VERSION_MINOR}) +add_definitions( + -DAPP_VERSION_MAJOR=${uavcanblid_sw_version_major} + -DAPP_VERSION_MINOR=${uavcanblid_sw_version_minor} +) + +set(uavcanblid_hw_version_major 0) +set(uavcanblid_hw_version_minor 89) +set(uavcanblid_name "\"org.ark.x20-gps\"") + +add_definitions( + -DHW_UAVCAN_NAME=${uavcanblid_name} + -DHW_VERSION_MAJOR=${uavcanblid_hw_version_major} + -DHW_VERSION_MINOR=${uavcanblid_hw_version_minor} +) diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h index 147eb049d6..1f74122014 100644 --- a/src/drivers/drv_sensor.h +++ b/src/drivers/drv_sensor.h @@ -214,6 +214,8 @@ #define DRV_GPS_DEVTYPE_UBX_8 0xA8 #define DRV_GPS_DEVTYPE_UBX_9 0xA9 #define DRV_GPS_DEVTYPE_UBX_F9P 0xAA +#define DRV_GPS_DEVTYPE_UBX_10 0xAC +#define DRV_GPS_DEVTYPE_UBX_20 0xAD #define DRV_GPS_DEVTYPE_NMEA 0xAB #define DRV_GPS_DEVTYPE_SIM 0xAF diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index af6508f8cf..91b73c6f6a 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -969,6 +969,14 @@ GPS::run() set_device_type(DRV_GPS_DEVTYPE_UBX_F9P); break; + case GPSDriverUBX::Board::u_blox10_L1L5: + set_device_type(DRV_GPS_DEVTYPE_UBX_10); + break; + + case GPSDriverUBX::Board::u_blox_X20: + set_device_type(DRV_GPS_DEVTYPE_UBX_20); + break; + default: set_device_type(DRV_GPS_DEVTYPE_UBX); break; From b081cf5c31afa5cc1b4e824d744f256230c01a9f Mon Sep 17 00:00:00 2001 From: H S Helson Go Date: Sat, 20 Sep 2025 11:32:00 -0400 Subject: [PATCH 060/812] ucrxe_dds_client: Implement simple parameter-driven message namespace (#25444) * ucrxe_dds_client: Implement simple parameter-driven message namespace * chore: remove change of parameter_reference.md Signed-off-by: Beniamino Pozzan --------- Signed-off-by: Beniamino Pozzan Co-authored-by: Beniamino Pozzan --- docs/en/middleware/uxrce_dds.md | 21 ++++++++++++++++++- src/modules/uxrce_dds_client/module.yaml | 13 ++++++++++++ .../uxrce_dds_client/uxrce_dds_client.cpp | 20 +++++++++++++++++- 3 files changed, 52 insertions(+), 2 deletions(-) diff --git a/docs/en/middleware/uxrce_dds.md b/docs/en/middleware/uxrce_dds.md index 5ab96699cf..d73e475415 100644 --- a/docs/en/middleware/uxrce_dds.md +++ b/docs/en/middleware/uxrce_dds.md @@ -274,6 +274,9 @@ The configuration can be done using the [UXRCE-DDS parameters](../advanced_confi - [UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT): Bridge time synchronization enable. The uXRCE-DDS client module can synchronize the timestamp of the messages exchanged over the bridge. This is the default configuration. In certain situations, for example during [simulations](../ros2/user_guide.md#ros-gazebo-and-px4-time-synchronization), this feature may be disabled. + - [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX): Index-based namespace definition + Setting this parameter to any value other than `-1` creates a namespace with the prefix `uav_` and the specified value, e.g. `uav_0`, `uav_1`, etc. + See [namespace](#customizing-the-namespace) for methods to define richer or arbitrary namespaces. ::: info Many ports are already have a default configuration. @@ -347,7 +350,7 @@ Therefore, ## Customizing the Namespace -Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](../middleware/dds_topics.md)) or at runtime (which is useful for multi vehicle operations): +Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](../middleware/dds_topics.md)), at runtime, or through a parameter (which is useful for multi vehicle operations): - One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line. This technique can be used both in simulation and real vehicles. @@ -376,6 +379,22 @@ will generate topics under the namespaces: ::: +- A simple index-based namespace can be applied by setting the parameter [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) to a value between 0 and 9999. + This will generate a namespace such as `/uav_0`, `/uav_1`, and so on. + This technique is ideal if vehicles must be persistently associated with namespaces because their clients are automatically started through PX4. + +::: info +PX4 parameters cannot carry rich text strings. +Therefore, you cannot use [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) to automatically start a client with an arbitrary message namespace through PX4. +You can however specify a namespace when starting the client, using the `-n` argument: + +```sh +# In etc/extras.txt on the MicroSD card +uxrce_dds_client start -n fancy_uav +``` + +This can be included in `etc/extras.txt` as part of a custom [System Startup](../concept/system_startup.md). + ## PX4 ROS 2 QoS Settings PX4 QoS settings for publishers are incompatible with the default QoS settings for ROS 2 subscribers. diff --git a/src/modules/uxrce_dds_client/module.yaml b/src/modules/uxrce_dds_client/module.yaml index 773475f1f5..3e9d03fcc9 100644 --- a/src/modules/uxrce_dds_client/module.yaml +++ b/src/modules/uxrce_dds_client/module.yaml @@ -129,3 +129,16 @@ parameters: reboot_required: true default: -1 unit: s + + UXRCE_DDS_NS_IDX: + description: + short: Define an index-based message namespace + long: | + Defines an index-based namespace for DDS messages, e.g, uav_0, uav_1, up to uav_9999 + A value less than zero leaves the namespace empty + type: int32 + min: -1 + max: 9999 + category: System + reboot_required: true + default: -1 diff --git a/src/modules/uxrce_dds_client/uxrce_dds_client.cpp b/src/modules/uxrce_dds_client/uxrce_dds_client.cpp index d8beb4f609..d5f2b57042 100644 --- a/src/modules/uxrce_dds_client/uxrce_dds_client.cpp +++ b/src/modules/uxrce_dds_client/uxrce_dds_client.cpp @@ -49,6 +49,7 @@ #include #include +static constexpr char NAMESPACE_PREFIX[] = "uav_"; #define PARTICIPANT_XML_SIZE 512 static constexpr uint8_t TIMESYNC_MAX_TIMEOUTS = 10; @@ -1028,6 +1029,23 @@ UxrceddsClient *UxrceddsClient::instantiate(int argc, char *argv[]) } } + if (client_namespace == nullptr) { + int32_t ns_idx = -1; + param_get(param_find("UXRCE_DDS_NS_IDX"), &ns_idx); + + if (ns_idx > -1) { + if (ns_idx < 10000) { + // Allocate buffer for prefix + '\0' + 4 digits + static char client_namespace_buf[sizeof(NAMESPACE_PREFIX) + 4]; + snprintf(client_namespace_buf, sizeof client_namespace_buf, "%s%u", NAMESPACE_PREFIX, (uint16_t)ns_idx); + client_namespace = client_namespace_buf; + + } else { + PX4_WARN("namespace index must be between 0 and 9999 inclusive; ignoring index-based namespace"); + } + } + } + #if defined(UXRCE_DDS_CLIENT_UDP) if (port[0] == '\0') { @@ -1092,7 +1110,7 @@ $ uxrce_dds_client start -t udp -h 127.0.0.1 -p 15555 PRINT_MODULE_USAGE_PARAM_INT('b', 0, 0, 3000000, "Baudrate (can also be p:)", true); PRINT_MODULE_USAGE_PARAM_STRING('h', nullptr, "", "Agent IP. If not provided, defaults to UXRCE_DDS_AG_IP", true); PRINT_MODULE_USAGE_PARAM_INT('p', -1, 0, 65535, "Agent listening port. If not provided, defaults to UXRCE_DDS_PRT", true); - PRINT_MODULE_USAGE_PARAM_STRING('n', nullptr, nullptr, "Client DDS namespace", true); + PRINT_MODULE_USAGE_PARAM_STRING('n', nullptr, nullptr, "Client DDS namespace. If not provided but UXRCE_DDS_NS_IDX is between 0 and 9999 inclusive, then uav_ + UXRCE_DDS_NS_IDX will be used", true); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); return 0; From f90d6c03fc36a65d6555a70e76dbdb563c7b3ada Mon Sep 17 00:00:00 2001 From: Claudio Chies Date: Wed, 17 Sep 2025 08:47:21 +0200 Subject: [PATCH 061/812] LOG: increase number of loggable batteries to 3 --- src/modules/logger/logged_topics.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index 38d6074d53..822191ac20 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -51,7 +51,7 @@ void LoggedTopics::add_default_topics() add_topic("airspeed", 1000); add_optional_topic("airspeed_validated", 200); add_optional_topic("autotune_attitude_control_status", 100); - add_topic_multi("battery_info", 5000, 2); + add_topic_multi("battery_info", 5000, 3); add_optional_topic("camera_capture"); add_optional_topic("camera_trigger"); add_topic("cellular_status", 200); From d3acee315a9ed36de70dd06e84e4fc5a6a198740 Mon Sep 17 00:00:00 2001 From: Claudio Chies Date: Wed, 17 Sep 2025 08:48:36 +0200 Subject: [PATCH 062/812] BAT: Consolidate the highest feasible number of batteries into just 3 --- .../nuttx-config/scripts/itcm_functions_includes.ld | 2 +- .../nuttx-config/scripts/itcm_functions_includes.ld | 2 +- msg/versioned/BatteryStatus.msg | 2 +- .../common/include/px4_platform_common/board_common.h | 4 ---- src/drivers/uavcan/sensors/battery.hpp | 8 +++----- src/modules/mavlink/streams/HIGH_LATENCY2.hpp | 2 +- 6 files changed, 7 insertions(+), 13 deletions(-) diff --git a/boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld b/boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld index 0e6701aae2..7102c196ae 100644 --- a/boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld +++ b/boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld @@ -394,7 +394,7 @@ *(.text._ZN4EKF215PublishBaroBiasERKy) *(.text._ZN4EKF221UpdateGyroCalibrationERKy) *(.text._ZN6matrix9constrainIfLj3ELj1EEENS_6MatrixIT_XT0_EXT1_EEERKS3_S2_S2_) -*(.text._ZN4uORB22SubscriptionMultiArrayI16battery_status_sLh4EE16advertised_countEv) +*(.text._ZN4uORB22SubscriptionMultiArrayI16battery_status_sLh3EE16advertised_countEv) *(.text._ZN23MavlinkStreamScaledIMU34sendEv) *(.text.__aeabi_ldivmod) *(.text._ZN15PositionControl16setInputSetpointERK21trajectory_setpoint_s) diff --git a/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld b/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld index a52a3b46b0..e6f5d02d04 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld +++ b/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld @@ -402,7 +402,7 @@ *(.text._ZN4EKF215PublishBaroBiasERKy) *(.text._ZN4EKF221UpdateGyroCalibrationERKy) *(.text._ZN6matrix9constrainIfLj3ELj1EEENS_6MatrixIT_XT0_EXT1_EEERKS3_S2_S2_) -*(.text._ZN4uORB22SubscriptionMultiArrayI16battery_status_sLh4EE16advertised_countEv) +*(.text._ZN4uORB22SubscriptionMultiArrayI16battery_status_sLh3EE16advertised_countEv) *(.text._ZN23MavlinkStreamScaledIMU34sendEv) *(.text.__aeabi_ldivmod) *(.text._ZN15PositionControl16setInputSetpointERK21trajectory_setpoint_s) diff --git a/msg/versioned/BatteryStatus.msg b/msg/versioned/BatteryStatus.msg index 94926ac3a2..7c390c4576 100644 --- a/msg/versioned/BatteryStatus.msg +++ b/msg/versioned/BatteryStatus.msg @@ -5,7 +5,7 @@ # Battery instance information is also logged and streamed in MAVLink telemetry. uint32 MESSAGE_VERSION = 1 -uint8 MAX_INSTANCES = 4 +uint8 MAX_INSTANCES = 3 uint64 timestamp # [us] Time since system start diff --git a/platforms/common/include/px4_platform_common/board_common.h b/platforms/common/include/px4_platform_common/board_common.h index 4b9678afd6..8905507cd0 100644 --- a/platforms/common/include/px4_platform_common/board_common.h +++ b/platforms/common/include/px4_platform_common/board_common.h @@ -173,10 +173,6 @@ # define BOARD_BATT_V_LIST {ADC_BATTERY1_VOLTAGE_CHANNEL, ADC_BATTERY2_VOLTAGE_CHANNEL, ADC_BATTERY3_VOLTAGE_CHANNEL} # define BOARD_BATT_I_LIST {ADC_BATTERY1_CURRENT_CHANNEL, ADC_BATTERY2_CURRENT_CHANNEL, ADC_BATTERY3_CURRENT_CHANNEL} # define BOARD_BRICK_VALID_LIST {BOARD_ADC_BRICK1_VALID, BOARD_ADC_BRICK2_VALID, BOARD_ADC_BRICK3_VALID} -#elif BOARD_NUMBER_BRICKS == 4 -# define BOARD_BATT_V_LIST {ADC_BATTERY1_VOLTAGE_CHANNEL, ADC_BATTERY2_VOLTAGE_CHANNEL, ADC_BATTERY3_VOLTAGE_CHANNEL, ADC_BATTERY4_VOLTAGE_CHANNEL} -# define BOARD_BATT_I_LIST {ADC_BATTERY1_CURRENT_CHANNEL, ADC_BATTERY2_CURRENT_CHANNEL, ADC_BATTERY3_CURRENT_CHANNEL, ADC_BATTERY4_CURRENT_CHANNEL} -# define BOARD_BRICK_VALID_LIST {BOARD_ADC_BRICK1_VALID, BOARD_ADC_BRICK2_VALID, BOARD_ADC_BRICK3_VALID, BOARD_ADC_BRICK4_VALID} #else # error Unsuported BOARD_NUMBER_BRICKS number. #endif diff --git a/src/drivers/uavcan/sensors/battery.hpp b/src/drivers/uavcan/sensors/battery.hpp index 0c0ab3c949..654486d681 100644 --- a/src/drivers/uavcan/sensors/battery.hpp +++ b/src/drivers/uavcan/sensors/battery.hpp @@ -105,7 +105,7 @@ private: hrt_abstime _last_timestamp; // Separate battery info publication because UavcanSensorBridgeBase only supports publishing one topic - uORB::PublicationMulti _battery_info_pub[battery_status_s::MAX_INSTANCES] {ORB_ID(battery_info), ORB_ID(battery_info), ORB_ID(battery_info), ORB_ID(battery_info)}; + uORB::PublicationMulti _battery_info_pub[battery_status_s::MAX_INSTANCES] {ORB_ID(battery_info), ORB_ID(battery_info), ORB_ID(battery_info)}; battery_info_s _battery_info[battery_status_s::MAX_INSTANCES] {}; battery_status_s _battery_status[battery_status_s::MAX_INSTANCES] {}; @@ -115,15 +115,13 @@ private: static constexpr int BATTERY_INDEX_1 = 1; static constexpr int BATTERY_INDEX_2 = 2; static constexpr int BATTERY_INDEX_3 = 3; - static constexpr int BATTERY_INDEX_4 = 4; static constexpr int SAMPLE_INTERVAL_US = 500_ms; // Typical message rate for a CAN battery monitor should be 2-5Hz. - static_assert(battery_status_s::MAX_INSTANCES <= BATTERY_INDEX_4, "Battery array too big"); + static_assert(battery_status_s::MAX_INSTANCES <= BATTERY_INDEX_3, "Battery array too big"); Battery battery1 = {BATTERY_INDEX_1, this, SAMPLE_INTERVAL_US, battery_status_s::SOURCE_EXTERNAL}; Battery battery2 = {BATTERY_INDEX_2, this, SAMPLE_INTERVAL_US, battery_status_s::SOURCE_EXTERNAL}; Battery battery3 = {BATTERY_INDEX_3, this, SAMPLE_INTERVAL_US, battery_status_s::SOURCE_EXTERNAL}; - Battery battery4 = {BATTERY_INDEX_4, this, SAMPLE_INTERVAL_US, battery_status_s::SOURCE_EXTERNAL}; - Battery *_battery[battery_status_s::MAX_INSTANCES] = { &battery1, &battery2, &battery3, &battery4 }; + Battery *_battery[battery_status_s::MAX_INSTANCES] = { &battery1, &battery2, &battery3}; }; diff --git a/src/modules/mavlink/streams/HIGH_LATENCY2.hpp b/src/modules/mavlink/streams/HIGH_LATENCY2.hpp index 8723f14131..74ca48d554 100644 --- a/src/modules/mavlink/streams/HIGH_LATENCY2.hpp +++ b/src/modules/mavlink/streams/HIGH_LATENCY2.hpp @@ -685,7 +685,7 @@ private: hrt_abstime _last_update_time{0}; float _update_rate_filtered{0}; - PerBatteryData _batteries[battery_status_s::MAX_INSTANCES] {0, 1, 2, 3}; + PerBatteryData _batteries[battery_status_s::MAX_INSTANCES] {0, 1, 2}; }; #endif // HIGH_LATENCY2_HPP From b730acfc7656581d6edd03384826996b1150acc8 Mon Sep 17 00:00:00 2001 From: Claudio Chies Date: Mon, 22 Sep 2025 09:48:07 +0200 Subject: [PATCH 063/812] BOARDS: MISC: remove "auto-generated" for files which are not autogenerated anymore --- .../nuttx-config/scripts/itcm_functions_includes.ld | 1 - .../fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld | 1 - 2 files changed, 2 deletions(-) diff --git a/boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld b/boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld index 7102c196ae..36330c1e85 100644 --- a/boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld +++ b/boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld @@ -1,4 +1,3 @@ -/* Auto-generated */ *(.text._ZN4uORB7Manager27orb_add_internal_subscriberE6ORB_IDhPj) *(.text._ZN13MavlinkStream6updateERKy) *(.text._ZN7Mavlink16update_rate_multEv) diff --git a/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld b/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld index e6f5d02d04..4d676a6998 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld +++ b/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld @@ -1,4 +1,3 @@ -/* Auto-generated */ *(.text._ZN4uORB7Manager27orb_add_internal_subscriberE6ORB_IDhPj) *(.text._ZN13MavlinkStream6updateERKy) *(.text._ZN7Mavlink16update_rate_multEv) From 061f34919e7abe749adf5ab6eca627cf2af95c2d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Mon, 22 Sep 2025 10:49:58 +0200 Subject: [PATCH 064/812] ci: JasonEtco/create-an-issue needs permissions to create issues --- .github/workflows/fuzzing.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/fuzzing.yml b/.github/workflows/fuzzing.yml index c2da779c62..5fc26f8063 100644 --- a/.github/workflows/fuzzing.yml +++ b/.github/workflows/fuzzing.yml @@ -5,6 +5,7 @@ on: permissions: contents: read + issues: write # for JasonEtco/create-an-issue env: RUNS_IN_DOCKER: true From 9670eb69b3f8449853f99a4295b045138979c63d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Mon, 22 Sep 2025 10:51:06 +0200 Subject: [PATCH 065/812] commander: use double literals to avoid implicit conversion Fixes a CI failure for fuzzing and macos: https://github.com/PX4/PX4-Autopilot/actions/runs/17906277709/job/50907922642 /__w/PX4-Autopilot/PX4-Autopilot/src/modules/commander/Commander.cpp:471:37: fatal error: implicit conversion increases floating-point precision: 'float' to 'double' [-Wdouble-promotion] 470 | bool ret = send_vehicle_command(vehicle_command_s::VEHICLE_CMD_EXTERNAL_ATTITUDE_ESTIMATE, | ~~~~~~~~~~~~~~~~~~~~ 471 | 0.f, 0.f, heading, 0.f, 0.f, 0.f, heading_accuracy); | ^~~ 1 error generated. --- src/modules/commander/Commander.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index cb5e87ff05..0f891b344b 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -468,7 +468,7 @@ int Commander::custom_command(int argc, char *argv[]) const float heading_accuracy = NAN; bool ret = send_vehicle_command(vehicle_command_s::VEHICLE_CMD_EXTERNAL_ATTITUDE_ESTIMATE, - 0.f, 0.f, heading, 0.f, 0.f, 0.f, heading_accuracy); + 0.f, 0.f, heading, 0.f, 0.0, 0.0, heading_accuracy); return (ret ? 0 : 1); } else { From 0a8a5472ec4f602146003e0635b8c362c6d76c29 Mon Sep 17 00:00:00 2001 From: Alexander Lerach Date: Mon, 22 Sep 2025 14:48:49 +0200 Subject: [PATCH 066/812] nuttx submodule update (fix sem holder list) --- platforms/nuttx/NuttX/nuttx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index b0b49a2106..dea4f18dbf 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit b0b49a210696dd0074dff9531fd1603afb0cc2e4 +Subproject commit dea4f18dbf71a72f36a1273117175fbb4191db10 From 06a3f15d39530ab5e4273e029a1559bdc2f25e3a Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 24 Sep 2025 10:01:55 +1000 Subject: [PATCH 067/812] [Docs] update metadata (#25603) --- .../en/advanced_config/parameter_reference.md | 426 +++++------------- docs/en/modules/modules_driver_ins.md | 25 + docs/en/modules/modules_system.md | 13 +- docs/en/msg_docs/ActuatorMotors.md | 4 +- docs/en/msg_docs/ActuatorServos.md | 2 +- docs/en/msg_docs/ArmingCheckReply.md | 42 +- docs/en/msg_docs/ArmingCheckRequest.md | 10 +- docs/en/msg_docs/BatteryStatus.md | 123 ++--- docs/en/msg_docs/EstimatorStatus.md | 6 +- docs/en/msg_docs/EstimatorStatusFlags.md | 4 +- docs/en/msg_docs/PurePursuitStatus.md | 12 +- docs/en/msg_docs/RoverAttitudeSetpoint.md | 4 +- docs/en/msg_docs/RoverAttitudeStatus.md | 6 +- docs/en/msg_docs/RoverPositionSetpoint.md | 12 +- docs/en/msg_docs/RoverRateSetpoint.md | 4 +- docs/en/msg_docs/RoverRateStatus.md | 8 +- docs/en/msg_docs/RoverSpeedSetpoint.md | 6 +- docs/en/msg_docs/RoverSpeedStatus.md | 14 +- docs/en/msg_docs/RoverSteeringSetpoint.md | 4 +- docs/en/msg_docs/RoverThrottleSetpoint.md | 6 +- docs/en/msg_docs/VehicleCommand.md | 1 + docs/en/msg_docs/VehicleStatus.md | 2 +- docs/en/msg_docs/index.md | 4 +- 23 files changed, 281 insertions(+), 457 deletions(-) diff --git a/docs/en/advanced_config/parameter_reference.md b/docs/en/advanced_config/parameter_reference.md index 9c8c4b9a15..10c8b67f67 100644 --- a/docs/en/advanced_config/parameter_reference.md +++ b/docs/en/advanced_config/parameter_reference.md @@ -10,264 +10,6 @@ If a listed parameter is missing from the Firmware see: [Finding/Updating Parame -## UAVCAN Motor Parameters - -### ctl_bw (`INT32`) {#ctl_bw} - -Speed controller bandwidth. - -Speed controller bandwidth, in Hz. Higher values result in faster speed and current rise times, but may result in overshoot and higher current consumption. For fixed-wing aircraft, this value should be less than 50 Hz; for multirotors, values up to 100 Hz may provide improvements in responsiveness. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 10 | 250 | | 75 | Hz | - -### ctl_dir (`INT32`) {#ctl_dir} - -Reverse direction. - -Motor spin direction as detected during initial enumeration. Use 0 or 1 to reverse direction. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1 | | 1 | - -### ctl_gain (`FLOAT`) {#ctl_gain} - -Speed (RPM) controller gain. - -Determines controller -aggressiveness; units are amp-seconds per radian. Systems with -higher rotational inertia (large props) will need gain increased; -systems with low rotational inertia (small props) may need gain -decreased. Higher values result in faster response, but may result -in oscillation and excessive overshoot. Lower values result in a -slower, smoother response. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | 0.00 | 1.00 | | 1 | C/rad | - -### ctl_hz_idle (`FLOAT`) {#ctl_hz_idle} - -Idle speed (e Hz). - -Idle speed (e Hz) - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 100.0 | | 3.5 | Hz | - -### ctl_start_rate (`INT32`) {#ctl_start_rate} - -Spin-up rate (e Hz/s). - -Spin-up rate (e Hz/s) - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | 5 | 1000 | | 25 | 1/s^2 | - -### esc_index (`INT32`) {#esc_index} - -Index of this ESC in throttle command messages. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 15 | | 0 | - -### id_ext_status (`INT32`) {#id_ext_status} - -Extended status ID. - -Extended status ID - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1 | 1000000 | | 20034 | - -### int_ext_status (`INT32`) {#int_ext_status} - -Extended status interval (µs). - -Extended status interval (µs) - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000000 | | 50000 | us | - -### int_status (`INT32`) {#int_status} - -ESC status interval (µs). - -ESC status interval (µs) - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | 1000000 | | 50000 | us | - -### mot_i_max (`FLOAT`) {#mot_i_max} - -Motor current limit in amps. - -This determines the maximum -current controller setpoint, as well as the maximum allowable -current setpoint slew rate. This value should generally be set to -the continuous current rating listed in the motor’s specification -sheet, or set equal to the motor’s specified continuous power -divided by the motor voltage limit. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1 | 80 | | 12 | A | - -### mot_kv (`INT32`) {#mot_kv} - -Motor Kv in RPM per volt. - -This can be taken from the motor’s -specification sheet; accuracy will help control performance but -some deviation from the specified value is acceptable. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | 0 | 4000 | | 2300 | rpm/V | - -### mot_ls (`FLOAT`) {#mot_ls} - -READ ONLY: Motor inductance in henries. - -This is measured on start-up. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | H | - -### mot_num_poles (`INT32`) {#mot_num_poles} - -Number of motor poles. - -Used to convert mechanical speeds to -electrical speeds. This number should be taken from the motor’s -specification sheet. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 2 | 40 | | 14 | - -### mot_rs (`FLOAT`) {#mot_rs} - -READ ONLY: Motor resistance in ohms. - -This is measured on start-up. When -tuning a new motor, check that this value is approximately equal -to the value shown in the motor’s specification sheet. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | Ohm | - -### mot_v_accel (`FLOAT`) {#mot_v_accel} - -Acceleration limit (V). - -Acceleration limit (V) - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.01 | 1.00 | | 0.5 | V | - -### mot_v_max (`FLOAT`) {#mot_v_max} - -Motor voltage limit in volts. - -The current controller’s -commanded voltage will never exceed this value. Note that this may -safely be above the nominal voltage of the motor; to determine the -actual motor voltage limit, divide the motor’s rated power by the -motor current limit. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | | | 14.8 | V | - -## UAVCAN GNSS - -### gnss.dyn_model (`INT32`) {#gnss.dyn_model} - -GNSS dynamic model. - -Dynamic model used in the GNSS positioning engine. 0 – -Automotive, 1 – Sea, 2 – Airborne. - -**Values:** - -- `0`: Automotive -- `1`: Sea -- `2`: Airborne - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 2 | | 2 | - -### gnss.old_fix_msg (`INT32`) {#gnss.old_fix_msg} - -Broadcast old GNSS fix message. - -Broadcast the old (deprecated) GNSS fix message -uavcan.equipment.gnss.Fix alongside the new alternative -uavcan.equipment.gnss.Fix2. It is recommended to -disable this feature to reduce the CAN bus traffic. - -**Values:** - -- `0`: Fix2 -- `1`: Fix and Fix2 - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1 | | 1 | - -### gnss.warn_dimens (`INT32`) {#gnss.warn_dimens} - -device health warning. - -Set the device health to Warning if the dimensionality of -the GNSS solution is less than this value. 3 for the full (3D) -solution, 2 for planar (2D) solution, 1 for time-only solution, -0 disables the feature. - -**Values:** - -- `0`: disables the feature -- `1`: time-only solution -- `2`: planar (2D) solution -- `3`: full (3D) solution - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 3 | | 0 | - -### gnss.warn_sats (`INT32`) {#gnss.warn_sats} - -Set the device health to Warning if the number of satellites -used in the GNSS solution is below this threshold. Zero -disables the feature - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - -### uavcan.pubp-pres (`INT32`) {#uavcan.pubp-pres} - -Set the device health to Warning if the number of satellites -used in the GNSS solution is below this threshold. Zero -disables the feature - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000000 | | 0 | us | - ## ADSB ### ADSB_CALLSIGN_1 (`INT32`) {#ADSB_CALLSIGN_1} @@ -15723,6 +15465,7 @@ selected flight mode will be applied. - `11`: Land - `12`: Follow Me - `13`: Precision Land +- `16`: Altitude Cruise - `100`: External Mode 1 - `101`: External Mode 2 - `102`: External Mode 3 @@ -15760,6 +15503,7 @@ selected flight mode will be applied. - `11`: Land - `12`: Follow Me - `13`: Precision Land +- `16`: Altitude Cruise - `100`: External Mode 1 - `101`: External Mode 2 - `102`: External Mode 3 @@ -15797,6 +15541,7 @@ selected flight mode will be applied. - `11`: Land - `12`: Follow Me - `13`: Precision Land +- `16`: Altitude Cruise - `100`: External Mode 1 - `101`: External Mode 2 - `102`: External Mode 3 @@ -15834,6 +15579,7 @@ selected flight mode will be applied. - `11`: Land - `12`: Follow Me - `13`: Precision Land +- `16`: Altitude Cruise - `100`: External Mode 1 - `101`: External Mode 2 - `102`: External Mode 3 @@ -15871,6 +15617,7 @@ selected flight mode will be applied. - `11`: Land - `12`: Follow Me - `13`: Precision Land +- `16`: Altitude Cruise - `100`: External Mode 1 - `101`: External Mode 2 - `102`: External Mode 3 @@ -15908,6 +15655,7 @@ selected flight mode will be applied. - `11`: Land - `12`: Follow Me - `13`: Precision Land +- `16`: Altitude Cruise - `100`: External Mode 1 - `101`: External Mode 2 - `102`: External Mode 3 @@ -16369,10 +16117,11 @@ External modes requiring stick input will still failsafe. - `1`: Hold - `2`: Offboard - `3`: External Mode +- `4`: Altitude Cruise | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 15 | | 0 | +|   | 0 | 31 | | 0 | ### COM_RC_ARM_HYST (`INT32`) {#COM_RC_ARM_HYST} @@ -24821,6 +24570,19 @@ arms and to the lower left disarms the vehicle. | ------ | -------- | -------- | --------- | ----------- | ---- | |   | | | | Enabled (1) | +### MAN_DEADZONE (`FLOAT`) {#MAN_DEADZONE} + +Deadzone for sticks (only specific use cases). + +Range around stick center ignored to prevent +vehicle drift from stick hardware inaccuracy. +Does not apply to any precise constant input like +throttle and attitude or rate piloting. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1 | 0.01 | 0.1 | + ### MAN_KILL_GEST_T (`FLOAT`) {#MAN_KILL_GEST_T} Trigger time for kill stick gesture. @@ -25672,16 +25434,6 @@ The speed threshold is MPC_HOLD_MAX_XY | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 2 | | 2 | -### MPC_HOLD_DZ (`FLOAT`) {#MPC_HOLD_DZ} - -Deadzone for sticks in manual piloted modes. - -Does not apply to manual throttle and direct attitude piloting by stick. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1 | 0.01 | 0.1 | - ### MPC_HOLD_MAX_XY (`FLOAT`) {#MPC_HOLD_MAX_XY} Maximum horizontal velocity for which position hold is enabled (use 0 to disable check). @@ -25824,7 +25576,7 @@ Airmode is used to keep torque authority with zero thrust (see MC_AIRMODE). ### MPC_MAN_TILT_MAX (`FLOAT`) {#MPC_MAN_TILT_MAX} -Maximal tilt angle in Stabilized or Altitude mode. +Maximal tilt angle in Stabilized, Altitude and Altitude Cruise mode. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26092,19 +25844,6 @@ capabilities of the vehicle. | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0.1 | 10 | 1 | 2. | -### MPC_XY_MAN_EXPO (`FLOAT`) {#MPC_XY_MAN_EXPO} - -Manual position control stick exponential curve sensitivity. - -The higher the value the less sensitivity the stick has around zero -while still reaching the maximum value with full stick deflection. -0 Purely linear input curve -1 Purely cubic input curve - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1 | 0.01 | 0.6 | - ### MPC_XY_P (`FLOAT`) {#MPC_XY_P} Proportional gain for horizontal position error. @@ -26177,32 +25916,6 @@ Defined as corrective acceleration in m/s^2 per m/s velocity error | ------ | -------- | -------- | --------- | ------- | ---- | |   | 1.2 | 5 | 0.1 | 1.8 | -### MPC_YAW_EXPO (`FLOAT`) {#MPC_YAW_EXPO} - -Manual control stick yaw rotation exponential curve. - -The higher the value the less sensitivity the stick has around zero -while still reaching the maximum value with full stick deflection. -0 Purely linear input curve -1 Purely cubic input curve - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1 | 0.01 | 0.6 | - -### MPC_Z_MAN_EXPO (`FLOAT`) {#MPC_Z_MAN_EXPO} - -Manual control stick vertical exponential curve. - -The higher the value the less sensitivity the stick has around zero -while still reaching the maximum value with full stick deflection. -0 Purely linear input curve -1 Purely cubic input curve - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1 | 0.01 | 0.6 | - ### MPC_Z_P (`FLOAT`) {#MPC_Z_P} Proportional gain for vertical position error. @@ -26537,7 +26250,7 @@ Pitch rate controller gain. Global gain of the controller. This gain scales the P, I and D terms of the controller: -output = MC_PITCHRATE_K _ (MC_PITCHRATE_P _ error +output = MC*PITCHRATE_K * (MC*PITCHRATE_P * error - MC_PITCHRATE_I \* error_integral - MC_PITCHRATE_D \* error_derivative) @@ -26604,7 +26317,7 @@ Roll rate controller gain. Global gain of the controller. This gain scales the P, I and D terms of the controller: -output = MC_ROLLRATE_K _ (MC_ROLLRATE_P _ error +output = MC*ROLLRATE_K * (MC*ROLLRATE_P * error - MC_ROLLRATE_I \* error_integral - MC_ROLLRATE_D \* error_derivative) @@ -26671,7 +26384,7 @@ Yaw rate controller gain. Global gain of the controller. This gain scales the P, I and D terms of the controller: -output = MC_YAWRATE_K _ (MC_YAWRATE_P _ error +output = MC*YAWRATE_K * (MC*YAWRATE_P * error - MC_YAWRATE_I \* error_integral - MC_YAWRATE_D \* error_derivative) @@ -26905,7 +26618,7 @@ Thrust to motor control signal model parameter. Parameter used to model the nonlinear relationship between motor control signal (e.g. PWM) and static thrust. -The model is: rel_thrust = factor _ rel_signal^2 + (1-factor) _ rel_signal, +The model is: rel*thrust = factor * rel*signal^2 + (1-factor) * rel_signal, where rel_thrust is the normalized thrust between 0 and 1, and rel_signal is the relative motor control signal between 0 and 1. @@ -29769,7 +29482,7 @@ Proportional gain for ground speed controller. Tuning parameter for the speed reduction based on the course error. -Reduced_speed = RO_MAX_THR_SPEED _ (1 - normalized_course_error _ RO_SPEED_RED) +Reduced*speed = RO_MAX_THR_SPEED * (1 - normalized*course_error * RO_SPEED_RED) The normalized course error is the angle between the current course and the bearing setpoint interpolated from [0, 180] -> [0, 1]. Higher value -> More speed reduction. @@ -33020,6 +32733,49 @@ reset of counter takes some time - measurement with reset has worse accuracy. | ------- | -------- | -------- | --------- | ------- | ---- | | ✓ | | | | 500000 | +### SBG_BAUDRATE (`INT32`) {#SBG_BAUDRATE} + +sbgECom driver baudrate. + +Baudrate used by default for serial communication between PX4 +and SBG Systems INS through sbgECom driver. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 9600 | 921600 | | 921600 | + +### SBG_CONFIGURE_EN (`INT32`) {#SBG_CONFIGURE_EN} + +sbgECom driver INS configuration enable. + +Enable SBG Systems INS configuration through sbgECom driver +on start. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------------ | ---- | +|   | | | | Disabled (0) | + +### SBG_MODE (`INT32`) {#SBG_MODE} + +sbgECom driver mode. + +Modes available for sbgECom driver. +In Sensors Only mode, use external IMU and magnetometer. +In GNSS mode, use external GNSS in addition to sensors only mode. +In INS mode, use external Kalman Filter in addition to GNSS mode. +In INS mode, requires EKF2_EN 0. Keeping both enabled +can lead to an unexpected behavior and vehicle instability. + +**Values:** + +- `0`: Sensors Only +- `1`: GNSS +- `2`: INS (default) + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 2 | + ### SENS_AFBR_HYSTER (`INT32`) {#SENS_AFBR_HYSTER} AFBR Rangefinder Short/Long Range Threshold Hysteresis. @@ -34556,6 +34312,31 @@ Analog Devices ADIS16448 IMU Orientation(external SPI). | ------- | -------- | -------- | --------- | ------- | ---- | | ✓ | 0 | 101 | | 0 | +### SENS_SBG_CFG (`INT32`) {#SENS_SBG_CFG} + +Serial Configuration for sbgECom. + +Configure on which serial port to run sbgECom. + +**Values:** + +- `0`: Disabled +- `6`: UART 6 +- `101`: TELEM 1 +- `102`: TELEM 2 +- `103`: TELEM 3 +- `104`: TELEM/SERIAL 4 +- `201`: GPS 1 +- `202`: GPS 2 +- `203`: GPS 3 +- `300`: Radio Controller +- `301`: Wifi Port +- `401`: EXT2 + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | + ### SENS_SF0X_CFG (`INT32`) {#SENS_SF0X_CFG} Serial Configuration for Lightware Laser Rangefinder (serial). @@ -36480,7 +36261,7 @@ Pitch rate controller gain. Global gain of the controller. This gain scales the P, I and D terms of the controller: -output = SC_PITCHRATE_K _ (SC_PITCHRATE_P _ error +output = SC*PITCHRATE_K * (SC*PITCHRATE_P * error - SC_PITCHRATE_I \* error_integral - SC_PITCHRATE_D \* error_derivative) @@ -36547,7 +36328,7 @@ Roll rate controller gain. Global gain of the controller. This gain scales the P, I and D terms of the controller: -output = SC_ROLLRATE_K _ (SC_ROLLRATE_P _ error +output = SC*ROLLRATE_K * (SC*ROLLRATE_P * error - SC_ROLLRATE_I \* error_integral - SC_ROLLRATE_D \* error_derivative) @@ -36614,7 +36395,7 @@ Yaw rate controller gain. Global gain of the controller. This gain scales the P, I and D terms of the controller: -output = SC_YAWRATE_K _ (SC_YAWRATE_P _ error +output = SC*YAWRATE_K * (SC*YAWRATE_P * error - SC_YAWRATE_I \* error_integral - SC_YAWRATE_D \* error_derivative) @@ -40029,6 +39810,17 @@ must have a unique session key. | ------- | -------- | -------- | --------- | ------- | ---- | | ✓ | | | | 1 | +### UXRCE_DDS_NS_IDX (`INT32`) {#UXRCE_DDS_NS_IDX} + +Define an index-based message namespace. + +Defines an index-based namespace for DDS messages, e.g, uav_0, uav_1, up to uav_9999 +A value less than zero leaves the namespace empty + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | -1 | 9999 | | -1 | + ### UXRCE_DDS_PRT (`INT32`) {#UXRCE_DDS_PRT} uXRCE-DDS UDP port. diff --git a/docs/en/modules/modules_driver_ins.md b/docs/en/modules/modules_driver_ins.md index 6d72447f28..844aa645bb 100644 --- a/docs/en/modules/modules_driver_ins.md +++ b/docs/en/modules/modules_driver_ins.md @@ -125,6 +125,31 @@ ilabs [arguments...] status Print driver status ``` +## sbgecom + +Source: [drivers/ins/sbgecom](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/sbgecom) + +Description du module + +### Usage {#sbgecom_usage} + +``` +sbgecom [arguments...] + Commands: + start Start driver + [-d ] Serial device + default: /dev/ttyS0 + [-b ] Baudrate device + default: 921600 + [-f ] Config JSON file path + default: /etc/extras/sbg_settings\.json + [-s ] Config JSON string + + status Driver status + + stop Stop driver +``` + ## vectornav Source: [drivers/ins/vectornav](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/vectornav) diff --git a/docs/en/modules/modules_system.md b/docs/en/modules/modules_system.md index c078d9202e..57c36506d8 100644 --- a/docs/en/modules/modules_system.md +++ b/docs/en/modules/modules_system.md @@ -140,9 +140,9 @@ commander [arguments...] transition VTOL transition mode Change flight mode - manual|acro|offboard|stabilized|altctl|posctl|position:slow|auto:mission|au - to:loiter|auto:rtl|auto:takeoff|auto:land|auto:precland|ext1 - Flight mode + manual|acro|offboard|stabilized|altctl|posctl|altitude_cruise|position:slow + |auto:mission|auto:loiter|auto:rtl|auto:takeoff|auto:land|auto: + precland|ext1 Flight mode pair @@ -154,6 +154,9 @@ commander [arguments...] lat|lon|alt Origin latitude longitude altitude + set_heading Set current heading + heading degrees from True North [0 360] + poweroff Power off board (if supported) stop @@ -1062,7 +1065,9 @@ uxrce_dds_client [arguments...] values: [-p ] Agent listening port. If not provided, defaults to UXRCE_DDS_PRT - [-n ] Client DDS namespace + [-n ] Client DDS namespace. If not provided but UXRCE_DDS_NS_IDX is + between 0 and 9999 inclusive, then uav_ + UXRCE_DDS_NS_IDX will + be used stop diff --git a/docs/en/msg_docs/ActuatorMotors.md b/docs/en/msg_docs/ActuatorMotors.md index ca739f6c22..701465d6ea 100644 --- a/docs/en/msg_docs/ActuatorMotors.md +++ b/docs/en/msg_docs/ActuatorMotors.md @@ -18,11 +18,11 @@ uint32 MESSAGE_VERSION = 0 uint64 timestamp # [us] Time since system start uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on -uint16 reversible_flags # Bitset indicating which motors are configured to be reversible +uint16 reversible_flags # [-] Bitset indicating which motors are configured to be reversible uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 # uint8 NUM_CONTROLS = 12 # -float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) +float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) ``` diff --git a/docs/en/msg_docs/ActuatorServos.md b/docs/en/msg_docs/ActuatorServos.md index 6f0a677dbf..ea053f67a3 100644 --- a/docs/en/msg_docs/ActuatorServos.md +++ b/docs/en/msg_docs/ActuatorServos.md @@ -19,6 +19,6 @@ uint64 timestamp # [us] Time since system start uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on uint8 NUM_CONTROLS = 8 # -float32[8] control # [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. +float32[8] control # [-] [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. ``` diff --git a/docs/en/msg_docs/ArmingCheckReply.md b/docs/en/msg_docs/ArmingCheckReply.md index 8d619f5aaf..14af54f0d1 100644 --- a/docs/en/msg_docs/ArmingCheckReply.md +++ b/docs/en/msg_docs/ArmingCheckReply.md @@ -1,6 +1,6 @@ # ArmingCheckReply (UORB message) -Arming check reply. +Arming check reply This is a response to an ArmingCheckRequest message sent by the FMU to an external component, such as a ROS 2 navigation mode. The response contains the current set of external mode requirements, and a queue of events indicating recent failures to set the mode (which the FMU may then forward to a ground station). @@ -12,7 +12,7 @@ The message is not used by internal/FMU components, as their mode requirements a [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ArmingCheckReply.msg) ```c -# Arming check reply. +# Arming check reply # # This is a response to an ArmingCheckRequest message sent by the FMU to an external component, such as a ROS 2 navigation mode. # The response contains the current set of external mode requirements, and a queue of events indicating recent failures to set the mode (which the FMU may then forward to a ground station). @@ -25,33 +25,33 @@ uint32 MESSAGE_VERSION = 1 uint64 timestamp # [us] Time since system start. -uint8 request_id # Id of ArmingCheckRequest for which this is a response. -uint8 registration_id # Id of external component emitting this response. +uint8 request_id # [-] Id of ArmingCheckRequest for which this is a response +uint8 registration_id # [-] Id of external component emitting this response -uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies. +uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX] -bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json). +bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json) +bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json) +bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json) -bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed. +bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed -uint8 num_events # Number of queued failure messages (Event) in the events field. +uint8 num_events # Number of queued failure messages (Event) in the events field -Event[5] events # Arming failure reasons (Queue of events to report to GCS). +Event[5] events # Arming failure reasons (Queue of events to report to GCS) # Mode requirements -bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope). -bool mode_req_attitude # Requires an attitude estimate. -bool mode_req_local_alt # Requires a local altitude estimate. -bool mode_req_local_position # Requires a local position estimate. -bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate. -bool mode_req_global_position # Requires a global position estimate. -bool mode_req_global_position_relaxed # Requires a relaxed global position estimate. -bool mode_req_mission # Requires an uploaded mission. -bool mode_req_home_position # Requires a home position (such as RTL/Return mode). -bool mode_req_prevent_arming # Prevent arming (such as in Land mode). +bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope) +bool mode_req_attitude # Requires an attitude estimate +bool mode_req_local_alt # Requires a local altitude estimate +bool mode_req_local_position # Requires a local position estimate +bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate +bool mode_req_global_position # Requires a global position estimate +bool mode_req_global_position_relaxed # Requires a relaxed global position estimate +bool mode_req_mission # Requires an uploaded mission +bool mode_req_home_position # Requires a home position (such as RTL/Return mode) +bool mode_req_prevent_arming # Prevent arming (such as in Land mode) bool mode_req_manual_control # Requires a manual controller uint8 ORB_QUEUE_LENGTH = 4 diff --git a/docs/en/msg_docs/ArmingCheckRequest.md b/docs/en/msg_docs/ArmingCheckRequest.md index 653d58d2d2..d093dfb5e1 100644 --- a/docs/en/msg_docs/ArmingCheckRequest.md +++ b/docs/en/msg_docs/ArmingCheckRequest.md @@ -1,6 +1,6 @@ # ArmingCheckRequest (UORB message) -Arming check request. +Arming check request Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. @@ -12,7 +12,7 @@ The reply will also include the registration_id for each external component, pro [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ArmingCheckRequest.msg) ```c -# Arming check request. +# Arming check request # # Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. # All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. @@ -23,10 +23,10 @@ The reply will also include the registration_id for each external component, pro uint32 MESSAGE_VERSION = 1 -uint64 timestamp # [us] Time since system start. +uint64 timestamp # [us] Time since system start -uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. +uint8 request_id # [-] Id of this request. Allows correlation with associated ArmingCheckReply messages. -uint32 valid_registrations_mask # Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) +uint32 valid_registrations_mask # [-] Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) ``` diff --git a/docs/en/msg_docs/BatteryStatus.md b/docs/en/msg_docs/BatteryStatus.md index 7204a2a12f..addd1ae524 100644 --- a/docs/en/msg_docs/BatteryStatus.md +++ b/docs/en/msg_docs/BatteryStatus.md @@ -16,76 +16,77 @@ Battery instance information is also logged and streamed in MAVLink telemetry. # Battery instance information is also logged and streamed in MAVLink telemetry. uint32 MESSAGE_VERSION = 1 -uint8 MAX_INSTANCES = 4 +uint8 MAX_INSTANCES = 3 -uint64 timestamp # [us] Time since system start -bool connected # Whether or not a battery is connected. For power modules this is based on a voltage threshold. -float32 voltage_v # [V] [@invalid 0] Battery voltage -float32 current_a # [A] [@invalid -1] Battery current -float32 current_average_a # [A] [@invalid -1] Battery current average (for FW average in level flight) -float32 discharged_mah # [mAh] [@invalid -1] Discharged amount -float32 remaining # [@range 0,1] [@invalid -1] Remaining capacity -float32 scale # [@range 1,] [@invalid -1] Scaling factor to compensate for lower actuation power caused by voltage sag -float32 time_remaining_s # [s] [@invalid NaN] Predicted time remaining until battery is empty under previous averaged load -float32 temperature # [°C] [@invalid NaN] Temperature of the battery -uint8 cell_count # [@invalid 0] Number of cells +uint64 timestamp # [us] Time since system start + +bool connected # Whether or not a battery is connected. For power modules this is based on a voltage threshold. +float32 voltage_v # [V] [@invalid 0] Battery voltage +float32 current_a # [A] [@invalid -1] Battery current +float32 current_average_a # [A] [@invalid -1] Battery current average (for FW average in level flight) +float32 discharged_mah # [mAh] [@invalid -1] Discharged amount +float32 remaining # [@range 0,1] [@invalid -1] Remaining capacity +float32 scale # [-] [@range 1,] [@invalid -1] Scaling factor to compensate for lower actuation power caused by voltage sag +float32 time_remaining_s # [s] [@invalid NaN] Predicted time remaining until battery is empty under previous averaged load +float32 temperature # [°C] [@invalid NaN] Temperature of the battery +uint8 cell_count # [-] [@invalid 0] Number of cells -uint8 source # [@enum SOURCE] Battery source -uint8 SOURCE_POWER_MODULE = 0 # Power module -uint8 SOURCE_EXTERNAL = 1 # External -uint8 SOURCE_ESCS = 2 # ESCs +uint8 source # [@enum SOURCE] Battery source +uint8 SOURCE_POWER_MODULE = 0 # Power module +uint8 SOURCE_EXTERNAL = 1 # External +uint8 SOURCE_ESCS = 2 # ESCs -uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 -uint16 capacity # [mAh] Capacity of the battery when fully charged -uint16 cycle_count # Number of discharge cycles the battery has experienced -uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge -uint16 manufacture_date # Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 -uint16 state_of_health # [%] [@range 0, 100] State of health. FullChargeCapacity/DesignCapacity -uint16 max_error # [%] [@range 1, 100] Max error, expected margin of error in the state-of-charge calculation -uint8 id # ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed -uint16 interface_error # Interface error counter +uint8 priority # [-] Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 +uint16 capacity # [mAh] Capacity of the battery when fully charged +uint16 cycle_count # [-] Number of discharge cycles the battery has experienced +uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge +uint16 manufacture_date # [-] Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 +uint16 state_of_health # [%] [@range 0, 100] State of health. FullChargeCapacity/DesignCapacity +uint16 max_error # [%] [@range 1, 100] Max error, expected margin of error in the state-of-charge calculation +uint8 id # [-] ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed +uint16 interface_error # [-] Interface error counter -float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages -float32 max_cell_voltage_delta # Max difference between individual cell voltages +float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages +float32 max_cell_voltage_delta # [V] Max difference between individual cell voltages -bool is_powering_off # Power off event imminent indication, false if unknown -bool is_required # Set if the battery is explicitly required before arming +bool is_powering_off # Power off event imminent indication, false if unknown +bool is_required # Set if the battery is explicitly required before arming -uint8 warning # [@enum WARNING STATE] Current battery warning -uint8 WARNING_NONE = 0 # No battery low voltage warning active -uint8 WARNING_LOW = 1 # Low voltage warning -uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately -uint8 WARNING_EMERGENCY = 3 # Immediate landing required -uint8 WARNING_FAILED = 4 # Battery has failed completely -uint8 STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field -uint8 STATE_CHARGING = 7 # Battery is charging +uint8 warning # [@enum WARNING STATE] Current battery warning +uint8 WARNING_NONE = 0 # No battery low voltage warning active +uint8 WARNING_LOW = 1 # Low voltage warning +uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately +uint8 WARNING_EMERGENCY = 3 # Immediate landing required +uint8 WARNING_FAILED = 4 # Battery has failed completely +uint8 STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field +uint8 STATE_CHARGING = 7 # Battery is charging -uint16 faults # [@enum FAULT] Smart battery supply status/fault flags (bitmask) for health indication -uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged -uint8 FAULT_SPIKES = 1 # Voltage spikes -uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed -uint8 FAULT_OVER_CURRENT = 3 # Over-current -uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature -uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault -uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage) -uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware -uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system -uint8 FAULT_HARDWARE_FAILURE = 9 # Hardware problem -uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming -uint8 FAULT_COUNT = 11 # Counter. Keep this as last element +uint16 faults # [@enum FAULT] Smart battery supply status/fault flags (bitmask) for health indication +uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged +uint8 FAULT_SPIKES = 1 # Voltage spikes +uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed +uint8 FAULT_OVER_CURRENT = 3 # Over-current +uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature +uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault +uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage) +uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware +uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system +uint8 FAULT_HARDWARE_FAILURE = 9 # Hardware problem +uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming +uint8 FAULT_COUNT = 11 # Counter. Keep this as last element -float32 full_charge_capacity_wh # [Wh] Compensated battery capacity -float32 remaining_capacity_wh # [Wh] Compensated battery capacity remaining -uint16 over_discharge_count # Number of battery overdischarge -float32 nominal_voltage # [V] Nominal voltage of the battery pack +float32 full_charge_capacity_wh # [Wh] Compensated battery capacity +float32 remaining_capacity_wh # [Wh] Compensated battery capacity remaining +uint16 over_discharge_count # [-] Number of battery overdischarge +float32 nominal_voltage # [V] Nominal voltage of the battery pack -float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate -float32 ocv_estimate # [V] Open circuit voltage estimate -float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate -float32 volt_based_soc_estimate # [@range 0, 1] Normalized volt based state of charge estimate -float32 voltage_prediction # [V] Predicted voltage -float32 prediction_error # [V] Prediction error -float32 estimation_covariance_norm # Norm of the covariance matrix +float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate +float32 ocv_estimate # [V] Open circuit voltage estimate +float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate +float32 volt_based_soc_estimate # [-] [@range 0, 1] Normalized volt based state of charge estimate +float32 voltage_prediction # [V] Predicted voltage +float32 prediction_error # [V] Prediction error +float32 estimation_covariance_norm # [-] Norm of the covariance matrix ``` diff --git a/docs/en/msg_docs/EstimatorStatus.md b/docs/en/msg_docs/EstimatorStatus.md index 96254b1d1c..9c24221691 100644 --- a/docs/en/msg_docs/EstimatorStatus.md +++ b/docs/en/msg_docs/EstimatorStatus.md @@ -1,7 +1,5 @@ # EstimatorStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorStatus.msg) ```c @@ -54,7 +52,9 @@ uint8 CS_SYNTHETIC_MAG_Z = 25 # 25 - true when we are using a synthesized measur uint8 CS_VEHICLE_AT_REST = 26 # 26 - true when the vehicle is at rest uint8 CS_GPS_YAW_FAULT = 27 # 27 - true when the GNSS heading has been declared faulty and is no longer being used uint8 CS_RNG_FAULT = 28 # 28 - true when the range finder has been declared faulty and is no longer being used -uint8 CS_GNSS_VEL = 44 # 44 - true if GNSS velocity measurements are being fused +uint8 CS_GNSS_VEL = 44 # 44 - true if GNSS velocity measurement fusion is intended +uint8 CS_GNSS_FAULT = 45 # 45 - true if GNSS measurements have been declared faulty and are no longer used +uint8 CS_YAW_MANUAL = 46 # 46 - true if yaw has been set manually uint32 filter_fault_flags # Bitmask to indicate EKF internal faults # 0 - true if the fusion of the magnetometer X-axis has encountered a numerical error diff --git a/docs/en/msg_docs/EstimatorStatusFlags.md b/docs/en/msg_docs/EstimatorStatusFlags.md index eede0693db..0ac832817d 100644 --- a/docs/en/msg_docs/EstimatorStatusFlags.md +++ b/docs/en/msg_docs/EstimatorStatusFlags.md @@ -1,7 +1,5 @@ # EstimatorStatusFlags (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorStatusFlags.msg) ```c @@ -56,6 +54,8 @@ bool cs_valid_fake_pos # 41 - true if a valid constant position is bein bool cs_constant_pos # 42 - true if the vehicle is at a constant position bool cs_baro_fault # 43 - true when the current baro has been declared faulty and is no longer being used bool cs_gnss_vel # 44 - true if GNSS velocity measurement fusion is intended +bool cs_gnss_fault # 45 - true if GNSS measurements have been declared faulty and are no longer used +bool cs_yaw_manual # 46 - true if yaw has been set manually # fault status uint32 fault_status_changes # number of filter fault status (fs) changes diff --git a/docs/en/msg_docs/PurePursuitStatus.md b/docs/en/msg_docs/PurePursuitStatus.md index 96577a0220..8d54ba473e 100644 --- a/docs/en/msg_docs/PurePursuitStatus.md +++ b/docs/en/msg_docs/PurePursuitStatus.md @@ -7,11 +7,11 @@ Pure pursuit status ```c # Pure pursuit status -uint64 timestamp # [us] Time since system start -float32 lookahead_distance # [m] [@range 0, inf] Lookahead distance of pure the pursuit controller -float32 target_bearing # [rad] [@range -pi, pi] [@frame NED] Target bearing calculated by the pure pursuit controller -float32 crosstrack_error # [m] [@range -inf (Left of the path), inf (Right of the path)] Shortest distance from the vehicle to the path -float32 distance_to_waypoint # [m] [@range -inf, inf]Distance from the vehicle to the current waypoint -float32 bearing_to_waypoint # [rad] [@range -pi, pi] [@frame NED]Bearing towards current waypoint +uint64 timestamp # [us] Time since system start +float32 lookahead_distance # [m] [@range 0, inf] Lookahead distance of pure the pursuit controller +float32 target_bearing # [rad] [@range -pi, pi] [@frame NED] Target bearing calculated by the pure pursuit controller +float32 crosstrack_error # [m] [@range -inf (Left of the path), inf (Right of the path)] Shortest distance from the vehicle to the path +float32 distance_to_waypoint # [m] [@range -inf, inf]Distance from the vehicle to the current waypoint +float32 bearing_to_waypoint # [rad] [@range -pi, pi] [@frame NED]Bearing towards current waypoint ``` diff --git a/docs/en/msg_docs/RoverAttitudeSetpoint.md b/docs/en/msg_docs/RoverAttitudeSetpoint.md index bd436278ca..ca75a6e3e2 100644 --- a/docs/en/msg_docs/RoverAttitudeSetpoint.md +++ b/docs/en/msg_docs/RoverAttitudeSetpoint.md @@ -7,7 +7,7 @@ Rover Attitude Setpoint ```c # Rover Attitude Setpoint -uint64 timestamp # [us] Time since system start -float32 yaw_setpoint # [rad] [@range -inf, inf] [@frame NED] Yaw setpoint +uint64 timestamp # [us] Time since system start +float32 yaw_setpoint # [rad] [@range -inf, inf] [@frame NED] Yaw setpoint ``` diff --git a/docs/en/msg_docs/RoverAttitudeStatus.md b/docs/en/msg_docs/RoverAttitudeStatus.md index e6df929abd..f5a9ce1f02 100644 --- a/docs/en/msg_docs/RoverAttitudeStatus.md +++ b/docs/en/msg_docs/RoverAttitudeStatus.md @@ -7,8 +7,8 @@ Rover Attitude Status ```c # Rover Attitude Status -uint64 timestamp # [us] Time since system start -float32 measured_yaw # [rad] [@range -pi, pi] [@frame NED]Measured yaw -float32 adjusted_yaw_setpoint # [rad] [@range -pi, pi] [@frame NED] Yaw setpoint that is being tracked (Applied slew rates) +uint64 timestamp # [us] Time since system start +float32 measured_yaw # [rad] [@range -pi, pi] [@frame NED]Measured yaw +float32 adjusted_yaw_setpoint # [rad] [@range -pi, pi] [@frame NED] Yaw setpoint that is being tracked (Applied slew rates) ``` diff --git a/docs/en/msg_docs/RoverPositionSetpoint.md b/docs/en/msg_docs/RoverPositionSetpoint.md index b45aa0515f..751536e7f9 100644 --- a/docs/en/msg_docs/RoverPositionSetpoint.md +++ b/docs/en/msg_docs/RoverPositionSetpoint.md @@ -7,11 +7,11 @@ Rover Position Setpoint ```c # Rover Position Setpoint -uint64 timestamp # [us] Time since system start -float32[2] position_ned # [m] [@range -inf, inf] [@frame NED] Target position -float32[2] start_ned # [m] [@range -inf, inf] [@frame NED] [@invalid NaN Defaults to vehicle position] Start position which specifies a line for the rover to track -float32 cruising_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to maximum speed] Cruising speed -float32 arrival_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to 0] Speed the rover should arrive at the target with -float32 yaw # [rad] [@range -pi,pi] [@frame NED] [@invalid NaN Defaults to vehicle yaw] Mecanum only: Specify vehicle yaw during travel +uint64 timestamp # [us] Time since system start +float32[2] position_ned # [m] [@range -inf, inf] [@frame NED] Target position +float32[2] start_ned # [m] [@range -inf, inf] [@frame NED] [@invalid NaN Defaults to vehicle position] Start position which specifies a line for the rover to track +float32 cruising_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to maximum speed] Cruising speed +float32 arrival_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to 0] Speed the rover should arrive at the target with +float32 yaw # [rad] [@range -pi,pi] [@frame NED] [@invalid NaN Defaults to vehicle yaw] Mecanum only: Specify vehicle yaw during travel ``` diff --git a/docs/en/msg_docs/RoverRateSetpoint.md b/docs/en/msg_docs/RoverRateSetpoint.md index 9bffa41b80..9bb844e802 100644 --- a/docs/en/msg_docs/RoverRateSetpoint.md +++ b/docs/en/msg_docs/RoverRateSetpoint.md @@ -7,7 +7,7 @@ Rover Rate setpoint ```c # Rover Rate setpoint -uint64 timestamp # [us] Time since system start -float32 yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint +uint64 timestamp # [us] Time since system start +float32 yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint ``` diff --git a/docs/en/msg_docs/RoverRateStatus.md b/docs/en/msg_docs/RoverRateStatus.md index 684e4c458a..70345fe315 100644 --- a/docs/en/msg_docs/RoverRateStatus.md +++ b/docs/en/msg_docs/RoverRateStatus.md @@ -7,9 +7,9 @@ Rover Rate Status ```c # Rover Rate Status -uint64 timestamp # [us] Time since system start -float32 measured_yaw_rate # [rad/s] [@range -inf, inf] [@frame NED] Measured yaw rate -float32 adjusted_yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint that is being tracked (Applied slew rates) -float32 pid_yaw_rate_integral # [] [@range -1, 1] Integral of the PID for the closed loop yaw rate controller +uint64 timestamp # [us] Time since system start +float32 measured_yaw_rate # [rad/s] [@range -inf, inf] [@frame NED] Measured yaw rate +float32 adjusted_yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint that is being tracked (Applied slew rates) +float32 pid_yaw_rate_integral # [-] [@range -1, 1] Integral of the PID for the closed loop yaw rate controller ``` diff --git a/docs/en/msg_docs/RoverSpeedSetpoint.md b/docs/en/msg_docs/RoverSpeedSetpoint.md index 9eea46e60f..84176cd1c3 100644 --- a/docs/en/msg_docs/RoverSpeedSetpoint.md +++ b/docs/en/msg_docs/RoverSpeedSetpoint.md @@ -7,8 +7,8 @@ Rover Speed Setpoint ```c # Rover Speed Setpoint -uint64 timestamp # [us] Time since system start -float32 speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction -float32 speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction +uint64 timestamp # [us] Time since system start +float32 speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction +float32 speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction ``` diff --git a/docs/en/msg_docs/RoverSpeedStatus.md b/docs/en/msg_docs/RoverSpeedStatus.md index 8c212e2b0f..4213e1e5df 100644 --- a/docs/en/msg_docs/RoverSpeedStatus.md +++ b/docs/en/msg_docs/RoverSpeedStatus.md @@ -7,12 +7,12 @@ Rover Velocity Status ```c # Rover Velocity Status -uint64 timestamp # [us] Time since system start -float32 measured_speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Measured speed in body x direction -float32 adjusted_speed_body_x_setpoint # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction that is being tracked (Applied slew rates) -float32 pid_throttle_body_x_integral # [] [@range -1, 1] Integral of the PID for the closed loop controller of the speed in body x direction -float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction -float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates) -float32 pid_throttle_body_y_integral # [] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction +uint64 timestamp # [us] Time since system start +float32 measured_speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Measured speed in body x direction +float32 adjusted_speed_body_x_setpoint # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction that is being tracked (Applied slew rates) +float32 pid_throttle_body_x_integral # [-] [@range -1, 1] Integral of the PID for the closed loop controller of the speed in body x direction +float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction +float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates) +float32 pid_throttle_body_y_integral # [-] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction ``` diff --git a/docs/en/msg_docs/RoverSteeringSetpoint.md b/docs/en/msg_docs/RoverSteeringSetpoint.md index 3e40a3986b..974f3fc4c9 100644 --- a/docs/en/msg_docs/RoverSteeringSetpoint.md +++ b/docs/en/msg_docs/RoverSteeringSetpoint.md @@ -7,7 +7,7 @@ Rover Steering setpoint ```c # Rover Steering setpoint -uint64 timestamp # [us] Time since system start -float32 normalized_steering_setpoint # [@range -1 (Left), 1 (Right)] [@frame Body] Ackermann: Normalized steering angle, Differential/Mecanum: Normalized speed difference between the left and right wheels +uint64 timestamp # [us] Time since system start +float32 normalized_steering_setpoint # [-] [@range -1 (Left), 1 (Right)] [@frame Body] Ackermann: Normalized steering angle, Differential/Mecanum: Normalized speed difference between the left and right wheels ``` diff --git a/docs/en/msg_docs/RoverThrottleSetpoint.md b/docs/en/msg_docs/RoverThrottleSetpoint.md index f1c4f7f653..bd5ee93d55 100644 --- a/docs/en/msg_docs/RoverThrottleSetpoint.md +++ b/docs/en/msg_docs/RoverThrottleSetpoint.md @@ -7,8 +7,8 @@ Rover Throttle setpoint ```c # Rover Throttle setpoint -uint64 timestamp # [us] Time since system start -float32 throttle_body_x # [] [@range -1 (Backwards), 1 (Forwards)] [@frame Body] Throttle setpoint along body X axis -float32 throttle_body_y # [] [@range -1 (Left), 1 (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Throttle setpoint along body Y axis +uint64 timestamp # [us] Time since system start +float32 throttle_body_x # [-] [@range -1 (Backwards), 1 (Forwards)] [@frame Body] Throttle setpoint along body X axis +float32 throttle_body_y # [-] [@range -1 (Left), 1 (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Throttle setpoint along body Y axis ``` diff --git a/docs/en/msg_docs/VehicleCommand.md b/docs/en/msg_docs/VehicleCommand.md index 19557cf496..6c5e87ff5b 100644 --- a/docs/en/msg_docs/VehicleCommand.md +++ b/docs/en/msg_docs/VehicleCommand.md @@ -96,6 +96,7 @@ uint16 VEHICLE_CMD_REQUEST_CAMERA_INFORMATION = 521 # Request camera information uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.). uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom. uint16 VEHICLE_CMD_SET_CAMERA_FOCUS = 532 +uint16 VEHICLE_CMD_EXTERNAL_ATTITUDE_ESTIMATE = 620 # Set an external estimate of vehicle attitude in degrees. uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw. uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control. uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence. diff --git a/docs/en/msg_docs/VehicleStatus.md b/docs/en/msg_docs/VehicleStatus.md index d1deeb0500..9d46e42cb3 100644 --- a/docs/en/msg_docs/VehicleStatus.md +++ b/docs/en/msg_docs/VehicleStatus.md @@ -48,7 +48,7 @@ uint8 NAVIGATION_STATE_AUTO_LOITER = 4 # Auto loiter mode uint8 NAVIGATION_STATE_AUTO_RTL = 5 # Auto return to launch mode uint8 NAVIGATION_STATE_POSITION_SLOW = 6 uint8 NAVIGATION_STATE_FREE5 = 7 -uint8 NAVIGATION_STATE_FREE4 = 8 +uint8 NAVIGATION_STATE_ALTITUDE_CRUISE = 8 # Altitude with Cruise mode uint8 NAVIGATION_STATE_FREE3 = 9 uint8 NAVIGATION_STATE_ACRO = 10 # Acro mode uint8 NAVIGATION_STATE_FREE2 = 11 diff --git a/docs/en/msg_docs/index.md b/docs/en/msg_docs/index.md index 2c8085dc85..23f6c9441f 100644 --- a/docs/en/msg_docs/index.md +++ b/docs/en/msg_docs/index.md @@ -16,8 +16,8 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [ActuatorMotors](ActuatorMotors.md) — Motor control message - [ActuatorServos](ActuatorServos.md) — Servo control message - [AirspeedValidated](AirspeedValidated.md) -- [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply. -- [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request. +- [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply +- [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request - [BatteryStatus](BatteryStatus.md) — Battery status - [ConfigOverrides](ConfigOverrides.md) — Configurable overrides by (external) modes or mode executors - [Event](Event.md) — Events interface From 9980dccf437538db7e581d40dfa3d21bede3caf7 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 24 Sep 2025 10:10:08 +1000 Subject: [PATCH 068/812] [Docs] Fix broken links internal (#25604) --- docs/en/flight_modes_mc/position.md | 28 ++++++++++++++-------------- docs/en/sensor/sbgecom.md | 5 +---- 2 files changed, 15 insertions(+), 18 deletions(-) diff --git a/docs/en/flight_modes_mc/position.md b/docs/en/flight_modes_mc/position.md index 746a1baaac..69367bc4b1 100644 --- a/docs/en/flight_modes_mc/position.md +++ b/docs/en/flight_modes_mc/position.md @@ -43,7 +43,7 @@ While very rare on a well calibrated vehicle, sometimes there may be problems wi RC mode where roll, pitch, throttle (RPT) sticks control movement in corresponding axes/directions. Centered sticks level vehicle and hold it to fixed altitude and position against wind. -- Centered roll, pitch, throttle sticks (within RC deadzone [MAN_DEADZONE](../advanced_config/parameter_reference.md#MAN_DEADZONE)) hold x, y, z position steady against any disturbance like wind. +- Centered roll, pitch, throttle sticks (within RC deadzone [MAN_DEADZONE](#MAN_DEADZONE)) hold x, y, z position steady against any disturbance like wind. - Outside center: - Roll/Pitch sticks control horizontal acceleration over ground in the vehicle's left-right and forward-back directions (respectively). - Throttle stick controls speed of ascent-descent. @@ -60,19 +60,19 @@ Centered sticks level vehicle and hold it to fixed altitude and position against All the parameters in the [Multicopter Position Control](../advanced_config/parameter_reference.md#multicopter-position-control) group are relevant. A few parameters of particular note are listed below. -| Parameter | Description | -| ----------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | -| [MAN_DEADZONE](../advanced_config/parameter_reference.md#MAN_DEADZONE) | Deadzone of sticks where position hold is enabled. Default: 0.1 (10% of full stick range). | -| [MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | Maximum vertical ascent velocity. Default: 3 m/s. | -| [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | Maximum vertical descent velocity. Default: 1 m/s. | -| [MPC_LAND_ALT1](../advanced_config/parameter_reference.md#MPC_LAND_ALT1) | Altitude for triggering first phase of slow landing. Below this altitude descending velocity gets limited to a value between [MPC_Z_VEL_MAX_DN](#MPC_Z_VEL_MAX_DN) (or `MPC_Z_V_AUTO_DN`) and [MPC_LAND_SPEED](#MPC_LAND_SPEED). Value needs to be higher than [MPC_LAND_ALT2](#MPC_LAND_ALT2). Default 10m. | -| [MPC_LAND_ALT2](../advanced_config/parameter_reference.md#MPC_LAND_ALT2) | Altitude for second phase of slow landing. Below this altitude descending velocity gets limited to [`MPC_LAND_SPEED`](#MPC_LAND_SPEED). Value needs to be lower than "MPC_LAND_ALT1". Default 5m. | -| `RCX_DZ` | RC dead zone for channel X. The value of X for throttle will depend on the value of [RC_MAP_THROTTLE](../advanced_config/parameter_reference.md#RC_MAP_THROTTLE). For example, if the throttle is channel 4 then [RC4_DZ](../advanced_config/parameter_reference.md#RC4_DZ) specifies the deadzone. | -| `MPC_XXXX` | Most of the MPC_xxx parameters affect flight behaviour in this mode (at least to some extent). For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | -| [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE) | Stick input to movement translation strategy. From PX4 v1.12 the default (`Acceleration based`) is that stick position controls acceleration (in a similar way to a car accelerator pedal). Other options allow stick deflection to directly control speed over ground, with and without smoothing and acceleration limits. | -| [MPC_ACC_HOR_MAX](../advanced_config/parameter_reference.md#MPC_ACC_HOR_MAX) | Maximum horizontal acceleration. | -| [MPC_VEL_MANUAL](../advanced_config/parameter_reference.md#MPC_VEL_MANUAL) | Maximum horizontal velocity. | -| [MPC_LAND_SPEED](../advanced_config/parameter_reference.md#MPC_LAND_SPEED) | Landing descend rate. Default 0.7 m/s. | +| Parameter | Description | +| ----------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [MAN_DEADZONE](../advanced_config/parameter_reference.md#MAN_DEADZONE) | Deadzone of sticks where position hold is enabled. Default: 0.1 (10% of full stick range). | +| [MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | Maximum vertical ascent velocity. Default: 3 m/s. | +| [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | Maximum vertical descent velocity. Default: 1 m/s. | +| [MPC_LAND_ALT1](../advanced_config/parameter_reference.md#MPC_LAND_ALT1) | Altitude for triggering first phase of slow landing. Below this altitude descending velocity gets limited to a value between [MPC_Z_VEL_MAX_DN](#MPC_Z_VEL_MAX_DN) (or `MPC_Z_V_AUTO_DN`) and [MPC_LAND_SPEED](#MPC_LAND_SPEED). Value needs to be higher than [MPC_LAND_ALT2](#MPC_LAND_ALT2). Default 10m. | +| [MPC_LAND_ALT2](../advanced_config/parameter_reference.md#MPC_LAND_ALT2) | Altitude for second phase of slow landing. Below this altitude descending velocity gets limited to [`MPC_LAND_SPEED`](#MPC_LAND_SPEED). Value needs to be lower than "MPC_LAND_ALT1". Default 5m. | +| `RCX_DZ` | RC dead zone for channel X. The value of X for throttle will depend on the value of [RC_MAP_THROTTLE](../advanced_config/parameter_reference.md#RC_MAP_THROTTLE). For example, if the throttle is channel 4 then [RC4_DZ](../advanced_config/parameter_reference.md#RC4_DZ) specifies the deadzone. | +| `MPC_XXXX` | Most of the MPC_xxx parameters affect flight behaviour in this mode (at least to some extent). For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | +| [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE) | Stick input to movement translation strategy. From PX4 v1.12 the default (`Acceleration based`) is that stick position controls acceleration (in a similar way to a car accelerator pedal). Other options allow stick deflection to directly control speed over ground, with and without smoothing and acceleration limits. | +| [MPC_ACC_HOR_MAX](../advanced_config/parameter_reference.md#MPC_ACC_HOR_MAX) | Maximum horizontal acceleration. | +| [MPC_VEL_MANUAL](../advanced_config/parameter_reference.md#MPC_VEL_MANUAL) | Maximum horizontal velocity. | +| [MPC_LAND_SPEED](../advanced_config/parameter_reference.md#MPC_LAND_SPEED) | Landing descend rate. Default 0.7 m/s. | ## Additional Information diff --git a/docs/en/sensor/sbgecom.md b/docs/en/sensor/sbgecom.md index 673856387c..508024bbd0 100644 --- a/docs/en/sensor/sbgecom.md +++ b/docs/en/sensor/sbgecom.md @@ -59,7 +59,6 @@ To use the sbgECom driver: 3. Set [SBG_BAUDRATE](../advanced_config/parameter_reference.md#SBG_BAUDRATE) to the desired default baudrate value. 4. Allow the sbgECom driver to initialize by restarting PX4. 5. Configure driver to provide IMU data, GNSS data and INS : - 1. Set [SBG_MODE](../advanced_config/parameter_reference.md#SBG_MODE) to the desired mode. 2. Make sensor module select sensors by enabling [SENS_IMU_MODE](../advanced_config/parameter_reference.md#SENS_IMU_MODE). 3. Prioritize SBG Systems sensors using [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO), [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO), [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO), [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO), where _n_ is the instance number of the IMU component (0, 1, etc.). @@ -78,7 +77,6 @@ To use the sbgECom driver: If you don't want to have this fallback mechanism, you must disable unwanted sensors. ::: - 4. If using the sbgECom as an INS, disable EKF2 using [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN). 6. Restart PX4. @@ -90,7 +88,7 @@ IMU data should be published at 200Hz. All High Performance and Ellipse 3.0 and higher SBG Systems INS can be configured directly from PX4 firmware: -1. Enable [SBG_CONFIGURATION_EN](../advanced_config/parameter_reference.md#SBG_CONFIGURATION_EN) +1. Enable [SBG_CONFIGURE_EN](../advanced_config/parameter_reference.md#SBG_CONFIGURE_EN). 2. Provide a JSON file `sbg_settings.json` containing SBG Systems INS settings to be applied in your PX4 board `extras` directory (ex: `boards/px4/fmu-v5/extras`). The settings JSON file will be installed in `/etc/extras/sbg_settings.json` on the board. ::: tip @@ -102,7 +100,6 @@ All High Performance and Ellipse 3.0 and higher SBG Systems INS can be configure ::: 3. For testing purpose, it's also possible to modify SBG Systems INS settings on the fly: - - By passing a JSON file path as argument when starting sbgecom driver (ex: `sbgecom start -f /fs/microsd/new_sbg_settings.json`) - By passing a JSON string as argument when starting sbgecom driver: (ex: `sbgecom start -s {"output":{"comA":{"messages":{"airData":"onChange"}}}}`) From db58ecb5eb012f994fd018948796ecba46a23b26 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Wed, 24 Sep 2025 10:33:22 +1000 Subject: [PATCH 069/812] New Crowdin translations - zh-CN (#25590) Co-authored-by: Crowdin Bot --- docs/zh/SUMMARY.md | 1 + docs/zh/advanced_config/tuning_the_ecl_ekf.md | 6 +- docs/zh/assembly/_assembly.md | 2 +- docs/zh/camera/fc_connected_camera.md | 14 +- docs/zh/concept/flight_modes.md | 6 +- docs/zh/dev_setup/vscode.md | 2 +- docs/zh/dronecan/ark_rtk_gps.md | 24 +- docs/zh/dronecan/escs.md | 15 + docs/zh/dronecan/index.md | 8 +- docs/zh/flight_controller/mindracer.md | 2 +- docs/zh/flight_controller/modalai_fc_v1.md | 2 +- .../flight_controller/modalai_voxl_flight.md | 2 +- docs/zh/flight_modes_fw/index.md | 2 + docs/zh/flight_modes_mc/altitude.md | 2 +- docs/zh/flight_modes_mc/altitude_cruise.md | 45 ++ docs/zh/flight_modes_mc/index.md | 4 +- docs/zh/flight_modes_mc/manual_stabilized.md | 2 +- docs/zh/flight_modes_mc/position.md | 4 +- docs/zh/flight_modes_rover/index.md | 4 +- docs/zh/flight_modes_rover/manual.md | 4 +- docs/zh/frames_rover/index.md | 6 +- docs/zh/middleware/uxrce_dds.md | 27 +- docs/zh/modules/modules_driver_ins.md | 25 + docs/zh/modules/modules_system.md | 13 +- docs/zh/msg_docs/ActuatorMotors.md | 4 +- docs/zh/msg_docs/ActuatorServos.md | 2 +- docs/zh/msg_docs/ArmingCheckReply.md | 42 +- docs/zh/msg_docs/ArmingCheckRequest.md | 10 +- docs/zh/msg_docs/BatteryStatus.md | 123 ++--- docs/zh/msg_docs/EstimatorStatus.md | 4 +- docs/zh/msg_docs/EstimatorStatusFlags.md | 3 +- docs/zh/msg_docs/PurePursuitStatus.md | 12 +- docs/zh/msg_docs/RoverAttitudeSetpoint.md | 4 +- docs/zh/msg_docs/RoverAttitudeStatus.md | 6 +- docs/zh/msg_docs/RoverPositionSetpoint.md | 12 +- docs/zh/msg_docs/RoverRateSetpoint.md | 4 +- docs/zh/msg_docs/RoverRateStatus.md | 8 +- docs/zh/msg_docs/RoverSpeedSetpoint.md | 6 +- docs/zh/msg_docs/RoverSpeedStatus.md | 14 +- docs/zh/msg_docs/RoverSteeringSetpoint.md | 4 +- docs/zh/msg_docs/RoverThrottleSetpoint.md | 6 +- docs/zh/msg_docs/VehicleCommand.md | 1 + docs/zh/msg_docs/VehicleStatus.md | 2 +- docs/zh/msg_docs/index.md | 4 +- docs/zh/releases/main.md | 7 +- docs/zh/ros2/index.md | 8 +- docs/zh/ros2/multi_vehicle.md | 6 +- docs/zh/ros2/offboard_control.md | 146 +++--- docs/zh/ros2/px4_ros2_control_interface.md | 488 +++++++++--------- docs/zh/ros2/px4_ros2_msg_translation_node.md | 252 +++++---- docs/zh/ros2/px4_ros2_navigation_interface.md | 147 +++--- docs/zh/ros2/user_guide.md | 114 ++-- docs/zh/sensor/sbgecom.md | 4 +- docs/zh/sim_sih/index.md | 2 +- 54 files changed, 904 insertions(+), 763 deletions(-) create mode 100644 docs/zh/flight_modes_mc/altitude_cruise.md diff --git a/docs/zh/SUMMARY.md b/docs/zh/SUMMARY.md index 048ee16c6b..ce8bb6cae4 100644 --- a/docs/zh/SUMMARY.md +++ b/docs/zh/SUMMARY.md @@ -7,6 +7,7 @@ - [位置模式(多旋翼)](flight_modes_mc/position.md) - [Position Slow Mode (MC)](flight_modes_mc/position_slow.md) - [高度模式(多旋翼)](flight_modes_mc/altitude.md) + - [Altitude Cruise Mode (MC)](flight_modes_mc/altitude_cruise.md) - [Stabilized Mode (MC)](flight_modes_mc/manual_stabilized.md) - [特技模式(多旋翼)](flight_modes_mc/acro.md) - [环绕模式(多旋翼)](flight_modes_mc/orbit.md) diff --git a/docs/zh/advanced_config/tuning_the_ecl_ekf.md b/docs/zh/advanced_config/tuning_the_ecl_ekf.md index 4f91ebfd61..6fcdfeb902 100644 --- a/docs/zh/advanced_config/tuning_the_ecl_ekf.md +++ b/docs/zh/advanced_config/tuning_the_ecl_ekf.md @@ -481,11 +481,11 @@ Position, velocity or orientation measurements from an external vision system, e The measurements that are fused are configured by setting the appropriate bits of [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL) to `true`: -- `0`: Horizontal position data +- `0`: 水平位置数据 - `1`: Vertical position data. Height sources may additionally be configured using [EKF2_HGT_REF](../advanced_config/parameter_reference.md#EKF2_HGT_REF) (see section [Height](#height)). -- `2`: Velocity data -- `3`: Yaw data +- `2`:速度数据 +- `3`:偏航角数据 Note that if yaw data is used (bit 3) the heading is with respect to the external vision frame; otherwise the heading is relative to North. diff --git a/docs/zh/assembly/_assembly.md b/docs/zh/assembly/_assembly.md index 15e97dc7ed..19062417ac 100644 --- a/docs/zh/assembly/_assembly.md +++ b/docs/zh/assembly/_assembly.md @@ -72,7 +72,7 @@ The FCs have much the same ports with similar names, and core peripherals are co | Full GPS plus Safety Switch | GPS1 | GPS&SAFETY | Primary GNSS module (GPS, compass, safety switch, buzzer, LED) | | Basic GPS | GPS2 | GPS2 | Secondary GNSS module (GNSS/compass) | | CAN | CAN1/CAN2 | CAN1/CAN2 | DroneCAN devices, such as GNSS modules, motors, etc | -| Telemetry | TELEM (1,2,3) | TELEM (1,2,3) | Telemetry radios, companion computers, MAVLink cameras, etc. | +| 数传 | TELEM (1,2,3) | TELEM (1,2,3) | Telemetry radios, companion computers, MAVLink cameras, etc. | | Analog Power | POWER (1,2) | POWER (1,2) | SMbus (I2C) power modules | | I2C | I2C | None | Other I2C peripherals | | SPI | SPI | SPI6 | SPI devices (note: 11 pin, not 6 as in standard) | diff --git a/docs/zh/camera/fc_connected_camera.md b/docs/zh/camera/fc_connected_camera.md index f6254eb86b..ea9e1e0164 100644 --- a/docs/zh/camera/fc_connected_camera.md +++ b/docs/zh/camera/fc_connected_camera.md @@ -97,13 +97,13 @@ For more information see [Finding/Updating Parameters > Parameters Not In Firmwa Four different modes are supported, controlled by the [TRIG_MODE](../advanced_config/parameter_reference.md#TRIG_MODE) parameter: -| Mode | 描述 | -| ---- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| 0 | Camera triggering is disabled. | -| 1 | Works like a basic intervalometer that can be enabled and disabled by using the MAVLink command `MAV_CMD_DO_TRIGGER_CONTROL`. See [command interface](#mavlink-command-interface) for more details. | -| 2 | Switches the intervalometer constantly on. | -| 3 | Triggers based on distance. A shot is taken every time the set horizontal distance is exceeded. The minimum time interval between two shots is however limited by the set triggering interval. | -| 4 | Triggers automatically when flying a survey in Mission mode. | +| 模式 | 描述 | +| -- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| 0 | Camera triggering is disabled. | +| 1 | Works like a basic intervalometer that can be enabled and disabled by using the MAVLink command `MAV_CMD_DO_TRIGGER_CONTROL`. See [command interface](#mavlink-command-interface) for more details. | +| 2 | Switches the intervalometer constantly on. | +| 3 | Triggers based on distance. A shot is taken every time the set horizontal distance is exceeded. The minimum time interval between two shots is however limited by the set triggering interval. | +| 4 | Triggers automatically when flying a survey in Mission mode. | :::info If it is your first time enabling the camera trigger app, remember to reboot after changing the `TRIG_MODE` parameter. diff --git a/docs/zh/concept/flight_modes.md b/docs/zh/concept/flight_modes.md index 02213e41b4..66a4e79841 100644 --- a/docs/zh/concept/flight_modes.md +++ b/docs/zh/concept/flight_modes.md @@ -95,9 +95,9 @@ mode_req_other # other requirements, not covered above (for external If the condition of restriction is not met: -- arming is not allowed, while the mode is selected -- when already armed, the mode cannot be selected -- when armed and the mode is selected, the relevant failsafe is triggered (e.g. RC loss for the manual control requirement). +- 在选定模式时不允许进行解锁操作 +- 当已处于武装状态时,该模式无法被选择。 +- 当载具已解锁且该模式被选中时,相关的故障保护机制会被触发(例如,针对手动控制需求的遥控器信号丢失故障保护)。 Check [Safety (Failsafe) Configuration](../config/safety.md) for how to configure failsafe behaviour. This is the corresponding flow diagram for the manual control flag (`mode_req_manual_control`): diff --git a/docs/zh/dev_setup/vscode.md b/docs/zh/dev_setup/vscode.md index 4b699c246b..27d65694fb 100644 --- a/docs/zh/dev_setup/vscode.md +++ b/docs/zh/dev_setup/vscode.md @@ -19,7 +19,7 @@ With _VScode_, configuration is stored in the PX4/PX4-Autopilot tree ([PX4-Autop You must already have installed the command line [PX4 developer environment](../dev_setup/dev_env.md) for your platform and downloaded the _Firmware_ source code repo. -## Installation & Setup +## 安装与设置 1. [Download and install VSCode](https://code.visualstudio.com/) (you will be offered the correct version for your OS). diff --git a/docs/zh/dronecan/ark_rtk_gps.md b/docs/zh/dronecan/ark_rtk_gps.md index fdecdc4b08..75064c1780 100644 --- a/docs/zh/dronecan/ark_rtk_gps.md +++ b/docs/zh/dronecan/ark_rtk_gps.md @@ -27,7 +27,7 @@ Order this module from: - Safety Button - 蜂鸣器 - Two Pixhawk Standard CAN Connectors (4 Pin JST GH) -- F9P “UART 2” Connector +- F9P `UART 2` Connector - 3 Pin JST GH - TX, RX, GND - Pixhawk Standard Debug Connector (6 Pin JST SH) @@ -87,6 +87,25 @@ You need to set necessary [DroneCAN](index.md) parameters and define offsets if - The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK RTK GPS from the vehicles centre of gravity. - Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` on the GPS if this it that last node on the CAN bus. +### Setting Up Rover and Fixed Base + +Position of the rover is established using RTCM messages from the RTK base module (the base module is connected to QGC, which sends the RTCM information to PX4 via MAVLink). + +PX4 DroneCAN parameters: + +- [UAVCAN_PUB_RTCM](../advanced_config/parameter_reference.md#UAVCAN_PUB_RTCM): + - Makes PX4 publish RTCM messages ([RTCMStream](https://dronecan.github.io/Specification/7._List_of_standard_data_types/#rtcmstream)) to the bus (which it gets from the RTK base module via QGC). + +Rover module parameters (also [set using QGC](../dronecan/index.md#qgc-cannode-parameter-configuration)): + +- [CANNODE_SUB_RTCM](../advanced_config/parameter_reference.md#CANNODE_SUB_RTCM) tells the rover that it should subscribe to [RTCMStream](https://dronecan.github.io/Specification/7._List_of_standard_data_types/#rtcmstream) RTCM messages on the bus (from the moving base). + +:::info +Use [UAVCAN_PUB_MBD](../advanced_config/parameter_reference.md#UAVCAN_PUB_MBD) and [CANNODE_SUB_MBD](../advanced_config/parameter_reference.md#CANNODE_SUB_MBD) instead if you want to implement moving base (see below) at the same time. +::: + +For more information see [Rover and Fixed Base](../dronecan/index.md#rover-and-fixed-base) in the DroneCAN guide. + ### Setting Up Moving Baseline & GPS Heading The simplest way to set up moving baseline and GPS heading with two ARK RTK GPS modules is via CAN, though it can be done via UART to reduce traffic on the CAN bus if desired. @@ -128,10 +147,11 @@ Setup via UART: - On the _Moving Base_, set the following: - [GPS_UBX_MODE](../advanced_config/parameter_reference.md#GPS_UBX_MODE) to `2`. +For more information see [Rover and Moving Base](../dronecan/index.md#rover-and-moving-base) in the DroneCAN guide. + ## LED含义 - The GPS status lights are located to the right of the connectors - - Blinking green is GPS fix - Blinking blue is received corrections and RTK Float - Solid blue is RTK Fixed diff --git a/docs/zh/dronecan/escs.md b/docs/zh/dronecan/escs.md index 9742e3739e..547208bf30 100644 --- a/docs/zh/dronecan/escs.md +++ b/docs/zh/dronecan/escs.md @@ -9,3 +9,18 @@ For more information, see the following articles for specific hardware/firmware: - [Vertiq](../peripherals/vertiq.md) (larger modules) - [VESC Project](../peripherals/vesc.md) - [RaccoonLab Cyphal and DroneCAN PWM nodes](raccoonlab_nodes.md) + +## 硬件配置 + +General DroneCAN hardware configuration is covered in [DroneCAN > Hardware Setup](../dronecan/index.md#hardware-setup). + +DroneCAN ESCs should be on their own dedicated CAN interface(s) because ESC messages can saturate the bus and starve other nodes of bandwidth. + +## PX4 配置 + +DroneCAN peripherals are configured by following the procedure outlined in [DroneCAN](../dronecan/index.md). + +In addition to the general setup, such as setting `UAVCAN_ENABLE` to `3`: + +- Select the specific CAN interface(s) used for ESC data output using the [UAVCAN_ESC_IFACE](../advanced_config/parameter_reference.md#UAVCAN_ESC_IFACE) parameter (all that all interfaces are selected by default). +- Configure the [motor order and servo outputs](../config/actuators.md). diff --git a/docs/zh/dronecan/index.md b/docs/zh/dronecan/index.md index 7e056d7be2..16915394f8 100644 --- a/docs/zh/dronecan/index.md +++ b/docs/zh/dronecan/index.md @@ -276,6 +276,9 @@ PX4 DroneCAN parameters: [DroneCAN ESCs and servos](../dronecan/escs.md) require the [motor order and servo outputs](../config/actuators.md) to be configured. +Select the specific CAN interface(s) used for ESC data output using the [UAVCAN_ESC_IFACE](../advanced_config/parameter_reference.md#UAVCAN_ESC_IFACE) parameter (all that all interfaces are selected by default). +Note that DroneCAN ESCs should be on their own dedicated CAN interface(s) because ESC messages can saturate the bus and starve other nodes of bandwidth. + ## QGC CANNODE Parameter Configuration QGroundControl can inspect and modify parameters belonging to CAN devices attached to the flight controller, provided the device are connected to the flight controller before QGC is started. @@ -313,7 +316,10 @@ If successful, the firmware binary will be removed from the root directory and t **Q**: The motors aren't spinning when armed. -**A**: Make sure `UAVCAN_ENABLE` is set to `3` to enable DroneCAN ESC output. +**A**: + +- Make sure `UAVCAN_ENABLE` is set to `3` to enable DroneCAN ESC output. +- Make sure `UAVCAN_ESC_IFACE` is set to enable the CAN interface(s) used for ESCs. --- diff --git a/docs/zh/flight_controller/mindracer.md b/docs/zh/flight_controller/mindracer.md index 14aedd78c0..a520ffd967 100644 --- a/docs/zh/flight_controller/mindracer.md +++ b/docs/zh/flight_controller/mindracer.md @@ -44,7 +44,7 @@ The main hardware documentation is [here](http://mindpx.net/assets/accessories/m | IMU | 10DOF | | IMU isolation | YES/Optional | | Radio Receiver | S.BUS/PPM/DSM/DSM2/DSMX/SUMD | -| Telemetry | FrSky® D.Port, S.Port, Wifi, 3DR radio | +| 数传 | FrSky® D.Port, S.Port, Wifi, 3DR radio | | On board TF card for flight data recording | YES | | OneShot ESC Support | YES | | Expansion Slots | 2x7(pin)x2 | diff --git a/docs/zh/flight_controller/modalai_fc_v1.md b/docs/zh/flight_controller/modalai_fc_v1.md index 1b8239b84d..1e9562b83d 100644 --- a/docs/zh/flight_controller/modalai_fc_v1.md +++ b/docs/zh/flight_controller/modalai_fc_v1.md @@ -40,7 +40,7 @@ This flight controller is [manufacturer supported](../flight_controller/autopilo | microSD Card | [Information on supported cards](../dev_log/logging.md#sd-cards) | | 输入 | GPS/Mag | | | Spektrum | -| | Telemetry | +| | 数传 | | | CAN bus | | | PPM | | Outputs | 6 LEDs (2xRGB) | diff --git a/docs/zh/flight_controller/modalai_voxl_flight.md b/docs/zh/flight_controller/modalai_voxl_flight.md index c77e143538..352fd22892 100644 --- a/docs/zh/flight_controller/modalai_voxl_flight.md +++ b/docs/zh/flight_controller/modalai_voxl_flight.md @@ -67,7 +67,7 @@ This flight controller is [manufacturer supported](../flight_controller/autopilo | microSD Card | [Information on supported cards](../dev_log/logging.md#sd-cards) | | 输入 | GPS/Mag | | | Spektrum | -| | Telemetry | +| | 数传 | | | CAN bus | | | PPM | | Outputs | 6 LEDs (2xRGB) | diff --git a/docs/zh/flight_modes_fw/index.md b/docs/zh/flight_modes_fw/index.md index d6fd66e2f5..0c9f655ad4 100644 --- a/docs/zh/flight_modes_fw/index.md +++ b/docs/zh/flight_modes_fw/index.md @@ -17,6 +17,8 @@ Manual-Easy: Airspeed is actively controlled if an airspeed sensor is installed. - [Altitude](../flight_modes_fw/altitude.md) — Easiest and safest _non-GPS_ manual mode. The only difference compared to _Position mode_ is that the pilot always directly controls the roll angle of the plane and there is no automatic course holding. +- Altitude Cruise mode — It behaves exactly like _Altitude mode_, with the only difference being that the manual control failsafe can be disabled. This is done by setting the corresponding flag in [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT). In that case the current altitude, airspeed and heading (by leveling out the roll angle) are kept until the manual control link is regained or the mode is exited. + It is highly recommended to only disable the manual control loss failsafe for this mode if there is a stable data link connection to the vehicle at all times, or to enable the data link loss failsafe through [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT). - [Stabilized mode](../flight_modes_fw/stabilized.md) — The pilot directly commands the roll and pitch angle and the vehicle keeps the setpoint until the sticks are moved again. Thrust is directly set by the pilot. Turn coordination is still handled by the controller. diff --git a/docs/zh/flight_modes_mc/altitude.md b/docs/zh/flight_modes_mc/altitude.md index 3e1af11c58..e7ce6d130e 100644 --- a/docs/zh/flight_modes_mc/altitude.md +++ b/docs/zh/flight_modes_mc/altitude.md @@ -21,7 +21,7 @@ The diagram below shows the mode behaviour visually (for a [mode 2 transmitter]( RC/manual mode like [Stabilized mode](../flight_modes_mc/manual_stabilized.md) but with _altitude stabilization_ (centred sticks level vehicle and hold it to fixed altitude). The horizontal position of the vehicle can move due to wind (or pre-existing momentum). -- 回正摇杆(内带死区): +- Centered sticks: - RPY摇杆使飞机水平。 - 油门(~50%)抗风保持当前姿态。 - 外部中心: diff --git a/docs/zh/flight_modes_mc/altitude_cruise.md b/docs/zh/flight_modes_mc/altitude_cruise.md new file mode 100644 index 0000000000..eda1cf30ce --- /dev/null +++ b/docs/zh/flight_modes_mc/altitude_cruise.md @@ -0,0 +1,45 @@ +# Altitude Cruise Mode (Multicopter) + +   + +_Altitude Cruise mode_ is a _relatively_ easy-to-fly manual control mode in which roll and pitch sticks control vehicle movement in the left-right and forward-back directions (relative to the "front" of the vehicle), yaw stick controls rate of rotation over the horizontal plane, and throttle controls speed of ascent-descent. + +When the sticks are released/centered the vehicle will keep the current tilt and heading angle and maintain the current _altitude_. +If moving in the horizontal plane the vehicle will accelerate until the wind resistance equals the acceleration caused by the set tilt angle. +The vehicle will then continue to move with a constant velocity (unlike for Altitude mode, in which the vehicle will eventually slow down and stop). +If the wind blows the aircraft will drift in the direction of the wind even if flying perfectly level. + +:::tip +_Altitude Cruise mode_ is intended for long distance flights where the same tilt angle is kept for a long period of time. It is just like [Altitude](../flight_modes_mc/altitude.md) mode but does not go back to level tilt when the sticks are released. +::: + +The diagram below shows the mode behaviour visually (for a [mode 2 transmitter](../getting_started/rc_transmitter_receiver.md#transmitter_modes)). + +![Altitude Control MC - Mode2 RC Controller](../../assets/flight_modes/altitude_mc.png) + +## 技术总结 + +A manual mode that is similar to [Altitude mode](../flight_modes_mc/altitude.md) but with different interpretation of roll and pitch sticks. + +- Centered sticks: + - Roll/Pitch sticks: the current tilt is kept. + - Yaw: the current heading is kept. + - Throttle (~50%) holds current altitude. +- 外部中心: + - Roll/Pitch sticks control the rate of change of the tilt angle, resulting in corresponding left-right and forward-back movement. A maximum stick deflection results in a tilting rate setpoint to go from level to max tilt within 0.5 seconds. + - Yaw stick deflection rotates the tilt angle either left or right, causing the vehicle to change course. It is _not_ causing a direct rotation around the body yaw axis like in [Acro mode](../flight_modes_mc/acro.md). + - 油门摇杆以预定的最大速率(和其他轴上的移动速度)控制上升速度。 +- 起飞: + - 降落时,如果将油门杆抬高至 62.5%(从油门杆最低开始的整个范围),无人机将起飞。 +- Manual control input is required (such as RC control, joystick) to enter this mode. Other than in all other manual modes, it's though possible to disable the manual control loss failsafe by setting the corresponding flag in [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT). In that case the current altitude, tilt and heading are kept until the manual control link is regained or the mode is exited. + It is highly recommended to only disable the manual control loss failsafe for this mode if there is a stable data link connection to the vehicle at all times, and to enable the data link loss failsafe through [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT). + +## 参数 + +Most of the relevant parameters are already covered in the corresponding section in the [Altitude mode](../flight_modes_mc/altitude.md). Here a list of parameters of particular importance for Altitude Cruise. + +| 参数 | 描述 | +| -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | The manual control failsafe can be disabled for Altitude Cruise by setting the corresponding bit in this parameter. | +| [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT) | Data link lost failsafe action. Recommended to set if the manual control failsafe is disabled to avoid fly-aways. | +| [MPC_MAN_TILT_MAX](../advanced_config/parameter_reference.md#MPC_MAN_TILT_MAX) | The maximum tilt angle the vehicle will go to. At max stick deflection, it will take 0.5 seconds from level flight to this tilt angle. | diff --git a/docs/zh/flight_modes_mc/index.md b/docs/zh/flight_modes_mc/index.md index 806046c6e7..1b407d6239 100644 --- a/docs/zh/flight_modes_mc/index.md +++ b/docs/zh/flight_modes_mc/index.md @@ -21,10 +21,12 @@ Manual-Easy: - [Stabilized mode](../flight_modes_mc/manual_stabilized.md) — Releasing the sticks levels and maintains the vehicle horizontal posture (but not altitude or position). The vehicle will continue to move with momentum, and both altitude and horizontal position may be affected by wind. This mode is also used if "Manual mode" is selected in a ground station. +- [Altitude Cruise mode](../flight_modes_mc/altitude_cruise.md) — Very similar to _Altitude mode_, with the difference that when the roll and pitch sticks are released the vehicle does not level out but keeps the tilt until further inputs are given. + Additionally it is possible to disable the manual control failsafe for this mode, having the vehicle continue on it's set path even if there are no new control inputs. Manual-Acrobatic -- [Acro](../flight_modes_mc/acro.md) — Manual mode for performing acrobatic maneuvers, such as rolls and loops. +- [Acro](../flight_modes_mc/acro.md) — Manual mode for performing acrobatic manoeuvrers, such as rolls and loops. Releasing the sticks stops the vehicle rotating in the roll, pitch, yaw axes, but does not otherwise stabilise the vehicle. Autonomous: diff --git a/docs/zh/flight_modes_mc/manual_stabilized.md b/docs/zh/flight_modes_mc/manual_stabilized.md index 671368ee82..b1f9de1f78 100644 --- a/docs/zh/flight_modes_mc/manual_stabilized.md +++ b/docs/zh/flight_modes_mc/manual_stabilized.md @@ -31,7 +31,7 @@ Throttle is rescaled (see [below](#params)) and passed directly to control alloc 自动驾驶仪控制着飞机的姿态角,这意味着当 RC 摇杆居中时自驾仪调整飞机的滚转和俯仰角为零(从而实现飞机姿态的改平)。 自动驾驶仪不能补偿由于风(或其他来源)引起的漂移。 -- 回正摇杆(内带死区): +- Centered sticks: - Roll/Pitch sticks level vehicle. - 外部中心: - Roll/Pitch sticks control tilt angle in those orientations, resulting in corresponding left-right and forward-back movement. diff --git a/docs/zh/flight_modes_mc/position.md b/docs/zh/flight_modes_mc/position.md index fa70ad7997..b35ce39d7b 100644 --- a/docs/zh/flight_modes_mc/position.md +++ b/docs/zh/flight_modes_mc/position.md @@ -43,7 +43,7 @@ While very rare on a well calibrated vehicle, sometimes there may be problems wi 遥控模式下,横滚、俯仰、油门 (RPT) 杆控制相应轴/方向的运动。 摇杆居中使机体水平并将其保持在固定的高度和位置并抗风。 -- Centered roll, pitch, throttle sticks (within RC deadzone [MPC_HOLD_DZ](../advanced_config/parameter_reference.md#MPC_HOLD_DZ)) hold x, y, z position steady against any disturbance like wind. +- Centered roll, pitch, throttle sticks (within RC deadzone [MAN_DEADZONE](#MAN_DEADZONE)) hold x, y, z position steady against any disturbance like wind. - 外部中心: - Roll/Pitch sticks control horizontal acceleration over ground in the vehicle's left-right and forward-back directions (respectively). - Throttle stick controls speed of ascent-descent. @@ -62,7 +62,7 @@ All the parameters in the [Multicopter Position Control](../advanced_config/para | 参数 | 描述 | | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [MPC_HOLD_DZ](../advanced_config/parameter_reference.md#MPC_HOLD_DZ) | 启用位置保持的摇杆死区。 默认值:0.1(摇杆全行程的 10%)。 | +| [MAN_DEADZONE](../advanced_config/parameter_reference.md#MAN_DEADZONE) | 启用位置保持的摇杆死区。 默认值:0.1(摇杆全行程的 10%)。 | | [MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | 最大垂直上升速度。 默认:3m/s。 | | [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | 最大垂直下降速度。 默认:1m/s。 | | [MPC_LAND_ALT1](../advanced_config/parameter_reference.md#MPC_LAND_ALT1) | 触发第一阶段降速的高度。 Below this altitude descending velocity gets limited to a value between [MPC_Z_VEL_MAX_DN](#MPC_Z_VEL_MAX_DN) (or `MPC_Z_V_AUTO_DN`) and [MPC_LAND_SPEED](#MPC_LAND_SPEED). Value needs to be higher than [MPC_LAND_ALT2](#MPC_LAND_ALT2). Default 10m. | diff --git a/docs/zh/flight_modes_rover/index.md b/docs/zh/flight_modes_rover/index.md index 38f185f784..567fb20460 100644 --- a/docs/zh/flight_modes_rover/index.md +++ b/docs/zh/flight_modes_rover/index.md @@ -12,7 +12,7 @@ Selecting any other mode than those listed below will either stop the rover or c ## Manual Modes -| Mode | 描述 | +| 模式 | 描述 | | --------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | | [Manual](manual.md#manual-mode) | No autopilot support. User is responsible for keeping the rover on the desired course and maintaining speed and rate of turn. | | [Acro](manual.md#acro-mode) | + Maintains the yaw rate (feels more like driving a car than manual mode).
+ Allows maximum yaw rate to be limited (protects against roll over). | @@ -21,7 +21,7 @@ Selecting any other mode than those listed below will either stop the rover or c ## Auto Modes -| Mode | 描述 | +| 模式 | 描述 | | ------------------------------- | --------------------------------------------------------------------------------------- | | [Mission](auto.md#mission-mode) | Automatic mode that causes the vehicle to execute a predefined mission. | | [Return](auto.md#return-mode) | Automatic mode that returns the vehicle to the launch position. | diff --git a/docs/zh/flight_modes_rover/manual.md b/docs/zh/flight_modes_rover/manual.md index 6363cd9baf..2f0cecdf04 100644 --- a/docs/zh/flight_modes_rover/manual.md +++ b/docs/zh/flight_modes_rover/manual.md @@ -14,7 +14,7 @@ The sticks provide the same "high level" control effects over direction and rate The manual modes provide progressively increasing levels of autopilot support for maintaining a course, speed, and rate of turn, compensating for external factors such as slopes or uneven terrain. -| Mode | 描述 | +| 模式 | 描述 | | --------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | | [Manual](manual.md#manual-mode) | No autopilot support. User is responsible for keeping the rover on the desired course and maintaining speed and rate of turn. | | [Acro](manual.md#acro-mode) | + Maintains the yaw rate (feels more like driving a car than manual mode).
+ Allows maximum yaw rate to be limited (protects against roll over). | @@ -24,7 +24,7 @@ The manual modes provide progressively increasing levels of autopilot support fo :::details Overview mode mapping to control effect -| Mode | Speed | Turning | Required measurements | +| 模式 | Speed | Turning | Required measurements | | ------------------------------ | ---------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------- | | [Manual](#manual-mode) | Directly map stick input to motor command. | Directly map stick input to steering angle/speed difference. | None. | | [Acro](#acro-mode) | Directly map stick input to motor command. | Stick input creates a yaw rate setpoint for the control system to regulate. | yaw rate. | diff --git a/docs/zh/frames_rover/index.md b/docs/zh/frames_rover/index.md index 59537ab34e..79d212bdca 100644 --- a/docs/zh/frames_rover/index.md +++ b/docs/zh/frames_rover/index.md @@ -21,7 +21,7 @@ The supported frames can be seen in [Airframes Reference > Rover](../airframes/a ## Ackermann - +<0/> <1/> An Ackermann rover controls its direction by pointing the front wheels in the direction of travel — the [Ackermann steering geometry](https://en.wikipedia.org/wiki/Ackermann_steering_geometry) compensates for the fact that wheels on the inside and outside of the turn move at different rates. This kind of steering is used on most commercial vehicles, including cars, trucks etc. @@ -34,7 +34,7 @@ PX4 does not require that the vehicle uses the Ackermann geometry and will work ## Differential - +<0/> <1/> A differential rover's motion is controlled using a differential drive mechanism, where the left and right wheel speeds are adjusted independently to achieve the desired forward speed and yaw rate. Forward motion is achieved by driving both wheels at the same speed in the same direction. @@ -48,7 +48,7 @@ The differential setup also work for rovers with skid or tank steering. ## Mecanum - +<0/> <1/> A Mecanum rover is a type of mobile robot that uses Mecanum wheels to achieve omnidirectional movement. These wheels are unique because they have rollers mounted at a 45-degree angle around their circumference, allowing the rover to move not only forward and backward but also side-to-side and diagonally without needing to rotate first. Each wheel is driven by its own motor, and by controlling the speed and direction of each motor, the rover can move in any direction or spin in place. diff --git a/docs/zh/middleware/uxrce_dds.md b/docs/zh/middleware/uxrce_dds.md index 3a6ad2baf6..8d04eb706f 100644 --- a/docs/zh/middleware/uxrce_dds.md +++ b/docs/zh/middleware/uxrce_dds.md @@ -65,7 +65,7 @@ PX4 Micro XRCE-DDS Client is based on version `v2.x` which is not compatible wit On Ubuntu you can build from source and install the Agent standalone using the following commands: ```sh -git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git +git clone -b v2.4.3 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git cd Micro-XRCE-DDS-Agent mkdir build cd build @@ -126,7 +126,7 @@ To build the agent within ROS: ```sh cd ~/px4_ros_uxrce_dds_ws/src - git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git + git clone -b v2.4.3 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git ``` 3. Source the ROS 2 development environment, and compile the workspace using `colcon`: @@ -279,6 +279,9 @@ The configuration can be done using the [UXRCE-DDS parameters](../advanced_confi - [UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT): Bridge time synchronization enable. The uXRCE-DDS client module can synchronize the timestamp of the messages exchanged over the bridge. This is the default configuration. In certain situations, for example during [simulations](../ros2/user_guide.md#ros-gazebo-and-px4-time-synchronization), this feature may be disabled. + - [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX): Index-based namespace definition + Setting this parameter to any value other than `-1` creates a namespace with the prefix `uav_` and the specified value, e.g. `uav_0`, `uav_1`, etc. + See [namespace](#customizing-the-namespace) for methods to define richer or arbitrary namespaces. :::info Many ports are already have a default configuration. @@ -354,7 +357,7 @@ Therefore, ## Customizing the Namespace -Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](../middleware/dds_topics.md)) or at runtime (which is useful for multi vehicle operations): +Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](../middleware/dds_topics.md)), at runtime, or through a parameter (which is useful for multi vehicle operations): - One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line. This technique can be used both in simulation and real vehicles. @@ -383,6 +386,22 @@ will generate topics under the namespaces: ::: +- A simple index-based namespace can be applied by setting the parameter [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) to a value between 0 and 9999. + This will generate a namespace such as `/uav_0`, `/uav_1`, and so on. + This technique is ideal if vehicles must be persistently associated with namespaces because their clients are automatically started through PX4. + +:::info +PX4 parameters cannot carry rich text strings. +Therefore, you cannot use [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) to automatically start a client with an arbitrary message namespace through PX4. +You can however specify a namespace when starting the client, using the `-n` argument: + +```sh +# In etc/extras.txt on the MicroSD card +uxrce_dds_client start -n fancy_uav +``` + +This can be included in `etc/extras.txt` as part of a custom [System Startup](../concept/system_startup.md). + ## PX4 ROS 2 QoS Settings PX4 QoS settings for publishers are incompatible with the default QoS settings for ROS 2 subscribers. @@ -516,7 +535,7 @@ For a list of services, details and examples see the [service documentation](../ These guidelines explain how to migrate from using PX4 v1.13 [Fast-RTPS](../middleware/micrortps.md) middleware to PX4 v1.14 `uXRCE-DDS` middleware. These are useful if you have [ROS 2 applications written for PX4 v1.13](https://docs.px4.io/v1.13/en/ros/ros2_comm.html), or you have used Fast-RTPS to interface your applications to PX4 [directly](https://docs.px4.io/v1.13/en/middleware/micrortps.html#agent-in-an-offboard-fast-dds-interface-ros-independent). -:::info +::: info This section contains migration-specific information. You should also read the rest of this page to properly understand uXRCE-DDS. ::: diff --git a/docs/zh/modules/modules_driver_ins.md b/docs/zh/modules/modules_driver_ins.md index d52df4c6a6..6d023b4d31 100644 --- a/docs/zh/modules/modules_driver_ins.md +++ b/docs/zh/modules/modules_driver_ins.md @@ -125,6 +125,31 @@ ilabs [arguments...] status Print driver status ``` +## sbgecom + +Source: [drivers/ins/sbgecom](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/sbgecom) + +Description du module + +### Usage {#sbgecom_usage} + +``` +sbgecom [arguments...] + Commands: + start Start driver + [-d ] Serial device + default: /dev/ttyS0 + [-b ] Baudrate device + default: 921600 + [-f ] Config JSON file path + default: /etc/extras/sbg_settings\.json + [-s ] Config JSON string + + status Driver status + + stop Stop driver +``` + ## vectornav Source: [drivers/ins/vectornav](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/vectornav) diff --git a/docs/zh/modules/modules_system.md b/docs/zh/modules/modules_system.md index 24246827fe..a1b139322d 100644 --- a/docs/zh/modules/modules_system.md +++ b/docs/zh/modules/modules_system.md @@ -140,9 +140,9 @@ commander [arguments...] transition VTOL transition mode Change flight mode - manual|acro|offboard|stabilized|altctl|posctl|position:slow|auto:mission|au - to:loiter|auto:rtl|auto:takeoff|auto:land|auto:precland|ext1 - Flight mode + manual|acro|offboard|stabilized|altctl|posctl|altitude_cruise|position:slow + |auto:mission|auto:loiter|auto:rtl|auto:takeoff|auto:land|auto: + precland|ext1 Flight mode pair @@ -154,6 +154,9 @@ commander [arguments...] lat|lon|alt Origin latitude longitude altitude + set_heading Set current heading + heading degrees from True North [0 360] + poweroff Power off board (if supported) stop @@ -1062,7 +1065,9 @@ uxrce_dds_client [arguments...] values: [-p ] Agent listening port. If not provided, defaults to UXRCE_DDS_PRT - [-n ] Client DDS namespace + [-n ] Client DDS namespace. If not provided but UXRCE_DDS_NS_IDX is + between 0 and 9999 inclusive, then uav_ + UXRCE_DDS_NS_IDX will + be used stop diff --git a/docs/zh/msg_docs/ActuatorMotors.md b/docs/zh/msg_docs/ActuatorMotors.md index ca739f6c22..701465d6ea 100644 --- a/docs/zh/msg_docs/ActuatorMotors.md +++ b/docs/zh/msg_docs/ActuatorMotors.md @@ -18,11 +18,11 @@ uint32 MESSAGE_VERSION = 0 uint64 timestamp # [us] Time since system start uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on -uint16 reversible_flags # Bitset indicating which motors are configured to be reversible +uint16 reversible_flags # [-] Bitset indicating which motors are configured to be reversible uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 # uint8 NUM_CONTROLS = 12 # -float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) +float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) ``` diff --git a/docs/zh/msg_docs/ActuatorServos.md b/docs/zh/msg_docs/ActuatorServos.md index 6f0a677dbf..ea053f67a3 100644 --- a/docs/zh/msg_docs/ActuatorServos.md +++ b/docs/zh/msg_docs/ActuatorServos.md @@ -19,6 +19,6 @@ uint64 timestamp # [us] Time since system start uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on uint8 NUM_CONTROLS = 8 # -float32[8] control # [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. +float32[8] control # [-] [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. ``` diff --git a/docs/zh/msg_docs/ArmingCheckReply.md b/docs/zh/msg_docs/ArmingCheckReply.md index 8d619f5aaf..14af54f0d1 100644 --- a/docs/zh/msg_docs/ArmingCheckReply.md +++ b/docs/zh/msg_docs/ArmingCheckReply.md @@ -1,6 +1,6 @@ # ArmingCheckReply (UORB message) -Arming check reply. +Arming check reply This is a response to an ArmingCheckRequest message sent by the FMU to an external component, such as a ROS 2 navigation mode. The response contains the current set of external mode requirements, and a queue of events indicating recent failures to set the mode (which the FMU may then forward to a ground station). @@ -12,7 +12,7 @@ The message is not used by internal/FMU components, as their mode requirements a [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ArmingCheckReply.msg) ```c -# Arming check reply. +# Arming check reply # # This is a response to an ArmingCheckRequest message sent by the FMU to an external component, such as a ROS 2 navigation mode. # The response contains the current set of external mode requirements, and a queue of events indicating recent failures to set the mode (which the FMU may then forward to a ground station). @@ -25,33 +25,33 @@ uint32 MESSAGE_VERSION = 1 uint64 timestamp # [us] Time since system start. -uint8 request_id # Id of ArmingCheckRequest for which this is a response. -uint8 registration_id # Id of external component emitting this response. +uint8 request_id # [-] Id of ArmingCheckRequest for which this is a response +uint8 registration_id # [-] Id of external component emitting this response -uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies. +uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX] -bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json). +bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json) +bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json) +bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json) -bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed. +bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed -uint8 num_events # Number of queued failure messages (Event) in the events field. +uint8 num_events # Number of queued failure messages (Event) in the events field -Event[5] events # Arming failure reasons (Queue of events to report to GCS). +Event[5] events # Arming failure reasons (Queue of events to report to GCS) # Mode requirements -bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope). -bool mode_req_attitude # Requires an attitude estimate. -bool mode_req_local_alt # Requires a local altitude estimate. -bool mode_req_local_position # Requires a local position estimate. -bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate. -bool mode_req_global_position # Requires a global position estimate. -bool mode_req_global_position_relaxed # Requires a relaxed global position estimate. -bool mode_req_mission # Requires an uploaded mission. -bool mode_req_home_position # Requires a home position (such as RTL/Return mode). -bool mode_req_prevent_arming # Prevent arming (such as in Land mode). +bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope) +bool mode_req_attitude # Requires an attitude estimate +bool mode_req_local_alt # Requires a local altitude estimate +bool mode_req_local_position # Requires a local position estimate +bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate +bool mode_req_global_position # Requires a global position estimate +bool mode_req_global_position_relaxed # Requires a relaxed global position estimate +bool mode_req_mission # Requires an uploaded mission +bool mode_req_home_position # Requires a home position (such as RTL/Return mode) +bool mode_req_prevent_arming # Prevent arming (such as in Land mode) bool mode_req_manual_control # Requires a manual controller uint8 ORB_QUEUE_LENGTH = 4 diff --git a/docs/zh/msg_docs/ArmingCheckRequest.md b/docs/zh/msg_docs/ArmingCheckRequest.md index 653d58d2d2..d093dfb5e1 100644 --- a/docs/zh/msg_docs/ArmingCheckRequest.md +++ b/docs/zh/msg_docs/ArmingCheckRequest.md @@ -1,6 +1,6 @@ # ArmingCheckRequest (UORB message) -Arming check request. +Arming check request Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. @@ -12,7 +12,7 @@ The reply will also include the registration_id for each external component, pro [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ArmingCheckRequest.msg) ```c -# Arming check request. +# Arming check request # # Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. # All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. @@ -23,10 +23,10 @@ The reply will also include the registration_id for each external component, pro uint32 MESSAGE_VERSION = 1 -uint64 timestamp # [us] Time since system start. +uint64 timestamp # [us] Time since system start -uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. +uint8 request_id # [-] Id of this request. Allows correlation with associated ArmingCheckReply messages. -uint32 valid_registrations_mask # Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) +uint32 valid_registrations_mask # [-] Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) ``` diff --git a/docs/zh/msg_docs/BatteryStatus.md b/docs/zh/msg_docs/BatteryStatus.md index 7204a2a12f..addd1ae524 100644 --- a/docs/zh/msg_docs/BatteryStatus.md +++ b/docs/zh/msg_docs/BatteryStatus.md @@ -16,76 +16,77 @@ Battery instance information is also logged and streamed in MAVLink telemetry. # Battery instance information is also logged and streamed in MAVLink telemetry. uint32 MESSAGE_VERSION = 1 -uint8 MAX_INSTANCES = 4 +uint8 MAX_INSTANCES = 3 -uint64 timestamp # [us] Time since system start -bool connected # Whether or not a battery is connected. For power modules this is based on a voltage threshold. -float32 voltage_v # [V] [@invalid 0] Battery voltage -float32 current_a # [A] [@invalid -1] Battery current -float32 current_average_a # [A] [@invalid -1] Battery current average (for FW average in level flight) -float32 discharged_mah # [mAh] [@invalid -1] Discharged amount -float32 remaining # [@range 0,1] [@invalid -1] Remaining capacity -float32 scale # [@range 1,] [@invalid -1] Scaling factor to compensate for lower actuation power caused by voltage sag -float32 time_remaining_s # [s] [@invalid NaN] Predicted time remaining until battery is empty under previous averaged load -float32 temperature # [°C] [@invalid NaN] Temperature of the battery -uint8 cell_count # [@invalid 0] Number of cells +uint64 timestamp # [us] Time since system start + +bool connected # Whether or not a battery is connected. For power modules this is based on a voltage threshold. +float32 voltage_v # [V] [@invalid 0] Battery voltage +float32 current_a # [A] [@invalid -1] Battery current +float32 current_average_a # [A] [@invalid -1] Battery current average (for FW average in level flight) +float32 discharged_mah # [mAh] [@invalid -1] Discharged amount +float32 remaining # [@range 0,1] [@invalid -1] Remaining capacity +float32 scale # [-] [@range 1,] [@invalid -1] Scaling factor to compensate for lower actuation power caused by voltage sag +float32 time_remaining_s # [s] [@invalid NaN] Predicted time remaining until battery is empty under previous averaged load +float32 temperature # [°C] [@invalid NaN] Temperature of the battery +uint8 cell_count # [-] [@invalid 0] Number of cells -uint8 source # [@enum SOURCE] Battery source -uint8 SOURCE_POWER_MODULE = 0 # Power module -uint8 SOURCE_EXTERNAL = 1 # External -uint8 SOURCE_ESCS = 2 # ESCs +uint8 source # [@enum SOURCE] Battery source +uint8 SOURCE_POWER_MODULE = 0 # Power module +uint8 SOURCE_EXTERNAL = 1 # External +uint8 SOURCE_ESCS = 2 # ESCs -uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 -uint16 capacity # [mAh] Capacity of the battery when fully charged -uint16 cycle_count # Number of discharge cycles the battery has experienced -uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge -uint16 manufacture_date # Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 -uint16 state_of_health # [%] [@range 0, 100] State of health. FullChargeCapacity/DesignCapacity -uint16 max_error # [%] [@range 1, 100] Max error, expected margin of error in the state-of-charge calculation -uint8 id # ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed -uint16 interface_error # Interface error counter +uint8 priority # [-] Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 +uint16 capacity # [mAh] Capacity of the battery when fully charged +uint16 cycle_count # [-] Number of discharge cycles the battery has experienced +uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge +uint16 manufacture_date # [-] Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 +uint16 state_of_health # [%] [@range 0, 100] State of health. FullChargeCapacity/DesignCapacity +uint16 max_error # [%] [@range 1, 100] Max error, expected margin of error in the state-of-charge calculation +uint8 id # [-] ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed +uint16 interface_error # [-] Interface error counter -float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages -float32 max_cell_voltage_delta # Max difference between individual cell voltages +float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages +float32 max_cell_voltage_delta # [V] Max difference between individual cell voltages -bool is_powering_off # Power off event imminent indication, false if unknown -bool is_required # Set if the battery is explicitly required before arming +bool is_powering_off # Power off event imminent indication, false if unknown +bool is_required # Set if the battery is explicitly required before arming -uint8 warning # [@enum WARNING STATE] Current battery warning -uint8 WARNING_NONE = 0 # No battery low voltage warning active -uint8 WARNING_LOW = 1 # Low voltage warning -uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately -uint8 WARNING_EMERGENCY = 3 # Immediate landing required -uint8 WARNING_FAILED = 4 # Battery has failed completely -uint8 STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field -uint8 STATE_CHARGING = 7 # Battery is charging +uint8 warning # [@enum WARNING STATE] Current battery warning +uint8 WARNING_NONE = 0 # No battery low voltage warning active +uint8 WARNING_LOW = 1 # Low voltage warning +uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately +uint8 WARNING_EMERGENCY = 3 # Immediate landing required +uint8 WARNING_FAILED = 4 # Battery has failed completely +uint8 STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field +uint8 STATE_CHARGING = 7 # Battery is charging -uint16 faults # [@enum FAULT] Smart battery supply status/fault flags (bitmask) for health indication -uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged -uint8 FAULT_SPIKES = 1 # Voltage spikes -uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed -uint8 FAULT_OVER_CURRENT = 3 # Over-current -uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature -uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault -uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage) -uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware -uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system -uint8 FAULT_HARDWARE_FAILURE = 9 # Hardware problem -uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming -uint8 FAULT_COUNT = 11 # Counter. Keep this as last element +uint16 faults # [@enum FAULT] Smart battery supply status/fault flags (bitmask) for health indication +uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged +uint8 FAULT_SPIKES = 1 # Voltage spikes +uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed +uint8 FAULT_OVER_CURRENT = 3 # Over-current +uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature +uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault +uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage) +uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware +uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system +uint8 FAULT_HARDWARE_FAILURE = 9 # Hardware problem +uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming +uint8 FAULT_COUNT = 11 # Counter. Keep this as last element -float32 full_charge_capacity_wh # [Wh] Compensated battery capacity -float32 remaining_capacity_wh # [Wh] Compensated battery capacity remaining -uint16 over_discharge_count # Number of battery overdischarge -float32 nominal_voltage # [V] Nominal voltage of the battery pack +float32 full_charge_capacity_wh # [Wh] Compensated battery capacity +float32 remaining_capacity_wh # [Wh] Compensated battery capacity remaining +uint16 over_discharge_count # [-] Number of battery overdischarge +float32 nominal_voltage # [V] Nominal voltage of the battery pack -float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate -float32 ocv_estimate # [V] Open circuit voltage estimate -float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate -float32 volt_based_soc_estimate # [@range 0, 1] Normalized volt based state of charge estimate -float32 voltage_prediction # [V] Predicted voltage -float32 prediction_error # [V] Prediction error -float32 estimation_covariance_norm # Norm of the covariance matrix +float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate +float32 ocv_estimate # [V] Open circuit voltage estimate +float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate +float32 volt_based_soc_estimate # [-] [@range 0, 1] Normalized volt based state of charge estimate +float32 voltage_prediction # [V] Predicted voltage +float32 prediction_error # [V] Prediction error +float32 estimation_covariance_norm # [-] Norm of the covariance matrix ``` diff --git a/docs/zh/msg_docs/EstimatorStatus.md b/docs/zh/msg_docs/EstimatorStatus.md index e36871df1a..9c24221691 100644 --- a/docs/zh/msg_docs/EstimatorStatus.md +++ b/docs/zh/msg_docs/EstimatorStatus.md @@ -52,7 +52,9 @@ uint8 CS_SYNTHETIC_MAG_Z = 25 # 25 - true when we are using a synthesized measur uint8 CS_VEHICLE_AT_REST = 26 # 26 - true when the vehicle is at rest uint8 CS_GPS_YAW_FAULT = 27 # 27 - true when the GNSS heading has been declared faulty and is no longer being used uint8 CS_RNG_FAULT = 28 # 28 - true when the range finder has been declared faulty and is no longer being used -uint8 CS_GNSS_VEL = 44 # 44 - true if GNSS velocity measurements are being fused +uint8 CS_GNSS_VEL = 44 # 44 - true if GNSS velocity measurement fusion is intended +uint8 CS_GNSS_FAULT = 45 # 45 - true if GNSS measurements have been declared faulty and are no longer used +uint8 CS_YAW_MANUAL = 46 # 46 - true if yaw has been set manually uint32 filter_fault_flags # Bitmask to indicate EKF internal faults # 0 - true if the fusion of the magnetometer X-axis has encountered a numerical error diff --git a/docs/zh/msg_docs/EstimatorStatusFlags.md b/docs/zh/msg_docs/EstimatorStatusFlags.md index e3e33c6a39..0ac832817d 100644 --- a/docs/zh/msg_docs/EstimatorStatusFlags.md +++ b/docs/zh/msg_docs/EstimatorStatusFlags.md @@ -54,7 +54,8 @@ bool cs_valid_fake_pos # 41 - true if a valid constant position is bein bool cs_constant_pos # 42 - true if the vehicle is at a constant position bool cs_baro_fault # 43 - true when the current baro has been declared faulty and is no longer being used bool cs_gnss_vel # 44 - true if GNSS velocity measurement fusion is intended -bool cs_yaw_manual # 45 - true if yaw has been set manually +bool cs_gnss_fault # 45 - true if GNSS measurements have been declared faulty and are no longer used +bool cs_yaw_manual # 46 - true if yaw has been set manually # fault status uint32 fault_status_changes # number of filter fault status (fs) changes diff --git a/docs/zh/msg_docs/PurePursuitStatus.md b/docs/zh/msg_docs/PurePursuitStatus.md index 96577a0220..8d54ba473e 100644 --- a/docs/zh/msg_docs/PurePursuitStatus.md +++ b/docs/zh/msg_docs/PurePursuitStatus.md @@ -7,11 +7,11 @@ Pure pursuit status ```c # Pure pursuit status -uint64 timestamp # [us] Time since system start -float32 lookahead_distance # [m] [@range 0, inf] Lookahead distance of pure the pursuit controller -float32 target_bearing # [rad] [@range -pi, pi] [@frame NED] Target bearing calculated by the pure pursuit controller -float32 crosstrack_error # [m] [@range -inf (Left of the path), inf (Right of the path)] Shortest distance from the vehicle to the path -float32 distance_to_waypoint # [m] [@range -inf, inf]Distance from the vehicle to the current waypoint -float32 bearing_to_waypoint # [rad] [@range -pi, pi] [@frame NED]Bearing towards current waypoint +uint64 timestamp # [us] Time since system start +float32 lookahead_distance # [m] [@range 0, inf] Lookahead distance of pure the pursuit controller +float32 target_bearing # [rad] [@range -pi, pi] [@frame NED] Target bearing calculated by the pure pursuit controller +float32 crosstrack_error # [m] [@range -inf (Left of the path), inf (Right of the path)] Shortest distance from the vehicle to the path +float32 distance_to_waypoint # [m] [@range -inf, inf]Distance from the vehicle to the current waypoint +float32 bearing_to_waypoint # [rad] [@range -pi, pi] [@frame NED]Bearing towards current waypoint ``` diff --git a/docs/zh/msg_docs/RoverAttitudeSetpoint.md b/docs/zh/msg_docs/RoverAttitudeSetpoint.md index bd436278ca..ca75a6e3e2 100644 --- a/docs/zh/msg_docs/RoverAttitudeSetpoint.md +++ b/docs/zh/msg_docs/RoverAttitudeSetpoint.md @@ -7,7 +7,7 @@ Rover Attitude Setpoint ```c # Rover Attitude Setpoint -uint64 timestamp # [us] Time since system start -float32 yaw_setpoint # [rad] [@range -inf, inf] [@frame NED] Yaw setpoint +uint64 timestamp # [us] Time since system start +float32 yaw_setpoint # [rad] [@range -inf, inf] [@frame NED] Yaw setpoint ``` diff --git a/docs/zh/msg_docs/RoverAttitudeStatus.md b/docs/zh/msg_docs/RoverAttitudeStatus.md index e6df929abd..f5a9ce1f02 100644 --- a/docs/zh/msg_docs/RoverAttitudeStatus.md +++ b/docs/zh/msg_docs/RoverAttitudeStatus.md @@ -7,8 +7,8 @@ Rover Attitude Status ```c # Rover Attitude Status -uint64 timestamp # [us] Time since system start -float32 measured_yaw # [rad] [@range -pi, pi] [@frame NED]Measured yaw -float32 adjusted_yaw_setpoint # [rad] [@range -pi, pi] [@frame NED] Yaw setpoint that is being tracked (Applied slew rates) +uint64 timestamp # [us] Time since system start +float32 measured_yaw # [rad] [@range -pi, pi] [@frame NED]Measured yaw +float32 adjusted_yaw_setpoint # [rad] [@range -pi, pi] [@frame NED] Yaw setpoint that is being tracked (Applied slew rates) ``` diff --git a/docs/zh/msg_docs/RoverPositionSetpoint.md b/docs/zh/msg_docs/RoverPositionSetpoint.md index b45aa0515f..751536e7f9 100644 --- a/docs/zh/msg_docs/RoverPositionSetpoint.md +++ b/docs/zh/msg_docs/RoverPositionSetpoint.md @@ -7,11 +7,11 @@ Rover Position Setpoint ```c # Rover Position Setpoint -uint64 timestamp # [us] Time since system start -float32[2] position_ned # [m] [@range -inf, inf] [@frame NED] Target position -float32[2] start_ned # [m] [@range -inf, inf] [@frame NED] [@invalid NaN Defaults to vehicle position] Start position which specifies a line for the rover to track -float32 cruising_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to maximum speed] Cruising speed -float32 arrival_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to 0] Speed the rover should arrive at the target with -float32 yaw # [rad] [@range -pi,pi] [@frame NED] [@invalid NaN Defaults to vehicle yaw] Mecanum only: Specify vehicle yaw during travel +uint64 timestamp # [us] Time since system start +float32[2] position_ned # [m] [@range -inf, inf] [@frame NED] Target position +float32[2] start_ned # [m] [@range -inf, inf] [@frame NED] [@invalid NaN Defaults to vehicle position] Start position which specifies a line for the rover to track +float32 cruising_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to maximum speed] Cruising speed +float32 arrival_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to 0] Speed the rover should arrive at the target with +float32 yaw # [rad] [@range -pi,pi] [@frame NED] [@invalid NaN Defaults to vehicle yaw] Mecanum only: Specify vehicle yaw during travel ``` diff --git a/docs/zh/msg_docs/RoverRateSetpoint.md b/docs/zh/msg_docs/RoverRateSetpoint.md index 9bffa41b80..9bb844e802 100644 --- a/docs/zh/msg_docs/RoverRateSetpoint.md +++ b/docs/zh/msg_docs/RoverRateSetpoint.md @@ -7,7 +7,7 @@ Rover Rate setpoint ```c # Rover Rate setpoint -uint64 timestamp # [us] Time since system start -float32 yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint +uint64 timestamp # [us] Time since system start +float32 yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint ``` diff --git a/docs/zh/msg_docs/RoverRateStatus.md b/docs/zh/msg_docs/RoverRateStatus.md index 684e4c458a..70345fe315 100644 --- a/docs/zh/msg_docs/RoverRateStatus.md +++ b/docs/zh/msg_docs/RoverRateStatus.md @@ -7,9 +7,9 @@ Rover Rate Status ```c # Rover Rate Status -uint64 timestamp # [us] Time since system start -float32 measured_yaw_rate # [rad/s] [@range -inf, inf] [@frame NED] Measured yaw rate -float32 adjusted_yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint that is being tracked (Applied slew rates) -float32 pid_yaw_rate_integral # [] [@range -1, 1] Integral of the PID for the closed loop yaw rate controller +uint64 timestamp # [us] Time since system start +float32 measured_yaw_rate # [rad/s] [@range -inf, inf] [@frame NED] Measured yaw rate +float32 adjusted_yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint that is being tracked (Applied slew rates) +float32 pid_yaw_rate_integral # [-] [@range -1, 1] Integral of the PID for the closed loop yaw rate controller ``` diff --git a/docs/zh/msg_docs/RoverSpeedSetpoint.md b/docs/zh/msg_docs/RoverSpeedSetpoint.md index 9eea46e60f..84176cd1c3 100644 --- a/docs/zh/msg_docs/RoverSpeedSetpoint.md +++ b/docs/zh/msg_docs/RoverSpeedSetpoint.md @@ -7,8 +7,8 @@ Rover Speed Setpoint ```c # Rover Speed Setpoint -uint64 timestamp # [us] Time since system start -float32 speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction -float32 speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction +uint64 timestamp # [us] Time since system start +float32 speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction +float32 speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction ``` diff --git a/docs/zh/msg_docs/RoverSpeedStatus.md b/docs/zh/msg_docs/RoverSpeedStatus.md index 8c212e2b0f..4213e1e5df 100644 --- a/docs/zh/msg_docs/RoverSpeedStatus.md +++ b/docs/zh/msg_docs/RoverSpeedStatus.md @@ -7,12 +7,12 @@ Rover Velocity Status ```c # Rover Velocity Status -uint64 timestamp # [us] Time since system start -float32 measured_speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Measured speed in body x direction -float32 adjusted_speed_body_x_setpoint # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction that is being tracked (Applied slew rates) -float32 pid_throttle_body_x_integral # [] [@range -1, 1] Integral of the PID for the closed loop controller of the speed in body x direction -float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction -float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates) -float32 pid_throttle_body_y_integral # [] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction +uint64 timestamp # [us] Time since system start +float32 measured_speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Measured speed in body x direction +float32 adjusted_speed_body_x_setpoint # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction that is being tracked (Applied slew rates) +float32 pid_throttle_body_x_integral # [-] [@range -1, 1] Integral of the PID for the closed loop controller of the speed in body x direction +float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction +float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates) +float32 pid_throttle_body_y_integral # [-] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction ``` diff --git a/docs/zh/msg_docs/RoverSteeringSetpoint.md b/docs/zh/msg_docs/RoverSteeringSetpoint.md index 3e40a3986b..974f3fc4c9 100644 --- a/docs/zh/msg_docs/RoverSteeringSetpoint.md +++ b/docs/zh/msg_docs/RoverSteeringSetpoint.md @@ -7,7 +7,7 @@ Rover Steering setpoint ```c # Rover Steering setpoint -uint64 timestamp # [us] Time since system start -float32 normalized_steering_setpoint # [@range -1 (Left), 1 (Right)] [@frame Body] Ackermann: Normalized steering angle, Differential/Mecanum: Normalized speed difference between the left and right wheels +uint64 timestamp # [us] Time since system start +float32 normalized_steering_setpoint # [-] [@range -1 (Left), 1 (Right)] [@frame Body] Ackermann: Normalized steering angle, Differential/Mecanum: Normalized speed difference between the left and right wheels ``` diff --git a/docs/zh/msg_docs/RoverThrottleSetpoint.md b/docs/zh/msg_docs/RoverThrottleSetpoint.md index f1c4f7f653..bd5ee93d55 100644 --- a/docs/zh/msg_docs/RoverThrottleSetpoint.md +++ b/docs/zh/msg_docs/RoverThrottleSetpoint.md @@ -7,8 +7,8 @@ Rover Throttle setpoint ```c # Rover Throttle setpoint -uint64 timestamp # [us] Time since system start -float32 throttle_body_x # [] [@range -1 (Backwards), 1 (Forwards)] [@frame Body] Throttle setpoint along body X axis -float32 throttle_body_y # [] [@range -1 (Left), 1 (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Throttle setpoint along body Y axis +uint64 timestamp # [us] Time since system start +float32 throttle_body_x # [-] [@range -1 (Backwards), 1 (Forwards)] [@frame Body] Throttle setpoint along body X axis +float32 throttle_body_y # [-] [@range -1 (Left), 1 (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Throttle setpoint along body Y axis ``` diff --git a/docs/zh/msg_docs/VehicleCommand.md b/docs/zh/msg_docs/VehicleCommand.md index 19557cf496..6c5e87ff5b 100644 --- a/docs/zh/msg_docs/VehicleCommand.md +++ b/docs/zh/msg_docs/VehicleCommand.md @@ -96,6 +96,7 @@ uint16 VEHICLE_CMD_REQUEST_CAMERA_INFORMATION = 521 # Request camera information uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.). uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom. uint16 VEHICLE_CMD_SET_CAMERA_FOCUS = 532 +uint16 VEHICLE_CMD_EXTERNAL_ATTITUDE_ESTIMATE = 620 # Set an external estimate of vehicle attitude in degrees. uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw. uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control. uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence. diff --git a/docs/zh/msg_docs/VehicleStatus.md b/docs/zh/msg_docs/VehicleStatus.md index d1deeb0500..9d46e42cb3 100644 --- a/docs/zh/msg_docs/VehicleStatus.md +++ b/docs/zh/msg_docs/VehicleStatus.md @@ -48,7 +48,7 @@ uint8 NAVIGATION_STATE_AUTO_LOITER = 4 # Auto loiter mode uint8 NAVIGATION_STATE_AUTO_RTL = 5 # Auto return to launch mode uint8 NAVIGATION_STATE_POSITION_SLOW = 6 uint8 NAVIGATION_STATE_FREE5 = 7 -uint8 NAVIGATION_STATE_FREE4 = 8 +uint8 NAVIGATION_STATE_ALTITUDE_CRUISE = 8 # Altitude with Cruise mode uint8 NAVIGATION_STATE_FREE3 = 9 uint8 NAVIGATION_STATE_ACRO = 10 # Acro mode uint8 NAVIGATION_STATE_FREE2 = 11 diff --git a/docs/zh/msg_docs/index.md b/docs/zh/msg_docs/index.md index 9e80e1af98..7b76ddabbf 100644 --- a/docs/zh/msg_docs/index.md +++ b/docs/zh/msg_docs/index.md @@ -16,8 +16,8 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [ActuatorMotors](ActuatorMotors.md) — Motor control message - [ActuatorServos](ActuatorServos.md) — Servo control message - [AirspeedValidated](AirspeedValidated.md) -- [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply. -- [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request. +- [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply +- [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request - [BatteryStatus](BatteryStatus.md) — Battery status - [ConfigOverrides](ConfigOverrides.md) — Configurable overrides by (external) modes or mode executors - [Event](Event.md) — Events interface diff --git a/docs/zh/releases/main.md b/docs/zh/releases/main.md index ce9b6b6e95..6166e251c5 100644 --- a/docs/zh/releases/main.md +++ b/docs/zh/releases/main.md @@ -44,7 +44,9 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Control -- TBD +- Added new flight mode(s): [Altitude Cruise (MC)](../flight_modes_mc/altitude_cruise.md), Altitude Cruise (FW). + For fixed-wing the mode behaves the same as Altitude mode but you can disable the manual control loss failsafe. (PX4-Autopilot#25435: Add new flight mode: Altitude Cruise + ). ### Estimation @@ -72,7 +74,8 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Multi-Rotor -- TBD +- Removed parameters `MPC_{XY/Z/YAW}_MAN_EXPO` and use default value instead, as they were not deemed necessary anymore. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)). +- Renamed `MPC_HOLD_DZ` to `MAN_DEADZONE` to have it globally available in modes that allow for a dead zone. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)). ### 垂直起降 diff --git a/docs/zh/ros2/index.md b/docs/zh/ros2/index.md index bf9ad53aa0..435dd9cfa0 100644 --- a/docs/zh/ros2/index.md +++ b/docs/zh/ros2/index.md @@ -7,13 +7,13 @@ ROS 2 是ROS (机器人操作系统)最新版本 , 一个通用的机器人库 PX4开发团队强烈建议您使用/迁移到此版本的 ROS! 这是最新版本的 [ROS](https://www.ros.org/) (机器人操作系统)。 -它大大改进了外空军备竞赛“1”,尤其是允许与PX4更深、更低的延迟结合。 +它大大改进了ROS1,特别是允许与PX4更深、更低的延迟结合。 ::: -ROS得益于一个活跃的生态系统,在这个生态系统里,开发者会解决常见的机器人问题,他们也有权使用为Linux编写的其他软件库。 -例如,它可以用于[计算机视图](../computer_vision/index.md)解决方案。 +ROS得益于一个活跃的生态系统,在这个生态系统里,开发者会解决常见的机器人问题,他们也为Linux编写软件库。 +例如,它可以用于[计算机视觉](../computer_vision/index.md)解决方案。 -ROS 2能够非常深入地与 PX4 集成 只要你可以在交战规则2中创建无法与内部的 PX4 模式区分的飞行模式, 并以高费率直接读取内部uORB主题。 +ROS 2深度与 PX4 集成, 在某种程度上,您能够在 ROS 2 中创建与内部 PX4 模式无法区分的飞行模式, 并高效率的直接订阅uORB内部的话题。 建议(尤其是)从同伴计算机进行控制和通信,因为这种计算机的延迟率很低。 当利用来自Linux的现有库时,或在编写新的高层飞行模式时。 ROS 2 和 PX4 之间的通信使用中间件实现[XRCE-DDS] (../middleware/uxrce_dds.md)。 diff --git a/docs/zh/ros2/multi_vehicle.md b/docs/zh/ros2/multi_vehicle.md index ab366b4a5a..a525a32445 100644 --- a/docs/zh/ros2/multi_vehicle.md +++ b/docs/zh/ros2/multi_vehicle.md @@ -1,4 +1,4 @@ -# 使用 ROS 2 进行多车辆仿真 +# 使用 ROS 2 进行多车辆模拟 [XRCE-DDS](../middleware/uxrce_dds.md) 支持多个客户端通过 UDP 协议连接到同一个代理。 这在模拟中特别有用,因为只有一个代理需要启动。 @@ -8,7 +8,7 @@ 唯一的要求是 - 能够在不依赖 ROS 2 的情况下,使用所需的仿真器([Gazebo](../sim_gazebo_gz/multi_vehicle_simulation.md), [Gazebo Classic](../sim_gazebo_classic/multi_vehicle_simulation.md#multiple-vehicle-with-gazebo-classic), [FlightGear](../sim_flightgear/multi_vehicle.md) 和 [JMAVSim](../sim_jmavsim/multi_vehicle.md))运行多车辆仿真[multi-vehicle simulation](../simulation/multi-vehicle-simulation.md)。 -- 能够在单车辆仿真中使用ROS 2(机器人操作系统 2) +- 能够在单一车辆仿真中使用ROS 2(机器人操作系统 2) ## 工作原理 @@ -51,4 +51,4 @@ PX4 只在他们的 `target_system` 字段为 0 (路由通信) 或与 `MAV_SYS_I 在所有其他情况下,信息都被忽视。 因此,当 ROS 2 节点需向 PX4 发送 VehicleCommand(载具指令)消息时,必须确保消息中填写了合适的 target_system(目标系统)字段值。 -For example, if you want to send a command to your third vehicle, which has `px4_instance=2`, you need to set `target_system=3` in all your `VehicleCommand` messages. +例如,若你想向 px4_instance=2 的第三台飞行器发送指令,则需要在所有 VehicleCommand消息中设置 target_system=3。 diff --git a/docs/zh/ros2/offboard_control.md b/docs/zh/ros2/offboard_control.md index 12c4217bf7..910eccde12 100644 --- a/docs/zh/ros2/offboard_control.md +++ b/docs/zh/ros2/offboard_control.md @@ -5,7 +5,7 @@ 示例将首先发送设置点、进入offboard模式、解锁、起飞至5米,并悬停等待。 虽然简单,但它显示了如何使用offboard控制以及如何向无人机发送指令。 -It has been tested on Ubuntu 20.04 with ROS 2 Foxy and PX4 v1.14. +该内容已在搭载 ROS 2 Foxy 与 PX4 v1.14 的 Ubuntu 20.04 系统上完成测试。 :::warning _Offboard_ control is dangerous. @@ -13,22 +13,22 @@ _Offboard_ control is dangerous. ::: :::info -ROS and PX4 make a number of different assumptions, in particular with respect to [frame conventions](../ros/external_position_estimation.md#reference-frames-and-ros). +ROS 与 PX4 存在若干不同的预设(假设),尤其是在坐标系约定([frame conventions])方面../ros/external_position_estimation.md#reference-frames-and-ros 当主题发布或订阅时,坐标系类型之间没有隐含转换! -这个例子按照PX4的定义在NED坐标系下发布位置。 -To subscribe to data coming from nodes that publish in a different frame (for example the ENU, which is the standard frame of reference in ROS/ROS 2), use the helper functions in the [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/src/lib/frame_transforms.cpp) library. +这个例子按照PX4的预期在NED坐标系下发布位置。 +若要订阅来自在不同框架内发布的节点的数据(例如ENU, 这是ROS/ROS 2中的标准参考框架,使用 [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/src/lib/frame_transforms.cpp)库中的辅助函数。 ::: -## 尝试一下 +## 小試身手 -Follow the instructions in [ROS 2 User Guide](../ros2/user_guide.md) to install PX and run the simulator, install ROS 2, and start the XRCE-DDS Agent. +请遵循 ROS 2 用户指南 (../ros2/user_guide.md)中的说明,完成安装 PX4和运行模拟器,安装 ROS 2和启动 XRCE-DDS 代理(Agent)。 -After that we can follow a similar set of steps to those in [ROS 2 User Guide > Build ROS 2 Workspace](../ros2/user_guide.md#build-ros-2-workspace) to run the example. +之后,我们可参照 ROS 2 用户指南 > 构建 ROS 2 工作空间 (../ros2/user_guide.md#build-ros-2-workspace)中的相似的步骤来运行这个例子。 :::tip -Make sure that QGC is connected to PX4 before running the ROS 2 node. -This is needed because, by default, you cannot arm a vehicle without a connection to ground station (QGC) or an established RC connection (this ensures there is always the option to regain manual control). +运行 ROS 2 节点前,请确保 QGC已连接到 PX4。 +之所以需要这样做,是因为默认情况下,若未连接地面控制站(QGC)或已建立的RC连接,飞行器无法解锁(这一机制可确保始终存在重新获得手动控制权的途径)。 ::: 构建并运行示例: @@ -42,14 +42,14 @@ This is needed because, by default, you cannot arm a vehicle without a connectio cd ~/ws_offboard_control/src/ ``` -3. Clone the [px4_msgs](https://github.com/PX4/px4_msgs) repo to the `/src` directory (this repo is needed in every ROS 2 PX4 workspace!): +3. 将 px4_msgs 代码仓库克隆到 /src 目录下(每个 ROS 2 PX4 工作空间都需要该仓库!): ```sh git clone https://github.com/PX4/px4_msgs.git - # checkout the matching release branch if not using PX4 main. + #若未使用 PX4 的 main 分支,请切换到对应的发布分支 ``` -4. Clone the example repository [px4_ros_com](https://github.com/PX4/px4_ros_com) to the `/src` directory: +4. 将示例代码仓库 px4_ros_com (https://github.com/PX4/px4_ros_com)克隆到 /src 目录下: ```sh git clone https://github.com/PX4/px4_ros_com.git @@ -83,7 +83,7 @@ This is needed because, by default, you cannot arm a vehicle without a connectio :::: -6. Source the `local_setup.bash`: +6. 来源 `local_setup.bash`: ```sh source install/local_setup.bash @@ -99,81 +99,81 @@ This is needed because, by default, you cannot arm a vehicle without a connectio ## 实现 -The source code of the offboard control example can be found in [PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) in the directory [/src/examples/offboard/offboard_control.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/offboard/offboard_control.cpp). +离板控制示例的源代码可以在[ PX4/px4_ros_com ]目录里 [/src/examples/offboard/offboard_control.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/offboard/offboard_control.cpp)中找到 [X4/px4_ros_com](https://github.com/PX4/px4_ros_com)。 :::info -PX4 publishes all the messages used in this example as ROS topics by default (see [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)). +PX4 默认情况下将此示例中使用的所有消息以ROS为话题发布(详见 [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml))。 ::: -PX4 requires that the vehicle is already receiving `OffboardControlMode` messages before it will arm in offboard mode, or before it will switch to offboard mode when flying. -In addition, PX4 will switch out of offboard mode if the stream rate of `OffboardControlMode` messages drops below approximately 2Hz. +PX4 要求,飞行器需先持续接收 OffboardControlMode(离板控制模式)消息,之后才能在离板模式下解锁(arm),或在飞行过程中切换至离板模式。 +此外,若 OffboardControlMode(离板控制模式)消息的数据流速率降至约 2Hz 以下,PX4 将会退出离板模式。 该行为在ROS 2 节点的主循环中实现的,如下所示: ```cpp -auto timer_callback = [this]() -> void { +auto timer_callback = [this]() -> void { - if (offboard_setpoint_counter_ == 10) { - // Change to Offboard mode after 10 setpoints - this->publish_vehicle_command(VehicleCommand::VEHICLE_CMD_DO_SET_MODE, 1, 6); + if (offboard_setpoint_counter_ == 10) { + // Change to Offboard mode after 10 setpoints + this->publish_vehicle_command(VehicleCommand::VEHICLE_CMD_DO_SET_MODE, 1, 6); - // Arm the vehicle - this->arm(); - } + // Arm the vehicle + this->arm(); + } - // OffboardControlMode needs to be paired with TrajectorySetpoint - publish_offboard_control_mode(); - publish_trajectory_setpoint(); + // OffboardControlMode needs to be paired with TrajectorySetpoint + publish_offboard_control_mode(); + publish_trajectory_setpoint(); - // stop the counter after reaching 11 - if (offboard_setpoint_counter_ < 11) { - offboard_setpoint_counter_++; - } + // stop the counter after reaching 11 + if (offboard_setpoint_counter_ < 11) { + offboard_setpoint_counter_++; + } }; -timer_ = this->create_wall_timer(100ms, timer_callback); +timer_ = this->create_wall_timer(100ms, timer_callback); ``` 循环运行在一个100毫秒计时器。 -For the first 10 cycles it calls `publish_offboard_control_mode()` and `publish_trajectory_setpoint()` to send [OffboardControlMode](../msg_docs/OffboardControlMode.md) and [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) messages to PX4. -The `OffboardControlMode` messages are streamed so that PX4 will allow arming once it switches to offboard mode, while the `TrajectorySetpoint` messages are ignored (until the vehicle is in offboard mode). +在最初的 10 个循环中,它会调用 publish_offboard_control_mode() 和 publish_trajectory_setpoint() 这两个函数,向 PX4 发送 OffboardControlMode(离板控制模式)(../msg_docs/OffboardControlMode.md) 和 TrajectorySetpoint(轨迹设定点)(../msg_docs/TrajectorySetpoint.md) 消息。 +OffboardControlMode消息会持续发送,以便 PX4 切换到离板模式后允许解锁;而 TrajectorySetpoint消息会被忽略(直到载具处于离板模式) -After 10 cycles `publish_vehicle_command()` is called to change to offboard mode, and `arm()` is called to arm the vehicle. -在飞行器解锁并和切换模式后,它将开始跟踪位置设定值。 -在每个周期内仍然发送设定值,确保飞行器不会切换出offboard模式。 +10 个循环后,会调用 publish_vehicle_command() 函数切换至离板模式,并调用 arm() 函数对载具进行解锁。 +在载具解锁并和切换模式后,它将开始跟踪位置设定值。 +在每个周期内仍然发送设定值,确保载具不会切换出offboard模式。 -The implementations of the `publish_offboard_control_mode()` and `publish_trajectory_setpoint()` methods are shown below. -These publish the [OffboardControlMode](../msg_docs/OffboardControlMode.md) and [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) messages to PX4 (respectively). +publish_offboard_control_mode() 和 publish_trajectory_setpoint() 这两个方法的实现代码如下所示。 +这些方法会分别发布到 PX4 的 [OffboardControlMode](../msg_docs/OffboardControlMode.md和 [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) 消息。 -The `OffboardControlMode` is required in order to inform PX4 of the _type_ of offboard control behing used. -Here we're only using _position control_, so the `position` field is set to `true` and all the other fields are set to `false`. +OffboardControlMode(离板控制模式)消息是必需的,其作用是告知 PX4 当前所使用的离板控制类型。 +此处我们仅使用位置控制,因此将 `position` 字段设为`true`,而所有其他字段均设为 `false`。 ```cpp /** - * @brief Publish the offboard control mode. - * For this example, only position and altitude controls are active. + * @short 发布离板控制模式。 + *在本示例中,仅位置控制和高度控制处于激活状态 */ -void OffboardControl::publish_offboard_control_mode() -{ - OffboardControlMode msg{}; - msg.position = true; - msg.velocity = false; - msg.acceleration = false; +无效的离板控制::publish_offboard_control_mode() +Power + OffboardControlModel msg{}; + msg.position = true; + msg.veocity = false; + msg. cceleration = false; msg.attitude = false; msg.body_rate = false; - msg.thrust_and_torque = false; - msg.direct_actuator = false; - msg.timestamp = this->get_clock()->now().nanoseconds() / 1000; + msg.subust_and_torque = false; + msg. irect_actuator = false; + msg.timestamp = this->get_clock()->now ().nanoseconds() / 1000; offboard_control_mode_publisher_->publish(msg); } ``` -`TrajectorySetpoint` provides the position setpoint. -In this case, the `x`, `y`, `z` and `yaw` fields are hardcoded to certain values, but they can be updated dynamically according to an algorithm or even by a subscription callback for messages coming from another node. +`TrattorySettpoint` 提供了位置设定点。 +在这种情况下,`x`、`y`、`z`和`yaw`字段的值是硬编码为特定数值的。 但它们可以根据算法动态更新,甚至可以通过订阅回调函数来从另一个节点进行更新。 ```cpp /** - * @brief Publish a trajectory setpoint - * For this example, it sends a trajectory setpoint to make the - * vehicle hover at 5 meters with a yaw angle of 180 degrees. + *@brief 发布轨迹设定点 + + 在本示例中,该函数会发送一个轨迹设定点,使载具在 5 米高度悬停,并保持 180 度的偏航角。 */ void OffboardControl::publish_trajectory_setpoint() { @@ -185,9 +185,9 @@ void OffboardControl::publish_trajectory_setpoint() } ``` -The `publish_vehicle_command()` sends [VehicleCommand](../msg_docs/VehicleCommand.md) messages with commands to the flight controller. -We use it above to change the mode to offboard mode, and also in `arm()` to arm the vehicle. -While we don't call `disarm()` in this example, it is also used in the implementation of that function. +`publish_vehicle_command()` 将带有命令的 [VehicleCommand](../msg_docs/VehicleCommand.md)消息发送给载具。 +我们使用上面的方法将模式切换为 offboard 模式,同时也在 arm() 函数中用它来对载具进行解锁。 +我们在此示例中不调用 `disarm()` ,但它也用于执行此功能。 ```cpp /** @@ -198,23 +198,23 @@ While we don't call `disarm()` in this example, it is also used in the implement */ void OffboardControl::publish_vehicle_command(uint16_t command, float param1, float param2) { - VehicleCommand msg{}; - msg.param1 = param1; - msg.param2 = param2; - msg.command = command; - msg.target_system = 1; - msg.target_component = 1; - msg.source_system = 1; - msg.source_component = 1; - msg.from_external = true; - msg.timestamp = this->get_clock()->now().nanoseconds() / 1000; - vehicle_command_publisher_->publish(msg); + VehicleCommand msg{}; + msg.param1 = param1; + msg.param2 = param2; + msg.command = command; + msg.target_system = 1; + msg.target_component = 1; + msg.source_system = 1; + msg.source_component = 1; + msg.from_external = true; + msg.timestamp = this->get_clock()->now().nanoseconds() / 1000; + vehicle_command_publisher_->publish(msg); } ``` :::info -[VehicleCommand](../msg_docs/VehicleCommand.md) is one of the simplest and most powerful ways to command PX4, and by subscribing to [VehicleCommandAck](../msg_docs/VehicleCommandAck.md) you can also confirm that setting a particular command was successful. -The param and command fields map to [MAVLink commands](https://mavlink.io/en/messages/common.html#mav_commands) and their parameter values. +[VehicleCommand](../msg_docs/VehicleCommand.md是命令PX4的最简单和最高效的方式之一。 通过订阅 [VehicleCommandAck](../msg_docs/VehicleCommandAck.md),您也可以确认设置特定命令是否成功。 +参数字段和 指令字段对应于 [MAVLink commands](https://mavlink.io/en/messages/common.html#mav_commands)以及他们的参数值 ::: ## See Also diff --git a/docs/zh/ros2/px4_ros2_control_interface.md b/docs/zh/ros2/px4_ros2_control_interface.md index cc1e139124..7aea8b7b58 100644 --- a/docs/zh/ros2/px4_ros2_control_interface.md +++ b/docs/zh/ros2/px4_ros2_control_interface.md @@ -1,108 +1,108 @@ -# PX4 ROS 2 Control Interface +# PX4 ROS 2 控制接口 <0/> <1/> :::warning Experimental -At the time of writing, parts of the PX4 ROS 2 Control Interface are experimental, and hence subject to change: +在撰写本文时,PX4 ROS 2 控制接口的部分内容仍处于实验阶段,因此可能会发生变动: -- The architecture and core interfaces for defining modes in ROS 2 modes are largely stable, and are tested in CI. - The library offers significant benefits over using offboard mode in its current state. -- Only a few setpoint types have settled (the others are still under development). - You may need to use internal PX4 topics which may not remain backwards-compatible over time. -- The API is not fully documented. +- ROS 2 模式中用于定义模式的架构及核心接口在很大程度上已趋于稳定,且会在CI中进行测试 + 相比当前状态下的离板模式,该代码库具有显著优势 +- 仅有少数几种设定点类型已趋于稳定。(其余设定点类型仍在开发中) + 您可能需要使用内部的 PX4 主题,这些主题可能不会随着时间的推移而保持与后方兼容。 +- 该 API没有完整的文档 ::: -The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) is a C++ library that simplifies controlling PX4 from ROS 2. +这[PX4 ROS 2接口库](../ros2/px4_ros2_interface_lib.md)是一个 C++ 库,可简化从 ROS 2 控制 PX4 的操作。 -Developers use the library to create and dynamically register modes written using ROS 2. -These modes are dynamically registered with PX4, and appear to be part of PX4 to a ground station or other external system. -They can even replace the default modes in PX4 with enhanced ROS 2 versions, falling back to the original version if the ROS2 mode fails. +开发者可使用该库创建并动态注册以 ROS 2 编写的模式。 +这些模式会动态注册到 PX4 中,并且对于地面站或其他外部系统而言,它们看起来就像是 PX4 的一部分。 +开发者甚至可以用功能增强的 ROS 2 版本模式替换 PX4 中的默认模式,且若 ROS 2 模式失效,系统会回退到原始版本的模式。 -The library also provides classes for sending different types of setpoints, ranging from high-level navigation tasks all the way down to direct actuator controls. -These classes abstract the internal setpoints used by PX4, and that can therefore be used to provide a consistent ROS 2 interface for future PX4 and ROS releases. +该库还提供了用于发送不同类型设定点的类,其涵盖范围从高层级的导航任务一直到直接的执行器控制。 +这些类对 PX4 所使用的内部设定点进行了抽象处理,因此可用于为未来的 PX4 和 ROS 版本提供统一的 ROS 2 接口。 -PX4 ROS 2 modes are easier to implement and maintain than PX4 internal modes, and provide more resources for developers in terms of processing power and pre-existing libraries. -Unless the mode is safety-critical, requires strict timing or very high update rates, or your vehicle doesn't have a companion computer, you should [consider using PX4 ROS 2 modes in preference to PX4 internal modes](../concept/flight_modes.md#internal-vs-external-modes). +PX4 ROS 2 模式相较于 PX4 内部模式,更易于实现和维护,并且在处理能力与既有代码库资源方面,能为开发者提供更丰富的支持。 +除非该模式属于安全关键型、对时序有严格要求或需要极高的更新速率,或者你的飞行器没有搭载伴随计算机,否则你应优先[考虑使用 PX4 ROS 2 模式,而非 PX4 内部模式](参考链接:../concept/flight_modes.md#internal-vs-external-modes)。 ## 综述 -This diagram provides a conceptual overview of how the control interface modes and mode executors interact with PX4. +该图从概念层面概述了控制接口模式与模式执行器如何与 PX4 进行交互。 -![ROS2 modes overview diagram](../../assets/middleware/ros2/px4_ros2_interface_lib/ros2_modes_overview.svg) +![ROS2 模式概览图](../../assets/middleware/ros2/px4_ros2_interface_lib/ros2_modes_overview.svg) -The following sections define and explain the terms used in the diagram. +以下章节对图表中使用的术语进行定义和解释。 -### Definitions +### 定义 -#### Mode +#### 模式 -A mode defined using the interface library has the following properties: +使用接口库定义的模式具有以下特性: -- A mode is a component that can send setpoints to the vehicle in order to control its motion (such as velocity or direct actuator commands). -- A mode selects a setpoint type and sends it while it is active. - It can switch between multiple setpoint types. -- A mode can't activate other modes, and must be activated by the user (through RC/GCS), the flight controller in a failsafe situation, a _mode executor_, or some other external system. -- Has a name displayed by the GCS. -- Can configure its mode requirements (for example that it requires a valid position estimate). -- A mode can perform different tasks, such as flying to a target, lowering a winch, releasing a payload and then fly back. -- A mode can replace a mode defined in PX4. +- 模式是一种组件,它可以向载具发送设定值以控制其运动(例如速度指令或直接执行器指令)。 +- 模式在激活状态下会选择一种设定值类型并发送该设定值。 + 它能够在多种设定值类型之间进行切换。 +- 一种模式无法激活其他模式,其必须由以下对象激活:用户(通过RC/GCS)、处于故障保护状态下的飞控、mode executor_,或其他某种外部系统。 +- 具有一个由GCS显示的名称。 +- 可配置其模式要求(例如,要求具备有效的位置估算值) +- 一种模式可执行不同任务,例如飞往目标点、下放绞盘、释放有效载荷,之后返航。 +- 一种模式可替换 PX4 中已定义的模式。 -#### Mode Executor +#### 模式执行器 -A mode executor is an optional component for scheduling modes. -For example, the mode executor for a custom payload delivery or survey mode might first trigger a take-off, then switch to the custom mode, and when that completes trigger an RTL. +模式执行器是用于调度模式的可选组件。 +例如,用于自定义有效载荷投放或测绘模式的模式执行器,可能会先触发起飞,随后切换至该自定义模式,待模式完成后再触发RTL。 -Specifically, it has the following properties: +具体而言,它具有以下特性: -- A mode executor is an optional component one level higher than a mode. - It is a state machine that can activate modes, and wait for their completion. -- It can only do so while it is in charge. - For that, an executor has exactly one _owned mode_ (and a mode can be owned by at most one executor). - This mode serves as activation for the executor: when the user selects the mode, the owning executor gets activated and can select any mode. - It stays in charge until the user switches modes (by RC or from a GCS), or a failsafe triggers a mode switch. - Should the failsafe clear, the executor gets reactivated. -- This allows multiple executors to coexist. -- Executors cannot activate other executors. -- Within the library, a mode executor is always implemented in combination with a custom mode. +- 模式执行器是一种可选组件,其层级比模式高一级。 + 它是一种状态机,能够激活模式并等待模式完成。 +- 它仅能在负责状态下执行此操作。 + 为此,一个执行器恰好拥有一个_owned mode_(且一个模式最多只能被一个执行器拥有)。 + 该模式可作为执行器的激活触发条件:当用户选择此模式时,其所属的执行器会被激活,进而能够选择任意模式。 + 它会一直处于管控状态,直至用户(通过遥控器或从地面控制站)切换模式,或故障保护机制触发模式切换。 + 若故障保护状态解除,执行器将重新激活。 +- 这允许多个执行器共存。 +- 执行器无法激活其他执行器。 +- 在该库中,模式执行器始终需结合自定义模式来实现。 ::: info -- These definitions guarantee that a user can take away control from a custom mode or executor at any point in time by commanding a mode switch through RC or a GCS. -- A mode executor is transparent to the user. - It gets indirectly selected and activated through the owning mode, and thus the mode should be named accordingly. +- 这些定义确保用户可在任意时刻通过RC或GCS发送模式切换指令,从而夺回对自定义模式或执行器的控制权。 +- 模式执行器对用户而言是透明的。 + 它通过所属模式被间接选择并激活,因此该模式应相应地命名。 ::: -#### Configuration Overrides +#### 配置覆盖 -Both modes and executors can define configuration overrides, allowing customisation of certain behaviors while the mode or executor is active. +模式和执行器均可定义配置覆盖,从而能在模式或执行器处于激活状态时,对特定行为进行自定义设置。 -These are currently implemented: +这些措施目前正在实施: - _Disabling auto-disarm_. - This permits landing and then taking off again (e.g. to release a payload). + 这允许着陆,然后再次起飞(例如释放有效载荷)。 - _Ability to defer non-essential failsafes_. - This allows an executor to run an action without being interrupted by non-critical failsafe. - For example, ignoring a low-battery failsafe so that a winch operation can complete. + 这使得执行器能够执行某项操作,且不会被非关键故障保护中断。 + 例如,忽略低电量故障保护(机制),以便绞车操作能够完成。 -### Comparison to Offboard Control +### 与离板控制的比较 -The above concepts provide a number of advantages over traditional [offboard control](../ros/offboard_control.md): +上述概念提供了一些优点,而不是传统的[离板控制](../ros/offboard_control.md): -- Multiple nodes or applications can coexist and even run at the same time. - But only one node can _control the vehicle_ at a given time, and this node is well defined. -- Modes have a distinct name and be displayed/selected in the GCS. -- Modes are integrated with the failsafe state machine and arming checks. -- The setpoint types that can be sent are well defined. -- ROS 2 modes can replace flight controller internal modes (such as [Return mode](../flight_modes/return.md)). +- 多个节点或应用程序可以共存,甚至能同时运行。 + 但在特定时刻,仅能有一个节点对载具进行控制,且该节点的定义是明确的。 +- 模式具有独特的名称,并且可在GCS中显示 / 选择。 +- 模式与故障保护状态机及解锁检查功能相集成。 +- 可发送的设定值类型定义明确。 +- ROS 2 模式可以替换飞行控制器内部模式(如[返回模式](../flight_modes/return.md))。 -## Installation and First Test +## 安装与首次测试 -The following steps are required to get started: +开始使用前,需完成以下步骤: 1. 请确保您在 ROS 2 工作区中有 [ROS 2 设置](../ros2/user_guide.md) 与 [`px4_msgs`](https://github.com/PX4/px4_msgs]。 @@ -127,35 +127,35 @@ The following steps are required to get started: source install/setup.bash ``` -4. In a different shell, start PX4 SITL: +4. 在另一个外壳中,启动 PX4 SITL: ```sh cd $px4-autopilot make px4_sitl gazebo-classic ``` - (here we use Gazebo-Classic, but you can use any model or simulator) + (这里我们使用Gazebo-Classic,但你可以使用任何模型或模拟器) -5. Run the micro XRCE agent in a new shell (you can keep it running afterward): +5. 在新的 shell 中运行微XRCE 代理 (您可以在以后继续运行): ```sh MicroXRCEAgent udp4 -p 8888 ``` -6. Start QGroundControl. +6. 启动QGroundControl。 ::: info Use QGroundControl Daily, which supports dynamically updating the list of modes. ::: -7. Back in the ROS 2 terminal, run one of the example modes: +7. 回到ROS2终端,运行一个示例模式: ```sh - ros2 run example_mode_manual_cpp example_mode_manual + ros2 运行 example_mode_manual_cpp example_mode_manual ``` - You should get an output like this showing 'My Manual Mode' mode being registered: + 你应会看到类似如下的输出,其中显示 “我的手动模式"已注册: ```sh [DEBUG] [example_mode_manual]: Checking message compatibility... @@ -168,13 +168,13 @@ The following steps are required to get started: [DEBUG] [example_mode_manual]: Arming check request (id=1, only printed once) ``` -8. On the PX4 shell, you can check that PX4 registered the new mode: +8. 在 PX4 外壳上,您可以检查 PX4 是否注册了新模式: ```sh - commander status + 指挥官状态 ``` - The output should contain: + 输出应包含: ```plain INFO [commander] Disarmed @@ -184,29 +184,29 @@ The following steps are required to get started: INFO [commander] External Mode 1: nav_state: 23, name: My Manual Mode ``` -9. At this point you should be able to see the mode in QGroundControl as well: +9. 在这一点上,您也应该能够在 QGroundControl 中看到模式: ![QGC Modes](../../assets/middleware/ros2/px4_ros2_interface_lib/qgc_modes.png) -10. Select the mode, make sure you have a manual control source (physical or virtual joystick), and arm the vehicle. - The mode will then activate, and it should print the following output: +10. 选择该模式,确保你拥有手动控制源(物理或虚拟操纵杆),并为载具解锁 + 然后模式将激活,它将打印以下输出: ```sh - [DEBUG] [example_mode_manual]: Mode 'My Manual Mode' activated + [DEBUG] [example_mode_manual]: 模式“我的手动模式” 已激活 ``` -11. Now you are ready to create your own mode. +11. 现在您已准备好创建自己的模式。 -## How to use the Library +## 如何使用代码库 -The following sections describe specific functionality provided by this library. -In addition, any other PX4 topic can be subscribed or published. +以下各节介绍该库提供的特定功能。 +此外,任何其他PX4主题都可以订阅或发布。 -### Mode Class Definition +### 模式类定义 -This section steps through an example of how to create a class for a custom mode. +此部分通过如何为自定义模式创建类的示例。 -For a complete application, check out the [examples in the `Auterion/px4-ros2-interface-lib` repository](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp), such as [examples/cpp/modes/manual](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/examples/cpp/modes/manual/include/mode.hpp). +若要完整的应用程序,请查看[示例在 `Auterion/px4-ros2-interfacee-lib` 仓库中](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp),例如[示例/cpp/mod/manual](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/examples/cpp/modes/manual/include/mode.hpp)。 ```cpp{1,5,7-9,24-31} class MyMode : public px4_ros2::ModeBase // [1] @@ -248,19 +248,19 @@ private: }; ``` -- `[1]`: First we create a class that inherits from [`px4_ros2::ModeBase`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1ModeBase.html). -- `[2]`: In the constructor, we pass the mode name. This also allows us to configure some other things, like replacing a flight controller internal mode. -- `[3]`: This is where we create all objects that we want to use later on. - This can be RC input, setpoint type(s), or telemetry. `*this` is passed as a `Context` to each object, which associates the object with the mode. -- `[4]`: Whenever the mode is active, this method gets called regularly (the update rate depends on the setpoint type). - Here is where we can do our work and generate a new setpoint. +- [1]`: 首先创建一个从 [`px4_ros2:::ModeBase\` ](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1ModeBase.html )继承的类。 +- [2]\`: 在构造函数中,我们传递模式名称。 这也使我们能够配置一些其他内容,例如替换飞行控制器的内置模式。 +- [3]:我们在此处创建后续想要使用的所有对象。 + 这可以是 RC 输入、设置点类型(s)或遥测数据。 `*this` 作为`Context`传递给每个对象,将对象与模式联系起来。 +- [4]:每当该模式处于激活状态时,此方法会定期被调用(更新频率取决于设定值类型)。 + 我们可以在这里开展工作并产生一个新的设定点。 -After creating an instance of that mode, `mode->doRegister()` must be called which does the actual registration with the flight controller and returns `false` if it fails. -In case a mode executor is used, `doRegister()` must be called on the mode executor, instead of for the mode. +创建此模式的实例后, `mode->doRegister()` 必须被调用,在飞行控制器中进行实际注册,如果失败则返回 `false` 。 +如果使用模式执行器,`doRegister()`必须调用模式执行器而不是模式。 -### Mode Executor Class Definition +### 模式执行器类定义 -This section steps through an example of how to create a mode executor class. +本节逐步讲解如何创建模式执行器类的示例。 ```cpp{1,4-5,9-16,20,33-57} class MyModeExecutor : public px4_ros2::ModeExecutorBase // [1] @@ -327,74 +327,74 @@ private: }; ``` -- `[1]`: First we create a class that inherits from [`px4_ros2::ModeExecutorBase`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1ModeExecutorBase.html). -- `[2]`: The constructor takes our custom mode that is associated with the executor and passes it to the constructor of `ModeExecutorBase`. -- `[3]`: We define an enum for the states we want to run through. -- `[4]`: `onActivate` gets called when the executor becomes active. At this point we can start to run through our states. - How you do this is up to you, in this example a method `runState` is used to execute the next state. -- `[5]`: On switching to a state we call an asynchronous method from `ModeExecutorBase` to start the desired mode: `run`, `takeoff`, `rtl`, and so on. - These methods are passed a function that is called on completion; the callback provides a `Result` argument that tells you whether the operation succeeded or not. - The callback runs the next state on success. -- `[6]`: We use the `scheduleMode()` method to start the executor's "owned mode", following the same pattern as the other state handlers. +- [1]`: 首先创建一个从 [`px4_ros2:::ModeExecutorBase\` ](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1ModeExecutorBase.html ) 继承的类。 +- [2]`: 构造函数采用与执行器相关联的自定义模式,并传递给`ModeExecutorBase\`的构造函数。 +- [3]\`: 我们为想要运行的状态定义一个枚举。 +- [4]`: `onActivate`在执行器激活时被调用。 此时,我们可以开始遍历这些状态了。 + 你是如何操作的,在这个示例中使用`runState\` 方法来执行下一个状态。 +- [5]`: 在切换到状态时,我们会调用 `ModeExecutorBase` 中的异步方法来启动所需的模式:`run`, “eff”、“rtl”、“等等”。 + 这些方法被传递了一个被要求完成的函数; 回调提供一个 `Result\` 参数,告诉您操作是否成功。 + 回调运行下一个成功状态。 +- [6]`: 我们使用 `scheduleMode()\` 方法来启动执行者"拥有模式", 遵循与其他状态处理器相同的模式。 -### Setpoint Types +### 设置点类型 -A mode can choose its setpoint type(s) it wants to use to control the vehicle. -The used types also define the compatibility with different vehicle types. +模式可选择其用于控制载具的设定值类型。 +所用类型还界定了与不同类型载具的兼容性。 -The following sections provide a list of supported setpoint types: +以下章节提供了支持的设置点类型列表: -- [GotoSetpointType](#go-to-setpoint-gotosetpointtype): Smooth position and (optionally) heading control -- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics -- [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype): Direct control of motors and flight surface servo setpoints +- [GotoSetpointType](#go-to-setpoint-gotosetpointtype): 平稳的位置控制以及(可选的)航向控制 +- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): 对横向和纵向固定翼动态的直接控制 +- [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype):直接控制发动机和飞行地面servo setpoints :::tip -The other setpoint types are currently experimental, and can be found in: [px4_ros2/control/setpoint_types/experimental](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/experimental). +其他设置点类型目前是实验性的,可在以下网址找到:[px4_ros2/control/setpoint_types/experimental](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/experimental)。 -You can add your own setpoint types by adding a class that inherits from `px4_ros2::SetpointBase`, sets the configuration flags according to what the setpoint requires, and then publishes any topic containing a setpoint. +您可以通过添加一个从 `px4_ros2::SetpointBase` 继承的类来添加您自己的 setpoint 类型, 根据设置点的要求设置配置标志,然后发布任何包含设置点的主题。 ::: -#### Go-to Setpoint (GotoSetpointType) +#### 转到设置点 (GotoSetpointType) :::info -This setpoint type is currently only supported for multicopters. +当前,此设定值类型仅支持多旋翼飞行器。 ::: -Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::GotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/goto.hpp) setpoint type. -The setpoint type is streamed to FMU based position and heading smoothers formulated with time-optimal, maximum-jerk trajectories, with velocity and acceleration constraints. +以[`px4_ros2:::GotoSetpootType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/goto.hpp) 设置点类型平滑控制位置和(可选) 设置点。 +该设定值类型会传输至FMU,用于基于位置和航向的平滑控制器;该平滑控制器采用时间最优、最大加加速度轨迹设计,并设有速度和加速度约束。 -The most trivial use is simply inputting a 3D position into the update method: +最简单的用法就是直接向update method中输入一个3D 位置 ```cpp const Eigen::Vector3f target_position_m{-10.F, 0.F, 3.F}; _goto_setpoint->update(target_position_m); ``` -In this case, heading will remain _uncontrolled_. -To additionally control heading, specify it as the second input argument: +在这种情况下,航向将保持不受控制的状态。 +若要额外控制航向,可将其指定为第二个输入参数: ```cpp -const Eigen::Vector3f target_position_m{-10.F, 0.F, 3.F}; +const Eigen:::Vector3f target_position_m{-10.F, 0.F, 3.F}; const float heading_rad = 3.14F; _goto_setpoint->update( target_position_m, heading_rad); ``` -An additional feature of the go-to setpoint is dynamic control on the underlying smoothers' speed limits (i.e. maximum horizontal and vertical translational velocities as well as heading rate). -If, as above, left unspecified, the smoothers will default to the vehicle's default maximums (typically set to the physical limitations). -The smoothers will _only_ decrease speed limits, never increase. +“前往设定值”(go-to setpoint)的一项额外功能是,可对底层平滑控制器的速度限制进行动态控制(即对最大水平和平动速度、最大垂直平动速度以及航向速率进行动态控制)。 +若如上文所述未指定(该参数),则平滑控制器将默认采用设备的默认最大值(通常设定为其物理极限值) +平滑控制器仅会降低速度限制,绝不会提高速度限制。 ```cpp _goto_setpoint->update( target_position_m, heading_rad, - max_horizontal_velocity_m_s, + max_水平_velocity_m_s, max_vertical_velocity_m_s, max_heading_rate_rad_s); ``` -All arguments in the update method except the position are templated as `std::optional`, meaning that if one desires constraining the heading rate, but not the translating velocities, this is possible using a `std::nullopt`: +更新方法中,除位置外的所有参数均被模板化为 std::optional 类型。这意味着,若需限制航向速率但不限制平动速度,可通过 std::nullopt 实现这一需求。 ```cpp _goto_setpoint->update( @@ -405,58 +405,58 @@ _goto_setpoint->update( max_heading_rate_rad_s); ``` -#### Fixed-Wing Lateral and Longitudinal Setpoint (FwLateralLongitudinalSetpointType) +#### 固定翼横向与纵向设定值(FwLateralLongitudinalSetpointType,固定翼横向纵向设定值类型) :::info -This setpoint type is supported for fixed-wing vehicles and for VTOLs in fixed-wing mode. +此设定值类型支持固定翼飞行器,以及处于固定翼模式下的垂直起降飞行器(VTOL)。 ::: -Use the [`px4_ros2::FwLateralLongitudinalSetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1FwLateralLongitudinalSetpointType.html) to directly control the lateral and longitudinal dynamics of a fixed-wing vehicle — that is, side-to-side motion (turning/banking) and forward/vertical motion (speeding up and climbing/descending), respectively. -This setpoint is streamed to the PX4 [_FwLateralLongitudinalControl_ module](../modules/modules_controller.md#fw-lat-lon-control), which decouples lateral and longitudinal inputs while ensuring that vehicle limits are respected. +使用[`px4_ros2::FwLateralLongitudinalSetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1FwLateralLongitudinalSetpointType.html)直接控制固定翼飞行器的横向与纵向动力学特性,即分别控制其侧向运动(转弯 / 倾斜)和前向 / 垂直运动(加速及爬升 / 下降)。 +这个设置点被传输到 PX4 [_FwLateralLongitudinalControl_module](../modules/modules_controller.md#fw-lat-lon-control),该模块会对横向与纵向输入进行解耦处理,同时确保不超出飞行器的各项限制范围。 -To control the vehicle, at least one lateral **and** one longitudinal setpoint must be provided: +为了控制载具,必须提供至少一个横向**和**一个纵向设定值: -1. Of the longitudinal inputs: either `altitude` or `height_rate` must be finite to control vertical motion. - If both are set to `NAN`, the vehicle will maintain its current altitude. -2. Of the lateral inputs: at least one of `course`, `airspeed_direction`, or `lateral_acceleration` must be finite. +1. 在纵向输入中:必须至少有一个 “高度”(altitude)或 “高度速率”(height_rate)为有限值,才能实现垂直运动控制。 + 若二者均设为 NAN,则载具将保持当前高度。 +2. 在横向输入中:“航线角”(course)、“空速方向”(airspeed_direction)或 “横向加速度”(lateral_acceleration)这三者中,至少有一个必须为有限值。 -For a detailed description of the controllable parameters, please refer to message definitions ([FixedWingLateralSetpoint](../msg_docs/FixedWingLateralSetpoint.md) and [FixedWingLongitudinalSetpoint](../msg_docs/FixedWingLongitudinalSetpoint.md)). +关于可控参数的详细说明,请参考消息定义([FixedWingLateralSetpoint](../msg_docs/FixedWingLateralSetpoint.md) 和 [FixedWingLongitudinalSetpoint](../msg_docs/FixedWingLongitudinalSetpoint.md))。 ##### 基本用法 -This type has a number of update methods, each allowing you to specify an increasing number of setpoints. +该类型包含多个更新方法,每种方法可支持你指定的设定值数量逐步增加。 -The simplest method is `updateWithAltitude()`, which allows you to specify a `course` and `altitude` target setpoint: +最简单的方法是 updateWithAltitude(),该方法可让你指定 “航线角”(course)和 “高度”(altitude)这两个目标设定值。 ```cpp -const float altitude_msl = 500.F; +const float altextede_msl = 500.F; const float course = 0.F; // due North -_fw_lateral_longitudinal_setpoint->updateWithAltitude(altitude_msl, course); +_fw_later_longitudinal_setpoint->updateWAltitude(altyde_msl, course); ``` -PX4 uses the setpoints to compute the _roll angle_, _pitch angle_ and _throttle_ setpoints that are sent to lower level controllers. -Note that the commanded flight is expected to be relatively gentle/unaggressive when using this method. -This is done as follows: +PX4 会利用这些设定值计算出横滚角(roll angle)、俯仰角(pitch angle)和油门(throttle)设定值,并将其发送至底层控制器。 +需注意,使用此方法时,预期的指令飞行会相对平缓 / 不激进。 +此操作按如下方式执行: -- Lateral control output: +- 横向控制输出: - course setpoint (set by user) → airspeed direction (heading) setpoint → lateral acceleration setpoint → roll angle setpoint. + 航线角设定值(由用户设定)→ 空速方向 (航向) 设定值 → 横向加速设定值 → 滚动角度设定值 -- Longitudinal control output: +- 纵向控制输出: - altitude setpoint (set by user) → height rate setpoint → pitch angle setpoint and throttle settings. + 高度设定值(由用户设定) → 高度速率设定值 → 俯仰角设定值及油门设定。 -The `updateWithHeightRate()` method allows you to set a target `course` and `height_rate` (this is useful if the speed of ascent or descent matters, or needs to be dynamically controlled): +updateWithHeightRate() 方法允许你设置目标 “航线角”(course)和 “高度速率”(height_rate)(当爬升或下降速度至关重要,或需要对其进行动态控制时,此方法非常实用): ```cpp const float height_rate = 2.F; -const float course = 0.F; // due North -_fw_lateral_longitudinal_setpoint->updateWithHeightRate(height_rate, course); +const float course = 0.F; //due North +_fw_lateral_longitudinal_setpoint->updateWheightRate(high_rate course); ``` -The `updateWithAltitude()` and `updateWithHeightRate()` methods allow you to additionally control the equivalent airspeed or lateral acceleration by specifying them as the third and fourth arguments, respectively: +updateWithAltitude() 和 updateWithHeightRate() 这两种方法还允许你分别将 “等效空速”(equivalent airspeed)或 “横向加速度”(lateral acceleration)指定为第三个和第四个参数,从而对其进行控制: ```cpp const float altitude_msl = 500.F; @@ -470,44 +470,44 @@ _fw_lateral_longitudinal_setpoint->updateWithAltitude(altitude_msl, lateral_acceleration); ``` -The equivalent airspeed and lateral acceleration arguments are defined as `std::optional`, so you can omit any of them by passing `std::nullopt`. +等效的空速和横向加速参数定义为 `std::opulatory`, 所以你可以通过 `std::nullopt` 省略其中任何一个。 :::tip -If both lateral acceleration and course setpoints are provided, the lateral acceleration setpoint will be used as feedforward. +若同时提供了横向加速度设定值和航线角设定值,横向加速度设定值将被用作前馈(feedforward) ::: -##### Full Control Using the Setpoint Struct +##### 使用设定值结构体实现完全控制 -For full flexibility, you can create and pass a [`FwLateralLongitudinalSetpoint`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1FwLateralLongitudinalSetpoint.html) struct. -Each field is templated with `std::optional`. +为实现充分的灵活性,你可以创建并传递一个[`FwLateralLongitudinalSetpoint` ](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1FwLateralLongitudinalSetpoint.html) 结构体。 +每个字段都使用 "std::opulatory "模板。 :::tip -If both course and airspeed direction are set: airspeed direction takes precedence, course is not controlled. -Lateral acceleration is treated as feedforward if either course or airspeed direction are also finite. -If both altitude and height rate are set: height rate takes precedence, altitude is not controlled. +若同时设置了航线角(course)和空速方向(airspeed direction),则空速方向优先,航线角不进行控制。 +若航线角或空速方向中任意一个为有限值,则横向加速度会被视为前馈。 +若同时设置了高度和高度速率,则高度速率优先,高度不进行控制。 ::: ```cpp -px4_ros2::FwLateralLongitudinalSetpoint setpoint_s; +px4_ros2:::FwLateralLongitudinalSetpoint setpoint_s; -setpoint_s.withCourse(0.F); -// setpoint_s.withAirspeedDirection(0.2F); // uncontrolled -setpoint_s.withLateralAcceleration(2.F); // feedforward -//setpoint_s.withAltitude(500.F); // uncontrolled -setpoint_s.withHeightRate(2.F); -setpoint_s.withEquivalentAirspeed(15.F); +settpoint_s.withCourse(0.F); +// setpoint_s.withAirspeedDirection(0.2F); // 失控 +setpoint_s.withLateralActivation(2.F); // feedforward +/setpoint_s.withAltude(500.F); // 失控 +setpoint_s.withightRate(2.F); +settpoint_s.withequivalentAirspeed(15.F); -_fw_lateral_longitudinal_setpoint->update(setpoint_s); +_fw_lateral_longitudinal_sett->upate(settpoint_ ``` -The diagram below illustrates the interaction between the `FwLateralLongitudinalSetpointType` and PX4 when all inputs are set. +下图展示了在所有输入均已设定的情况下,FwLateralLongitudinalSetpointType 与 PX4 之间的交互关系。 -![FW ROS Interaction](../../assets/middleware/ros2/px4_ros2_interface_lib/fw_lat_long_ros_interaction.svg) +![FW ROS交互](../../assets/middleware/ros2/px4_ros2_interface_lib/fw_lat_long_ros_interaction.svg) -##### Advanced Configuration (Optional) +##### 高级配置(可选) -You can also pass a [`FwControlConfiguration`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1FwControlConfiguration.html) struct along with the setpoint to override default controller settings and constraints such as pitch limits, throttle limits, and target sink/climb rates. -This is intended for advanced users: +你还可以传递一个[`FwControlConfiguration`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1FwControlConfiguration.html) 结构体以及设定值,以覆盖默认的控制器设置和约束条件,例如俯仰角限制、油门限制以及目标下降 / 爬升速率。 +这是针对高级用户的: ```cpp px4_ros2::FwLateralLongitudinalSetpoint setpoint_s; @@ -526,47 +526,47 @@ config_s.withThrottleLimits(0.4F, 0.6F); _fw_lateral_longitudinal_setpoint->update(setpoint_s, config_s); ``` -All configuration fields are defined as `std::optional`. -Unset values will default to the PX4 configuration. -See [LateralControlConfiguration](../msg_docs/LateralControlConfiguration.md) and [FixedWingLongitudinalConfiguration](../msg_docs/LongitudinalControlConfiguration.md) for more information on configuration options. +所有配置字段都定义为 "std::opulatory"。 +未设置的值将默认采用 PX4 的配置。 +更多关于配置选项的信息,请参阅 [LateralControlConfiguration](../msg_docs/LateralControlConfiguration.md) 和 [FixedWingLongitudinalConfiguration](../msg_docs/LongitudinalControlConfiguration.md)。 :::info -For safety, PX4 automatically limits configuration values to stay within the vehicle’s constraints. -For example, throttle overrides are clamped to remain between [`FW_THR_MIN`](../advanced_config/parameter_reference.md#FW_THR_MIN) -and [`FW_THR_MAX`](../advanced_config/parameter_reference.md#FW_THR_MAX). +为保障安全,PX4 会自动将配置值限制在飞行器的约束范围内。 +例如,油门覆盖值会被限制在[`FW_THR_MIN`](../advanced_config/parameter_reference.md#FW_THR_MIN) +和 [`FW_THR_MAX`](../advanced_config/parameter_reference.md#FW_THR_MAX)之间。 ::: -#### Direct Actuator Control Setpoint (DirectActuatorsSetpointType) +#### 直接执行器控制设定点(DirectActuatorsSetpointType) -Actuators can be directly controlled using the [px4_ros2::DirectActuatorsSetpointType](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1DirectActuatorsSetpointType.html) setpoint type. -Motors and servos can be set independently. -Be aware that the assignment is vehicle and setup-specific. -For example to control a quadrotor, you need to set the first 4 motors according to its [output configuration](../concept/control_allocation.md). +可以使用 [px4_ros2::DirectActActorsSetpootType](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1DirectActuatorsSetpointType.html) 设置点类型直接控制执行器。 +电机和舵机可独立设置。 +请注意,该分配(设置 / 指派)具有载具和配置特定性。 +例如,要控制一架四旋翼飞行器,你需要根据其 [输出配置] (../concept/control_allocation.md )来设置前 4 个电机。 :::info -If you want to control an actuator that does not control the vehicle's motion, but for example a payload servo, see [below](#controlling-an-independent-actuator-servo). +若你想控制的执行器并非用于控制飞行器的运动(例如,而是用于控制有效载荷舵机),请参阅 [below](#controlling-an-independent-actuator-servo)。 ::: -### Controlling a VTOL +### 控制VTOL -To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration: +要在外部飞行模式下控制VTOL,需确保根据当前飞行配置返回正确的设定值类型: -- Multicopter mode: use a setpoint type that is compatible with multicopter control. For example: either the [`GotoSetpointType`](#go-to-setpoint-gotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html). -- Fixed-wing mode: Use the [`FwLateralLongitudinalSetpointType`](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype). +- 多旋翼模式:使用与多旋翼控制兼容的设定值类型。 例如:要么[`GotoSetpootType`](#go-to-setpoint-gotosetpointtype) 要么[`TracjectorySettpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html)。 +- 固定翼形模式:使用 [`FwLateralLongitudinalSetpointType` ](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype)。 -As long as the VTOL remains in either multicopter or fixed-wing mode throughout the external mode, no additional handling is required. +只要VTOL在整个外部模式期间始终处于多旋翼模式或固定翼模式中的任意一种,就无需额外处理。 -If you would like to command a VTOL transition in your external mode, you need to use the [VTOL API](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1VTOL.html). The VTOL API provides the functionality to command a transition and query the current state of the vehicle. +如果您想要在您的外部模式中命令一个 VTAL 过渡,您需要使用 [VTOL API](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1VTOL.html)。 VTAL API具备下达转换指令和查询载具当前状态的功能。 -Use this API with caution! -Commanding transitions externally makes the user partially responsible for ensuring smooth and safe behavior, unlike onboard transitions (e.g. via RC switch) where PX4 handles the full process: +谨慎使用此 API ! +通过外部下达转换指令时,用户需部分负责确保(飞行器)运行平稳且安全;这与机上转换(例如通过遥控器开关实现)不同,在机上转换模式下,整个过程由 PX4 全权处理。 -1. Ensure that both the `TrajectorySetpointType` and the `FwLateralLongitudinalSetpointType` are available to your mode. -2. Create an instance of `px4_ros2::VTOL` in the constructor of your mode. -3. To command a transition, you can use the `toMulticopter()` or `toFixedwing()` methods on your VTOL object to set the desired state. -4. During transition, send the following combination of setpoints: +1. 确保你的模式可调用 TrajectorySetpointType(轨迹设定值类型)和 FwLateralLongitudinalSetpointType(固定翼横纵向设定值类型)这两种设定值类型。 +2. 在您模式的构造函数中创建 `px4_ros2::VTOL` 的实例。 +3. 要下达转换指令,你可以在 VTOL 对象上调用 toMulticopter() 或 toFixedwing() 方法,以设置所需状态。 +4. 在转换过程中,发送以下设定值组合: ```cpp // Assuming the instance of the px4_ros2::VTOL object is called vtol @@ -584,35 +584,35 @@ Commanding transitions externally makes the user partially responsible for ensur _fw_lateral_longitudinal_setpoint->updateWithAltitude(NAN, course_sp) ``` - This will ensure that the transition is handled properly within PX4. - You can optionally pass a deceleration setpoint to `computeAccelerationSetpointDuringTransition()` to be used during back-transitions. + 这将确保转换过程在 PX4 系统内部得到妥善处理。 + 你可以选择性地将一个减速度设定值传递给 computeAccelerationSetpointDuringTransition(),以便在反向转换过程中使用。 -To check the current state of the vehicle, use the `getCurrentState()` method on your `px4_ros2::VTOL` object. +要查询载具的当前状态,可在 px4_ros2::VTOL 对象上调用 getCurrentState() 方法。 -See [this external flight mode implementation](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/vtol) for a practical example on how to use this API. +请参阅[此外部飞行模式实现](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/vtol)有关如何使用此 API 的实际示例。 -### Controlling an Independent Actuator/Servo +### 控制独立执行器/Servo -If you want to control an independent actuator (a servo), follow these steps: +如果您想要控制一个独立执行器(aservo),遵循以下步骤: 1. [Configure the output](../payloads/generic_actuator_control.md#generic-actuator-control-with-mavlink). -2. Create an instance of [px4_ros2::PeripheralActuatorControls](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1PeripheralActuatorControls.html) in the constructor of your mode. -3. Call the `set()` method to control the actuator(s). - This can be done independently of any active setpoints. +2. 在您的模式的构造函数中创建一个实例[px4_ros2::PeripheralActorControls](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1PeripheralActuatorControls.html)。 +3. 调用`set()` 方法以控制执行器 + 此操作可独立于任何活跃的设定点执行。 -### Telemetry +### 数传 -You can access PX4 telemetry topics directly via the following classes: +你可以通过以下类直接访问 PX4 遥测主题: -- [OdometryGlobalPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryGlobalPosition.html): Global position -- [OdometryLocalPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryLocalPosition.html): Local position, velocity, acceleration, and heading -- [OdometryAttitude](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryAttitude.html): Vehicle attitude -- [OdometryAirspeed](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryAirspeed.html): Airspeed +- [OdometryGlobalPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryGlobalPosition.html): 全球位置 +- [OdometryLocalPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryLocalPosition.html): 本地位置、速度、加速度和航向 +- [OdometryAttitude](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryAttitude.html): 载具状态 +- [OdometryAirspeed](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1OdometryAirspeed.html):空速 -For example, you can query the vehicle's current position estimate as follows: +例如,你可以通过以下方式查询飞行器当前的位置估算值: ```cpp -std::shared_ptr _vehicle_local_position; +std::shared_ptr<0> _vehicle_local_position; ... // Get vehicle's last local position @@ -623,55 +623,55 @@ _vehicle_local_position->positionXYValid(); ``` :::info -These topics provide a wrapper around the internal PX4 topics, allowing the library to maintain compatibility if the internal topics change. -Check [px4_ros2/odometry](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/px4_ros2_cpp/include/px4_ros2/odometry) for new topics, and of course you can use any ROS 2 topic published from PX4. +这些主题围绕内部的 PX4 主题提供了一个包装程序,使代码库能够在内部主题发生变化时保持兼容性。 +检查 [px4_ros2/odometry](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/px4_ros2_cpp/include/px4_ros2/odometry) 新主题,当然你也可以使用任何由 PX4 发布的 ROS 2 主题。 ::: -### Failsafes and Mode Requirements +### 故障保护与模式要求 -Each mode has a set of requirement flags. -These are generally automatically set, depending on which objects are used within the context of a mode. -For example when adding manual control input with the code below the requirement flag for manual control gets set: +每种模式都有一组需求标志。 +这些(需求标志)通常会根据模式语境下所使用的对象自动设置。 +例如,当通过以下代码添加手动控制输入时,手动控制的需求标志会被设置: ```cpp _manual_control_input = std::make_shared(*this); ``` -Specifically, setting a flag has the following consequences in PX4, if the condition is not met: +具体而言,在 PX4 中,若条件未满足,设置某个标志会产生以下结果: -- arming is not allowed, while the mode is selected -- when already armed, the mode cannot be selected -- when armed and the mode is selected, the relevant failsafe is triggered (e.g. RC loss for the manual control requirement). - Check the [safety page](../config/safety.md) for how to configure failsafe behavior. - A failsafe is also triggered when the mode crashes or becomes unresponsive while it is selected. +- 在选定模式时不允许进行解锁操作 +- 当已处于武装状态时,该模式无法被选择。 +- 当载具已解锁且该模式被选中时,相关的故障保护机制会被触发(例如,针对手动控制需求的遥控器信号丢失故障保护)。 + 检查 [safety page] (../config/safety.md) 如何配置故障安全行为。 + 当某模式已被选中,且该模式发生崩溃或失去响应时,也会触发故障保护机制。 -This is the corresponding flow diagram for the manual control flag: +这是手动控制标志对应的流程图: ![Mode requirements diagram](../../assets/middleware/ros2/px4_ros2_interface_lib/mode_requirements_diagram.png) -It is possible to manually update any mode requirement after the mode is registered. -For example to add home position as requirement: +在模式注册后,可以手动更新任意模式要求。 +例如,要将返航点(home position)添加为一项要求: ```cpp modeRequirements().home_position = true; ``` -The full list of flags can be found in [requirement_flags.hpp](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/common/requirement_flags.hpp). +标记的完整列表可以在 [requirement_flags.hpp](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/common/requirement_flags.hpp 中找到。 -#### Deferring Failsafes +#### 延迟故障保护 -A mode or mode executor can temporarily defer non-essential failsafes by calling the method [`deferFailsafesSync()`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1ModeExecutorBase.html#a16ec5be6ebe70e1d0625bf696c3e29ae). -To get notified when a failsafe would be triggered, override the method [`void onFailsafeDeferred()`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1ModeExecutorBase.html#ad80a234c8cb2f4c186fa2b7bffd1a1dd). +模式或模式执行器可以通过调用该方法暂时延迟非必要的故障保护。 [`deferFailsafesSync()`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1ModeExecutorBase.html#a16ec5be6ebe70e1d0625bf696c3e29ae). +若想在故障保护即将被触发时收到通知,需重写该方法。 [`void onFailsafeDeferred()`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1ModeExecutorBase.html#ad80a234c8cb2f4c186fa2b7bffd1a1dd). -Check the [integration test](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/test/integration/overrides.cpp) for an example. +例如检查[integration test](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/test/integration/overrides.cpp)。 -### Assigning a Mode to an RC Switch or Joystick Action +### 将模式指派给 RC 切换或操纵动作 -External modes can be assigned to [RC switches](../config/flight_mode.md) or joystick actions. -When assigning a mode to an RC switch, you need to know the index (because the parameter metadata does not contain the dynamic mode name). -Use `commander status` while the mode is running to get that information. +外部模式可以被分配给[RC switches](../config/flight_mode.md) 或操纵杆动作。 +当将模式分配给RC开关时,你需要知道其索引(因为参数元数据中不包含动态模式名称)。 +在模式运行期间,使用 'commander status'(指令状态)来获取该信息。 例如: @@ -679,23 +679,23 @@ Use `commander status` while the mode is running to get that information. INFO [commander] External Mode 1: nav_state: 23, name: My Manual Mode ``` -means you would select **External Mode 1** in QGC: +意味着你需要在 QGC中选择外部模式 1(External Mode 1) : -![QGC Mode Assignment](../../assets/middleware/ros2/px4_ros2_interface_lib/qgc_mode_assignment.png) +![QGC Modes](../../assets/middleware/ros2/px4_ros2_interface_lib/qgc_mode_assignment.png) :::info -PX4 ensures a given mode is always assigned to the same index by storing a hash of the mode name. -This makes it independent of startup ordering in case of multiple external modes. +PX4通过存储模式名称的散列确保指定模式始终分配到同一索引。 +这使它独立于多个外部模式下的启动订购。 ::: -### Replacing an Internal Mode +### 替换内部模式 -An external mode can replace an existing internal mode, such as [Return](../flight_modes/return.md) mode (RTL). -By doing so, whenever RTL gets selected (through the user or a failsafe situation), the external mode is used instead of the internal one. -The internal one is only used as a fallback when the external one becomes unresponsive or crashes. +外部模式可替换现有的内部模式,例如[Return](../flight_modes/return.md) mode (RTL). +这样做,每当选择RTL(通过用户或故障安全情况),就使用外部模式而不是内部模式。 +当外部模式失去响应或发生崩溃时,内部模式仅用作备用模式。 -The replacement mode can be set in the settings of the `ModeBase` constructor: +替换模式可在' ModeBase '构造函数的设置中进行配置: ```cpp -Settings{kName, false, ModeBase::kModeIDRtl} +设置{kName, false, ModeBase::kModeIDRtl} ``` diff --git a/docs/zh/ros2/px4_ros2_msg_translation_node.md b/docs/zh/ros2/px4_ros2_msg_translation_node.md index 6d69dc3c01..c496de825e 100644 --- a/docs/zh/ros2/px4_ros2_msg_translation_node.md +++ b/docs/zh/ros2/px4_ros2_msg_translation_node.md @@ -1,81 +1,82 @@ -# PX4 ROS 2 Message Translation Node +# PX4 ROS 2 消息翻译节点 - +<0/> <1/> -The message translation node allows ROS 2 applications that were compiled against different versions of the PX4 messages to interwork with newer versions of PX4, and vice versa, without having to change either the application or the PX4 side. +消息翻译节点允许针对不同版本的 PX4 消息编译的 ROS 2 应用程序与更新版本的 PX4 交互。 反之亦然,而不必更改应用程序或PX4一侧。 ## 综述 -The translation of messages from one definition version to another is possible thanks to the introduction of [message versioning](../middleware/uorb.md#message-versioning). +由于引入了[消息版本](../middleware/uorb.md#message-versioning),将消息从一个定义版本翻译成另一个定义版本是可能的。 -The translation node has access to all message versions previously defined by PX4. -It dynamically observes the DDS data space, monitoring the publications, subscriptions and services originating from either PX4 via the [uXRCE-DDS Bridge](../middleware/uxrce_dds.md), or ROS 2 applications. -When necessary, it converts messages to the current versions expected by both applications and PX4, ensuring compatibility. +翻译节点可以访问之前由 PX4 定义的所有消息版本。 +它积极观察了光盘系统的数据空间,监测出版物。 通过[uXRCE-DDS桥](../middleware/uxrce_dds.md)或外空委2应用源于PX4的订阅和服务。 +必要时,它会将消息转换到应用程序和PX4预期的当前版本,确保兼容性。 -![Overview ROS 2 Message Translation Node](../../assets/middleware/ros2/px4_ros2_interface_lib/translation_node.svg) +![概述ROS 2消息转换节点] +(../../assets/middleware/ros2/px4_ros2_interface_lib/translation_node.svg) -To support the coexistence of different versions of the same messages within the ROS 2 domain, the ROS 2 topic-names for publications, subscriptions, and services include their respective message version as a suffix. -This naming convention takes the form `_v`, as shown in the diagram above. +支持不同版本的同一消息在交战规则2域内共存, 出版、订阅和服务的ROS 2主题名称包括各自的信息版本的后缀。 +这个命名协议的形式为`_v`。 ## 用法 ### 安装 -The following steps describe how to install and run the translation node on your machine. +以下步骤描述如何在您的机器上安装和运行翻译节点。 -1. (Optional) Create a new ROS 2 workspace in which to build the message translation node and its dependencies: +1. (可选) 创建一个新的 ROS2 工作空间,用于构建消息翻译节点及其依赖: ```sh mkdir -p /path/to/ros_ws/src ``` -2. Run the following helper script to copy the message definitions and translation node into your ROS workspace directory. +2. 运行下面的帮助脚本来复制消息定义并将节点翻译到您的ROS工作区目录。 ```sh cd /path/to/ros_ws /path/to/PX4-Autopilot/Tools/copy_to_ros_ws.sh . ``` -3. Build and source the workspace. +3. 构建并源自工作区。 ```sh colcon build source /path/to/ros_ws/install/setup.bash ``` -4. Finally, run the translation node. +4. 最后,运行翻译节点。 ```sh ros2 run translation_node translation_node_bin ``` - You should see an output similar to: + 您应该看到一个相似的输出: ```sh - [INFO] [1734525720.729530513] [translation_node]: Registered pub/sub topics and versions: - [INFO] [1734525720.729594413] [translation_node]: Registered services and versions: + [INFO] [1734525720.729530513] [translation_node]: 注册的 pub/子主题和版本: + [INFO] [1734525720.729594413] [translation_node]: 注册的服务和版本: ``` -With the translation node running, any simultaneously running ROS 2 application designed to communicate with PX4 can do so, as long as it uses message versions recognized by the node. -The translation node will print a warning if it encounters an unknown topic version. +在正在运行翻译节点时,任何同时运行旨在与 PX4 通信的 ROS 2 应用程序都可以这样做。 只要它使用节点承认的消息版本。 +翻译节点如果遇到未知的主题版本,将打印警告。 :::info -After making a modification in PX4 to the message definitions and/or translation node code, you will need to rerun the steps above from point 2 to update your ROS workspace accordingly. +在 PX4 修改消息定义和/或翻译节点代码后, 您需要从点2重新运行以上步骤来相应更新您的ROS工作区。 ::: ### 在ROS 应用中 -While developing a ROS 2 application that communicates with PX4, it is not necessary to know the specific version of a message being used. -The message version can be added generically to a topic name like this: +开发与 PX4 通信的 ROS 2 应用程序时,不必知道正在使用的消息的特定版本。 +消息版本可以以如以下方式一般添加到主题名称中: :::: tabs :::tab C++ ```c++ -topic_name + "_v" + std::to_string(T::MESSAGE_VERSION) +主题名称+ "_v" + std::to_string(T::MESSAGE_VERSION) ``` ::: @@ -83,30 +84,30 @@ topic_name + "_v" + std::to_string(T::MESSAGE_VERSION) :::tab Python ```python -topic_name + "_v" + VehicleAttitude.MESSAGE_VERSION +主题名称 + "_v" + VehicleAttitude.MESSAGE_VERSION ``` ::: :::: -where `T` is the message type, e.g. `px4_msgs::msg::VehicleAttitude`. +其中‘T’消息类型,例如`px4_msgs::msg::VehicleAttitude`. -For example, the following implements a minimal subscriber and publisher node that uses two versioned PX4 messages and topics: +例如,以下是一个实现最小化订阅者和发布者节点的示例,该节点使用两个带版本的 PX4 消息和主题: :::: tabs :::tab C++ ```c++ -#include -#include -#include -#include +#include <0> +#include <1> +#include <2> +#include <3> // Template function to get the message version suffix // The correct message version is directly inferred from the message defintion -template +template <4> std::string getMessageNameVersion() { if (T::MESSAGE_VERSION == 0) return ""; return "_v" + std::to_string(T::MESSAGE_VERSION); @@ -116,13 +117,13 @@ class MinimalPubSub : public rclcpp::Node { public: MinimalPubSub() : Node("minimal_pub_sub") { // Use template function to define the correct topics automatically - const std::string sub_topic = "/fmu/out/vehicle_attitude" + getMessageNameVersion(); - const std::string pub_topic = "/fmu/in/vehicle_command" + getMessageNameVersion(); + const std::string sub_topic = "/fmu/out/vehicle_attitude" + getMessageNameVersion<5>(); + const std::string pub_topic = "/fmu/in/vehicle_command" + getMessageNameVersion<6>(); - _subscription = this->create_subscription( + _subscription = this->create_subscription<5>( sub_topic, 10, std::bind(&MinimalPubSub::attitude_callback, this, std::placeholders::_1)); - _publisher = this->create_publisher(pub_topic, 10); + _publisher = this->create_publisher<6>(pub_topic, 10); } private: @@ -130,8 +131,8 @@ class MinimalPubSub : public rclcpp::Node { RCLCPP_INFO(this->get_logger(), "Received attitude message."); } - rclcpp::Publisher::SharedPtr _publisher; - rclcpp::Subscription::SharedPtr _subscription; + rclcpp::Publisher<6>::SharedPtr _publisher; + rclcpp::Subscription<5>::SharedPtr _subscription; }; ``` @@ -180,34 +181,34 @@ class MinimalPubSub(Node): :::: -On the PX4 side, the DDS client automatically adds the version suffix if a message definition contains the field `uint32 MESSAGE_VERSION = x`. +在 PX4 侧,如果消息定义包含字段`uint32 MESSAGE_VERSION = x`,DDS客户端自动添加版本后缀。 :::info 主题版本0意味着不应添加`_v`后缀。 ::: -## Development +## 开发 -### Definitions +### 定义 -A **message** defines the data format used for communication, whether over a topic or a service. -Therefore a message can be either a _topic_ message defined by a `.msg` file, or a _service_ message defined by a `.srv` file. +**消息** 定义了用于通信的数据格式,无论是主题还是服务。 +因此,消息可以是 ".msg" 文件定义的 _topic_ 消息,也可以是 ".srv" 文件定义的 _service_ 消息。 -A **versioned message** is a message for which changes are tracked and each change results in a version bump, with the previous state of the definition being stored in history. -The latest version of every message is stored in `msg/versioned/` for topics (or `srv/versioned` for services), and all older versions are stored in `msg/px4_msgs_old/msg/` (or `msg/px4_msgs_old/srv/`). +**版本信息** 是指跟踪更改的消息,每次变更都会导致版本号递增,且定义的历史状态会被保存下来。 +每个消息的最新版本都存储在 `msg/versioned/` 中,用于主题(或`srv/versioned` 用于服务), 所有旧版本都存储在`msg/px4_msgs_old/msg/`(或`msg/px4_msgs_old/srv/`)中。 -A **version translation** defines a bidirectional mapping of the contents of one or more message definition across different versions. -Each translation is stored as a separate `.h` header file under `msg/translation_node/translations/`. -Message translations can be either _direct_ or _generic_. +**版本翻译**定义了一个或多个消息定义的内容在不同版本之间的双向映射。 +每个翻译以单独的 .h 头文件形式存储在 msg/translation_node/translations/ 目录下。 +消息翻译可以是 _direct_或 _generic_。 -- A **direct translation** defines a bidirectional mapping of the contents of a _single_ message between two of its versions. - This is the simpler case and should be preferred if possible. -- A **generic translation** defines a bidirectional mapping of the contents of `n` input messages to `m` output messages across different versions. - This can be used for merging or splitting a message, or when moving a field from one message to another. +- **直接翻译** 定义一个双向映射其两个版本之间消息的内容。 + 这是更简单的情况,在可能的情况下应优先选择。 +- **通用翻译** 定义了双向映射`n`输入消息的内容到不同版本的`m`输出消息。 + 这可用于合并或拆分消息,也可用于将某个字段从一个消息迁移至另一个消息。 ### File Structure -Starting from PX4 v1.16, the PX4-Autopilot `msg/` and `srv/` directories are structured as follows: +从 PX4 v1.16 版本开始,PX4-Autopilot(PX4 自动驾驶系统)的 msg/ 和 srv/ 目录结构如下: ``` PX4-Autopilot @@ -222,15 +223,15 @@ PX4-Autopilot └── versioned/ # Latest versioned service message files ``` -This structure introduces new directories: `versioned/`, `px4_msgs_old/`, and `translation_node/`. +这个结构引入了新的目录:“versioned/`,`px4_msgs_old/`,以及`translation_node/\`。 -#### Directories `msg/versioned/` and `srv/versioned/` +#### 目录`msg/versioned/` 和 `srv/versioned/` -- Contain the current latest version of each message. -- Files in these directories must include a `MESSAGE_VERSION` field to indicate that they are versioned. -- File names follow the conventional naming scheme (without a version suffix). +- 包含每条消息当前的最新版本。 +- 这些目录中的文件必须包含 `MESSAGE_VERSION` 字段以表明它们是版本控制。 +- 文件名遵循常规命名规则(不带版本后缀)。 -Example directory structure: +示例目录结构: ``` PX4-Autopilot @@ -244,13 +245,13 @@ PX4-Autopilot └── VehicleCommand.srv # e.g. MESSAGE_VERSION = 2 ``` -#### Directory `px4_msgs_old/` +#### 目录`px4_msgs_old/` -- Archives the history of all versioned messages, including both topic and service messages (resp. under `msg/` and `srv/` subdirectories). -- Each file includes a `MESSAGE_VERSION` field. -- File names reflect the message's version with a suffix (e.g., `V1`, `V2`). +- 将所有版本信息的历史记录存档,包括主题和服务信息(resp. under `msg/`和`srv/`子目录)。 +- 每个文件都包含一个 MESSAGE_VERSION 字段。 +- 文件名反映了带有后缀的消息版本(如:`V1`、`V2`)。 -Example directory structure (matching the example above): +示例目录结构(匹配上面的示例): ``` ... @@ -264,13 +265,13 @@ Example directory structure (matching the example above): └── VehicleCommandV1.srv ``` -#### Directory `translation_node/` +#### 目录`translation_node/` -- Contains headers for translating between all different versions of messages. -- Each translation (direct or generic) is a single `.h` header file. -- The header `all_translation.h` acts as the main header, and includes all subsequent translation headers. +- 包含用于在所有不同版本的消息之间进行翻译的标题。 +- 每个翻译 (直接或通用) 都是单个的 `.h` 标题文件。 +- 标题`all_translation.h`是主标题,包含所有其后的翻译标题。 -Example directory structure (matching the example above): +示例目录结构(匹配上面的示例): ``` ... @@ -287,36 +288,36 @@ Example directory structure (matching the example above): └── translation_vehicle_command_v2.h # Direct translation v1 <-> latest (v2) ``` -### Updating a Versioned Message +### 正在更新版本信息... -This section provides a step-by-step walkthrough and a basic working example of what the process of changing a versioned message looks like. +本节提供了分步操作指南以及一个基础的可运行示例,以展示修改版本化消息的流程具体是怎样的。 -The example describes the process of updating the `VehicleAttitude` message definition to contain an additional `new_field` entry, incrementing the message version from `3` to `4`, and creating a new direct translation in the process. +该示例描述了更新VehicleAttitude消息定义的流程,具体包括:为其添加一个额外的new_field字段、将消息版本从3递增至4,并在此过程中创建一个新的直接转换。 -1. **Create an Archived Definition of the Current Versioned Message** +1. **创建当前版本信息的存档定义** - Copy the versioned `.msg` topic message file (or `.srv` service message file) to `px4_msgs_old/msg/` (or `px4_msgs_old/srv/`), and append its message version to the file name. + 将版本号的`.msg`主题消息文件(或`.srv`服务消息文件)复制到`px4_msgs_old/msg/`(或`px4_msgs_old/srv/`),并将其消息版本附加到文件名。 - For example:
- Copy `msg/versioned/VehicleAttitude.msg` → `msg/versioned/px4_msgs_old/msg/VehicleAttitudeV3.msg` + 例如:
+ 复制 `msg/versioned/VehicleAttitude.msg` → `msg/versioned/px4_msgs_old/msg/VehicleAttitudeV3.msg` -2. **Update Translation References to the Archived Definition** +2. **更新对存档定义的转化引用** - Update the existing translations header files `msg/translation_node/translations/*.h` to reference the newly archived message definition. + 更新现有翻译标头文件 `msg/translation_node/translations/*.h` 以参考新存档的消息定义。 - For example, update references in those files:
+ 例如,更新这些文件中的引用:
- - Replace `px4_msgs::msg::VehicleAttitude` → `px4_msgs_old::msg::VehicleAttitudeV3` - - Replace `#include ` → `#include ` + - 替换 `px4_msgs::msg::VehicleAttitude` → `px4_msgs_old::msg::VehicleAttitudeV3` + - 替换`#include ` -> \`#include -3. **Update the Versioned Definition** +3. **更新版本定义** - Update the versioned `.msg` topic message file (or `.srv` service message file) with required changes. + 更新版本的 `.msg` 主题消息文件 (或`.srv` 服务消息文件) 并进行必要的更改。 - First increment the `MESSAGE_VERSION` field. - Then update the message fields that prompted the version change. + 第一次递增`MESSAGE_VERSION`字段。 + 然后更新促使版本变更的消息字段。 - For example, update `msg/versioned/VehicleAttitude.msg` from: + 例如,更新 `msg/versioned/vehicleAttitde.msg` 从: ```txt uint32 MESSAGE_VERSION = 3 @@ -324,20 +325,19 @@ The example describes the process of updating the `VehicleAttitude` message defi ... ``` - to + 到 ```txt uint32 MESSAGE_VERSION = 4 # Increment uint64 timestamp float32 new_field # Make definition changes - ... ``` -4. **Add a New Translation Header** +4. **添加新的翻译标头** - Add a new version translation to bridge the archived version and the updated current version, by creating a new translation header. + 通过创建一个新的翻译标头来添加一个新的版本翻译来连接存档版本和更新的当前版本。 - For example, create a direct translation header `translation_node/translations/translation_vehicle_attitude_v4.h`: + 例如,创建一个直接翻译标题`translation_node/translation_vaille_attitude_v4.h`: ```c++ // Translate VehicleAttitude v3 <--> v4 @@ -381,72 +381,70 @@ The example describes the process of updating the `VehicleAttitude` message defi // Discards `new_field` from MessageNewer } }; - - REGISTER_TOPIC_TRANSLATION_DIRECT(VehicleAttitudeV4Translation); ``` - Version translation templates are provided here: + 版本翻译模板在此提供: - [Direct Topic Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_direct_v1.h) - [Generic Topic Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_multi_v2.h) - [Direct Service Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_service_v1.h) -5. **Include New Headers in `all_translations.h`** +5. **在`all_translations.h`中包含新标头** - Add all newly created headers to [`translations/all_translations.h`](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/all_translations.h) so that the translation node can find them. + 将所有新创建的标题添加到[`translations/all_translations.h`](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/all_translations.h),以便翻译节点能够找到它们。 - For example, append the following line to `all_translation.h`: + 例如,在`all_translation.h`上加上以下一行: ```c++ #include "translation_vehicle_attitude_v4.h" ``` -Note that in the example above and in most cases, step 4 only requires the developer to create a direct translation for the definition change. -This is because the changes only involved a single message. -In more complex cases of splitting, merging and/or moving definitions then a generic translation must be created. +请注意,在上述示例中以及在大多数情况下,步骤 4 仅要求开发者针对此次定义变更创建一个直接转换。 +这是因为更改只涉及一个消息。 +在更复杂的分割、合并和/或移动定义的情况下,必须创建一个通用转化。 -For example when moving a field from one message to another, a single generic translation should be added with the two older message versions as input, and the two newer versions as output. -This ensures there is no information lost when translating forward or backward. +例如,当一个字段从一个消息移动到另一个消息时。 应增加一个单一通用翻译,两个较旧的信息版本作为输入,两个较新的版本作为输出。 +这就确保了在向前或向后翻译时不会丢失信息。 -This is exactly the approach shown by the [Generic Topic Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_multi_v2.h), omitting only the code for actually modifying fields in the `fromOlder()` and `toOlder()` methods. +这正是 [Generic Topic Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_multi_v2.h) 所显示的方法。 只省略`fromOlder()` 和 `toOlder()` 方法中的字段的代码。 :::warning -If a nested message definition changes, all messages including that message also require a version update. -For example this would be the case for message [PositionSetpointTriplet](../msg_docs/PositionSetpointTriplet.md) if it were versioned. -This is primarily important for services which are more likely reference other message definitions. +如果嵌套消息定义发生了变化,包括该消息在内的所有消息也需要版本更新。 +例如,如果消息 [PositionSetpointTriplet](../msg_docs/PositionSetpointTriplet.md)有版本,将会出现这种情况。 +这一点对于服务而言尤为重要,因为服务更有可能引用其他消息定义。 ::: -## Implementation Details +## 实现细节 -The translation node dynamically monitors the topics and services. -It then instantiates the counterside of the publications and subscribers as required. -For example if there is an external publisher for version 1 of a topic and subscriber for version 2. +转换节点动态监测主题和服务。 +然后视需要举例说明出版物和订阅者的对应情况。 +例如,如果主题第1版有外部发行商,第2版则有订阅商。 -Internally, it maintains a graph of all known topic and version tuples (which are the graph nodes). -The graph is connected by the message translations. -As arbitrary message translations can be registered, the graph can have cycles and multiple paths from one node to another. -Therefore on a topic update, the graph is traversed using a shortest path algorithm. -When moving from one node to the next, the message translation method is called with the current topic data. -If a node contains an instantiated publisher (because it previously detected an external subscriber), the data is published. -Thus, multiple subscribers of any version of the topic can be updated with the correct version of the data. +在内部,它保存一份所有已知主题和版本管束的图表(即图节点)。 +该图通过消息转换实现连接。 +由于任意的消息转换可以注册,图可以有周期和从一个节点到另一个节点的多个路径。 +因此,在主题更新中,图形使用最短路径算法。 +当从一个节点移动到另一个节点时,消息翻译方法将与当前主题数据调用。 +如果节点包含实例化发布器 (因为它先前检测到外部订阅者),数据将被发布。 +这样,本专题任何版本的多个订阅者都可以用正确的数据更新数据。 -For translations with multiple input topics, the translation continues once all input messages are available. +对于有多个输入主题的转化,转化将在所有输入消息都可用后继续。 ## 局限 -- Translation of service messages does not work on ROS Humble, but does on ROS Jazzy. - This is because the current implementation depends on a service API that is not yet available in ROS Humble. - Translation of topic messages is fully supported. -- Services messages only support a linear history, i.e. no message splitting or merging. -- Having both publishers and subscribers for two different versions of the same topic is currently not handled by the translation node and would trigger infinite circular publications. - This refers to the following problematic configuration: +- 服务消息的转化不适用于 ROS Humble,而是适用于ROSJazzy。 + 这是因为当前的实现取决于尚未在ROS人类中提供的服务 API 。 + 完全支持主题信息转化。 +- 服务消息只支持线性历史记录,即没有消息拆分或合并。 +- 两个不同版本的同一主题的出版商和订户目前都不是由转化节点处理的,会引发无限的循环出版物。 + 这是指下列有问题的配置: ``` app 1: pub topic_v1, sub topic_v1 app 2: pub topic_v2, sub topic_v2 ``` - In practice this configuration is unlikely to occur because ROS topics shared with the FMU are intended to be directional (e.g. `/fmu/out/vehicle_status` or `/fmu/in/trajectory_setpoint`), therefore apps typically do not publish and subscribe simultaneously to the same topic. - The translation node could be extended to handle this corner-case if required. + 实际上,这种配置不大可能发生,因为与金融监督单位共享的外空系统专题是指向的(例如)。 `/fmu/out/vehicle_status` 或 `/fmu/in/tracjectory_setpoint` ,因此应用通常不会同时发布和订阅相同的主题。 + 如果需要,可以扩展翻译节点来处理这个卷轴。 -Original document with requirements: https://docs.google.com/document/d/18_RxV1eEjt4haaa5QkFZAlIAJNv9w5HED2aUEiG7PVQ/edit?usp=sharing +需要原始文件:https://docs.google.com/document/d/18_RxV1eEjt4haaa5QkFZAlIAJNv9w5HED2aUEiG7PVQ/edit?usp=sharing diff --git a/docs/zh/ros2/px4_ros2_navigation_interface.md b/docs/zh/ros2/px4_ros2_navigation_interface.md index c726973a17..120183b7e1 100644 --- a/docs/zh/ros2/px4_ros2_navigation_interface.md +++ b/docs/zh/ros2/px4_ros2_navigation_interface.md @@ -7,16 +7,16 @@ Experimental 在撰写本文时,PX4 ROS 2 接口库的部分内容仍处于试验阶段,因此可能会发生变动。 ::: -The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) navigation interface enables developers to send their position measurements to PX4 directly from ROS 2 applications, such as a VIO system or a map matching system. -The interface provides a layer of abstraction from PX4 and the uORB messaging framework, and introduces a few sanity checks on the requested state estimation updates sent via the interface. -These measurements are then fused into the EKF just as though they were internal PX4 measurements. +[PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) 中的导航接口,支持开发者直接从 ROS 2 应用(如视觉惯性里程计系统或地图匹配系统)向 PX4 发送位置测量数据。 +该接口提供了对 PX4 和 uORB 消息框架的抽象层,并对通过该接口发送的请求状态估计更新引入了一些合理性检查。 +这些测量数据随后会被融合到扩展EKF中,其处理方式与 PX4 内部生成的测量数据完全一致。 -The library provides two classes, [`LocalPositionMeasurementInterface`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1LocalPositionMeasurementInterface.html) and [`GlobalPositionMeasurementInterface`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1GlobalPositionMeasurementInterface.html), which both expose a similar `update` method to provide either a local position or global position update to PX4, respectively. -The `update` method expects a position measurement `struct` ([`LocalPositionMeasurement`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1LocalPositionMeasurement.html) or [`GlobalPositionMeasurement`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1GlobalPositionMeasurement.html)) which developers can populate with their own generated position measurements. +库提供两个类,[`LocalPositionMeasurementInterface`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1LocalPositionMeasurementInterface.html) 和 [`GlobalPositionMeasureInterface`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1GlobalPositionMeasurementInterface.html) 它都会暴露出一个类似的 "update" 方法来提供一个本地位置或全球位置更新到 PX4。 +`update`方法需要一个位置测量`struct`(`LocalPositionMeasure`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1LocalPositionMeasurement.html)或[\`GlobalPositionMeasure\`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1GlobalPositionMeasurement.html)],开发者可以在其中填入自己生成的位置测量数据。 -## Installation and First Test +## 安装与首次测试 -The following steps are required to get started: +开始使用前,需完成以下步骤: 1. 请确保您在 ROS 2 工作区中有 [ROS 2 设置](../ros2/user_guide.md) 与 [`px4_msgs`](https://github.com/PX4/px4_msgs]。 @@ -37,32 +37,32 @@ The following steps are required to get started: ```sh cd .. - colcon build + colcon版本 ``` -4. In a different shell, start PX4 SITL: +4. 在另一个外壳中,启动 PX4 SITL: ```sh cd $px4-autopilot make px4_sitl gazebo-classic ``` - (here we use Gazebo-Classic, but you can use any model or simulator) + (这里我们使用Gazebo-Classic,但你可以使用任何模型或模拟器) -5. In yet a different shell, run the micro XRCE agent (you can keep it running afterward): +5. 在另一个独立的终端中,运行 micro XRCE 代理(运行后可保持后台持续运行): ```sh MicroXRCEAgent udp4 -p 8888 ``` -6. Back in the ROS 2 terminal, source the workspace you just built (in step 3) and run the [global_navigation](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/navigation/global_navigation) example, which periodically sends dummy global position updates: +6. 返回ROS2终端,为您刚刚构建的工作空间(步骤3),运行 [global_navigation](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/navigation/global_navigation) 示例。 它会周期性地发送虚拟的全球位置更新(数据): ```sh source install/setup.bash ros2 run example_global_navigation_cpp example_global_navigation ``` - You should get an output like this showing that the global interface is successfully sending position updates: + 你应会看到如下所示的输出,该输出表明全球位置接口正成功发送位置更新: ```sh [INFO] [1702030701.836897756] [example_global_navigation_node]: example_global_navigation_node running! @@ -70,13 +70,13 @@ The following steps are required to get started: [DEBUG] [1702030703.837223884] [example_global_navigation_node]: Successfully sent position update to navigation interface. ``` -7. In the PX4 shell, you can check that PX4 receives global position updates: +7. 在 PX4 终端(PX4 shell)中,你可以通过以下操作检查 PX4 是否接收到全球位置更新(数据) ```sh listener aux_global_position ``` - The output should look like: + 输出内容应如下所示: ```sh TOPIC: aux_global_position @@ -97,31 +97,31 @@ The following steps are required to get started: dead_reckoning: False ``` -8. Now you are ready to use the navigation interface to send your own position updates. +8. 现在你已准备好使用该导航接口发送自己的位置更新数据了。 -## How to use the Library +## 如何使用代码库 -To send a position measurement, you populate the position struct with the values you have measured. -Then call the interface's update function with that struct as the argument. +要发送位置测量数据,你需要用所测量的值填充位置结构体。 +然后以此结构调用接口的更新功能作为参数。 -For a basic example of how to use this interface, check out the [examples](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/navigation) in the `Auterion/px4-ros2-interface-lib` repository, such as [examples/cpp/navigation/local_navigation](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/examples/cpp/navigation/local_navigation/include/local_navigation.hpp) or [examples/cpp/navigation/global_navigation](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/examples/cpp/navigation/local_navigation/include/global_navigation.hpp). +关于如何使用此接口的基本示例,请在“Auterion/px4-ros2-interface-lib”仓库中查看 [examples](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/navigation) 例如[示例/cpp/navigation/local_navigation](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/examples/cpp/navigation/local_navigation/include/local_navigation.hpp)或[示例/cpp/navigation/global_navigation](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/examples/cpp/navigation/local_navigation/include/global_navigation.hpp)。 -### Local Position Updates +### 局部位置更新 -First ensure that the PX4 parameter [`EKF2_EV_CTRL`](../advanced_config/parameter_reference.md#EKF2_EV_CTRL) is properly configured to fuse external local measurements, by setting the appropriate bits to `true`: +首先确保正确配置 PX4 参数[`EKF2_EV_CTRL`](../advanced_config/parameter_reference.md#EKF2_EV_CTRL)通过将相应的位设置为true,可以正确配置(系统)以融合外部局部测量数据: -- `0`: Horizontal position data -- `1`: Vertical position data -- `2`: Velocity data -- `3`: Yaw data +- `0`: 水平位置数据 +- `1`:垂直位置数据 +- `2`:速度数据 +- `3`:偏航角数据 -To send a local position measurement to PX4: +向PX4发送局部位置测量: -1. Create a [`LocalPositionMeasurementInterface`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1LocalPositionMeasurementInterface.html) instance by providing it with: a ROS node, and the pose and velocity reference frames of your measurements. -2. Populate a [`LocalPositionMeasurement`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1LocalPositionMeasurement.html) `struct` with your measurements. -3. Pass the `struct` to the `LocalPositionMeasurementInterface` [`update()`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1LocalPositionMeasurementInterface.html#a6fd180b944710716d418b2cfe1c0c8e3) method. +1. 通过提供一个 ROS节点,创建一个 [`localPositionMeasureInterface` ](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1LocalPositionMeasurementInterface.html) 实例:您测量的位置和速度参考框架。 +2. 包含一个[`本地定位测量`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1LocalPositionMeasurement.html) `structt` ,包含你测量的数据。 +3. 将 `struct` 传入 `LocalPositionMeasurementInterface` [`update()`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1LocalPositionMeasurementInterface.html#a6fd180b944710716d418b2cfe1c0c8e3) 方法中。 -The available pose and velocity reference frames for your measurements are defined by the following `enum`: +你的测量数据可用的位置和速度参考坐标系由以下枚举(enum)定义: ```cpp enum class PoseFrame @@ -140,36 +140,36 @@ enum class VelocityFrame }; ``` -The `LocalPositionMeasurement` struct is defined as follows: +`LocalPositionMeasurement`结构定义如下: ```cpp struct LocalPositionMeasurement { rclcpp::Time timestamp_sample {}; - std::optional position_xy {std::nullopt}; - std::optional position_xy_variance {std::nullopt}; - std::optional position_z {std::nullopt}; - std::optional position_z_variance {std::nullopt}; + std::optional<0> position_xy {std::nullopt}; + std::optional<0> position_xy_variance {std::nullopt}; + std::optional<1> position_z {std::nullopt}; + std::optional<1> position_z_variance {std::nullopt}; - std::optional velocity_xy {std::nullopt}; - std::optional velocity_xy_variance {std::nullopt}; - std::optional velocity_z {std::nullopt}; - std::optional velocity_z_variance {std::nullopt}; + std::optional<0> velocity_xy {std::nullopt}; + std::optional<0> velocity_xy_variance {std::nullopt}; + std::optional<1> velocity_z {std::nullopt}; + std::optional<1> velocity_z_variance {std::nullopt}; - std::optional attitude_quaternion {std::nullopt}; - std::optional attitude_variance {std::nullopt}; + std::optional<2> attitude_quaternion {std::nullopt}; + std::optional<3> attitude_variance {std::nullopt}; }; ``` -The `update()` method of the local interface expects the following conditions to hold for `LocalPositionMeasurement`: +局部接口的update()方法要求LocalPositionMeasurement(局部位置测量结构体)满足以下条件: -- The sample timestamp is defined. -- Values do not have a \`NAN\`\`. -- If a measurement value is provided, its associated variance value is well defined (e.g. if `position_xy` is defined, then `position_xy_variance` must be defined). -- If a measurement value is provided, its associated reference frame is not unknown (e.g. if `position_xy` is defined, then the interface was initialised with a pose frame different from `PoseFrame::Unknown`). +- 示例时间戳已定义。 +- 数值不得包含 `NAN` 。 +- 如果提供了某个测量值,则其关联的方差值必须明确定义(例如,若position_xy已定义,则position_xy_variance也必须定义)。 +- 如果提供了某个测量值,那么其关联的参考坐标系不得为 “未知”(例如,若position_xy已定义,则接口必须以不同于PoseFrame::Unknown的位置坐标系进行初始化)。 -The following code snippet is an example of a ROS 2 node which uses the local navigation interface to send 3D pose updates in the North-East-Down (NED) reference frame to PX4: +以下是一个 ROS 2 节点的示例代码片段,该节点使用局部导航接口向 PX4 发送东北天(NED)参考坐标系下的 3D 位姿更新: ```cpp class MyLocalMeasurementUpdateNode : public rclcpp::Node @@ -185,7 +185,7 @@ public: const px4_ros2::VelocityFrame velocity_frame = px4_ros2::VelocityFrame::Unknown; // Initialize local interface [1] _local_position_measurement_interface = - std::make_shared(*this, pose_frame, velocity_frame); + std::make_shared(*this, pose_frame, velocity_frame); } void sendUpdate() @@ -217,45 +217,44 @@ public: } private: - std::shared_ptr _local_position_measurement_interface; + std::shared_ptr _local_position_measurement_interface; }; ``` -### Global Position Updates +### 全局位置更新 -First ensure that the PX4 parameter [`EKF2_AGP_CTRL`](../advanced_config/parameter_reference.md#EKF2_AGP_CTRL) is properly configured to fuse external global measurements, by setting the appropriate bits to `true`: +首先确保正确配置 PX4 参数[`EKF2_EV_CTRL`](../advanced_config/parameter_reference.md#EKF2_AGP_CTRL)通过将相应的位设置为true,可以正确配置(系统)以融合外部全部测量数据: -- `0`: Horizontal position data -- `1`: Vertical position data +- `0`: 水平位置数据 +- `1`:垂直位置数据 -To send a global position measurement to PX4: +向PX4发送全局位置测量: -1. Create a [`GlobalPositionMeasurementInterface`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1GlobalPositionMeasurementInterface.html) instance by providing it with a ROS node. -2. Populate a [`GlobalPositionMeasurement`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1GlobalPositionMeasurement.html) `struct` with your measurements. -3. Pass the struct to the `GlobalPositionMeasurementInterface` [update()](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1GlobalPositionMeasurementInterface.html#a1a183b595ef7f6a22f3a83ba543fe86d) method. +1. 创建一个 [`GlobalPositionMeasureInterface`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1GlobalPositionMeasurementInterface.html) 实例,并提供一个 ROS节点。 +2. 包含一个[`GlobalPositionMeasurement`](https://auterion.github.io/px4-ros2-interface-lib/structpx4__ros2_1_1GlobalPositionMeasurement.html) `struct` ,包含你测量的数据。 +3. 将结构移至`GlobalPositionMeasurementInterface` [update()](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1GlobalPositionMeasurementInterface.html#a1a183b595ef7f6a22f3a83ba543fe86d) 方法中。 -The `GlobalPositionMeasurement` struct is defined as follows: +`GlobalPositionMeasurement`结构定义如下: ```cpp struct GlobalPositionMeasurement { rclcpp::Time timestamp_sample {}; - std::optional lat_lon {std::nullopt}; - std::optional horizontal_variance {std::nullopt}; + std::optional lat_lon {std::nullopt}; + std::optional<1> horizontal_variance {std::nullopt}; - std::optional altitude_msl {std::nullopt}; - std::optional vertical_variance {std::nullopt}; -}; + std::optional<1> altitude_msl {std::nullopt}; + std::optional<1> vertical_variance {std::nullopt}; ``` -The `update()` method of the global interface expects the following conditions to hold for `GlobalPositionMeasurement`: +全局接口的 `update()` 方法预计在 `GlobalPositionMeasurement` 中保留以下条件: -- The sample `timestamp_sample` is defined. -- Values do not have a NAN. -- If a measurement value is provided, its associated variance value is well defined (e.g. if `lat_lon` is defined, then `horizontal_variance` must be defined). +- 样本`timestamp_sample`已定义。 +- 数据不得包含NAN。 +- 如果提供了某个测量值,那么其关联的方差值必须明确定义(例如,若lat_lon(经纬度)已定义,则horizontal_variance(水平方差)也必须定义)。 -The following code snippet is an example of a ROS 2 node which uses the global navigation interface to send a measurement with latitude, longitude and altitude to PX4: +下面的代码片段是一个 ROS 2 节点的示例,该节点使用全局导航接口来发送一个测量纬度。 经度和高度到 PX4: ```cpp class MyGlobalMeasurementUpdateNode : public rclcpp::Node @@ -266,7 +265,7 @@ public: { // Initialize global interface [1] _global_position_measurement_interface = - std::make_shared(*this); + std::make_shared(*this); } void sendUpdate() @@ -298,11 +297,11 @@ public: } private: - std::shared_ptr _global_position_measurement_interface; + std::shared_ptr<0> _global_position_measurement_interface; }; ``` -## Multiple Instances of an Interface +## 接口的多个实例 -Using multiple instances of the same interface (e.g. local and local) to send estimation updates will stream all update messages to the same topic and result in cross-talk. -This should not affect measurement fusion into the EKF, but different measurement sources will become indistinguishable. +使用同一接口的多个实例(例如,多个局部接口实例)发送估计更新时,会将所有更新消息发送到同一个主题,从而导致串扰。 +这不应影响计量并入EKF,但不同的计量来源将无法区分。 diff --git a/docs/zh/ros2/user_guide.md b/docs/zh/ros2/user_guide.md index 0a8bff0037..2bf55616cd 100644 --- a/docs/zh/ros2/user_guide.md +++ b/docs/zh/ros2/user_guide.md @@ -5,11 +5,11 @@ ROS 2-PX4 架构在ROS 2和PX4之间进行了深度整合。 允许 ROS 2 订阅 本指南介绍了系统架构和应用程序流程,并解释了如何与PX4一起安装和使用ROS2。 :::info -From PX4 v1.14, ROS 2 uses [uXRCE-DDS](../middleware/uxrce_dds.md) middleware, replacing the _FastRTPS_ middleware that was used in version 1.13 (v1.13 does not support uXRCE-DDS). +从 PX4 v1.14, ROS 2 使用 [uXRCE-DDS](../middleware/uxrce_dds.md) 中间件替换版本 1 中使用的 _FastRTPS_ 中间件. 3 (v1.13不支持uXRCE-DDS)。 -The [migration guide](../middleware/uxrce_dds.md#fast-rtps-to-uxrce-dds-migration-guidelines) explains what you need to do in order to migrate ROS 2 apps from PX4 v1.13 to PX4 v1.14. +[migration guide](../middleware/uxrce_dds.md#fast-rtps-to-uxrce-dds-migration-guidelines) 解释您需要做什么来将ROS2 应用程序从 PX4 v1.13 迁移到 PX4 v1.14。 -If you're still working on PX4 v1.13, please follow the instructions in the [PX4 v1.13 Docs](https://docs.px4.io/v1.13/en/ros/ros2_comm.html). +如果您仍然在 PX4 v1.13 上工作,请按照[PX4 v1.13 文档](https://docs.px4.io/v1.13/en/ros/ros2_comm.html)中的说明操作。 @@ -17,66 +17,66 @@ If you're still working on PX4 v1.13, please follow the instructions in the [PX4 ## 综述 -The application pipeline for ROS 2 is very straightforward, thanks to the use of the [uXRCE-DDS](../middleware/uxrce_dds.md) communications middleware. +得益于 uXRCE-DDS(../middleware/uxrce_dds.md) 通信中间件的使用,ROS 2 的应用流程非常简单直接。 ![Architecture uXRCE-DDS with ROS 2](../../assets/middleware/xrce_dds/architecture_xrce-dds_ros2.svg) -The uXRCE-DDS middleware consists of a client running on PX4 and an agent running on the companion computer, with bi-directional data exchange between them over a serial, UDP, TCP or custom link. -The agent acts as a proxy for the client to publish and subscribe to topics in the global DDS data space. +uXRCE-DDS 中间件由两部分组成:一部分是运行在 PX4 上的客户端,另一部分是运行在伴飞计算机上的代理;二者之间通过串口、UDP、TCP或自定义链路进行双向数据交换。 +代理充当客户端的代理角色,以便在全局 DDS 数据空间中发布和订阅主题。 -The PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) is generated at build time and included in PX4 firmware by default. -It includes both the "generic" micro XRCE-DDS client code, and PX4-specific translation code that it uses to publish to/from uORB topics. -The subset of uORB messages that are generated into the client are specified in [dds_topics.yaml](../middleware/dds_topics.md). -The generator uses the uORB message definitions in the source tree: [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to create the code for sending ROS 2 messages. +PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) 是在构建时生成,并且默认包含在 PX4 固件中。 +它包含“通用”XRCE-DDS客户端代码和它用来发布到/来自uORB主题的 PX4 特定转换代码。 +生成到客户端中的 uORB 消息子集在 [dds_topics.yaml](../middleware/dds_topics.md)中说明。 +生成器使用源代码树中的 uORB 消息定义:[PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) 用于生成发送 ROS 2 消息的代码。 -ROS 2 applications need to be built in a workspace that has the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware. -You can include these by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your ROS 2 workspace (branches in the repo correspond to the messages for different PX4 releases). +ROS 2 应用程序需要在一个工作空间中构建,该工作空间需包含与 PX4 固件中创建 uXRCE-DDS 客户端模块时所用完全相同的消息定义。 +您可以通过克隆接口包[PX4/px4_msgs](https://github.com/PX4/px4_msgs)将这些内容纳入您的 ROS 2 工作空间(repo 中的范围与不同的 PX4 版本的消息相对应)。 -Starting from PX4 v1.16, in which [message versioning](../middleware/uorb.md#message-versioning) was introduced, ROS2 applications may use a different version of message definitions than those used to build PX4. -This requires the [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to be running to ensure that messages can be converted and exchanged correctly. +从 PX4 v1.16 版本开始[message versioning](../middleware/uorb.md#message-versioning),ROS 2 应用程序所使用的消息定义版本,可与构建 PX4 时所用的消息定义版本不同。 +这需要[ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md)运行ROS 2 消息转换节点,以确保消息能够正确转换和交互。 -Note that the micro XRCE-DDS _agent_ itself has no dependency on client-side code. -It can be built from [source](https://github.com/eProsima/Micro-XRCE-DDS-Agent) either standalone or as part of a ROS build, or installed as a snap. +需要注意的是,微型XRCE-DDS _agent_ 本身并不依赖客户端代码。 +它可以从 [source](https://github.com/eProsima/Micro-XRCE-DDS-Agent)中单独构建,或者作为ROS构建的一部分,或者作为snap包安装。 -You will normally need to start both the client and agent when using ROS 2. -Note that the uXRCE-DDS client is built into firmware by default but not started automatically except for simulator builds. +在使用 ROS 2 时,您通常需要同时启动客户端和代理。 +需要注意的是,uXRCE-DDS 客户端默认已内置到固件中,但除仿真器构建版本外,不会自动启动。 :::info -In PX4v1.13 and earlier, ROS 2 was dependent on definitions in [px4_ros_com](https://github.com/PX4/px4_ros_com). -This repo is no longer needed, but does contain useful examples. +在 PX4 v1.13 及更早版本中,ROS 2 依赖于 [px4_ros_com](https://github.com/PX4/px4_ros_com) 中的消息定义。 +该代码仓库已不再需要,但其中包含一些实用的示例。 ::: -## Installation & Setup +## 安装与设置 -The supported and recommended ROS 2 platform for working with PX4 is ROS 2 "Humble" LTS on Ubuntu 22.04. +支持和推荐使用 PX4 的 ROS 2 平台是 Ubuntu 的 ROS 2 “简易” LTS 22.04。 :::tip -If you're working on Ubuntu 20.04 we recommend you update to Ubuntu 22.04. -In the meantime you can use ROS 2 "Foxy" with [Gazebo Classic](../sim_gazebo_classic/index.md) on Ubuntu 20.04. -Note that ROS 2 "Foxy" reached end-of-life in May 2023, but is (at time of writing) still stable and works with PX4. +如果您在 Ubuntu 20.04 上工作,我们建议您更新到 Ubuntu 22.04。 +同时,你可以在 Ubuntu 20.04 上使用 [Gazebo Class](../sim_gazebo_classic/index.md) 的 ROS 2 "Foxy" 。 +请注意,第二号外空系统“Foxy”在2023年5月到达寿命终结,但在撰写本报告时仍然稳定并与PX4合作。 ::: -To setup ROS 2 for use with PX4: +安装使用 PX4 的 ROS 2: - [Install PX4](#install-px4) (to use the PX4 simulator) - [Install ROS 2](#install-ros-2) - [Setup Micro XRCE-DDS Agent & Client](#setup-micro-xrce-dds-agent-client) - [Build & Run ROS 2 Workspace](#build-ros-2-workspace) -Other dependencies of the architecture that are installed automatically, such as _Fast DDS_, are not covered. +该架构中会自动安装的其他依赖项(如 Fast DDS)未在此处提及。 ### 安装PX4 -You need to install the PX4 development toolchain in order to use the simulator. +若要使用该仿真器,你需要安装 PX4 开发工具链。 :::info -The only dependency ROS 2 has on PX4 is the set of message definitions, which it gets from [px4_msgs](https://github.com/PX4/px4_msgs). -You only need to install PX4 if you need the simulator (as we do in this guide), or if you are creating a build that publishes custom uORB topics. +唯一依赖于ROS2的 PX4 是一组信息定义,它从 [px4_msgs](https://github.com/PX4/px4_msgs)获取。 +您只需要安装 PX4 当您需要模拟器时(如我们在本指南中所做的那样), 或者如果您正在创建一个发布自定义uORB主题的构建。 ::: -Set up a PX4 development environment on Ubuntu in the normal way: +通过以下方式在 Ubuntu 上配置一个 PX4 开发环境: ```sh cd @@ -86,16 +86,16 @@ cd PX4-Autopilot/ make px4_sitl ``` -Note that the above commands will install the recommended simulator for your version of Ubuntu. -If you want to install PX4 but keep your existing simulator installation, run `ubuntu.sh` above with the `--no-sim-tools` flag. +请注意,上述命令将为您的Ubuntu版本安装推荐的模拟器。 +如果您想要安装 PX4,但保留您现有的模拟器安装,请使用 "--no-sim-tools" 标志运行 `ubuntu.sh`。 -For more information and troubleshooting see: [Ubuntu Development Environment](../dev_setup/dev_env_linux_ubuntu.md) and [Download PX4 source](../dev_setup/building_px4.md). +欲了解更多信息和故障排除,请参阅:[Ubuntu 开发环境](../dev_setup/dev_env_linux_ubuntu.md) 和 [下载 PX4 源](../dev_setup/building_px4.md)。 ### 安装 ROS 2 -To install ROS 2 and its dependencies: +安装 ROS 2 及其依赖: -1. Install ROS 2. +1. 安装 ROS 2. :::: tabs @@ -118,35 +118,35 @@ To install ROS 2 and its dependencies: source /opt/ros/humble/setup.bash && echo "source /opt/ros/humble/setup.bash" >> .bashrc ``` - The instructions above are reproduced from the official installation guide: [Install ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html). - You can install _either_ the desktop (`ros-humble-desktop`) _or_ bare-bones versions (`ros-humble-ros-base`), _and_ the development tools (`ros-dev-tools`). + 以上说明转载自官方安装指南:[Install ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html)。 + 您可以安装 _either_ the desktop (`ros-humble-desktop`) _or_ bare-bones versions (`ros-humble-ros-base`), _and_ the development tools (`ros-dev-tools`). ::: ::: tab foxy To install ROS 2 "Foxy" on Ubuntu 20.04: - - Follow the official installation guide: [Install ROS 2 Foxy](https://docs.ros.org/en/foxy/Installation/Ubuntu-Install-Debians.html). + - 按照官方安装指南: [Install ROS 2 Foxy](https://docs.ros.org/en/foxy/Installation/Ubuntu-Install-Debians.html). - You can install _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), _and_ the development tools (`ros-dev-tools`). + 您可以安装 _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), _and_ the development tools (`ros-dev-tools`). ::: :::: -2. Some Python dependencies must also be installed (using **`pip`** or **`apt`**): +2. 一些Python 依赖关系也必须安装 (使用 **`pip`** 或 **`apt`**): ```sh pip install --user -U empy==3.3.4 pyros-genmsg setuptools ``` -### Setup Micro XRCE-DDS Agent & Client +### 配置微型 XRCE-DDS 代理与客户端 -For ROS 2 to communicate with PX4, [uXRCE-DDS client](../modules/modules_system.md#uxrce-dds-client) must be running on PX4, connected to a micro XRCE-DDS agent running on the companion computer. +要实现 ROS 2 与 PX4 的通信,[uXRCE-DDS client](../modules/modules_system.md#uxrce-dds-client)必须在 PX4 上运行,且需与运行在机载计算机上的微型 XRCE-DDS 代理建立连接。 #### 设置代理(Agent) -The agent can be installed onto the companion computer in a [number of ways](../middleware/uxrce_dds.md#micro-xrce-dds-agent-installation). +代理可以安装在机载计算机上 [number of ways](../middleware/uxrce_dds.md#micro-xrce-dds-agent-installation)。 Below we show how to build the agent "standalone" from source and connect to a client running on the PX4 simulator. To setup and start the agent: @@ -156,7 +156,7 @@ To setup and start the agent: 2. 输入以下命令从仓库获取源代码并构建代理(Agent): ```sh - git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git + git clone -b v2.4.3 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git cd Micro-XRCE-DDS-Agent mkdir build cd build @@ -224,7 +224,6 @@ INFO [uxrce_dds_client] synchronized with time offset 1675929429203524us INFO [uxrce_dds_client] successfully created rt/fmu/out/failsafe_flags data writer, topic id: 83 INFO [uxrce_dds_client] successfully created rt/fmu/out/sensor_combined data writer, topic id: 168 INFO [uxrce_dds_client] successfully created rt/fmu/out/timesync_status data writer, topic id: 188 -... ``` The micro XRCE-DDS agent terminal should also start to show output, as equivalent topics are created in the DDS network: @@ -234,7 +233,6 @@ The micro XRCE-DDS agent terminal should also start to show output, as equivalen [1675929445.268957] info | ProxyClient.cpp | create_publisher | publisher created | client_key: 0x00000001, publisher_id: 0x0DA(3), participant_id: 0x001(1) [1675929445.269521] info | ProxyClient.cpp | create_datawriter | datawriter created | client_key: 0x00000001, datawriter_id: 0x0DA(5), publisher_id: 0x0DA(3) [1675929445.270412] info | ProxyClient.cpp | create_topic | topic created | client_key: 0x00000001, topic_id: 0x0DF(2), participant_id: 0x001(1) -... ``` ### Build ROS 2 Workspace @@ -378,7 +376,7 @@ accelerometer_integral_dt: 4739 #### (Optional) Starting the Translation Node - +<0/> <1/> This example is built with PX4 and ROS2 versions that use the same message definitions. If you were to use incompatible [message versions](../middleware/uorb.md#message-versioning) you would need to install and run the [Message Translation Node](./px4_ros2_msg_translation_node.md) as well, before running the example: @@ -607,7 +605,7 @@ The lines below create a publisher to the `SensorCombined` uORB topic, which can ````cpp private: - rclcpp::Subscription::SharedPtr subscription_; + rclcpp::Subscription::SharedPtr subscription_; }; ```s @@ -619,7 +617,7 @@ int main(int argc, char *argv[]) std::cout << "Starting sensor_combined listener node..." << std::endl; setvbuf(stdout, NULL, _IONBF, BUFSIZ); rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); + rclcpp::spin(std::make_shared()); rclcpp::shutdown(); return 0; @@ -835,7 +833,7 @@ where `request_vehicle_command` handles formatting the request and sending it ov ```cpp void OffboardControl::request_vehicle_command(uint16_t command, float param1, float param2) { - auto request = std::make_shared(); + auto request = std::make_shared(); VehicleCommand msg{}; msg.param1 = param1; @@ -860,7 +858,7 @@ The response is finally captured asynchronously by the `response_callback` metho ```cpp void OffboardControl::response_callback( - rclcpp::Client::SharedFuture future) { + rclcpp::Client<0>::SharedFuture future) { auto status = future.wait_for(1s); if (status == std::future_status::ready) { auto reply = future.get()->reply; @@ -941,17 +939,17 @@ The output will look something like: ```sh average rate: 248.187 - min: 0.000s max: 0.012s std dev: 0.00147s window: 2724 +min: 0.000s max: 0.012s std dev: 0.00147s window: 2724 average rate: 248.006 - min: 0.000s max: 0.012s std dev: 0.00147s window: 2972 +min: 0.000s max: 0.012s std dev: 0.00147s window: 2972 average rate: 247.330 - min: 0.000s max: 0.012s std dev: 0.00148s window: 3212 +min: 0.000s max: 0.012s std dev: 0.00148s window: 3212 average rate: 247.497 - min: 0.000s max: 0.012s std dev: 0.00149s window: 3464 +min: 0.000s max: 0.012s std dev: 0.00149s window: 3464 average rate: 247.458 - min: 0.000s max: 0.012s std dev: 0.00149s window: 3712 +min: 0.000s max: 0.012s std dev: 0.00149s window: 3712 average rate: 247.485 - min: 0.000s max: 0.012s std dev: 0.00148s window: 3960 +min: 0.000s max: 0.012s std dev: 0.00148s window: 3960 ``` ### ros2 launch diff --git a/docs/zh/sensor/sbgecom.md b/docs/zh/sensor/sbgecom.md index 315365ab74..b8dd1f5141 100644 --- a/docs/zh/sensor/sbgecom.md +++ b/docs/zh/sensor/sbgecom.md @@ -84,7 +84,6 @@ To use the sbgECom driver: If you don't want to have this fallback mechanism, you must disable unwanted sensors. ::: - 4. If using the sbgECom as an INS, disable EKF2 using [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN). 6. Restart PX4. @@ -96,7 +95,7 @@ IMU data should be published at 200Hz. All High Performance and Ellipse 3.0 and higher SBG Systems INS can be configured directly from PX4 firmware: -1. Enable [SBG_CONFIGURATION_EN](../advanced_config/parameter_reference.md#SBG_CONFIGURATION_EN) +1. Enable [SBG_CONFIGURE_EN](../advanced_config/parameter_reference.md#SBG_CONFIGURE_EN). 2. Provide a JSON file `sbg_settings.json` containing SBG Systems INS settings to be applied in your PX4 board `extras` directory (ex: `boards/px4/fmu-v5/extras`). The settings JSON file will be installed in `/etc/extras/sbg_settings.json` on the board. @@ -111,7 +110,6 @@ All High Performance and Ellipse 3.0 and higher SBG Systems INS can be configure ::: 3. For testing purpose, it's also possible to modify SBG Systems INS settings on the fly: - - By passing a JSON file path as argument when starting sbgecom driver (ex: `sbgecom start -f /fs/microsd/new_sbg_settings.json`) - By passing a JSON string as argument when starting sbgecom driver: (ex: `sbgecom start -s {"output":{"comA":{"messages":{"airData":"onChange"}}}}`) diff --git a/docs/zh/sim_sih/index.md b/docs/zh/sim_sih/index.md index f4896ab8db..b2b2c20c05 100644 --- a/docs/zh/sim_sih/index.md +++ b/docs/zh/sim_sih/index.md @@ -65,7 +65,7 @@ These include: [`pwm_out_sim`](../modules/modules_driver.md#pwm-out-sim), [`sens To check that these are present on your flight controller: -1. Start QGroundControl. +1. 启动QGroundControl。 2. Open **Analyze Tools > Mavlink Console**. From be3354d238768fc323830bf5e467eb0a1a1c1727 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Wed, 24 Sep 2025 10:33:34 +1000 Subject: [PATCH 070/812] New Crowdin translations - uk (#25589) Co-authored-by: Crowdin Bot --- docs/uk/SUMMARY.md | 1 + docs/uk/dronecan/ark_rtk_gps.md | 24 +++- docs/uk/dronecan/escs.md | 15 +++ docs/uk/dronecan/index.md | 8 +- docs/uk/flight_modes_fw/index.md | 2 + docs/uk/flight_modes_mc/altitude.md | 2 +- docs/uk/flight_modes_mc/altitude_cruise.md | 45 +++++++ docs/uk/flight_modes_mc/index.md | 4 +- docs/uk/flight_modes_mc/manual_stabilized.md | 2 +- docs/uk/flight_modes_mc/position.md | 4 +- docs/uk/middleware/uxrce_dds.md | 27 +++- docs/uk/modules/modules_driver_ins.md | 25 ++++ docs/uk/modules/modules_system.md | 13 +- docs/uk/msg_docs/ActuatorMotors.md | 4 +- docs/uk/msg_docs/ActuatorServos.md | 2 +- docs/uk/msg_docs/ArmingCheckReply.md | 42 +++---- docs/uk/msg_docs/ArmingCheckRequest.md | 10 +- docs/uk/msg_docs/BatteryStatus.md | 123 ++++++++++--------- docs/uk/msg_docs/EstimatorStatus.md | 4 +- docs/uk/msg_docs/EstimatorStatusFlags.md | 2 + docs/uk/msg_docs/PurePursuitStatus.md | 12 +- docs/uk/msg_docs/RoverAttitudeSetpoint.md | 4 +- docs/uk/msg_docs/RoverAttitudeStatus.md | 6 +- docs/uk/msg_docs/RoverPositionSetpoint.md | 12 +- docs/uk/msg_docs/RoverRateSetpoint.md | 4 +- docs/uk/msg_docs/RoverRateStatus.md | 8 +- docs/uk/msg_docs/RoverSpeedSetpoint.md | 6 +- docs/uk/msg_docs/RoverSpeedStatus.md | 14 +-- docs/uk/msg_docs/RoverSteeringSetpoint.md | 4 +- docs/uk/msg_docs/RoverThrottleSetpoint.md | 6 +- docs/uk/msg_docs/VehicleCommand.md | 1 + docs/uk/msg_docs/VehicleStatus.md | 2 +- docs/uk/msg_docs/index.md | 4 +- docs/uk/releases/main.md | 7 +- docs/uk/ros2/user_guide.md | 2 +- docs/uk/sensor/sbgecom.md | 4 +- 36 files changed, 301 insertions(+), 154 deletions(-) create mode 100644 docs/uk/flight_modes_mc/altitude_cruise.md diff --git a/docs/uk/SUMMARY.md b/docs/uk/SUMMARY.md index 037c8e78fe..512b8e365b 100644 --- a/docs/uk/SUMMARY.md +++ b/docs/uk/SUMMARY.md @@ -7,6 +7,7 @@ - [Position Mode (MC)](flight_modes_mc/position.md) - [Position Slow Mode (MC)](flight_modes_mc/position_slow.md) - [Altitude Mode (MC)](flight_modes_mc/altitude.md) + - [Altitude Cruise Mode (MC)](flight_modes_mc/altitude_cruise.md) - [Stabilized Mode (MC)](flight_modes_mc/manual_stabilized.md) - [Acro Mode (MC)](flight_modes_mc/acro.md) - [Orbit Mode (MC)](flight_modes_mc/orbit.md) diff --git a/docs/uk/dronecan/ark_rtk_gps.md b/docs/uk/dronecan/ark_rtk_gps.md index 091365f591..4034e1ed9d 100644 --- a/docs/uk/dronecan/ark_rtk_gps.md +++ b/docs/uk/dronecan/ark_rtk_gps.md @@ -27,7 +27,7 @@ - Кнопка безпеки - Зумер - Два роз'єми стандарту CAN для Pixhawk (4 контакти JST GH) -- Роз'єм F9P "UART 2" +- F9P `UART 2` Connector - 3-контактний JST-GH - TX, RX, GND - Роз'єм для відлагодження стандарту Pixhawk (6 контактів JST SH) @@ -87,6 +87,25 @@ You need to set necessary [DroneCAN](index.md) parameters and define offsets if - The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK RTK GPS from the vehicles centre of gravity. - Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` on the GPS if this it that last node on the CAN bus. +### Setting Up Rover and Fixed Base + +Position of the rover is established using RTCM messages from the RTK base module (the base module is connected to QGC, which sends the RTCM information to PX4 via MAVLink). + +Параметри PX4 DroneCAN: + +- [UAVCAN_PUB_RTCM](../advanced_config/parameter_reference.md#UAVCAN_PUB_RTCM): + - Makes PX4 publish RTCM messages ([RTCMStream](https://dronecan.github.io/Specification/7._List_of_standard_data_types/#rtcmstream)) to the bus (which it gets from the RTK base module via QGC). + +Rover module parameters (also [set using QGC](../dronecan/index.md#qgc-cannode-parameter-configuration)): + +- [CANNODE_SUB_RTCM](../advanced_config/parameter_reference.md#CANNODE_SUB_RTCM) tells the rover that it should subscribe to [RTCMStream](https://dronecan.github.io/Specification/7._List_of_standard_data_types/#rtcmstream) RTCM messages on the bus (from the moving base). + +:::info +Use [UAVCAN_PUB_MBD](../advanced_config/parameter_reference.md#UAVCAN_PUB_MBD) and [CANNODE_SUB_MBD](../advanced_config/parameter_reference.md#CANNODE_SUB_MBD) instead if you want to implement moving base (see below) at the same time. +::: + +For more information see [Rover and Fixed Base](../dronecan/index.md#rover-and-fixed-base) in the DroneCAN guide. + ### Setting Up Moving Baseline & GPS Heading Найпростіший спосіб налаштування рухомого базису та напрямку GPS з двома модулями GPS ARK RTK відбувається через CAN, хоча можна зробити це через UART, щоб зменшити обсяг даних на шині CAN, якщо це потрібно. @@ -128,10 +147,11 @@ You need to set necessary [DroneCAN](index.md) parameters and define offsets if - On the _Moving Base_, set the following: - [GPS_UBX_MODE](../advanced_config/parameter_reference.md#GPS_UBX_MODE) to `2`. +For more information see [Rover and Moving Base](../dronecan/index.md#rover-and-moving-base) in the DroneCAN guide. + ## Значення LED індикаторів - Світлодіоди статусу GPS розташовані праворуч від роз'ємів - - Миготіння зеленого - це фіксація GPS - Миготіння синього - це отримані корекції та RTK Float - Сталий синій - це RTK зафіксовано diff --git a/docs/uk/dronecan/escs.md b/docs/uk/dronecan/escs.md index f37cd1a66b..03cb7e87e8 100644 --- a/docs/uk/dronecan/escs.md +++ b/docs/uk/dronecan/escs.md @@ -9,3 +9,18 @@ PX4 підтримує ESCs, які відповідають стандарту - [Vertiq](../peripherals/vertiq.md) (larger modules) - [VESC Project](../peripherals/vesc.md) - [RaccoonLab Cyphal and DroneCAN PWM nodes](raccoonlab_nodes.md) + +## Конфігурація апаратного забезпечення + +General DroneCAN hardware configuration is covered in [DroneCAN > Hardware Setup](../dronecan/index.md#hardware-setup). + +DroneCAN ESCs should be on their own dedicated CAN interface(s) because ESC messages can saturate the bus and starve other nodes of bandwidth. + +## Конфігурація PX4 + +DroneCAN peripherals are configured by following the procedure outlined in [DroneCAN](../dronecan/index.md). + +In addition to the general setup, such as setting `UAVCAN_ENABLE` to `3`: + +- Select the specific CAN interface(s) used for ESC data output using the [UAVCAN_ESC_IFACE](../advanced_config/parameter_reference.md#UAVCAN_ESC_IFACE) parameter (all that all interfaces are selected by default). +- Configure the [motor order and servo outputs](../config/actuators.md). diff --git a/docs/uk/dronecan/index.md b/docs/uk/dronecan/index.md index 25902f61fa..76f7b7ad8d 100644 --- a/docs/uk/dronecan/index.md +++ b/docs/uk/dronecan/index.md @@ -276,6 +276,9 @@ If the rangefinder is connected via DroneCAN (whether inbuilt or separate), you [DroneCAN ESCs and servos](../dronecan/escs.md) require the [motor order and servo outputs](../config/actuators.md) to be configured. +Select the specific CAN interface(s) used for ESC data output using the [UAVCAN_ESC_IFACE](../advanced_config/parameter_reference.md#UAVCAN_ESC_IFACE) parameter (all that all interfaces are selected by default). +Note that DroneCAN ESCs should be on their own dedicated CAN interface(s) because ESC messages can saturate the bus and starve other nodes of bandwidth. + ## Налаштування параметрів CANNODE QGC QGroundControl може переглядати та змінювати параметри, що належать до пристроїв CAN, підключених до автопілота, за умови, що пристрої підключені до автопілота до запуску QGC. @@ -313,7 +316,10 @@ If successful, the firmware binary will be removed from the root directory and t **Q**: The motors aren't spinning when armed. -**A**: Make sure `UAVCAN_ENABLE` is set to `3` to enable DroneCAN ESC output. +**A**: + +- Make sure `UAVCAN_ENABLE` is set to `3` to enable DroneCAN ESC output. +- Make sure `UAVCAN_ESC_IFACE` is set to enable the CAN interface(s) used for ESCs. --- diff --git a/docs/uk/flight_modes_fw/index.md b/docs/uk/flight_modes_fw/index.md index d9acb980ac..3a0799a7de 100644 --- a/docs/uk/flight_modes_fw/index.md +++ b/docs/uk/flight_modes_fw/index.md @@ -17,6 +17,8 @@ Manual-Easy: Швидкість активно контролюється, якщо встановлений датчик швидкості. - [Режим висоти](../flight_modes_fw/altitude.md) — Найпростіший і найбезпечніший _непідтримуваний GPS_ ручний режим. Єдина відмінність порівняно з _Режимом положення_ полягає в тому, що пілот завжди безпосередньо керує кутом кочення літака і немає автоматичного утримання курсу. +- Altitude Cruise mode — It behaves exactly like _Altitude mode_, with the only difference being that the manual control failsafe can be disabled. This is done by setting the corresponding flag in [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT). In that case the current altitude, airspeed and heading (by leveling out the roll angle) are kept until the manual control link is regained or the mode is exited. + It is highly recommended to only disable the manual control loss failsafe for this mode if there is a stable data link connection to the vehicle at all times, or to enable the data link loss failsafe through [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT). - [Режим стабілізації](../flight_modes_fw/stabilized.md) — Пілот напряму керує кутом крену та тангажу, і апарат зберігає задану точку до тих пір, поки стіки знову не будуть переміщені. Тяга безпосередньо встановлюється пілотом. Координація повороту все ще обробляється контролером. diff --git a/docs/uk/flight_modes_mc/altitude.md b/docs/uk/flight_modes_mc/altitude.md index c758cfb10b..62231d3190 100644 --- a/docs/uk/flight_modes_mc/altitude.md +++ b/docs/uk/flight_modes_mc/altitude.md @@ -21,7 +21,7 @@ The diagram below shows the mode behaviour visually (for a [mode 2 transmitter]( RC/manual mode like [Stabilized mode](../flight_modes_mc/manual_stabilized.md) but with _altitude stabilization_ (centred sticks level vehicle and hold it to fixed altitude). Горизонтальне положення транспортного засобу може змінюватися через вплив вітру (або наявного імпульсу). -- Центровані палиці (в межах дедбенду): +- Centered sticks: - Рівень RPY прикріплюється до транспортного засобу. - Дросель (~50%) утримує поточну висоту стабільно проти вітру. - Зовнішній центр: diff --git a/docs/uk/flight_modes_mc/altitude_cruise.md b/docs/uk/flight_modes_mc/altitude_cruise.md new file mode 100644 index 0000000000..52533d0852 --- /dev/null +++ b/docs/uk/flight_modes_mc/altitude_cruise.md @@ -0,0 +1,45 @@ +# Altitude Cruise Mode (Multicopter) + +   + +_Altitude Cruise mode_ is a _relatively_ easy-to-fly manual control mode in which roll and pitch sticks control vehicle movement in the left-right and forward-back directions (relative to the "front" of the vehicle), yaw stick controls rate of rotation over the horizontal plane, and throttle controls speed of ascent-descent. + +When the sticks are released/centered the vehicle will keep the current tilt and heading angle and maintain the current _altitude_. +If moving in the horizontal plane the vehicle will accelerate until the wind resistance equals the acceleration caused by the set tilt angle. +The vehicle will then continue to move with a constant velocity (unlike for Altitude mode, in which the vehicle will eventually slow down and stop). +If the wind blows the aircraft will drift in the direction of the wind even if flying perfectly level. + +:::tip +_Altitude Cruise mode_ is intended for long distance flights where the same tilt angle is kept for a long period of time. It is just like [Altitude](../flight_modes_mc/altitude.md) mode but does not go back to level tilt when the sticks are released. +::: + +The diagram below shows the mode behaviour visually (for a [mode 2 transmitter](../getting_started/rc_transmitter_receiver.md#transmitter_modes)). + +![Altitude Control MC - Mode2 RC Controller](../../assets/flight_modes/altitude_mc.png) + +## Технічний підсумок + +A manual mode that is similar to [Altitude mode](../flight_modes_mc/altitude.md) but with different interpretation of roll and pitch sticks. + +- Centered sticks: + - Roll/Pitch sticks: the current tilt is kept. + - Yaw: the current heading is kept. + - Throttle (~50%) holds current altitude. +- Зовнішній центр: + - Roll/Pitch sticks control the rate of change of the tilt angle, resulting in corresponding left-right and forward-back movement. A maximum stick deflection results in a tilting rate setpoint to go from level to max tilt within 0.5 seconds. + - Yaw stick deflection rotates the tilt angle either left or right, causing the vehicle to change course. It is _not_ causing a direct rotation around the body yaw axis like in [Acro mode](../flight_modes_mc/acro.md). + - Ручка дроселя керує швидкістю вгору/вниз з попередньо визначеною максимальною швидкістю (та швидкістю руху в інших осях). +- Зліт: + - Після посадки транспортний засіб злетить, якщо важіль керування газом підніметься вище 62.5% від повного діапазону (від низу). +- Manual control input is required (such as RC control, joystick) to enter this mode. Other than in all other manual modes, it's though possible to disable the manual control loss failsafe by setting the corresponding flag in [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT). In that case the current altitude, tilt and heading are kept until the manual control link is regained or the mode is exited. + It is highly recommended to only disable the manual control loss failsafe for this mode if there is a stable data link connection to the vehicle at all times, and to enable the data link loss failsafe through [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT). + +## Параметри + +Most of the relevant parameters are already covered in the corresponding section in the [Altitude mode](../flight_modes_mc/altitude.md). Here a list of parameters of particular importance for Altitude Cruise. + +| Параметр | Опис | +| -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | The manual control failsafe can be disabled for Altitude Cruise by setting the corresponding bit in this parameter. | +| [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT) | Data link lost failsafe action. Recommended to set if the manual control failsafe is disabled to avoid fly-aways. | +| [MPC_MAN_TILT_MAX](../advanced_config/parameter_reference.md#MPC_MAN_TILT_MAX) | The maximum tilt angle the vehicle will go to. At max stick deflection, it will take 0.5 seconds from level flight to this tilt angle. | diff --git a/docs/uk/flight_modes_mc/index.md b/docs/uk/flight_modes_mc/index.md index 45d354a960..333dc5917e 100644 --- a/docs/uk/flight_modes_mc/index.md +++ b/docs/uk/flight_modes_mc/index.md @@ -21,10 +21,12 @@ Manual-Easy: - [Stabilized mode](../flight_modes_mc/manual_stabilized.md) — Releasing the sticks levels and maintains the vehicle horizontal posture (but not altitude or position). Транспортний засіб продовжить рухатися з імпульсом, і як висота, так і горизонтальна позиція можуть бути піддані впливу вітру. This mode is also used if "Manual mode" is selected in a ground station. +- [Altitude Cruise mode](../flight_modes_mc/altitude_cruise.md) — Very similar to _Altitude mode_, with the difference that when the roll and pitch sticks are released the vehicle does not level out but keeps the tilt until further inputs are given. + Additionally it is possible to disable the manual control failsafe for this mode, having the vehicle continue on it's set path even if there are no new control inputs. Manual-Acrobatic -- [Acro](../flight_modes_mc/acro.md) — Ручний режим для виконання акробатичних маневрів, таких як креніння та петлі. +- [Acro](../flight_modes_mc/acro.md) — Manual mode for performing acrobatic manoeuvrers, such as rolls and loops. Відпускання палиць призупиняє обертання транспортного засобу в площині крена, тангажу та розвороту, але іншим чином не стабілізує транспортний засіб. Автономний: diff --git a/docs/uk/flight_modes_mc/manual_stabilized.md b/docs/uk/flight_modes_mc/manual_stabilized.md index a3fe372f1d..f51b9663e5 100644 --- a/docs/uk/flight_modes_mc/manual_stabilized.md +++ b/docs/uk/flight_modes_mc/manual_stabilized.md @@ -31,7 +31,7 @@ Throttle is rescaled (see [below](#params)) and passed directly to control alloc Автопілот контролює положення, це означає що він регулює кути крену та тангажу до нуля коли органи керування пульту РК центровані всередині мертвої зони контролера (як наслідок вирівнюючи положення). Автопілот не компенсує дрейф через вітер (або інші джерела). -- Центровані палиці (в межах дедбенду): +- Centered sticks: - Рівень ковзання/крена прикріплюється до транспортного засобу. - Зовнішній центр: - Палиці кочення/крену керують кутом нахилу у цих орієнтаціях, що призводить до відповідного руху ліворуч-праворуч та вперед-назад. diff --git a/docs/uk/flight_modes_mc/position.md b/docs/uk/flight_modes_mc/position.md index 2323cbd341..8e43219a1a 100644 --- a/docs/uk/flight_modes_mc/position.md +++ b/docs/uk/flight_modes_mc/position.md @@ -43,7 +43,7 @@ While very rare on a well calibrated vehicle, sometimes there may be problems wi Режим RC, де рульові, кренові, керування газом (RPT) керують рухом у відповідних осях/напрямках. Центральні палиці рівняють транспортний засіб і утримують його на фіксованій висоті та позиції проти вітру. -- Centered roll, pitch, throttle sticks (within RC deadzone [MPC_HOLD_DZ](../advanced_config/parameter_reference.md#MPC_HOLD_DZ)) hold x, y, z position steady against any disturbance like wind. +- Centered roll, pitch, throttle sticks (within RC deadzone [MAN_DEADZONE](#MAN_DEADZONE)) hold x, y, z position steady against any disturbance like wind. - Зовнішній центр: - Ручки кочення/крена керують горизонтальним прискоренням над землею у ліво-правому та передньо-задньому напрямках транспортного засобу (відповідно). - Палиця дросельного клапана контролює швидкість підйому-спуску. @@ -62,7 +62,7 @@ All the parameters in the [Multicopter Position Control](../advanced_config/para | Параметр | Опис | | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [MPC_HOLD_DZ](../advanced_config/parameter_reference.md#MPC_HOLD_DZ) | Мертва зона палиць, де активовано утримання позиції. За замовчуванням: 0.1 (10% від повного діапазону палиці). | +| [MAN_DEADZONE](../advanced_config/parameter_reference.md#MAN_DEADZONE) | Мертва зона палиць, де активовано утримання позиції. За замовчуванням: 0.1 (10% від повного діапазону палиці). | | [MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | Максимальна швидкість вертикального підйому. За замовчуванням: 3 м/с. | | [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | Максимальна швидкість вертикального спуску. За замовчуванням: 1 m/s. | | [MPC_LAND_ALT1](../advanced_config/parameter_reference.md#MPC_LAND_ALT1) | Висота для спрацювання першої фази повільної посадки. Below this altitude descending velocity gets limited to a value between [MPC_Z_VEL_MAX_DN](#MPC_Z_VEL_MAX_DN) (or `MPC_Z_V_AUTO_DN`) and [MPC_LAND_SPEED](#MPC_LAND_SPEED). Value needs to be higher than [MPC_LAND_ALT2](#MPC_LAND_ALT2). За замовчуванням 10м. | diff --git a/docs/uk/middleware/uxrce_dds.md b/docs/uk/middleware/uxrce_dds.md index 613bb93f41..1bdd2a6863 100644 --- a/docs/uk/middleware/uxrce_dds.md +++ b/docs/uk/middleware/uxrce_dds.md @@ -65,7 +65,7 @@ PX4 Micro XRCE-DDS Client is based on version `v2.x` which is not compatible wit В Ubuntu ви можете зібрати з вихідного коду і встановити Агент окремо за допомогою наступних команд: ```sh -git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git +git clone -b v2.4.3 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git cd Micro-XRCE-DDS-Agent mkdir build cd build @@ -126,7 +126,7 @@ This considerably speeds up the build process but requires that the Agent depend ```sh cd ~/px4_ros_uxrce_dds_ws/src - git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git + git clone -b v2.4.3 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git ``` 3. Source the ROS 2 development environment, and compile the workspace using `colcon`: @@ -279,6 +279,9 @@ The configuration can be done using the [UXRCE-DDS parameters](../advanced_confi - [UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT): Bridge time synchronization enable. Клієнтський модуль uXRCE-DDS може синхронізувати мітку часу повідомлень, якими обмінюються через міст. Це стандартна конфігурація. In certain situations, for example during [simulations](../ros2/user_guide.md#ros-gazebo-and-px4-time-synchronization), this feature may be disabled. + - [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX): Index-based namespace definition + Setting this parameter to any value other than `-1` creates a namespace with the prefix `uav_` and the specified value, e.g. `uav_0`, `uav_1`, etc. + See [namespace](#customizing-the-namespace) for methods to define richer or arbitrary namespaces. :::info Many ports are already have a default configuration. @@ -354,7 +357,7 @@ Note that all the messages from PX4 source code are present in the repository, b ## Customizing the Namespace -Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](../middleware/dds_topics.md)) or at runtime (which is useful for multi vehicle operations): +Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](../middleware/dds_topics.md)), at runtime, or through a parameter (which is useful for multi vehicle operations): - One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line. Ця техніка може бути використана як у симуляторах, так і на реальних транспортних засобах. @@ -383,6 +386,22 @@ PX4_UXRCE_DDS_NS=uav_1 make px4_sitl gz_x500 ::: +- A simple index-based namespace can be applied by setting the parameter [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) to a value between 0 and 9999. + This will generate a namespace such as `/uav_0`, `/uav_1`, and so on. + This technique is ideal if vehicles must be persistently associated with namespaces because their clients are automatically started through PX4. + +:::info +PX4 parameters cannot carry rich text strings. +Therefore, you cannot use [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) to automatically start a client with an arbitrary message namespace through PX4. +You can however specify a namespace when starting the client, using the `-n` argument: + +```sh +# In etc/extras.txt on the MicroSD card +uxrce_dds_client start -n fancy_uav +``` + +This can be included in `etc/extras.txt` as part of a custom [System Startup](../concept/system_startup.md). + ## PX4 ROS 2 QoS Settings PX4 QoS settings for publishers are incompatible with the default QoS settings for ROS 2 subscribers. @@ -516,7 +535,7 @@ For a list of services, details and examples see the [service documentation](../ These guidelines explain how to migrate from using PX4 v1.13 [Fast-RTPS](../middleware/micrortps.md) middleware to PX4 v1.14 `uXRCE-DDS` middleware. These are useful if you have [ROS 2 applications written for PX4 v1.13](https://docs.px4.io/v1.13/en/ros/ros2_comm.html), or you have used Fast-RTPS to interface your applications to PX4 [directly](https://docs.px4.io/v1.13/en/middleware/micrortps.html#agent-in-an-offboard-fast-dds-interface-ros-independent). -:::info +::: info This section contains migration-specific information. You should also read the rest of this page to properly understand uXRCE-DDS. ::: diff --git a/docs/uk/modules/modules_driver_ins.md b/docs/uk/modules/modules_driver_ins.md index c48ae1db0f..0385004203 100644 --- a/docs/uk/modules/modules_driver_ins.md +++ b/docs/uk/modules/modules_driver_ins.md @@ -125,6 +125,31 @@ ilabs [arguments...] status Print driver status ``` +## sbgecom + +Source: [drivers/ins/sbgecom](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/sbgecom) + +Description du module + +### Usage {#sbgecom_usage} + +``` +sbgecom [arguments...] + Commands: + start Start driver + [-d ] Serial device + default: /dev/ttyS0 + [-b ] Baudrate device + default: 921600 + [-f ] Config JSON file path + default: /etc/extras/sbg_settings\.json + [-s ] Config JSON string + + status Driver status + + stop Stop driver +``` + ## vectornav Source: [drivers/ins/vectornav](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/vectornav) diff --git a/docs/uk/modules/modules_system.md b/docs/uk/modules/modules_system.md index 339d94e1c9..66171c3846 100644 --- a/docs/uk/modules/modules_system.md +++ b/docs/uk/modules/modules_system.md @@ -140,9 +140,9 @@ commander [arguments...] transition VTOL transition mode Change flight mode - manual|acro|offboard|stabilized|altctl|posctl|position:slow|auto:mission|au - to:loiter|auto:rtl|auto:takeoff|auto:land|auto:precland|ext1 - Flight mode + manual|acro|offboard|stabilized|altctl|posctl|altitude_cruise|position:slow + |auto:mission|auto:loiter|auto:rtl|auto:takeoff|auto:land|auto: + precland|ext1 Flight mode pair @@ -154,6 +154,9 @@ commander [arguments...] lat|lon|alt Origin latitude longitude altitude + set_heading Set current heading + heading degrees from True North [0 360] + poweroff Power off board (if supported) stop @@ -1062,7 +1065,9 @@ uxrce_dds_client [arguments...] values: [-p ] Agent listening port. If not provided, defaults to UXRCE_DDS_PRT - [-n ] Client DDS namespace + [-n ] Client DDS namespace. If not provided but UXRCE_DDS_NS_IDX is + between 0 and 9999 inclusive, then uav_ + UXRCE_DDS_NS_IDX will + be used stop diff --git a/docs/uk/msg_docs/ActuatorMotors.md b/docs/uk/msg_docs/ActuatorMotors.md index f35f523185..f9b6a826f2 100644 --- a/docs/uk/msg_docs/ActuatorMotors.md +++ b/docs/uk/msg_docs/ActuatorMotors.md @@ -18,11 +18,11 @@ uint32 MESSAGE_VERSION = 0 uint64 timestamp # [us] Time since system start uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on -uint16 reversible_flags # Bitset indicating which motors are configured to be reversible +uint16 reversible_flags # [-] Bitset indicating which motors are configured to be reversible uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 # uint8 NUM_CONTROLS = 12 # -float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) +float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) ``` diff --git a/docs/uk/msg_docs/ActuatorServos.md b/docs/uk/msg_docs/ActuatorServos.md index 530331c16b..6dfe1ddd7a 100644 --- a/docs/uk/msg_docs/ActuatorServos.md +++ b/docs/uk/msg_docs/ActuatorServos.md @@ -19,6 +19,6 @@ uint64 timestamp # [us] Time since system start uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on uint8 NUM_CONTROLS = 8 # -float32[8] control # [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. +float32[8] control # [-] [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. ``` diff --git a/docs/uk/msg_docs/ArmingCheckReply.md b/docs/uk/msg_docs/ArmingCheckReply.md index 97347eaa8d..d1e79e5a49 100644 --- a/docs/uk/msg_docs/ArmingCheckReply.md +++ b/docs/uk/msg_docs/ArmingCheckReply.md @@ -1,6 +1,6 @@ # ArmingCheckReply (повідомлення UORB) -Arming check reply. +Arming check reply This is a response to an ArmingCheckRequest message sent by the FMU to an external component, such as a ROS 2 navigation mode. The response contains the current set of external mode requirements, and a queue of events indicating recent failures to set the mode (which the FMU may then forward to a ground station). @@ -12,7 +12,7 @@ The message is not used by internal/FMU components, as their mode requirements a [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ArmingCheckReply.msg) ```c -# Arming check reply. +# Arming check reply # # This is a response to an ArmingCheckRequest message sent by the FMU to an external component, such as a ROS 2 navigation mode. # The response contains the current set of external mode requirements, and a queue of events indicating recent failures to set the mode (which the FMU may then forward to a ground station). @@ -25,33 +25,33 @@ uint32 MESSAGE_VERSION = 1 uint64 timestamp # [us] Time since system start. -uint8 request_id # Id of ArmingCheckRequest for which this is a response. -uint8 registration_id # Id of external component emitting this response. +uint8 request_id # [-] Id of ArmingCheckRequest for which this is a response +uint8 registration_id # [-] Id of external component emitting this response -uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies. +uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX] -bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json). +bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json) +bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json) +bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json) -bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed. +bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed -uint8 num_events # Number of queued failure messages (Event) in the events field. +uint8 num_events # Number of queued failure messages (Event) in the events field -Event[5] events # Arming failure reasons (Queue of events to report to GCS). +Event[5] events # Arming failure reasons (Queue of events to report to GCS) # Mode requirements -bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope). -bool mode_req_attitude # Requires an attitude estimate. -bool mode_req_local_alt # Requires a local altitude estimate. -bool mode_req_local_position # Requires a local position estimate. -bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate. -bool mode_req_global_position # Requires a global position estimate. -bool mode_req_global_position_relaxed # Requires a relaxed global position estimate. -bool mode_req_mission # Requires an uploaded mission. -bool mode_req_home_position # Requires a home position (such as RTL/Return mode). -bool mode_req_prevent_arming # Prevent arming (such as in Land mode). +bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope) +bool mode_req_attitude # Requires an attitude estimate +bool mode_req_local_alt # Requires a local altitude estimate +bool mode_req_local_position # Requires a local position estimate +bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate +bool mode_req_global_position # Requires a global position estimate +bool mode_req_global_position_relaxed # Requires a relaxed global position estimate +bool mode_req_mission # Requires an uploaded mission +bool mode_req_home_position # Requires a home position (such as RTL/Return mode) +bool mode_req_prevent_arming # Prevent arming (such as in Land mode) bool mode_req_manual_control # Requires a manual controller uint8 ORB_QUEUE_LENGTH = 4 diff --git a/docs/uk/msg_docs/ArmingCheckRequest.md b/docs/uk/msg_docs/ArmingCheckRequest.md index a919ec405a..45fd9a48f4 100644 --- a/docs/uk/msg_docs/ArmingCheckRequest.md +++ b/docs/uk/msg_docs/ArmingCheckRequest.md @@ -1,6 +1,6 @@ # ArmingCheckRequest (повідомлення UORB) -Arming check request. +Arming check request Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. @@ -12,7 +12,7 @@ The reply will also include the registration_id for each external component, pro [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ArmingCheckRequest.msg) ```c -# Arming check request. +# Arming check request # # Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. # All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. @@ -23,10 +23,10 @@ The reply will also include the registration_id for each external component, pro uint32 MESSAGE_VERSION = 1 -uint64 timestamp # [us] Time since system start. +uint64 timestamp # [us] Time since system start -uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. +uint8 request_id # [-] Id of this request. Allows correlation with associated ArmingCheckReply messages. -uint32 valid_registrations_mask # Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) +uint32 valid_registrations_mask # [-] Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) ``` diff --git a/docs/uk/msg_docs/BatteryStatus.md b/docs/uk/msg_docs/BatteryStatus.md index fdbc766cf6..068b6a5b82 100644 --- a/docs/uk/msg_docs/BatteryStatus.md +++ b/docs/uk/msg_docs/BatteryStatus.md @@ -16,76 +16,77 @@ Battery instance information is also logged and streamed in MAVLink telemetry. # Battery instance information is also logged and streamed in MAVLink telemetry. uint32 MESSAGE_VERSION = 1 -uint8 MAX_INSTANCES = 4 +uint8 MAX_INSTANCES = 3 -uint64 timestamp # [us] Time since system start -bool connected # Whether or not a battery is connected. For power modules this is based on a voltage threshold. -float32 voltage_v # [V] [@invalid 0] Battery voltage -float32 current_a # [A] [@invalid -1] Battery current -float32 current_average_a # [A] [@invalid -1] Battery current average (for FW average in level flight) -float32 discharged_mah # [mAh] [@invalid -1] Discharged amount -float32 remaining # [@range 0,1] [@invalid -1] Remaining capacity -float32 scale # [@range 1,] [@invalid -1] Scaling factor to compensate for lower actuation power caused by voltage sag -float32 time_remaining_s # [s] [@invalid NaN] Predicted time remaining until battery is empty under previous averaged load -float32 temperature # [°C] [@invalid NaN] Temperature of the battery -uint8 cell_count # [@invalid 0] Number of cells +uint64 timestamp # [us] Time since system start + +bool connected # Whether or not a battery is connected. For power modules this is based on a voltage threshold. +float32 voltage_v # [V] [@invalid 0] Battery voltage +float32 current_a # [A] [@invalid -1] Battery current +float32 current_average_a # [A] [@invalid -1] Battery current average (for FW average in level flight) +float32 discharged_mah # [mAh] [@invalid -1] Discharged amount +float32 remaining # [@range 0,1] [@invalid -1] Remaining capacity +float32 scale # [-] [@range 1,] [@invalid -1] Scaling factor to compensate for lower actuation power caused by voltage sag +float32 time_remaining_s # [s] [@invalid NaN] Predicted time remaining until battery is empty under previous averaged load +float32 temperature # [°C] [@invalid NaN] Temperature of the battery +uint8 cell_count # [-] [@invalid 0] Number of cells -uint8 source # [@enum SOURCE] Battery source -uint8 SOURCE_POWER_MODULE = 0 # Power module -uint8 SOURCE_EXTERNAL = 1 # External -uint8 SOURCE_ESCS = 2 # ESCs +uint8 source # [@enum SOURCE] Battery source +uint8 SOURCE_POWER_MODULE = 0 # Power module +uint8 SOURCE_EXTERNAL = 1 # External +uint8 SOURCE_ESCS = 2 # ESCs -uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 -uint16 capacity # [mAh] Capacity of the battery when fully charged -uint16 cycle_count # Number of discharge cycles the battery has experienced -uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge -uint16 manufacture_date # Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 -uint16 state_of_health # [%] [@range 0, 100] State of health. FullChargeCapacity/DesignCapacity -uint16 max_error # [%] [@range 1, 100] Max error, expected margin of error in the state-of-charge calculation -uint8 id # ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed -uint16 interface_error # Interface error counter +uint8 priority # [-] Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 +uint16 capacity # [mAh] Capacity of the battery when fully charged +uint16 cycle_count # [-] Number of discharge cycles the battery has experienced +uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge +uint16 manufacture_date # [-] Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 +uint16 state_of_health # [%] [@range 0, 100] State of health. FullChargeCapacity/DesignCapacity +uint16 max_error # [%] [@range 1, 100] Max error, expected margin of error in the state-of-charge calculation +uint8 id # [-] ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed +uint16 interface_error # [-] Interface error counter -float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages -float32 max_cell_voltage_delta # Max difference between individual cell voltages +float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages +float32 max_cell_voltage_delta # [V] Max difference between individual cell voltages -bool is_powering_off # Power off event imminent indication, false if unknown -bool is_required # Set if the battery is explicitly required before arming +bool is_powering_off # Power off event imminent indication, false if unknown +bool is_required # Set if the battery is explicitly required before arming -uint8 warning # [@enum WARNING STATE] Current battery warning -uint8 WARNING_NONE = 0 # No battery low voltage warning active -uint8 WARNING_LOW = 1 # Low voltage warning -uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately -uint8 WARNING_EMERGENCY = 3 # Immediate landing required -uint8 WARNING_FAILED = 4 # Battery has failed completely -uint8 STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field -uint8 STATE_CHARGING = 7 # Battery is charging +uint8 warning # [@enum WARNING STATE] Current battery warning +uint8 WARNING_NONE = 0 # No battery low voltage warning active +uint8 WARNING_LOW = 1 # Low voltage warning +uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately +uint8 WARNING_EMERGENCY = 3 # Immediate landing required +uint8 WARNING_FAILED = 4 # Battery has failed completely +uint8 STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field +uint8 STATE_CHARGING = 7 # Battery is charging -uint16 faults # [@enum FAULT] Smart battery supply status/fault flags (bitmask) for health indication -uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged -uint8 FAULT_SPIKES = 1 # Voltage spikes -uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed -uint8 FAULT_OVER_CURRENT = 3 # Over-current -uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature -uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault -uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage) -uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware -uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system -uint8 FAULT_HARDWARE_FAILURE = 9 # Hardware problem -uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming -uint8 FAULT_COUNT = 11 # Counter. Keep this as last element +uint16 faults # [@enum FAULT] Smart battery supply status/fault flags (bitmask) for health indication +uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged +uint8 FAULT_SPIKES = 1 # Voltage spikes +uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed +uint8 FAULT_OVER_CURRENT = 3 # Over-current +uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature +uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault +uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage) +uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware +uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system +uint8 FAULT_HARDWARE_FAILURE = 9 # Hardware problem +uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming +uint8 FAULT_COUNT = 11 # Counter. Keep this as last element -float32 full_charge_capacity_wh # [Wh] Compensated battery capacity -float32 remaining_capacity_wh # [Wh] Compensated battery capacity remaining -uint16 over_discharge_count # Number of battery overdischarge -float32 nominal_voltage # [V] Nominal voltage of the battery pack +float32 full_charge_capacity_wh # [Wh] Compensated battery capacity +float32 remaining_capacity_wh # [Wh] Compensated battery capacity remaining +uint16 over_discharge_count # [-] Number of battery overdischarge +float32 nominal_voltage # [V] Nominal voltage of the battery pack -float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate -float32 ocv_estimate # [V] Open circuit voltage estimate -float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate -float32 volt_based_soc_estimate # [@range 0, 1] Normalized volt based state of charge estimate -float32 voltage_prediction # [V] Predicted voltage -float32 prediction_error # [V] Prediction error -float32 estimation_covariance_norm # Norm of the covariance matrix +float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate +float32 ocv_estimate # [V] Open circuit voltage estimate +float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate +float32 volt_based_soc_estimate # [-] [@range 0, 1] Normalized volt based state of charge estimate +float32 voltage_prediction # [V] Predicted voltage +float32 prediction_error # [V] Prediction error +float32 estimation_covariance_norm # [-] Norm of the covariance matrix ``` diff --git a/docs/uk/msg_docs/EstimatorStatus.md b/docs/uk/msg_docs/EstimatorStatus.md index 8fb0122c74..9054870693 100644 --- a/docs/uk/msg_docs/EstimatorStatus.md +++ b/docs/uk/msg_docs/EstimatorStatus.md @@ -52,7 +52,9 @@ uint8 CS_SYNTHETIC_MAG_Z = 25 # 25 - true when we are using a synthesized measur uint8 CS_VEHICLE_AT_REST = 26 # 26 - true when the vehicle is at rest uint8 CS_GPS_YAW_FAULT = 27 # 27 - true when the GNSS heading has been declared faulty and is no longer being used uint8 CS_RNG_FAULT = 28 # 28 - true when the range finder has been declared faulty and is no longer being used -uint8 CS_GNSS_VEL = 44 # 44 - true if GNSS velocity measurements are being fused +uint8 CS_GNSS_VEL = 44 # 44 - true if GNSS velocity measurement fusion is intended +uint8 CS_GNSS_FAULT = 45 # 45 - true if GNSS measurements have been declared faulty and are no longer used +uint8 CS_YAW_MANUAL = 46 # 46 - true if yaw has been set manually uint32 filter_fault_flags # Bitmask to indicate EKF internal faults # 0 - true if the fusion of the magnetometer X-axis has encountered a numerical error diff --git a/docs/uk/msg_docs/EstimatorStatusFlags.md b/docs/uk/msg_docs/EstimatorStatusFlags.md index 947c67bf60..7aaef39405 100644 --- a/docs/uk/msg_docs/EstimatorStatusFlags.md +++ b/docs/uk/msg_docs/EstimatorStatusFlags.md @@ -54,6 +54,8 @@ bool cs_valid_fake_pos # 41 - true if a valid constant position is bein bool cs_constant_pos # 42 - true if the vehicle is at a constant position bool cs_baro_fault # 43 - true when the current baro has been declared faulty and is no longer being used bool cs_gnss_vel # 44 - true if GNSS velocity measurement fusion is intended +bool cs_gnss_fault # 45 - true if GNSS measurements have been declared faulty and are no longer used +bool cs_yaw_manual # 46 - true if yaw has been set manually # fault status uint32 fault_status_changes # number of filter fault status (fs) changes diff --git a/docs/uk/msg_docs/PurePursuitStatus.md b/docs/uk/msg_docs/PurePursuitStatus.md index 96577a0220..8d54ba473e 100644 --- a/docs/uk/msg_docs/PurePursuitStatus.md +++ b/docs/uk/msg_docs/PurePursuitStatus.md @@ -7,11 +7,11 @@ Pure pursuit status ```c # Pure pursuit status -uint64 timestamp # [us] Time since system start -float32 lookahead_distance # [m] [@range 0, inf] Lookahead distance of pure the pursuit controller -float32 target_bearing # [rad] [@range -pi, pi] [@frame NED] Target bearing calculated by the pure pursuit controller -float32 crosstrack_error # [m] [@range -inf (Left of the path), inf (Right of the path)] Shortest distance from the vehicle to the path -float32 distance_to_waypoint # [m] [@range -inf, inf]Distance from the vehicle to the current waypoint -float32 bearing_to_waypoint # [rad] [@range -pi, pi] [@frame NED]Bearing towards current waypoint +uint64 timestamp # [us] Time since system start +float32 lookahead_distance # [m] [@range 0, inf] Lookahead distance of pure the pursuit controller +float32 target_bearing # [rad] [@range -pi, pi] [@frame NED] Target bearing calculated by the pure pursuit controller +float32 crosstrack_error # [m] [@range -inf (Left of the path), inf (Right of the path)] Shortest distance from the vehicle to the path +float32 distance_to_waypoint # [m] [@range -inf, inf]Distance from the vehicle to the current waypoint +float32 bearing_to_waypoint # [rad] [@range -pi, pi] [@frame NED]Bearing towards current waypoint ``` diff --git a/docs/uk/msg_docs/RoverAttitudeSetpoint.md b/docs/uk/msg_docs/RoverAttitudeSetpoint.md index bd436278ca..ca75a6e3e2 100644 --- a/docs/uk/msg_docs/RoverAttitudeSetpoint.md +++ b/docs/uk/msg_docs/RoverAttitudeSetpoint.md @@ -7,7 +7,7 @@ Rover Attitude Setpoint ```c # Rover Attitude Setpoint -uint64 timestamp # [us] Time since system start -float32 yaw_setpoint # [rad] [@range -inf, inf] [@frame NED] Yaw setpoint +uint64 timestamp # [us] Time since system start +float32 yaw_setpoint # [rad] [@range -inf, inf] [@frame NED] Yaw setpoint ``` diff --git a/docs/uk/msg_docs/RoverAttitudeStatus.md b/docs/uk/msg_docs/RoverAttitudeStatus.md index e6df929abd..f5a9ce1f02 100644 --- a/docs/uk/msg_docs/RoverAttitudeStatus.md +++ b/docs/uk/msg_docs/RoverAttitudeStatus.md @@ -7,8 +7,8 @@ Rover Attitude Status ```c # Rover Attitude Status -uint64 timestamp # [us] Time since system start -float32 measured_yaw # [rad] [@range -pi, pi] [@frame NED]Measured yaw -float32 adjusted_yaw_setpoint # [rad] [@range -pi, pi] [@frame NED] Yaw setpoint that is being tracked (Applied slew rates) +uint64 timestamp # [us] Time since system start +float32 measured_yaw # [rad] [@range -pi, pi] [@frame NED]Measured yaw +float32 adjusted_yaw_setpoint # [rad] [@range -pi, pi] [@frame NED] Yaw setpoint that is being tracked (Applied slew rates) ``` diff --git a/docs/uk/msg_docs/RoverPositionSetpoint.md b/docs/uk/msg_docs/RoverPositionSetpoint.md index b45aa0515f..751536e7f9 100644 --- a/docs/uk/msg_docs/RoverPositionSetpoint.md +++ b/docs/uk/msg_docs/RoverPositionSetpoint.md @@ -7,11 +7,11 @@ Rover Position Setpoint ```c # Rover Position Setpoint -uint64 timestamp # [us] Time since system start -float32[2] position_ned # [m] [@range -inf, inf] [@frame NED] Target position -float32[2] start_ned # [m] [@range -inf, inf] [@frame NED] [@invalid NaN Defaults to vehicle position] Start position which specifies a line for the rover to track -float32 cruising_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to maximum speed] Cruising speed -float32 arrival_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to 0] Speed the rover should arrive at the target with -float32 yaw # [rad] [@range -pi,pi] [@frame NED] [@invalid NaN Defaults to vehicle yaw] Mecanum only: Specify vehicle yaw during travel +uint64 timestamp # [us] Time since system start +float32[2] position_ned # [m] [@range -inf, inf] [@frame NED] Target position +float32[2] start_ned # [m] [@range -inf, inf] [@frame NED] [@invalid NaN Defaults to vehicle position] Start position which specifies a line for the rover to track +float32 cruising_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to maximum speed] Cruising speed +float32 arrival_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to 0] Speed the rover should arrive at the target with +float32 yaw # [rad] [@range -pi,pi] [@frame NED] [@invalid NaN Defaults to vehicle yaw] Mecanum only: Specify vehicle yaw during travel ``` diff --git a/docs/uk/msg_docs/RoverRateSetpoint.md b/docs/uk/msg_docs/RoverRateSetpoint.md index 9bffa41b80..9bb844e802 100644 --- a/docs/uk/msg_docs/RoverRateSetpoint.md +++ b/docs/uk/msg_docs/RoverRateSetpoint.md @@ -7,7 +7,7 @@ Rover Rate setpoint ```c # Rover Rate setpoint -uint64 timestamp # [us] Time since system start -float32 yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint +uint64 timestamp # [us] Time since system start +float32 yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint ``` diff --git a/docs/uk/msg_docs/RoverRateStatus.md b/docs/uk/msg_docs/RoverRateStatus.md index 684e4c458a..70345fe315 100644 --- a/docs/uk/msg_docs/RoverRateStatus.md +++ b/docs/uk/msg_docs/RoverRateStatus.md @@ -7,9 +7,9 @@ Rover Rate Status ```c # Rover Rate Status -uint64 timestamp # [us] Time since system start -float32 measured_yaw_rate # [rad/s] [@range -inf, inf] [@frame NED] Measured yaw rate -float32 adjusted_yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint that is being tracked (Applied slew rates) -float32 pid_yaw_rate_integral # [] [@range -1, 1] Integral of the PID for the closed loop yaw rate controller +uint64 timestamp # [us] Time since system start +float32 measured_yaw_rate # [rad/s] [@range -inf, inf] [@frame NED] Measured yaw rate +float32 adjusted_yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint that is being tracked (Applied slew rates) +float32 pid_yaw_rate_integral # [-] [@range -1, 1] Integral of the PID for the closed loop yaw rate controller ``` diff --git a/docs/uk/msg_docs/RoverSpeedSetpoint.md b/docs/uk/msg_docs/RoverSpeedSetpoint.md index 9eea46e60f..84176cd1c3 100644 --- a/docs/uk/msg_docs/RoverSpeedSetpoint.md +++ b/docs/uk/msg_docs/RoverSpeedSetpoint.md @@ -7,8 +7,8 @@ Rover Speed Setpoint ```c # Rover Speed Setpoint -uint64 timestamp # [us] Time since system start -float32 speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction -float32 speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction +uint64 timestamp # [us] Time since system start +float32 speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction +float32 speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction ``` diff --git a/docs/uk/msg_docs/RoverSpeedStatus.md b/docs/uk/msg_docs/RoverSpeedStatus.md index 8c212e2b0f..4213e1e5df 100644 --- a/docs/uk/msg_docs/RoverSpeedStatus.md +++ b/docs/uk/msg_docs/RoverSpeedStatus.md @@ -7,12 +7,12 @@ Rover Velocity Status ```c # Rover Velocity Status -uint64 timestamp # [us] Time since system start -float32 measured_speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Measured speed in body x direction -float32 adjusted_speed_body_x_setpoint # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction that is being tracked (Applied slew rates) -float32 pid_throttle_body_x_integral # [] [@range -1, 1] Integral of the PID for the closed loop controller of the speed in body x direction -float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction -float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates) -float32 pid_throttle_body_y_integral # [] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction +uint64 timestamp # [us] Time since system start +float32 measured_speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Measured speed in body x direction +float32 adjusted_speed_body_x_setpoint # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction that is being tracked (Applied slew rates) +float32 pid_throttle_body_x_integral # [-] [@range -1, 1] Integral of the PID for the closed loop controller of the speed in body x direction +float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction +float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates) +float32 pid_throttle_body_y_integral # [-] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction ``` diff --git a/docs/uk/msg_docs/RoverSteeringSetpoint.md b/docs/uk/msg_docs/RoverSteeringSetpoint.md index 3e40a3986b..974f3fc4c9 100644 --- a/docs/uk/msg_docs/RoverSteeringSetpoint.md +++ b/docs/uk/msg_docs/RoverSteeringSetpoint.md @@ -7,7 +7,7 @@ Rover Steering setpoint ```c # Rover Steering setpoint -uint64 timestamp # [us] Time since system start -float32 normalized_steering_setpoint # [@range -1 (Left), 1 (Right)] [@frame Body] Ackermann: Normalized steering angle, Differential/Mecanum: Normalized speed difference between the left and right wheels +uint64 timestamp # [us] Time since system start +float32 normalized_steering_setpoint # [-] [@range -1 (Left), 1 (Right)] [@frame Body] Ackermann: Normalized steering angle, Differential/Mecanum: Normalized speed difference between the left and right wheels ``` diff --git a/docs/uk/msg_docs/RoverThrottleSetpoint.md b/docs/uk/msg_docs/RoverThrottleSetpoint.md index f1c4f7f653..bd5ee93d55 100644 --- a/docs/uk/msg_docs/RoverThrottleSetpoint.md +++ b/docs/uk/msg_docs/RoverThrottleSetpoint.md @@ -7,8 +7,8 @@ Rover Throttle setpoint ```c # Rover Throttle setpoint -uint64 timestamp # [us] Time since system start -float32 throttle_body_x # [] [@range -1 (Backwards), 1 (Forwards)] [@frame Body] Throttle setpoint along body X axis -float32 throttle_body_y # [] [@range -1 (Left), 1 (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Throttle setpoint along body Y axis +uint64 timestamp # [us] Time since system start +float32 throttle_body_x # [-] [@range -1 (Backwards), 1 (Forwards)] [@frame Body] Throttle setpoint along body X axis +float32 throttle_body_y # [-] [@range -1 (Left), 1 (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Throttle setpoint along body Y axis ``` diff --git a/docs/uk/msg_docs/VehicleCommand.md b/docs/uk/msg_docs/VehicleCommand.md index 00848d8e4b..5ed9a339c1 100644 --- a/docs/uk/msg_docs/VehicleCommand.md +++ b/docs/uk/msg_docs/VehicleCommand.md @@ -96,6 +96,7 @@ uint16 VEHICLE_CMD_REQUEST_CAMERA_INFORMATION = 521 # Request camera information uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.). uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom. uint16 VEHICLE_CMD_SET_CAMERA_FOCUS = 532 +uint16 VEHICLE_CMD_EXTERNAL_ATTITUDE_ESTIMATE = 620 # Set an external estimate of vehicle attitude in degrees. uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw. uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control. uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence. diff --git a/docs/uk/msg_docs/VehicleStatus.md b/docs/uk/msg_docs/VehicleStatus.md index eb32a77eb5..f598e1e5b2 100644 --- a/docs/uk/msg_docs/VehicleStatus.md +++ b/docs/uk/msg_docs/VehicleStatus.md @@ -48,7 +48,7 @@ uint8 NAVIGATION_STATE_AUTO_LOITER = 4 # Auto loiter mode uint8 NAVIGATION_STATE_AUTO_RTL = 5 # Auto return to launch mode uint8 NAVIGATION_STATE_POSITION_SLOW = 6 uint8 NAVIGATION_STATE_FREE5 = 7 -uint8 NAVIGATION_STATE_FREE4 = 8 +uint8 NAVIGATION_STATE_ALTITUDE_CRUISE = 8 # Altitude with Cruise mode uint8 NAVIGATION_STATE_FREE3 = 9 uint8 NAVIGATION_STATE_ACRO = 10 # Acro mode uint8 NAVIGATION_STATE_FREE2 = 11 diff --git a/docs/uk/msg_docs/index.md b/docs/uk/msg_docs/index.md index b4f0082888..4e64d5af95 100644 --- a/docs/uk/msg_docs/index.md +++ b/docs/uk/msg_docs/index.md @@ -16,8 +16,8 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [ActuatorMotors](ActuatorMotors.md) — Motor control message - [ActuatorServos](ActuatorServos.md) — Servo control message - [AirspeedValidated](AirspeedValidated.md) -- [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply. -- [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request. +- [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply +- [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request - [BatteryStatus](BatteryStatus.md) — Battery status - [ConfigOverrides](ConfigOverrides.md) — Configurable overrides by (external) modes or mode executors - [Event](Event.md) — Events interface diff --git a/docs/uk/releases/main.md b/docs/uk/releases/main.md index b2e252a05d..dd3875875b 100644 --- a/docs/uk/releases/main.md +++ b/docs/uk/releases/main.md @@ -44,7 +44,9 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Управління -- Уточнюється +- Added new flight mode(s): [Altitude Cruise (MC)](../flight_modes_mc/altitude_cruise.md), Altitude Cruise (FW). + For fixed-wing the mode behaves the same as Altitude mode but you can disable the manual control loss failsafe. (PX4-Autopilot#25435: Add new flight mode: Altitude Cruise + ). ### Оцінки @@ -72,7 +74,8 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Мульти-Ротор -- Уточнюється +- Removed parameters `MPC_{XY/Z/YAW}_MAN_EXPO` and use default value instead, as they were not deemed necessary anymore. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)). +- Renamed `MPC_HOLD_DZ` to `MAN_DEADZONE` to have it globally available in modes that allow for a dead zone. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)). ### VTOL diff --git a/docs/uk/ros2/user_guide.md b/docs/uk/ros2/user_guide.md index b09de1bf84..2f5ff0d4c0 100644 --- a/docs/uk/ros2/user_guide.md +++ b/docs/uk/ros2/user_guide.md @@ -156,7 +156,7 @@ To setup and start the agent: 2. Введіть наступні команди для витягування та побудови агента з вихідного коду: ```sh - git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git + git clone -b v2.4.3 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git cd Micro-XRCE-DDS-Agent mkdir build cd build diff --git a/docs/uk/sensor/sbgecom.md b/docs/uk/sensor/sbgecom.md index f02ce87683..706c96b1b2 100644 --- a/docs/uk/sensor/sbgecom.md +++ b/docs/uk/sensor/sbgecom.md @@ -84,7 +84,6 @@ To use the sbgECom driver: If you don't want to have this fallback mechanism, you must disable unwanted sensors. ::: - 4. If using the sbgECom as an INS, disable EKF2 using [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN). 6. Перезавантажте PX4. @@ -96,7 +95,7 @@ IMU data should be published at 200Hz. All High Performance and Ellipse 3.0 and higher SBG Systems INS can be configured directly from PX4 firmware: -1. Enable [SBG_CONFIGURATION_EN](../advanced_config/parameter_reference.md#SBG_CONFIGURATION_EN) +1. Enable [SBG_CONFIGURE_EN](../advanced_config/parameter_reference.md#SBG_CONFIGURE_EN). 2. Provide a JSON file `sbg_settings.json` containing SBG Systems INS settings to be applied in your PX4 board `extras` directory (ex: `boards/px4/fmu-v5/extras`). The settings JSON file will be installed in `/etc/extras/sbg_settings.json` on the board. @@ -111,7 +110,6 @@ All High Performance and Ellipse 3.0 and higher SBG Systems INS can be configure ::: 3. For testing purpose, it's also possible to modify SBG Systems INS settings on the fly: - - By passing a JSON file path as argument when starting sbgecom driver (ex: `sbgecom start -f /fs/microsd/new_sbg_settings.json`) - By passing a JSON string as argument when starting sbgecom driver: (ex: `sbgecom start -s {"output":{"comA":{"messages":{"airData":"onChange"}}}}`) From 9b6d07ee6720a9eb1dfe59cd26d8a602c62a623e Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Wed, 24 Sep 2025 10:33:44 +1000 Subject: [PATCH 071/812] New Crowdin translations - ko (#25588) Co-authored-by: Crowdin Bot --- docs/ko/SUMMARY.md | 1 + docs/ko/dronecan/ark_rtk_gps.md | 24 ++- docs/ko/dronecan/escs.md | 15 ++ docs/ko/dronecan/index.md | 8 +- docs/ko/flight_modes_fw/index.md | 2 + docs/ko/flight_modes_mc/altitude.md | 2 +- docs/ko/flight_modes_mc/altitude_cruise.md | 45 ++++ docs/ko/flight_modes_mc/index.md | 4 +- docs/ko/flight_modes_mc/manual_stabilized.md | 2 +- docs/ko/flight_modes_mc/position.md | 4 +- docs/ko/middleware/uxrce_dds.md | 107 ++++++---- docs/ko/modules/modules_driver_ins.md | 25 +++ docs/ko/modules/modules_system.md | 13 +- docs/ko/msg_docs/ActuatorMotors.md | 4 +- docs/ko/msg_docs/ActuatorServos.md | 2 +- docs/ko/msg_docs/ArmingCheckReply.md | 42 ++-- docs/ko/msg_docs/ArmingCheckRequest.md | 10 +- docs/ko/msg_docs/BatteryStatus.md | 123 +++++------ docs/ko/msg_docs/EstimatorStatus.md | 4 +- docs/ko/msg_docs/EstimatorStatusFlags.md | 2 + docs/ko/msg_docs/PurePursuitStatus.md | 12 +- docs/ko/msg_docs/RoverAttitudeSetpoint.md | 4 +- docs/ko/msg_docs/RoverAttitudeStatus.md | 6 +- docs/ko/msg_docs/RoverPositionSetpoint.md | 12 +- docs/ko/msg_docs/RoverRateSetpoint.md | 4 +- docs/ko/msg_docs/RoverRateStatus.md | 8 +- docs/ko/msg_docs/RoverSpeedSetpoint.md | 6 +- docs/ko/msg_docs/RoverSpeedStatus.md | 14 +- docs/ko/msg_docs/RoverSteeringSetpoint.md | 4 +- docs/ko/msg_docs/RoverThrottleSetpoint.md | 6 +- docs/ko/msg_docs/VehicleCommand.md | 1 + docs/ko/msg_docs/VehicleStatus.md | 2 +- docs/ko/msg_docs/index.md | 4 +- docs/ko/releases/main.md | 7 +- docs/ko/ros2/user_guide.md | 212 +++++++++---------- docs/ko/sensor/sbgecom.md | 4 +- 36 files changed, 446 insertions(+), 299 deletions(-) create mode 100644 docs/ko/flight_modes_mc/altitude_cruise.md diff --git a/docs/ko/SUMMARY.md b/docs/ko/SUMMARY.md index e0bc2578cc..e383e68ffb 100644 --- a/docs/ko/SUMMARY.md +++ b/docs/ko/SUMMARY.md @@ -7,6 +7,7 @@ - [위치 모드 (멀티콥터)](flight_modes_mc/position.md) - [Position Slow Mode (MC)](flight_modes_mc/position_slow.md) - [고도 모드 (멀티콥터)](flight_modes_mc/altitude.md) + - [Altitude Cruise Mode (MC)](flight_modes_mc/altitude_cruise.md) - [Stabilized Mode (MC)](flight_modes_mc/manual_stabilized.md) - [아크로 모드 (멀티콥터)](flight_modes_mc/acro.md) - [궤도 모드 (멀티콥터)](flight_modes_mc/orbit.md) diff --git a/docs/ko/dronecan/ark_rtk_gps.md b/docs/ko/dronecan/ark_rtk_gps.md index 33d67fc4ee..917dd95e30 100644 --- a/docs/ko/dronecan/ark_rtk_gps.md +++ b/docs/ko/dronecan/ark_rtk_gps.md @@ -27,7 +27,7 @@ Order this module from: - Safety Button - 부저 - Two Pixhawk Standard CAN Connectors (4 Pin JST GH) -- F9P “UART 2” Connector +- F9P `UART 2` Connector - 3 Pin JST GH - TX, RX, GND - Pixhawk Standard Debug Connector (6 Pin JST SH) @@ -87,6 +87,25 @@ You need to set necessary [DroneCAN](index.md) parameters and define offsets if - The parameters [EKF2_GPS_POS_X](../advanced_config/parameter_reference.md#EKF2_GPS_POS_X), [EKF2_GPS_POS_Y](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Y) and [EKF2_GPS_POS_Z](../advanced_config/parameter_reference.md#EKF2_GPS_POS_Z) can be set to account for the offset of the ARK RTK GPS from the vehicles centre of gravity. - Set [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) to `1` on the GPS if this it that last node on the CAN bus. +### Setting Up Rover and Fixed Base + +Position of the rover is established using RTCM messages from the RTK base module (the base module is connected to QGC, which sends the RTCM information to PX4 via MAVLink). + +PX4 DroneCAN parameters: + +- [UAVCAN_PUB_RTCM](../advanced_config/parameter_reference.md#UAVCAN_PUB_RTCM): + - Makes PX4 publish RTCM messages ([RTCMStream](https://dronecan.github.io/Specification/7._List_of_standard_data_types/#rtcmstream)) to the bus (which it gets from the RTK base module via QGC). + +Rover module parameters (also [set using QGC](../dronecan/index.md#qgc-cannode-parameter-configuration)): + +- [CANNODE_SUB_RTCM](../advanced_config/parameter_reference.md#CANNODE_SUB_RTCM) tells the rover that it should subscribe to [RTCMStream](https://dronecan.github.io/Specification/7._List_of_standard_data_types/#rtcmstream) RTCM messages on the bus (from the moving base). + +:::info +Use [UAVCAN_PUB_MBD](../advanced_config/parameter_reference.md#UAVCAN_PUB_MBD) and [CANNODE_SUB_MBD](../advanced_config/parameter_reference.md#CANNODE_SUB_MBD) instead if you want to implement moving base (see below) at the same time. +::: + +For more information see [Rover and Fixed Base](../dronecan/index.md#rover-and-fixed-base) in the DroneCAN guide. + ### Setting Up Moving Baseline & GPS Heading The simplest way to set up moving baseline and GPS heading with two ARK RTK GPS modules is via CAN, though it can be done via UART to reduce traffic on the CAN bus if desired. @@ -128,10 +147,11 @@ Setup via UART: - On the _Moving Base_, set the following: - [GPS_UBX_MODE](../advanced_config/parameter_reference.md#GPS_UBX_MODE) to `2`. +For more information see [Rover and Moving Base](../dronecan/index.md#rover-and-moving-base) in the DroneCAN guide. + ## LED 신호의 의미 - The GPS status lights are located to the right of the connectors - - Blinking green is GPS fix - Blinking blue is received corrections and RTK Float - Solid blue is RTK Fixed diff --git a/docs/ko/dronecan/escs.md b/docs/ko/dronecan/escs.md index 9742e3739e..4d97c7cfd1 100644 --- a/docs/ko/dronecan/escs.md +++ b/docs/ko/dronecan/escs.md @@ -9,3 +9,18 @@ For more information, see the following articles for specific hardware/firmware: - [Vertiq](../peripherals/vertiq.md) (larger modules) - [VESC Project](../peripherals/vesc.md) - [RaccoonLab Cyphal and DroneCAN PWM nodes](raccoonlab_nodes.md) + +## 하드웨어 설정 + +General DroneCAN hardware configuration is covered in [DroneCAN > Hardware Setup](../dronecan/index.md#hardware-setup). + +DroneCAN ESCs should be on their own dedicated CAN interface(s) because ESC messages can saturate the bus and starve other nodes of bandwidth. + +## PX4 설정 + +DroneCAN peripherals are configured by following the procedure outlined in [DroneCAN](../dronecan/index.md). + +In addition to the general setup, such as setting `UAVCAN_ENABLE` to `3`: + +- Select the specific CAN interface(s) used for ESC data output using the [UAVCAN_ESC_IFACE](../advanced_config/parameter_reference.md#UAVCAN_ESC_IFACE) parameter (all that all interfaces are selected by default). +- Configure the [motor order and servo outputs](../config/actuators.md). diff --git a/docs/ko/dronecan/index.md b/docs/ko/dronecan/index.md index c50f5bcfdb..f5b9efe0ce 100644 --- a/docs/ko/dronecan/index.md +++ b/docs/ko/dronecan/index.md @@ -276,6 +276,9 @@ PX4 DroneCAN parameters: [DroneCAN ESCs and servos](../dronecan/escs.md) require the [motor order and servo outputs](../config/actuators.md) to be configured. +Select the specific CAN interface(s) used for ESC data output using the [UAVCAN_ESC_IFACE](../advanced_config/parameter_reference.md#UAVCAN_ESC_IFACE) parameter (all that all interfaces are selected by default). +Note that DroneCAN ESCs should be on their own dedicated CAN interface(s) because ESC messages can saturate the bus and starve other nodes of bandwidth. + ## QGC CANNODE Parameter Configuration QGroundControl can inspect and modify parameters belonging to CAN devices attached to the flight controller, provided the device are connected to the flight controller before QGC is started. @@ -313,7 +316,10 @@ If successful, the firmware binary will be removed from the root directory and t **Q**: The motors aren't spinning when armed. -**A**: Make sure `UAVCAN_ENABLE` is set to `3` to enable DroneCAN ESC output. +**A**: + +- Make sure `UAVCAN_ENABLE` is set to `3` to enable DroneCAN ESC output. +- Make sure `UAVCAN_ESC_IFACE` is set to enable the CAN interface(s) used for ESCs. --- diff --git a/docs/ko/flight_modes_fw/index.md b/docs/ko/flight_modes_fw/index.md index ac7acee269..20443d82a5 100644 --- a/docs/ko/flight_modes_fw/index.md +++ b/docs/ko/flight_modes_fw/index.md @@ -17,6 +17,8 @@ Manual-Easy: Airspeed is actively controlled if an airspeed sensor is installed. - [Altitude](../flight_modes_fw/altitude.md) — Easiest and safest _non-GPS_ manual mode. The only difference compared to _Position mode_ is that the pilot always directly controls the roll angle of the plane and there is no automatic course holding. +- Altitude Cruise mode — It behaves exactly like _Altitude mode_, with the only difference being that the manual control failsafe can be disabled. This is done by setting the corresponding flag in [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT). In that case the current altitude, airspeed and heading (by leveling out the roll angle) are kept until the manual control link is regained or the mode is exited. + It is highly recommended to only disable the manual control loss failsafe for this mode if there is a stable data link connection to the vehicle at all times, or to enable the data link loss failsafe through [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT). - [Stabilized mode](../flight_modes_fw/stabilized.md) — The pilot directly commands the roll and pitch angle and the vehicle keeps the setpoint until the sticks are moved again. Thrust is directly set by the pilot. Turn coordination is still handled by the controller. diff --git a/docs/ko/flight_modes_mc/altitude.md b/docs/ko/flight_modes_mc/altitude.md index 7c0f13424b..36aff1468f 100644 --- a/docs/ko/flight_modes_mc/altitude.md +++ b/docs/ko/flight_modes_mc/altitude.md @@ -21,7 +21,7 @@ The diagram below shows the mode behaviour visually (for a [mode 2 transmitter]( RC/manual mode like [Stabilized mode](../flight_modes_mc/manual_stabilized.md) but with _altitude stabilization_ (centred sticks level vehicle and hold it to fixed altitude). The horizontal position of the vehicle can move due to wind (or pre-existing momentum). -- 중앙 스틱 (데드밴드 내부) : +- Centered sticks: - RPY sticks levels vehicle. - 스로틀(~ 50 %)은 현재 고도를 바람에 대해 일정하게 유지합니다. - Outside center: diff --git a/docs/ko/flight_modes_mc/altitude_cruise.md b/docs/ko/flight_modes_mc/altitude_cruise.md new file mode 100644 index 0000000000..a608e273fb --- /dev/null +++ b/docs/ko/flight_modes_mc/altitude_cruise.md @@ -0,0 +1,45 @@ +# Altitude Cruise Mode (Multicopter) + +   + +_Altitude Cruise mode_ is a _relatively_ easy-to-fly manual control mode in which roll and pitch sticks control vehicle movement in the left-right and forward-back directions (relative to the "front" of the vehicle), yaw stick controls rate of rotation over the horizontal plane, and throttle controls speed of ascent-descent. + +When the sticks are released/centered the vehicle will keep the current tilt and heading angle and maintain the current _altitude_. +If moving in the horizontal plane the vehicle will accelerate until the wind resistance equals the acceleration caused by the set tilt angle. +The vehicle will then continue to move with a constant velocity (unlike for Altitude mode, in which the vehicle will eventually slow down and stop). +If the wind blows the aircraft will drift in the direction of the wind even if flying perfectly level. + +:::tip +_Altitude Cruise mode_ is intended for long distance flights where the same tilt angle is kept for a long period of time. It is just like [Altitude](../flight_modes_mc/altitude.md) mode but does not go back to level tilt when the sticks are released. +::: + +The diagram below shows the mode behaviour visually (for a [mode 2 transmitter](../getting_started/rc_transmitter_receiver.md#transmitter_modes)). + +![Altitude Control MC - Mode2 RC Controller](../../assets/flight_modes/altitude_mc.png) + +## Technical Summary + +A manual mode that is similar to [Altitude mode](../flight_modes_mc/altitude.md) but with different interpretation of roll and pitch sticks. + +- Centered sticks: + - Roll/Pitch sticks: the current tilt is kept. + - Yaw: the current heading is kept. + - Throttle (~50%) holds current altitude. +- Outside center: + - Roll/Pitch sticks control the rate of change of the tilt angle, resulting in corresponding left-right and forward-back movement. A maximum stick deflection results in a tilting rate setpoint to go from level to max tilt within 0.5 seconds. + - Yaw stick deflection rotates the tilt angle either left or right, causing the vehicle to change course. It is _not_ causing a direct rotation around the body yaw axis like in [Acro mode](../flight_modes_mc/acro.md). + - 스로틀 스틱은 미리 정해진 최대 속도 (및 다른 축의 이동 속도)로 속도를 올리거나 내립니다. +- 이륙: + - 착륙했을 때 스로틀 스틱을 62.5 % (하단에서 전체 범위) 이상으로 올리면 기체가 이륙합니다. +- Manual control input is required (such as RC control, joystick) to enter this mode. Other than in all other manual modes, it's though possible to disable the manual control loss failsafe by setting the corresponding flag in [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT). In that case the current altitude, tilt and heading are kept until the manual control link is regained or the mode is exited. + It is highly recommended to only disable the manual control loss failsafe for this mode if there is a stable data link connection to the vehicle at all times, and to enable the data link loss failsafe through [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT). + +## 매개변수 + +Most of the relevant parameters are already covered in the corresponding section in the [Altitude mode](../flight_modes_mc/altitude.md). Here a list of parameters of particular importance for Altitude Cruise. + +| 매개변수 | 설명 | +| -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | The manual control failsafe can be disabled for Altitude Cruise by setting the corresponding bit in this parameter. | +| [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT) | Data link lost failsafe action. Recommended to set if the manual control failsafe is disabled to avoid fly-aways. | +| [MPC_MAN_TILT_MAX](../advanced_config/parameter_reference.md#MPC_MAN_TILT_MAX) | The maximum tilt angle the vehicle will go to. At max stick deflection, it will take 0.5 seconds from level flight to this tilt angle. | diff --git a/docs/ko/flight_modes_mc/index.md b/docs/ko/flight_modes_mc/index.md index 752fd4aeb2..73cb4fc032 100644 --- a/docs/ko/flight_modes_mc/index.md +++ b/docs/ko/flight_modes_mc/index.md @@ -21,10 +21,12 @@ Manual-Easy: - [Stabilized mode](../flight_modes_mc/manual_stabilized.md) — Releasing the sticks levels and maintains the vehicle horizontal posture (but not altitude or position). The vehicle will continue to move with momentum, and both altitude and horizontal position may be affected by wind. This mode is also used if "Manual mode" is selected in a ground station. +- [Altitude Cruise mode](../flight_modes_mc/altitude_cruise.md) — Very similar to _Altitude mode_, with the difference that when the roll and pitch sticks are released the vehicle does not level out but keeps the tilt until further inputs are given. + Additionally it is possible to disable the manual control failsafe for this mode, having the vehicle continue on it's set path even if there are no new control inputs. Manual-Acrobatic -- [Acro](../flight_modes_mc/acro.md) — Manual mode for performing acrobatic maneuvers, such as rolls and loops. +- [Acro](../flight_modes_mc/acro.md) — Manual mode for performing acrobatic manoeuvrers, such as rolls and loops. Releasing the sticks stops the vehicle rotating in the roll, pitch, yaw axes, but does not otherwise stabilise the vehicle. Autonomous: diff --git a/docs/ko/flight_modes_mc/manual_stabilized.md b/docs/ko/flight_modes_mc/manual_stabilized.md index 129613235d..8127254ebf 100644 --- a/docs/ko/flight_modes_mc/manual_stabilized.md +++ b/docs/ko/flight_modes_mc/manual_stabilized.md @@ -31,7 +31,7 @@ Throttle is rescaled (see [below](#params)) and passed directly to control alloc 자동 조종 장치는 자세를 제어합니다. 즉, RC 스틱이 컨트롤러 데드 존 내부에 집중 될 때 롤과 피치 각을 제로로 조절합니다 (결과적으로 태도가 수평이 됨). 자동 조종 장치는 바람 (또는 다른 원인)으로 인한 드리프트를 보상하지 않습니다. -- 중앙 스틱 (데드밴드 내부) : +- Centered sticks: - Roll/Pitch sticks level vehicle. - Outside center: - Roll/Pitch sticks control tilt angle in those orientations, resulting in corresponding left-right and forward-back movement. diff --git a/docs/ko/flight_modes_mc/position.md b/docs/ko/flight_modes_mc/position.md index 01f7b573e2..a86b9dbea4 100644 --- a/docs/ko/flight_modes_mc/position.md +++ b/docs/ko/flight_modes_mc/position.md @@ -43,7 +43,7 @@ While very rare on a well calibrated vehicle, sometimes there may be problems wi RC mode where roll, pitch, throttle (RPT) sticks control movement in corresponding axes/directions. Centered sticks level vehicle and hold it to fixed altitude and position against wind. -- Centered roll, pitch, throttle sticks (within RC deadzone [MPC_HOLD_DZ](../advanced_config/parameter_reference.md#MPC_HOLD_DZ)) hold x, y, z position steady against any disturbance like wind. +- Centered roll, pitch, throttle sticks (within RC deadzone [MAN_DEADZONE](#MAN_DEADZONE)) hold x, y, z position steady against any disturbance like wind. - Outside center: - Roll/Pitch sticks control horizontal acceleration over ground in the vehicle's left-right and forward-back directions (respectively). - Throttle stick controls speed of ascent-descent. @@ -62,7 +62,7 @@ All the parameters in the [Multicopter Position Control](../advanced_config/para | 매개변수 | 설명 | | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [MPC_HOLD_DZ](../advanced_config/parameter_reference.md#MPC_HOLD_DZ) | Deadzone of sticks where position hold is enabled. Default: 0.1 (10% of full stick range). | +| [MAN_DEADZONE](../advanced_config/parameter_reference.md#MAN_DEADZONE) | Deadzone of sticks where position hold is enabled. Default: 0.1 (10% of full stick range). | | [MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | 최대 수직 상승 속도. 기본값: 3 m/s. | | [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | 최대 수직 하강 속도. 기본값: 1 m/s. | | [MPC_LAND_ALT1](../advanced_config/parameter_reference.md#MPC_LAND_ALT1) | Altitude for triggering first phase of slow landing. Below this altitude descending velocity gets limited to a value between [MPC_Z_VEL_MAX_DN](#MPC_Z_VEL_MAX_DN) (or `MPC_Z_V_AUTO_DN`) and [MPC_LAND_SPEED](#MPC_LAND_SPEED). Value needs to be higher than [MPC_LAND_ALT2](#MPC_LAND_ALT2). Default 10m. | diff --git a/docs/ko/middleware/uxrce_dds.md b/docs/ko/middleware/uxrce_dds.md index d9d83d1f48..25856d4cf4 100644 --- a/docs/ko/middleware/uxrce_dds.md +++ b/docs/ko/middleware/uxrce_dds.md @@ -65,7 +65,7 @@ PX4 Micro XRCE-DDS Client is based on version `v2.x` which is not compatible wit On Ubuntu you can build from source and install the Agent standalone using the following commands: ```sh -git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git +git clone -b v2.4.3 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git cd Micro-XRCE-DDS-Agent mkdir build cd build @@ -118,78 +118,78 @@ To build the agent within ROS: 1. Create a workspace directory for the agent: - ```sh - mkdir -p ~/px4_ros_uxrce_dds_ws/src - ``` + ```sh + mkdir -p ~/px4_ros_uxrce_dds_ws/src + ``` 2. Clone the source code for the eProsima [Micro-XRCE-DDS-Agent](https://github.com/eProsima/Micro-XRCE-DDS-Agent) to the `/src` directory (the `main` branch is cloned by default): - ```sh - cd ~/px4_ros_uxrce_dds_ws/src - git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git - ``` + ```sh + cd ~/px4_ros_uxrce_dds_ws/src + git clone -b v2.4.3 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git + ``` 3. Source the ROS 2 development environment, and compile the workspace using `colcon`: - :::: tabs + :::: tabs - ::: tab humble + ::: tab humble - ```sh - source /opt/ros/humble/setup.bash - colcon build - ``` + ```sh + source /opt/ros/humble/setup.bash + colcon build + ``` ::: - ::: tab foxy + ::: tab foxy - ```sh - source /opt/ros/foxy/setup.bash - colcon build - ``` + ```sh + source /opt/ros/foxy/setup.bash + colcon build + ``` ::: - :::: + :::: - This builds all the folders under `/src` using the sourced toolchain. + This builds all the folders under `/src` using the sourced toolchain. To run the micro XRCE-DDS agent in the workspace: 1. Source the `local_setup.bash` to make the executables available in the terminal (also `setup.bash` if using a new terminal). - :::: tabs + :::: tabs - ::: tab humble + ::: tab humble - ```sh - source /opt/ros/humble/setup.bash - source install/local_setup.bash - ``` + ```sh + source /opt/ros/humble/setup.bash + source install/local_setup.bash + ``` ::: - ::: tab foxy + ::: tab foxy - ```sh - source /opt/ros/foxy/setup.bash - source install/local_setup.bash - ``` + ```sh + source /opt/ros/foxy/setup.bash + source install/local_setup.bash + ``` ::: - :::: + :::: 1) Start the agent with settings for connecting to the uXRCE-DDS client running on the simulator: - ```sh - MicroXRCEAgent udp4 -p 8888 - ``` + ```sh + MicroXRCEAgent udp4 -p 8888 + ``` ## Starting Agent and Client @@ -279,6 +279,9 @@ The configuration can be done using the [UXRCE-DDS parameters](../advanced_confi - [UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT): Bridge time synchronization enable. The uXRCE-DDS client module can synchronize the timestamp of the messages exchanged over the bridge. This is the default configuration. In certain situations, for example during [simulations](../ros2/user_guide.md#ros-gazebo-and-px4-time-synchronization), this feature may be disabled. + - [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX): Index-based namespace definition + Setting this parameter to any value other than `-1` creates a namespace with the prefix `uav_` and the specified value, e.g. `uav_0`, `uav_1`, etc. + See [namespace](#customizing-the-namespace) for methods to define richer or arbitrary namespaces. :::info Many ports are already have a default configuration. @@ -354,7 +357,7 @@ Therefore, ## Customizing the Namespace -Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](../middleware/dds_topics.md)) or at runtime (which is useful for multi vehicle operations): +Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](../middleware/dds_topics.md)), at runtime, or through a parameter (which is useful for multi vehicle operations): - One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line. This technique can be used both in simulation and real vehicles. @@ -383,6 +386,22 @@ will generate topics under the namespaces: ::: +- A simple index-based namespace can be applied by setting the parameter [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) to a value between 0 and 9999. + This will generate a namespace such as `/uav_0`, `/uav_1`, and so on. + This technique is ideal if vehicles must be persistently associated with namespaces because their clients are automatically started through PX4. + +:::info +PX4 parameters cannot carry rich text strings. +Therefore, you cannot use [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX) to automatically start a client with an arbitrary message namespace through PX4. +You can however specify a namespace when starting the client, using the `-n` argument: + +```sh +# In etc/extras.txt on the MicroSD card +uxrce_dds_client start -n fancy_uav +``` + +This can be included in `etc/extras.txt` as part of a custom [System Startup](../concept/system_startup.md). + ## PX4 ROS 2 QoS Settings PX4 QoS settings for publishers are incompatible with the default QoS settings for ROS 2 subscribers. @@ -466,15 +485,15 @@ Each (`topic`,`type`) pairs defines: 1. A new `publication`, `subscription`, or `subscriptions_multi`, depending on the list to which it is added. 2. The topic _base name_, which **must** coincide with the desired uORB topic name that you want to publish/subscribe. - It is identified by the last token in `topic:` that starts with `/` and does not contains any `/` in it. - `vehicle_odometry`, `vehicle_status` and `offboard_control_mode` are examples of base names. + It is identified by the last token in `topic:` that starts with `/` and does not contains any `/` in it. + `vehicle_odometry`, `vehicle_status` and `offboard_control_mode` are examples of base names. 3. The topic [namespace](https://design.ros2.org/articles/topic_and_service_names.html#namespaces). - By default it is set to: - - `/fmu/out/` for topics that are _published_ by PX4. - - `/fmu/in/` for topics that are _subscribed_ by PX4. + By default it is set to: + - `/fmu/out/` for topics that are _published_ by PX4. + - `/fmu/in/` for topics that are _subscribed_ by PX4. 4. The message type (`VehicleOdometry`, `VehicleStatus`, `OffboardControlMode`, etc.) and the ROS 2 package (`px4_msgs`) that is expected to provide the message definition. 5. **(Optional)**: An additional `rate_limit` field (only for publication entries), which specifies the maximum rate (Hz) at which messages will be published on this topic by PX4 to ROS 2. - If left unspecified, the maximum publication rate limit is set to 100 Hz. + If left unspecified, the maximum publication rate limit is set to 100 Hz. `subscriptions` and `subscriptions_multi` allow us to choose the uORB topic instance that ROS 2 topics are routed to: either a shared instance that may also be getting updates from internal PX4 uORB publishers, or a separate instance that is reserved for ROS2 publications, respectively. Without this mechanism all ROS 2 messages would be routed to the _same_ uORB topic instance (because ROS 2 does not have the concept of [multiple topic instances](../middleware/uorb.md#multi-instance)), and it would not be possible for PX4 subscribers to differentiate between streams from ROS 2 or PX4 publishers. @@ -516,7 +535,7 @@ For a list of services, details and examples see the [service documentation](../ These guidelines explain how to migrate from using PX4 v1.13 [Fast-RTPS](../middleware/micrortps.md) middleware to PX4 v1.14 `uXRCE-DDS` middleware. These are useful if you have [ROS 2 applications written for PX4 v1.13](https://docs.px4.io/v1.13/en/ros/ros2_comm.html), or you have used Fast-RTPS to interface your applications to PX4 [directly](https://docs.px4.io/v1.13/en/middleware/micrortps.html#agent-in-an-offboard-fast-dds-interface-ros-independent). -:::info +::: info This section contains migration-specific information. You should also read the rest of this page to properly understand uXRCE-DDS. ::: diff --git a/docs/ko/modules/modules_driver_ins.md b/docs/ko/modules/modules_driver_ins.md index 93b8af3e7a..ca390b9321 100644 --- a/docs/ko/modules/modules_driver_ins.md +++ b/docs/ko/modules/modules_driver_ins.md @@ -125,6 +125,31 @@ ilabs [arguments...] status Print driver status ``` +## sbgecom + +Source: [drivers/ins/sbgecom](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/sbgecom) + +Description du module + +### Usage {#sbgecom_usage} + +``` +sbgecom [arguments...] + Commands: + start Start driver + [-d ] Serial device + default: /dev/ttyS0 + [-b ] Baudrate device + default: 921600 + [-f ] Config JSON file path + default: /etc/extras/sbg_settings\.json + [-s ] Config JSON string + + status Driver status + + stop Stop driver +``` + ## vectornav Source: [drivers/ins/vectornav](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/vectornav) diff --git a/docs/ko/modules/modules_system.md b/docs/ko/modules/modules_system.md index a62410de31..66b946220f 100644 --- a/docs/ko/modules/modules_system.md +++ b/docs/ko/modules/modules_system.md @@ -140,9 +140,9 @@ commander [arguments...] transition VTOL transition mode Change flight mode - manual|acro|offboard|stabilized|altctl|posctl|position:slow|auto:mission|au - to:loiter|auto:rtl|auto:takeoff|auto:land|auto:precland|ext1 - Flight mode + manual|acro|offboard|stabilized|altctl|posctl|altitude_cruise|position:slow + |auto:mission|auto:loiter|auto:rtl|auto:takeoff|auto:land|auto: + precland|ext1 Flight mode pair @@ -154,6 +154,9 @@ commander [arguments...] lat|lon|alt Origin latitude longitude altitude + set_heading Set current heading + heading degrees from True North [0 360] + poweroff Power off board (if supported) stop @@ -1062,7 +1065,9 @@ uxrce_dds_client [arguments...] values: [-p ] Agent listening port. If not provided, defaults to UXRCE_DDS_PRT - [-n ] Client DDS namespace + [-n ] Client DDS namespace. If not provided but UXRCE_DDS_NS_IDX is + between 0 and 9999 inclusive, then uav_ + UXRCE_DDS_NS_IDX will + be used stop diff --git a/docs/ko/msg_docs/ActuatorMotors.md b/docs/ko/msg_docs/ActuatorMotors.md index ca739f6c22..701465d6ea 100644 --- a/docs/ko/msg_docs/ActuatorMotors.md +++ b/docs/ko/msg_docs/ActuatorMotors.md @@ -18,11 +18,11 @@ uint32 MESSAGE_VERSION = 0 uint64 timestamp # [us] Time since system start uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on -uint16 reversible_flags # Bitset indicating which motors are configured to be reversible +uint16 reversible_flags # [-] Bitset indicating which motors are configured to be reversible uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 # uint8 NUM_CONTROLS = 12 # -float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) +float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) ``` diff --git a/docs/ko/msg_docs/ActuatorServos.md b/docs/ko/msg_docs/ActuatorServos.md index 6f0a677dbf..ea053f67a3 100644 --- a/docs/ko/msg_docs/ActuatorServos.md +++ b/docs/ko/msg_docs/ActuatorServos.md @@ -19,6 +19,6 @@ uint64 timestamp # [us] Time since system start uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on uint8 NUM_CONTROLS = 8 # -float32[8] control # [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. +float32[8] control # [-] [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. ``` diff --git a/docs/ko/msg_docs/ArmingCheckReply.md b/docs/ko/msg_docs/ArmingCheckReply.md index 8d619f5aaf..14af54f0d1 100644 --- a/docs/ko/msg_docs/ArmingCheckReply.md +++ b/docs/ko/msg_docs/ArmingCheckReply.md @@ -1,6 +1,6 @@ # ArmingCheckReply (UORB message) -Arming check reply. +Arming check reply This is a response to an ArmingCheckRequest message sent by the FMU to an external component, such as a ROS 2 navigation mode. The response contains the current set of external mode requirements, and a queue of events indicating recent failures to set the mode (which the FMU may then forward to a ground station). @@ -12,7 +12,7 @@ The message is not used by internal/FMU components, as their mode requirements a [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ArmingCheckReply.msg) ```c -# Arming check reply. +# Arming check reply # # This is a response to an ArmingCheckRequest message sent by the FMU to an external component, such as a ROS 2 navigation mode. # The response contains the current set of external mode requirements, and a queue of events indicating recent failures to set the mode (which the FMU may then forward to a ground station). @@ -25,33 +25,33 @@ uint32 MESSAGE_VERSION = 1 uint64 timestamp # [us] Time since system start. -uint8 request_id # Id of ArmingCheckRequest for which this is a response. -uint8 registration_id # Id of external component emitting this response. +uint8 request_id # [-] Id of ArmingCheckRequest for which this is a response +uint8 registration_id # [-] Id of external component emitting this response -uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies. +uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX] -bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json). -bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json). +bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json) +bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json) +bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json) -bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed. +bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed -uint8 num_events # Number of queued failure messages (Event) in the events field. +uint8 num_events # Number of queued failure messages (Event) in the events field -Event[5] events # Arming failure reasons (Queue of events to report to GCS). +Event[5] events # Arming failure reasons (Queue of events to report to GCS) # Mode requirements -bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope). -bool mode_req_attitude # Requires an attitude estimate. -bool mode_req_local_alt # Requires a local altitude estimate. -bool mode_req_local_position # Requires a local position estimate. -bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate. -bool mode_req_global_position # Requires a global position estimate. -bool mode_req_global_position_relaxed # Requires a relaxed global position estimate. -bool mode_req_mission # Requires an uploaded mission. -bool mode_req_home_position # Requires a home position (such as RTL/Return mode). -bool mode_req_prevent_arming # Prevent arming (such as in Land mode). +bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope) +bool mode_req_attitude # Requires an attitude estimate +bool mode_req_local_alt # Requires a local altitude estimate +bool mode_req_local_position # Requires a local position estimate +bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate +bool mode_req_global_position # Requires a global position estimate +bool mode_req_global_position_relaxed # Requires a relaxed global position estimate +bool mode_req_mission # Requires an uploaded mission +bool mode_req_home_position # Requires a home position (such as RTL/Return mode) +bool mode_req_prevent_arming # Prevent arming (such as in Land mode) bool mode_req_manual_control # Requires a manual controller uint8 ORB_QUEUE_LENGTH = 4 diff --git a/docs/ko/msg_docs/ArmingCheckRequest.md b/docs/ko/msg_docs/ArmingCheckRequest.md index 653d58d2d2..d093dfb5e1 100644 --- a/docs/ko/msg_docs/ArmingCheckRequest.md +++ b/docs/ko/msg_docs/ArmingCheckRequest.md @@ -1,6 +1,6 @@ # ArmingCheckRequest (UORB message) -Arming check request. +Arming check request Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. @@ -12,7 +12,7 @@ The reply will also include the registration_id for each external component, pro [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ArmingCheckRequest.msg) ```c -# Arming check request. +# Arming check request # # Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. # All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. @@ -23,10 +23,10 @@ The reply will also include the registration_id for each external component, pro uint32 MESSAGE_VERSION = 1 -uint64 timestamp # [us] Time since system start. +uint64 timestamp # [us] Time since system start -uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. +uint8 request_id # [-] Id of this request. Allows correlation with associated ArmingCheckReply messages. -uint32 valid_registrations_mask # Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) +uint32 valid_registrations_mask # [-] Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) ``` diff --git a/docs/ko/msg_docs/BatteryStatus.md b/docs/ko/msg_docs/BatteryStatus.md index 7204a2a12f..addd1ae524 100644 --- a/docs/ko/msg_docs/BatteryStatus.md +++ b/docs/ko/msg_docs/BatteryStatus.md @@ -16,76 +16,77 @@ Battery instance information is also logged and streamed in MAVLink telemetry. # Battery instance information is also logged and streamed in MAVLink telemetry. uint32 MESSAGE_VERSION = 1 -uint8 MAX_INSTANCES = 4 +uint8 MAX_INSTANCES = 3 -uint64 timestamp # [us] Time since system start -bool connected # Whether or not a battery is connected. For power modules this is based on a voltage threshold. -float32 voltage_v # [V] [@invalid 0] Battery voltage -float32 current_a # [A] [@invalid -1] Battery current -float32 current_average_a # [A] [@invalid -1] Battery current average (for FW average in level flight) -float32 discharged_mah # [mAh] [@invalid -1] Discharged amount -float32 remaining # [@range 0,1] [@invalid -1] Remaining capacity -float32 scale # [@range 1,] [@invalid -1] Scaling factor to compensate for lower actuation power caused by voltage sag -float32 time_remaining_s # [s] [@invalid NaN] Predicted time remaining until battery is empty under previous averaged load -float32 temperature # [°C] [@invalid NaN] Temperature of the battery -uint8 cell_count # [@invalid 0] Number of cells +uint64 timestamp # [us] Time since system start + +bool connected # Whether or not a battery is connected. For power modules this is based on a voltage threshold. +float32 voltage_v # [V] [@invalid 0] Battery voltage +float32 current_a # [A] [@invalid -1] Battery current +float32 current_average_a # [A] [@invalid -1] Battery current average (for FW average in level flight) +float32 discharged_mah # [mAh] [@invalid -1] Discharged amount +float32 remaining # [@range 0,1] [@invalid -1] Remaining capacity +float32 scale # [-] [@range 1,] [@invalid -1] Scaling factor to compensate for lower actuation power caused by voltage sag +float32 time_remaining_s # [s] [@invalid NaN] Predicted time remaining until battery is empty under previous averaged load +float32 temperature # [°C] [@invalid NaN] Temperature of the battery +uint8 cell_count # [-] [@invalid 0] Number of cells -uint8 source # [@enum SOURCE] Battery source -uint8 SOURCE_POWER_MODULE = 0 # Power module -uint8 SOURCE_EXTERNAL = 1 # External -uint8 SOURCE_ESCS = 2 # ESCs +uint8 source # [@enum SOURCE] Battery source +uint8 SOURCE_POWER_MODULE = 0 # Power module +uint8 SOURCE_EXTERNAL = 1 # External +uint8 SOURCE_ESCS = 2 # ESCs -uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 -uint16 capacity # [mAh] Capacity of the battery when fully charged -uint16 cycle_count # Number of discharge cycles the battery has experienced -uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge -uint16 manufacture_date # Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 -uint16 state_of_health # [%] [@range 0, 100] State of health. FullChargeCapacity/DesignCapacity -uint16 max_error # [%] [@range 1, 100] Max error, expected margin of error in the state-of-charge calculation -uint8 id # ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed -uint16 interface_error # Interface error counter +uint8 priority # [-] Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 +uint16 capacity # [mAh] Capacity of the battery when fully charged +uint16 cycle_count # [-] Number of discharge cycles the battery has experienced +uint16 average_time_to_empty # [minutes] Predicted remaining battery capacity based on the average rate of discharge +uint16 manufacture_date # [-] Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 +uint16 state_of_health # [%] [@range 0, 100] State of health. FullChargeCapacity/DesignCapacity +uint16 max_error # [%] [@range 1, 100] Max error, expected margin of error in the state-of-charge calculation +uint8 id # [-] ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed +uint16 interface_error # [-] Interface error counter -float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages -float32 max_cell_voltage_delta # Max difference between individual cell voltages +float32[14] voltage_cell_v # [V] [@invalid 0] Battery individual cell voltages +float32 max_cell_voltage_delta # [V] Max difference between individual cell voltages -bool is_powering_off # Power off event imminent indication, false if unknown -bool is_required # Set if the battery is explicitly required before arming +bool is_powering_off # Power off event imminent indication, false if unknown +bool is_required # Set if the battery is explicitly required before arming -uint8 warning # [@enum WARNING STATE] Current battery warning -uint8 WARNING_NONE = 0 # No battery low voltage warning active -uint8 WARNING_LOW = 1 # Low voltage warning -uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately -uint8 WARNING_EMERGENCY = 3 # Immediate landing required -uint8 WARNING_FAILED = 4 # Battery has failed completely -uint8 STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field -uint8 STATE_CHARGING = 7 # Battery is charging +uint8 warning # [@enum WARNING STATE] Current battery warning +uint8 WARNING_NONE = 0 # No battery low voltage warning active +uint8 WARNING_LOW = 1 # Low voltage warning +uint8 WARNING_CRITICAL = 2 # Critical voltage, return / abort immediately +uint8 WARNING_EMERGENCY = 3 # Immediate landing required +uint8 WARNING_FAILED = 4 # Battery has failed completely +uint8 STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field +uint8 STATE_CHARGING = 7 # Battery is charging -uint16 faults # [@enum FAULT] Smart battery supply status/fault flags (bitmask) for health indication -uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged -uint8 FAULT_SPIKES = 1 # Voltage spikes -uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed -uint8 FAULT_OVER_CURRENT = 3 # Over-current -uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature -uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault -uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage) -uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware -uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system -uint8 FAULT_HARDWARE_FAILURE = 9 # Hardware problem -uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming -uint8 FAULT_COUNT = 11 # Counter. Keep this as last element +uint16 faults # [@enum FAULT] Smart battery supply status/fault flags (bitmask) for health indication +uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged +uint8 FAULT_SPIKES = 1 # Voltage spikes +uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed +uint8 FAULT_OVER_CURRENT = 3 # Over-current +uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature +uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault +uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage) +uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware +uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system +uint8 FAULT_HARDWARE_FAILURE = 9 # Hardware problem +uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming +uint8 FAULT_COUNT = 11 # Counter. Keep this as last element -float32 full_charge_capacity_wh # [Wh] Compensated battery capacity -float32 remaining_capacity_wh # [Wh] Compensated battery capacity remaining -uint16 over_discharge_count # Number of battery overdischarge -float32 nominal_voltage # [V] Nominal voltage of the battery pack +float32 full_charge_capacity_wh # [Wh] Compensated battery capacity +float32 remaining_capacity_wh # [Wh] Compensated battery capacity remaining +uint16 over_discharge_count # [-] Number of battery overdischarge +float32 nominal_voltage # [V] Nominal voltage of the battery pack -float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate -float32 ocv_estimate # [V] Open circuit voltage estimate -float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate -float32 volt_based_soc_estimate # [@range 0, 1] Normalized volt based state of charge estimate -float32 voltage_prediction # [V] Predicted voltage -float32 prediction_error # [V] Prediction error -float32 estimation_covariance_norm # Norm of the covariance matrix +float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate +float32 ocv_estimate # [V] Open circuit voltage estimate +float32 ocv_estimate_filtered # [V] Filtered open circuit voltage estimate +float32 volt_based_soc_estimate # [-] [@range 0, 1] Normalized volt based state of charge estimate +float32 voltage_prediction # [V] Predicted voltage +float32 prediction_error # [V] Prediction error +float32 estimation_covariance_norm # [-] Norm of the covariance matrix ``` diff --git a/docs/ko/msg_docs/EstimatorStatus.md b/docs/ko/msg_docs/EstimatorStatus.md index e36871df1a..9c24221691 100644 --- a/docs/ko/msg_docs/EstimatorStatus.md +++ b/docs/ko/msg_docs/EstimatorStatus.md @@ -52,7 +52,9 @@ uint8 CS_SYNTHETIC_MAG_Z = 25 # 25 - true when we are using a synthesized measur uint8 CS_VEHICLE_AT_REST = 26 # 26 - true when the vehicle is at rest uint8 CS_GPS_YAW_FAULT = 27 # 27 - true when the GNSS heading has been declared faulty and is no longer being used uint8 CS_RNG_FAULT = 28 # 28 - true when the range finder has been declared faulty and is no longer being used -uint8 CS_GNSS_VEL = 44 # 44 - true if GNSS velocity measurements are being fused +uint8 CS_GNSS_VEL = 44 # 44 - true if GNSS velocity measurement fusion is intended +uint8 CS_GNSS_FAULT = 45 # 45 - true if GNSS measurements have been declared faulty and are no longer used +uint8 CS_YAW_MANUAL = 46 # 46 - true if yaw has been set manually uint32 filter_fault_flags # Bitmask to indicate EKF internal faults # 0 - true if the fusion of the magnetometer X-axis has encountered a numerical error diff --git a/docs/ko/msg_docs/EstimatorStatusFlags.md b/docs/ko/msg_docs/EstimatorStatusFlags.md index 19a6a00d23..0ac832817d 100644 --- a/docs/ko/msg_docs/EstimatorStatusFlags.md +++ b/docs/ko/msg_docs/EstimatorStatusFlags.md @@ -54,6 +54,8 @@ bool cs_valid_fake_pos # 41 - true if a valid constant position is bein bool cs_constant_pos # 42 - true if the vehicle is at a constant position bool cs_baro_fault # 43 - true when the current baro has been declared faulty and is no longer being used bool cs_gnss_vel # 44 - true if GNSS velocity measurement fusion is intended +bool cs_gnss_fault # 45 - true if GNSS measurements have been declared faulty and are no longer used +bool cs_yaw_manual # 46 - true if yaw has been set manually # fault status uint32 fault_status_changes # number of filter fault status (fs) changes diff --git a/docs/ko/msg_docs/PurePursuitStatus.md b/docs/ko/msg_docs/PurePursuitStatus.md index 96577a0220..8d54ba473e 100644 --- a/docs/ko/msg_docs/PurePursuitStatus.md +++ b/docs/ko/msg_docs/PurePursuitStatus.md @@ -7,11 +7,11 @@ Pure pursuit status ```c # Pure pursuit status -uint64 timestamp # [us] Time since system start -float32 lookahead_distance # [m] [@range 0, inf] Lookahead distance of pure the pursuit controller -float32 target_bearing # [rad] [@range -pi, pi] [@frame NED] Target bearing calculated by the pure pursuit controller -float32 crosstrack_error # [m] [@range -inf (Left of the path), inf (Right of the path)] Shortest distance from the vehicle to the path -float32 distance_to_waypoint # [m] [@range -inf, inf]Distance from the vehicle to the current waypoint -float32 bearing_to_waypoint # [rad] [@range -pi, pi] [@frame NED]Bearing towards current waypoint +uint64 timestamp # [us] Time since system start +float32 lookahead_distance # [m] [@range 0, inf] Lookahead distance of pure the pursuit controller +float32 target_bearing # [rad] [@range -pi, pi] [@frame NED] Target bearing calculated by the pure pursuit controller +float32 crosstrack_error # [m] [@range -inf (Left of the path), inf (Right of the path)] Shortest distance from the vehicle to the path +float32 distance_to_waypoint # [m] [@range -inf, inf]Distance from the vehicle to the current waypoint +float32 bearing_to_waypoint # [rad] [@range -pi, pi] [@frame NED]Bearing towards current waypoint ``` diff --git a/docs/ko/msg_docs/RoverAttitudeSetpoint.md b/docs/ko/msg_docs/RoverAttitudeSetpoint.md index bd436278ca..ca75a6e3e2 100644 --- a/docs/ko/msg_docs/RoverAttitudeSetpoint.md +++ b/docs/ko/msg_docs/RoverAttitudeSetpoint.md @@ -7,7 +7,7 @@ Rover Attitude Setpoint ```c # Rover Attitude Setpoint -uint64 timestamp # [us] Time since system start -float32 yaw_setpoint # [rad] [@range -inf, inf] [@frame NED] Yaw setpoint +uint64 timestamp # [us] Time since system start +float32 yaw_setpoint # [rad] [@range -inf, inf] [@frame NED] Yaw setpoint ``` diff --git a/docs/ko/msg_docs/RoverAttitudeStatus.md b/docs/ko/msg_docs/RoverAttitudeStatus.md index e6df929abd..f5a9ce1f02 100644 --- a/docs/ko/msg_docs/RoverAttitudeStatus.md +++ b/docs/ko/msg_docs/RoverAttitudeStatus.md @@ -7,8 +7,8 @@ Rover Attitude Status ```c # Rover Attitude Status -uint64 timestamp # [us] Time since system start -float32 measured_yaw # [rad] [@range -pi, pi] [@frame NED]Measured yaw -float32 adjusted_yaw_setpoint # [rad] [@range -pi, pi] [@frame NED] Yaw setpoint that is being tracked (Applied slew rates) +uint64 timestamp # [us] Time since system start +float32 measured_yaw # [rad] [@range -pi, pi] [@frame NED]Measured yaw +float32 adjusted_yaw_setpoint # [rad] [@range -pi, pi] [@frame NED] Yaw setpoint that is being tracked (Applied slew rates) ``` diff --git a/docs/ko/msg_docs/RoverPositionSetpoint.md b/docs/ko/msg_docs/RoverPositionSetpoint.md index b45aa0515f..751536e7f9 100644 --- a/docs/ko/msg_docs/RoverPositionSetpoint.md +++ b/docs/ko/msg_docs/RoverPositionSetpoint.md @@ -7,11 +7,11 @@ Rover Position Setpoint ```c # Rover Position Setpoint -uint64 timestamp # [us] Time since system start -float32[2] position_ned # [m] [@range -inf, inf] [@frame NED] Target position -float32[2] start_ned # [m] [@range -inf, inf] [@frame NED] [@invalid NaN Defaults to vehicle position] Start position which specifies a line for the rover to track -float32 cruising_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to maximum speed] Cruising speed -float32 arrival_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to 0] Speed the rover should arrive at the target with -float32 yaw # [rad] [@range -pi,pi] [@frame NED] [@invalid NaN Defaults to vehicle yaw] Mecanum only: Specify vehicle yaw during travel +uint64 timestamp # [us] Time since system start +float32[2] position_ned # [m] [@range -inf, inf] [@frame NED] Target position +float32[2] start_ned # [m] [@range -inf, inf] [@frame NED] [@invalid NaN Defaults to vehicle position] Start position which specifies a line for the rover to track +float32 cruising_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to maximum speed] Cruising speed +float32 arrival_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to 0] Speed the rover should arrive at the target with +float32 yaw # [rad] [@range -pi,pi] [@frame NED] [@invalid NaN Defaults to vehicle yaw] Mecanum only: Specify vehicle yaw during travel ``` diff --git a/docs/ko/msg_docs/RoverRateSetpoint.md b/docs/ko/msg_docs/RoverRateSetpoint.md index 9bffa41b80..9bb844e802 100644 --- a/docs/ko/msg_docs/RoverRateSetpoint.md +++ b/docs/ko/msg_docs/RoverRateSetpoint.md @@ -7,7 +7,7 @@ Rover Rate setpoint ```c # Rover Rate setpoint -uint64 timestamp # [us] Time since system start -float32 yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint +uint64 timestamp # [us] Time since system start +float32 yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint ``` diff --git a/docs/ko/msg_docs/RoverRateStatus.md b/docs/ko/msg_docs/RoverRateStatus.md index 684e4c458a..70345fe315 100644 --- a/docs/ko/msg_docs/RoverRateStatus.md +++ b/docs/ko/msg_docs/RoverRateStatus.md @@ -7,9 +7,9 @@ Rover Rate Status ```c # Rover Rate Status -uint64 timestamp # [us] Time since system start -float32 measured_yaw_rate # [rad/s] [@range -inf, inf] [@frame NED] Measured yaw rate -float32 adjusted_yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint that is being tracked (Applied slew rates) -float32 pid_yaw_rate_integral # [] [@range -1, 1] Integral of the PID for the closed loop yaw rate controller +uint64 timestamp # [us] Time since system start +float32 measured_yaw_rate # [rad/s] [@range -inf, inf] [@frame NED] Measured yaw rate +float32 adjusted_yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint that is being tracked (Applied slew rates) +float32 pid_yaw_rate_integral # [-] [@range -1, 1] Integral of the PID for the closed loop yaw rate controller ``` diff --git a/docs/ko/msg_docs/RoverSpeedSetpoint.md b/docs/ko/msg_docs/RoverSpeedSetpoint.md index 9eea46e60f..84176cd1c3 100644 --- a/docs/ko/msg_docs/RoverSpeedSetpoint.md +++ b/docs/ko/msg_docs/RoverSpeedSetpoint.md @@ -7,8 +7,8 @@ Rover Speed Setpoint ```c # Rover Speed Setpoint -uint64 timestamp # [us] Time since system start -float32 speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction -float32 speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction +uint64 timestamp # [us] Time since system start +float32 speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction +float32 speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction ``` diff --git a/docs/ko/msg_docs/RoverSpeedStatus.md b/docs/ko/msg_docs/RoverSpeedStatus.md index 8c212e2b0f..4213e1e5df 100644 --- a/docs/ko/msg_docs/RoverSpeedStatus.md +++ b/docs/ko/msg_docs/RoverSpeedStatus.md @@ -7,12 +7,12 @@ Rover Velocity Status ```c # Rover Velocity Status -uint64 timestamp # [us] Time since system start -float32 measured_speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Measured speed in body x direction -float32 adjusted_speed_body_x_setpoint # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction that is being tracked (Applied slew rates) -float32 pid_throttle_body_x_integral # [] [@range -1, 1] Integral of the PID for the closed loop controller of the speed in body x direction -float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction -float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates) -float32 pid_throttle_body_y_integral # [] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction +uint64 timestamp # [us] Time since system start +float32 measured_speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Measured speed in body x direction +float32 adjusted_speed_body_x_setpoint # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction that is being tracked (Applied slew rates) +float32 pid_throttle_body_x_integral # [-] [@range -1, 1] Integral of the PID for the closed loop controller of the speed in body x direction +float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction +float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates) +float32 pid_throttle_body_y_integral # [-] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction ``` diff --git a/docs/ko/msg_docs/RoverSteeringSetpoint.md b/docs/ko/msg_docs/RoverSteeringSetpoint.md index 3e40a3986b..974f3fc4c9 100644 --- a/docs/ko/msg_docs/RoverSteeringSetpoint.md +++ b/docs/ko/msg_docs/RoverSteeringSetpoint.md @@ -7,7 +7,7 @@ Rover Steering setpoint ```c # Rover Steering setpoint -uint64 timestamp # [us] Time since system start -float32 normalized_steering_setpoint # [@range -1 (Left), 1 (Right)] [@frame Body] Ackermann: Normalized steering angle, Differential/Mecanum: Normalized speed difference between the left and right wheels +uint64 timestamp # [us] Time since system start +float32 normalized_steering_setpoint # [-] [@range -1 (Left), 1 (Right)] [@frame Body] Ackermann: Normalized steering angle, Differential/Mecanum: Normalized speed difference between the left and right wheels ``` diff --git a/docs/ko/msg_docs/RoverThrottleSetpoint.md b/docs/ko/msg_docs/RoverThrottleSetpoint.md index f1c4f7f653..bd5ee93d55 100644 --- a/docs/ko/msg_docs/RoverThrottleSetpoint.md +++ b/docs/ko/msg_docs/RoverThrottleSetpoint.md @@ -7,8 +7,8 @@ Rover Throttle setpoint ```c # Rover Throttle setpoint -uint64 timestamp # [us] Time since system start -float32 throttle_body_x # [] [@range -1 (Backwards), 1 (Forwards)] [@frame Body] Throttle setpoint along body X axis -float32 throttle_body_y # [] [@range -1 (Left), 1 (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Throttle setpoint along body Y axis +uint64 timestamp # [us] Time since system start +float32 throttle_body_x # [-] [@range -1 (Backwards), 1 (Forwards)] [@frame Body] Throttle setpoint along body X axis +float32 throttle_body_y # [-] [@range -1 (Left), 1 (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Throttle setpoint along body Y axis ``` diff --git a/docs/ko/msg_docs/VehicleCommand.md b/docs/ko/msg_docs/VehicleCommand.md index 19557cf496..6c5e87ff5b 100644 --- a/docs/ko/msg_docs/VehicleCommand.md +++ b/docs/ko/msg_docs/VehicleCommand.md @@ -96,6 +96,7 @@ uint16 VEHICLE_CMD_REQUEST_CAMERA_INFORMATION = 521 # Request camera information uint16 VEHICLE_CMD_SET_CAMERA_MODE = 530 # Set camera capture mode (photo, video, etc.). uint16 VEHICLE_CMD_SET_CAMERA_ZOOM = 531 # Set camera zoom. uint16 VEHICLE_CMD_SET_CAMERA_FOCUS = 532 +uint16 VEHICLE_CMD_EXTERNAL_ATTITUDE_ESTIMATE = 620 # Set an external estimate of vehicle attitude in degrees. uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000 # Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw. uint16 VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001 # Gimbal configuration to set which sysid/compid is in primary and secondary control. uint16 VEHICLE_CMD_IMAGE_START_CAPTURE = 2000 # Start image capture sequence. diff --git a/docs/ko/msg_docs/VehicleStatus.md b/docs/ko/msg_docs/VehicleStatus.md index d1deeb0500..9d46e42cb3 100644 --- a/docs/ko/msg_docs/VehicleStatus.md +++ b/docs/ko/msg_docs/VehicleStatus.md @@ -48,7 +48,7 @@ uint8 NAVIGATION_STATE_AUTO_LOITER = 4 # Auto loiter mode uint8 NAVIGATION_STATE_AUTO_RTL = 5 # Auto return to launch mode uint8 NAVIGATION_STATE_POSITION_SLOW = 6 uint8 NAVIGATION_STATE_FREE5 = 7 -uint8 NAVIGATION_STATE_FREE4 = 8 +uint8 NAVIGATION_STATE_ALTITUDE_CRUISE = 8 # Altitude with Cruise mode uint8 NAVIGATION_STATE_FREE3 = 9 uint8 NAVIGATION_STATE_ACRO = 10 # Acro mode uint8 NAVIGATION_STATE_FREE2 = 11 diff --git a/docs/ko/msg_docs/index.md b/docs/ko/msg_docs/index.md index 3699e70936..7887060b3b 100644 --- a/docs/ko/msg_docs/index.md +++ b/docs/ko/msg_docs/index.md @@ -16,8 +16,8 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [ActuatorMotors](ActuatorMotors.md) — Motor control message - [ActuatorServos](ActuatorServos.md) — Servo control message - [AirspeedValidated](AirspeedValidated.md) -- [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply. -- [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request. +- [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply +- [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request - [BatteryStatus](BatteryStatus.md) — Battery status - [ConfigOverrides](ConfigOverrides.md) — Configurable overrides by (external) modes or mode executors - [Event](Event.md) — Events interface diff --git a/docs/ko/releases/main.md b/docs/ko/releases/main.md index e94a31e199..b46977d55c 100644 --- a/docs/ko/releases/main.md +++ b/docs/ko/releases/main.md @@ -44,7 +44,9 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### 제어 -- TBD +- Added new flight mode(s): [Altitude Cruise (MC)](../flight_modes_mc/altitude_cruise.md), Altitude Cruise (FW). + For fixed-wing the mode behaves the same as Altitude mode but you can disable the manual control loss failsafe. (PX4-Autopilot#25435: Add new flight mode: Altitude Cruise + ). ### Estimation @@ -72,7 +74,8 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Multi-Rotor -- TBD +- Removed parameters `MPC_{XY/Z/YAW}_MAN_EXPO` and use default value instead, as they were not deemed necessary anymore. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)). +- Renamed `MPC_HOLD_DZ` to `MAN_DEADZONE` to have it globally available in modes that allow for a dead zone. ([PX4-Autopilot#25435: Add new flight mode: Altitude Cruise](https://github.com/PX4/PX4-Autopilot/pull/25435)). ### 수직이착륙기(VTOL) diff --git a/docs/ko/ros2/user_guide.md b/docs/ko/ros2/user_guide.md index d6c567dcd7..64e10d82e8 100644 --- a/docs/ko/ros2/user_guide.md +++ b/docs/ko/ros2/user_guide.md @@ -97,48 +97,48 @@ To install ROS 2 and its dependencies: 1. Install ROS 2. - :::: tabs + :::: tabs - ::: tab humble - To install ROS 2 "Humble" on Ubuntu 22.04: + ::: tab humble + To install ROS 2 "Humble" on Ubuntu 22.04: - ```sh - sudo apt update && sudo apt install locales - sudo locale-gen en_US en_US.UTF-8 - sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 - export LANG=en_US.UTF-8 - sudo apt install software-properties-common - sudo add-apt-repository universe - sudo apt update && sudo apt install curl -y - sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg - echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null - sudo apt update && sudo apt upgrade -y - sudo apt install ros-humble-desktop - sudo apt install ros-dev-tools - source /opt/ros/humble/setup.bash && echo "source /opt/ros/humble/setup.bash" >> .bashrc - ``` + ```sh + sudo apt update && sudo apt install locales + sudo locale-gen en_US en_US.UTF-8 + sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 + export LANG=en_US.UTF-8 + sudo apt install software-properties-common + sudo add-apt-repository universe + sudo apt update && sudo apt install curl -y + sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg + echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null + sudo apt update && sudo apt upgrade -y + sudo apt install ros-humble-desktop + sudo apt install ros-dev-tools + source /opt/ros/humble/setup.bash && echo "source /opt/ros/humble/setup.bash" >> .bashrc + ``` - The instructions above are reproduced from the official installation guide: [Install ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html). - You can install _either_ the desktop (`ros-humble-desktop`) _or_ bare-bones versions (`ros-humble-ros-base`), _and_ the development tools (`ros-dev-tools`). + The instructions above are reproduced from the official installation guide: [Install ROS 2 Humble](https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html). + You can install _either_ the desktop (`ros-humble-desktop`) _or_ bare-bones versions (`ros-humble-ros-base`), _and_ the development tools (`ros-dev-tools`). ::: - ::: tab foxy - To install ROS 2 "Foxy" on Ubuntu 20.04: + ::: tab foxy + To install ROS 2 "Foxy" on Ubuntu 20.04: - - Follow the official installation guide: [Install ROS 2 Foxy](https://docs.ros.org/en/foxy/Installation/Ubuntu-Install-Debians.html). + - Follow the official installation guide: [Install ROS 2 Foxy](https://docs.ros.org/en/foxy/Installation/Ubuntu-Install-Debians.html). - You can install _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), _and_ the development tools (`ros-dev-tools`). + You can install _either_ the desktop (`ros-foxy-desktop`) _or_ bare-bones versions (`ros-foxy-ros-base`), _and_ the development tools (`ros-dev-tools`). ::: - :::: + :::: 2. Some Python dependencies must also be installed (using **`pip`** or **`apt`**): - ```sh - pip install --user -U empy==3.3.4 pyros-genmsg setuptools - ``` + ```sh + pip install --user -U empy==3.3.4 pyros-genmsg setuptools + ``` ### Setup Micro XRCE-DDS Agent & Client @@ -155,22 +155,22 @@ To setup and start the agent: 2. Enter the following commands to fetch and build the agent from source: - ```sh - git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git - cd Micro-XRCE-DDS-Agent - mkdir build - cd build - cmake .. - make - sudo make install - sudo ldconfig /usr/local/lib/ - ``` + ```sh + git clone -b v2.4.3 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git + cd Micro-XRCE-DDS-Agent + mkdir build + cd build + cmake .. + make + sudo make install + sudo ldconfig /usr/local/lib/ + ``` 3. Start the agent with settings for connecting to the uXRCE-DDS client running on the simulator: - ```sh - MicroXRCEAgent udp4 -p 8888 - ``` + ```sh + MicroXRCEAgent udp4 -p 8888 + ``` The agent is now running, but you won't see much until we start PX4 (in the next step). @@ -187,31 +187,31 @@ To start the simulator (and client): 1. Open a new terminal in the root of the **PX4 Autopilot** repo that was installed above. - :::: tabs + :::: tabs - ::: tab humble + ::: tab humble - - Start a PX4 [Gazebo](../sim_gazebo_gz/index.md) simulation using: + - Start a PX4 [Gazebo](../sim_gazebo_gz/index.md) simulation using: - ```sh - make px4_sitl gz_x500 - ``` + ```sh + make px4_sitl gz_x500 + ``` ::: - ::: tab foxy + ::: tab foxy - - Start a PX4 [Gazebo Classic](../sim_gazebo_classic/index.md) simulation using: + - Start a PX4 [Gazebo Classic](../sim_gazebo_classic/index.md) simulation using: - ```sh - make px4_sitl gazebo-classic - ``` + ```sh + make px4_sitl gazebo-classic + ``` ::: - :::: + :::: The agent and client are now running they should connect. @@ -261,52 +261,52 @@ To create and build the workspace: 2. Create and navigate into a new workspace directory using: - ```sh - mkdir -p ~/ws_sensor_combined/src/ - cd ~/ws_sensor_combined/src/ - ``` + ```sh + mkdir -p ~/ws_sensor_combined/src/ + cd ~/ws_sensor_combined/src/ + ``` - ::: info - A naming convention for workspace folders can make it easier to manage workspaces. + ::: info + A naming convention for workspace folders can make it easier to manage workspaces. ::: 3. Clone the example repository and [px4_msgs](https://github.com/PX4/px4_msgs) to the `/src` directory (the `main` branch is cloned by default, which corresponds to the version of PX4 we are running): - ```sh - git clone https://github.com/PX4/px4_msgs.git - git clone https://github.com/PX4/px4_ros_com.git - ``` + ```sh + git clone https://github.com/PX4/px4_msgs.git + git clone https://github.com/PX4/px4_ros_com.git + ``` 4. Source the ROS 2 development environment into the current terminal and compile the workspace using `colcon`: - :::: tabs + :::: tabs - ::: tab humble + ::: tab humble - ```sh - cd .. - source /opt/ros/humble/setup.bash - colcon build - ``` + ```sh + cd .. + source /opt/ros/humble/setup.bash + colcon build + ``` ::: - ::: tab foxy + ::: tab foxy - ```sh - cd .. - source /opt/ros/foxy/setup.bash - colcon build - ``` + ```sh + cd .. + source /opt/ros/foxy/setup.bash + colcon build + ``` ::: - :::: + :::: - This builds all the folders under `/src` using the sourced toolchain. + This builds all the folders under `/src` using the sourced toolchain. #### Running the Example @@ -322,42 +322,42 @@ In a new terminal: 1. Navigate into the top level of your workspace directory and source the ROS 2 environment (in this case "Humble"): - :::: tabs + :::: tabs - ::: tab humble + ::: tab humble - ```sh - cd ~/ws_sensor_combined/ - source /opt/ros/humble/setup.bash - ``` + ```sh + cd ~/ws_sensor_combined/ + source /opt/ros/humble/setup.bash + ``` ::: - ::: tab foxy + ::: tab foxy - ```sh - cd ~/ws_sensor_combined/ - source /opt/ros/foxy/setup.bash - ``` + ```sh + cd ~/ws_sensor_combined/ + source /opt/ros/foxy/setup.bash + ``` ::: - :::: + :::: 2. Source the `local_setup.bash`. - ```sh - source install/local_setup.bash - ``` + ```sh + source install/local_setup.bash + ``` 3. Now launch the example. - Note here that we use `ros2 launch`, which is described below. + Note here that we use `ros2 launch`, which is described below. - ```sh - ros2 launch px4_ros_com sensor_combined_listener.launch.py - ``` + ```sh + ros2 launch px4_ros_com sensor_combined_listener.launch.py + ``` If this is working you should see data being printed on the terminal/console where you launched the ROS listener: @@ -385,18 +385,18 @@ If you were to use incompatible [message versions](../middleware/uorb.md#message 1. Include the [Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) into the example workspace or a separate workspace by running the following script: - ```sh - cd /path/to/ros_ws - /path/to/PX4-Autopilot/Tools/copy_to_ros_ws.sh . - ``` + ```sh + cd /path/to/ros_ws + /path/to/PX4-Autopilot/Tools/copy_to_ros_ws.sh . + ``` 2. Build and run the translation node: - ```sh - colcon build - source install/local_setup.bash - ros2 run translation_node translation_node_bin - ``` + ```sh + colcon build + source install/local_setup.bash + ros2 run translation_node translation_node_bin + ``` ## Controlling a Vehicle diff --git a/docs/ko/sensor/sbgecom.md b/docs/ko/sensor/sbgecom.md index 6d9a292d53..8c721b5ecb 100644 --- a/docs/ko/sensor/sbgecom.md +++ b/docs/ko/sensor/sbgecom.md @@ -84,7 +84,6 @@ To use the sbgECom driver: If you don't want to have this fallback mechanism, you must disable unwanted sensors. ::: - 4. If using the sbgECom as an INS, disable EKF2 using [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN). 6. Restart PX4. @@ -96,7 +95,7 @@ IMU data should be published at 200Hz. All High Performance and Ellipse 3.0 and higher SBG Systems INS can be configured directly from PX4 firmware: -1. Enable [SBG_CONFIGURATION_EN](../advanced_config/parameter_reference.md#SBG_CONFIGURATION_EN) +1. Enable [SBG_CONFIGURE_EN](../advanced_config/parameter_reference.md#SBG_CONFIGURE_EN). 2. Provide a JSON file `sbg_settings.json` containing SBG Systems INS settings to be applied in your PX4 board `extras` directory (ex: `boards/px4/fmu-v5/extras`). The settings JSON file will be installed in `/etc/extras/sbg_settings.json` on the board. @@ -111,7 +110,6 @@ All High Performance and Ellipse 3.0 and higher SBG Systems INS can be configure ::: 3. For testing purpose, it's also possible to modify SBG Systems INS settings on the fly: - - By passing a JSON file path as argument when starting sbgecom driver (ex: `sbgecom start -f /fs/microsd/new_sbg_settings.json`) - By passing a JSON string as argument when starting sbgecom driver: (ex: `sbgecom start -s {"output":{"comA":{"messages":{"airData":"onChange"}}}}`) From cb9641c989b47dc80fc88cc251baa3e023a8cb76 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Wed, 24 Sep 2025 16:19:00 +1000 Subject: [PATCH 072/812] New Crowdin translations - zh-CN (#25608) Co-authored-by: Crowdin Bot --- docs/zh/ros2/px4_ros2_control_interface.md | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/docs/zh/ros2/px4_ros2_control_interface.md b/docs/zh/ros2/px4_ros2_control_interface.md index 7aea8b7b58..94e34e245b 100644 --- a/docs/zh/ros2/px4_ros2_control_interface.md +++ b/docs/zh/ros2/px4_ros2_control_interface.md @@ -327,15 +327,15 @@ private: }; ``` -- [1]`: 首先创建一个从 [`px4_ros2:::ModeExecutorBase\` ](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1ModeExecutorBase.html ) 继承的类。 -- [2]`: 构造函数采用与执行器相关联的自定义模式,并传递给`ModeExecutorBase\`的构造函数。 -- [3]\`: 我们为想要运行的状态定义一个枚举。 -- [4]`: `onActivate`在执行器激活时被调用。 此时,我们可以开始遍历这些状态了。 - 你是如何操作的,在这个示例中使用`runState\` 方法来执行下一个状态。 -- [5]`: 在切换到状态时,我们会调用 `ModeExecutorBase` 中的异步方法来启动所需的模式:`run`, “eff”、“rtl”、“等等”。 - 这些方法被传递了一个被要求完成的函数; 回调提供一个 `Result\` 参数,告诉您操作是否成功。 +- `[1]`: 首先创建一个从 [`px4_ros2::ModeExecutorBase`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1ModeExecutorBase.html) 继承的类。 +- `[2]`: 构造函数采用与执行器相关联的自定义模式,并传递给`ModeExecutorBase`的构造函数。 +- `[3]`: 我们为想要运行的状态定义一个枚举。 +- `[4]`: `onActivate` 在执行器激活时被调用。 此时,我们可以开始遍历这些状态了。 + 你是如何操作的,在这个示例中使用 `runState` 方法来执行下一个状态。 +- `[5]`: 在切换到状态时,我们会调用 `ModeExecutorBase` 中的异步方法来启动所需的模式:`run`, `eff`、`rtl`、“等等”。 + 这些方法被传递了一个被要求完成的函数; 回调提供一个 `Result` 参数,告诉您操作是否成功。 回调运行下一个成功状态。 -- [6]`: 我们使用 `scheduleMode()\` 方法来启动执行者"拥有模式", 遵循与其他状态处理器相同的模式。 +- `[6]`: 我们使用 `scheduleMode()` 方法来启动执行者"拥有模式", 遵循与其他状态处理器相同的模式。 ### 设置点类型 From cf0def1b69c965613abe53693277881be0cc7a02 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Wed, 24 Sep 2025 09:13:04 +0200 Subject: [PATCH 073/812] docs: minor api updates for ros modes (#25563) --- docs/en/ros2/px4_ros2_control_interface.md | 20 ++++++++++++-------- 1 file changed, 12 insertions(+), 8 deletions(-) diff --git a/docs/en/ros2/px4_ros2_control_interface.md b/docs/en/ros2/px4_ros2_control_interface.md index e7e3151c6c..79866097af 100644 --- a/docs/en/ros2/px4_ros2_control_interface.md +++ b/docs/en/ros2/px4_ros2_control_interface.md @@ -262,9 +262,9 @@ This section steps through an example of how to create a mode executor class. class MyModeExecutor : public px4_ros2::ModeExecutorBase // [1] { public: - MyModeExecutor(rclcpp::Node & node, px4_ros2::ModeBase & owned_mode) // [2] - : ModeExecutorBase(node, px4_ros2::ModeExecutorBase::Settings{}, owned_mode), - _node(node) + MyModeExecutor(px4_ros2::ModeBase & owned_mode) // [2] + : ModeExecutorBase(px4_ros2::ModeExecutorBase::Settings{}, owned_mode), + _node(owned_mode.node()) { } enum class State // [3] @@ -340,8 +340,8 @@ The used types also define the compatibility with different vehicle types. The following sections provide a list of supported setpoint types: -- [GotoSetpointType](#go-to-setpoint-gotosetpointtype): Smooth position and (optionally) heading control -- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics +- [MulticopterGotoSetpointType](#go-to-setpoint-multicoptergotosetpointtype): Smooth position and (optionally) heading control +- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics - [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype): Direct control of motors and flight surface servo setpoints :::tip @@ -350,15 +350,19 @@ The other setpoint types are currently experimental, and can be found in: [px4_r You can add your own setpoint types by adding a class that inherits from `px4_ros2::SetpointBase`, sets the configuration flags according to what the setpoint requires, and then publishes any topic containing a setpoint. ::: -#### Go-to Setpoint (GotoSetpointType) +#### Go-to Setpoint (MulticopterGotoSetpointType) + + ::: info This setpoint type is currently only supported for multicopters. ::: -Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::GotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/goto.hpp) setpoint type. +Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::MulticopterGotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp) setpoint type. The setpoint type is streamed to FMU based position and heading smoothers formulated with time-optimal, maximum-jerk trajectories, with velocity and acceleration constraints. +There is also a [`px4_ros2::MulticopterGotoGlobalSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp) class that allows to send setpoints in global coordinates. + The most trivial use is simply inputting a 3D position into the update method: ```cpp @@ -549,7 +553,7 @@ If you want to control an actuator that does not control the vehicle's motion, b To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration: -- Multicopter mode: use a setpoint type that is compatible with multicopter control. For example: either the [`GotoSetpointType`](#go-to-setpoint-gotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html). +- Multicopter mode: use a setpoint type that is compatible with multicopter control. For example: either the [`MulticopterGotoSetpointType`](#go-to-setpoint-multicoptergotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html). - Fixed-wing mode: Use the [`FwLateralLongitudinalSetpointType`](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype). As long as the VTOL remains in either multicopter or fixed-wing mode throughout the external mode, no additional handling is required. From 26c420c1a67fcf0ea2ff868805e57c381a3081d4 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Wed, 24 Sep 2025 17:14:17 +1000 Subject: [PATCH 074/812] New Crowdin translations - zh-CN (#25609) Co-authored-by: Crowdin Bot --- docs/zh/flight_modes_mc/throw_launch.md | 2 +- docs/zh/ros2/px4_ros2_control_interface.md | 2 +- docs/zh/ros2/px4_ros2_interface_lib.md | 2 +- docs/zh/ros2/px4_ros2_navigation_interface.md | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/docs/zh/flight_modes_mc/throw_launch.md b/docs/zh/flight_modes_mc/throw_launch.md index fed2552df0..8bfa6c55f3 100644 --- a/docs/zh/flight_modes_mc/throw_launch.md +++ b/docs/zh/flight_modes_mc/throw_launch.md @@ -1,6 +1,6 @@ # Throw Launch (Multicopter) -<0/> <1/> + :::warning Experimental diff --git a/docs/zh/ros2/px4_ros2_control_interface.md b/docs/zh/ros2/px4_ros2_control_interface.md index 94e34e245b..8ceacb5b67 100644 --- a/docs/zh/ros2/px4_ros2_control_interface.md +++ b/docs/zh/ros2/px4_ros2_control_interface.md @@ -1,6 +1,6 @@ # PX4 ROS 2 控制接口 -<0/> <1/> + :::warning Experimental diff --git a/docs/zh/ros2/px4_ros2_interface_lib.md b/docs/zh/ros2/px4_ros2_interface_lib.md index b689861fbe..5be98766c8 100644 --- a/docs/zh/ros2/px4_ros2_interface_lib.md +++ b/docs/zh/ros2/px4_ros2_interface_lib.md @@ -1,6 +1,6 @@ # PX4 ROS 2 接口库 -<0/> <1/> + :::warning Experimental diff --git a/docs/zh/ros2/px4_ros2_navigation_interface.md b/docs/zh/ros2/px4_ros2_navigation_interface.md index 120183b7e1..5ef18c1879 100644 --- a/docs/zh/ros2/px4_ros2_navigation_interface.md +++ b/docs/zh/ros2/px4_ros2_navigation_interface.md @@ -1,6 +1,6 @@ # PX4 ROS2 导航接口 -<0/> <1/> + :::warning Experimental From 11359791a09d42221e6c02f1d1451453d4ebbc03 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Wed, 24 Sep 2025 17:25:03 +1000 Subject: [PATCH 075/812] New Crowdin translations - ko (#25610) Co-authored-by: Crowdin Bot --- docs/ko/ros2/px4_ros2_control_interface.md | 152 +++++++++++---------- 1 file changed, 78 insertions(+), 74 deletions(-) diff --git a/docs/ko/ros2/px4_ros2_control_interface.md b/docs/ko/ros2/px4_ros2_control_interface.md index 890858df38..fb7d9a4c76 100644 --- a/docs/ko/ros2/px4_ros2_control_interface.md +++ b/docs/ko/ros2/px4_ros2_control_interface.md @@ -108,92 +108,92 @@ The following steps are required to get started: 2. Clone the repository into the workspace: - ```sh - cd $ros_workspace/src - git clone --recursive https://github.com/Auterion/px4-ros2-interface-lib - ``` + ```sh + cd $ros_workspace/src + git clone --recursive https://github.com/Auterion/px4-ros2-interface-lib + ``` - ::: info - To ensure compatibility, use the latest _main_ branches for PX4, _px4_msgs_ and the library. - See also [here](https://github.com/Auterion/px4-ros2-interface-lib#compatibility-with-px4). + ::: info + To ensure compatibility, use the latest _main_ branches for PX4, _px4_msgs_ and the library. + See also [here](https://github.com/Auterion/px4-ros2-interface-lib#compatibility-with-px4). ::: 3. Build the workspace: - ```sh - cd .. - colcon build - source install/setup.bash - ``` + ```sh + cd .. + colcon build + source install/setup.bash + ``` 4. In a different shell, start PX4 SITL: - ```sh - cd $px4-autopilot - make px4_sitl gazebo-classic - ``` + ```sh + cd $px4-autopilot + make px4_sitl gazebo-classic + ``` - (here we use Gazebo-Classic, but you can use any model or simulator) + (here we use Gazebo-Classic, but you can use any model or simulator) 5. Run the micro XRCE agent in a new shell (you can keep it running afterward): - ```sh - MicroXRCEAgent udp4 -p 8888 - ``` + ```sh + MicroXRCEAgent udp4 -p 8888 + ``` 6. Start QGroundControl. - ::: info - Use QGroundControl Daily, which supports dynamically updating the list of modes. + ::: info + Use QGroundControl Daily, which supports dynamically updating the list of modes. ::: 7. Back in the ROS 2 terminal, run one of the example modes: - ```sh - ros2 run example_mode_manual_cpp example_mode_manual - ``` + ```sh + ros2 run example_mode_manual_cpp example_mode_manual + ``` - You should get an output like this showing 'My Manual Mode' mode being registered: + You should get an output like this showing 'My Manual Mode' mode being registered: - ```sh - [DEBUG] [example_mode_manual]: Checking message compatibility... - [DEBUG] [example_mode_manual]: Subscriber found, continuing - [DEBUG] [example_mode_manual]: Publisher found, continuing - [DEBUG] [example_mode_manual]: Registering 'My Manual Mode' (arming check: 1, mode: 1, mode executor: 0) - [DEBUG] [example_mode_manual]: Subscriber found, continuing - [DEBUG] [example_mode_manual]: Publisher found, continuing - [DEBUG] [example_mode_manual]: Got RegisterExtComponentReply - [DEBUG] [example_mode_manual]: Arming check request (id=1, only printed once) - ``` + ```sh + [DEBUG] [example_mode_manual]: Checking message compatibility... + [DEBUG] [example_mode_manual]: Subscriber found, continuing + [DEBUG] [example_mode_manual]: Publisher found, continuing + [DEBUG] [example_mode_manual]: Registering 'My Manual Mode' (arming check: 1, mode: 1, mode executor: 0) + [DEBUG] [example_mode_manual]: Subscriber found, continuing + [DEBUG] [example_mode_manual]: Publisher found, continuing + [DEBUG] [example_mode_manual]: Got RegisterExtComponentReply + [DEBUG] [example_mode_manual]: Arming check request (id=1, only printed once) + ``` 8. On the PX4 shell, you can check that PX4 registered the new mode: - ```sh - commander status - ``` + ```sh + commander status + ``` - The output should contain: + The output should contain: - ```plain - INFO [commander] Disarmed - INFO [commander] navigation mode: Position - INFO [commander] user intended navigation mode: Position - INFO [commander] in failsafe: no - INFO [commander] External Mode 1: nav_state: 23, name: My Manual Mode - ``` + ```plain + INFO [commander] Disarmed + INFO [commander] navigation mode: Position + INFO [commander] user intended navigation mode: Position + INFO [commander] in failsafe: no + INFO [commander] External Mode 1: nav_state: 23, name: My Manual Mode + ``` 9. At this point you should be able to see the mode in QGroundControl as well: - ![QGC Modes](../../assets/middleware/ros2/px4_ros2_interface_lib/qgc_modes.png) + ![QGC Modes](../../assets/middleware/ros2/px4_ros2_interface_lib/qgc_modes.png) 10. Select the mode, make sure you have a manual control source (physical or virtual joystick), and arm the vehicle. - The mode will then activate, and it should print the following output: + The mode will then activate, and it should print the following output: - ```sh - [DEBUG] [example_mode_manual]: Mode 'My Manual Mode' activated - ``` + ```sh + [DEBUG] [example_mode_manual]: Mode 'My Manual Mode' activated + ``` 11. Now you are ready to create your own mode. @@ -266,9 +266,9 @@ This section steps through an example of how to create a mode executor class. class MyModeExecutor : public px4_ros2::ModeExecutorBase // [1] { public: - MyModeExecutor(rclcpp::Node & node, px4_ros2::ModeBase & owned_mode) // [2] - : ModeExecutorBase(node, px4_ros2::ModeExecutorBase::Settings{}, owned_mode), - _node(node) + MyModeExecutor(px4_ros2::ModeBase & owned_mode) // [2] + : ModeExecutorBase(px4_ros2::ModeExecutorBase::Settings{}, owned_mode), + _node(owned_mode.node()) { } enum class State // [3] @@ -344,8 +344,8 @@ The used types also define the compatibility with different vehicle types. The following sections provide a list of supported setpoint types: -- [GotoSetpointType](#go-to-setpoint-gotosetpointtype): Smooth position and (optionally) heading control -- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics +- [MulticopterGotoSetpointType](#go-to-setpoint-multicoptergotosetpointtype): Smooth position and (optionally) heading control +- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics - [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype): Direct control of motors and flight surface servo setpoints :::tip @@ -354,15 +354,19 @@ The other setpoint types are currently experimental, and can be found in: [px4_r You can add your own setpoint types by adding a class that inherits from `px4_ros2::SetpointBase`, sets the configuration flags according to what the setpoint requires, and then publishes any topic containing a setpoint. ::: -#### Go-to Setpoint (GotoSetpointType) +#### Go-to Setpoint (MulticopterGotoSetpointType) + + :::info This setpoint type is currently only supported for multicopters. ::: -Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::GotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/goto.hpp) setpoint type. +Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::MulticopterGotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp) setpoint type. The setpoint type is streamed to FMU based position and heading smoothers formulated with time-optimal, maximum-jerk trajectories, with velocity and acceleration constraints. +There is also a [`px4_ros2::MulticopterGotoGlobalSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp) class that allows to send setpoints in global coordinates. + The most trivial use is simply inputting a 3D position into the update method: ```cpp @@ -419,7 +423,7 @@ This setpoint is streamed to the PX4 [_FwLateralLongitudinalControl_ module](../ To control the vehicle, at least one lateral **and** one longitudinal setpoint must be provided: 1. Of the longitudinal inputs: either `altitude` or `height_rate` must be finite to control vertical motion. - If both are set to `NAN`, the vehicle will maintain its current altitude. + If both are set to `NAN`, the vehicle will maintain its current altitude. 2. Of the lateral inputs: at least one of `course`, `airspeed_direction`, or `lateral_acceleration` must be finite. For a detailed description of the controllable parameters, please refer to message definitions ([FixedWingLateralSetpoint](../msg_docs/FixedWingLateralSetpoint.md) and [FixedWingLongitudinalSetpoint](../msg_docs/FixedWingLongitudinalSetpoint.md)). @@ -553,7 +557,7 @@ If you want to control an actuator that does not control the vehicle's motion, b To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration: -- Multicopter mode: use a setpoint type that is compatible with multicopter control. For example: either the [`GotoSetpointType`](#go-to-setpoint-gotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html). +- Multicopter mode: use a setpoint type that is compatible with multicopter control. For example: either the [`MulticopterGotoSetpointType`](#go-to-setpoint-multicoptergotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html). - Fixed-wing mode: Use the [`FwLateralLongitudinalSetpointType`](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype). As long as the VTOL remains in either multicopter or fixed-wing mode throughout the external mode, no additional handling is required. @@ -568,24 +572,24 @@ Commanding transitions externally makes the user partially responsible for ensur 3. To command a transition, you can use the `toMulticopter()` or `toFixedwing()` methods on your VTOL object to set the desired state. 4. During transition, send the following combination of setpoints: - ```cpp - // Assuming the instance of the px4_ros2::VTOL object is called vtol + ```cpp + // Assuming the instance of the px4_ros2::VTOL object is called vtol - // Send TrajectorySetpointType as follows: - Eigen::Vector3f acceleration_sp = vtol.computeAccelerationSetpointDuringTransition(); - Eigen::Vector3f velocity_sp{NAN, NAN, 0.f}; + // Send TrajectorySetpointType as follows: + Eigen::Vector3f acceleration_sp = vtol.computeAccelerationSetpointDuringTransition(); + Eigen::Vector3f velocity_sp{NAN, NAN, 0.f}; - _trajectory_setpoint->update(velocity_sp, acceleration_sp); + _trajectory_setpoint->update(velocity_sp, acceleration_sp); - // Send FwLateralLongitudinalSetpointType with lateral input to realign vehicle as desired + // Send FwLateralLongitudinalSetpointType with lateral input to realign vehicle as desired - float course_sp = 0.F; // North + float course_sp = 0.F; // North - _fw_lateral_longitudinal_setpoint->updateWithAltitude(NAN, course_sp) - ``` + _fw_lateral_longitudinal_setpoint->updateWithAltitude(NAN, course_sp) + ``` - This will ensure that the transition is handled properly within PX4. - You can optionally pass a deceleration setpoint to `computeAccelerationSetpointDuringTransition()` to be used during back-transitions. + This will ensure that the transition is handled properly within PX4. + You can optionally pass a deceleration setpoint to `computeAccelerationSetpointDuringTransition()` to be used during back-transitions. To check the current state of the vehicle, use the `getCurrentState()` method on your `px4_ros2::VTOL` object. @@ -598,7 +602,7 @@ If you want to control an independent actuator (a servo), follow these steps: 1. [Configure the output](../payloads/generic_actuator_control.md#generic-actuator-control-with-mavlink). 2. Create an instance of [px4_ros2::PeripheralActuatorControls](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1PeripheralActuatorControls.html) in the constructor of your mode. 3. Call the `set()` method to control the actuator(s). - This can be done independently of any active setpoints. + This can be done independently of any active setpoints. ### 텔레메트리 From b28bdd600b4fd71a803d0fd030a3a8124db68964 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Wed, 24 Sep 2025 17:25:13 +1000 Subject: [PATCH 076/812] New Crowdin translations - uk (#25611) Co-authored-by: Crowdin Bot --- docs/uk/ros2/px4_ros2_control_interface.md | 24 +++++++++++++--------- 1 file changed, 14 insertions(+), 10 deletions(-) diff --git a/docs/uk/ros2/px4_ros2_control_interface.md b/docs/uk/ros2/px4_ros2_control_interface.md index 3eb6178220..1bf129ee18 100644 --- a/docs/uk/ros2/px4_ros2_control_interface.md +++ b/docs/uk/ros2/px4_ros2_control_interface.md @@ -267,9 +267,9 @@ private: class MyModeExecutor : public px4_ros2::ModeExecutorBase // [1] { public: - MyModeExecutor(rclcpp::Node & node, px4_ros2::ModeBase & owned_mode) // [2] - : ModeExecutorBase(node, px4_ros2::ModeExecutorBase::Settings{}, owned_mode), - _node(node) + MyModeExecutor(px4_ros2::ModeBase & owned_mode) // [2] + : ModeExecutorBase(px4_ros2::ModeExecutorBase::Settings{}, owned_mode), + _node(owned_mode.node()) { } enum class State // [3] @@ -345,8 +345,8 @@ private: Наступні розділи надають список підтримуваних типів установок: -- GotoSetpointType: Плавне позиціонування та (за бажанням) керування курсом -- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics +- [MulticopterGotoSetpointType](#go-to-setpoint-multicoptergotosetpointtype): Smooth position and (optionally) heading control +- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics - DirectActuatorsSetpointType: Пряме керування моторами та установками сервоприводів польотних поверхонь :::tip @@ -355,14 +355,18 @@ The other setpoint types are currently experimental, and can be found in: [px4_r Ви можете додати свої власні типи установок, додавши клас, який успадковується від px4_ros2::SetpointBase, встановлює прапорці конфігурації відповідно до того, що вимагає установка, а потім публікує будь-яку тему, що містить установку ::: -#### Установка "перейти до" (GotoSetpointType) +#### Go-to Setpoint (MulticopterGotoSetpointType) + + :::info -Цей тип установки наразі підтримується лише для багтрикоптерів. +This setpoint type is currently only supported for multicopters. ::: -Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::GotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/goto.hpp) setpoint type. -Тип установки транслюється до плавних позиційних та курсових вирівнювачів на основі FMU, сформульованих з оптимальним за часом, максимальною швидкістю зміни прискорення, з обмеженнями швидкості та прискорення. +Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::MulticopterGotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp) setpoint type. +The setpoint type is streamed to FMU based position and heading smoothers formulated with time-optimal, maximum-jerk trajectories, with velocity and acceleration constraints. + +There is also a [`px4_ros2::MulticopterGotoGlobalSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp) class that allows to send setpoints in global coordinates. Найбільш тривіальне використання полягає в простому введенні 3D-позиції в метод оновлення: @@ -554,7 +558,7 @@ and [`FW_THR_MAX`](../advanced_config/parameter_reference.md#FW_THR_MAX). To control a VTOL in an external flight mode, ensure you're returning the correct setpoint type based on the current flight configuration: -- Multicopter mode: use a setpoint type that is compatible with multicopter control. For example: either the [`GotoSetpointType`](#go-to-setpoint-gotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html). +- Multicopter mode: use a setpoint type that is compatible with multicopter control. For example: either the [`MulticopterGotoSetpointType`](#go-to-setpoint-multicoptergotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html). - Fixed-wing mode: Use the [`FwLateralLongitudinalSetpointType`](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype). As long as the VTOL remains in either multicopter or fixed-wing mode throughout the external mode, no additional handling is required. From 8efb5230ae27e7e05ce04f88d83b7efebec1c929 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Wed, 24 Sep 2025 17:25:45 +1000 Subject: [PATCH 077/812] New Crowdin translations - zh-CN (#25612) Co-authored-by: Crowdin Bot --- docs/zh/ros2/px4_ros2_control_interface.md | 32 ++++++++++++---------- 1 file changed, 18 insertions(+), 14 deletions(-) diff --git a/docs/zh/ros2/px4_ros2_control_interface.md b/docs/zh/ros2/px4_ros2_control_interface.md index 8ceacb5b67..602c235848 100644 --- a/docs/zh/ros2/px4_ros2_control_interface.md +++ b/docs/zh/ros2/px4_ros2_control_interface.md @@ -248,11 +248,11 @@ private: }; ``` -- [1]`: 首先创建一个从 [`px4_ros2:::ModeBase\` ](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1ModeBase.html )继承的类。 -- [2]\`: 在构造函数中,我们传递模式名称。 这也使我们能够配置一些其他内容,例如替换飞行控制器的内置模式。 -- [3]:我们在此处创建后续想要使用的所有对象。 +- `[1]`: 首先创建一个从 [`px4_ros2:::ModeBase`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1ModeBase.html)继承的类。 +- `[2]`: 在构造函数中,我们传递模式名称。 这也使我们能够配置一些其他内容,例如替换飞行控制器的内置模式。 +- `[3]`:我们在此处创建后续想要使用的所有对象。 这可以是 RC 输入、设置点类型(s)或遥测数据。 `*this` 作为`Context`传递给每个对象,将对象与模式联系起来。 -- [4]:每当该模式处于激活状态时,此方法会定期被调用(更新频率取决于设定值类型)。 +- `[4]`:每当该模式处于激活状态时,此方法会定期被调用(更新频率取决于设定值类型)。 我们可以在这里开展工作并产生一个新的设定点。 创建此模式的实例后, `mode->doRegister()` 必须被调用,在飞行控制器中进行实际注册,如果失败则返回 `false` 。 @@ -266,9 +266,9 @@ private: class MyModeExecutor : public px4_ros2::ModeExecutorBase // [1] { public: - MyModeExecutor(rclcpp::Node & node, px4_ros2::ModeBase & owned_mode) // [2] - : ModeExecutorBase(node, px4_ros2::ModeExecutorBase::Settings{}, owned_mode), - _node(node) + MyModeExecutor(px4_ros2::ModeBase & owned_mode) // [2] + : ModeExecutorBase(px4_ros2::ModeExecutorBase::Settings{}, owned_mode), + _node(owned_mode.node()) { } enum class State // [3] @@ -344,8 +344,8 @@ private: 以下章节提供了支持的设置点类型列表: -- [GotoSetpointType](#go-to-setpoint-gotosetpointtype): 平稳的位置控制以及(可选的)航向控制 -- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): 对横向和纵向固定翼动态的直接控制 +- [MulticopterGotoSetpointType](#go-to-setpoint-multicoptergotosetpointtype): Smooth position and (optionally) heading control +- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics - [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype):直接控制发动机和飞行地面servo setpoints :::tip @@ -354,14 +354,18 @@ private: 您可以通过添加一个从 `px4_ros2::SetpointBase` 继承的类来添加您自己的 setpoint 类型, 根据设置点的要求设置配置标志,然后发布任何包含设置点的主题。 ::: -#### 转到设置点 (GotoSetpointType) +#### Go-to Setpoint (MulticopterGotoSetpointType) + + :::info -当前,此设定值类型仅支持多旋翼飞行器。 +This setpoint type is currently only supported for multicopters. ::: -以[`px4_ros2:::GotoSetpootType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/goto.hpp) 设置点类型平滑控制位置和(可选) 设置点。 -该设定值类型会传输至FMU,用于基于位置和航向的平滑控制器;该平滑控制器采用时间最优、最大加加速度轨迹设计,并设有速度和加速度约束。 +Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::MulticopterGotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp) setpoint type. +The setpoint type is streamed to FMU based position and heading smoothers formulated with time-optimal, maximum-jerk trajectories, with velocity and acceleration constraints. + +There is also a [`px4_ros2::MulticopterGotoGlobalSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp) class that allows to send setpoints in global coordinates. 最简单的用法就是直接向update method中输入一个3D 位置 @@ -553,7 +557,7 @@ _fw_lateral_longitudinal_setpoint->update(setpoint_s, config_s); 要在外部飞行模式下控制VTOL,需确保根据当前飞行配置返回正确的设定值类型: -- 多旋翼模式:使用与多旋翼控制兼容的设定值类型。 例如:要么[`GotoSetpootType`](#go-to-setpoint-gotosetpointtype) 要么[`TracjectorySettpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html)。 +- 多旋翼模式:使用与多旋翼控制兼容的设定值类型。 For example: either the [`MulticopterGotoSetpointType`](#go-to-setpoint-multicoptergotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html). - 固定翼形模式:使用 [`FwLateralLongitudinalSetpointType` ](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype)。 只要VTOL在整个外部模式期间始终处于多旋翼模式或固定翼模式中的任意一种,就无需额外处理。 From a464825b3370e023c9692d21095aaeb9ab9624a9 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 24 Sep 2025 10:16:53 +1000 Subject: [PATCH 078/812] Fix links to param ref in FW position tuning guide --- docs/en/config_fw/position_tuning_guide_fixedwing.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/en/config_fw/position_tuning_guide_fixedwing.md b/docs/en/config_fw/position_tuning_guide_fixedwing.md index b4061c0b00..d1be79cdd0 100644 --- a/docs/en/config_fw/position_tuning_guide_fixedwing.md +++ b/docs/en/config_fw/position_tuning_guide_fixedwing.md @@ -9,7 +9,7 @@ A pilot tuning the TECS gains should therefore be able to fly and land the plane ::: :::tip -All parameters are documented in the [Parameter Reference](../advanced_config/parameter_reference.md#fw-tecs). +All parameters are documented in the Parameter Reference [FW Performance](../advanced_config/parameter_reference.md#fw-performance) and [FW NPFG Control](../advanced_config/parameter_reference.md#fw-npfg-control) sections. The most important parameters are covered in this guide. ::: @@ -78,7 +78,7 @@ Furthermore, these two values define the height rate limits commanded by the use ### FW Path Control Tuning (Position) -All path control parameters are described [here](../advanced_config/parameter_reference.md#fw-path-control). +All path control parameters are described in [FW NPFG Control (Parameter Reference)](../advanced_config/parameter_reference.md#fw-npfg-control). - [NPFG_PERIOD](../advanced_config/parameter_reference.md#NPFG_PERIOD) - This is the previously called L1 distance and defines the tracking point ahead of the aircraft it's following. A value of 10-20 meters works for most aircraft. From 82ecc9c8c768accb7702646dac97434f1b616c8b Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Wed, 24 Sep 2025 17:41:50 +1000 Subject: [PATCH 079/812] New Crowdin translations - ko (#25613) Co-authored-by: Crowdin Bot --- docs/ko/config_fw/position_tuning_guide_fixedwing.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/ko/config_fw/position_tuning_guide_fixedwing.md b/docs/ko/config_fw/position_tuning_guide_fixedwing.md index 403ce4c12e..0908eaba3a 100644 --- a/docs/ko/config_fw/position_tuning_guide_fixedwing.md +++ b/docs/ko/config_fw/position_tuning_guide_fixedwing.md @@ -9,7 +9,7 @@ An incorrectly set gain during tuning can make altitude or heading control unsta ::: :::tip -All parameters are documented in the [Parameter Reference](../advanced_config/parameter_reference.md#fw-tecs). +All parameters are documented in the Parameter Reference [FW Performance](../advanced_config/parameter_reference.md#fw-performance) and [FW NPFG Control](../advanced_config/parameter_reference.md#fw-npfg-control) sections. 이 가이드에서는 중요한 매개변수들을 설명합니다. ::: @@ -78,7 +78,7 @@ Furthermore, these two values define the height rate limits commanded by the use ### FW Path Control Tuning (Position) -All path control parameters are described [here](../advanced_config/parameter_reference.md#fw-path-control). +All path control parameters are described in [FW NPFG Control (Parameter Reference)](../advanced_config/parameter_reference.md#fw-npfg-control). - [NPFG_PERIOD](../advanced_config/parameter_reference.md#NPFG_PERIOD) - This is the previously called L1 distance and defines the tracking point ahead of the aircraft it's following. A value of 10-20 meters works for most aircraft. From b26046e1378c15bb12a280876e9623b1fbe55b70 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Wed, 24 Sep 2025 17:41:56 +1000 Subject: [PATCH 080/812] New Crowdin translations - uk (#25614) Co-authored-by: Crowdin Bot --- docs/uk/config_fw/position_tuning_guide_fixedwing.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/uk/config_fw/position_tuning_guide_fixedwing.md b/docs/uk/config_fw/position_tuning_guide_fixedwing.md index 0cf742894d..69e19aaa92 100644 --- a/docs/uk/config_fw/position_tuning_guide_fixedwing.md +++ b/docs/uk/config_fw/position_tuning_guide_fixedwing.md @@ -9,7 +9,7 @@ An incorrectly set gain during tuning can make altitude or heading control unsta ::: :::tip -All parameters are documented in the [Parameter Reference](../advanced_config/parameter_reference.md#fw-tecs). +All parameters are documented in the Parameter Reference [FW Performance](../advanced_config/parameter_reference.md#fw-performance) and [FW NPFG Control](../advanced_config/parameter_reference.md#fw-npfg-control) sections. Найважливіші параметри охоплені в цьому керівництві. ::: @@ -78,7 +78,7 @@ Furthermore, these two values define the height rate limits commanded by the use ### Налаштування контролю траєкторії FW (Позиція) -All path control parameters are described [here](../advanced_config/parameter_reference.md#fw-path-control). +All path control parameters are described in [FW NPFG Control (Parameter Reference)](../advanced_config/parameter_reference.md#fw-npfg-control). - [NPFG_PERIOD](../advanced_config/parameter_reference.md#NPFG_PERIOD) - This is the previously called L1 distance and defines the tracking point ahead of the aircraft it's following. Значення 10-20 метрів працює для більшості літаків. From f2c0e09505498134bdfad7676e965549832ea2b3 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Wed, 24 Sep 2025 17:42:43 +1000 Subject: [PATCH 081/812] New Crowdin translations - zh-CN (#25615) Co-authored-by: Crowdin Bot --- docs/zh/config_fw/position_tuning_guide_fixedwing.md | 4 ++-- docs/zh/ros2/px4_ros2_control_interface.md | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/docs/zh/config_fw/position_tuning_guide_fixedwing.md b/docs/zh/config_fw/position_tuning_guide_fixedwing.md index 0b0dd06044..556cbfe6fb 100644 --- a/docs/zh/config_fw/position_tuning_guide_fixedwing.md +++ b/docs/zh/config_fw/position_tuning_guide_fixedwing.md @@ -9,7 +9,7 @@ An incorrectly set gain during tuning can make altitude or heading control unsta ::: :::tip -All parameters are documented in the [Parameter Reference](../advanced_config/parameter_reference.md#fw-tecs). +All parameters are documented in the Parameter Reference [FW Performance](../advanced_config/parameter_reference.md#fw-performance) and [FW NPFG Control](../advanced_config/parameter_reference.md#fw-npfg-control) sections. 本指南将介绍所有重要参数。 ::: @@ -77,7 +77,7 @@ Furthermore, these two values define the height rate limits commanded by the use ### 固定翼轨迹控制调整(位置) -All path control parameters are described [here](../advanced_config/parameter_reference.md#fw-path-control). +All path control parameters are described in [FW NPFG Control (Parameter Reference)](../advanced_config/parameter_reference.md#fw-npfg-control). - [NPFG_PERIOD](../advanced_config/parameter_reference.md#NPFG_PERIOD) - This is the previously called L1 distance and defines the tracking point ahead of the aircraft it's following. 大多数飞机适用于10-20米的数值范围。 diff --git a/docs/zh/ros2/px4_ros2_control_interface.md b/docs/zh/ros2/px4_ros2_control_interface.md index 602c235848..94c3033284 100644 --- a/docs/zh/ros2/px4_ros2_control_interface.md +++ b/docs/zh/ros2/px4_ros2_control_interface.md @@ -398,7 +398,7 @@ _goto_setpoint->update( max_heading_rate_rad_s); ``` -更新方法中,除位置外的所有参数均被模板化为 std::optional 类型。这意味着,若需限制航向速率但不限制平动速度,可通过 std::nullopt 实现这一需求。 +更新方法中,除位置外的所有参数均被模板化为 `std::optional` 类型。这意味着,若需限制航向速率但不限制平动速度,可通过 `std::nullopt` 实现这一需求。 ```cpp _goto_setpoint->update( From 8fe2a2218ece7820bf99ae6182030f465b7523f7 Mon Sep 17 00:00:00 2001 From: Beniamino Pozzan Date: Wed, 24 Sep 2025 09:24:03 +0100 Subject: [PATCH 082/812] docs: clarify Micro-XRCE-DDS-Agent versions ROS 2 compatibility (#25591) --------- Signed-off-by: Beniamino Pozzan Co-authored-by: Hamish Willee --- docs/en/middleware/uxrce_dds.md | 59 +++++++++++++++++++++++++++++---- 1 file changed, 53 insertions(+), 6 deletions(-) diff --git a/docs/en/middleware/uxrce_dds.md b/docs/en/middleware/uxrce_dds.md index d73e475415..8f8da255d3 100644 --- a/docs/en/middleware/uxrce_dds.md +++ b/docs/en/middleware/uxrce_dds.md @@ -106,12 +106,19 @@ The development version, fetched using `--edge` above, does work. ### Build/Run within ROS 2 Workspace -The agent can be built and launched within a ROS 2 workspace (or build standalone and launched from a workspace. +The agent can be built and launched within a ROS 2 workspace (or build standalone and launched from a workspace). You must already have installed ROS 2 following the instructions in: [ROS 2 User Guide > Install ROS 2](../ros2/user_guide.md#install-ros-2). ::: warning This approach will use the existing ROS 2 versions of the Agent dependencies, such as `fastcdr` and `fastdds`. -This considerably speeds up the build process but requires that the Agent dependency versions match the ROS 2 ones. +This considerably speeds up the build process but requires that the Agent dependency versions match the ROS 2 ones: + +| ROS 2 version | Micro-XRCE-DDS-Agent version | +| ------------- | ---------------------------- | +| Foxy | v2.4.2 | +| Humble | v2.4.2 | +| Jazzy | v2.4.3 | + ::: To build the agent within ROS: @@ -124,15 +131,50 @@ To build the agent within ROS: 1. Clone the source code for the eProsima [Micro-XRCE-DDS-Agent](https://github.com/eProsima/Micro-XRCE-DDS-Agent) to the `/src` directory (the `main` branch is cloned by default): + ::::tabs + + ::: tab jazzy + ```sh cd ~/px4_ros_uxrce_dds_ws/src git clone -b v2.4.3 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git ``` + ::: + + ::: tab humble + + ```sh + cd ~/px4_ros_uxrce_dds_ws/src + git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git + ``` + + ::: + + ::: tab foxy + + ```sh + cd ~/px4_ros_uxrce_dds_ws/src + git clone -b v2.4.2 https://github.com/eProsima/Micro-XRCE-DDS-Agent.git + ``` + + ::: + + :::: + 1. Source the ROS 2 development environment, and compile the workspace using `colcon`: :::: tabs + ::: tab jazzy + + ```sh + source /opt/ros/jazzy/setup.bash + colcon build + ``` + + ::: + ::: tab humble ```sh @@ -161,6 +203,15 @@ To run the micro XRCE-DDS agent in the workspace: :::: tabs + ::: tab jazzy + + ```sh + source /opt/ros/jazzy/setup.bash + source install/local_setup.bash + ``` + + ::: + ::: tab humble ```sh @@ -230,7 +281,6 @@ The configuration can be done using the [UXRCE-DDS parameters](../advanced_confi - [UXRCE_DDS_CFG](../advanced_config/parameter_reference.md#UXRCE_DDS_CFG): Set the port to connect on, such as `TELEM2`, `Ethernet`, or `Wifi`. - If using an Ethernet connection: - - [UXRCE_DDS_PRT](../advanced_config/parameter_reference.md#UXRCE_DDS_PRT): Use this to specify the agent UDP listening port. The default value is `8888`. @@ -240,7 +290,6 @@ The configuration can be done using the [UXRCE-DDS parameters](../advanced_confi The default value is `2130706433` which corresponds to the _localhost_ `127.0.0.1`. You can use [Tools/convert_ip.py](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/convert_ip.py) to convert between the formats: - - To obtain the `int32` version of an IP in decimal dot notation the command is: ```sh @@ -254,14 +303,12 @@ The configuration can be done using the [UXRCE-DDS parameters](../advanced_confi ``` - If using a serial connection: - - [SER_TEL2_BAUD](../advanced_config/parameter_reference.md#SER_TEL2_BAUD), [SER_URT6_BAUD](../advanced_config/parameter_reference.md#SER_URT6_BAUD) (and so on): Use the `_BAUD` parameter associated with the serial port to set the baud rate. For example, you'd set a value for `SER_TEL2_BAUD` if you are connecting to the companion using `TELEM2`. For more information see [Serial port configuration](../peripherals/serial_configuration.md#serial-port-configuration). - Some setups might also need these parameters to be set: - - [UXRCE_DDS_KEY](../advanced_config/parameter_reference.md#UXRCE_DDS_KEY): The uXRCE-DDS key. If you're working in a multi-client, single agent configuration, each client should have a unique non-zero key. This is primarily important for multi-vehicle simulations, where all clients are connected in UDP to the same agent. From e71faf38a0390ff5e589537264bae63ea5b4fc53 Mon Sep 17 00:00:00 2001 From: Louis-max-H Date: Wed, 24 Sep 2025 17:08:10 +0200 Subject: [PATCH 083/812] Septentrio GNSS resilience reporting (#25012) Co-authored-by: Tory9 --- msg/CMakeLists.txt | 1 + msg/SensorGnssStatus.msg | 10 ++ msg/SensorGps.msg | 40 +++-- src/drivers/gnss/septentrio/CMakeLists.txt | 2 +- src/drivers/gnss/septentrio/sbf/decoder.cpp | 2 +- src/drivers/gnss/septentrio/sbf/messages.h | 18 ++- src/drivers/gnss/septentrio/septentrio.cpp | 150 +++++++++++++++++- src/drivers/gnss/septentrio/septentrio.h | 23 ++- src/examples/fake_gps/FakeGps.cpp | 8 + src/examples/fake_gps/FakeGps.hpp | 2 + .../checks/estimatorCheck.cpp | 6 +- src/modules/ekf2/EKF2.cpp | 2 +- src/modules/mavlink/mavlink_main.cpp | 4 + src/modules/mavlink/mavlink_messages.cpp | 6 + .../mavlink/streams/GNSS_INTEGRITY.hpp | 115 ++++++++++++++ 15 files changed, 360 insertions(+), 29 deletions(-) create mode 100644 msg/SensorGnssStatus.msg create mode 100644 src/modules/mavlink/streams/GNSS_INTEGRITY.hpp diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index dcb33a5cbd..7eda1cc316 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -195,6 +195,7 @@ set(msg_files SensorCombined.msg SensorCorrection.msg SensorGnssRelative.msg + SensorGnssStatus.msg SensorGps.msg SensorGyro.msg SensorGyroFft.msg diff --git a/msg/SensorGnssStatus.msg b/msg/SensorGnssStatus.msg new file mode 100644 index 0000000000..1562d47ce7 --- /dev/null +++ b/msg/SensorGnssStatus.msg @@ -0,0 +1,10 @@ +# Gnss quality indicators + +uint64 timestamp # time since system start (microseconds) +uint32 device_id # unique device ID for the sensor that does not change between power cycles + +bool quality_available # Set to true if quality indicators are available +uint8 quality_corrections # Corrections quality from 0 to 10, or 255 if not available +uint8 quality_receiver # Overall receiver operating status from 0 to 10, or 255 if not available +uint8 quality_gnss_signals # Quality of GNSS signals from 0 to 10, or 255 if not available +uint8 quality_post_processing # Expected post processing quality from 0 to 10, or 255 if not available diff --git a/msg/SensorGps.msg b/msg/SensorGps.msg index ce2bfad4fd..2e94d174f3 100644 --- a/msg/SensorGps.msg +++ b/msg/SensorGps.msg @@ -30,18 +30,26 @@ float32 vdop # Vertical dilution of precision int32 noise_per_ms # GPS noise per millisecond uint16 automatic_gain_control # Automatic gain control monitor -uint8 JAMMING_STATE_UNKNOWN = 0 -uint8 JAMMING_STATE_OK = 1 -uint8 JAMMING_STATE_WARNING = 2 -uint8 JAMMING_STATE_CRITICAL = 3 -uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical -int32 jamming_indicator # indicates jamming is occurring +uint8 JAMMING_STATE_UNKNOWN = 0 #default +uint8 JAMMING_STATE_OK = 1 +uint8 JAMMING_STATE_MITIGATED = 2 +uint8 JAMMING_STATE_DETECTED = 3 +uint8 jamming_state # indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Mitigated, 3: Detected +int32 jamming_indicator # indicates jamming is occurring -uint8 SPOOFING_STATE_UNKNOWN = 0 -uint8 SPOOFING_STATE_NONE = 1 -uint8 SPOOFING_STATE_INDICATED = 2 -uint8 SPOOFING_STATE_MULTIPLE = 3 -uint8 spoofing_state # indicates whether spoofing has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Warning, 3: Critical +uint8 SPOOFING_STATE_UNKNOWN = 0 #default +uint8 SPOOFING_STATE_OK = 1 +uint8 SPOOFING_STATE_MITIGATED = 2 +uint8 SPOOFING_STATE_DETECTED = 3 +uint8 spoofing_state # indicates whether spoofing has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Mitigated, 3: Detected + +# Combined authentication state (e.g. Galileo OSNMA) +uint8 AUTHENTICATION_STATE_UNKNOWN = 0 #default +uint8 AUTHENTICATION_STATE_INITIALIZING = 1 +uint8 AUTHENTICATION_STATE_ERROR = 2 +uint8 AUTHENTICATION_STATE_OK = 3 +uint8 AUTHENTICATION_STATE_DISABLED = 4 +uint8 authentication_state # GPS signal authentication state float32 vel_m_s # GPS ground speed, (metres/sec) float32 vel_n_m_s # GPS North velocity, (metres/sec) @@ -55,6 +63,16 @@ uint64 time_utc_usec # Timestamp (microseconds, UTC), this is the timestamp whi uint8 satellites_used # Number of satellites used +uint32 SYSTEM_ERROR_OK = 0 #default +uint32 SYSTEM_ERROR_INCOMING_CORRECTIONS = 1 +uint32 SYSTEM_ERROR_CONFIGURATION = 2 +uint32 SYSTEM_ERROR_SOFTWARE = 4 +uint32 SYSTEM_ERROR_ANTENNA = 8 +uint32 SYSTEM_ERROR_EVENT_CONGESTION = 16 +uint32 SYSTEM_ERROR_CPU_OVERLOAD = 32 +uint32 SYSTEM_ERROR_OUTPUT_CONGESTION = 64 +uint32 system_error # General errors with the connected GPS receiver + float32 heading # heading angle of XYZ body frame rel to NED. Set to NaN if not available and updated (used for dual antenna GPS), (rad, [-PI, PI]) float32 heading_offset # heading offset of dual antenna array in body frame. Set to NaN if not applicable. (rad, [-PI, PI]) float32 heading_accuracy # heading accuracy (rad, [0, 2PI]) diff --git a/src/drivers/gnss/septentrio/CMakeLists.txt b/src/drivers/gnss/septentrio/CMakeLists.txt index 6971f57e28..3b3cd47ecc 100644 --- a/src/drivers/gnss/septentrio/CMakeLists.txt +++ b/src/drivers/gnss/septentrio/CMakeLists.txt @@ -37,7 +37,7 @@ px4_add_module( COMPILE_FLAGS # -DDEBUG_BUILD # Enable during development of the module -DSEP_LOG_ERROR # Enable module-level error logs - # -DSEP_LOG_WARN # Enable module-level warning logs + -DSEP_LOG_WARN # Enable module-level warning logs # -DSEP_LOG_INFO # Enable module-level info logs # -DSEP_LOG_TRACE_PARSING # Tracing of parsing steps SRCS diff --git a/src/drivers/gnss/septentrio/sbf/decoder.cpp b/src/drivers/gnss/septentrio/sbf/decoder.cpp index 308d26ef9b..3c66555449 100644 --- a/src/drivers/gnss/septentrio/sbf/decoder.cpp +++ b/src/drivers/gnss/septentrio/sbf/decoder.cpp @@ -163,7 +163,7 @@ int Decoder::parse(QualityInd *message) const int Decoder::parse(RFStatus *message) const { - if (can_parse() && id() == BlockID::PVTGeodetic) { + if (can_parse() && id() == BlockID::RFStatus) { static_assert(sizeof(*message) <= sizeof(_message.payload), "Buffer too small"); memcpy(message, _message.payload, sizeof(RFStatus) - sizeof(RFStatus::rf_band)); diff --git a/src/drivers/gnss/septentrio/sbf/messages.h b/src/drivers/gnss/septentrio/sbf/messages.h index 8b7ca0c95e..704f4c3b6e 100644 --- a/src/drivers/gnss/septentrio/sbf/messages.h +++ b/src/drivers/gnss/septentrio/sbf/messages.h @@ -243,9 +243,14 @@ struct QualityInd { }; struct RFBand { + enum class InfoMode : uint8_t { + Suppressed = 1, + Mitigated = 2, + Interference = 8 + }; uint32_t frequency; uint16_t bandwidth; - uint8_t info_mode: 4; + uint8_t info_mode: 4; uint8_t info_reserved: 2; uint8_t info_antenna_id: 2; }; @@ -261,6 +266,15 @@ struct RFStatus { }; struct GALAuthStatus { + enum class OSNMAStatus : uint16_t { + Disabled = 0, + Initializing = 1, + AwaitingTrustedTimeInfo = 2, + InitFailedInconsistentTime = 3, + InitFailedKROOTInvalid = 4, + InitFailedInvalidParam = 5, + Authenticating = 6, + }; uint16_t osnma_status_status: 3; uint16_t osnma_status_initialization_progress: 8; uint16_t osnma_status_trusted_time_source: 3; @@ -271,6 +285,8 @@ struct GALAuthStatus { uint64_t gal_authentic_mask; uint64_t gps_active_mask; uint64_t gps_authentic_mask; + + OSNMAStatus osnmaStatus() const { return static_cast(osnma_status_status); } }; struct VelCovGeodetic { diff --git a/src/drivers/gnss/septentrio/septentrio.cpp b/src/drivers/gnss/septentrio/septentrio.cpp index d05e0b61e5..f3c182be23 100644 --- a/src/drivers/gnss/septentrio/septentrio.cpp +++ b/src/drivers/gnss/septentrio/septentrio.cpp @@ -92,7 +92,7 @@ constexpr size_t k_min_receiver_read_bytes = 32; */ constexpr uint32_t k_septentrio_receiver_default_baud_rate = 115200; -constexpr uint8_t k_max_command_size = 120; +constexpr uint8_t k_max_command_size = 140; constexpr uint16_t k_timeout_5hz = 500; constexpr uint32_t k_read_buffer_size = 150; constexpr time_t k_gps_epoch_secs = 1234567890ULL; // TODO: This seems wrong @@ -112,7 +112,7 @@ constexpr const char *k_command_reset_hot = "erst,soft,none\n"; constexpr const char *k_command_reset_warm = "erst,soft,PVTData\n"; constexpr const char *k_command_reset_cold = "erst,hard,SatData\n"; constexpr const char *k_command_sbf_output_pvt = - "sso,Stream%" PRIu32 ",%s,PVTGeodetic+VelCovGeodetic+DOP+AttEuler+AttCovEuler+EndOfPVT+ReceiverStatus,%s\n"; + "sso,Stream%lu,%s,PVTGeodetic+VelCovGeodetic+DOP+AttEuler+AttCovEuler+EndOfPVT+ReceiverStatus+GALAuthStatus+RFStatus+QualityInd,%s\n"; constexpr const char *k_command_set_sbf_output = "sso,Stream%" PRIu32 ",%s,%s%s,%s\n"; constexpr const char *k_command_clear_sbf = "sso,Stream%" PRIu32 ",%s,none,off\n"; @@ -967,7 +967,7 @@ SeptentrioDriver::ConfigureResult SeptentrioDriver::configure() } // Output a set of SBF blocks on a given connection at a regular interval. - snprintf(msg, sizeof(msg), k_command_sbf_output_pvt, _receiver_stream_main, com_port, sbf_frequency); + snprintf(msg, sizeof(msg), k_command_sbf_output_pvt, (long unsigned int) _receiver_stream_main, com_port, sbf_frequency); if (!send_message_and_wait_for_ack(msg, k_receiver_ack_timeout_fast)) { SEP_WARN("CONFIG: Failed to configure SBF"); return ConfigureResult::FailedCompletely; @@ -1191,20 +1191,138 @@ int SeptentrioDriver::process_message() if (_sbf_decoder.parse(&receiver_status) == PX4_OK) { _sensor_gps.rtcm_msg_used = receiver_status.rx_state_diff_corr_in ? sensor_gps_s::RTCM_MSG_USED_USED : sensor_gps_s::RTCM_MSG_USED_NOT_USED; _time_synced = receiver_status.rx_state_wn_set && receiver_status.rx_state_tow_set; + + _sensor_gps.system_error = sensor_gps_s::SYSTEM_ERROR_OK; + + if (receiver_status.rx_error_cpu_overload) { + _sensor_gps.system_error |= sensor_gps_s::SYSTEM_ERROR_CPU_OVERLOAD; + } + if (receiver_status.rx_error_antenna) { + _sensor_gps.system_error |= sensor_gps_s::SYSTEM_ERROR_ANTENNA; + } + if (receiver_status.ext_error_diff_corr_error) { + _sensor_gps.system_error |= sensor_gps_s::SYSTEM_ERROR_INCOMING_CORRECTIONS; + } + if (receiver_status.ext_error_setup_error) { + _sensor_gps.system_error |= sensor_gps_s::SYSTEM_ERROR_CONFIGURATION; + } + if (receiver_status.rx_error_software) { + _sensor_gps.system_error |= sensor_gps_s::SYSTEM_ERROR_SOFTWARE; + } + if (receiver_status.rx_error_congestion) { + _sensor_gps.system_error |= sensor_gps_s::SYSTEM_ERROR_OUTPUT_CONGESTION; + } + if (receiver_status.rx_error_missed_event) { + _sensor_gps.system_error |= sensor_gps_s::SYSTEM_ERROR_EVENT_CONGESTION; + } } break; } case BlockID::QualityInd: { + using Type = QualityIndicator::Type; + SEP_TRACE_PARSING("Processing QualityInd SBF message"); + + QualityInd quality_ind; + + if (_sbf_decoder.parse(&quality_ind) == PX4_OK) { + _message_sensor_gnss_status.quality_available = true; + _message_sensor_gnss_status.device_id = get_device_id(); + + _message_sensor_gnss_status.quality_corrections = 255; + _message_sensor_gnss_status.quality_receiver = 255; + _message_sensor_gnss_status.quality_post_processing = 255; + _message_sensor_gnss_status.quality_gnss_signals = 255; + + for (int i = 0; i < math::min(quality_ind.n, static_cast(sizeof(quality_ind.indicators) / sizeof(quality_ind.indicators[0]))); i++) { + int quality = quality_ind.indicators[i].value; + + switch (quality_ind.indicators[i].type) { + case Type::BaseStationMeasurements: + _message_sensor_gnss_status.quality_corrections = quality; + break; + case Type::Overall: + _message_sensor_gnss_status.quality_receiver = quality; + break; + case Type::RTKPostProcessing: + _message_sensor_gnss_status.quality_post_processing = quality; + break; + case Type::GNSSSignalsMainAntenna: + _message_sensor_gnss_status.quality_gnss_signals = quality; + break; + default: + break; + } + } + + + _message_sensor_gnss_status.timestamp = hrt_absolute_time(); + _time_last_qualityind_received = hrt_absolute_time(); + _sensor_gnss_status_pub.publish(_message_sensor_gnss_status); + } + break; } case BlockID::RFStatus: { + using InfoMode = RFBand::InfoMode; + SEP_TRACE_PARSING("Processing RFStatus SBF message"); + + RFStatus rf_status; + + if (_sbf_decoder.parse(&rf_status) == PX4_OK) { + _sensor_gps.jamming_state = sensor_gps_s::JAMMING_STATE_OK; + _sensor_gps.spoofing_state = sensor_gps_s::SPOOFING_STATE_OK; + + for (int i = 0; i < math::min(rf_status.n, static_cast(sizeof(rf_status.rf_band) / sizeof(rf_status.rf_band[0]))); i++) { + InfoMode status = static_cast(rf_status.rf_band[i].info_mode); + + if(status == InfoMode::Interference){ + _sensor_gps.jamming_state = sensor_gps_s::JAMMING_STATE_DETECTED; + break; // Worst case, we don't need to check the other bands + } + + if(status == InfoMode::Suppressed || status == InfoMode::Mitigated){ + _sensor_gps.jamming_state = sensor_gps_s::JAMMING_STATE_MITIGATED; + } + } + + if (rf_status.flags_inauthentic_gnss_signals || rf_status.flags_inauthentic_navigation_message) { + _sensor_gps.spoofing_state = sensor_gps_s::SPOOFING_STATE_DETECTED; + } + _time_last_resilience_received = hrt_absolute_time(); + } + break; } case BlockID::GALAuthStatus: { + using OSNMAStatus = GALAuthStatus::OSNMAStatus; + SEP_TRACE_PARSING("Processing GALAuthStatus SBF message"); + + GALAuthStatus gal_auth_status; + + if (_sbf_decoder.parse(&gal_auth_status) == PX4_OK) { + switch (gal_auth_status.osnmaStatus()) { + case OSNMAStatus::Disabled: + _sensor_gps.authentication_state = sensor_gps_s::AUTHENTICATION_STATE_DISABLED; + break; + case OSNMAStatus::AwaitingTrustedTimeInfo: + case OSNMAStatus::Initializing: + _sensor_gps.authentication_state = sensor_gps_s::AUTHENTICATION_STATE_INITIALIZING; + break; + case OSNMAStatus::InitFailedInconsistentTime: + case OSNMAStatus::InitFailedKROOTInvalid: + case OSNMAStatus::InitFailedInvalidParam: + _sensor_gps.authentication_state = sensor_gps_s::AUTHENTICATION_STATE_ERROR; + break; + case OSNMAStatus::Authenticating: + _sensor_gps.authentication_state = sensor_gps_s::AUTHENTICATION_STATE_OK; + break; + } + } + break; } case BlockID::EndOfPVT: { @@ -1277,6 +1395,31 @@ int SeptentrioDriver::process_message() } } + //Check for how recent the resilience data for reciever is, if outdated set to unknown + if ((_time_last_resilience_received != 0) && (hrt_elapsed_time(&_time_last_resilience_received) > 5_s)) { + _sensor_gps.jamming_state = sensor_gps_s::JAMMING_STATE_UNKNOWN; + _sensor_gps.spoofing_state = sensor_gps_s::SPOOFING_STATE_UNKNOWN; + + _time_last_resilience_received = 0; // Reset + } + + // Check for how recent the status data for receiver is, if outdated set to unknown + if ((_time_last_qualityind_received != 0) && (hrt_elapsed_time(&_time_last_qualityind_received) > 5_s)) { + _message_sensor_gnss_status.quality_available = false; + _message_sensor_gnss_status.device_id = get_device_id(); + _message_sensor_gnss_status.timestamp = hrt_absolute_time(); + + _message_sensor_gnss_status.quality_corrections = 255; + _message_sensor_gnss_status.quality_receiver = 255; + _message_sensor_gnss_status.quality_post_processing = 255; + _message_sensor_gnss_status.quality_gnss_signals = 255; + + + _sensor_gnss_status_pub.publish(_message_sensor_gnss_status); + + _time_last_qualityind_received = 0; // Reset + } + break; } case DecodingStatus::RTCMv3: { @@ -1532,6 +1675,7 @@ void SeptentrioDriver::publish() _sensor_gps.device_id = get_device_id(); _sensor_gps.selected_rtcm_instance = _selected_rtcm_instance; _sensor_gps.rtcm_injection_rate = rtcm_injection_frequency(); + _sensor_gps.timestamp = hrt_absolute_time(); _sensor_gps_pub.publish(_sensor_gps); } diff --git a/src/drivers/gnss/septentrio/septentrio.h b/src/drivers/gnss/septentrio/septentrio.h index 052d6ac1cd..cdc21fd092 100644 --- a/src/drivers/gnss/septentrio/septentrio.h +++ b/src/drivers/gnss/septentrio/septentrio.h @@ -53,6 +53,7 @@ #include #include #include +#include #include #include #include @@ -710,12 +711,16 @@ private: char _port[20] {}; ///< The path of the used serial device hrt_abstime _last_rtcm_injection_time {0}; ///< Time of last RTCM injection uint8_t _selected_rtcm_instance {0}; ///< uORB instance that is being used for RTCM corrections + uint8_t _spoofing_state {0}; ///< Receiver spoofing state + uint8_t _jamming_state {0}; ///< Receiver jamming state bool _time_synced {false}; ///< Receiver time in sync with GPS time const Instance _instance {Instance::Main}; ///< The receiver that this instance of the driver controls uint32_t _chosen_baud_rate {0}; ///< The baud rate requested by the user static px4::atomic _secondary_instance; hrt_abstime _sleep_end {0}; ///< End time for sleeping State _resume_state {State::OpeningSerialPort}; ///< Resume state after sleep + hrt_abstime _time_last_qualityind_received{0}; ///< Time of last quality message reception + hrt_abstime _time_last_resilience_received{0}; ///< Time of last resilience message reception // Module configuration float _heading_offset {0.0f}; ///< The heading offset given by the `SEP_YAW_OFFS` parameter @@ -737,14 +742,16 @@ private: rtcm::Decoder *_rtcm_decoder {nullptr}; ///< RTCM message decoder // uORB topics and subscriptions - sensor_gps_s _sensor_gps{}; ///< uORB topic for position - gps_dump_s *_message_data_to_receiver {nullptr}; ///< uORB topic for dumping data to the receiver - gps_dump_s *_message_data_from_receiver {nullptr}; ///< uORB topic for dumping data from the receiver - satellite_info_s *_message_satellite_info {nullptr}; ///< uORB topic for satellite info - uORB::PublicationMulti _sensor_gps_pub {ORB_ID(sensor_gps)}; ///< uORB publication for gps position - uORB::Publication _gps_dump_pub {ORB_ID(gps_dump)}; ///< uORB publication for dump GPS data - uORB::Publication _gps_inject_data_pub {ORB_ID(gps_inject_data)}; ///< uORB publication for injected data to the receiver - uORB::PublicationMulti _satellite_info_pub {ORB_ID(satellite_info)}; ///< uORB publication for satellite info + sensor_gps_s _sensor_gps {}; ///< uORB topic for position + sensor_gnss_status_s _message_sensor_gnss_status {}; ///< uORB topic for gps status + gps_dump_s *_message_data_to_receiver {nullptr}; ///< uORB topic for dumping data to the receiver + gps_dump_s *_message_data_from_receiver {nullptr}; ///< uORB topic for dumping data from the receiver + satellite_info_s *_message_satellite_info {nullptr}; ///< uORB topic for satellite info + uORB::PublicationMulti _sensor_gps_pub {ORB_ID(sensor_gps)}; ///< uORB publication for gps position + uORB::PublicationMulti _sensor_gnss_status_pub {ORB_ID(sensor_gnss_status)}; ///< uORB publication for gnss status + uORB::Publication _gps_dump_pub {ORB_ID(gps_dump)}; ///< uORB publication for dump GPS data + uORB::Publication _gps_inject_data_pub {ORB_ID(gps_inject_data)}; ///< uORB publication for injected data to the receiver + uORB::PublicationMulti _satellite_info_pub {ORB_ID(satellite_info)}; ///< uORB publication for satellite info uORB::SubscriptionMultiArray _gps_inject_data_sub {ORB_ID::gps_inject_data}; ///< uORB subscription about data to inject to the receiver // Data about update frequencies of various bits of information like RTCM message injection frequency, received data rate... diff --git a/src/examples/fake_gps/FakeGps.cpp b/src/examples/fake_gps/FakeGps.cpp index e2f966e023..ad1166e49c 100644 --- a/src/examples/fake_gps/FakeGps.cpp +++ b/src/examples/fake_gps/FakeGps.cpp @@ -87,6 +87,14 @@ void FakeGps::Run() sensor_gps.satellites_used = 14; sensor_gps.timestamp = hrt_absolute_time(); _sensor_gps_pub.publish(sensor_gps); + + sensor_gnss_status_s sensor_gnss_status{}; + sensor_gnss_status.quality_corrections = 0; + sensor_gnss_status.quality_receiver = 9; + sensor_gnss_status.quality_gnss_signals = 10; + sensor_gnss_status.quality_post_processing = 255; + sensor_gnss_status.timestamp = hrt_absolute_time(); + _sensor_gnss_status_pub.publish(sensor_gnss_status); } int FakeGps::task_spawn(int argc, char *argv[]) diff --git a/src/examples/fake_gps/FakeGps.hpp b/src/examples/fake_gps/FakeGps.hpp index eae3b47512..223f372e44 100644 --- a/src/examples/fake_gps/FakeGps.hpp +++ b/src/examples/fake_gps/FakeGps.hpp @@ -41,6 +41,7 @@ #include #include #include +#include class FakeGps : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem { @@ -66,6 +67,7 @@ private: void Run() override; uORB::PublicationMulti _sensor_gps_pub{ORB_ID(sensor_gps)}; + uORB::PublicationMulti _sensor_gnss_status_pub{ORB_ID(sensor_gnss_status)}; double _latitude{29.6603018}; // Latitude in degrees double _longitude{-82.3160500}; // Longitude in degrees diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp index 60b922bd18..add7456b59 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp @@ -594,15 +594,15 @@ void EstimatorChecks::checkEstimatorStatusFlags(const Context &context, Report & void EstimatorChecks::checkGps(const Context &context, Report &reporter, const sensor_gps_s &vehicle_gps_position) const { - if (vehicle_gps_position.jamming_state == sensor_gps_s::JAMMING_STATE_CRITICAL) { + if (vehicle_gps_position.jamming_state == sensor_gps_s::JAMMING_STATE_DETECTED) { /* EVENT */ reporter.armingCheckFailure(NavModes::None, health_component_t::gps, events::ID("check_estimator_gps_jamming_critical"), - events::Log::Critical, "GPS reports critical jamming state"); + events::Log::Critical, "GPS jamming detected"); if (reporter.mavlink_log_pub()) { - mavlink_log_critical(reporter.mavlink_log_pub(), "GPS reports critical jamming state\t"); + mavlink_log_critical(reporter.mavlink_log_pub(), "GPS jamming detected\t"); } } } diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index c409a3ef47..197179dc6d 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -2467,7 +2467,7 @@ void EKF2::UpdateGpsSample(ekf2_timestamps_s &ekf2_timestamps) .yaw = vehicle_gps_position.heading, //TODO: move to different message .yaw_acc = vehicle_gps_position.heading_accuracy, .yaw_offset = vehicle_gps_position.heading_offset, - .spoofed = vehicle_gps_position.spoofing_state == sensor_gps_s::SPOOFING_STATE_MULTIPLE, + .spoofed = vehicle_gps_position.spoofing_state == sensor_gps_s::SPOOFING_STATE_DETECTED, }; _ekf.setGpsData(gnss_sample); diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index f0a693b085..3b4c39a73e 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1441,6 +1441,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("GIMBAL_MANAGER_STATUS", 0.5f); configure_stream_local("GLOBAL_POSITION", 5.0f); configure_stream_local("GLOBAL_POSITION_INT", 5.0f); + configure_stream_local("GNSS_INTEGRITY", 1.0f); configure_stream_local("GPS2_RAW", 1.0f); configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f); configure_stream_local("GPS_RAW_INT", 5.0f); @@ -1513,6 +1514,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("GIMBAL_DEVICE_SET_ATTITUDE", 5.0f); configure_stream_local("GIMBAL_MANAGER_STATUS", 0.5f); configure_stream_local("GLOBAL_POSITION_INT", 50.0f); + configure_stream_local("GNSS_INTEGRITY", 1.0f); configure_stream_local("GPS2_RAW", unlimited_rate); configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f); configure_stream_local("GPS_RAW_INT", unlimited_rate); @@ -1673,6 +1675,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("ESTIMATOR_STATUS", 5.0f); configure_stream_local("EXTENDED_SYS_STATE", 2.0f); configure_stream_local("GLOBAL_POSITION_INT", 10.0f); + configure_stream_local("GNSS_INTEGRITY", 1.0f); configure_stream_local("GPS2_RAW", unlimited_rate); configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f); configure_stream_local("GPS_RAW_INT", unlimited_rate); @@ -1775,6 +1778,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("GLOBAL_POSITION", 10.0f); configure_stream_local("GLOBAL_POSITION_INT", 10.0f); configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f); + configure_stream_local("GNSS_INTEGRITY", 1.0f); configure_stream_local("GPS2_RAW", unlimited_rate); configure_stream_local("GPS_RAW_INT", unlimited_rate); configure_stream_local("HOME_POSITION", 0.5f); diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 876d4c5825..a68c138747 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -79,6 +79,9 @@ #include "streams/GLOBAL_POSITION.hpp" #endif //MAVLINK_MSG_ID_GLOBAL_POSITION #include "streams/GLOBAL_POSITION_INT.hpp" +#if defined(MAVLINK_MSG_ID_GNSS_INTEGRITY) +#include "streams/GNSS_INTEGRITY.hpp" +#endif #include "streams/GPS_GLOBAL_ORIGIN.hpp" #include "streams/GPS_RAW_INT.hpp" #include "streams/GPS_RTCM_DATA.hpp" @@ -507,6 +510,9 @@ static const StreamListItem streams_list[] = { #if defined(UAVIONIX_ADSB_OUT_DYNAMIC_HPP) create_stream_list_item(), #endif // UAVIONIX_ADSB_OUT_DYNAMIC_HPP +#if defined(GNSS_INTEGRITY_HPP) + create_stream_list_item(), +#endif // GNSS_INTEGRITY_HPP #if defined(AVAILABLE_MODES_HPP) create_stream_list_item(), #endif // AVAILABLE_MODES_HPP diff --git a/src/modules/mavlink/streams/GNSS_INTEGRITY.hpp b/src/modules/mavlink/streams/GNSS_INTEGRITY.hpp new file mode 100644 index 0000000000..a7205952e8 --- /dev/null +++ b/src/modules/mavlink/streams/GNSS_INTEGRITY.hpp @@ -0,0 +1,115 @@ +/**************************************************************************** + * + * Copyright (c) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#ifndef GNSS_INTEGRITY_HPP +#define GNSS_INTEGRITY_HPP + + +#include +#include +#include + +using namespace time_literals; + +class MavlinkStreamGNSSIntegrity : public MavlinkStream +{ +public: + static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamGNSSIntegrity(mavlink); } + + static constexpr const char *get_name_static() { return "GNSS_INTEGRITY"; } + static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_GNSS_INTEGRITY; } + + const char *get_name() const override { return get_name_static(); } + uint16_t get_id() override { return get_id_static(); } + + unsigned get_size() override + { + return _vehicle_gps_position_sub.advertised() ? (MAVLINK_MSG_ID_GNSS_INTEGRITY_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0; + } + +private: + static constexpr int GPS_MAX_RECEIVERS = 2; + + explicit MavlinkStreamGNSSIntegrity(Mavlink *mavlink) : MavlinkStream(mavlink) {} + + uORB::Subscription _vehicle_gps_position_sub{ORB_ID(vehicle_gps_position)}; + uORB::SubscriptionMultiArray _sensor_gnss_status_sub{ORB_ID::sensor_gnss_status}; + + bool send() override + { + sensor_gps_s vehicle_gps_position{}; + + if (_vehicle_gps_position_sub.update(&vehicle_gps_position)) { + mavlink_gnss_integrity_t msg{}; + + msg.id = vehicle_gps_position.device_id; + msg.system_errors = vehicle_gps_position.system_error; + msg.authentication_state = vehicle_gps_position.authentication_state; + msg.jamming_state = vehicle_gps_position.jamming_state; + msg.spoofing_state = vehicle_gps_position.spoofing_state; + + msg.corrections_quality = UINT8_MAX; + msg.system_status_summary = UINT8_MAX; + msg.gnss_signal_quality = UINT8_MAX; + msg.post_processing_quality = UINT8_MAX; + + for (int i = 0; i < GPS_MAX_RECEIVERS; i++) { + sensor_gnss_status_s sensor_gnss_status{}; + + if (_sensor_gnss_status_sub[i].copy(&sensor_gnss_status)) { + if ((hrt_elapsed_time(&sensor_gnss_status.timestamp) < 3_s) + && (sensor_gnss_status.device_id == vehicle_gps_position.device_id) + && (sensor_gnss_status.quality_available)) { + msg.corrections_quality = sensor_gnss_status.quality_corrections; + msg.system_status_summary = sensor_gnss_status.quality_receiver; + msg.gnss_signal_quality = sensor_gnss_status.quality_gnss_signals; + msg.post_processing_quality = sensor_gnss_status.quality_post_processing; + break; + } + } + } + + msg.raim_hfom = UINT16_MAX; + msg.raim_vfom = UINT16_MAX; + + mavlink_msg_gnss_integrity_send_struct(_mavlink->get_channel(), &msg); + + return true; + } + + return false; + } + +}; + +#endif // GNSS_INTEGRITY_HPP From 3925562ce66f2b04945a5f5c91f2aa83463a59a3 Mon Sep 17 00:00:00 2001 From: Parkhb1106 Date: Thu, 25 Sep 2025 03:55:32 +0900 Subject: [PATCH 084/812] commander: fix tune_control timestamp on initial publication --- src/modules/commander/Commander.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 0f891b344b..606445ebb6 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -1790,7 +1790,7 @@ void Commander::run() _power_button_state_sub.copy(&button_state); tune_control_s tune_control{}; - button_state.timestamp = hrt_absolute_time(); + tune_control.timestamp = hrt_absolute_time(); tune_control_pub = orb_advertise(ORB_ID(tune_control), &tune_control); } From 26760e3c2cebddbeead20ab7dd41eaad340d6068 Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Wed, 24 Sep 2025 11:27:24 -0800 Subject: [PATCH 085/812] ekf2: reduce EKF2_MIN_RNG to 0.01 (#25574) --- src/modules/ekf2/params_terrain.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/ekf2/params_terrain.yaml b/src/modules/ekf2/params_terrain.yaml index 5fc361c5cd..6a0b61295d 100644 --- a/src/modules/ekf2/params_terrain.yaml +++ b/src/modules/ekf2/params_terrain.yaml @@ -28,7 +28,7 @@ parameters: where the range finder may be inside its minimum measurements distance when on ground. type: float - default: 0.1 + default: 0.01 min: 0.01 unit: m decimal: 2 From a5c4cc38ac7412d7fcaae4a900f6d3edad2abe0c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Wed, 24 Sep 2025 22:17:25 +0200 Subject: [PATCH 086/812] lightware_laser_i2c: add binary protocol support for SF30/d (#25570) Using the SF30/d with the legacy protocol caused a delay of the measurements of ~1s. This is not the case with the binary protocol anymore. The initialization sequence used for SF20/c did not work and is therefore updated. Tested on both SF20/c and SF30/d. --- docs/en/sensor/sfxx_lidar.md | 11 +- .../lightware_laser_i2c.cpp | 149 ++++++++++-------- .../lightware_laser_i2c/parameters.c | 2 +- 3 files changed, 89 insertions(+), 73 deletions(-) diff --git a/docs/en/sensor/sfxx_lidar.md b/docs/en/sensor/sfxx_lidar.md index 57ad174826..ccc080107c 100644 --- a/docs/en/sensor/sfxx_lidar.md +++ b/docs/en/sensor/sfxx_lidar.md @@ -9,11 +9,12 @@ These are useful for applications including terrain following, precision hoverin The following models are supported by PX4, and can be connected to either the I2C or Serial bus (the tables below indicates what bus can be used for each model). -| Model | Range (m) | Bus | Description | -| ---------------------------------------------------------- | --------- | ----------------- | ------------------------------------------------------------------------------------------ | -| [SF11/C](https://lightwarelidar.com/products/sf11-c-100-m) | 100 | Serial or I2C bus | -| [LW20/C](https://lightware.co.za/products/lw20-c-100-m) | 100 | I2C bus | Waterproofed (IP67) with servo for sense-and-avoid applications | -| [SF45/B](../sensor/sf45_rotating_lidar.md) | 50 | Serial | Rotary Lidar (Used for [Collision Prevention](../computer_vision/collision_prevention.md)) | +| Model | Range (m) | Bus | Description | +| ------------------------------------------------------- | --------- | ----------------- | ------------------------------------------------------------------------------------------ | +| [SF11/C](https://lightwarelidar.com/shop/sf11-c-100-m/) | 100 | Serial or I2C bus | +| [LW20/C](https://lightware.co.za/products/lw20-c-100-m) | 100 | I2C bus | Waterproofed (IP67) with servo for sense-and-avoid applications | +| [SF30/D](https://lightwarelidar.com/shop/sf30-d-200-m/) | 200 | I2C bus | Waterproofed (IP67) | +| [SF45/B](../sensor/sf45_rotating_lidar.md) | 50 | Serial | Rotary Lidar (Used for [Collision Prevention](../computer_vision/collision_prevention.md)) | ::: details Discontinued diff --git a/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp b/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp index 825cbdf97f..73f637addb 100644 --- a/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp +++ b/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp @@ -83,19 +83,33 @@ private: static constexpr uint8_t I2C_LEGACY_CMD_WRITE_LASER_CONTROL = 5; enum class Register : uint8_t { - // see http://support.lightware.co.za/sf20/#/commands + // Common registers ProductName = 0, - DistanceOutput = 27, DistanceData = 44, LaserFiring = 50, + Protocol = 120, + }; + + enum class RegisterSF20 : uint8_t { + // See http://support.lightware.co.za/sf20/#/commands + DistanceOutput = 27, MeasurementMode = 93, ZeroOffset = 94, LostSignalCounter = 95, - Protocol = 120, ServoConnected = 121, }; - static constexpr uint16_t output_data_config = 0b11010110100; + enum class RegisterSF30 : uint8_t { + // See https://lightwarelidar.com/wp-content/uploads/2025/06/SF30D-Product-Guide-v3.pdf + DistanceOutput = 29, + UpdateRate = 76, + LostSignalCounter = 115, + ZeroOffset = 116, + }; + + static constexpr uint16_t output_data_config_sf20 = 0b110'1011'0100; + static constexpr uint8_t output_data_config_sf30 = 0b0111'1110; + struct OutputData { int16_t first_return_median; int16_t first_return_strength; @@ -107,7 +121,8 @@ private: enum class Type { Generic = 0, - LW20c + LW20c, + SF30d, }; enum class State { Configuring, @@ -118,10 +133,11 @@ private: void start(); - int readRegister(Register reg, uint8_t *data, int len); + template + int readRegister(RegisterType reg, uint8_t *data, int len); int configure(); - int enableI2CBinaryProtocol(); + int enableI2CBinaryProtocol(const char *product_name1, const char *product_name2); int collect(); int updateRestriction(); @@ -219,10 +235,11 @@ int LightwareLaser::init() break; case 7: - /* SF/LW30/d (200m 49-20'000Hz) */ + /* SF/SF30/d (200m 39-20'000Hz) */ _px4_rangefinder.set_min_distance(0.2f); _px4_rangefinder.set_max_distance(200.0f); - _conversion_interval = 20409; + _conversion_interval = 25641; + _type = Type::SF30d; break; default: @@ -240,7 +257,8 @@ int LightwareLaser::init() return ret; } -int LightwareLaser::readRegister(Register reg, uint8_t *data, int len) +template +int LightwareLaser::readRegister(RegisterType reg, uint8_t *data, int len) { const uint8_t cmd = (uint8_t)reg; return transfer(&cmd, 1, data, len); @@ -256,12 +274,21 @@ int LightwareLaser::probe() } case Type::LW20c: - // try to enable I2C binary protocol - int ret = enableI2CBinaryProtocol(); + return enableI2CBinaryProtocol("SF20", "LW20"); - if (ret != 0) { - return ret; - } + case Type::SF30d: + return enableI2CBinaryProtocol("SF30", "LW30"); + } + + return -1; +} + +int LightwareLaser::enableI2CBinaryProtocol(const char *product_name1, const char *product_name2) +{ + for (int i = 0; i < 3; ++i) { + // try to enable I2C binary protocol (this command is undocumented) + const uint8_t cmd[] = {(uint8_t)Register::Protocol, 0xaa, 0xaa}; + int ret = transfer(cmd, sizeof(cmd), nullptr, 0); // read the product name uint8_t product_name[16]; @@ -269,43 +296,10 @@ int LightwareLaser::probe() product_name[sizeof(product_name) - 1] = '\0'; PX4_DEBUG("product: %s", product_name); - if (ret == 0 && (strncmp((const char *)product_name, "SF20", sizeof(product_name)) == 0 || - strncmp((const char *)product_name, "LW20", sizeof(product_name)) == 0)) { + if (ret == 0 && (strncmp((const char *)product_name, product_name1, sizeof(product_name)) == 0 || + strncmp((const char *)product_name, product_name2, sizeof(product_name)) == 0)) { return 0; } - - return -1; - } - - return -1; -} - -int LightwareLaser::enableI2CBinaryProtocol() -{ - const uint8_t cmd[] = {(uint8_t)Register::Protocol, 0xaa, 0xaa}; - int ret = transfer(cmd, sizeof(cmd), nullptr, 0); - - if (ret != 0) { - return ret; - } - - // Now read and check against the expected values - for (int i = 0; i < 2; ++i) { - uint8_t value[2]; - ret = transfer(cmd, 1, value, sizeof(value)); - - if (ret != 0) { - return ret; - } - - PX4_DEBUG("protocol values: 0x%" PRIx8 " 0x%" PRIx8, value[0], value[1]); - - if (value[0] == 0xcc && value[1] == 0x00) { - return 0; - } - - // Occasionally the previous transfer returns ret == value[0] == value[1] == 0. If so, wait a bit and retry - px4_usleep(1000); } return -1; @@ -330,23 +324,42 @@ int LightwareLaser::configure() } break; - case Type::LW20c: + case Type::LW20c: { + // There are commonly 2 hardware variants (SF + LW) with the same specifications + int ret = enableI2CBinaryProtocol("SF20", "LW20"); + const uint8_t cmd1[] = {(uint8_t)RegisterSF20::ServoConnected, 0}; + ret |= transfer(cmd1, sizeof(cmd1), nullptr, 0); + const uint8_t cmd2[] = {(uint8_t)RegisterSF20::ZeroOffset, 0, 0, 0, 0}; + ret |= transfer(cmd2, sizeof(cmd2), nullptr, 0); + const uint8_t cmd3[] = {(uint8_t)RegisterSF20::MeasurementMode, 1}; // 48Hz + ret |= transfer(cmd3, sizeof(cmd3), nullptr, 0); + const uint8_t cmd4[] = {(uint8_t)RegisterSF20::DistanceOutput, output_data_config_sf20 & 0xff, (output_data_config_sf20 >> 8) & 0xff, 0, 0}; + ret |= transfer(cmd4, sizeof(cmd4), nullptr, 0); + const uint8_t cmd5[] = {(uint8_t)RegisterSF20::LostSignalCounter, 0, 0, 0, 0}; // immediately report lost signal + ret |= transfer(cmd5, sizeof(cmd5), nullptr, 0); + const uint8_t cmd6[] = {(uint8_t)Register::LaserFiring, (uint8_t)(_restriction ? 0 : 1)}; + ret |= transfer(cmd6, sizeof(cmd6), nullptr, 0); - int ret = enableI2CBinaryProtocol(); - const uint8_t cmd1[] = {(uint8_t)Register::ServoConnected, 0}; - ret |= transfer(cmd1, sizeof(cmd1), nullptr, 0); - const uint8_t cmd2[] = {(uint8_t)Register::ZeroOffset, 0, 0, 0, 0}; - ret |= transfer(cmd2, sizeof(cmd2), nullptr, 0); - const uint8_t cmd3[] = {(uint8_t)Register::MeasurementMode, 1}; // 48Hz - ret |= transfer(cmd3, sizeof(cmd3), nullptr, 0); - const uint8_t cmd4[] = {(uint8_t)Register::DistanceOutput, output_data_config & 0xff, (output_data_config >> 8) & 0xff, 0, 0}; - ret |= transfer(cmd4, sizeof(cmd4), nullptr, 0); - const uint8_t cmd5[] = {(uint8_t)Register::LostSignalCounter, 0, 0, 0, 0}; // immediately report lost signal - ret |= transfer(cmd5, sizeof(cmd5), nullptr, 0); - const uint8_t cmd6[] = {(uint8_t)Register::LaserFiring, (uint8_t)(_restriction ? 0 : 1)}; - ret |= transfer(cmd6, sizeof(cmd6), nullptr, 0); + return ret; + } + break; - return ret; + case Type::SF30d: { + // There are commonly 2 hardware variants (SF + LW) with the same specifications + int ret = enableI2CBinaryProtocol("SF30", "LW30"); + const uint8_t cmd2[] = {(uint8_t)RegisterSF30::ZeroOffset, 0, 0, 0, 0}; + ret |= transfer(cmd2, sizeof(cmd2), nullptr, 0); + const uint8_t cmd3[] = {(uint8_t)RegisterSF30::UpdateRate, 9}; // 39Hz + ret |= transfer(cmd3, sizeof(cmd3), nullptr, 0); + const uint8_t cmd4[] = {(uint8_t)RegisterSF30::DistanceOutput, output_data_config_sf30, 0, 0, 0}; + ret |= transfer(cmd4, sizeof(cmd4), nullptr, 0); + const uint8_t cmd5[] = {(uint8_t)RegisterSF30::LostSignalCounter, 0, 0, 0, 0}; // immediately report lost signal + ret |= transfer(cmd5, sizeof(cmd5), nullptr, 0); + const uint8_t cmd6[] = {(uint8_t)Register::LaserFiring, (uint8_t)(_restriction ? 0 : 1)}; + ret |= transfer(cmd6, sizeof(cmd6), nullptr, 0); + + return ret; + } break; } @@ -378,6 +391,7 @@ int LightwareLaser::collect() } case Type::LW20c: + case Type::SF30d: /* read from the sensor */ perf_begin(_sample_perf); @@ -479,7 +493,8 @@ int LightwareLaser::updateRestriction() return transfer(cmd, sizeof(cmd), nullptr, 0); } - case Type::LW20c: { + case Type::LW20c: + case Type::SF30d: { const uint8_t cmd[] = {(uint8_t)Register::LaserFiring, (uint8_t)(_restriction ? 0 : 1)}; return transfer(cmd, sizeof(cmd), nullptr, 0); } @@ -551,7 +566,7 @@ void LightwareLaser::print_usage() R"DESCR_STR( ### Description -I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20. +I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20, SF30/d. Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html )DESCR_STR"); diff --git a/src/drivers/distance_sensor/lightware_laser_i2c/parameters.c b/src/drivers/distance_sensor/lightware_laser_i2c/parameters.c index 161e9d3cab..40b8264f49 100644 --- a/src/drivers/distance_sensor/lightware_laser_i2c/parameters.c +++ b/src/drivers/distance_sensor/lightware_laser_i2c/parameters.c @@ -36,7 +36,7 @@ * * @reboot_required true * @min 0 - * @max 6 + * @max 7 * @group Sensors * @value 0 Disabled * @value 1 SF10/a From 2ec040781509cf05950ace1c0c7cb02e85e469be Mon Sep 17 00:00:00 2001 From: Radiolink <31606489+radiolinkW@users.noreply.github.com> Date: Thu, 25 Sep 2025 04:17:43 +0800 Subject: [PATCH 087/812] boards: add Radiolink PIX6 (#25562) * boards: add Radiolink PIX6 * Fix newlines and format issues * Fix newlines issues * docs:add radiolink_pix6.md document * Subedit, prettier, get images * Add hero image * docs:Add some necessary instructions * Subedit --------- Co-authored-by: Ubuntu Co-authored-by: Hamish Willee --- boards/radiolink/PIX6/default.px4board | 107 ++++ .../PIX6/extras/px4_io-v2_default.bin | Bin 0 -> 40160 bytes boards/radiolink/PIX6/firmware.prototype | 13 + boards/radiolink/PIX6/init/rc.board_defaults | 14 + boards/radiolink/PIX6/init/rc.board_extras | 9 + boards/radiolink/PIX6/init/rc.board_sensors | 53 ++ boards/radiolink/PIX6/nuttx-config/Kconfig | 17 + .../PIX6/nuttx-config/include/board.h | 455 ++++++++++++++++++ .../PIX6/nuttx-config/include/board_dma_map.h | 39 ++ .../radiolink/PIX6/nuttx-config/nsh/defconfig | 259 ++++++++++ .../PIX6/nuttx-config/scripts/kernel-space.ld | 146 ++++++ .../PIX6/nuttx-config/scripts/memory.ld | 98 ++++ .../PIX6/nuttx-config/scripts/script.ld | 181 +++++++ .../PIX6/nuttx-config/scripts/user-space.ld | 124 +++++ boards/radiolink/PIX6/src/CMakeLists.txt | 55 +++ boards/radiolink/PIX6/src/board_config.h | 293 +++++++++++ boards/radiolink/PIX6/src/can.c | 124 +++++ boards/radiolink/PIX6/src/i2c.cpp | 39 ++ boards/radiolink/PIX6/src/init.cpp | 277 +++++++++++ boards/radiolink/PIX6/src/led.c | 227 +++++++++ boards/radiolink/PIX6/src/mtd.cpp | 78 +++ boards/radiolink/PIX6/src/sdio.c | 177 +++++++ boards/radiolink/PIX6/src/spi.cpp | 54 +++ boards/radiolink/PIX6/src/timer_config.cpp | 54 +++ boards/radiolink/PIX6/src/usb.c | 110 +++++ .../radiolink_pix6/left_view.png | Bin 0 -> 53795 bytes .../radiolink_pix6/radiolink_pix6_hero.png | Bin 0 -> 1159928 bytes .../radiolink_power_modules.png | Bin 0 -> 156667 bytes .../radiolink_pix6/rear_view.png | Bin 0 -> 123976 bytes .../radiolink_pix6/right_view.png | Bin 0 -> 51865 bytes .../radiolink_pix6/top_view.png | Bin 0 -> 230145 bytes docs/en/SUMMARY.md | 1 + .../autopilot_manufacturer_supported.md | 1 + docs/en/flight_controller/radiolink_pix6.md | 346 +++++++++++++ 34 files changed, 3351 insertions(+) create mode 100644 boards/radiolink/PIX6/default.px4board create mode 100755 boards/radiolink/PIX6/extras/px4_io-v2_default.bin create mode 100644 boards/radiolink/PIX6/firmware.prototype create mode 100644 boards/radiolink/PIX6/init/rc.board_defaults create mode 100644 boards/radiolink/PIX6/init/rc.board_extras create mode 100644 boards/radiolink/PIX6/init/rc.board_sensors create mode 100644 boards/radiolink/PIX6/nuttx-config/Kconfig create mode 100644 boards/radiolink/PIX6/nuttx-config/include/board.h create mode 100644 boards/radiolink/PIX6/nuttx-config/include/board_dma_map.h create mode 100644 boards/radiolink/PIX6/nuttx-config/nsh/defconfig create mode 100644 boards/radiolink/PIX6/nuttx-config/scripts/kernel-space.ld create mode 100644 boards/radiolink/PIX6/nuttx-config/scripts/memory.ld create mode 100644 boards/radiolink/PIX6/nuttx-config/scripts/script.ld create mode 100644 boards/radiolink/PIX6/nuttx-config/scripts/user-space.ld create mode 100644 boards/radiolink/PIX6/src/CMakeLists.txt create mode 100644 boards/radiolink/PIX6/src/board_config.h create mode 100644 boards/radiolink/PIX6/src/can.c create mode 100644 boards/radiolink/PIX6/src/i2c.cpp create mode 100644 boards/radiolink/PIX6/src/init.cpp create mode 100644 boards/radiolink/PIX6/src/led.c create mode 100644 boards/radiolink/PIX6/src/mtd.cpp create mode 100644 boards/radiolink/PIX6/src/sdio.c create mode 100644 boards/radiolink/PIX6/src/spi.cpp create mode 100644 boards/radiolink/PIX6/src/timer_config.cpp create mode 100644 boards/radiolink/PIX6/src/usb.c create mode 100644 docs/assets/flight_controller/radiolink_pix6/left_view.png create mode 100644 docs/assets/flight_controller/radiolink_pix6/radiolink_pix6_hero.png create mode 100644 docs/assets/flight_controller/radiolink_pix6/radiolink_power_modules.png create mode 100644 docs/assets/flight_controller/radiolink_pix6/rear_view.png create mode 100644 docs/assets/flight_controller/radiolink_pix6/right_view.png create mode 100644 docs/assets/flight_controller/radiolink_pix6/top_view.png create mode 100644 docs/en/flight_controller/radiolink_pix6.md diff --git a/boards/radiolink/PIX6/default.px4board b/boards/radiolink/PIX6/default.px4board new file mode 100644 index 0000000000..abb34d8de7 --- /dev/null +++ b/boards/radiolink/PIX6/default.px4board @@ -0,0 +1,107 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS3" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2" +CONFIG_DRIVERS_ADC_ADS1115=y +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_GOERTEK_SPA06=y +CONFIG_DRIVERS_BAROMETER_MS5611=y +CONFIG_DRIVERS_BATT_SMBUS=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y +CONFIG_DRIVERS_IMU_INVENSENSE_MPU6500=y +CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y +CONFIG_DRIVERS_IRLOCK=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_COMMON_OSD=y +CONFIG_DRIVERS_OSD_MSP_OSD=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_POWER_MONITOR_INA228=y +CONFIG_DRIVERS_POWER_MONITOR_INA238=y +CONFIG_DRIVERS_PWM_INPUT=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_PX4IO=y +CONFIG_COMMON_RC=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_DRIVERS_SMART_BATTERY_BATMON=y +CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=6 +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y +CONFIG_MODULES_PAYLOAD_DELIVERER=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_ROVER_POS_CONTROL=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_UUV_ATT_CONTROL=y +CONFIG_MODULES_UUV_POS_CONTROL=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BL_UPDATE=y +CONFIG_SYSTEMCMDS_BSONDUMP=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_DUMPFILE=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_REFLECT=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_USB_CONNECTED=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/radiolink/PIX6/extras/px4_io-v2_default.bin b/boards/radiolink/PIX6/extras/px4_io-v2_default.bin new file mode 100755 index 0000000000000000000000000000000000000000..145089ae0d7c21936cb60cc5c39501280771cf92 GIT binary patch literal 40160 zcmeFZ`+pSG-8lX}Gqbz1n?N=fAlZa4yAyPi1zZSd6s^l{a&p;d5NvCO>R`}kLa0fl zR_x`&Vz35-Pf=)}NW7rfRz)kjuzd`gE=sjtYP-v&4-nB*)G>*cvm`LH+3e2ub#{Z; zKHt~p_5B0BKO}Qz&ilO2``q65v)1V#EXfD{-O~U6@Bix@@L?d8DIk|?Kf+8T#irUa?UCcd6fa-SS|aO{qINv6xJa@$qn(Q}dJ^Ve_95C83fg1` zA&gD3$&PVpMfN##N9IXb#!FD9jv=`WS2YovA&L?!`^LBUeB?Tom2za?_#rVzV)v1O z8S=~Q@nh&obRGKDUzJ=d<0-N-o?{T|;4&;CUN_w5t^Iku?3o+~|0 z+kr6f1?j?uyyG8h4Tpf_GQWovTJDgM%yXiy!@hv@mZu3N(Y$%CzP5ef#(5vfNTQKxZu&%Uq`&gmJw@V-Z8$3B_?)- zCJIp5LJ(UNvD%C5K=Oc{0Mfmj&H-)zzu?^zW|xda3TO2eMT#*9o%QsO!m~|<@+#xx zamHVqnMbHW9ITB7RuuI&sP>oD>Uv} zas0KFA}M3N8h34uERGMgiUhGaQq<1-OEM6?aaidixfuw4fUcFb26>8TKQ+i>4Ram4 zwbj;7WHcV#;24kIQ|LP*F&&5?w6cxjD)HU4#yVgPpB>BJl3g=h{Z#)nv}G*6`(M8= z3o;!?=rXi=CG*xAJQt` zHv)y$jxNbQzHjAY+8QgWEQ|TZ54Ap~-2rAN6Xl&u%pCNM2Ug~Hyf5W^ zVOkdSkpS8n($zJWaFGBqbLQMjxDHuq+b!#lX#oK8w~1p~xBF0BfG%%t^q96ynB$7B zX5)ylL_qwL)-C)=>vmfQK$ui&!YuBSgXcGI`hJ@gzqI~a(ct;sO~$C_94dU=Ym0V} zVyGDqJKi*Xzpb^yeB3vF$fK*SbRFRhV#oK_fN)k3#}9ct;{lJZ&PmTDyy2VzRaZxM zYHQqkgUHn~9=Inr(lQPkKrHm_)LI3oDvEd<;3)L@h@0(_*4z!`%j8MLhX1LI1b4_R zaWn3!;#lE$;GTkL;W%t6iXf2@w`gnJUGm|vK;agx)eU4kDc$A7x~isMQ?_Vp1d=(0 zzf2ZFRUI!zI_m&Cj8)fV`CNml_mos%@Z6h?x$rSMM(kI447vD zUlT6EE#rZE9UX;oU+8h;bJ}h0lH&)o)z)s~jN<}EBv(V?0qr&+-)N%Wg#sgcT);ry z)scvKUNc3>HQ%IU(d-7W z1KFCOeOptzJ9Kqg%F(e?Yqb`(QT{_uBCIT2FN(65TSB?JAfb{5H^Ji z8VeeL)TgYC`3*pPsp$>6`l2r5yhb3>1XLh#+6~{X5m2J?~@|1v?eb%YIz48uOBzf!( ziP^XV@*KN7K3N>!v_T{+d#lu0U)aT>kV_qkEl z`Y`0#ee$E8i|uC1m7ecO56bg{d%pjs+y^H;?}nbI(ry4E`w$47VVIlKoO>g3fPHrv zkpD`6Vs9^kaGm^;TtN``l2j|(*DRBp)_CQk(lVLtdpI**$GGlY#W_ePvnsdH z*CV+H4h=H}%j9m^Ll6@%nvQ|1IFc*!5sOIcJL~EDbn$|st9M3x@(G#p>r3mz%Hjw@ z79S&>2~oYoIso7foBig75*b7r=9|qoyfJ37Kkj8>CcjN`53rI$Le*8$d1d=oFx2}M z4DJ33hMxEehIW1hLubbffpWs-G10SQ=FN}bb(o0@%-OO0uKB~0Ep7Ojcr)W5CgxWd z$jjQkFD6?kbZ#Ut#&-wC%-xiR&U%16r!{OnZLO)zXGgcNY+UlO=hyghBqRcvlhIqO z5}mzie$JUAv9Xr%Ky{&XUNJZs%7>~o#h57t#4#n$$;LQ8ZTpqdLUi{T1tJw+!H{(b zhHAoeN0c;`G#5%Mr4oNh)1C|5%EKBrzl8)A9oCBGJEX%}+5A$us1a2U0$Muj2+S?; zSK)%j9AUNuMAoaYwUHHowCbWPl1)Az8S;q|$>@i7{Gn!GnZ~(3Q6Lid2Mm>c1w;H- zFa%cM;Zqp8g#+P**}!j}4SZoZAhu!jB8PQ#lU~z*dKebw&HJB-O)ilh_Sq!5`wPSH zHOvqG4aPDBL+7tEY`MXRU2-nY=`X{Tk{j#lnC`}vGLVIOQ9p?DWS1mhy0<9}eAwtO zmFXW{tE`^%vYl-JQm)PW3Wl6t!O#~^0{`ARK8&jPC{tyL+WMOvd^?aO8VLM=rJeQL zq=aH=&zG9oHRU2+hL|)Y0GXq?gQ4@#!X7CIF#)PWQq8rqo)7=)cYXi})@F*VMAu4H zkU;Gm(D*PSA0{ldk9r}lS3`{M<9rSIAN8^tYDvVb1K#p{4J~CfbUnBdvCevMxWm)^ zM~C6&ZC-QituB-~}%edt;3q#}%|_P8A#HSta(ynwIgvO<;b0$zIDa*^M|#Tx}JTBa`*fYTEgLO{3zb*JrRMqEhJ!RAt+~0Pibhc z*Bk|*wa2lpG&DcNXl&rlu7NMKU-ri#&k;R4mjBShWBJ`#$l_S*`YjsThwOvv1l(KC z#R~vPEZw@^h^d4aT-RH#haRFf$Aajo4#L7o1ui?UbPx+1Q|1q=EnTt^AJvKi(=Z>e zFgIZI7?5C^D=!~}ii=dCz9+o4qi4tR9}GAi7|ZWIq16g2)>(ocyuJRb(1TN7JQ&#@ zYujGmfPqBQ0%rFOd_jKss^%14)h@GIL*~$CuRVG~n`cFf_|>l_s;mW}N9pJt&udQM zgvJR4<3pPaQH#?QDa|?prIVJ_>amoXChWG9@tbIu?XV|%zHH!lA)?Lx>znE z9?loLI4hJgJASNvWx1jSMN(Y(6eWa-2JPh$>Bg9u5zN2yep9NdxXXT}y zLf;U5xsdw3cO*tF>iNT(uS=eeSGUc;TzqC`48Kd6%D*)T z^Zii}xp*_PLgQA!{F)dy+Qk%BbE91>7cVydeQg8Yum;G%RBO+HM7dBJLe;zI8jH{N z6ohtpov{YY#VgD}A}P90ew+GaoA^jUs5G?8TO8RSH{h}eOAtHT2jusu*+F`Gbaj_b zXXCf28a(iY)`hA$S0n~v2gx&SSQA(7l?{Y598os3fomi>Te^3Rq5#YvCiPu%0Dr&j zTmC#;D$m3}4PKIbrcopRYMmI%Y9os?XOuhy#F*NQ!8sB$#EUJ(7@e@ zyNHLUD?!gx5Wh1PD5fW}B(@kY9oj3;(opFM6MKAGr6FcB8IENvgw$UYOJyQfNGkH! z=rlY1_EpMaC(1YBEis$Pa?Fcq?LSjoxpmMS*RPH$mdf!=OBA!%&njM=ZGSq&m0vg& ztV2hBJ8I_E_3Z7*&K?)d?gL64r93aSQ=z<_&I81Yc@BHUWa{+`9fEPl5T$sVrZa?uYr0<2my5Q*@1vO*-k0 zeW+#pC!Ij5QztcW50>ut8jnz}xGKXHNpx80AR7$B%GxY_%iiB;z`58Jd|#&irS~O+ z*dtLri;EY7u6{C^Emwf9emGUOg0B935*%E-z?6?`u&(|s^HyZc$5h(AGX*yjboI?i zu-9OQ{9OaP8#CmHCgKd0%UZ?47 zAKr9t)N^h|;Zt59TLaX_rS>j;>kjPlw-Rj z5dNV!9vRwpAW`Km2tla8M!wPZ*`C&^wP!zU?RmDRG&H0<+au94oPk!p0efkm7*Fl# zxuYlB4_f-Ja!1eZ9*R5D$~I2h{31)+62h>2dpFv z&@aaFyI)qk=d3@Z=lwV79%V_eRdz{x-EcxPg3{r2B(%=Z}*p zvr~Ya%9JVq$nhi>p9#pGUAw=&MpwpwSGRF-tI>^ttV@a;k;`}zEfqWI`^IEO)3>*- zw|DlnQAz5OR~fluE#p5~Ln&IF&PczER!4X8pxj%3W@Bl8W>?F-Q&NyZo=(&Md-bD= z7KXVTz5-vGuiuBPu}g1U?9zFZpkFI|3$4mOd7tuXE_H}oxFAY7m?%mY_-d?{a z!&Ol=<(GT93~^*Q5&2!$2Z}Z@e|T)!Tif;}s-|>{tX=_^&6)UxmZ7+*I zD5Y>~nxXP}^W~3Z#?W?s2))o-|BCmE=$UPwtSb#gZ+3;wY@xdaEy?0SSDsL4FD5)4 zZ^yGSkW!5+FBn{gYcP5d$j>yc+&l;ssPEL)!^7O24w9GgQ_6% zK$OWmKZkFXXXEYOf@nFWtMI!CaGFl(YF!d!&Urq%%{dnJcx(ERxL$H?W`{tqZAFW0 zo2lL^FjQ}){LIq8Zbh!#7>Mj}GzdjWx_-4j1D> z4Y{iNp|s46$m5g6{nmjis>Wg$6o?nI=-MI;T~W{v4qN9r<%+6_D61jYxWb32E&7p8 zeV!EGzUP3KI1oUj62DNIiJ6Vv`=F{W`oS<_(eob+v(+CA8>%1C%G^MjHE=FDb$Xb+ z89iNtfn2Gv8w0oo9}Vj20llHWgXD0=UOtG(vPl8+nc2E7*e)L$2A?d|V-CaIPn12G z_uUe;=^od?c_zB#YZ$0-OQ*kvP?Zj1<&M*n!~I=hammJFY{RH}VepDdEoQ~+MzrV( z*F?0lUJJ9b0oyiSQN>3uZ*n#kxe@71x3__7S=1%X^*iM$(_Rb`@^!ci;|! z*tdp(duy2aan+h)tPODSS;$9q@V^ym=!)0lke3&;1h1%?71Px>bavxw!82P~lE<>H zqUdFKj|>$#Lyq7TRZMheo#E&wC!vDkbl{^(t9&^w!|y8${y&KB!~SA9S8fa zLg&2b>Fm5Ca-g4SDwI)mVa5kd*$UR9;T+l2^qKsU1rv*6xi2Nd1 z$%$CI`OAZL>X$6ncX4>;!dZ4xV1cLLe1 zG31p*nLj58M3^k~=LB_iw{FY4-=QP&tpp+$5)64D!HMPu+Tv`|kZCzrGiIK@)DXEn zF{z01DhMeM>Eu8l90)g50WWhP*q#O+3?T3Z5WeINuJ&B8cm4&whzxrw5o1L9uDvgUyT;kp({kr;!=D?2k z=v&~GDA%TZliG4g1tQbt0bgbSq1nlYb5EF?R%mYbsvt9Zh*=@`)*Jmc+32^?ljAV> zFDN!l+few6bkp`c^-oOMpjX;agRXw4{m0Y58~mlRD`;pckPG^4+t4E0mP|AvLfcY3 z#~RM}+vHtAtG`t4>c6Dvg%W}rT;>l!EZk!8m&z;qvpOI3AE2dup~5ZTIv+c$AmUBL zsogh)Z=3^x^OwqEuvp$V5g;COXFa0v4+97_;XHpXo-KCJLDL}9JLF5uQJh}@?gNH_qTBt0d z)o)*l`8;ZywAa)|VM@r_haO;yDa~`EKF@ z-0Ph-Xq68EB57@LlL3Ph$Fi0{ z2g!kJhS2<1BWP}+jF!4QH)-N_G}<+t+DY!%Up4UPq0glEHCUdpr~5wXc~Wy*Th}1M zBGl&~t&GKYA+%>rBmSg|6}WgUbJ>sX`Vo-R2^xVY+m6UgO;;yU0-n`~NY4c4aNMV> zOuAvp*MOEF_sdG5JiT!h6iVR8kxysEFu9FQZUMQmLE z)?s=22+P)KB7Ckug!0azDc(tW=t4i8A*d{hJdAhY0A7w~U_^eL#$|P{&BM%MSE9w0hE#|LpuH~+~s`j8kc)Q z7Q2z#So@TB<`J~`buWo^5F;pxU*lT7t#NaB zj2=Z~LHYrV9v84Bjx1^Q{`AeYA1EETG;X?1BDxp#Zd#*m;X2-7oRp3pM9$KWrP-9dH} z>q4r=KvQM;DCgPAx%fg zrC{z@=ByJXI?ODxNyu^QJ)QM6;VrTOFAlc;1i84AXld&`AnuiF1}GkDW|aN}#e~Rb zDT;?o(wdv}Q5pfY8*okoB4avNo)bfMM4n6wn6V@Bc$(U$H69?zgXlCON7Ef-Ce#ej zm3AY3Ds}GHY57c=#vilih~m`3v+zv65mR}ot7VgU!S?k_rROO2t}KaipeKAw`-UEh$_AUx6bqoCvdhrPxa8!txgejX#@)VLu5SIBV% zk$F?Hkj8ecVfLr1zM+#?8i9QD_32|=M(Pcm%1_`LiGo~Xv8?5K?H^w8g->l3yu6 zI+7%FwjgfJK>bB`_7^XvBmc8r+)v?tJaJCZ)jj%n#+Nw_n>TVe5v+A1vPwfv6TXX5 zJZ0O9n=XWmu7X(QMlRj}h%{+Z&?O7_%$@DBco&F!)&lu-GNUVA_NyWKd`_<1cxiX- zX)6pC-{0-!V@EQ+it1pMe5EJvOb;&-d zUG9=DaR@G6jA(=-d;b6YP5(m!knc_T8Nm6Em{kDs>l8S{Q6#b(PAaGC(HJh+d;Y4x|s77{SCG8ey@M>`HA9ByU@ z7jI_S9rVm?9n0@ldTyWSnwT{X_gSJemXKDrB~c$MF@3FD3{*GxCEE++jWm^K|BQap zvkZI3;hs;rfOMsgX|?;pvVX*2xN|LSdkx+oyMJno=c3+vsy|TtXL^=laU3?B>1ti? z#^3jJjpVSiJr9oL817sPWK%k;FX*b6rdGdmB9!shs=ho-^@%H^Ub)P_%e&|s7Rbli z+U+tvsX+k9OuY(&ooaU9OIYJMc^tkFGR89dt70nZ(Dln8dV!vW-D&E9M7?`Pd1kwJ zTjY=pgsX9P#8V4oOPaR%EW=4YQS^6rEv5FOHGH^-!=;89$FAuQ$j+eeC&GTKLA#hg(flesu{8pab(0zX;sASE{n-QvUuNt8 zD&MT(Kgkql`PZ##U$1cMYS-%^QeB?G$X<*Qc`fC@AR6sRKqQ<3(SeP2MnL416t!a9 zLAJY;L&uQFej~C*_3d*ReLJl_IWeXCXY}n$Cy(7^a2aE0eNINl&k2CYuFZ0GD%mnT zDHHEuHW{kSF~j<*ZnUT%R22ZnvMtP7Ac={rEmboBpoO8r>94%;@G#Um{gObRm;2uy zhFV&>%uoLV`7mj~4MB)Yrg`@|@j_g@1jzSNuXxp%Bmns!$>Cdq%;m*5LR>Ojey>0w z76WNW{l=@tJOYr{GZ1ij{*4g#7%tyHA*_pmT=g}?-YFdBe}lLz1ECFUGl8(v1i}+0 z`1<_(OH8~Gh&AK ztNViJd0pjFRLj!ULzDA^3|^se*Sn;Za=T=_UssP!QZ3q@)qT6F&+ zmp7c$VCYcs$J);hEgL=a!!MK55s0=XhHx4euiz0D@vJ7Qxjw83*k}jRobcd`?@ipP zt+wu2JEyYX1U;X3q`HGUwbc^Le>-}!w)%RP)GD`2hZN%!FZ!HDy^Lp-4#FD0%*e{? zy?H=wt-oCZJiNDSX-#+<=CCKIt7Te6TTxK_*-&i-Nn$bktyh(z{Y>j3ouTwGUcnEm;`%iGJQ z+FAdv@^;I?i#Vu9FBi|my&0agDEjbzsJ!AEaTA|ReK^0LnA3Q-G+lm6%MGB#<^7cB z#FO)e+;|ZN@lknIF*=?vFYMprE&4EDuIw*r{M7cPV#O9rlx~@=&6X9a;H_CF)jB@Bv>8qF%8ye{ec}bdz=h7U~%@E1zveTPI*&m#X;j&#a zx@MOo%7wu`8C-C>bAZw`n9S+|jVf~dq!Ovr5eqP49R$UzN+ z(H@$;Ioee-;A`LG{W1!~r%?-BiG7mEEIFqboB6Q#jT{O@nkPm1#N9v`jrNH!gpmLr z(_8^+5#d{nozOER6$Zu>k2hh?yS4QM-Nq3O<+hj*@&EEr&qVO(ww=j_77%rcrGy+ej4<(@AXbU zdAPj_7h{?!XVh8zNqbf8C#`q1uPD8vwHQ;6Q&M5E1v5ekhH#c@npCx5GU;ETL!(Hu^^A%w+xOo$``gQdgeO_$^F>z~3o%rqH z>EHfgD-c%8czPfZeslH%`)I~cA%<7(@4tF>ztb^d91I<&S@E~BgO zM?CE%cz3*+8EUuI4&Bx40P^$nnf5j9pWK~OTPU@*eR4O=CSJL=g#_+7bN8;b9mL3- zxqH_g#Bt{CTP2#uMbC>h?7f@AIe4Vs)>I%r;I+j{n(cCahL;uBzd2m8@R@isG&=+- zr9Pe(Wj5Z-*d$T5Hr={5;J8(y*mte94lKLtjk}v2oA08~LwBXruJoC^v#@9GHe_IF zuV?P2{tCLU=pJZXmf1W0GMR|KxtnHE-SGzjx89x6%BD^gh)&#km#)5+&bG5)K8!HU z^SMd87}Mx}8u$Yy5Ewtg#WIk$Uxmmw-)Hpy>-*hP?^<{oo=IaAihiCpay z@X7#?+cKJw<^gikt0UUD$M1x2;r=-+#DOLv8*oUej;E{|z&iG5^oc^@Bb)d68 z%UcYX@6N?QW@@?OEk1}_nW|btZF`#-Ea}b<3f%wlDhVv_27&YNeJcYL-%`D`n_EnC3+PWGm98z+G z!%7)`OQD*Ju2LUSagbUaKz=w$brulm9hAa;UTTm!>-}=EG@<0kti<*=NW9cp&te|u z;{v%L*d*`rqL{9J9=u0zrKPa{jbVV! z`dcy-MTcS0qW&DIy1z*R@z5|-ch(n5s&cEODlOwbxo3Ow+*pppBnw%l!RG^kQbTpP z&hT^$_F9>dP5#ejok=ov#s(0DVnb8iC_?mXxTOrYes9;(i+UgB1U&Uf5G_f))4S_a zYWbuyXb-a8Ae4rvhLO$xqgD#_e;H1t)TYUAS}8nU7;GqKoQoqJ^@s@D#d|?x6cp9F~FzFT%#>fq0UY8114Zqjs${ zZ66t+`HK^ZDGZN+BM0YWAe=T8hoHGhEi{_Dbzi}*9UAOD7>7I{zj)wad~Tj4%EnR7 zO<2I943G8J!!ERB7XIhZ4h`*Q<4g{PIU8*uz+3DXzk&PX*XJ!iaWL-6^G1tK9E=Nj zp6J22nCFYW7L(MXYi> z&^BjcYoc*nXnS2b7_Z8+#wgwu8n={*iX&$>1{HAqE>eyu-M4ugNw@iVJ})O$G7g)HBaP$Gb_p}w|4ZdyT+Y-6Ixg12{n>s4Z2{$Ayfcr9 zRE`T%w7~s8Ra%IN|DV~H6O-vSL2qp5X3*C6}hLyi!4MD z>~zI?>uK)RJ9X;OeRaPb<=LGP8wSVWII!Ij5NFhu*IGt-^LusXSY7QtOtUdOq-*n% z+H3GCocNq#uxY5Yw;mRJ8Aab3Q4Yq}=9$NZRyKMt-j?Sf4+Zw07dqC(vUI6mFd~iH zoF0Y(sH_|hth^@{K1w~U;*hf=mE?( zY?S@mY#fZ=l2=KLY+q4wbNj>tlds3kc`Hwtt8O~+@fQrab>Z^m%a;qwmwRbn zR+))&CMHUA4L(w6Z;7ei5N5Ci9|`f1$3jGb$giFT{*kAFw>T=vOtvp{(qPQYCrjrO zA>V>%b}nyG`ZN%}Q)P)kZ%!QL_+*>RJ%%zC{)H5;_=uG~VMND$;{l)5F{qRfYaWXF z#t->g#<_crDs&&rwfEL%xd5}IxBj1>^Nv3&Z{WpBBi@A@ltzpd+jyV_#n3_+Vivv| zYEhP*GqSc3Ht+iJrdP(M_9OdPZ#}yUExD=W-B8dwJ{a`A6oJcrY@@5?h`OitEX9-` zLrdPo@6|a!e16o-zESs11jO03)T3}&4Eko*{_gX4@W+a69Bwa)++yEo7iDG%&6E1{ z>wZ6u+6a?Z6mi)FyKOvhdvRpGU6j$1QRQMkmbiY+2MRqQbbryEB4CGHsO6SzuYdRJ z6U4{$nje1d#O91AlIB$NxL_Q9SQbHc$2i<`AbIXQlbqo*yDr1?u;D{@b;t`ET6*qe z=YTnQRkf;oxB9$7+X?&OG9YytvJ11RZ;s}P(TuUuOo`@+&D8E}pPRA!uF>4MbHKH= z&ty7I^J#(b+La@M(HSw~`SO>F5&u)683)!da?l(!r#q$Y)~J0otD0sViLK&V@y@It z(CJRA*QY@g?;836^jim5`OKZV`ke_ilfNe5w7N(G=ft3OAgyl5_z4fm?QLbYonB|8 z2*W(fX;+&A7uTlLUua+-m8;ss+EFQXGu1pyVdQv3Gg+s_O-NV&p(JGuRqNwGVp>F^U!2tOI2m(IS|4A*N;XZkJh_9kRFI za)af@oR*KZd4aH(jUiFY*y7*TxTUXo&mZ;GjUDN&k1Ma5K&W^Tc=|{0MP!~N_f={i z7t6&#R_>G8U~fJ3Lbw?avTIP3(XW79n4}p5Jf2hs2U2S6buHYrk;6US=~z7SKIksT z36H!LfRITOmV>|97!Y*z*+jiI7drd*Y(&>R={209*`wVF8ey{xeOH?cy1F?*6tpDl zRgV6L^xIAlw1EyX3z7=87bewR5iQK&2REYYOh+VHSJx$|&sX!L)oTViFM9=AKj~j3tRit*QL`E#i?d;&9z@1#e)i3 z%+I4Yrap{ODstk;va+s)07pJ-z&UXS>8fAn%KHZ?u9lJaxRqL!`*5}=H!Wv-p`~mu zv~*f}hGs;HIg$bAVIau~BPKzZKWDIOV|es%Ug@cn`gEEr&l}tzk62e~4lodt0Y(io zu9No4)j=0_7(JVKf%f_jwwE^U>6R^O5mkf4o{KM$syoIOW ziYo?F>JKxx_ik(%QTYEJJ)B4FIX;e%u6~xL`ll18)O#=H+snkdQgaF`H33Y-gp9;w zWJXawj2f*#R%slj(6^Zagr0 zIL~~lUH&99GLD!y80Cug$kqK6)79w?!h>NS84&T^n2TFYi*T|0J(;g&-+awG6RR<+ zBYWR(QJTWr(=_^lw9k~z@GoQo{y)LRZDql=a&B;UJ@tzLDW3rGtzoEsYnZ8~_k0%P zq(Z{eun|AFFR=e1`M&*a`@6lBQJRPN8O<>ntd?QN2Kj?wbQOr~j-_qw!E-YESgGs} z%Jg1IIXx#p&Lsp)>7xV*%hcOvz}s>6KB%mX!eum%lDX@H zVeT&UsPWg2Xk`-6tex_bLFQ?idz#I0nl@NG4jpd|!!Kw~qBZKohR1{wWY^ z@LmbXV+mug989a*b<0pPlaGj8d9kH!rE+z@vA3q5Mv$_Zm-J@Ekdjt^s*fuj#K4`- z#EH%-?#vyZhxP%9CGEHhGtbl8om_eD;OSwe07R}Ab{P6})sp7QnNzfOzAj+XKKH;k z?G0TW)Gyf^(+|uF8>TD~UHxmu9-36&OkJ{vXm*IzLv0g296Y~l(_z^Vv*Pc`lWJFr zaz>ga2lfwyI-ygE9q>Z+6bSigE~DypsdIpHp%^O;DF)X^ zQKRd0%p{(g%CP7R|4H609~*`{`5=&!8kKh^GLgQc8ug(ZNmF}~uCft#W5;W?@}K2r zyaSP?auI$~9*|S&*~GNq?z*Db|7d(*K$;QUyA@UM-JDWQ6I6R;qBLspvIg^D@JCYi zhRhFSwD?m6RTV{OUO=rprf6XUen`$0rsK5wLYl)HgC^-!dA9`Q2O2#gOj44#hPQ?p z4#-+9%j0QGZZQMGVflNqu6`7uxm(8aZaf3e!Ht6j{XkYE447Fk^H}qmgP95 zrjnGS(>ZBK4=E=#$^FydY-u@uSCf{f)CH4wOTW?hz<&jy;yP(6fBKO!HE>L&~-I%S=>%c`&8km@t%cgL}53>OGrNYJ0+oYX%IMX4Fv5bbW#= zw+vEF!c1`G&qUVAJGP?g9h+0?cM?>`ps~kyf+^LN0B3UWKqA-e??1D3(3o>PrPgJn z9la4@c@-_CIe~jNlhbr}rqrwYv-;2Sphwo#34OP$tE!%jh^E!Q572x#>LcrwAt<=B zxs){S!{JhSe?kzT%5vKFGxle@yv8FmN1{?gA_(Gr)&U_C{jh6{CJ z-WSiro2W0pChU_rysDpdpt-DUyHCJeV_My!Q=g}JU(Eo_J)eQKhI3@*XZwR?Kilaw z9=TP%qyNw_ETTS=!l6?6oI>BMQiB9S?ohUTi=-({GE~K5)N4Y0D)i<&34_2~#$KM^ zT+rx{bL7(g9LX<{fdV-c+@V!IJ`T^Y|8ah%G2tBG`&4YW!oa0R+nkdY@)lR(?eqeDYbuq)@Cxv2I#n`PCp&j zmCw*no;A3k^h2tn4os@2wet$&x8SVDnt7G_tEr|Hz(qI@+xzM7Fla4l^}h!S`qS$7 zQ?rJccp>#A=iFKc=l(k|ZBANEOSIf27xY z%aJ{!ki+8Y{#E!|Tru>NH+f_~?kkNABk#>pZt!9GS*h3in^D$)Pg=VBLPu==+P;t_ z;0jo}J(&I)&bq)sjS;fG*%vj&omQihtMI(p$>6DBRA3o3!c9_s@RY_24@*_ub0)eb z@2Gt&^pv+MF#qIlM{|vT2>pJAtNVpwf56vGZ`hUlaDa~PtuB9^iRYqiUdz#6haN9}uJnl&HwMZBeYa9S zZ+qY?g}k1VGCVYzzEP9?zQWr&>SH_Wvriyb{4a=0b@p%6U2M0qzo{Q8vs6(ZUY4r6 zFHuE|-)NQ5%GNb%x-Bp&wJtAa9}5%Zwn{WWO~y2Z9WMa?cY$lyUsM#KXYVv9h^HEu;S-Nd5-pdNa^wN zCt(4QU;ylI4}*cv+=1Lb(G`bEe{8RpIr@MX&h-bj*zO!hw};`z-ziUf z4#x#1MrZ2AU@}eSOgyAbPg?UUCYWfydnuQ&h0+~(Ydxf_jp z4Z8$8jMiDv4whIa#f>1En#9iRttEOV&YjWgZ)QL^WCCH*1j6eknuo?=L~hZUl4WsV znZ`GUL8S8ios4WFExPddK1BQz)G~akA+65U8FEwu#}my@-f*+VE#>S5&ll`qNig}6 zm%-;_z0F;rGY^2sD} zB-L{X18zRI0Fvrg3C~C!ASV~4Fi$~J{YwHa|HTal@vHa+Ousz|N%hSH*nJmzAgK-{ zkbT*Oosd*tO#qoW2?WwWwxob~Qn}9~^2Wa+I=Vw+^hKQ+sL zG2|@`k%bx%Q<~;LA1>u~tQobih8@)7&7pNoJzhTYfVbobB7aJoFs1fkoK$yxP4BO! z=;fo5pVC{haWnm0xz428nP|D7-_yFSFSNruGwMB;cTej!+Md4GpGc}3zs9kF;y|d9 zjV;TJcx9rsyU#TH7$Og+{Wlu$--lt*VViNsno))|WhgVgj+QOL|9ou|sg(i@Hs)8DE3X%vy$(zKi%+lC{E{AVhu zy1%B!H8rN!Vqgy|3z`=At@45!?sbYMTFBbm5_!Iyn?x6KlZNvxOs>5nJM{5BaavPu0)Sp$- z4gB^f3r-#cHxGjFj0xx-7I+ZKco3E|AXM-mR5Z=?TjdhD+nXPy&jPvIYm;)K!VPwR z)kc%Rj(Q8`G_vIAgli*+u1-YWOYIxwS$>D5&(^eNlx5AC+2>Jq<|5-C|NhR03!d-S zIO%}K1P*Ah50UR^Gy3LCbZak%{t%io(UYvgNcdnF?ayhf#vf=9(AC*#M4n6qu;tM| zeooJ!W&$BPbuP81fu}Li$)_{)Of3aw}ue;y(R?5rfSCm)b}pvJQb?N?(iV_KB~98(n-t2bY)ZNSVGk6vB1#a{;0ja_C@5N(L2+q{I8-b_#2FcN zCSlPcV5>NWwk|iNaBtJn{GW4El=(h0-|z2#pQk-J`#JA9=RMndKCgbTZ;amI2d4B^ zcTvau$>wy>k2sa#b&rOMhywdD0{MMH%#DUr~N3U)k z;&QrCj;q1MQQ&kDc^!dVK?4WOTCYyf0LrTm95BD&O?7Eq?ExH%YSg-j);W5zd9VxR z5P2s92h2AwrMiT`7uv94MX7U&+xtl{OuZQ-lqUN=3T{*Z_o3^f zAX1sQCKr(%?IW`#{%-fy23@;E((6K_e`&xs3*QG$xV2LL!pE+gfdSdj`Da(l^(ao6 zmOH-a(4s?!9(efBp+hUGp4h(qsi&TL3KBR{rSu{lh&kQGUh?MygID(Y;%Vi~A z2_xZTWS;9EfhxCz+bAJ96PaqMa?g{Ry;W|Kqsdgu!G^W2lYyW+ck9-M9Ss=Ss75t-qNnmS0`nR^(N`+-ML$LG`Jdm4czO&zM|jSq^z;tq@nfhpgWD-+VERo z?Ne)>13J5SM?;wZYwwPLVg4@-z@;~IMV-E#20Ng`ib>lE0(KJ8M)89{f zTn_{wdt=wk_kXnD*+Rl06yiVYvx$;$%|C(HN&$^|1MaI|Qb1qn@3ScffI9FD0-4x% z@ri9Bo65?XWqM_E%XQ$^#7D1tGt*tBcA^$j=y;VX3 z_eQAnR=8@nIn`_Ke5YczrA6p+rFu`@P#F&kN{FI?+twdqh}U%MN6TzW#4i>;6Tn3= zn${NKu*;MNI=owXrU$3_Xy~v2V%#;M!vZ0Oq#4FO$TrwH$Tq~uI9@k5o&(z8AUh_J z2D{F2HbsYTHJ)t|=5NDkB^LGZ_8xpY|95c*d8LmEBI4@oz zX^QEqK4$Gqgb+Wdk1nCD4o{tXjzn<*uQ22Wja_yLBkj?H!u;kQ)C!EoUgy?yxmFFd zCHv;NOK*i&YdAtx*g2J?yh&_)37*9nM^gS-%iL6qq?u+9@y)jxhsv|OW z(JHMMbWt{mSDcekl5-P>&@Tb-io8uOVk|Lajm##q;#G=FT&3VO3owX#qc?)Ll)pIA zmyG{M_^tinuPz3v=sE(m9O$ZJni9&jaW<`^hhN;Scl7X; z-KAaT89A)p0X0f%0n@{0cLNh$oXle1{BFj9IVfW%>YYsq1z?gCfN7r`Xea>F0XfjK zd!@d}44sU61oL*wxh!Rs%PYd@XgFljvZjyUfx{@dE1D)El+ z#7#s*PWluZlshFI`Dl}Q_$9S~9$#;2m@fpH8*yCX2>EuHzqb$c-(4nZ$vw1Ti(qc+r2koG&%HkgJE|hj8 zvq@|Z|AAm|SU4AHu;aS|@M1b(`pl67JsyvLInbC^V~-`-k{yz~crI3z;*j|U6i15) zFwu6TORyz5&r78j<86bgvppDzAJ$$Y(z&5Z%YmcIP_$(pOHej;W zUU-Xu5P!4B+DSr)5B5NsS{G+av#Td0mu1>h94gxwI>ixdOR~on_wtK{F*u!W#2D=6 z&QucLa$=mzf1U&{t|!hH=ZWjD?(ZX10hqd%V0qD$5(SNM;}FT%5w}2K910qrUtrs8 zfpH+(!cn4an!q?xWW+_x3Dr%Eqms68649qXpdD&X0zp4zlUtMRM6h}KTswntD@n#4 zWz*Vc+jrZ441kv!icHF($aML`6_7O)nJ~^1F!*gvi%{u0D}WIr9cgSDtJba&TS8+; z+<=Sy#eol&j8;5WB8Ems3Z zYZ^5anQ*=^6q!nfV$5C`3Ob-ETdIq~uR;)2L~z<}nN7!P?Xn`ojqQ`#w4zKc=5=@u z!8ns!2%yKm0hF5%<-tp*P2OH_aL<*ExEMuags8}DAYq63N=nB%2#yciiV5zyJ}FDH z1jmJoiV1FWA7U{A(6}(kO%zPGek?HE3RjJ_+bxy4`kos%Y!;KX#=P5mw5RLF{nl5! z8dsd_zLNW=RJb*qnv{6QSv4+8Cq*1}Cz}`eIl?;BlZYBjY8b};iuT+ z9<|OmD9nE$>=*7ef?=XBH?6{r+jYM%Rt*{V`S41x!ewyJlc5VkZON`bUS1>aVIi6& z*cM^;sVi;JznWE?Z|DH3q65i+NwwMvDX+Qk6c@88*_K?C;!d{48{FP_hH(L-bMG-5 zFDVTpd`5vtL3wEckE(Sx;K#K>wQZxdv- z6Fd^#8%1H>Dpa^JDrbf3s9VD&kS5N!=|v&S7|%#*R7bG1%m|XGi9Ld9c3Gp3>?*>P zj0t9wn3e>0UyqB`9^Efw(-m&W1nyNA?(;8MReRKqIQu5E)ElXjIATPK?iWTF_jiw= zD-E({gPY+bBwqO#Tu<4OUBH+-DcQTiDC1H05Yt*83{(4n|Z)W?Y#Q?jwb$`r85=Tiu(AYVM142)W^Rcu5cqAmiMY~0aH@Mxcd0*;W$xl z2AF#Sxc;>bivo>oDOVZ2U&u1r3KK8I*1jl=tk(!~h-XmEM4R$$sEG-VL@`GYH?vzF zL~_tm-boyi{VM1T%>%`}bLw|L6cfxNiJEvOCYX!m(`sUZIVdJLhD6-R5E_H?FXT|v zwE$#K>>B-klQ71JX|EJ>pu_uxJbQ(Ega@~NWF#>G+{;F=6|TVnj8Rk1W@8LW+)w-a zGUgwLjfhXjV{)~4~e@H36Y`xrYu8mlX&vYJWmys`&MEmR9`=#VXL_b&D z$1B6MZfj8=&-D#y1@76tMl_0~Jz3Pp|E;gI3(7VW z_3@|sHWd5YfH`5Nybb2n=j+_FrK>O2x%Ws{UVPN{sFe(=(F{Qn{k+*MNTR#_cyC$f zUNc$K<*L$pm$_F@(Rx3>RaZXE1Tj)Or0AeR4=tIE!8;d+}l_jBh`yt zO_~YLBQMl8%=0t`k&5!?Rp)u?+$mAyMOtSs>f@{Xmbpv2VD&!fjG_@2`*>$xDM!fj zs!1-anAf;l03-gD*Vq^&R65@T>@G<;vD}@&sU=JO*fq&tY@1@u6Nr=~Pp*)lW&|P? z?_+QJVQ5P0CvC9!xd7hF?g{kqv-AWa~YD33DS z^ou2s=G`fQG`jKr>RS!V++#{LoLV)Z8u?+wJwB2Pqj`-OV{}Y6(lJHjoPE5iZ$xnv z-N)b4H=!B~xjs?8*1z^B3>`9sX2)Q@I10EU0+q%44eq@%`9;Q-hRl2VpR&>9!kMFphQ2f^b-Umd^LonYgd;=)l z_waegaXE;F`=|kE;I4%*eN(%Kw#y`F%ufMz zP_3f8K&xA+tT-PPlJFzV3Lh{?m&{_hg!@A2?XoD0+jzePje_hBKjt8j*VBZaWYr%; zH>VD*uuvt}X6Jd#o$9JRW@)qfW8fO_>v*I3V=RH9gHQmx+i<&aUB@x)ars~EFMo{? zCARwWJy{mo=`S>-u@W6{&xg`PM8UBpqyuitM_5LU(94@snc0>oTgq%OD6w1u zVE2gZc_bg_F+xOL2mQdy_(n7hW;aF`CnD5ABoxm<>6H#;!5e1Dd5e$+*w@(<6+*X+ z7L;=%05l&sBM16NT;6`Y4FAbgi+LOm7d2A0tqplXyh-VK!5rmhgm|^OAGv82rvi-G z>yra5)2ojqG%KwL5gnkmtgrH)c7))>FUAM(pPXjp^U9B_6`LWEu zl#|<%-D&MWB)js21X^ujgaiOO@(LGYP(|v1^TTK7Vg5`Q^wC!lBem9;uy+8Ch`5q8<>CO*rM1xL2XpB$bftj!z@3RJlNQm zWgW0}hI^np&qB5Xie{B3a@u8(;6=k>c&;!I@+@>af;3?uXg1}vOG%Y4l`galvCW+` zCkad4o-hBxF{t=xPw)nsP*aYW8D%s(tTmE`WEc#~6$U^gg#nOCKj1F3Q+X9glt%>dCpYKhw&Mnv>$WNuFm2zQ<=uw0ct;%3H zZ@QpRm$uJ{jSWg;rwJoyl0$F`s1OJ{8lE+!wNu1+%Z`S8VFV3nB&`f8mH9#zy%(aF zZZp+3FzrC@GUZun8=}kKy^9w_-nqoEuh$P`LAN}OJbat?cSBZ!x0E9&d`c$G#_|`K zUi0UdOXknF!!UM^El)^P!^k;!^`pe7*oGmO8(M^!-?s=Q+fhxN=i?xyD!FS+K>AxO z`A*uB@}qG}83!Kc6^>|&rrhWF-ho^H4F|IL?Wt)?EtcZx0y>c285gfHX?%z&Bn3(Gf5YF8+p1+%dH9f|1Tz%DYg;MhP6mxUlSU9k7N*f&fUDmPFe z2t`6vZdmI<*@O@6B{JpBWXGrE;J3*FqGL1podC2&n4P5zB4un)9lJo3(mN2i(~mLV z#&UzPY*>`pa5v(SIqWvl6FzbXVTf){Wu!&2V(5rc6YFPKh{wN}{quj;{fd)<6=zqz$XBHn0r^ILjM?FE4JN-w_M!*_(;yb!XA zvAROm&XLf~b0K_k+0FkP!Y8BM{PhsNLF?v!4B=DPZoV~?f9qZ7=C6cGI$wrvzBy#= zR6;j@Aym{E1>L+aRMaVfZvM-VwKD~}`Oic7x00coKNE`Fj&}1IJ@}Tin?Dhu~UKr24q!27-|WD<_W*-{)6Jiaz!@%c8Q z@O?Ao{gYXGF1omvAKZiG_{03C-hC`aoBYH7);T1~_}f`z?d8=cz>Cww>*9gz;Ja2W zzBYogjB$%cZz#f z@wsGRb~NM&L^PIA+3cELJWXI|l$$RwSY}CqWx%FP4)Y1&EQcsvpY@pULL0&CF;m`c z=Bo1;pS_pg6}r$yY^_^zrj0lf?P*=Id(wqA37XoD$nV9_krs+Nuk8S`xC0Sq+K61d zq8b)6sRC{HZv=11I?>Jn@T*2JO&JJ!Ot$Br0HvC>Z3 z3+yCK*$2`ul)LTtwDog4##wil8R&dLd9TLa&Hs8EOX3!Ex}lqYO z6JC>P`^$~bJg&A;Tcg;kZHn~?>|i#`>-vbKui6yr_3T$|)YkkCDT(*QVgC7(0M=V? zr`^$+2SzYOTY-~-#_`FGXoT;DHTJ^JS<|tW7@1XVpJp$)^`$x4j$`%f*`p<`IG)4^ zCR1lPM@nO42+LrM#D~V6Z3t&*d{mlis762w*aj1vYJd^Py)I4$>1M5HqVc8eGbNlq z5O9jPn%ty~Q}(cV)iU-ub{pFy44oQfP&Kz)Cpl6PpTgwK(wn%SU5GY1@y>jfp7aw; zo)gi00GLp~tnX=tG^cI1(`id~l1wnL!nVTN?9^1FJdIPrv;~$HJFL;wKJAWbly|uS zjju8P%^B_d&L72G4pi96N|LI#2nB$0&NduKO>$y1=Hq4)_pU2YjYiJ)5hHAPHU-enDS_Uu0Q&6b zpWlDv?YHlznEXy1;c7>;x(iB6+fAVLPBozku7+D!D~$N|dc~Ay>m@aL)e?3)tA4#n zC^$fFml=jNw_Mk76c}I%tcC-?!3S^}DoV#!$9pP@5Jz_(&N6X3HlcK&?KT~o>RezO ztVeM_tQcfcE94&u_Z-U0=VtJ4s0Gg*wEdaZ`wg>WT#?nF6 zyV>-=Sj99HrY)V#VZiENl37zR7ZQF zm^}e0^J+k4+bk3SzP&Se)Hq!Az#_!06lBcS0A<@O6hf3(i=TXmjVnT2necsJhXUx` z3ZM_Z2^4Pk0|d}D3ZP$A0R4&r=v@k+PrnJ&Pj3PxuLEji9Z)mtfO@hHsJH8Y`nnFN zxwd)5+G;nesGd8yMcC$vssTN4n_W)}1*S~T12!F-Ts^A@aT&r4+fKovPIm7U3XEh2 zV)mM!@FV7V0gU)eRO6Xkgz;#j_F`LnHDs>$Re6ewu#P_LV)0C}O)5&NM&nS2f6a6? z;y~Dg&rzA#M{C?b(`Pj04_Y04;Q2pk5tbn9CHbm10%xD z@T5In@putyX(x1N)nBzi+%y)r<6-PdjEbZ-Tp%W13#8hf7FbiJC%Ib3Vl4ANg$LSp z3M`#cy%E1@HiE(BkJMgM1l+4(k*gba_~MG53Pd=ROxzWbG(Jni?StD3w-s(5bP%Yy z2Z3625GdSkyAA?{+bruKQ2#gx)RPB+!foj}2$b=dWN-|-wSMU3B_gI}e6fS=<`a5| z+NG?e>p&HLGeFb;cQu^tL20F3yI13rz+HVX6w)c%AbXhqC?peC4m2yZ4YJGYjTn<* z6qc>P@+Zd?Kp#*5eOQ6-f@4^Vu9u&1JA=h1N1ud2uk_;6$*>V)+u?oe*7|KMUIB&q zmqIVFWAQ0|?wRC!Y|A@{sALB)k=5sdb1DX}nLcR)WnvoWh{LF6KHJMb5JKsgySE7S z2bv2fT{;m|s|tMg2q_TNaUtqJ=Tal$-t5MFJV(I1^16VyU%O46;We&?ZDze!&3;dP z(vh!`bbLxm*k2l`w~CU~LTc*e21$tQ&2LvC5K>dAw;ZWdfm%rY^3x!N3PLFOyU*db zQc=ODK{ZJ7(7gj#g7=IDWf%kk4~7yz%BGjGMRJO!`c> z!fUphfAMElt1?YovkNh4PE%(%ZXcV>4q(w}UjQ+tTjACFSQz$mV5b15)}(4PC4%&n zsq>JFsa6>he9q!%2g<{`-@c!(%E0pKpj%q>b@EH*T-MZC?>apn<$!<;w*t(Q35I){ zkq(8(8z`ubOEN*mHD4nO!~S9(eMy-H^uspTM)XK?cL>BOtlc2ir>UM>yhA{(^X4<5 z*c&?pvQ^nmDwUzwUQ@dgpjMKL@<;>J{L7EHdI66(OLz_oTquk<=vLN3=Tajh3;;Cd z%K*v!Mh-Q+?f)!rJQ$}+xTGE#?>BY+qsr9zQ||XqlydR%I1Z_>4qi1I#}O*Zt6`O| z8MjnziK(p|4zZQ@%`|F^s1!H6Gx z12ccRG^|=PqCJqy8gL7BhIRYcXnf2=Cbjmf zHe$04zX$J2#C&WsMEKZUWy0mDzqw14&D-V7)sOY&(uD135649`A>%VoJZ?_i_>_q@ zVBM~F zQ|A%wF8Cp!GDP_yll(T!L_6`zGps)syiZI_oCv4N3V=ysqpiv!ja_LK|6F&OE~ORa zB^YRdNWpRdf?vEL@Vb;h8uB#i+4reLfI z*HqvaeH5v)z?X$0GCb3~`L~_}{9E9EX@sHgm=nIOru+Ek`>;Idb0F{~A#C5=hht)U zK?sfN2w;8J*8*dkaNdadJB2tI!l*@?=SQ0pyhy|_h|DQpwIQa-DrIr6J#(kmMm1U^ zvx$m5UgF|ja^ZTKIJXOHG(rl1x~`%)7!M(^mo%)c3iG_n@-ChjHI1R;?|xdtJTrrstxE=G}@j6h6{DN&%ZG?plVy0?gp z2@W7)f{6&feQovZ7ZRt2v$ehqR(3edZwP~axgY7=)?6Xch^0~zjnomc<06S)`J+(O zO^qN)jj@n|WWFqm3KCSUC`&QR54B)$_#d}w+$gWMA=aRAJ=zR(WR?o^u0BkgiCt^n zkFTxrtg+Q}i))n5xJ{a%OQrGxv(h@xe13lXUX2rmF0{1>hc{u$xwp3nFTBwryx_S* zx!nR`+%1rBNr0)Qc9I50k&S8hqA)UA z=FNcEKGaO>%*nX48kdg6bnNS+J(&(FB)Orn80=_NLRP20ra!FBYWqDbrqlKR5Y`ni zSy6g|1JcxN92*rvy{YXI)hr+AAMo8Z{hR5>o8(eD-V%_to*Dt(Yu?pJ2G*@KagREw~- z^?rem;5KwsB zW8Q>$7UoZwXJI~o`3UA=%Ek;94Mn39vR!@{`g8!&cVo#Wy2=kSyd{Q6mad^Uf;qCBG(b*fjZoemeJ0>^)g?Z{W=&$>`enM$6L0YNo@GDaV z$UtA->;2yPK7(mC{$PPmDX&WqV z60~&krpP$h*wygfptR-wt4=g=B3=3JhAf^$N(&4Ubsd_beoTtIEO)$cxD zoJ&9GAn{ENxvYbb=XbhuBa$s`=Ma-wJ;9l0&#@&te+c9{b_&osBXvZv%8+MA0@2!h zDZZ9wp(fKdhfQ&-_lEgrZsYtw|Al|7^K2llHpMg47AMa9?xQ*zqz`uElU`ux;`hwz zOQ<6%^-3FT2&53NF6&Ur$XBnn5!IGL%KMRd$aysS=RlKCVpQ!-FzCGr%u%!6o5yNg zkfxqoW0w0yY#rf=-J=uY?I>40`ewk$h63W8WQ*XNN9J`rAL01~_a)rlF#T|U!}P=F zW6#v@VV`2Ru`0HYuj!4Og7wtUX*n#$I(tJP2Pa;Q-K%FcPSsu=JHXx~6wzO`L3Pv) z^#)0K32RdNHC|}-^8I6Z-=C77#8iLHV6dj! zieTVIzrHQXH;%=!5Ew=Cnd2B~lq*}Jm@$ujg7?Cjx3-j)oOUe085 zShPFLzbE2Q2>g?G;qqY|3a9v9P5lAs*y6Y>lU^+GFiR$QY8?iT`eW^+Rh$wc@)Q(= z0{0wKvgoZuwueWzK`*(S$?C+kTf-Px6QlqA+MkQJKE2gEHC0%?_I;}Uyb6A{9&59}m{uZf4~O{A#88pC=~>+p z;Oqi2lD=yWly}WOwn^Z3_K*&Vfy4Uf;SU_BQ*C69bJDC=BREi4zD0@Kt*30TK^rIP z!%KEz90{xo?^ZyDbw*c{`52u5?ZEo~D(>JLdg}?G{~hh*`dw%z3f9z#;==r?llVRV z05*ml=K(H9AhJn6-qiy)Ovvrmnq1noX?2)Ca`K*I3id@o2DrUqf-=BzHiIy>%N4w* zk7)Q%WQF`k*3XmiB7Rp7uMdGf`0cL&1zXzn-0CpzJ_%{2&cwJdzxgCymt(vDjNkNI zALvhd>(*mQ!n!r;rU+f1uE!WVS^-l&(-Gp6!%_9drkIQfU1dIu5SA#AgUQQx=qkzU z^7RD%pl1YE>&Wgq^i+sA7xKvy8oT*(-E^bgVe*iU6bIR=7jdrUIdtsqNf>_vW5;5w zs|Z$xUX+o+cnj3AQ#bxLW8;JY2E@i*0RzFRFGm+?^N~5qSK8%5N%?UFx^_SmOEtL+ zJ$~TM2vifw0}k@L{Q2CI(}IC;cq5c@VP$H&Z~9ND~kudKa|kfGG$tqrHTrymb2&r*qN{4x?s53E?$? zx(ifje76tpylXg6A#Oh?IVjP3b2unz_Pg2arV{d-36&qmCH*!+>!n!g_jo3*&xGsaoD}(G0_P+b2PUEw zyqh@4H^UH2RdPo=soL0{wtQndvwW$qv^~E3T!*IO6Yn`~zNyHRZ#wRsXHGJ>z0OH$ z4oY!~G`G>D^_t9a9F*pF0n%|B^R?b$Gfruu@68}0@YM`TC%1qx8IqDs9g}L=X{unbXdB{;j=C?IbuS6@#e*0FBpsalBv7)rVZY z?*u7jLx+-pkdk}b3mvDYPB&{UAA5Z!ttHY5o4No=y{;|*l#3=D3zW9!lemsrFRrD| zhf6B);r61u6ziO{tsSXSy?8Gg&uuJ~_)Vbqn#7im55k&zy>JuL5!b@JMiWw7r?w*k zyWy~kR`A}j$BFccU@9zVM@quGg+(mT7Vbj}<*f_4X4KsT^5f78oz(ccj?**Lmr;o5 ztth}f6Zg=MgHTF`h)zof0e5;o5u^zm3j0rOFTuU}j=$J@%@BL8A=p=h%+)~s0IC|gsx zsBGQxwIeF-WCOVXfB?V-00aQ61OO5Mo&f*}0PF&QC;<2z0Hgqrg#cs#Fq;4|(|QSj z8~`X8fC2#Qa)4+6I28||1OQh$Kn%{!1`vzQT>vUkl3VTAi;u+ zZ^$4D+y7316r1W;kf}kG|Dv${l{k>A0qoZXfI!Pcjc;;Wh)lm53^P*TmhMjmai&Xn+f`r>y|Iifcz;y;Xj;KPQST*CQ$#J z0aWpfi2KbMKxOy;R!p5esIOJ4_73)j+>3(MCn79&6u5I}+nD4-x7_YqmF zJT)agaqPq~IYXJuZ0Dm-KDK;W`NE=7Hh<=fxev7ler@aR>Acz8^0oiWr+@!y+pDkb zdExn|o<98kpWgW3=toU|J9YLSm#y2H$7AH%Kp8> z>5LH*?j4;wL>o7Nl*A|=oI2-WTS=jLm7{D?)!HZ4Z++=m*UlZa`#c|dkH7nN-NEiY zp8MAi9Y25a*MEL~_1p6omaJTCU$^G*4bvW2FnhAqQjj!wpgM|(R_cb0)ZaHgZ`71x z)1>LM=FfX%b@j%jD=I7QA7{KLEj`O1MU*OeP=e;Yw+{Td;n>F~c5UDN`g1RC+5Ful z-#4c}`|^vQzQ6uk=yunQ-v@av8<;xdV_S-6# zR7I@*wLlfG18VX*pr)+@YSucS=BxuMe;rVT>%=xSrK$;&*w4nSL|M4;?|f9m506Le zH{y;v{v;7UJa(~P_T7H{V;ZN4{qOwY@r{4u^za|{7t@{%00*!GL5#x2YygDqghVnH z0JO6Kvc}MojB}4^mP%MGT-%ugv)G2^Hke%%7KD`4A5JUrU4o(b?Jbq9rSr zR5|GE?Ef0lGTo9hW?qh%98J^n(yJf(Kf>nzKZTt!YjV+onS~{VlM81~pYy*K)-v7l zKN9`lN-$PTS|n6|aTP#Yrd#N2y3~frHfhyb`jN8bODe_IqNkQsEL*ttf4Ud_;XZwK zgz%L#J+k}(^62gQ8kV1ksLKLX*R0dHJ6-Z&DI0U3J1TqLC3P?FcOawU$!P6ed zqhz3fFdjM(4Pj9Br>`W3Kumx7F;Ws@Axx+MDO6}9sQc4bOH>fopMIPSK|F+!21vPv zmGM%j^pterW!@xpQVe_`s~0Gp0`~oif>GEuO>{nDZyz zH(}g8qjE=PXAWoRRIMgPtn&Z)jqDGx%P4y^t1R}{kEY4@B%N6yd%0_=bM&E#wz{2_ zujRTg#~wU><*~tS7hBzz&b?|V`B2`p!Skdn`*>jcAn&$H^E#ox9* z?O8qK*oV?XKYCx!yKwyan`dR!qq;%$(qZ{7?e5s`PsA+Un0?<0>ec0y+tK`rpSq?k zTUK7SJhj=l@aZW~-ucT;>GH=9p_EU$sHYx0qq_OmOZ5w2>pO1$wklgv@UKB+-hvXv+h;e#T)lU7)YP~0iQ#H>^vP#v<=OOOjt7rE zy^5A!Sk(CXk7fUe?f&lJ-DfXlr0w?Ae{lGlzYVnVzv(aUF8}Bhz4`br zA0GAYRsQfHx%ZrB?YK!7+uwim-2TL2mnEAAT&aqWuDG^kLgg#>FI^FHc<$2m(f^G7 zaer7|GyFYJcwUn|QBb4e&ec)RIy%wdzSGhr4?S4Uf3bL>YxS7rNdf7ym5-!c=xa5c z-#T~wx9TsgR~N5pY3%O)?c__AlYbd_@uhnE^}4UWezL~@#+lR2W2bkvlm-`{@GpMw z<3C-M9-C+z(@^xSA*Q(`Me+VED>=r#UXuUmZ}yg1EsGET_R`9n$4)L`UpQL!Me^oF zA0IfkDt*ikj_EreReniMiayaefJhrTENa%t2_Jo?k8Wz%G4}(5Wa-iQe-3|hI_ICh zW6!^KDQnPs-_5H(U0FMSZD z?-@Lgk4^bdS^Ltt9Wf^_{_8KlUD=>(xg34r-1%qBKU@e3N3S|oZvJ-2R|8INnm4TR z*7uLruX=RSU$j5XrQFV?s_@?@NEgkIMseZS7QVdXy>j7vcv)HDKbH@v{y}lz*K;x7 z%-k%Qa{4Gau58%iKl20ZzR8o86kmRH<^9&B{`aoT{rb|P=oS+M&o#6Rw5XSO!C{!4iI`04g literal 0 HcmV?d00001 diff --git a/boards/radiolink/PIX6/firmware.prototype b/boards/radiolink/PIX6/firmware.prototype new file mode 100644 index 0000000000..28c9d11fb5 --- /dev/null +++ b/boards/radiolink/PIX6/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 1410, + "magic": "PX4FWv1", + "description": "Firmware for the RadiolinkPIX6 board", + "image": "", + "build_time": 0, + "summary": "RadiolinkPIX6", + "version": "0.1", + "image_size": 0, + "image_maxsize": 2064384, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/radiolink/PIX6/init/rc.board_defaults b/boards/radiolink/PIX6/init/rc.board_defaults new file mode 100644 index 0000000000..6e48130e10 --- /dev/null +++ b/boards/radiolink/PIX6/init/rc.board_defaults @@ -0,0 +1,14 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ + +param set-default BAT1_V_DIV 18.1 +param set-default BAT2_V_DIV 18.1 + +param set-default BAT1_A_PER_V 36.367515152 +param set-default BAT2_A_PER_V 36.367515152 + +param set-default EKF2_MULTI_IMU 2 +param set-default SENS_IMU_MODE 0 +#safety_button start diff --git a/boards/radiolink/PIX6/init/rc.board_extras b/boards/radiolink/PIX6/init/rc.board_extras new file mode 100644 index 0000000000..a6dadf5699 --- /dev/null +++ b/boards/radiolink/PIX6/init/rc.board_extras @@ -0,0 +1,9 @@ +#!/bin/sh +# +# board extras init +#------------------------------------------------------------------------------ + +if ! param compare OSD_ATXXXX_CFG 0 +then + atxxxx start -s +fi diff --git a/boards/radiolink/PIX6/init/rc.board_sensors b/boards/radiolink/PIX6/init/rc.board_sensors new file mode 100644 index 0000000000..abd52fe183 --- /dev/null +++ b/boards/radiolink/PIX6/init/rc.board_sensors @@ -0,0 +1,53 @@ +#!/bin/sh +# +# board sensors init +#------------------------------------------------------------------------------ + +set HAVE_PM2 yes + +board_adc start + +if param compare SENS_EN_INA226 1 +then + if [ $HAVE_PM2 = yes ] + then + ina226 -X -b 2 -t 2 -k start + fi + +fi + +if param compare SENS_EN_INA228 1 +then + if [ $HAVE_PM2 = yes ] + then + ina228 -X -b 2 -t 2 -k start + fi + +fi + +if param compare SENS_EN_INA238 1 +then + if [ $HAVE_PM2 = yes ] + then + ina238 -X -b 2 -t 2 -k start + fi + +fi + +# Internal SPI bus ICM42688p +icm42688p -R 2 -s start + +# Internal SPI BMI088 +bmi088 -A -R 4 -s start +bmi088 -G -R 4 -s start + +spa06 -I start + +# internal compass +ist8310 -I start + +# External compass on GPS1/I2C1 +ist8310 -X start + +# Possible internal Baro +unset HAVE_PM2 diff --git a/boards/radiolink/PIX6/nuttx-config/Kconfig b/boards/radiolink/PIX6/nuttx-config/Kconfig new file mode 100644 index 0000000000..520c5abadb --- /dev/null +++ b/boards/radiolink/PIX6/nuttx-config/Kconfig @@ -0,0 +1,17 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# +config BOARD_HAS_PROBES + bool "Board provides GPIO or other Hardware for signaling to timing analyze." + default y + ---help--- + This board provides GPIO FMU-CH1-8, CAP1 as PROBE_1-9 to provide timing signals from selected drivers. + +config BOARD_USE_PROBES + bool "Enable the use the board provided FMU-CH1-8, CAP1 as PROBE_1-9" + default n + depends on BOARD_HAS_PROBES + + ---help--- + Select to use GPIO FMU-CH1-8, CAP1 to provide timing signals from selected drivers. diff --git a/boards/radiolink/PIX6/nuttx-config/include/board.h b/boards/radiolink/PIX6/nuttx-config/include/board.h new file mode 100644 index 0000000000..186af298dd --- /dev/null +++ b/boards/radiolink/PIX6/nuttx-config/include/board.h @@ -0,0 +1,455 @@ +/************************************************************************************ + * + * Copyright (C) 2016-2019 Gregory Nutt. All rights reserved. + * Authors: David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * +/************************************************************************************ + * Included Files + ************************************************************************************/ +#include "board_dma_map.h" + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdmmc.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The radiolink_pix6 board provides the following clock sources: + * + * 24 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 16 MHz RC factory-trimmed + * HSE: 24 MHz crystal for HSE + */ +#define STM32_BOARD_XTAL 24000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE = 24,000,000 + * + * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 2 <= PLLM <= 63 + * 192 <= PLLN <= 432 + * 192 MHz <= PLL_VCO <= 432MHz + * + * SYSCLK = PLL_VCO / PLLP + * Subject to + * + * PLLP = {2, 4, 6, 8} + * SYSCLK <= 216 MHz + * + * USB OTG FS, SDMMC and RNG Clock = PLL_VCO / PLLQ + * Subject to + * The USB OTG FS requires a 48 MHz clock to work correctly. The SDMMC + * and the random number generator need a frequency lower than or equal + * to 48 MHz to work correctly. + * + * 2 <= PLLQ <= 15 + */ + +/* Highest SYSCLK with USB OTG FS clock = 48 MHz + * + * PLL_VCO = (24,000,000 / 24) * 432 = 432 MHz + * SYSCLK = 432 MHz / 2 = 216 MHz + * USB OTG FS, SDMMC and RNG Clock = 432 MHz / 9 = 48 MHz + */ + +#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(24) +#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(432) +#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2 +#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(9) + +#define STM32_VCO_FREQUENCY ((STM32_HSE_FREQUENCY / 24) * 432) +#define STM32_SYSCLK_FREQUENCY (STM32_VCO_FREQUENCY / 2) +#define STM32_OTGFS_FREQUENCY (STM32_VCO_FREQUENCY / 9) + +/* Configure factors for PLLSAI clock */ +#define CONFIG_STM32F7_PLLSAI 1 +#define STM32_RCC_PLLSAICFGR_PLLSAIN RCC_PLLSAICFGR_PLLSAIN(192) +#define STM32_RCC_PLLSAICFGR_PLLSAIP RCC_PLLSAICFGR_PLLSAIP(8) +#define STM32_RCC_PLLSAICFGR_PLLSAIQ RCC_PLLSAICFGR_PLLSAIQ(4) +#define STM32_RCC_PLLSAICFGR_PLLSAIR RCC_PLLSAICFGR_PLLSAIR(2) + +/* Configure Dedicated Clock Configuration Register */ +#define STM32_RCC_DCKCFGR1_PLLI2SDIVQ RCC_DCKCFGR1_PLLI2SDIVQ(1) +#define STM32_RCC_DCKCFGR1_PLLSAIDIVQ RCC_DCKCFGR1_PLLSAIDIVQ(1) +#define STM32_RCC_DCKCFGR1_PLLSAIDIVR RCC_DCKCFGR1_PLLSAIDIVR(0) +#define STM32_RCC_DCKCFGR1_SAI1SRC RCC_DCKCFGR1_SAI1SEL(0) +#define STM32_RCC_DCKCFGR1_SAI2SRC RCC_DCKCFGR1_SAI2SEL(0) +#define STM32_RCC_DCKCFGR1_TIMPRESRC 0 +#define STM32_RCC_DCKCFGR1_DFSDM1SRC 0 +#define STM32_RCC_DCKCFGR1_ADFSDM1SRC 0 + +/* Configure factors for PLLI2S clock */ +#define CONFIG_STM32F7_PLLI2S 1 +#define STM32_RCC_PLLI2SCFGR_PLLI2SN RCC_PLLI2SCFGR_PLLI2SN(192) +#define STM32_RCC_PLLI2SCFGR_PLLI2SP RCC_PLLI2SCFGR_PLLI2SP(2) +#define STM32_RCC_PLLI2SCFGR_PLLI2SQ RCC_PLLI2SCFGR_PLLI2SQ(2) +#define STM32_RCC_PLLI2SCFGR_PLLI2SR RCC_PLLI2SCFGR_PLLI2SR(2) + +/* Configure Dedicated Clock Configuration Register 2 */ +#define STM32_RCC_DCKCFGR2_USART1SRC RCC_DCKCFGR2_USART1SEL_APB +#define STM32_RCC_DCKCFGR2_USART2SRC RCC_DCKCFGR2_USART2SEL_APB +#define STM32_RCC_DCKCFGR2_UART4SRC RCC_DCKCFGR2_UART4SEL_APB +#define STM32_RCC_DCKCFGR2_UART5SRC RCC_DCKCFGR2_UART5SEL_APB +#define STM32_RCC_DCKCFGR2_USART6SRC RCC_DCKCFGR2_USART6SEL_APB +#define STM32_RCC_DCKCFGR2_UART7SRC RCC_DCKCFGR2_UART7SEL_APB +#define STM32_RCC_DCKCFGR2_UART8SRC RCC_DCKCFGR2_UART8SEL_APB +#define STM32_RCC_DCKCFGR2_I2C1SRC RCC_DCKCFGR2_I2C1SEL_HSI +#define STM32_RCC_DCKCFGR2_I2C2SRC RCC_DCKCFGR2_I2C2SEL_HSI +#define STM32_RCC_DCKCFGR2_I2C3SRC RCC_DCKCFGR2_I2C3SEL_HSI +#define STM32_RCC_DCKCFGR2_I2C4SRC RCC_DCKCFGR2_I2C4SEL_HSI +#define STM32_RCC_DCKCFGR2_LPTIM1SRC RCC_DCKCFGR2_LPTIM1SEL_APB +#define STM32_RCC_DCKCFGR2_CECSRC RCC_DCKCFGR2_CECSEL_HSI +#define STM32_RCC_DCKCFGR2_CK48MSRC RCC_DCKCFGR2_CK48MSEL_PLL +#define STM32_RCC_DCKCFGR2_SDMMCSRC RCC_DCKCFGR2_SDMMCSEL_48MHZ +#define STM32_RCC_DCKCFGR2_SDMMC2SRC RCC_DCKCFGR2_SDMMC2SEL_48MHZ +#define STM32_RCC_DCKCFGR2_DSISRC RCC_DCKCFGR2_DSISEL_PHY + + + +/* Several prescalers allow the configuration of the two AHB buses, the + * high-speed APB (APB2) and the low-speed APB (APB1) domains. The maximum + * frequency of the two AHB buses is 216 MHz while the maximum frequency of + * the high-speed APB domains is 108 MHz. The maximum allowed frequency of + * the low-speed APB domain is 54 MHz. + */ + +/* AHB clock (HCLK) is SYSCLK (216 MHz) */ + +#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/4 (54 MHz) */ + +#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4) + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* APB2 clock (PCLK2) is HCLK/2 (108MHz) */ + +#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* SDMMC dividers. Note that slower clocking is required when DMA is disabled + * in order to avoid RX overrun/TX underrun errors due to delayed responses + * to service FIFOs in interrupt driven mode. These values have not been + * tuned!!! + * + * SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(118+2)=400 KHz + */ + +/* Use the Falling edge of the SDIO_CLK clock to change the edge the + * data and commands are change on + */ + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + +#define STM32_SDMMC_INIT_CLKDIV (118 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* DMA ON: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(1+2)=16 MHz + * DMA OFF: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(2+2)=12 MHz + */ + +#ifdef CONFIG_STM32F7_SDMMC_DMA +# define STM32_SDMMC_MMCXFR_CLKDIV (1 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (2 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +/* DMA ON: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(1+2)=16 MHz + * DMA OFF: SDMMCCLK=48MHz, SDMMC_CK=SDMMCCLK/(2+2)=12 MHz + */ +//TODO #warning "Check Freq for 24mHz" + +#ifdef CONFIG_STM32F7_SDMMC_DMA +# define STM32_SDMMC_SDXFR_CLKDIV (1 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (2 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +/* FLASH wait states + * + * --------- ---------- ----------- + * VDD MAX SYSCLK WAIT STATES + * --------- ---------- ----------- + * 1.7-2.1 V 180 MHz 8 + * 2.1-2.4 V 216 MHz 9 + * 2.4-2.7 V 216 MHz 8 + * 2.7-3.6 V 216 MHz 7 + * --------- ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 7 + +/* LED definitions ******************************************************************/ +/* The radiolink_pix6 board has numerous LEDs but only three, LED_GREEN a Green LED, LED_BLUE + * a Blue LED and LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_GREEN BOARD_LED2 +#define BOARD_LED_BLUE BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* Alternate function pin selections ************************************************/ + +#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PB7 */ +#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PB6 */ + +#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */ +#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ +#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */ +#define GPIO_USART2_CTS GPIO_USART2_CTS_2 /* PD3 */ + +#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ +#define GPIO_USART3_RTS GPIO_USART3_RTS_2 /* PD12 */ +#define GPIO_USART3_CTS GPIO_USART3_CTS_2 /* PD11 */ + +#define GPIO_UART4_RX GPIO_UART4_RX_1 /* PA1 */ +#define GPIO_UART4_TX GPIO_UART4_TX_1 /* PA0 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_1 /* PE7 */ +#define GPIO_UART7_TX GPIO_UART7_TX_1 /* PE8 */ + +/* UART8: has no remap + * + * GPIO_UART8_RX PE0 + * GPIO_UART8_TX PE1 + */ + + +/* CAN + * + * CAN1 is routed to transceiver. + * CAN2 is routed to transceiver. + */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */ +#define GPIO_CAN2_RX GPIO_CAN2_RX_2 /* PB13 */ +#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB5 */ + +/* SPI + * SPI1 is sensors + * SPI2 is OSD & RAMTRON + * SPI4 is EXTERNAL1 + * + */ + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 /* PA6 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_3 /* PD7 */ +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_2 /* PB3 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 /* PB15 */ +#define GPIO_SPI2_SCK GPIO_SPI2_SCK_1 /* PA9 */ + +#define GPIO_SPI4_MISO GPIO_SPI4_MISO_2 /* PE13 */ +#define GPIO_SPI4_MOSI GPIO_SPI4_MOSI_1 /* PE6 */ +#define GPIO_SPI4_SCK GPIO_SPI4_SCK_1 /* PE2 */ + +/* I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + * + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */ + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 /* PB10 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 /* PB11 */ + + +/* SDMMC1 + * + * VDD 3.3 + * GND + * SDMMC1_CK PC12 + * SDMMC1_CMD PD2 + * SDMMC1_D0 PC8 + * SDMMC1_D1 PC9 + * SDMMC1_D2 PC10 + * SDMMC1_D3 PC11 + */ + +// #define GPIO_SDMMC1_D0 GPIO_SDMMC1_D0 +// #define GPIO_SDMMC1_D1 GPIO_SDMMC1_D1 +// #define GPIO_SDMMC1_D2 GPIO_SDMMC1_D2 +// #define GPIO_SDMMC1_D3 GPIO_SDMMC1_D3 + +/* The STM32 F7 connects to a TI DP83848TSQ/NOPB + * using RMII + * + * STM32 F7 BOARD DP83848TSQ/NOPB + * GPIO SIGNAL PIN NAME + * -------- ------------ ------------- + * PA7 ETH_CRS_DV CRS_DV + * PC1 ETH_MDC MDC + * PA2 ETH_MDIO MDIO + * PA1 ETH_REF_CL X1 + * PC4 ETH_RXD0 RX_D0 + * PC5 ETH_RXD1 RX_D1 + * PB11 ETH_TX_EN TX_EN + * PG13 ETH_TXD0 TX_D0 + * PB13 ETH_TXD1 TX_D1 + * + * The PHY address is 1, since COL/PHYAD0 features a pull up. + */ + +// #define GPIO_ETH_RMII_TX_EN GPIO_ETH_RMII_TX_EN_1 +// #define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_2 +// #define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_1 + + +/* USB + * + * OTG_FS_DM PA11 + * OTG_FS_DP PA12 + * VBUS PA9 + */ + + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +#if defined(CONFIG_BOARD_USE_PROBES) +# include "stm32_gpio.h" +# define PROBE_N(n) (1<<((n)-1)) +# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN14) /* PE14 AUX1 */ +# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN10) /* PA10 AUX2 */ +# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 AUX3 */ +# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9) /* PE9 AUX4 */ +# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15) /* PA15 AUX5 */ +# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN7) /* PA7 AUX6 */ +# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN6) /* PC6 AUX7 */ +# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN3) /* PA3 AUX8 */ +# //define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 CAP1 */ + +# define PROBE_INIT(mask) \ + do { \ + if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \ + if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \ + if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \ + if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \ + if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \ + if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \ + if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \ + if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \ + /*if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \*/ + +} while (0) + +# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0) +# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) +#else +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) +#endif diff --git a/boards/radiolink/PIX6/nuttx-config/include/board_dma_map.h b/boards/radiolink/PIX6/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..3e4eb5c326 --- /dev/null +++ b/boards/radiolink/PIX6/nuttx-config/include/board_dma_map.h @@ -0,0 +1,39 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +#define DMAMAP_USART3_TX DMAMAP_USART3_TX_1 // DMA1, Stream 3, Channel 4 (TELEM2 RX) +#define DMAMAP_SDMMC1 DMAMAP_SDMMC1_2 // DMA2, Stream 6, Channel 11 +#define DMAMAP_SPI1_RX DMAMAP_SPI1_RX_1 // DMA2, Stream 0, Channel 3 (SPI sensors RX) +#define DMAMAP_SPI1_TX DMAMAP_SPI1_TX_1 // DMA2, Stream 3, Channel 3 (SPI sensors TX) diff --git a/boards/radiolink/PIX6/nuttx-config/nsh/defconfig b/boards/radiolink/PIX6/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..56616a4298 --- /dev/null +++ b/boards/radiolink/PIX6/nuttx-config/nsh/defconfig @@ -0,0 +1,259 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_IFUPDOWN is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TELNETD is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/radiolink/PIX6/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="radiolink" +CONFIG_ARCH_CHIP="stm32f7" +CONFIG_ARCH_CHIP_STM32F765II=y +CONFIG_ARCH_CHIP_STM32F7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_ITCM=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=22114 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0032 +CONFIG_CDCACM_PRODUCTSTR="radiolink PIX6" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x26ac +CONFIG_CDCACM_VENDORSTR="radiolink" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_GPIO=y +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_EXAMPLES_CALIB_UDELAY=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=3 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDMMC1_SDIO_MODE=y +CONFIG_SDMMC1_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32F7_ADC1=y +CONFIG_STM32F7_BBSRAM=y +CONFIG_STM32F7_BBSRAM_FILES=5 +CONFIG_STM32F7_BKPSRAM=y +CONFIG_STM32F7_DMA1=y +CONFIG_STM32F7_DMA2=y +CONFIG_STM32F7_DMACAPABLE=y +CONFIG_STM32F7_FLOWCONTROL_BROKEN=y +CONFIG_STM32F7_I2C1=y +CONFIG_STM32F7_I2C2=y +CONFIG_STM32F7_I2C_DYNTIMEO=y +CONFIG_STM32F7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32F7_OTGFS=y +CONFIG_STM32F7_PROGMEM=y +CONFIG_STM32F7_PWR=y +CONFIG_STM32F7_RTC=y +CONFIG_STM32F7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y +CONFIG_STM32F7_RTC_MAGIC_REG=1 +CONFIG_STM32F7_SAVE_CRASHDUMP=y +CONFIG_STM32F7_SDMMC1=y +CONFIG_STM32F7_SDMMC_DMA=y +CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32F7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32F7_SPI1=y +CONFIG_STM32F7_SPI1_DMA=y +CONFIG_STM32F7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32F7_SPI2=y +#CONFIG_STM32F7_SPI2_DMA=y +#CONFIG_STM32F7_SPI2_DMA_BUFFER=1024 +CONFIG_STM32F7_SPI4=y +CONFIG_STM32F7_SPI_DMATHRESHOLD=8 +CONFIG_STM32F7_TIM5=y +CONFIG_STM32F7_UART4=y +CONFIG_STM32F7_UART7=y +CONFIG_STM32F7_UART8=y +CONFIG_STM32F7_USART1=y +CONFIG_STM32F7_USART2=y +CONFIG_STM32F7_USART3=y +CONFIG_STM32F7_USART_BREAKS=y +CONFIG_STM32F7_USART_INVERT=y +CONFIG_STM32F7_USART_SINGLEWIRE=y +CONFIG_STM32F7_USART_SWAP=y +CONFIG_STM32F7_WWDG=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_RXBUFSIZE=180 +CONFIG_UART7_SERIAL_CONSOLE=y +CONFIG_UART7_TXBUFSIZE=1500 +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_RXDMA=y +CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_RXDMA=y +CONFIG_USART2_TXBUFSIZE=3000 +CONFIG_USART3_IFLOWCONTROL=y +CONFIG_USART3_OFLOWCONTROL=y +CONFIG_USART3_RXBUFSIZE=600 +CONFIG_USART3_RXDMA=y +CONFIG_USART3_TXBUFSIZE=3000 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/radiolink/PIX6/nuttx-config/scripts/kernel-space.ld b/boards/radiolink/PIX6/nuttx-config/scripts/kernel-space.ld new file mode 100644 index 0000000000..8ad6e7bf44 --- /dev/null +++ b/boards/radiolink/PIX6/nuttx-config/scripts/kernel-space.ld @@ -0,0 +1,146 @@ +/**************************************************************************** + * kernel-space.ld + * + * Copyright (C) 2015 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* NOTE: This depends on the memory.ld script having been included prior to + * this script. + */ + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) +/* + * TODO: Fill in the signature location into TOC from user-space elf +EXTERN(_main_toc) +*/ + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + /* + *(.main_toc) + */ + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > kflash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > kflash + + + .ARM.extab : { + *(.ARM.extab*) + } > kflash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > kflash + + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > ksram AT > kflash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > ksram + + /* Stabs debugging sections */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } + + .ramfunc : { + _sramfuncs = .; + *(.ramfunc .ramfunc.*) + . = ALIGN(4); + _eramfuncs = .; + } > ksram AT > kflash + + _framfuncs = LOADADDR(.ramfunc); +} diff --git a/boards/radiolink/PIX6/nuttx-config/scripts/memory.ld b/boards/radiolink/PIX6/nuttx-config/scripts/memory.ld new file mode 100644 index 0000000000..23e536e9c5 --- /dev/null +++ b/boards/radiolink/PIX6/nuttx-config/scripts/memory.ld @@ -0,0 +1,98 @@ +/**************************************************************************** + * scripts/memory.ld + * + * Copyright (C) 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The STM32F765IIT6 has 2048 KiB of main FLASH memory. This FLASH memory + * can be accessed from either the AXIM interface at address 0x0800:0000 or + * from the ITCM interface at address 0x0020:0000. + * + * Additional information, including the option bytes, is available at at + * FLASH at address 0x1ff0:0000 (AXIM) or 0x0010:0000 (ITCM). + * + * In the STM32F765IIT6, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash on ITCM at 0x0020:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x0010:0000 + * + * NuttX does not modify these option byes. On the unmodified NUCLEO-144 + * board, the BOOT0 pin is at ground so by default, the STM32F765IIT6 will + * boot from address 0x0020:0000 in ITCM FLASH. + * + * The STM32F765IIT6 also has 512 KiB of data SRAM (in addition to ITCM SRAM). + * SRAM is split up into three blocks: + * + * 1) 128 KiB of DTCM SRM beginning at address 0x2000:0000 + * 2) 368 KiB of SRAM1 beginning at address 0x2002:0000 + * 3) 16 KiB of SRAM2 beginning at address 0x2007:c000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * Bootloader reserves the first 32K bank (2 Mbytes Flash memory single bank) + * organization (256 bits read width) + */ + +MEMORY +{ + /* ITCM boot address */ + + itcm (rwx) : ORIGIN = 0x00208000, LENGTH = 2048K-32K + + /* 2048KB FLASH, bootloader reserves the first 32kb */ + + kflash (rx) : ORIGIN = 0x08008000, LENGTH = 1024K-32K + uflash (rx) : ORIGIN = 0x08100000, LENGTH = 1024K + + /* ITCM RAM */ + + itcm_ram (rwx) : ORIGIN = 0x00000000, LENGTH = 16K + + /* DTCM SRAM */ + + dtcm_ram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + + /* 368KB of contiguous SRAM1 */ + + ksram (rwx) : ORIGIN = 0x20020000, LENGTH = 128K + usram (rwx) : ORIGIN = 0x20040000, LENGTH = 368K-128K + + /* 16KB of SRAM2 */ + + sram2 (rwx) : ORIGIN = 0x2007c000, LENGTH = 16K +} diff --git a/boards/radiolink/PIX6/nuttx-config/scripts/script.ld b/boards/radiolink/PIX6/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..db0f740cf0 --- /dev/null +++ b/boards/radiolink/PIX6/nuttx-config/scripts/script.ld @@ -0,0 +1,181 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The STM32F765IIT6 has 2048 KiB of main FLASH memory. This FLASH memory + * can be accessed from either the AXIM interface at address 0x0800:0000 or + * from the ITCM interface at address 0x0020:0000. + * + * Additional information, including the option bytes, is available at at + * FLASH at address 0x1ff0:0000 (AXIM) or 0x0010:0000 (ITCM). + * + * In the STM32F765IIT6, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash on ITCM at 0x0020:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x0010:0000 + * + * NuttX does not modify these option byes. On the unmodified NUCLEO-144 + * board, the BOOT0 pin is at ground so by default, the STM32F765IIT6 will + * boot from address 0x0020:0000 in ITCM FLASH. + * + * The STM32F765IIT6 also has 512 KiB of data SRAM (in addition to ITCM SRAM). + * SRAM is split up into three blocks: + * + * 1) 128 KiB of DTCM SRM beginning at address 0x2000:0000 + * 2) 368 KiB of SRAM1 beginning at address 0x2002:0000 + * 3) 16 KiB of SRAM2 beginning at address 0x2007:c000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * Bootloader reserves the first 32K bank (2 Mbytes Flash memory single bank) + * organization (256 bits read width) + */ + +MEMORY +{ + FLASH_ITCM (rx) : ORIGIN = 0x00208000, LENGTH = 2016K + FLASH_AXIM (rx) : ORIGIN = 0x08008000, LENGTH = 2016K + + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 16K + DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K + SRAM2 (rwx) : ORIGIN = 0x2007c000, LENGTH = 16K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH_AXIM + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH_AXIM + + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH_AXIM + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH_AXIM + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > SRAM1 AT > FLASH_AXIM + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > SRAM1 + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } + + .ramfunc : { + _sramfuncs = .; + *(.ramfunc .ramfunc.*) + . = ALIGN(4); + _eramfuncs = .; + } > ITCM_RAM AT > FLASH_AXIM + + _framfuncs = LOADADDR(.ramfunc); +} diff --git a/boards/radiolink/PIX6/nuttx-config/scripts/user-space.ld b/boards/radiolink/PIX6/nuttx-config/scripts/user-space.ld new file mode 100644 index 0000000000..e19ddea756 --- /dev/null +++ b/boards/radiolink/PIX6/nuttx-config/scripts/user-space.ld @@ -0,0 +1,124 @@ +/**************************************************************************** + * user-space.ld + * + * Copyright (C) 2015 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* NOTE: This depends on the memory.ld script having been included prior to + * this script. + */ +EXTERN(userspace) +OUTPUT_ARCH(arm) +SECTIONS +{ + .userspace : { + *(.userspace) + } > uflash + + .text : { + _stext = ABSOLUTE(.); + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > uflash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > uflash + + + .ARM.extab : { + *(.ARM.extab*) + } > uflash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > uflash + + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > usram AT > uflash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + /* Kernel heap start at _ebss, make _ebss MPU-friendly aligned */ + . = ALIGN(0x1000); + _ebss = ABSOLUTE(.); + } > usram + + /* Stabs debugging sections */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } + + /* Start of the image signature. This + * has to be in the end of the image + */ + .signature : { + _boot_signature = ALIGN(4); + } > uflash +} diff --git a/boards/radiolink/PIX6/src/CMakeLists.txt b/boards/radiolink/PIX6/src/CMakeLists.txt new file mode 100644 index 0000000000..7fbfb7b94d --- /dev/null +++ b/boards/radiolink/PIX6/src/CMakeLists.txt @@ -0,0 +1,55 @@ +############################################################################ +# +# Copyright (c) 2016 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +add_library(drivers_board + can.c + i2c.cpp + init.cpp + led.c + mtd.cpp + sdio.c + spi.cpp + timer_config.cpp + usb.c +) +add_dependencies(drivers_board arch_board_hw_info) +target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + arch_board_hw_info + drivers__led # drv_led_start + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer +) diff --git a/boards/radiolink/PIX6/src/board_config.h b/boards/radiolink/PIX6/src/board_config.h new file mode 100644 index 0000000000..845d5d7bd4 --- /dev/null +++ b/boards/radiolink/PIX6/src/board_config.h @@ -0,0 +1,293 @@ +/**************************************************************************** + * + * Copyright (c) 2016-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * board internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include +#include + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +/* PX4IO connection configuration */ + +#define BOARD_USES_PX4IO_VERSION 2 +#define PX4IO_SERIAL_DEVICE "/dev/ttyS5" +#define PX4IO_SERIAL_TX_GPIO GPIO_UART8_TX +#define PX4IO_SERIAL_RX_GPIO GPIO_UART8_RX +#define PX4IO_SERIAL_BASE STM32_UART8_BASE +#define PX4IO_SERIAL_VECTOR STM32_IRQ_UART8 +#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_UART8_TX +#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_UART8_RX +#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB1ENR +#define PX4IO_SERIAL_RCC_EN RCC_APB1ENR_UART8EN +#define PX4IO_SERIAL_CLOCK STM32_PCLK1_FREQUENCY +#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */ + +/* Configuration ************************************************************************************/ + +#define BOARD_HAS_STATIC_MANIFEST 1 + +#define BOARD_HAS_LTC44XX_VALIDS 0 // No LTC or N Bricks +#define BOARD_HAS_USB_VALID 0 // LTC Has No USB valid +#define BOARD_HAS_NBAT_V 1 // Only one Vbat to ADC +#define BOARD_HAS_NBAT_I 0 // No Ibat ADC + +/* LEDs */ +#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_25MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN14) +#define GPIO_LED2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_25MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN1) +#define GPIO_LED3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_25MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN7) + +#define GPIO_LED_RED GPIO_LED1 +#define GPIO_LED_GREEN GPIO_LED2 +#define GPIO_LED_BLUE GPIO_LED3 + +#define BOARD_HAS_CONTROL_STATUS_LEDS 1 +#define BOARD_OVERLOAD_LED LED_RED +#define BOARD_ARMED_LED LED_BLUE +#define BOARD_ARMED_STATE_LED LED_GREEN + +/* Safety Switch is HW version dependent on having an PX4IO + * So we init to a benign state with the _INIT definition + * and provide the the non _INIT one for the driver to make a run time + * decision to use it. + */ +#define GPIO_nSAFETY_SWITCH_LED_OUT_INIT /* PB0 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTB|GPIO_PIN0) +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that + * can be used by the Px4 Firmware in the adc driver + */ + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ + +#define ADC1_CH(n) (n) +#define ADC1_GPIO(n) GPIO_ADC1_IN##n + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ + +#define PX4_ADC_GPIO \ + /* PA2 */ ADC1_GPIO(2), \ + /* PA4 */ ADC1_GPIO(4), \ + /* PA5 */ ADC1_GPIO(5), \ + /* PC0 */ ADC1_GPIO(10), \ + /* PC2 */ ADC1_GPIO(12), \ + /* PC3 */ ADC1_GPIO(13) + +/* Define Channel numbers must match above GPIO pin IN(n)*/ + +#define ADC_BATTERY_VOLTAGE_CHANNEL /* PA2 */ ADC1_CH(2) +#define ADC_BATTERY_CURRENT_CHANNEL /* PA5 */ ADC1_CH(5) +#define ADC_SCALED_V5_CHANNEL /* PC0 */ ADC1_CH(10) +#define ADC_ADC1_6V6_CHANNEL /* PC2 */ ADC1_CH(12) +#define ADC_ADC1_3V3_CHANNEL1 /* PC3 */ ADC1_CH(13) +#define ADC_ADC1_3V3_CHANNEL2 /* PA4 */ ADC1_CH(4) + +#define ADC_CHANNELS \ + ((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY_CURRENT_CHANNEL) | \ + (1 << ADC_SCALED_V5_CHANNEL) | \ + (1 << ADC_ADC1_3V3_CHANNEL2) | \ + (1 << ADC_ADC1_6V6_CHANNEL) | \ + (1 << ADC_ADC1_3V3_CHANNEL1)) + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ + +#define SYSTEM_ADC_BASE STM32_ADC1_BASE + +#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f) + +//#define UAVCAN_NUM_IFACES_RUNTIME 1 + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 8 + + +#define GPIO_VDD_5V_PERIPH_nEN /* PC4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN4) +#define GPIO_VDD_5V_PERIPH_nOC /* PE15 */ (GPIO_INPUT |GPIO_PULLUP|GPIO_PORTE|GPIO_PIN15) +#define GPIO_VDD_5V_HIPOWER_nEN /* PD13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN13) +#define GPIO_VDD_5V_HIPOWER_nOC /* PE10 */ (GPIO_INPUT |GPIO_PULLUP|GPIO_PORTE|GPIO_PIN10) +#define GPIO_VDD_3V3_SENSORS_EN /* PE3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN3) +#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN4) + +/* Define True logic Power Control in arch agnostic form */ + +#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_nEN, !(on_true)) +#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, !(on_true)) +#define VDD_3V3_SENSORS4_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, (on_true)) +#define VDD_3V3_SPEKTRUM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SPEKTRUM_POWER_EN, (on_true)) +#define READ_VDD_3V3_SPEKTRUM_POWER_EN() px4_arch_gpioread(GPIO_VDD_3V3_SPEKTRUM_POWER_EN) + + +/* Tone alarm output */ + +#define TONE_ALARM_TIMER 9 /* Timer 14 */ +#define TONE_ALARM_CHANNEL 1 /* PE5 GPIO_TIM14_CH1OUT_2 */ + +#define GPIO_BUZZER_1 /* PE5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN5) + +#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 +#define GPIO_TONE_ALARM GPIO_TIM9_CH1OUT_2 + +#define HRT_TIMER 5 /* use timer5 for the HRT */ +#define HRT_TIMER_CHANNEL 4 /* use capture/compare channel 4 */ +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing + */ +#define GPIO_nVDD_USB_VALID /* PB2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PORTB|GPIO_PIN2) + +/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */ +#define PWMIN_TIMER 2 +#define PWMIN_TIMER_CHANNEL /* T2C1 */ 1 +#define GPIO_PWM_IN /* PA15 */ GPIO_TIM2_CH1IN_2 +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* SD card bringup does not work if performed on the IDLE thread because it + * will cause waiting. Use either: + * + * CONFIG_BOARDCTL=y, OR + * CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y + */ + +#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_BOARDCTL) && \ + !defined(CONFIG_BOARD_INITTHREAD) +# warning SDIO initialization cannot be perfomed on the IDLE thread +#endif + +/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction) + * this board support the ADC system_power interface, and therefore + * provides the true logic GPIO BOARD_ADC_xxxx macros. + */ +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_nVDD_USB_VALID)) +#define BOARD_ADC_USB_VALID BOARD_ADC_USB_CONNECTED + +#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_nOC)) +#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC)) + + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ + +#define BOARD_HAS_ON_RESET 1 + +#define PX4_GPIO_INIT_LIST { \ + PX4_ADC_GPIO, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN2_TX, \ + GPIO_CAN2_RX, \ + GPIO_VDD_5V_PERIPH_nEN, \ + GPIO_VDD_5V_PERIPH_nOC, \ + GPIO_VDD_5V_HIPOWER_nEN, \ + GPIO_VDD_5V_HIPOWER_nOC, \ + GPIO_VDD_3V3_SENSORS_EN, \ + GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_nVDD_USB_VALID, \ + PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C1_SCL), \ + PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C1_SDA), \ + PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C2_SCL), \ + PX4_MAKE_GPIO_OUTPUT_CLEAR(GPIO_I2C2_SDA), \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define BOARD_NUM_IO_TIMERS 3 + + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/radiolink/PIX6/src/can.c b/boards/radiolink/PIX6/src/can.c new file mode 100644 index 0000000000..4f97951860 --- /dev/null +++ b/boards/radiolink/PIX6/src/can.c @@ -0,0 +1,124 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file can.c + * + * Board-specific CAN functions. + */ + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_internal.h" + +#include "chip.h" +#include "stm32_can.h" +#include "board_config.h" + +#ifdef CONFIG_CAN + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) +# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." +# undef CONFIG_STM32_CAN2 +#endif + +#ifdef CONFIG_STM32_CAN1 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int can_devinit(void); + +/************************************************************************************ + * Name: can_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/can. + * + ************************************************************************************/ + +int can_devinit(void) +{ + static bool initialized = false; + struct can_dev_s *can; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) { + /* Call stm32_caninitialize() to get an instance of the CAN interface */ + + can = stm32_caninitialize(CAN_PORT); + + if (can == NULL) { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + + if (ret < 0) { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} + +#endif diff --git a/boards/radiolink/PIX6/src/i2c.cpp b/boards/radiolink/PIX6/src/i2c.cpp new file mode 100644 index 0000000000..2b708954d5 --- /dev/null +++ b/boards/radiolink/PIX6/src/i2c.cpp @@ -0,0 +1,39 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusInternal(1), + initI2CBusExternal(2), +}; diff --git a/boards/radiolink/PIX6/src/init.cpp b/boards/radiolink/PIX6/src/init.cpp new file mode 100644 index 0000000000..6db9aea80f --- /dev/null +++ b/boards/radiolink/PIX6/src/init.cpp @@ -0,0 +1,277 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * PX4FMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialization. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "board_config.h" + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ +#define _GPIO_PULL_DOWN_INPUT(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_2MHz)) + +/* Configuration ************************************************************/ + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + /* set the peripheral rails off */ + + VDD_5V_PERIPH_EN(false); + board_control_spi_sensors_power(false, 0xffff); + VDD_3V3_SENSORS4_EN(false); + + bool last = READ_VDD_3V3_SPEKTRUM_POWER_EN(); + /* Keep Spektum on to discharge rail*/ + VDD_3V3_SPEKTRUM_POWER_EN(false); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ + VDD_3V3_SPEKTRUM_POWER_EN(last); + board_control_spi_sensors_power(true, 0xffff); + VDD_3V3_SENSORS4_EN(true); + VDD_5V_PERIPH_EN(true); + +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i))); + } + + if (status >= 0) { + up_mdelay(100); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +extern "C" __EXPORT void +stm32_boardinitialize(void) +{ + board_on_reset(-1); /* Reset PWM first thing */ + + /* configure LEDs */ + + board_autoled_initialize(); + + /* configure pins */ + + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + board_control_spi_sensors_power_configgpio(); + + /* configure USB interfaces */ + stm32_usbinitialize(); + +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ +static struct spi_dev_s *spi4; +__EXPORT int board_app_initialize(uintptr_t arg) +{ + /* Power on Interfaces */ + VDD_5V_PERIPH_EN(true); + VDD_5V_HIPOWER_EN(true); + board_control_spi_sensors_power(true, 0xffff); + VDD_3V3_SENSORS4_EN(true); + VDD_3V3_SPEKTRUM_POWER_EN(true); + + /* Need hrt running before using the ADC */ + + px4_platform_init(); + + /* Configure the Actual SPI interfaces (after we determined the HW version) */ + + stm32_spiinitialize(); + + spi4 = px4_spibus_initialize(4); + + if (!spi4) { + syslog(LOG_ERR, "[boot] FAILED to initialize SPI port 4\n"); + board_autoled_on(LED_AMBER); + } + + /* Default SPI4 to 10MHz and de-assert the known chip selects. */ + SPI_SETFREQUENCY(spi4, 10000000); + SPI_SETBITS(spi4, 8); + SPI_SETMODE(spi4, SPIDEV_MODE3); + up_udelay(20); + + //board_spi_reset(10, 0xffff); + + /* Configure the DMA allocator */ + + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + +#if defined(SERIAL_HAVE_RXDMA) + // set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event. + static struct hrt_call serial_dma_call; + hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL); +#endif + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_on(LED_GREEN); // Indicate Power. + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_RED); + } + +#ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_RED); + } + +#endif /* CONFIG_MMCSD */ + + /* Configure the HW based on the manifest */ + + px4_platform_configure(); + + return OK; +} diff --git a/boards/radiolink/PIX6/src/led.c b/boards/radiolink/PIX6/src/led.c new file mode 100644 index 0000000000..178c373637 --- /dev/null +++ b/boards/radiolink/PIX6/src/led.c @@ -0,0 +1,227 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * PX4FMU LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +#ifdef CONFIG_ARCH_LEDS +static bool nuttx_owns_leds = true; +// B R S G +// 0 1 2 3 +static const uint8_t xlatpx4[] = {1, 2, 4, 0}; +# define xlat(p) xlatpx4[(p)] +static uint32_t g_ledmap[] = { + GPIO_LED_GREEN, // Indexed by BOARD_LED_GREEN + GPIO_LED_BLUE, // Indexed by BOARD_LED_BLUE + GPIO_LED_RED, // Indexed by BOARD_LED_RED +}; + +#else + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_LED_BLUE, // Indexed by LED_BLUE + GPIO_LED_RED, // Indexed by LED_RED, LED_AMBER + GPIO_nSAFETY_SWITCH_LED_OUT_INIT, // Indexed by LED_SAFETY (defaulted to an input) + GPIO_LED_GREEN, // Indexed by LED_GREEN +}; + +#endif + +__EXPORT void led_init(void) +{ + + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + stm32_configgpio(g_ledmap[l]); + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + + stm32_gpiowrite(g_ledmap[led], !state); +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + return !stm32_gpioread(g_ledmap[led]); +} + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} + +#ifdef CONFIG_ARCH_LEDS +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + led_init(); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_HEAPALLOCATE: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_IRQSENABLED: + phy_set_led(BOARD_LED_BLUE, false); + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_STACKCREATED: + phy_set_led(BOARD_LED_GREEN, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, true); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, true); + break; + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, false); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, false); + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, false); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, false); + break; + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/boards/radiolink/PIX6/src/mtd.cpp b/boards/radiolink/PIX6/src/mtd.cpp new file mode 100644 index 0000000000..450dcdaf2b --- /dev/null +++ b/boards/radiolink/PIX6/src/mtd.cpp @@ -0,0 +1,78 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +//TODO:Prepare for NxtDual + +#include +#include +// KiB BS nB +static const px4_mft_device_t spi2 = { // FM25V02A on FMUM native: 32K X 8, emulated as (1024 Blocks of 32) + .bus_type = px4_mft_device_t::SPI, + .devid = SPIDEV_FLASH(0) +}; + +static const px4_mtd_entry_t fmum_fram = { + .device = &spi2, + .npart = 1, + .partd = { + { + .type = MTD_PARAMETERS, + .path = "/fs/mtd_params", + .nblocks = 1024 + } + }, +}; + + +static const px4_mtd_manifest_t board_mtd_config = { + .nconfigs = 1, + .entries = { + &fmum_fram + } +}; + +static const px4_mft_entry_s mtd_mft = { + .type = MTD, + .pmft = (void *) &board_mtd_config, +}; + +static const px4_mft_s mft = { + .nmft = 1, + .mfts = { + &mtd_mft + } +}; + +const px4_mft_s *board_get_manifest(void) +{ + return &mft; +} diff --git a/boards/radiolink/PIX6/src/sdio.c b/boards/radiolink/PIX6/src/sdio.c new file mode 100644 index 0000000000..869d757756 --- /dev/null +++ b/boards/radiolink/PIX6/src/sdio.c @@ -0,0 +1,177 @@ +/**************************************************************************** + * + * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "board_config.h" +#include "stm32_gpio.h" +#include "stm32_sdmmc.h" + +#ifdef CONFIG_MMCSD + + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Card detections requires card support and a card detection GPIO */ + +#define HAVE_NCD 1 +#if !defined(GPIO_SDMMC1_NCD) +# undef HAVE_NCD +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static FAR struct sdio_dev_s *sdio_dev; +#ifdef HAVE_NCD +static bool g_sd_inserted = 0xff; /* Impossible value */ +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_ncd_interrupt + * + * Description: + * Card detect interrupt handler. + * + ****************************************************************************/ + +#ifdef HAVE_NCD +static int stm32_ncd_interrupt(int irq, FAR void *context) +{ + bool present; + + present = !stm32_gpioread(GPIO_SDMMC1_NCD); + + if (sdio_dev && present != g_sd_inserted) { + sdio_mediachange(sdio_dev, present); + g_sd_inserted = present; + } + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void) +{ + int ret; + +#ifdef HAVE_NCD + /* Card detect */ + + bool cd_status; + + /* Configure the card detect GPIO */ + + stm32_configgpio(GPIO_SDMMC1_NCD); + + /* Register an interrupt handler for the card detect pin */ + + stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt); +#endif + + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + + finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO); + + sdio_dev = sdio_initialize(SDIO_SLOTNO); + + if (!sdio_dev) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + + finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR); + + ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev); + + if (ret != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + return ret; + } + + finfo("Successfully bound SDIO to the MMC/SD driver\n"); + +#ifdef HAVE_NCD + /* Use SD card detect pin to check if a card is g_sd_inserted */ + + cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD); + finfo("Card detect : %d\n", cd_status); + + sdio_mediachange(sdio_dev, cd_status); +#else + /* Assume that the SD card is inserted. What choice do we have? */ + + sdio_mediachange(sdio_dev, true); +#endif + + return OK; +} + +#endif /* CONFIG_MMCSD */ diff --git a/boards/radiolink/PIX6/src/spi.cpp b/boards/radiolink/PIX6/src/spi.cpp new file mode 100644 index 0000000000..0c47fe1e6b --- /dev/null +++ b/boards/radiolink/PIX6/src/spi.cpp @@ -0,0 +1,54 @@ +/**************************************************************************** + * + * Copyright (C) 2019-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortB, GPIO::Pin12}), + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortE, GPIO::Pin12}), + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortB, GPIO::Pin4}), + }), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortD, GPIO::Pin10}), + initSPIDevice(DRV_OSD_DEVTYPE_ATXXXX, SPI::CS{GPIO::PortA, GPIO::Pin8}), + }), + initSPIBusExternal(SPI::Bus::SPI4, { + initSPIConfigExternal(SPI::CS{GPIO::PortC, GPIO::Pin14}, SPI::DRDY{GPIO::PortD, GPIO::Pin15}), + initSPIConfigExternal(SPI::CS{GPIO::PortC, GPIO::Pin15}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/radiolink/PIX6/src/timer_config.cpp b/boards/radiolink/PIX6/src/timer_config.cpp new file mode 100644 index 0000000000..e4c42e6599 --- /dev/null +++ b/boards/radiolink/PIX6/src/timer_config.cpp @@ -0,0 +1,54 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer1, DMA{DMA::Index2, DMA::Stream5, DMA::Channel6}), + initIOTimer(Timer::Timer2, DMA{DMA::Index1, DMA::Stream7, DMA::Channel3}), + initIOTimer(Timer::Timer3, DMA{DMA::Index1, DMA::Stream2, DMA::Channel5}), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortA, GPIO::Pin10}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), + initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel1}, {GPIO::PortA, GPIO::Pin15}), + initIOTimerChannel(io_timers, {Timer::Timer2, Timer::Channel4}, {GPIO::PortA, GPIO::Pin3}), + initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel2}, {GPIO::PortA, GPIO::Pin7}), + initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel1}, {GPIO::PortC, GPIO::Pin6}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/radiolink/PIX6/src/usb.c b/boards/radiolink/PIX6/src/usb.c new file mode 100644 index 0000000000..4d2949c789 --- /dev/null +++ b/boards/radiolink/PIX6/src/usb.c @@ -0,0 +1,110 @@ +/**************************************************************************** + * + * Copyright (C) 2016 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file px4fmu_usb.c + * + * Board-specific USB functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include "board_config.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the PX4FMU board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32F7_OTGFS + //stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} + +__EXPORT int board_read_VBUS_state(void) +{ + return 0; +} diff --git a/docs/assets/flight_controller/radiolink_pix6/left_view.png b/docs/assets/flight_controller/radiolink_pix6/left_view.png new file mode 100644 index 0000000000000000000000000000000000000000..9fc02eb309152e9a93835bd010579b3254b1ef4d GIT binary patch literal 53795 zcmbT6V|N@3!)_;b8{4*Rb7EVQiP6~39h)<;-Plf(#%PSDvDv6`-t~Mqf8bne?H{n$ z{(8k~s3~Be5~BhD01PEXSuFqn4gvrGej>vG007s{)>;4n0B`9KSwuucR8&+-N=iaPLRMB*TwGjIQc_GzOh!gVNl8gwUS3*S zT1ZGxPEJlxP(W8#S3yBROG`^pQBhA%PgqDuKtNDkT|-b%NKH*mN=k}>fx*Sa#m2@) zM@L6lS(%BE(a6Zi)z#I?%F58t(AwG>3bIXF0IYirxu+S=ROYiOvuySuBZstSwzPXq)485kHC8ylOO zn|peCdU<&Pfj~PuJ2NvgK_NkZe}4f%0d{tF6B83b0YNu6H$fpG4Gm3iZ*L(%Ax1`~ zKY#w%+S-2m_Dxt=go%ksKv2-v*VoU_kCT&AL`3xH=!l=6-@w2?NKjBrOk7J#>*VBQ zb#--ZZB1H6nw6E6g@r{>K)}w^KI%;8I9vmF3uA#22tpfxC zr>3ShHa1*cT{ky3x3;$C=jZkG^d=@IMn*<9!SV_{;_(bB%Wyu7`=-QC@N|Nh<2 z->FLSQ(c!=U{)0du>FMcladFAX$u!i|1qB6JSy_aHgxA;Cxw(0a40P4i z)fE*LrKP3C#l;e${EUpuI$9c9>I(BsWcL67B|u45O2>EOB3C5&Oc8(VSjI*90$D`< z1CS*L4~xc1jhuplP9`n6Cr=5#-Y&~gB61Q9t<8@Hk5pa%2F=xySDXgeMl7RNe+1v! zSsbl2d>rT1yqq%pf3NaWIM+va6O zPv1(Y?sdsokz5eW*?jEs$w;E03+p}|QgLlq(3Xg6c~xwDz-zC$#Tx-Ij_P&L6rdes@T76*xRCkalrkAPnqff8anZIoY%adAc z=i}z)29_kx{ObDJ{Oa%9;Ya)m4!Qi?+?;Pltp2l{mtd3e*Hg> zzP=%L|DaKsQ;SozQ+&Q-o>=x4q6?l27!5ZvEpy5DuoZ{4VQW+oRFUXY&#(C-F6v{! zu3q@%0b3C_;)D4;INciC(j2==Tlw!qpUaZsl4924C`;x4#)CRU1~FWB61Fn0T6UH+ zgY@9M&)TxqJT%9=;6xrxCb)?bi?)^9&-w06H@%u>JLJp`guKl*MZ?utCxay7imp+E zPWz#2K2bHV4%)|=x-Xe^+vK~(YA#f6Ey~aFA$`HhTj_E zycHu=DkV6miq5V^0-ypXb^js`t4_X=eMNTtwX5KWyCM1#sN`oD`h~O~GvkM;TB_v1 z@r^;ozSMQ%Q$xE@P=+w7ARg_TmS7x~$+JR22KG|o2(_>D@Ejh^zo)`B_V%gA7RN*V zDvk$)$K&`Rwx@&59-9PLI(nE<{mXba(gXq2w3C#Bq>Ffuds)>(4Okl)T3>3)>fdgY zj~$ERh}qx2m3I#}8PjVG+p|EyAy%xr08-5<#4bF(^&H|BD{NySGG7TRMX7Um3kyd1 zkxBg08`yPA5uDZ%Hk>S$+Y&${Eo~dMcnM{5L5JDDy9J&&Yl++C%#+#Y#It}Ct3QdZ zONCf&W`K%~?`4|XkR!aa>ImnK#najCfvlodv1ZcmG46GAO^U7)#<8p5(K zv5JQ&0m6VETfvlm7iNEBq^$mt$~P&_&>VE~r*TCk{G`@Ap!(({beI-f_LeP0n|;v3 zCwz#Ef#$Kt2PMQd46WZCN>a$ZNyQNZB!4|YfVql9WFAiUKiO0trYSVXp@j2N=&f#n z$vsVi7x$BPOQ`FR{>y+hRuh$N$Hs%Q^XUq5U$2b=bun!MF&a!y95g#AoqqWjZsztb)Ulm@Fu$?3uxB|AmtMGx5#Pt$QP zOUYnOTNvj%_Ccnp41Qh#rGV0ZKkeeaIQjNtqz*Trh*-j)`hBfO3S=0WOqAo)B(+Q6 zn|>j!aqWd~q)_}ifAFG_J4A|9;CQlHfjkZ8UU!H(D0;GxbW_#D8%wL}4GyQ}wjW;E zHN=lqI#9OwtuExA`Ib6Ws53`ewM&3DF$!5DB}kK0epG~UoF>eg6z;A{ZxquSgc@j` zLE)Cev3@UP)@x48(d9(u{i@U?o7%&Z2&3b;FEG&_VCQSsWv1=L%jm ziq=C_DkWPiemYRD5e7>R-;TQk6@}Ju)cLEKmNFKf4cD~(9Ht?ln4(jfC3D4I*J*{i zWz?8pO%)>GyT!=-m2Vw2QD!qSOoZK!E-p?X5fk{(Q(@G(X)|_sE2$piy7%}jhaNRj zu5KHZtYigqSStNs5Zp6%)>r>tZ=T6bdV|D^6#Z{igz55kfxh<$`LbeJ=RxBL?H94L z;aMHqWKndxJzXBD-QGbXR6P<@xmZ12JcUw48ield$)7pD=R2i~gEXTmM`&OOHQDgU zxQ0Rkyap#V{zHyrvo5=15dH!+p@W zON7Koz%;_MzmAt5>u$CYtgbaE?GKOX87+NvZSX;z?BQYM^3Si1tDPx>VsIX&c-7pF zNihW-5Z8(!$KtQEEp|4_Q;H;Zn&>Vo-p-o}>6tQ=rV?KppBphB#?h-BKWZFaJ1|Iq^XFe0@3;J3}zp zb-vHUbh+3;W~5DrM3I=y)~AdJAV5Rv&MQMANu{qvCplW||3wvRAQWYZhA>WEoA>ZU zhXMT4V=03;JY15hjF167nF20qm}0j3w6b-#YzTK*T?IOb#?+Ub@u0F7yzqyrk?emS(y>-@_+%076 z13>z_Rd-`@_C+!Tdi%b9;v%-O=__TSGPFr+iiq`KZv0VvQr$svYA~Iqr zMeaYordChSIBVa{<;cM_6=Dl8eH(*!xTVJl2XN-Z{Iu0K&MwHE7wt}FtW|iQi@b}L z5QW@c6FIWhwj~}fORxTEkgo)6+G4UDHz4sChgMvfFn4^37EScxYcpM-P4oX_(&0j% zXtYoE=mbDFYRZWC=2$9P4W!Sn_7mjp)VyIOEeMThaRIrI5V+8a>T)W_Hk-5y)h=d) z51`JbRTAPF_uO)DlQS11`^Ob2)o_vUIK{xoCEB_CaTtb)n10lrMW1KfSNfp6U9b3D30peaSAtImu|%wouPSo*sbiwD$`D6 zX-_LIV$$e8_S7*6t=a6N!Idkfni^eo4};oCWercpCHbvDoy>S zyqk*pVp~Et974kb^QXI&2Na)gKiZya=e4tveynenJbD7ZNPIqCn}^7}OTXMD7fNjh ze?E$wZN7@sF9iljkp3}q{o3IZ{p{>2m>XVv<)iI3i9l$>;KE9R8S^LMmilH>DxQ?+ ziJPpm)vB$?keG{?yv(SJYtqIU2L|`sG+y zI2oQSpi)^JP(rutn`Rz9yzTvxnzUp&aq6j~PVSsZQCt=vGtu?4wjX0@`Lof(TSB$M zp0ILsJ_WMC^q!+O(2TBBT&=Nz2*usda$;D+-x#7Z%q2`?>e)~QiUO1g6TM{&zRFsy z39SuPfl!3u624CY<@HzTufXfmvGo6KC0wOwYDSFLq*8h`{~No*_xXTT>MVE-`qObg z{S?q}-cMlzXX#&5c=7%zvGGpQ5Y4dn8UJ~_{qOVdxw-f@wTJe}(DCs<(crh!i1&EQ zt*57c9=ca$$=Ak{Q`O7Owg%h*ro&{4w~~7}|EIEhnHQ5=rHSup+aC`4O7=`kV-#6g zPOkx{?aA9rK?4Wx&J;m9CMLa?TRxN9Y$4YIhle3-Ec)4GE2Mg7Uu$*z^VKSs4O=&q z>bJ;aN$WIn4r#zGZT{bf&J5gGN79-qth24Xyu6BKbs0NB9!T<=CeeGb3FTyyZY&cFa0th5frdD$I$sH6-`Xy6zBg&rgvA!R$?1f*XBGpOP(3dN6tr0m0lF)tFmd&q8D_R07SbS@Jm zv;(X~7{gVx=mM(}c7}&3WSMO;Gn-@3y?xVCnL*s6U!tU&UW-hqvZs7Sx_jU@KeEkD&6Z*Ax1|+fH=&YW zcDAk6I4k9|2DaMT-1zZy=}n-Z+q1(LgP_D!!~IJLs*thFYj#V7+} z-bfIIB?!PLYnz_!Np1hoKsPNr8sGd?@f9Y`%y`oG_O}~eQ$?P^dQeL=6 zA(>bj6$$Ey2A9^ek-Nf`Z)h=vOkS(ME*81yC@3g!oUF7wjIyj|+kQ#@>^y|zN~-sp zhdfzyb(WzgXw~Z|S19?C&r?{CzrKbkfHli4)8VsqPIX3Tu$a2aXNP&!!u4m347}qT zRWc5;Kw0B-_>}AHqL{c+lq_LCQKR-AzX?hE8M6<75xHlM!e2Fu&l4M;!~Ui26Cvb4 zx_~my&M+zp&P!4(agrsW6KZ?6$N-3}Ih;!TD6*O>jQZdL%3NtI_99`h^@OIN2X%$O*sU!i^v8KM_$`C?V9h`|agR%Bc>;7PSXYXxHOdi5T9# zje~NdKi$?kf2Ku_G6qN=V|RVd0J|uN7*2X!K@mGQ$3nAPX|W9Du6Dc;R5-CCH({_fwvkvs*Dq;`?7RP7@ks;I76}=K!WKTUTnzKm7Fq`z%c_25hC;}1f*LFI$mmJdDmCl4gmW)`narGuf2C zhKQXD57xd_Oh{ub@~bPTx?eGQGe%_<@zQCC#}pKp!`) zsJe}K6YnC;65S)rX%m;=VB|OKdD4O$!pVqn9(6NAFIb52=fX}slE-E6uf^?5nyfSK zLnglDpnF*5a>5t8&Z!HeF;bn~dxeN^?Q=zG{wmc&OAs)F?YCRF)GVO(RFrT3F4Vh+ zQ~5{>-3LB%flz^JvpB^vMJy(X$rZ7sj4NpnyV!|5^*_NB>sVFN<#|PU2d-aSWN9|+ zvK(^7?8WA3meL+fz1Z5U(uN_+0bPijDzl9jnQF&Nxc-L%8eX~=**R8JBlOs~)(F`< z*=#X%$enqQs@7Q#MYhexu$cutKEIfpow6Idhr`(a?p7f^5KA#$22O^g`+?z$jRw{fO^WpyvQd+1Kitm2jq@6DQsNv-!TdGsZ%a; zA}frT1`oh36bl!WjjXDrF5EOQ@=aYA`B=>BAS-+(D+_aB9p~-E z5vFpp;{ePo=0b98V1Yf4{(GyREI*CCs99yQ!E!Z}g*<5t$%PYQEjTlTnOkC?RJbw8 zE4#L6-#YQdQ)MTW$4Mb;E3FBhGj-B(vPlN#ARDJ6Wx6ewLEWW%UA0I*gr&PsRGIe{ z289oz+y{k}?bey8@2`IZU+`k7LTC0YQKAfcJrTKJxMQ91OE1a}NjEE2N)BmodZGeb zQlUWmCmg1{xL!+WCvM!nA~;IA-}pSJj3gV(t25aQZH9&Dte z;~_soKG9d+{0U$%Ky4Cy)~tE47Y>k=SuB)F^bA%~r58U%XU6#l^^8Mtu9)yti)MiQ zwsY`H->Wkf9(3v;*Z?-qD0Ai19|+d2X~KMa47o5h2QHoB0BO{&*_vJ<$OZ{Z`JW$ z!sQaGj?`Bh<&H8W&UpVT|5xBKu)T97^ST4~HE;kDb~6p}xE4D8!;!M9z?EC+3`Q)T z_-M{fqU`~mbLRi(wDg7>>_U5|J2QAtftIH%FD~`gSFf93*ED0=ltaa|xrXSq9X71+ zTP9x84sP67-DLjXG=5_gCqrSTR#36Nzb08;2MEWdNJKV&PqjAJBj_TDPN(qD>)HZl#?n z#QPqk`jj3bYW{I;K75>;9N1s82mr4=(>5x9@v<+Hlw8l0`&>|?&A{|537wg={7#ux z3KQ`=&qV9cMx%1kCXpj-s)YJD8$_V__Dv~VZtb@c3r=;|prK#C*7NZ{wlF5W79vkz zYtiMU*Eg7Mx&_PTDOQd`-FJq5OK$?FkaSSK;a;pnMlclkPl_yFx_#{%-PzinrIZ!7 zy?CrrGoRY4lvM4R`o6)X0b5%kLN$ot5X(fZhFS!+p-f$Qy}zGt!RmW;4fi3E`vv{8 zT`1wEg;kw$Q$1L@-3V`!JYJ4PH$D+N{nw9t%}KHEU1j*2G!5FQQ!14UZ1fvI+7ca@ zvydh(&lmlvag*WW35uZpli-zx6(htS|EXC{;lZj_TmC?t#@vPlGJ!mbJ{u#;0cFsO z!{1YdXSU)%oT)cX6OD{Mya@{00MYlc5sJ6_W`yzECphzGgdFLdIAAw@D>p(G(IA)u zp~%dw;tr_yYb;@rFLrFzka~&`HN7&*aA3fLG*NBVb z=seN3&xIOK8ZpClNK+}`AZ(N?=NL7(Cb?#UEBuru5Ej{qUr`E!MD@Da?ms#m3y&=io*Ln*&lFGS$sw{?c zV;Ks*chisxZv0kui%@8LNhIB6qXu|FwH90qP>Q!#13M#ar5Vwp z=CdT0!u>kC$0wRI>tuX|pbE=|%x0tMf@Bm{YszVFm1lJS7~pYWB*WLz0b0%;7_}&R zqPrEkbME7+nLl{5PU!jnOU}=2{w)4^a9I@JP|0FcI?WEdhz5w-v4-BJYuNKgpBBc9 zLBgk}o{eUxZ3q2VVExQA9=!~`YjMDfd+K5F1W#=fIv_QwtV+Q0#n&S!9!;gvK;auVj8+q?i z0`3%gZ8t+WoAwQC#N~_-e%Hsr>N24LGq3fBbHgeBVuKet4E*O`xCP;NZ_j!e&C__2 zIl3h2!^zYRTdS)nl-J9cnW}lX-V9)3_;q_Czo$nOqGo zAKkad#IID2{tv8MX&NUQYuJ8`D$?VGf>g-MPPBWvEk&wTlFwZNIv>Bro!Ea!e91nT zc2YUk1l$tOgu^0&-&yS}tzV4KENt3Apw5eA2*l{uR+3ErzhA;rj4_I14&a2^Sxf`uWXQ6XYMMgwpWcq(jY{n^J{aVX<$Ne`nst`lBaOv z1-xe79wn(%Sv_e8j}*<~A-W3yD#-vISYV2v{)gN3luQ8faj6i3tT-T^agIDp0gQl9 zdcSy2LyT$n-jQz=)e;F!*<%7HEiCmPZoQFY73Jtoz3>@b$LKhcajGmJ-47-D_;aF( z+U=Z`kf)`=aUI=u?*t*kVwF>F2CB&{7jmu#g+q#J(5g-~tj@A+IxTzB>JeBDoRr38 zpR1$HR-3V|JO|P!U(XSu|2`-Bn~2Z(k@E+F*p}j67*hZ{5x28JW`^JS^OP$^#fy2u zf9!Qh?A8`a1z$h+1KJ*JA&@a7+zdD=fmHj2i#WWjEL{t7YTE+Q)BjWzA$jBXvl#rj z!q10^Ah7ZHV0p-a%_u7v$OzN4J`xyv$Biavaw=g=U{|f})(!${!fzBL9X)7ev`sX) z!+PKkvzp)(t5)2S8w#^`d)UHfpLS+PSEEtZ~TFA$>e< zK;o)T9V2g3V^v0pCR=18+08-}>+TDG265fgKBOu5@r#udm=~Zb(IDsFn)U2q$RY4vH>i zN5&i9|N8A;e+R#FjHjXJ06_($5FuqE}aM_IunSS1d=tl#Yc_>8T-o&eRfkaVGfk*J(p+?77XT3oQ<0{lHC0D_!CN zxs`;M&DNsSoPGR@vz~@f&0mV?8~|h~_(->~jeW5f2*ZfTp+u*1)sYF?!<-V@a;!rN1bMmE0dRnAG`fAemvQAOq#f950 z^B%9Capy8N>XWwJ7vN(=v6T~7zE}NGT#V}-o4nn{4Z1#u)fIoM{4{pAp^x(W=IToG zPdmA(Jw7%Av4@#GT}^c-tmSQ6NPpDD-rBBrD&AQT za)w~2d8)Q5>9#0mDvYmGESQ7xwZu{vP$^y&BlocFMMT)_q)dW7_dQ z)kWLXIcpHUqvT^AQ)#}Trd}Ph212S~LQWV)$g(yZb6u0Dh|vu36$e0&0AD^+P=$+C zY%jwQ$97c%a=AYYo6*XtMmTdPjffGDpKrKc1Fi_9hOW8)Qojrs0s1dxw|hk_*pn8zcTmOKe6WJ6TjxwQp@= zfMIEVpGT?`xJguBvG(0&vzP}5M+tQNg(iF*z~v2o6L-Zp=BuU%`3oc7{{&$9+!`J0 z6+zO^JV!|J`5FE5b*wAW>m=#QrjKSDezBVBS$-aGvX`^A&}V(?(d?=M(@(48QrY0$ z^dn38FPhDUX>q}xDZ+a^hdPCiO3v7r`9Q9r>&kHYpL2)o$df$}(~#h+kNMGmX3yf# z*Gtz7_O`4U&%HVuTek5p!zRUsa4mehjx~a{`;fekxV1c`Bsp-ts3TteooXHQp|NXO zx3$4h65(Jb|M$thz@Jt_9J1V>WlDdRs8w24?Ikfo{|qt1O#x7Zeb(KMgn9UUtl{en z|7^CKTEil%$gAZ&aX79LlZ^Vw$sE_NmOfbb1*0QQ4;K+?I5b#~wSmYH;qWm<8ov}_ zu#ChB#}-+`0j9Xe)&6gu-@lyjw=P&~Lp5N!6I{T(S6W-RxRNX$ z{D|CKTa>2hFe@!^P-SR+j01@#q7_J)sw!5c#a!AU)Cs4>{9Jdcp9qfrH{WRqS=!9` zNKU|5w>!*bE;U3BZJZCuSzY^;KBB|(N@bm!aju~CR+JpBXXw`j$LE%gxLIc~ zdCK$gbzyhV)sn4wZ_D*XDMNChsQ+}UQs6T~{{!=O)7e)i=HR5nk&wG|kNez!SAvd^ zx6;jyO#Cpu{!tQ_c3)KQAB8(Ed=jq*9TLZzNFnMjHvx~VSBx#L+x^LFLZ78`u*`u9 z^^)tL8&~tH9%dj$CQKCkXw?I|F}wH^aU>Er!iTztssASX_;%gH>WMNdn+zG-yvij( zxq2n~FVRuZjl$o!AWF3a!QR&gG@rRYj@0GmK`)y_8rzMDewiGB2mYZMBAoZB}R0KPpA0Xw-f<|FN{Voi~yNLo--q5oY zvFv^j(a8T1b3aT@Sd@S)4aSAue$2##B&ebVSuo*Ws=T-}o5uWL?SEZ5c(hpg#|x zeE*UTi+{p*&d#OO!hDEibdUXXS* zzdo-t$w@PXksQIBE}`+BG=k~EbzS{-U%>IkQMdlKE5t#*+R|ofQXPqSLqM%#wf(Z; z{mTc5Ir-**pD9B)^y(^};Uq4mb~|yPMW&SX#^&v)(4pe->tE&9uNOpx;z73=-)#)Y z-yi-83^*F45%XaYrB`^xEKArZ=e#(jDh;x-kLj5O$D{#&0fLHJ%oXsDP$kRTE4xza z<>w`;u{2-ze&@xa-ZN+L)FaG8`TQd2cc$5tb6D_WSXL|YevPMDuktH~=~b%UUS8v~ zwGFT5mLQ~=-~_2E@pm|G%c5g|+>GqBGbDwb78bAtJ$?}rU}1i>MSPS^$8t*U5D`G$+dHrB7RGPR`xG_6;1t?aTI2FUp+RcnjSI2~Pkz2p~ zl!&o~2wvlOon^$@fiGKIX>%hw5M9@2W5E#YG3uES-wOGb0qFw6HNmgrCeIDS{jq!9 zSKsT6kD3kl3I9{!{yFz$;O7r7>+k24*gyHc7k;xZ)+R4V5A3bm@G`F~wYg`k`svs4 z0ua?i`J$xMeRF?9Zn5ay``8ZByAiYbNC|^v!J-* z1dcO2-QH#uKyy;g6Z>QJgO|^}=gZ6MK#C|W@cf7-P`QE$YsioZJ$*&|)E)kETXwBf z_DN`tFpD#W-GBS*%1S&eoW+KJn=b8E45oTT(Nvh`q)|q?y}un%$FN85g(?iEu-}aDX1xUg)xTo$bN>*ndGOJ!M^^NeAG+UN zu=?;B@BOuKf6)p&SB|QXZP}1mZ_*U)LPYf4kd-llZ#@Ig>ufS27ITMlrD_EPF^)tbi!CgoUE%?nseWy} z9gUXcDeE7)pEt7hy*)hrHVYu@pWm$1vhhF+82@&k#ff*8vbYcpM)(Cmg3>W`n&DPVt;h{1n|ELbZyb<;|?6BXqN0Okd*gdIoXK*9ntQtFo z{R7ioV1E8b;OjB6T}P>NbHMS2q>BYoB}&$egTs8<-4PTT7oTi1FS2WrE{4IlI4zXe zY94k{bm>4sy-^Ew=6BF<@eZm#fbN-2&_G|4aXk7fA2afq7p73cE_~^uTF?FcWnJB< zG)O$-y&oGD?`1{MJ}H)u@_Pvl5`WJJABjnW*$yEj$1o6ze(7=6WFPZ}P3&EB$MlTt zYl8(wSNaS|7=moT8LZXM2f}=&WJx$q%Tls1HcKsb>vSvy*Sml7_Fs_?qu0}ilE3LY#_OOoo9&2N>pgT?myqJMIO3mphwOx$SvXc7x;<w@K{+)(v zv`XgYLQ#ZFkY49M5n*9~2E*2F=AQkHS_da2&RcN@y;nJmQdgUl!Q zV&}YRNhy`JI)l990^3~ZT-8RG@YI6g@=0v9lpVt6H1;=_VL}7UU(KEG8xRbK{0?UI zwSrvOMIzN5cjF+7xoNASOOE3F>MnZJ)(pq~24~eJTXW}vOh23_KJ)%MZyF6)snuCH z25&_kH&U$V@BHZMG}}&xKaXUdrrLw!s5MFrj`*l@Yyv+xqg5XO8>|(G8zPzrmpR`2 z_2F5zY8F{YXj8BM)}3TCFQdz)MSP(wQbze0zKdC*F+A5?wn+p(k6|E==BFg&Y_7g7 zwO4J(T(sXn{Qpt%%L8T04$H6&8_Or2h)NB3afh%~u>~>IusKaDB&};^$fY$FLJY!o9Ecf)-TDunVro0!xfm|NYJ0r8I__ zAi&wDeXg?(k)AUgn+IF18{lIiNE1PK-GmeMC7n`vxM9y|Y5U0lJghh9cc#ej*)V?O z@Xqo_gHSBWbPeUsJe)tRByK`w6BRi}O<0&UlE>v<;q6L)i)(6R+Ia(b=Mae5X1-GX zf^*iJoR57n(rd2Ex8+?fuKoGNe&xVVvIS%QOq9U;+>WXLd_y>Fbv*8HN~Tx}wo-26kMdvEN+@g5vL6mtuzZyF=TY7dr$Ol6 zX>WE=J{x!a1%S@z%IUGHR;t5hW@xd}Ui-Z+DPlcTuc9(++FZLpNMgMAnVPD_*HPVe zDy!-ZienmHOZwVV$VbYt@T1|8DFsgv8(TYz04slCJ(9DAr7X+sAK^71Y3RF!swHqh z_!REHdlU-0$29akbk1{<6*)|s=ufA1;H4|)N zX$%#j!VEYz)R@evID&+Iy@wUSXpbGM+(yP?XPQ8_ygGn7+|RC|rYLTdVSV^h=(wwj)*DN4L6qMyR3kQJ{j>nfEB z>fZ1%Axbgi+~{amlW^*pq*+pJuV0S=YHu*GB59rX+JY{f7Dja`!;cK~E2%w9v)k1L zH#26B-g^TVv%+D0zT*fr4V{{F`|VSUZlFNw75vd`k6|G3W)~FXZ24!WbpdP+>*GqC zFmz;U>=<;>F03|b8Ij#gN-r@#(-aXfe7Rxl=uZN%vFMLe#DjBSaM46Ngr!VQs496~ z&IamCRe?J8_!#|TbEQu>kw~yv;)}>!musp^@Srjxx+j^Axk4o+wkk@!R)0eM(7)~3TaP&)+81j?Srz-?J=DPj`=w30UNEH9} z75rBaaMgv{1S^h>df$Q|WvUy=@lyBAULe;x7< z8O%|OCL2Syl2yu1S^d9fd4VH_MoN7cl}_E;y|;wd5uG0?Y~l0FgGT)yg=*I^hzkXN zd)4amY@n!g_zaiQ7$9$+von}ba_<&KZCWr`D#6tgh22!(@(28IwijPGz*=d6{(2Zh zn9X`r^RAUv`N~!-)Et?HU+1^8Pxo^FvQM*q+wc(>aQj#m-%2ZNDI|DQg2C!_ zFqQq*{jogm$sO6eZd7wR;- zMQzJ`xx|jK`hSSe`nMrDq1{xoF3j;K?%JwBOe!$Slk3i#O>4kplX(8=$@7&iUXpp&knIzI|Xjt-ZKRWcQ4DHm_HE2qnrHtf2WX_nSDp`Xv4?X;mJ~j-ezX zUh_`h$5<-72t^2^UGW09jI00SMeCU)!bQrn1`1L*jjp}s|qQr7-aikTgy8CEKdI(UlW`gq8UK=}1%zhWRPw@r?YeO4hW z2LaPNuHh1P31(Q?rU^(Ye%SlF{j3{P-l=$VIDWjvc2;Fl4%$gyxZZg4=oPxD1M6Hk zB0q&sGqjIk^dd-l(K*jE`zxQbs&)fI#%NMiz{>MRhra%2xwQ4hFFUQ=sQsO;vz8yG zeYw%m)zc+aTP3+ro7u;{o=0hTYI`kISZ;L+zbDK;-eg6LHsk~Tc;F&2C^81zWr6Kn z-RcsA{$CXWRJ|~qcg(wXb5NDvUg#;Dx!x110_SfVll|YzYga&ck+-uzlmEj0?@M+( z#UI_`%u&g`0Ku^_bIRXZ9eni#QHsXIPN?Ed^?uSSM)a_!k0>79D=ULgqhF}P2oTp0 z{Mp`C&K5_q6d?nqy!GaN*3=1M&Pd$c|Lo4>M#w0;hw)RD)ewD|K+QFqkr`T1#6ect zgf5f+bZ=lxQK8MZ{2(rt10ob}5se&q!stCFE+m`yQv%etl37z78PwsNv=rA8rxAG^ zx+VtKL-T)6XeC7;$YCqI0V|TNT6u9svbZ+0v5k_0Wa%ABM9ocU!wWfTiX(U1FL=Rt zVPPyFes=L^75>ta25)A2*jKNkF!AFv68;qtxO$g-TA7)4mI~N5I+>X)6}Gr(TIcpY zu`Yq7i8}VPmVeg_W6vgHo6ffv7HLQso%g@F32BQ^#Xwr7Qnb`_x6=^RrDofuqUh6! zn??`Vhd=Ip6^o%J7Z)|Ct(alnWbJzC3elV*VbW8+5eLn&SDLxIfR~E`TM)3X@Mbsq z>rZk{-0=ketM9SoB-}wO3I0fBC1iv|gU&c{t!K`kYcPuo7-{?FO0=zfx$Ko&U3Ozz zW^0j%r0A;Yf`$wIT+y$wh5{0hQNSVhjQ^^=D8N38>h9R5!l3`~p*vUt+9{hUxu`Wwh~F7k+mh7HdCJxAtAv$5hkkDr>ItjYFn6#Qu%O?l zQ;7h7A9{CT0=F&q+KMm)5j!_3xkBxf9P#_4vXON(`}$hi>L)}#x4IhC^IrpsyXu1$ zD|@FH)&k8gXT!ugcCfNqe&o7p!k%sI0sTEsoTY?%x+jb2$&eI0NzhXzbL`Hz2^AMt zsv4SCd%wwuwYt=uI{EwOU!Q)xI!X!X^qo@gcdJw_%L{7O5k}w-{hb=};K<6W9p>*D zzLzzOn|+4#lBVQ8`{%>TN^}B|nE5an-SDwa+T#UdQNao35ZZsTP*Kymy~);i&Jn`E z9Y9O~=5K)GHg*i1CbRuYe(6|p^`lxAaUbXFbTus=YRG>&o>t1dMUso5(hl6p{#+Ux zLj%#mEH|mmZOQ;hDq^ekxz3HgXMrX?YWYeziIgx#TtrT$Ak;o{7+-P)aw3;D;#8fa>4tZl5Vt!*6N zk(qgWq*G(ut+FXtjM_SsrRIOB;f#$^_TgP?JCqx6D&Xd4YBVP`2QVh7p=o(rPAgo#(djLwHe z0<9%j$9ceIG@1Pb+b!4`;9PoEV=_l;RRplh62(LHT*aiZ+N7jVYu>X7bG4O_;E;&# zms|c7-q?1vcL_IAWZ~@WU!Lp)mM|saXcU;XjIE#2`I-Mb__>-!)7uwjmHG;xKjXk? zn(KSCMr?LOYs(vJ4!2JBhX>z|`&L$7wHC0m^Py#x#?W?Yv6Juj>)dOPGWA}^UFZ~+JJ64_&hRdywszOlLT_Nn+DF){ZG8I0 zhYt+v?YvIm8-KfonWorvc{eLWLqoWEFdwVNyhYcz9&uqW4TPK>WG9<2r?7Z6)a8ubXvjn-^7yk`Sy zOD-wY8!oT3X({{p=WbI|V=lib<&Gq2U65xxlWnk8RcDns=>)=I6I%4jx52=ghbsEK zQ^e#&MW#S<#va6GP2~r*-?jI4xwx(*5~xe_4Q^@ntcpOJU6LLLCwmXW*nU{OKs4!D zWEVEVZ103Nz5PHYy+CA5q#W$y!lvzN(hY=_um@_>8`E5%-6b>7CnL75`2@5%GO%=D zX#l7C^!N}bn?1S~_KN2ebTdqSdb)ZtX|4keI^g4luAg87WyoSk)Z@Tfyqz0639;^omw1%Ngh-TR05K7-0CyZB3oix* zh>*J>Nr9*mB9oA67E`fcSqV~Uh$^LQ0x65MN>`EQFPIHTtinj$AQq^zo9~?O`(2yS zEMpUg8d_&_dcMaw=PPPKiy>|*^rz#XDBy|9)8irW8kB-mDP}b+O(iPYD&7-hR;7c@ zm$A?q@~3KdMW~HYa&1&s37Q>q7%&d zq^ULgz=ADXbq18JD`zP-xZTcb_92deJ#2s2e%F$r2~T(6mc1sSnPa#mUpnf}Xu1?V zCbmOnu!l!9fB$*k9GpUPicKL*<4k~Ziq$Q^*>E$ryQk-OJv}`xt?SW=9sy$x{Uw;AOJ~3 zK~&z)n_yDY3Myae{h``LmA?&>S2)g^OJ|vr9(4I556#6p46w% zo=)aK*r1I3Vv4=1TF}CKg4L!zc-fZcPVU@bO^c%n42RZGy>F1+jsz0=ssHi*!*6fi zU~4kju?5J?Y@3=}%pDvQ&ditqRe2_=R3cWgzSfPZOs}d=od|+hC#54G7N4-4MCJT+ z97mNHrW0X3DM6>pm7)MK6hsh z;2fChKY~1><;99t|C2G0pA@y8qfKfJe77~hj24PL@a6<2LL384*mQP*#Vn9Hk*qWg zoGlqJ<`+ttx;tqx&LkuuZg;%-M6D;;)~0NdZ)qWVCTgES9#AL51~Zlh-E3P;m)4a- z_DHVoz-{;HQf{?(i8nO6ldLW`oi)9I3%G=wJu@n(gkx`t_C0y9iY0TBG0}Sxo8NU5 zdhG19&SzQ8J~AB;EOxADk6J+s*NL9Eg&K%`rcGzh+4-U4ZVZ%|HQ@*YIH98*7+Awm zumLVls5w}Ej&9Rg!s?PPHM9$6O^9gm5P+_%@EknDE|I8bw3+zAUO!F}NOTT#pV3{I z1D&>fAZ|75GV_dtG5 zF9^M=Bl{W}>*hc{{U+F&=)36+5~tL+9MA%VUPb^qQJc_O+nJ`I))li(4Ma$0TGpXB zFu`71Qp*CIx;jx65c7btdODM|`J`6R!V5NobOQ#^b~bk!INMDM)RlzKHXCDhsnj5+ zVeO^_N@!E}nH_4>+@oiwTSjT5#V@5yt!2rXQ>4pn_GoO}vEy%_7kV`0@`M?}c2lbN zsE}MZ*?bG$9PH36jRpZRL)-6D0YMb<#UCV<*$2-zio_apm zlG*}K{UOpSR-qZ-+Jp)Ke~jdcJxH}!;YI^nl{`@-jb&7geKm37z47TVKb8-o6!9xh z`93XtJEohMfO>>{YC2$p36W9N&3`y>f^HY@;p1aS9aQt+$DCDp2;13c{;B=u)ZE;tqf8~tNge;ltH5$T0j4&b4U0dY;CPnA*`vp&Pb8ib;!`Ezudug>gB zG_-oM56o#7s2w&}AUjw&yuwRFM}AUpTG}O6CopV2cKZ`^Y`P<1y4gey33$^If*?E? z{1$d<+*Ww%PAfo1dqa=Hv!vDIeJ&^3&h~vR$lQGMaVU3dvUv-Td5hKTuIrDFceGh8 z7)HUy22GQoy%6JAkW^Ta>NK=b3ExBJYpqi$M__8b{-ypgGcgOAy7jQ=!bZTnR8HCSc`rlv@L>p1lC8 zlE8E7S>HsneRVThY)ksco9Sz;W{E^PH`7X*u!3PY3uXH?!g7LE6E>P@41tnHQ=qBE z?7DWCE%byvgHMy%c3W(=wmvhh0g&l7CPtcWo5`AXhD#IV&UQAp&&(KSVsWCO&^$fe ztjkP;r+H3ty^c3~mpYU+_tb)+l`=De$kEX`&7M%ooJ__)TE*62sm~o#7YjX>*TriJ z2<$4jc!TX4K#Ncy(B?mp3UrnU5(3S=?l{=Fw{NjIQPQL%j4Hk3m(R~4vkS>U3QoiV z^}BFrNP(WC*L?NLvVqPRHn}{xbm<_|^mInc@$4zVm0Wf7uBl>@EeO zj8tb=3`)K)G?`EN#bC@&r4VpX%m-uRQ5?#5VO?-)5fdSQtcoQl%_{mDSGhe6ZR;7> z$f=B-Nmzvit&0Bv;Iqo8di(s)+rTt9G)a3oS!`}7R);sRAc5tCbXn8tK{@NC7qHgM zWQHde7944s{9xh#=-NS=>@KOFWv^*A&1X#}IB-e>9nU_{Yw%B;eAaC=v(U7gg}Rd` z`#POQ&yq*1@#N}+f&Ih(a(CrNJmWuWuC ziQ8vq^#akr-}~L}MAJv4o?T`@^k=+u^6H>VZdY|XJ59^(0&8AUQ<#*q9MB$tg!TvC z)I4lLJ%+fy9-@YJ$T?4Rt@#zTdIHZ8^PfQCP95#lkwHs}R%l{-qOInQJ1TO&r-29e z>Qo2veE;!3o0}ho?%tZqZUHh8=z~7<@s-|842IzZMrg|OL18p};d>nFmCg#-R76Xx2KdPW7`p>c=f!Tb>G{rhf_w%a%S<;Ga%M0u*=SO;2SZp! z-CzqgpPg7pXWCQ;G*QzVkTutZE7@hPx2=;l*9DDjCe73JiSQ>kC$yd*;xhZd%wVmx zeP(C&c9z={r_pP+ji$wpSeuz^HUVun7;`nZy2|_0tKGd=X)Y~EO-s1}@4>6lUL zXmKL!#a`%VbqIvLCg!uV?%FM8K-itEnOk$<<;&-s0_{Izp0HiX!CMz}c~DckC~m(* zPZ-jHjzLAc!poXWqCMdX7#kfX|kps3d5N&cZ}%Jh?KM=7cN+{Y12BHSg$RQ)}99-hcdUbMxbo+^sop3y`@DoS8d0xbs|Z212$d@&Z9< z2*nNhJE<0-8i4)FTp*;*5aS<#pzx}Y7m!&VOJTK=Dh1`DpUUTpDd{Iu0?L%H3R*#E z3ZAg>pftwdAZab7GOa+s7er&hG>hDnps@&qR#f*_ic~gVRs}mIQE;Fslp~E!2)qi4 zZ>wtSWI%-GhH8O4+n)IBFMVo&hII}!OzITGW)lCj_L=FlcA6$JQ0**U*IP22{=f{j zZcU~k^Vu`!pl)@!22EKV(AK82nxdE7AevF5CU%;ZJj*1#yV7n_2z1wkK&CcO2`#|c zt73zWj{i-ag~*_jxoJpGo7DM_(j^D7Q`_d{S$oVAk;0md4UO{+jeq#gGW0aC-8nU# z9ZVD3)kcleee%#7L}&Nf9qMzs)1>XhOw@@=PlMa()$G^X@cnBzsUV~|pxSocx?Se_ zoepXLeD98>1SN-wz6NLh`@hUxU1(Ez7H91B zPOts0*7Vw`xuj%Wr&z643o2EawbW|YiK(I31xvIcrZ2XUjtI-_c2N4T%Rcy6GPbZC zgwdB(cLFOYc@Siv$&%24;DhPIBIvBv4R&TIyL-;>{Qo!U&VIb~VNX8pP129}adN(X zzu$S=(;S_uUI)*tWY26lHn5LkCZ~s9FV8c$j-$-hLcFAy7_(xc%o7kdH5?;usm_hZ z7x%=>VaLbbYkQ2iFXXVh4l~dvXqaIntd@m!k8L;_v(}yt& z`7XT&@@aBS+hYeX*A$wyOf-iuPxS^=V$B#NK?ZW%Wc<3@336Mr;+tOhtn_{i1)r_z z)oielst8@LQ&uZpsi1n1h=%7?SFfox$7HstOHIY7Ry<9ngTYCeYtq0`vljCc!R7(p z{`poH3B*wo7`@AiLtO{2R0@}yA=Fhj*;H4ip{LiwGlI6Yb#s&QQos&w>s2Q||8#VY zE-=AV&of5_7eZ5grFFc{B`Q=xAeVVT6Ziz>a7J7Q8fo=z5lMBs< z50C8C3yA=5zXLeXGqqY%*P2k(;~vm8giZ3!YcknXJBbD!pPRvGlh;yTI43|_S+aSC z^4ePrbO-(9jGmte{e-z;uit(D;xF%d9z>^%b?{93H{zIij$-C@jfg`|_(YSE^^-o; zCzY`YPyI!GOIRfV3tZ?J#*&z13OSQvsR#OcCG#k~J#<it%@azJHJy$WggD5@rVB}0KwY+_)dN=^xrRV8S<76U3l4V2aE zd#D>=m{~8{1}dY4PXgF3o!JJF=+a9x^;K36ZM}N6B%-Hv+FiAF^2N!fW>>0R!X?Yj zVqDVFv@4k|lv!F^A(JTw{Xs3R|lc%|02jN%;M71U3eKi0x@%6~tl$+mhYtfUzPut?12PSYCWWO>K{ zM$iEKU1{$b!)rc?gkSwH1|0l|1}8*%Bk*5_BQ#c_Z|l0RB)t&@Mrc%eLG=oSAmUx~ z^Yxl0R@+d*?$s!`dyN}N1sqgUVux`gbzRn-al&nDZY=yyOD0l@L~0?yXUSwTL6%LV zlF1Z3#3hj^B(sS`Qay)bDwU;6fzGp8I%ZR;bT*UB07om^h}4RBI4AaLc4&a!Jz;^} zJB)OdXCo!X*Y3Lv!rR@q<8EIWm;jBQ9VJz+D_WXeZ8TBYDrnM7Em3nz%toHU?|Srj zMC5;ZTqqvwn%W58IiOa8fnzcw{ht( z+Z%7brEK=y`R3^0^g4Lv5`8KzjW)l3sBv^7eVo#VsGknFgQ>&+qxt0{A9sGgU!Qcz zA3#~@%)e1?IBcZr8uRm|@)uNQ@s&*uU+af@!~nF6+*elWOmGtlxQR+Z)l5uGxUkeU zwnk4|Yi_SGE(@p1g|!FEB(^y%mDF^!WK);^yH_UIGuii&i3Rb)Y?57dA(hA`$?@nR zdtkDVqJWzzWYg(TJF9LJ(-dro-0OrY*M*?c8$c_#w6Fg*R`DJQ?Hm zxy3~(0RX|=#o`7tG*ehuY=1XZ!e6ndJUUayb^yr>oZt~qxA(nz`~3^@%m?e_nd4J~ zvs+GIxOujXcbBjqACrc&e z*ch@`7Rqbn(IqFajFRQlb-q>`s!6IKOKO%4dI4BXO*!fZyKPxuMEX9WG^ZBymcgC2bjgYt{t@I;>Rb4W3fXKT zzwN{UwR&3in(*Cowc(cI<-O-;`_&|~ec;gO@`uYSi@9Qg-M^4Zr_!0_+;X0NDmg#- zeOlu5LZ+h|o2k2{B_!LaQF>}>wYIygAk7=)`37Z7y8KDhzV7cAlzjJns$fs<@BX+O zAYI;k^ee7$`%fP3KYXwKYacO%$!wktMxBc$uPq%Y7`sjuYA8`}x z{k9El?|t+^TibgKKt8_nI1h?jcr5jxbtic2O?54G&8_rrRoC|Nuiw3RceBMDoLdji zoR}D#Z8>&oZ+puKO9U{}#9(n(nOq8bT?q+Djj8HLAKIfs;6j^b$c#}I8TQ3FpA1`O z$nu39dfqZ(wiAv!Ha%xMW-xB~=oqq`VbkY{@gOB0bYi9_P8F)-gkn4xWvM*|C|I$8 z8I<4ZNZ~moDt?BN=L3EgussX9mL9K{alTJvhFKv9cSEvL1|Jx`j0vhTl=F_1^hY9S z1C6lyNOg62p~)kZh>L13(Wl4i8v$(x)If`lJgU`H6DW_k9xDF&X)SBcHk82)$`%l* zyd7yc_W%HRrj^bOIs!9}=@HO$fGA}JRt|k{< z%Pp!W^nt#BuFG`c^StZ2=|V1(N#>81Z93U@Kp7+3pB``vP1OT>`jcCKd-Lk|x32wt zE?r1*@J=KaQmd=0^S!I9v!g4^xetrWn^u-a$Fqy=%JHbWq|2@^WupSwo-zO}a$N=j z>HT0=knFzX7LZV=@7&p^McX;a#nxNFv-ij>^So?_r~Aj9nrw288JaVC&j}APFS@J2 zWPB+p>?f=N#E_pG-?;lt+}+b;Z{GeuF|+4^IXJowp1C|RJ~-RD=8`63Q zF$iJuxF#n3+lnWaSH>n@AKcMblDRY>KHDq7cm&FMqCUdFcD9OQx+dg=dvomztb>z7^uLsQOyAYn8y|{CsJm*`S&}CCW*IRyR;wYUXG{MX$6OOqxDC)0~|ACu`Ri+Eku} z!Cvo7+St~{_V(6)mkZObW9^{T7MxY5T`kiwuA3%=&%FuUhF=l4sp%xgPodUF%ehko;& z-#Op;KB$1C!fkEWJ10EW3|!uDJ^Hn$U;Sbl{hdsf;7Bzh{h)i9v~+gpB*~4P433xR z0?`E@JGtY-@J*{{x%%DL`ua?{obmQ`RJuQZ&|xQtI-v>|W_pkVO^X(&XS#RcyMKLm z`ohbeBPaS#Jl5r_iXuY1rdH{7 zRa>+wl^PDwtkmP6FsOl^yb%|YXD544!sP(VC%hHL>(t`mUKyX@adYhES+OC(XfwDV z9zhq>Y!g22&qb#?WnrY!;`JSJme=7a4MDl`qkqK|mYac$y9B0BU*>B3AT2&N$d zo#~p`mo~$MzogH0xR*+h45P|T;KTIC9F8c8g;2cuqApmP{>!w%EmTy;_p{pW2V$EsgJ<``Re0W;gw1|1RW$`2A zvb|)I&}msQi+(0~kJ+L#WGKXgN8~5C1UGt05h{JAVc5|GXwpf6DnX4r)d=~VFqo0* z+oXkoMlwm)RNFelvV=`4fgPTGptyChaRS*8`yM!u*5Xtdx8trauH?HlBUMYhNPIY* z9z4h%UIb4=r4Dfis?wnn{}I_dS*xSEc1SDq>XaCWFgZD--9}KD4K5|-w&Fa?742Om0-8rtXkIMa>8dF(f31Q{R?p7q z_K@_1+K~$;HhOylqwlxx%;mjILB^W7LP6#obWzL#jyVEtA(zb&9O;^Ffx0q9;1&ZB zhAO=P%?hbzg?YJ=n_(VikgnT=OybNA9d&X5(sqF+Z-n&?_r2&Dmh3)|=JZz!-)!b0 zi;LHHZkE>rhaex^v-ckm7q;%YwDZyjrOje~>q8>Vbnej+4!%9YnuC7Xq-H75r(jN% z7q3JI92GXp%hZFcI=DDEJE(Y*)$P2m$yNuw5*Q{so89b1`>OMFjl^Bc^&r**HiMGo zN6!#~;><}1jX5bzp+?9tLkTQnnwFDPtDn;G(N59Iine-(I}7m%|vcn9bv6jxmW5WtOiB`D`|qDex;{*epQEIL%ZZ zz@*~N^)=7Sddf%-Yt%||z-!cW)Rc}bn|84hsOQD8M=SPAf6|U zk!kbEAQ!V|AfshL&{xl(qwVCHmbW%vb$7pFpJ?$1;wSby5I0)U(N^Q*gV?FQqgPN) zX;a$EI;Hxu3P9n^%^N@b2xN}!pNjl#TdLWa2qE+6ndv4f0h8!<##w@A;My`m2?sln z^cD)*c$^bTh*x8_4W~RG6J8R2&Q9EyqVpk&SGvcPm~e2!v>A0cS(;HaeZqYH4Ew?^ zDq?;sWfBX+`M`%ai6l+aaM+qQrL3ZT+@EDngc|1L(3E%xtDBG$KtzN|P2HNy0uD3{<0&C}D6{rms`AOJ~3K~$AV*tR#+6tpc$ z8q};jM^ws5Bh|Iaq)Rq6QPN7v$t|VOQ>1xUCs6BW-lB#k2r9iMs%&+0Ho%-YHwW>o zqD+wlNt|Ze=<+_Rh=E5jhYoG7P|g>NV7HE+-NM< zd+ComSQx)=$L)PP-rI4`@vSURM7%r|xLc)6x##f-nVX#G@7G&lcz`m${-}!`_1GDx zx=THvQcpO;kHf-vXY&mzT479O4|J@PLvZQ2TY9#gr@K#A)~Rno5yUCDV+-oAsq7A< z7ZgO;CL0A^5G5^3_U`e6fO(I3lPL4`=ZwssZnm0{QNB*d60BW24R>RYuyCDYdf+eMhLZu_n_l(6DFKY2;qhZW8;wNSw_mR#O=UP|2FJsTfD<5 z_U&=EPPBzJvsYQyjnL zUB!Z?8ksaUE4>~Rdbe0TdrL&Kj7n(->2!ErIU%})O;_7B_#0GwN01IC^UbD85Or%i z2M?hK)EWq`bQpzvzU-9=dHFI#0vMR&fkn(x${0@KCw=4nT-oE>gid-*-#{%uN(9Sj zMX}3pEpRc62RD$?&7M~%f6{TgVmxv{n*w#HEozQcV1+Htnti7a&#hcK)YR5&%y{X) z9v&XQ||God|iKpD3eXMrEK02a@CtVV(pmP;K zn=14KouFCX*px(~hl5%)bnN6aUC$otl=TxrClTi>L~T~Fc^cD{v4t`C(JtUA$X!~o zaSyUw=#B&}oEjY+)vmN0>8B5yudmz~xgwl-biX-KzfGJ8WDXvfYp`6G7q56PSq^co zIDgnNgZ-PWc*2M#qAto<1JMUoB1$}%G{J^Mph+`9Eb7uZ(onz)Cr#C)k$k$hxk=(m;!>q>QqA5IQUYRv_zOoN`0r*2*R0HuliRtXQDl;<#;U* zSl8ajc3rCV!>eG8D(99vvv-k0)TZ)>q&qu5FNN&E#G_`HdpMlaR<*1vcq6xKselUre(=qsR+z$;d=S4CYkFQ29>Z z+8|^y@zq38i!V^cgSM~dh4Q%^?m2Mm%m4lwIk$gr+xViF-uFk|Jb|{RXS%OrS96Oo zwY=e>DO8`%fA;wN)AJm7LdVU=(9kO9E}eYK)vQc6yQ+SAjLku{Pt5_Fz~{p^a5^|6 z(B$9~<=rK@M4dvK;zPpq?Afz7xe-KwQ9HA11YCgO0h zf&vNO$d%XM|M<(#?|wSFXDaf+wsGdgvB8d}1~4Q2{>RYciN#$G{1GL2+=%l81MabO zQZ!8TQZ3>&qCY1tJsxP%9dve51WgxsOr=bYho>t$&O^><7%Q5lkI2;iA8S_^6IFgk zqjPih$}ls0ICx=!n`>M!3bHDafL~Z7i(fc9>;#<$%@hpc3w4a4jmFJJlXK&;AG50D;~4%5T4w8>9Ll)Fyq?u7C z^JUj|L#F*Oxr}MBiP>t#G$0Hon%83eY&EZ06FnTA2tcFhkJhp{I6)HibJ{`kOw-tN zY5WkIO&bocM`1emv8E&P6_ZX>-9D+bsluT2WO+V|YE}&{ZM=yZk7zkNdGgxf327+b zefJI|`RQlUAuv{hJh?~=x!oC0fJ#()+9)wbb0ViqVYXnD8!;-tCW)bKEX zbI%AHPF|pld`4vc{gch^=mTU0Y`ST$s~E$A2`e%Yv!v*2$r`-K#E8c7Ej@z z;m-=^v|`gtXz8OzxB`r)t=OQ#I2)*z?@ZaNOTS3jrAg|!Zcq{s@EPSE)4^EYRw+8G zuGp<+!mLiF(~)Qo_6C(Tw1rOBOe802uC9;)!Fxotd&%`ttJ#1n>WQOO`>#NbOZ+?X{ z6i9)jfjw_H(^!v01KK8Yd}3)+Tg`#?T{|BA_u^3Ns-7pQ(O2(q!9p<-J}oC3YNo3l zclqTT`FR!vnc8Fmn~&wav+Xe)+)acZ{q(lY&1ps3qQuFYFqIrAZ(g9)!P9P4!Aq<8 zcHj250?w~>d15?*lslJ}n6w$m4)z+?%Tt<9{Tn9w;e(q^Na1fDHAmHy9vCkYGAHg( zutXX8{)d0Qe~+!n=$oI9%)bzsJ-w#}>yxK_*fx*X|^h8{U)DC7*+8F5~Qo(P$7{+yntPI@tKrE9yA<~*|eq>i0e zFTDzr;AeYHoeEj^ynf?2qTH$8K;g4z&Bs>#f(Fh!aaPTo)Qe3EXW^WF z=+W*+n*L)#M)Vqsc6PW2IWE5=PdM~B90;fo7#JAn*v`n11Kry%t=@RBHd$FcHoA5Z z`^?oy)x2?o&}=fkKtHkUqB*qCX4Ag63;!z()UQ6cAwD{~ZV2X@xH?>Sekgsgc0Ug%T4ZwV$J_m%R4Zl^*fjOpz>fi#C6`s-{ z=%K(l4)ko!n!NH%CS| zs=ak<nfxTZCTX);V-%#gJy(5)en9XWQ4iWHRdDP|XxPbg!o+D#S58-z zvotI1>DOeXiPKCc@u8~|=w_juwIL^}byq{6iLIk!B^=Ss;FK;H^Tx)c@Nnu<^^LO) z7dOa%B5~&m##8CaN%`~gqQKcyoN*8GqomHI6Y{rkQm378xKt{QmP)rvqcbrlS%YbC zQi}XAGd5Nl9sP3M+MUbinM8!h6RS8-)~r|a5rz@TyT+aDXqouW+EjJi>vv~LW2G^C zl5c+dc4=&EW@dC~Xq~ja!k_~9vz=cMn!=i$wxpGIQ^!CLXh0&}=A4d!tX9v=Xw~kL zMhAm7TtQR(9wJ>q9cjBw2CfMuVnIt)?UJrg$eVqHCXO~Wpc?rnLYyynI3~RL0ybVp z4Q=kRv^fG(T7jn`vv0HaA*$KGacj~ucxtdUdDU zgX4h9Hj?UBj97g@OZr4%ML;T-&B3^`5CjnI3B;iP5ftWx@`|2-)AfqQf**ig$(24w zLZOR4;1+{0kp6O5z9Y>L0M2}1L$W3o)>jGYxCiCr`b?rObqz2IdZg| zJ@Wgd9o-i?wsr2_a<=KlM;njz)UMx??O+OL=HZI}K=CTWzi;h3$|Wa7fErO+7_Hux3-&;m&QHozxEyVbW#Zn|siL@j_T?Ihg>u)_hPGpy&+UIxp*R z7n#Wg*C(2oLMC#CjS?tP7&Tx3Ije3NX^x!gA8iKY_2(R zVzs{QU(Ha3)>iePZB^Q=H&Y<>9#MTeN3>GS?&`h1(2nCUsgVa3tnC4oE41`N0w*|j z*T6#i!lC0|Ao1inEDq>D(%EU%K(q$J2#A}_sMlN(89&(3p|nXWTH5NFi|cL#u^$f4~1> zuk@LV9{`!JwVIvkZM_;pE^Wvq1=D{(OT5Su?kf0UCU68gVJ0sW2XRjhwX2&ItObzD zVj>hk)>AAHgI>1i7d#5vi9R?z`|yLtUQ?=CXyB~M*>p^LAI~}aY1dw{ zA{z`L)JO-5SDXe-noCYWC1yZp;*t2rUWTROakI^&iuT;O=M?BA66X@ue6|WDZBH;*|*w9dG47(a@8z!*myt{otD09`pV?B*edex;9g3C1w?PCxT zE!zQ3>`hwLx!t(wfmKbiCWU(B%=Rtqo!2!;^N|Lfn5Yw*serH4kc0+7hhal|T_ZNH z!-w`++cR@{BItyBJ1Sa8+~@4=iTYi3Txc0oMG&I=AP0IXZwQWuz`d-aRfnMa+dsDV zCtGUMiWf5(QwzxWQSsywyBv=5J!R)Aw^aYTGof{QwxHH*nqkV z{%Ic)t57Nw`eNCAC|K~Z&{~!j7OF4(&iTIIo!R$fhfMx#+%@Fne1Fb&PE?_^#Qn304q?=hnOGHradgl7XWxfY9zEOFqFENN_a^4((G8loIdw4 zUN$>d_Op4lb!XN|K0d&PiJwh{uw;S2@Re6&;9x!WCRw9SdR&^1-U8dr#$Fh9v6!X3 zWh3XaHUWxX7Bg}7ZS@vRmnW@N9S}?|QOvf|({fEy`_O8xuEpontEvF9V=yRZZ9v-OT5*Wqt3Gn zG&ntg_=Fjjz^ZVE3+-O!o;;a(!W3MDZO%Bu%kyU}j|fN4Lr($DA*XMD@ZbT~CyxM7 zJw7340-H56S}af|^mucO2Pi5z06sM^4A_)c)qZ~aOO`~&CZ?>WbUZX^DerqnpB=j z76KeUmMVEcZJzRguo478s>ItZiUw#9#0gKjB=1$obCp0iGtcpA;02K%k{23n1FIt=8nSNwq+zW#M+9A-Ae*XGEA?oV2vWdlP`O3q}We6822v z!Me=n5~+PHCyt$eviE2Ys@d5#Aae%>K$*-`Zz_EWwjC^IV|Nd{zIkslxwGN3M8l1Q zVDiR1ahU^mK4%KixS6+W5Rocqdz|QihbIuXQv?J6&bXj>m>#@^dAmLtMlZ~m+a7xDiqzfh1!oi}?EO#?-?eSM9haA)+#mym}}03Ruy_KOrd&n(#&Hp;PS48gPAKAi`i?YHt28`mzJox!{Rhs z?0nkXXW>Aiftp~3{q~j}9jj~GGmG*ak!n`U*?ae# z`6a!48gnNTLYWOa=cUmU)?~j4a3&c;gmQLVt!VFPIqMR_)P+_Tnn(YvX$lsou%sGy zfN?+}xp%+_l(p=LrG@?Myh}X!#SkU#n9mNG6o_^0qX)G2qDQpK+trNrTpS#KLjApd z$Ft3`iN~~x7HmEqlTLF`C$xixO3rHE$ctW|d|nL>bCV!-_!8#4PWMYqsy<6_qT}R# z(;CiEa^`Eql%Y>gI~;QQX*QXmRJ)a^#BC?V?mjjz3fB?~ zS&o@tP$Cs>5dvC|_6FEurg;xjH1%w`Kxh`TMWi^W&bE+pLGiG+_G$+}(rQB6PJm9O z)G4UmVH55KQ-;;WTMLVsYCyb+4r)Du;&jbcH48!t_412lh=Vx$SyTCJbL+O6l_qme z?7>KdyG_-Ac)ST{+NmZYh}=CGDq7l(v{2e^ttOw8H;Kvh`)D=0EQF|g&$DOecTe{} zN1xf&eZO<%T2oW=vLJH--)SAt-mXFB&HBD%qA$^KvLPYhBqrx?jJ2jbyXJf-q-iBfU1C-sD!&r4Ua>G&oI_wk8DY2(uYdPm6Q4vz5>DAbung$+ zQqD$9<+G{YUL6P7N2m1c#0lIR&F0I6!!IgzHfD4J1Y{zJ+LkA#a?cQw)B-JAFql%N zwwbUuaJOL1tE;Q5W>>Y4Rfu*t6I$&zkwER@6zJDZ&g^XYlwGFk4Rk<@hbDuOHP_d* zn0?0hp>9pP?P|NQ(ckcy^qFnzox+*Tg3OHkB|R98k~43|xJ(Tv`x1S9eSbaK2XG1& z1)Jc`=P_&MG$&q>X(wT(1B#P1Ct(rau+%UMmxJVN&(e4TNbH*)c>8u>d=j>G(?Xhb z^xDht6NYRGYhExTT0nD%H7zpyR1HK4tt~exIpE3W!5TkIbs>pov|~IBqr_dXNjDPC zXb;259fCcZ(eC4YSk*3?_hF}wyO8Qr8tZpTufq-TL*LBk5NE5pdgpOd0hi&flGrc02*asn$92vJ_7@5tvW z_<(@2ofD39&ffmeWPx*6Us(z6oT4~2< zJu*df-fFzHxIJSLn~gQ~ERl)vkGge1Ov`J{7i=)s7}`gK@)S%@sO^f{;`{D)#1mRP zIVI5L4re#3o0Ao!gR$RSS?R1YrVeKXpW0=1b=`04a*#s(D6tsk8a@@L1gb@*&<8G}<&Q$yMuAlOk ze(M)?ZA$}*|JCgu{_WrP3=DME9XL8OkoW^W`SW4*@q%kKI#2a*A31XD!Wqj6L$k?r z1(nYZ?N<*yL@QuKi)aPTflgaRd$4+ZqH>@Kw3}nBXl+8fIrh)TgPZXrNKdMX%zbaD zK2Y1*>LAF3L3X(b+LW3Wxqj867LQRA)4u-Z-G>iU8f*bFzxe9Pm5ymHUNaTu3(R3i1p>=7vK6v<;YqUw zf>l_-n=2OJwg8>PD-X5?8o%k%;cKQr3;f6B5G`2H3FD~k7OZhWeu8Z@%X6@rF0(dN zlSvB8RlxzzPN1G$CT*%`*S6*w+mU7){50v5_O27pHrbKpHMIod8TF@D%DNnCwSiuV zb55QqUn*}ReMr&SZ9&w`Ai6&}Gcw=SCI7noH@3BcH02u>BNKz4+qY(ueSHaGOg>o4 z?v%$3kY?`2d``;Q=gFjtyajLG>4!{@Q=p!HcXuMs?O%SK8yT7D{!`uSW&Qm z{l|jLmbxQHXQunU{#CkVsqP;;2N;LTRED?A4I8=e(SLrEL?96<^9ZWi4Z-Hd(+yO# zLkBkWX7d2In~xqKTOl3;?LM*lVAaB1iIXGR#}ik_utBlYFx3NX@^14XZ^I~br_bIl zjX%K#<@1YF)528xBGvAP=tZJh_v<{~=PgpoVg`ilRt86GI`?g zqugE0ei*inJIu0I2$&TV31voefme>AQd#=H2*3gzlH7#JP={h^0<#egc|zS+rt<(~ zz(Tgd>eWx%yOim9=}2o`^p_zi)yE$ZMnM!txVQEzfgWMw<}90qg$XL`z?0${4ql_(D}9^1nW6+JzN1zVP^LPX)sl9*lhJN(tU}Z6 zQ7lFQ_3ZK*q(JJVN4+i^R`QR%-}$KW^Gf8l+r|IYuKJSGoxFR zXYJZtB$A;!vQVbH3no#`u8-`!&N)!<4`1H^03ZNKL_t(AcvMHULYqNOfiMVy7U*7QS7Ql9W{Lvq})?NMbuib*oW+Jn_XJ_DspcJ3DD#V-_*dNS{X4-qc9~|yn zdM3E~Mpw`H`1nbAP!2@W?C;i_O(|(FFkM0F*~K>(A$0HPxU@;$lr~3Hci?3bF<$}f ziOVpJ^TYmRi|4IJ-rUe@WCw^@fbzf?9?YAo>SOz=YFaj&npCY;L07KuLhOfnyt(^* zaOUdfoc%aB^J5_M%;3m|CxW#_c*v6@1@Nq^%_Y<{XjaW=F}q#azMc2d zr7FPz^#-L9mL@!&USq=hj4#kbj9F6&Iq~+Iybf!WV%7wmfHmhD&ekg^8|ZbpP^WfX zoX@h=^yIULjo9F@aqDXFkxAPT2E+rOJ~%6JC&>giCu}t}>Xz@2>#2S(+u4?lHPzLV zF(CoMKJ!fd+KjMeR&c4%Bx$momB%P**&ub$>}&EHe8&2u zQ#kV^BnL>0NBAw&dfggKZKgm^EH2U=NOMm*stZ~g9niarX?~E=Vy(&ilW#bteY;n^ z4$yF_QjfxejXXcuh~3Es;}XP<(>p<7iu{qMHL4ml?XDwN5G22w>H{{M?~^n4J)UZo z$h5QD`npFKu!lfuUYwpDX&O$3je(ZJ#dQ=pae)lZwm^09xYnSl33c@;&~D3)ry)Hc zgL3+cZ!Wv|4mP2-BHp1ChzJEgx_~g&CIv281gb1&3s3@0f@;aY)VLv9>(Ssn91c}`92loAdd`9|x2uG`Q@QJyJ(2Jw4TAMcYsh{WuS)=XAO0#hD=RwxNnN*=hO)v`sDE%}Mn5@#9*^ zMl~YdI9w*^q=)s16tm1Bs;o4VN|;`#Ch~4iwY4n;vbjVwDqq``1#xjClLIh0{>cRN z0c-~Mt`Ew`qYM~mTMDA01#$XY&C`Bm>n23?Yx$>Pni&T z4r=!uQ`G?mLA#YRH4k^!?kl*f7Sh}$$h`MJkSUz`_eVzNOPByTxseUsky?0)w5IZD zCtpx|JXh*X7f7;c?<@dA2$9sU()CRsRT^taNMz%Vxt-S1)unIjjO)n?QVKyXMdCUI zavjHf7GI!Gc4~s(0^u!fgVK2jg21ry(;$zswiSB%$;ou9n&Gz2rdu_8TG+8{_L|07 zKJBE7P6)T1;7*6wTnSZ0g)#D$nxHiyUuob6QN!J`1`33l8ZRAe$^g?B8&pMV*6T=C z`b$=`b&Y0`Nv|%9fzE2DS*P#pITtF!*@jBE0$WXQp?SE;^E7Dkf^K=Hd5CMxSTtr5 zHL=yah>laR31lX8sp*xo8m!rje0cMe8_Wt6b6N8YSfZGfccDzY4y?~aBG)+$+PgOr zJSrcg)6@~|5(-+*f=;&?ivtrytp)AcU*dnQmgZ}>@1BTSFIZz$oOv~K8-KW(j9S55 zpvC%~bw809h+3V2;h0tT;RnI3TQyzN3#J~Ua~DAQ?u9CeJB*@rNW0_GC4ll$hdKoL z;8eLDCP7@EyhBG?R7WIp|Pka^;B;mlNKq_;b=5Y89E@s%<{^wQH*g z%I9>PIz4yNnT7RxJZ#&uh|mqY*l0=(PJ0x6%qlYT#mNvv@bV;-3ipxkVTBT^N=RAJ zi?9+nvs9J%<;j9d;LR7ePx)d4?%>#Qb!c{X}y=lpXM9nsF2 zy@@An*PThNCMg^?34WS?;(K**1ca3)12ui`S%Q-JeXqu-IC#~c&Q_q=3`{CIyK*@J z=b#`mhj+my%2_2(Lzw`kw3!0U(csZjd!^Szo4F*Ij$4&4V}+eUt88!Rzt^E)`O(^&D`Y=g3@L_ zPsSWaD)souu_s|cg2hRAeuB4bR$z$yxMhxOcR}^cqNG{8OZ|+>KA9@_N@SaGXfR)z!x}Qytw z^04VS=`~i;;SW?;lhRpv1$fpUIJ<1FO=v+jNU8)VshsIGnq*EEvxv*lUjj@)=OEFUB{*5lk~=vB z%0vREMg!MJBY_A@Sycj|(`@4}6&;*rB((ywvt7qP>tfS4bMmtJ+Ks87O#idq8q0iV z)ea0lZ`JM}7|7n7PBvNp9ZXt{(L}6iAX58d>p!(t{p-10bKB)>K^%7jmXIBcnPX}l z(PDu@A+0gI?B1a^Bpo|;_-C6cIvCls#~ACuS`Yo^&xiB?&Uu-n>?7X=_@y@FE(e;2q^1C*Bm(`@sU)&XB{(Ez-`0Qu@cw}ULqJ8F` z-v0FsI4wbvkQ9)!t!_N*BIX@?5rrd4P)Oz+3|ZL^7AB~-GqziC9A={Sba6$ZXye?5 ze}|@CnyMBo2nS0dnqwaw2idywBuYuExDB&8zHRl+vY`cnD{V1sw}y*(l&gj@rKZgn z)fi|}x0-1u1j8|>SX?p9rSnj;2{F)`Fs-`yMkk={C1jmYOB>o=Q!16<3FM)(=Ea&R z(k6GB)mNG|%TUZNFRS%P;{l~i-ks>;q~6?5n-T4Tc9-ll7tG0t-f13&v>l%9-XsWV zw^gP<%A064Jz2X}w6VlRb54z`6Jj&r$@IF+;igy8LJBZQY|0zU*&Jz;Lm)C|CXxwU zkBnkOdn%~l+{?9Q+b|BomUww0$UH3%w42&$atw5F`qrROry#TGUsg-4H9ow~dM+6~ zAb;HCau!kftA91>^_ox=kLUVVCl(r1#2 z*lcbze$igHspB9|>rO50kj>Kdi8U1po97SU!ji!!!uPMr7|b9i8e*RURy4gmzs{VJ?*+oMC~*uD$~@E$n(vO=aq7BzNYzHO)zTKVoi$^CvZ8$hBk}h$*S3Jr4vOn zl&$AslPxVMv>QUw%@!TBB@os?MW5?cQ=S>hP8x!4Rvybwu4Y?Wx@vy;S$5@7M4H%4 z_P^eTZ+a^YhuhoJSD!R@ReSHτ3d-2P5@1rlhGohS(^0QN+4)4^9!zAeqbNe&A zT~n!7kle=vJ{HYIH6bB1@ow)X#-Dr|_>h1UWSpSg0OjspcC`RzH;gagu1DGCl`HB+ z!cEXd#pl->mFR8>MLT)e+-cLMnUZuk{U+G7*FZhEc1@AF+BcN?E|B>?5{LZs?(XgB zd2mtl0!dJQ@-x`DBnop05C;;4ICiJWFuVweOA0F0p^~MLa+0vFd-75K2t1sXXh%(S zQgAq}JiIW;w9@;|xoH$Y#o`DXUzLf0#E_8bQ~uEcgHzz7ARTU$A!8%(*efJ8aVSpb zp9IEDG_oVar$0WX=I+pM#xZD)6}uSupkxL?VU{>881yLxV*#Bko)TE%QZl)g4kq8K zDzUI>mq4U{n8l=NCVDbx((qDB=)!_tP8QUx%LPq4pspoO2UXLe!Rp?ymL9|^WL|sJ)Smg#i=s?=_4$KPCiD3DmPmU;WcAsDo=chi_g;G? zw+>ODFKThW-K^oJqp8EGx3RsiIf^UCz6RZ5-gl&h&)!$ z={cBd39_-DohJ8{H1>i{mPkyX|BqlhUtpcoD+@|zA)&uR+S`O8HepN!z10-3s1;la z+~q|UfKRMo3+APVW2^;!!Yx{W%AuJYcmeJ8;+b)uhI+mqAhY%Qbq2nd__%AfGFm~A zNs`{cB&ucclvd0VGl!ls$FA7As_9B6r_I@_idke2VI`!d&}B|QJx_B>bGj^DPd5nC zZ%J)GQe9VSc?xxKpVj>=LvStVgol%$nYEMVGI80cYy_nSN*4w*zFK7pw7BOya)s|ML&7hkNqKRDUW^dqo z*}b%6RwNgU<-W1g9XY9~{u*{9n(Q}W7f$eLZBcu?gI5$2Rd;m!{o&)M-^!dR-R!?! z8kv6sGLz|}yKRE{Q-D(;$20-7kG;1OWc z%CIjUDf#up^mNn_YUO9-GctcDJi(X>zpk*mq7?LslEgVBYRe^Te}H%Zn0jhnMtKvN z36IEJ933MA$Z=?4J?rdg;ogq75#M*AeZiX#mLA|aS>pVS*hJD@L4KN?O9Bj>wy_aP7IfHhkio^VR}I! zCXbP%cg)E&!E9%$rWDO{JZnn9Bs94Rs@v&3oPYcNX8*Pq?*GEuUyW&Vz_hi<=G zmd!TTH48Lrv)S^YbldXTM_w$gz}z73Z$u)eL)ZZA0W!gECot`%3BEy(B`R1;OJaM2 zdg?jx35*WDf;w!F$qH&a(ym_a%qN04?9u@zJK3=V*gP?ubM`ELLu8F(G-y?ps7$h1pKmo))p*S{~2=uXRnZN}H@w8TwJo5rU- zqx+yf7g5yL_ttS#PO7V!AJ*|YYNjA_?9k1ByfiXz<7y&v=B`}2Y$hT9vvJE$!ObTO zg%^j%(S+S9bvi`W7Y`%JQD&FmA|hpTRIMoK`a_?CL_$pojHp1SEnF+Tvp#gQ2qZ%W3tHOv$eg_3kr~?rIpRT_Qn6IZFOF+` zCRlp$R)0O^z@PM62e<@c$@DEo9>kylx{mOSS#r`i2U7qgf%$(MTJC5Ci7|#Km}fg+ zsv#!}yl5&-Z{B9jv(9+d$-!L83CTb(=?XaQ)#lXYqE6K1^4PK3+H!4YmzUMv03_Pw zWwf&J1>zT}QbRS(rZNT*+% zu1`PQ{J@(PWU^`sG*5%yUK9!)+#vAe_2hGonmD5Lyw}r|=~2fnr`8N|Z|#QCVje+o z{eb}xkvRyTAmg;R4-Qhq`A@SRQD_cp*(4b#2c913K(Ov|=3O>xF2cM^I$EIeQ)Ci3 zaH@Nk*g*_f*D#{arlTdyX zTmu<;N9P2V*bk4B=$;pF`qCZCbBvNwKQ#mEgVdPwAaTyLDL)W{jr(hPnp^|H^s;r* z_Xn<%HVabTz@%L?F>J=BV4yd^dO0;kuAWl#oZpDCff%T%DJLpC(e>=Cf|f zv~*4S8|ePWjhngyDg`o2;RpnSOA0ns5eB!ea^=t3@~775Kz2H5Y_4rIvVoF;nrkW_ zdEbv!Hn+{*^QLPW>%5l6Y&Q0r_hYryD+@3y- zEzpJts^zZ$&7y-kYDzmx4lVt<5O$(B&A@|JP?=fp6s^$;=BfuWyQ->bctB)AP<=^d zCkGUo!%79BU^A!66Vy$? zRutHTNxPs?elM;kbCv`~A80hH(fpjda-v$IwdIS^tt@!-EZqgZGQs8899rnH)F}D0 zV}5}PStcl8RVx*f#$97GN?(_evv@p+J84x`5bO>7lH%(!SGHO_7;c)AnskfZEKNrS zoFR})?~4Vdmd=9&J0OgjF_|=>q&A}ir#6v-S>do*rdE2S<~bWZTLT5{tkGtx8Q>Qr zgXy2t-QbvNPTW<~nC%RU=S}k*RhqzN>@VJ*9xT+(-W6ol{Ly<_+ScZK&nw%8AP)O+ z#i5^g#j)Rd>DWo{i|OcXucAL4h)%GdJsr7mgG(S9=^bq1lD5Z8yUgX%Y}+$IsYG9E zrkE}&tP8=^?bgt$;enx3-ofBN9+%)-O(k^>{y;hIXSb^^3>(^&%`orc{X~5ZunAh+ zLSMa)@n*8kP0Ya6rgonTLDBokWyXhH2K}JBx0@1_3ufYV!7iNJ^t#ze7q5wpMy7Rq zTBROL=t9U^S|D>(kU7yW$b9nB$b9~vU;O+~G_rNyaDN4ajx(u53ZfC*Nw9K(ku0^7 z8g>cuSag+nJ(lQhW=_{a@|X_e$LXUtt!C>9^WlI`B4aVk*;PVKOL+~~1c@&W?-7}uNjMP5 z&ahs_4W62*30plWnat7T#91;40rg3eX;B}GO+xKtC-}@lHmla+G%E;Br5PxNRs*PM zJED(@`GvB12Tj}3I``SL4vXQey;?$-#gLLp#ZBymXco4cKcHBzEV~zr z?5;-BmKN#W?Du)j`MwjcHL)6lU~eAJ`JVHf&r`(DSej%aBZE(!RL6UNjI8!Jqhqz^ zoe4vbjDRjxRPwP|VH#R)G`TyuE!3{o)>iPkgiNc3gLYnP+K=`i_M~0jn)~FDX*$@T zW~xL@JKNn2E)a_*mAPMwCIBQnru0IV;gRsn z-S?hfndoM{&h*g4$f?OGkFf|a)0M=;jui+lKIFogPM!if(j3hJ3E51RaD&Uyj;VQm z3HwV|Vy2Bi%^x+T&W}N>u5V=N`B;hilK$lj3)(GYjb5`kmt+LwDl?z-WWE$@_L87;AuL|sna!RAg*B6%+u<=Z$qRSL4l`7?(Bd1T`c2{tf*@*3 zaGy3k?S+tLPe&pFy*&sXD*NL{+ZzmQ0?5l<92aY?^^4OUkQ8Q3y=a;ynHjm9qu(w~@RyhZ|!CY%4Y_xKC zf`{g11sw3H*^VFWyCh`OzBPpr#NgY2LxL7IsGZ&2r0N|#%!XF0CMH22kgA8md6C%) z@B{VtOTdC9??9Ne4+rdfQ-l5bx-5~T ziyKac6k$kfr$N@VXLKoX@@JoHZv3!0+_^q;_s!>4=KsFIKC?1Cbabo^8%4Q@jwMki zU1>~>Oi=pdqy(KP`^|!#v&s$<+!1_JGcijssht#HEaxZuf+m?HpiKwz~8$~+;gu5xOhvM%w|BpbTHt~Jdk z1bJ2Ld4h%3m5Jg~*oN`7&pWUf%`kfOSYkcH1 zjA+s1CAE2FRva`6oim@h)wFv}I%r7*x-8Qlna-kC>LNubB=({C8a^P+Zk1+luXMB| zc#)+CZK7%_>T*Kgn|e)s>msyC=K-cbD=Q4z#P!KFz-T`=%EWRLcbhvcELwok7T+Z) z)#L;z^5CI7IDtJ-_T{Iz5W@n6qo6+e^-RIMa=%CJHv>cMt9)?M6m;(R*+-8zHXgs8 z3BL$s{)l&`QRbjgW^-c7h21ov6g)A}B?>XQu@rUz{H#EU$k~Z$V2xUQMTl_5TB0~h zE+2xvP0sYitnN#NgdPj}w}`>rPY8b`=968UP*@QAXf^WDz7QjugnGwpDbHku>=f+q zVcPMKBj_>wA#dKA`LJA?dc`o9ogsP;)&T=rw>c+FK9O56xPdyRL*mjCBoG3^st|V) z*|Ie`QLdcNpbZ#tf_`?bF2EbCDWglwvsX35k3NGM;kMT-R9nZvf<_Ppr(mapg!owr z?mOQYbhDawi>Ia*O|bzHrbkmdjXr&1aGhaEssvmcrHl#AC#YX2&?b^OS zR6TubCi2+Hgxc@n52)b)b0GcD zyOSNe0>55)4AjoBc+I`-Ro=)yMV-A0zBKPljA##&J~FZ2s&m2`4=!G0#pH~Z$?>~a z^k|dn1c>C&AsN)#8Ex7Eyd*eme2`(AH-~5pGQYes0BAHJUVC*?yO+oVd1|7qy~6vj zo*n^U+EK0A-QSnQ>fxU~+BC`>?(}BvU4L$6ev5ZzxN_(C(Xj@ML4lE-^hya(eyALr zKg$a+2go`aOFTnMP>@Tafz-JK3K={;P-}uoLO%AEZpn|Cf@#{?gqy_@GvP~)pZUW% z)Kv2~_%6YgG4sNKwsFV+03ZNKL_t)P^GyYm=zJETe^Nxj;LA#(&Y3@oF|v8t!q5j) zGzcRw9E7>&EE-{g$~g(V(c}~hsd;cFi}nP}PJ!$(80@nM>NBs+X|0*lj8rfcG%|f6 zGI~L6?YIV$5p4tD2G49xA~K^5q7)i9oUOBInhZR-I**pNMkciN^VXeLy&wYBa}&Yn z$=!*xwA7_w^q@_d&emdaqP=WOoc`HWEKU}e$hlPf?Dn7j!+F#Bs3!6?TykHBqtQ$z z)p*NsK5_nD)8<_N{fAB_{GU73W3x}3>)-#)S)+rN^I2N-Dh}fIq+)LFB^nN(OPK<- z3K|;zSw%x%-l2HtUHa10G(RRRkVLyr5F@>o4=un;{2s_IP~8zGsK)waMVs2)f;w0REPB~?wHi~c!05D;PHZ>1M8W#x%mA~)l;v)N$*Y;4s~D+ipxg_s(HUNy@6?uX5Do%xx&KYt<0d?Vb+n&}k^z)S)slEh?&Ne4y= zL~?O1i&?5)U~GcX671$aUXxg!6ihwzAv^Qtj4>0FIn*wry>ckAsFN`SZ1T9;rzE*K zl_#fONW=9LgUY2uia<+QIVdyVDF_j)q%+&F>zaa@$NwME)y+lRaGK9NAtc2xJwf?U zGD(&$QF?00D+f}qhY18)Cp9lLsx%-u(=?*IFkKZHt$LQ(ZnU{2g<7w{I0GW#0KF{k z!3fd2N^iTJ&>CUROG~>Tr(iWT8Vzp^LEEc?A&~h38ANh+0%tpr(26%`v1K#BwTp!| zt}s0#%%vuIY)0eT!~L5Tp?K4gC!3E}BhgeeV?JBz{`&Z(NG6`z81m1iT7J1FIyP2) z#e|3cD0mwBBv*lf)Aa zXHRO8gdX|SWTGJZS(~yT99n5->7~UWh+`lQg!*6Z5AMQ(aB7@WAG(I=Ec)8?A^YAe z4{7CdNDiyd3>jJ8R9DcAfg3mEJWR~AKfj^zM&Tb-SWF>`* zug5H7h9p-HQ&?YCA?DWtbQ%-AqM?nMFCb8iflA1fV}t8*k}J1pV&iq@ZCKD*^>eP(VM)HX;45qQw2)|jQxV8e&7+>}!=4LOnVti>B_ zuScH3mP1Xk&`Ls>rYW2coIu=biiy^S-5O!G@Q`}7X$cWT0@Fj?tgUY{FV3cgh3Ytt z!RVY#)ozEsJ=z%0G>whL+hEa)*0zl`iIJA}cB4u-fp8C2`I32SUcy=v_V!l6bxA*a z8SN~=KP$8;97GcDvxb<;{yD}&mbXC$DAR@#RTDNd=IebUszPHTrj zJu(i$f|F=>{dk{iPU&WUlIi%<-M3$WGEp;)w9004zR%|+2+uBQKFrC~JOrH+ndaE_(H67Znzk2Rt&wC2 z%8zArl}YQY3wV1>$d;_#$%Jr)JT}tiTSeT*6if+iHcBi`d4V!P12lavu_E4NQ3$ko zTRO{Bpipo?9WK|*DoG`ZgqW#mCqTl4j#%!jMO@*w|G#I&>X3lgZXpf61usDOv&EKa9SH=dqF1`&@n`QN*G5Y{9=qqVh5&A42H#es%i zZChHxLUSn^+)?vXGivmh$xxoWHlgLf9-NquPGua3eU>)8gO{*7p}(DDpt)_gZ(IKC z0pg(#C>3bO0o`owux?sKUP|T(lfcl;o;+!D6=W2IuYl3RboMV|H`qUc=jIX4Y0=S6 z=xdXyVf`2ctw=15N9%^dDb&fNR;b1U;Zd1t26hcl-TUV;r_R=uix z;$>rkgQYHvMto6L)|Au)gS!6D+VzB3d0p`_GiSVWY(|NW8e5}P-lTlN#?%*uMo?o% znn(>c(=g&)l(x!5H@+vdU8GpvmlmPLE`%;iT_m`$8+o=t_0Dy&7I!v+Pi@|AF<@Ks2!VUeCmnKqh8ox zMh7Qlre=cW$#WYwzHttYyL@!^INqK7>bSl>Ns8=o4S2Gv;M04WPrZKlrNao=Cl<8N z1e_rNGFGhVbDPj z>X$u{sFgd6+;v{{U3d$U*P9v#<(PLklf1+rtF*Cg+=Bs)I#)#Cu z7Ex@c^z?nN&Fs5+R-*b{+AH4Hr(T=BG_xeWOuqN(Ssl}rU`8^mx=+qOn?6g$#sGI6 zOP3IXI+aUIl_XeM0@)=|W|wBnf_=x-|44h_-cl6VKWaa7kIu`?32|*FD{b~-aSc?3 zp{_tVhRn-mX@G8~d%2YNCnhdoruWvYni$M_03rl8u|8&wKI9I&%o3kV z20z^CPTO}{v|9}jCPP4T7@ge)-_T-o09?uhYM|3*Xue=B4${YQxd5@buwO@kWQg{L zxHq_wgyv%#PrmWx1kv}-xz~0VoL|zgw>eH2py}hX8v9nwXC?HBnCZRb?@erUR)Q&L ztT1_dab359fs@1_SVX!ANHlM%uyb8@D_ta(d0W}Gd&|&g&^XcD-H9hrYiGIP^oPk(3b`e-;94hDlE(qO1tRT`!5Xf(jm(&DI261sR1!HX9W zzgWNjC*_EZix=uYjZJmSS8r+Z|LgGgFH8S=lE_xSO=($w@|TwOmsV1mmhoa)K%<5| zFgnvE!5y|moS(`_-h&?Kqzcfr>1UhPqV);02EtNofVNzI%YuVpj;3`l{bh;1&Gg{Y z>IKNXvv1v6T+WJzcI#NW#q6BVm-ck~_U*T~?Jm>5Og?5A=}?52T*$6Q&McUxk^HV? zqd99oC%)Rn>8!-lv>>-K-6W;=ERurG1GASVU-=L7pQmydqNK=vRRL+{c{2QiVIK() z_KZf;d>OAy6pe<-v~t?sn`lo{ErE~@h(XYi16f`kc-B03X=n4BZg!wy7BVhRn74yh zPQ3U^(P&{6q_zil_3g>KU%T_}A($ViN_%Hs2ZZM5ZyvJXn>Xhz?t&q6|M?3me|ThM z{(WI(uz2D6;%dJ~kqAHPh=TkF{OPjO9XXAiP#=l*-{r09s*<|3J9@V0;e*Xy&-PGA z`?~b&^{^jVVpad~?b!vsVc8*Bo|;2%>_%O_iSKEsG({65nj^?hs;diPPAeQ(zT5^5 zLs>~_m>04%HaF0P@Vb%w^pn1eX_NKenFOYI?{Y&Rc!*XDS{?ey?@DB{$z9Ae5f^%Q@STUbECQYAs}YZ; zU?IYOVgadTZYF%Sn=>G!=YI50^fNb1U0C_`qdT0Pc=`Tdn20V>nj|5)n8>dc3Ji^t zBM1`5?M%?BP;1l!X_bw9v4c2L43;P#iNJDbDRkH;G)|I-oYGaqpMI_0xQn{G@tny@ zOHxqIr6ez5iws)5F?Uq*)YJ76ze}nC+e(MB5r4F4b);q_{ zuuvGk(6TXX7jEYKEsXKCK)v8h3K@o8=w%jU94Ua&Q064T7?v|C|MZMyIlt=ldnIAL zPkr0yr___L9m5_wQ})`yet)%ZY1Ot?Q|jyf)wE$N_Vx2udw!wkC_n1=N$)7N&{{@o zgJSC3!HE{9!vzNDQk#}7>^+5clZGZE}R}!2H7b`GarW zn7Z}hFV+E>6USCYsqU>)qQHbfRkD^=rJ0&eK_o;hw8)(UHqjn6T_RJ~9jxe8bY|*T zT(o51Y2=GLDe((BTjK#FG+#kOAC!VCIs;KAB6}Oz-5ESk{NS|SDSqtcN&E$HoX+l| znGi}#F=ixcfykLkljUS9nMc%7;oDgzvPxVasq9Ot7jd4o12{?3u@xS$l}a#f5nBDz zDHzsAgh+Lg2e9F0$@hb2TWm?9ll*bg_RQ)M?y1z2o{LYaVrg-#^^+4vtHxe|N zz2TyYFq0nMzG$qDDR|Qv`#0EN53AVBbWgb@4Ua?)D3zZvgmOWr`;5BfNvOOdm2)*n z6*tuB@$~2#6R(6ExVoDOcRg6h*myHTij!YPPCr>cNQ6q6mgK~TN@QK47LX@*McxLl zb7oN5io!jRn#{9sH!=tphT!s|oCf_ufl`5uDX)@YOTIWu3oP}ZHdLooJZ)_KVY-^5 zD--MwJLx>kj;*XvRZy>a2ID|ms$}3U1@1KamW`;K6QDa#)>tny4iZ@_PF%Q-5?Nvn zU?$A@k-CzkE0#lDQM+1mC%rmtwN`{+d$CEn%W`R}Vya%r+IPtp>b4XlVRyK?`L7e} zlYYLE)P$D3y(1S2RdtgdDl*YfF>~q69}T!pkz|rJWO-HOVXQi@`6;_p%oHsLJ3pzZ zb|t6i8P9B?PNK(hE;Y}Vz~|nqx-ui)-8Ryl2rIyff&6- zJH=&27ny9VIVR5NO64Ca{Oq!#nJUzyfk-JiDjkgLT@{6AVcZ3!$}ve{0+B-{yuBp$ zT;*siJ>cq)t#)hBmNZt;=g6>FG+(Od$47(&!ZBoFQ!S zGQCn=KgUZqu6I}BI#j4I0qAhhYg)^jjR98h2d)J)mG++nn-eS7diFE~?Mk|LV)-ipapvk$avB)y2x;Z5M!>D>8hHawJFJ-zV9Doj}BRJl7 zwT5ZXbMs*lE&%6Rj%E7u5vGDSqmD9C8Y#;P^nacAk`Kc~zlZdVf#a^TOq*JU^OzQC zl#0G$k@AMq%%t+jk^zql>O|GkE(2j?dTk7T276DtEe+yN8R~(a6s#|4+tV8^bfwBCm_eXhEbD$B&)@~#Lm*HXwt85NGexfRJe_~055nzxH% zc79k&mx>T8LCavRStjY&o~fE`QBIgRmz%j(1f>6~8Rfzig`)5PY)uW;koGm4 z^;tt9v0;;gOJ%GL2OoYgv99S~_Z^znfQ}bu!=Vhr+OTXFE4J@l%MRUh;I`A=9M`fi zm;#x*jKTVQP1bxlpBn?kv0e?+!%9Jv&YgDr2)ux6VMvwsR(L(02((Db%CmM8t?O3? zFFI;7tr?%_#)ejia;Gx0<9`!(Juh}7b$se=if+qHvLTZ=GBZN?cu4x>;@n0gP|iur zX$1!w+)HqA5t%tGiUUI4B@pO?tXG-6$odC(TyqdS*e4r3co1R4!+LNDqTnt8yS~4x zUuW^K6DygSe)YPms;lbz`Tndbw*NApA|*+AR)Z~o7i&-o&r6|Xi?j0(Tlf6&Pb}GR$04pq1}VRmv4du` z&l}Pf>ypvdh*Hd?Jxge8|FWhu;oz(bpv4w}P_(UF<64YssFv33%c{L0L-9>{)vmn# z!q+8nkpO2QOKs>a(M_;rwuSXq%-1|nMt3ZQa#B`tqY7?7ONnoAjKGU z4@o~X0p)>`YN)O?a7<5Hq!nZXvpVG9Y#1W#b-eB;CZstADRL}}0paxQ^3PkJdU|q5 zq{$kTifbMvEl;9`@hC!vsvlmsL(?$ZBl1+<)QFs^PSM5}J^`BBJqk7;PqtpH18792 z(O;_p#P{k>@MwoOo)`A;WXVm8RLt*NZXKzuEn2ixa>GGwnnuiB@R^NBK$$^RxxzXY z3Yt(M&8tWtTt>CeHi!-&R+5sJcppMN;geh>GP@uaJyg$vH65$nf~xIHgObS9mWMHm zYu5}{0R?us$%in*V|6mu)<~q5pHO7C_8~u89@u<*U^Oy`8i=OmfS#UEPpC_(P|GUw z%7E4&CB!vLtYUl>gD$h?Ad+)-xt`YbldUUAzp2A%2-0VvWf@JxSsXntdPQFwwt=Sh zz6Y}rnz6l#zoa@c^ zV5~3dHnFCkI;avT%5LUs?B^&Y(?VQ@LOrXIV!f$DC=5X%Sh*iey{OQtttuF!vM^2I z`y*lchdIL%yTkAt^_%Z{GVc$MrVqK70)HdPs0U+ay*zX+A` zn+|^ll){+RtJ$ZuxMbO`Q5R}{HL{bmq^$DwT5jO353To;soPBA5DMmm?P)gsLpC_7 zHWpyv;S(34w`3Y>>*%mn&hd9|yc1KV4U+&ERj&qlu`REOF8WY#S?&g7)>{X|0@1)0 z*tl93lv?;n=n7q&j413E4dT?vgn4-FgRLt{Ke{-q>lH;gT&@mR8UR5TEAvr9wm9I5 zGgh4EIpB+vmtXQ{l1!im#g%z;%{Q#P34Zmf9;4DQ>Z69xR}2Z!K)4#EXx}s@^q0dN zTD3)!atQgoxK70p6im1s&5|{RWxx}HR@U1j9!%r0@uBrP-CHZ*sUl^=8)>R>P*dLo zYx$kpQ5ua75K_)uQ4BJKPfA&A41ge~wlK4njj1PQl&QDF*UD#tXa1-@6gI;L6L4Tm zK|!G+pp+KK(P*j?nKJ~@8nZT9_8NZl>$O;;OD`nQR&SVb(7=WexJ$B(+cJ2BhQFkM z15YG+_UPHsU$?F-{p_-4gHple%O<4khaf}=3U0zu7!lY4>|6Ae(F{iwA2G-H!6!Kq)#|)I} zvtXRoBKI{SAZV04#di6_@$(^veEF3EmIk7lz*7k2TFH-ryp8OYKqKLt28*pEzLi4A zsB~$?ilb3i68?H9k^WO8WGIxtTMlPi>C3KGnn`E}0loH_5z{#|xRqjZ-ikDQi-+oV zLW^4|WAyBOn?xMV2<4$JT#_wYAA)GpK^>je8DorL4M!hpw3E>u2>{l_J0V1s>`{O% zK%e8JdiIU2D^1`1=u3AGmJ8Sz4c7(i)Aoh$({aO)MZfm>3cgrq-Xy(mZrzs!eVhp^ ziDsT%a3(!2J1OEW#ODj#Es9cAIk&`PlyTJ)EI?kuk!9lKg zge3o`b;J*jB+(h_oM2@IuR_MfRd@?rjmbZB`v3x2EEFpR0+O^+a`}XI) zht6@QdEGF|`SwXG{pKmG7q+k3|jPEDkgkG9Ck=H+?r@-NNj%Oz!3UBy@CDb8_x ze^JVy_i+_k5kBeY+2rW1Se@_Oxc2zr>!%=$=j9KV&&Gea4q_b4v%J#nGp`;u|!5$G0k{od$EgbD4cTz3RVF!+U*Z3Lp@$_^#Mx8DNMixb?>~Hhk ze#PLlzyoCwEa6(Pj4=_<=$b&Lxn7iTH{#v>4Jh27!^eFAU9O*-dqNwJRMhY)uk(T) zi#VXk<#Ya)xN)uH-4S>lC~eTE*a-Kz44B6ZvAC%8fuu2Whk$pd0LOfWFDyyJgClVN z0lyJI?xQ_gM4nHT*rg30=;*Xv+7kk?@h0q02wS1)xlgz^(=A%!j_3%$`1Gw;-@5*k zHnI5Z_by%!uY9=mGSXju_xt_rouxCBm}vs`8-t>5|TpRCUyii3cHJ&%4g_Z^yT#yxCeTSkoqL zVlm0ih&V&eZbHwMOvA|?Gc1V!oy%WxyG?CTr*qj(gEvf>8`xqS;U+C|#f?tsHs5Kd z@MMY?&tr#AiUZ(+8J=4eNeoESwmW&pq6=Nw&*SGMKAUh*oKxVOg;vDHeEZU&oD-?< z;><|9;sxDM(0*jpb;tMa9o%{Q_QI1DH(sKLy{2NtF9ZHySsh=J0JbvZ(A=peelPx?A<(aUFJwB64%O; z!6ljmLp~|Ib4rZ^wi(}b9HPO#6iSeWh{qy_IL@n7#Z+`zEP6Nc+|(gXTn_#jxm$|b z-^6sQZaM-3@n5(~SY4U}Zfq(wSFT>3XrR z5_Bpcr*czT8#elg**%T6!%^+3a>^ye=jiw`kaW@}D2=ZGRQa`!fBe#^lG67-{_?Fm z#|}H!v4ZAsXBZfgh&|i^#SS^Q>juQ=lX!w6mI|&eA`K(cNbq%x`O!Q+1L!6B42@`{ zDd1Ll@#B+-000hTNkl z6JQB;JirSzklt1$Lc_;+xD#mN`T4QDAu{o$LF94Fi4ow)%wH1Llato!F#5hC)W z;d=@;9_1@|GHx*MJX+Ab3Cgh(S_}i+1+JjuRI(yzS2XwlDnO^?DSAzE2DtGJ43sDQ zGuQ?hl1awgF@Y0mY=MRe<*Fm?SoxlRz6a z4KjJy0m*|A+lRzjuwm$d;ylEMkONLKU`1NX2+}@GD$)lBMi3Q6^uY_mFih3bHlouc ziosywOZWQQd*3+is|wxc-kW=K&)L6ged}kha~ES%RwYg)s?BhPOXYp#Jbab{Jj95s z#bQe|g&wqW>P9JQ7#WOgC}&Isne>nU$@rZ|ZNg-!I)@c!hSZj*gNZ!Cp?C@{Sq5Yo zjTWcVAz^03nPrt=%Xg_1)FTas`kM$vo*f;gVR>&D7et53c;ZU#dr4wZMLi=W0XG4c z5&MTUt{fLekj!AOh@wixL`5Q+%W9cW4f_J9E*h#R;2B%~mgoS7Sw@rD@W^tWwwzX$ ziH0V-WRB($$?~AgG=aE1SFUS>p{1iQm@B1xJl9p$9#j;Th%RuRb(h^$-nK(85 zIfZ57w)9nr0|lHhu`Btv_#LY;xk)jfXEMua(VS>SBnrr61Op{u1c*Q=g&CL#9M?yV zLE>kvF*me#QX(ZY50~uL!R4e*5-cLRGMI!YW((dt6;$1KW|InQOm`BZ$ zPf`uZWSJj1)r}lbhSS8O;(Ne|#bjING>OOpg@_&X5h<%klj@+$conow#lak@-`Bx# z%3owca=3a`qq3TjRoz_GvdX`o2lOxjaA>wN`Ek9x%vecrSdF5eXh8&ZrO~S`sWwHG zMUOJ9I^qcC4X;GNB_aZ4?9^8n!~rX)SuVZHOQ2r^E3FV}bn8dwm8g0dA%L8KxwXgdlVV!;-fssP*|ie*pN)v7a*>phwx)PO~+0pzzTeUn9SCNJ&fT=I% zZ*$>iqVKBKV`6Q{hnehZD0vBO0n(i*AbK8i0Of900dlIa$|4zp)dTi<8)p?yL)r^Z zU{;z@%psU45}ySyWm}#fXP8!H+6wTpDOaF_uze%C8&xFJ1*zo|`oG#E4`1TN*m zGVniyy<5b(T!t^Y2@^Hsxq(_I66qL}w~w`s+?pEC5wOi}g}Y1Kyzom1G8xEs!4d$S zcx@zsPA6?b@ICM#92q|uupj{DAfD}lmQy_fId8F*t9Olfb*V+#oR*##9XeF8LUdcV zuB*30^B>Qyd0ETI^7rf3^$0B+-9NImbOFjoHWfxh;WQDBCRIojrxbX*sa6IXfiVa> z{s6g)UWm}LCuV1pMkFYLzQgnREJGb;l5*THU>R?@OPSVYMC3bEIi0LhkuX~!i%G3i zfk!NShRTohKe8&10_>`Js&#WhR5y4#POHGtd7_7sK}c#3;Kh**fuwvt7-Q%vh7^cQ ztVRZRoJK)Oq+O^?`QT3^Q&?13;g0!SoKI#n4V7V>a8qV3aoi98m(8 zNIwu!4H(mKjq#VLLAqaqjSe*d<06F!n-yWcK}Eex6pIYe-au5MfU#jvL<#Gl$}e7DhV5v zEbchU2J>ooO)p#lj^HwtAFx`;xkQ>sH5rpb2C9DRMG&qoQN`2X93_#Y1*rWDQE;#3 zNMrv?QTlPpOc2JxwJ_D>*aOxc;)&FVQx3A=lKLPqCS*-a4FU=j0lAnIB;}6_Od^7{ z6vTy^@v-wDGMTI`L~&QxxMvK4nTGWP6L1W2sF@-5KNJcjWdDGPQyzPf*Dx&x5g4Tk zr6x3WHAsntByxOQA5gsJS&~WdTv^w*W8r1gV86DE&UMu_(72$a@rD6{!hHn=;B3}-nRnz}FwRJ3yv9X86|D6?g@bQO@e zjngR=WK_qTj*wq*>Rn`62N>l~%Mnfu$!>-<85^*=45q#5w|zs4 zH(wR56o1h1!wqZO4b!`jaA{+#ljT?^l`#;5D+8AyXQFDMVWP?hw3O8tb0v~2i9Zd| zs8N-U#2_sc{4Y*}!;$dN{Hc|#>rcBlH%>EImnwc^H#1pp!+$b}oa98F;5m?@ta1oj zDWI(3q^2mM1S4z#Nwuj=%L2CsZs%{DO_)=52 z%yLXD_oCDowqzJ|6vigjOvL37Mr+dr0%v1XFlUvwVZN;fAIr#1BEfCiI>c}Uj=`%j zZBmsRf{6A_IGd0QsPgYPse^$qYzq5sZ>npZTDbITaix?y7lzi>H#TaXi}jlHcwNYY z6La9SG)YSG=ZfB;(I9UdVrgw?(0o;LcSl3bjUJSjl@ma=hlEziE8Z#6_>EKh-#-*$ z-2WjF?s#j!p?ClI^Y1ja_i(B7^!4b?CzX%_ixcl~DlCe}HXN5-$@$%CQCK5 z*>kZwUfoC)VgrE_U11ZIm|2;>2zp1#jM36Jz{1`sAu6l2K(FhL{pjR{+n?QgdjF{}%PUV; zR#uju`SSR&e?D89f4nq5KfkcFu(-IexS-{cmWL1hf<+lv3bK!H~etJ>zg)oZE9}b)Vv7;pPPHYRC;U$v%Mn2x3+6~tp*P`>l*yC zDcr$;IE9(J8vQ}p^?u1YFzfs)rmS6CC%3*f*4H;`Qoef5%Et-%==4TS2){OF>Wk_6 z^o^zn)3Tmn^4Efs-}^eK)Es`2E~tfW%xG!h+cR3^whevLPy?0>n5~SO2}CBjIMcL$ zs|wyH(o+B0sr~Q%>RTyT(j8Ub{Pv;u_n&(0yDgQT0G5i7NrE!Hh0m-i6=Py-ONjnW zLnQx4jAJa7zNY$ysfFvaYyMweV7Ytu?!UPF6Avn1;UVPw^U|f8f4+YG`q^Vw&z`+{_1N*_$B$jPGI3>M z;&&4ted&+$6W7k4KXdKcnG0u5esc1Y3zsin`0VoS%lB^IyZ!Xu{riZOD^Hh~m!GYy zJX>Btq+D5g{CIxJKj!C`7Clxz!k2}`M~apH4@2c6M#}(|_#m*nNYC-ptDi06u>D)8iIovt;ht9!$y9Wn%@9rLK^HAB{HZ;_>acF4c&_>K}_s);D zZr!?N%MZ4{xwE6cw_{+lfA+pUF!1-@Ud;R6-@kL9qhn{kN6r7Vcel6+g8>|eGYo2} zcr&uVunSB5%=8Qbhu{PRL4w6kZ}*tlIXJ=$7%G^W!SjB!nVH2sPt*1QO@FQXPwU;h zUe$TxZ}{;%nZ#Dc?`rSirvJL==ZUejE;xIdz2x=mQTxvoOBovz>vNa$RHaew@K%M* z{UB5^ZfPfY6Y?!*usd%1euGHs`LErI*F2 z$hmBLnOnJCrd+02rc{2#>vFw4?Y}(&00000000000000000000000000000000000 b0Iuxz1m%ofKM00000NkvXXu0mjfR4Dv1 literal 0 HcmV?d00001 diff --git a/docs/assets/flight_controller/radiolink_pix6/radiolink_pix6_hero.png b/docs/assets/flight_controller/radiolink_pix6/radiolink_pix6_hero.png new file mode 100644 index 0000000000000000000000000000000000000000..1296d02ed881c3218a1b3f35973916bca49004e2 GIT binary patch literal 1159928 zcmV(jK=!|hP)Px#32;bRa{vGf6951U69E94oEQKA0{~D=R7Lah^S!;j zyu7@+y1Kx?z__@$%gf90@$tL6yS25oxw*N@%E}=jA=cK`zP`Tj@bJ*k(7(UG%*@QU zx3})@?zXnJuCA{0^Ykw-FC!x($;rvh&CNMEIX^!?$jHbbARx}p&pJ9f$H&LBv$H-v zJ}fLO!o$O{v9YqUvOqvU!^6ZkH#e=Vt;NO0#Kgts=H@CYDkLN%@bK~N?d`_K$2K-K zNJvP}&(Nx>sxdJ!!NI|)sj088uRJ_FJ3BiiB_*)1u-x0*>FMdKtgGwm>)P7d;^N}= z_VzV3H69)w*VowD+1cgg*{KsPrz`uh5^v$Od4_(erU z=;-LMu(3l!L*(P+-re1&r>Cr|twcmbudlG(+}r~M1N8Lu&CJgA@#q;D81nP;^YZP< z$H&RY%HPM9_Vw`P(yHLhqLY%6=**bq#*3Jjm-_kh4iOKXoSfU)*RQa!`t|HNIyj`G zqvzJL>CmFJv$a1yK21$c>Ds);#>4aN-^$F$z`(t{y}9JUf9>bnQ&Usl(680f(4e59 zjf{-%=F#%w#_8V0Sy@@x*VNF>%jMtE^4`1e?d7kptU5O`)WDeF*vEr{f%fayh=+#E z$;Vz^UUqeK{3H?OyK#Pfd~k4ZtsOFuPXS4oL>S-mJEkuWaO z&A-w5l6PiM!K8L*FD|U?bNhjQxWTFXS5f}0t^S*vPYTI<;wuXLk zOunw2AA0Y->F$h&It0`?rlEGhXRRBC+WX%5sqPHg#-r2T>)LmJ`%u?iJ%x{{t~!~X z+KztRezo;i>u=phSBJK35voJi*2h~L+N$lUx@~{Zt?RF;)ZpY*MM~h5VS1n7m)v>Fps(o*(Th$(ArK09=9>weVjk-gNR>N?Ku#@0S6>!v!md+?6e9tIPv;Z1sv zjGwr<0ZZOYNP9aBSm0xM?~EUuM}DeJ&x8x6=bMQY>jNGVjC^^%x$*a@@0}S2Jfe45 zZSHsDd?MSMOmMxicQfD@1O5>VKF6T5#%j@?5AIfMy4f48F;=EB@AM>d$%K+-+#AQu z<9Fi2iP2cJ);Mu{bgXFF?CHW>5`rO_Jsda2=QVB33}NELg2aXhaVL(j?+6=0O{RpD`lIXjPDgB63lhl9CjwMrpw>&2!O;A~BOI zHS6RI%WByul8ENB1{a;OVL7zAT*eeZY(^PL4?9@rnvQXrtD;b%$Zq1XQ0!J+#yn@4 zT;=Jg9vA(%U__0%8q*?*V^oWr9TjOl7R4CNtK@WxsK`eV(~q%0JBspnjN|dUD8&5o zLN#olq4BF=a(*zBS!h+=y0wJv4C>7w33?ZLaZkA7AN9yV=X% z8KM1tf8C!L*q;yQ=6t1}H`l`GZm1 z`1O3=y>h>1}=S#U*zrB^)&yve}`?=n3>91cFZ`<;X_V(p%yIyZ;zO3a}ZeL#hwcTz@I@|Tj z8-s5zh`wxpOK_+Q5tQQ9D#KsJv&C-{on9_!_8|6jrXm5U)&gn5lT<>~C36H5E@X*k z|CvsbL=r`kNLXf)J#03oBw;C|l6X8xfaKFBz*L}2+O)!AL)OXMGdUSfNwz zoAV+$gj8#i0EWFo%Lue3h05?mf`kb@DcsoLLJ%UG!QAcO?{{ZH2QZ8$u?ETW2%GwD zNXI1e8Z-n_KgTqK85Rryz=B{%RDX2Pp#FQH)732)3q3q*!HyTMbpqZ=n1z8>0NsH@ zfg-4cn(fEbRnI2KYyWJ2KXR$M-yyAlw>nm0_Q&rZg6AJ1cxz>psk(;WnBaV`kH=$s z{OZ2i+azpfObi}nJ?VDUM^ztb%Xk2(R1e*)t}#;kzM=-;=^!wrLkLw6tOtq%Avh1v z4Y07gSM4p-)Fd-xZwPghybwP?O@TKr0_M(zMi4vQ{MdqEEA;kKy42x5zs4{G)0)9g zyhtNJ4MyHLrUb}PQOY68BRD!4OR2=Cac<&^QaJfupxr&G>}So|3Na_XGtMz&!e1Q2 zCt^c*EQIzHXs*Xzk7H5j^`;M$Y=S&EOF@@_cxX8pfgo;a@J2s#7lXYW#M7Xm)QPy4 zKwBuA+_NWo#gp+p=hL|!v_>E+ewzq3GwT!9l)@A8+Ia#$70Zd>S>T2ePeJ4eUC|K# z7UNXCRGJV`$Ss7;o~14kARL4^so3Iz)&f*O44YGh0BfW=8-=7& zDq}+Mt$VSS2u>r3ahuJUB>_leYgtHH5`%zKXwAfv=fYD#CF_GY_JyFVm6In3d8mj9 zl}HxJlvU$JlSqWw>Y}0xIx2Zc)&EnT;F6Pk?9V4=0c$ZTGEuI7szfM>HTB3@Tj>ih z)0amg{~@HgP!~SJQW#nYW8J>L;-0k^auD*F%m9ows8^5X)!~UM$X=7 zAOl(-7#4~bWJNAH+gCA5fkFO1i5}DdOsH53q38A0I0DoMWkZf0RF!Q2W*srYEI5r~ z5L(EV@)TqWzA4k=3ko-p3pbx%AeD>JOkN?6Fx6By@Aa+U_MLcaI2;aO zbN1S6Gpn@Wp@rsc`_R(!v4W~w)=JRXZmXv!7At7_B%nU>5nXAgX`5HuZCSQuo44RM zs>(9o>U9OQF!EXoy;TlVY0fLJEFa2JByOSVHHXI@+oJ0QjOLyvKu1yOdDnu46(qij zwO(}b7%lfeD{L3;s}DVv^9yU2 zA1gt;h*r-U?lPYXwyWpmoP91Ax;;PBCNK-hjBqD(@h$!@!StC|zA{&3yv|oLWddj- zX|nkfW*+lY!NPKSW=^AwRdWaaCW%2hR$yU@q6nc9bK-%k%->>_B8ox}fdng+IY3Rt zO)SGDd>z(s`#=CY5Ss`h39^$ab{-ThO!$C7JcLv08ui1PGi$D;{Va4_Nd~Qr)4X4@t?d9cV1BJ!kp2bb} z9q?keyZ-cDu+79bDRHeH5c2b_Kf_qIL*f$$6(;HU&OX^EFX$_S&W87_Hy&f&i~?o* zArq<_S@IvwycZd3UCFM_$S*ijuRNmXVj=RH%i67>@0jj{>i)*nuTL<1Cmz>huZ|9;0>+RZX=nynZ93crdbp{0uRDR;z>GMd3r(z~ff7B20M!S6?gTX+ z8^JNqZRu(m9yg-BM$-M|Cd%xBAWZ6YNVex#l_orJi>BOhoQONp2ULN&|jQYHsG59JB~FtvTR?< zyO_$$rOKg%)_3;mu3TL>hj5~_Nj3YyN*WbMrk2q=PRzLb@Gt#85L*&{5mh#Ap-2Bi zjdr(HVh|AKxS*Tirm<_Vv>n399!kS^AD$VAO>y^&qX-|HRRiYOusQ*pv6=Mri#A!R z)Oo*`{)+dw_MS_?!deZ3TI&pV%|_ZMXkI;O!Oy3(MOoFNMj+N^4h478Pcp1;GrGdop6U zoR_&*l~G<^K_zPd+5@nqjQ4+DDb%tEdW$GpmX+uI1hCO{nZwQ^Dp_HG@?jy? zyRe1bE*?~0dMng-$zl$Cmlq_roEM&aH}amL@?1;Ns<@!I#U*-PT|6jC7jN}rbpgF_ zH^OkE)iM&Q)wc44-Q`7otfl#nV)X+G&!2%d3j9rl80Cbz_ol8hxfgB1Nphe0Rcj7{n}yyRVQ_6e6O2N3qp%m$ zEY`U12zZAYREwn&EI`Ue><%QDwWTU8gOI+F=VHZJVol6O_)s>$^v(uJGN|c$DQLgW z1hm?^3wozaRp5RH%EZ1k7=F)c)uK=RSq}Wt17FehC3|~&+dyk5+zZN3_ADZwMN2@4 z&Kk38`LJ5*^Gn~*rp`clqvP-1IR2TgnNSE!vri6RpEfTXv(B*G?97SOC$aJ@1b+r6 zgqZ8tWX);!4t`nS{AK=p7Xm-nu64Pzje_+~UaA7Ts>Ai#s?PFRcCadb6AXMGpmDTf zK0Q?LZ)(z&M%}bQ73#(%HDafA4c%-x28%BP5 z44WkDkP4yWTI6(VC2|K^8R?LW$&DfP2tp}bP@{UPEeBRUfwL-Erz(9UjewclbXVQ^ zZ69*tL=HW(Kxiam3S#8$F54mDu21EUGus#5pTAVvPxMTNTY>E$JnVlx1+~W zeqy@I;77g@-%jsKcvc}?$0E0%+Sn53dwrY{_EXVS0yz!cSdqq`eyRTMOY((bMIy(- zlM2TOrhn(AFC}(jGwfJHin~5Zf_!$t!315^n~!mL1Uzt5AZ9PP_aU50Y*p+P!ov?P zNbp4yKm6{f$8oa-(yD5+>cO3lg-!%TQFf}ratHFoMIZTH96y9p#nGb*)|{!z%<^FH zEIRtrk8WauKCum4G_Z`>&IsnT&^A7b$%692fGgjIjx*tz*KwxuF=HsiC?J-;vl&Vo|E5O_VeQbo!0jv2`=Afe`4RmE z)ejwz?Y0nj26R>sofl@rDmX7M#eIhr0~R3pA1(efUrC%V(ASF7{H=;_`~CjI z{MGqQ{^l$~-SocIn)mj2SGPCmt0dU9WrY=H-BIbTYdL(PDficP?$2=@5`Q(=Be1ET z`c7&Ix}Iv;QaU&?+t9NA&`Njc%zw|qq$_llpNPPOs00>FP*LhQ)gh5dgAa1e~ zlvdq2d(YlJ-(EiZ?-;Itdj5_SfA7E3^<^WRW+uX_JlC6b1G+aVLc@E3d8apadt>yo znek@#{(j;NWWGBU!Lz#G)Ssu*`DV3pY*kr8kEO%nKT0m{?z__k?sO52gnhK9z+7Up z8|&;(ef~d-X0Mw#+J@oJHb%CQtQcepBB2ONwuOQ#q>Q{2mgWRpdOMH{3Yt}lG+$0& zDvD^r32ZUlw5d|ff$e=gZ)Rp^1H69CB*xcs|G-?nKTIC{!@+J`bn)e^*9g~1$P04z z*gR(m)eiSRH+x?stuXlU{mMAI>t~B^ajpb$tPIUg`i|FENz}YL z4|zVEb4w(2h;+0-S;x*7F+;}J!@d>#>$3lmnuKway>5F=JY zs6B-CL4cvIF0rtTg;SBPL~c;cL(5=EjdK*R&SY{F9y9a$p>v(XV1UIo>@IRZ8AJ3mf z{N98xnp=nU+A71()9yDNi`h@8OPS~-SXy0s&>2$7!lPHIt%9+Z_US;_OkaBt(%^_2*hV(w>L@WQ-&bc%mI|O?Y@J+&@iQ?wYO8t3w*C*lk$17f}V= zU4sY~me&n17IaU$X1(Txx8`-fZ`Lqb3&d);`r06TSFh{UPEuInS919E|MNF8;1!a1 z|0-*IM1jdJ6!_q0wLgb$W#4l)I zXe+|b^)k4f>kB{)l^eqou^MCvDEI<%bmb}|5NMl z{(X27c<)?{{4de3AS@PRLEHSul@MYlaakjJ!>>{KYs@u&DX}(4gcP<9aIkO%69OeX zG@LZi8;#4ro{;i_TiYNclCr_u)NJBZEvax4Gs}Oe4sK|9cs1j>(49B7kQX&$nxU{H zS$_$d+^I;a^!df}p!X=HaI$3NjF5O~}$3^YjW;D}5xR!K2>#kiD z=b7n`| z?P^%A_}^n!FU@>DEdP4`hP(Vt*afCpgtczkxTuX)Kl(pSGQkq_1KQPh3>5NIDe z7UD2l2rQx=b^P+z0eAXRBeeB&b-C80(cSa1KK#HbN9BGX%)#!nfx7#JRelios-q6a zQ?E2vEYD0b-vI8Em^F0rb(pkBzh@U9cw3wwY0V^P{3MsJX#IT zl-WQNV;H}Hy3aZVbvAM0VhLzof~fh>Qs*AW<3-0N?JNI zTc3{v^N7I5+0K^cgw}<0{_~K;#^>OZCk>l?ik)el>*FkaNns-bavm1emz8ZFb(&5X zSYBkxH_`$0J)~j@Z}lL@hbElLb!=~nSkOfzqdEhNs6K&cq#Zc77g%mAq)GUW$l-)F zIy+{y<0P@IgfKNPk2)5*S29rq*NrGOt(-#r9!&b50Gi^Lz|FCq(es8RMoo`YsIY{! zs=t{QHYXczSqhXQmEKE)t?c)r>DZ^Z+di&!){j6l^(KO~(22}V)830(5z|Z1z8*rg z=Y>RkCj2EPCagWBmi$H&(HNW;3B$8d!>WjyJto-OZ=u#Pi>J zmeSUA`hxXr`qpvTG%(F9ZRMI+53}jZ3;3NsX!+B8`V*^KzwdvGvoCb4?&k9~*7E#r zItRb^;<6q|4pYe@+qLv}ipUj-QO0ok{ti=ryZ;5@Ez+pk>zePe zmh_>*h6bhNIE>jIle1MDDO6cQ)6K`Xz!F~UX@DE}Hnwx$pzWchNCIw3*2%(b9tH#X z;)wFqonfGxVma}3(9LmSwjZ~4W?5=M{#i-P-efk9dvsp}R_6?eqQF3+@9mV{dU3o8}q z7<{^Ajjj`%BnvOgT$<2tz&*#b$q1}eZ;gd-}$N^GRUlA*Q}<>ms>5*dRlQJIr_o1paV#5M{yby; zG%U2tgdjK1EqF=3vfg|V5d|lPO~Eh5C|U%r(C}5rimcBZ8r#D>u$omEyAq?hx@Kgf zjDxQ#vt_wqkei(>^nK>ZS8(LxS%*f^#E6dchGUWW$`POs2J?~wI{*NK{|Jm*A=7GH zw3>;Cbt>O=F`XQy!-WCuQxXvxZ)QcKm}xhAyc?sTn+V`9;#4;i(UO!o3Nmq3SPOa+ z&)k4gO3R2_-`ZZIWywL5LVPfXfjioJ2+4-~kpn$sH5$0@T}K*{reTyN-VJJE7W1D~ zv#3}>am#|=rJ>0J9=nf&*U*JY{7HH6Q*Njr<0PU_AFg0 zf{WR{Azm!?G$g+zf3_m<=Cqf%9Z%@sa>}PxG z(GtF|A}YAv%=W_ZeohlwtHj{x3$^Ik>#MN4fv>aG{c0t(DmwFM_Bwl7S=V{>9}VZP zn>d?C;lW^J8wmw0Qv?a2SPE8@q>4m@C@kd$DE)0^MB##FM3H8515;6qCfvYRq}w)C zs{QV3&vV|aMl%EWPe=%U-gAEEFuV~lht59_M~LEAiQV;d`ZoVF$DF>Jzv^^iE0(ob zI)s@EjOEw)8n*r+Ty-@f4lUYi>wLOi&qeX&e{^d)T;$_f>dy9NVvR!N@bZDiyGC^K>cBEkne}yo_~4r1jy5 zO^)EzKe1=T$Y2L@e0fH@#$Z#F?V2txw}tNHopg001f{Ew^s~e76fGK9P<`r>zv#A8Gl(sXI^~I ztXU@}5-pk@YZPxMA)=%w>=M=1Llmg06I&4K$8G(&tv(!Q*4n}e zXNg?YaH=oTwQXhn+HMJ@`OK;HFtc%j-z;Q4sT%3$$WON`>tpMmB~2y~a@BCSlVAEj zF1?cBPFsnLl~n6z-C;ljRdILKcCB84w$l=-X-UR0HDI71h7z<(Lz)_iEy27pYg3X= zX-lS=%siDSehpd}+c5&hU1pZS)WQSU*2rXzi-V1}Wgn)n+96H7e2i1`8N}L)Ni*7V z@Q{@tN1MFv%N4=j$@36~F6iK;R?EV0n9JlLiWU5$@3xYS>)e4VOW6S70=>(YBKH`F zV=;^`*>|onrWKen{~;}{^=U%OAPa={J5&#WY~=44-^%Y(vRL5Tdx5vy9&#M&4@t1T zU?xO1=}cf9mwA%Qp$SuAz1yRJ{yr0G3t^gypfn4ZCQHTqmx*%1M)JtXxbKLQ^s;?z zFpDZC=oLKdh+;-0Ws9+mqnp{$wYwcf-!ZXJHX1Xv-LY;k?N}cON%r-6<37XS{)CGh zXB7tdLIkQXld*6w2Z`6icM!{dwl9Z~1J6>n$lD3NvQD4q=pCV`!=!hy3GJv9DPsX} zfMFeB`}UaV>f7F%p$9EB2z2kF%i%H}^vBLg4JMxS;vVmq8P7%qN7sbOtHlXhPWPVM7EO z7QZ8R2mieze07WD-3JZ4*+1?FcZ0ikJ$!cunMK}-bnkwDC!{{!Jy1+~gv$HV#!xTvFE{$$YIc`?I_?UT1byilE1%cCp}!>5|c(QFRq{77CLtEwpi@RT}d84 zEk?tUB<+X_(qc6FeKXSL>D$d{`tKncc=U8V)IQo}`W<^7j)rfq63L8%)iauPIA4z5rqqZ;SYS+8YdR;WB{~j6-RO0BHC$`Y;c_@%OF_?v0<9!2IjgJT zHSY6r4R7b`tMw}>=fCDxuWKE*y!uGw zZ4lBDeZN7pG|iF_nEVQ13`V+a`d(GjN7R8KZ1rUuEe=JAn8C3Y@kNM*q`qgL8RxAZ z`imHG6+X7N2%DL%i*3w2?0T?Mxscf+gIR z;xZX4A*$7l4j6rOh|TSB>o)GJaLg77nw?@s@A6x%yq@dGJ-6*y*Ek2GCyWP1i zk8PL{&(gY`RaVDZtCYERYzuI_YDI9ZZ-{V_N~??XC|O!{Rqzg&2Nyx)u2R1w&YhQS z+UZq0>yR*xKo$SRJ%E=<)Vjs&0u;1{&PhMiaard(CmkV!4Y@dR zorf@1a09d^XG^khUfqE1n7 zGp4l^!9OuR`bVb%pglb2UUV7jc}-{zp^y`IcE^IUtHFB_@^WzLX>v#S>7it?uJ^a^@3$M_mBJB0EXL6L$>Zjo=(FxJ{oMd(_HyBO{B-;9 zBvpKSbN9%7N#R?@zK=JL`-dl~UYNWPYab<;7os*g_xIb|;{pTv@s0k`A4}oi4>uH# z+(UW*wN64i7d;w1++6FAAAAys7e?##jdb$@gLx!*>{OQaVPGtIJ46qM1QzWjF?skp z8oBqoM((qd!%Xz3E{kfjcUH27Voyr={M^IQIR)k(k&C*`t5faZsMDp;@RAAQQ zY+a6A2X?yZYPnu7|GE;EDgCcO;(bADKP{??@~g^5~s+ef8wsFawYx8+g7XZ?3EzZZ3`fr z3UTe055E9^tF2BpBO_hvKGmcdt={_doo0RxC8T>2&p+?EAw5hbc`(C*g(ZfCI7nD#%;AdzRZX~YgK@^?S;VB8L$;&VC`K0qPe7Jp%uajBGW=9 zuFdzSb;aqZ2dNnG?dV%MqT_|pu5R^=x4(iaM(oy5SqeBMgJpM~_V3vNEJv*{@j+}? z7N7nE6Ea!4SEcn?Kkt3*2 zK5^lGuw*O7vhdzidF~foo3u!4^Y2gBXev)}OAuNX%^B8)1bx%Q=hPn#Lt@_cG463G ztaglaJ?<^@kj2--&f}B4%JbHPV?1Gh{Dv2i!hHj7n=E`D29S>(+45@CYg4M~t{G9K zZ){MDR%md23EmfaYT3a?Qev@cL)-C15{p^s{%_=fG<4Rxvxvh-Y+z!;{jcCcGwe+` zF2eTK+Yt)KiR=6RppV>q4Z$hrJtBY3jt9=L3@7>$c#AEJZEc)qIjrr+mqWkDA{*x{ z3oHc6ks~F@UxSxZ*~*O${hf8PJ4c9XKK8;pCUh@$x&VDi?`B_G?ng$ukjzxfHyv&k zLdQB_7X|i9B-7Ik=gX3T#A)L2)B&36a;0sD0P~1pG6HiPGSak=bgpbXPWr+pyG;6F znoMcs_>U2hTM-OeJK8x7 zc(xKpe9@#C41=a*h=h$u-bmk-T7(^%T8#>WVp6;JLXSQ2FreM~Qz4$z5}NL9@Nx{v z9Ub&(VBB^^hv0izX=uTpb0`RcV@&*JE(!*iZK^S99~=n z;+M9Nel2ZJ%~6v0Q=bc=!7WKUQr_O~-=t(fGIU`8Tm7 zk>0VG?vrTp0MC_}E(75?_GWbJ#XuN5*L~u`JrYL^0Gbr=Xfz(_j|lJkOqUBFbTPWa z?qbnv(5vy@6P(t68K_6Sh0t_H4@ZOf?_zNl^VR;qDk)%5U+Omo4FRXnwAVNbct^S> zG!~}zuv<0GJ*4S(p>e$d5D)e5JivYR_%Or^{rF4{c!(YPq28~1uuBk0+u6qLzSF`? zf<AC><9{@P%Bn}}(#@g721iT$N+Z#Wx(tLvR#O8d7!+cXqTy=@3^%o zs}Rc+HVbz3%h86-rNi&hjbrV&5Wl^E!kysY5^~+LJQueva9$mpC*$gbfh{?)-1S=e z6tz&>rrY+$D<>NT@aYi($B-A>siid=ogCP;yh5`LAWt{8bva26!0TIvh~f!Hut(<` zJEs8FOFIkG5$p-na&*GFP_L>*XNqwlOgik-H^Od1I0??}g(cs~#F%S++f(7TaWwXD z*p6ruU-)kr5vOL&5M5DV;c{w0TpMeU=aeZ=8oD`bkBqD)>zJ`HopzEqn6TU_6^A@8 z>{$mh5hfeJUPcS@iB9G#qL}&6Gmoc`W1zQFw*wgigYtG zWsQPn*A%3$|77NyB!(F(Uz0tB8+z$>NE0X2Yv89ACq}Ji%J#iZzB#Wo?XC_&_I|x5 zpyY0@%GKQnW*+d_s!OV>33K6=BSbZRl!_s@)~qI>1&intBVj$J5(znZ5U;J5!F^mI z_S6)pLwcLv&|-c^WSU&l0gWX+RKr=tq#4U}jgT<;U)r`%kC)COU7M|l$?l%_L|lo9 za}C@@Gl%{%Uv3dpsBygAcoy~Rv-vxtU8nNaBk>TD9VR|+m z{aU;uNspfv^TDT^H-OvOU@#jHV`_*uFBb1kBn?K|Zvn5x^Q`}7y~Vs?KNc+c{jnid zto=q#0r!XrGZpUD-~SyD1g_JRH8}U&e$}h%4k&T`Q84{Dc>K3-YxHCN{N9J_LVxST zgoWcnd$XP&`(X4VVIn5LBCLTGQ@_zijHVFFxQo}SfhP+dOmhd5-TE_A;l5|S!{;;Q z8z|5BJ`Qa=y9jIeJp3!u5$6yvQ8*?XE{4zIlI z_O^pN)7jw2r!Iz9S?)1!&TuTc_wn6ZvqT%R_+HDQ^OwiTdJ-f`oh`MI_B{JkQ%-gO z>$c;Q?;(^13cIngYRfH{x8SmANG-X3A$9FiF#R}Wgy`8xi;bs|mwbD`JOo$6ER=6P z@~u-f+fIH$WG4Cw{oAILM1j<|V^D2z{T`^FIKUB0h@=s#WGA5~eOWM2yvtp(LiAI? zZ@Vwk^5ymI6$94W>7{)An<^}X=dSZdC3D}Y9&8W}yT3Y+B>X)w2kw4|BQw!`Ev-v; zv0)WQ0rjL?+W0JBrM$BE(%bKzPN!)%r+wr0v2sDjkxL3F{lia=hs)`e+)@hoGAGv7 zTOj%ebaooC!q7HHR@a4A9pbU##~b^!DD7Asv|b@0TzF{S7M*p=RcDK>t(Y8yf^0aX zc5rQ}A=3tGPgp%2Qo(ZS&xxR~IPt9$-$3b5YG&Bw15VpF^1qXGv-Lcgc|s16_H-A~ zV{4Il5^Q*UlhCD&wIR1gc3fX4OW5(o-|Dx$>}mU=Mnk8+UnX~5I)@5DVLbekWI#*obtjvt{_V$3SxG%kwH7Y!;C4;a; z8^hzB?5)OtBc830N6wsX!mlj6Hz+&wRH-^3?5TE0`?}8x%MxW;(Y|`E8LKT^M~P^n zc1LV(tp!vJb`#pQnw;e*(Q01r-5)L0Nz_5@} zXiR5D_5S+k*-fZ))3IM@Y|8~%%ZgLOtxv%$TPkj_T(|r*nc}0=OlwPszH=A|2b4&>pnrZNO z96Bk5wWEdeN28}6Rg@T_5tkPvfydNdjYhu&sSJqmM-OH_=Efs>DaCgefbc*R*kj$1 zAavBY!!3E>LGSA@1dKKCAlzz_6g4I#d8X53diW=L$w>7$4G(9M!(i169CE5<9h{U5Vm z*KrIHsLy?yqaPm5eNTj+|9P-W`ma!#di9!kAKcH5<|mbVI037q1?j2>wg|`s2eRbK zL0^qSFP`H>;T(WAX5UuZA&1yicmmjs%PQ%R=B%@cCT%wrIHJTE1t(R9tYW^gshXCJ zNuF6dBm=^kFwd}IwK;X?VGf7q#`8PhbQyHpCDCZxlTD|Hw^fC&#kbl&j0O)I%M= zo%|@#M_nzaE_hs(A0fMYIu=61>D$Zn?X~;%@;3;po28K!h%JFuK`PFG)$<>QBd z`}L$J7e6k)^cXy(Ma)79h5FfudQ)P0eT9PuTy z&-vR*b|{sB`vy(9t*>YnX1wikqsrM0LyfOMSymtaP zciLC#-;kuSS6CCrdKlKTv|2IQ3GFrshl_c&mb@J>J#yVNOWq`yBSGlucbtX6v5`3# zu(3#se6wMbxuz;)j}m$^#2Eby$xjV*X8z~u$-thotm(yf=2>e@ZkPZPHZT`^2s&=P0mUWg*}jagq_FemC_P#N_{II)B~7*)@nS7$XA`3RtEHQiQMsC<3ZT ziC79txdBR_4n*OC<|sv)lN(4y5fN@+i*#R`YO9m`I`f;?XSGWBV;hoS&pXdEGtb{9 zi2@jpq99(T7>D0C4FY6b!@?^B)#Ph=P2d<1thw$D1F7NN5~kZUBjwPpI5)_>pb8E^ zp<=cII_Y1D+4XvWj&wrkq>iwo@LQ)ugRlvbYrQK0FG}PMMdav8BlWnWY~Al$_SLxV zoZDeSO4dgcw@-tLb*pK{8i=W|_39=x4dKx z8Z-|Lq|^hVF#A`k&5qLg6j6mo(+n1Nn*E9l>p-oI!>K>@t{q1C+1mV2exCLF2a436 zn~mr%=zE-94|WZ2ptY7^@vJB>CFuJN;M!WPEq~tJ6GkZ*=Id(KIy~r`aCd{!YJGTE zuWpzsD!RsM{s_~!8 z4gTRa5m;@(H(INIA;NM{^aRng`7ab1q!uM^kAEfBDbfMfxupeW7uS8<=d`EMl32P( z>UyvxM2_dNTqAXnI0WTIuB3&$=hP8>l%Tbs58zDeEcUjkwbRbw;fiMO24ysxlVV*J zZ4gfFpUkZ;)g`lJlS~&q@mXE0_BID+Tv;8`3lygzks*yq)F29Lk%zz|Yig^#Ai#4N zV7j_Q@5#g}_i){Pire=rIu$yYi+p>wGnM?|4oMXBLjwz*Z$o&6J*qTW3x5~H5j?T2 zMrYc?FI0j-yV0I(E8A|XXFVjiHjVxA_=Tq>rlY5ki12US|4r4|snE;qNPPE+`&$v% zlNc^mCFAi60apcV_!-TXBPmbC3-DWPX*H9crMDzXOdz!&|Ab`BO6R$!E{t9%H!p&b zSsZx2FTUoX&8wpeK#To;OL@8I1P9g}lDsJN8~d*4it~8>1r;qsd8>+F33lPLEA!g_ zl-1$RkY+807L`NEaso9*6=i-3{hh2@Xl~N9VC_4jO_H?IrIt?jDylEuEF!#wR1SN zu|Fs=qB_YkwUxn6|G2jETS?Weqc?)XuvwF4*3o9rX%qr9F%dQ#DGhjgv(VZV-;2qF zw}zQaNJ?h<22v*oubA9`J6QW!AqAm5TK^2IO^$?G0iAS*A<A3b9Q>f-;$>;wUXPfCLK0xu z27uL}2ZT3AWLOcTb!`y3fvyXuuwx?|$AJyV&awhU6URdil4~nz{n)5`j5dy}a&pE| zz`8@14C!rJGsR=Ljjo8c;MH#W_J1~wfbug0&CO4gS@tab7|79rQKuf*aYU%r!Mf-M z^01BPGhl5(mZc>E8Zb;rjZdNTq0uMis+MSNHlN20Y0$WkM0=@6Q-xmZ-Y0Uad(&GY zp{X^uR%CRDw7R6cW)j2d9z)V*bm$}w8ov`E@c4p28XgN52AFT!j~A5CqQp0siJpCY70zN@dPFHr4|wwDk9hH) zi=#O7?-vm<$#oa(2Mu>lLS9TtH7fSmu&XRMho*$%A-WLhZ`(#ZV*c8=zK5QQ`a54W$tSs8CV!IGTWDg zwYqAj4)*WhNa~(*3YMLHo>plk?om3{A-6UNsTR&(b6!VcVHut~JTVsDBFduLIyx+<*V_Y?5^yKw(^`Tl|d$@7pF^ombU+m~XweSf9`?VFUf1+f3tYcH4c(P@M=iHE*M z4*38q#g&D`dz*%zmxMeoEs{nJZC*>48dWxhLW$2bp(lto!bKI8q>PfGK+pb%^xTrs#|>jM3Pu}BP%LZ`*pi`>d(6jy>-t!q-E z$x)U74$6uYD`Z(h<4%!xE27M@Fu|ci0v0{uu9sm|R z8X`Ju3DWyDL8jCss_Q{1U8hA`f8_>{b-+eH$1}%uDH;V=Gmz@qDulwSVb&VsMoMrS zb$5=U%m~?V`ODp4+EY=Onvi1AjjmDYqYNxu27$)u97g^QMfIP~PxZWx`I-xljg`(Y&7x9DzG**sPxUnAgA#`akn9hEJP;4=pRM*i5&?aX;6G!C=-BqPF<5W+Rbh&q|`%d%roX zTWbtPvjg^{_2yIj79sVToM;evhVSdj-Ai|9J9|5SoZd{ePPXiP1dYtuAdN zwLtq;kKgsgOO3ug)Xp@0DJZvl?TbMAa%sN}>CX;_Q#!-2T+*<5uL9?>!>mZSg3+SP z8n!`I1k{u9X~KiO_bx3*)MMAijAc95r+id4CU0>69~(Ws4hmP z1>N4CPmRbgEeN7Q1goXz@M=l(vfy;RLb(35&hIkq)Ixx5Ki8 z*AA)xlD6L=0Xh%mXSB++Wlvv>OxWhnqQ@f-MSv3**p7i!`u~p@aaUc$?qWJzIL@fwkp1U{9c!-k& zpAkYC(dR|x#18$##k&wm)vqf1E(qChEJ7zAC39yxh zR$8UbgNw_k8xlC&+KsJ&$gH{w2pfkij@lIvVfwXq0PxmHR^ksd2@WF)X#!JvW^R*H zZ=6*X|Lq37lTS@on4rlHz(Qlu)Y+KD^<=|v*8Z3oJEDX0myu{Y$5$OgV>qtIDa2kY z#P?QYy88S-p3Yx4adnI0*ZwdvMzR143L~K?mSPJHR7i}t6i9giN~Qx*P|!pasqzA; zC`J=rV2bHZn<~|v_qzMHHus+5WC9M8On~*Rz1JW8MT*r@V-m9Dqt`CPo>vP_Cj|4v zGB@Rk4g&~H`iTf~*fRO`i8jXK)RVUq4q}f&99GtfC6&%oHx@_1jgbhSx1l9#MxIC_ zCYVgAUck0tgj77-pb2+}5pC)P@egeQ`~Xh(Q^(L;IxWrsfT%t64bO3WWYf!bxR0dT z2ny@t)`~w9ei1-vFnOCx&SaN`_%Ea8{w>dq3=^A`5;_U8izDZ)%%xVie$h$y{VqdQ z3`cP8{G+AB>eNVV-rpjuB9Tig-n^x8bF7@KqqAPJHrV;f`>U<68XmOo1!`lgPR4W% zdq3>*Cm%#>i_Aut2X-K)n()8?njkDBTB}Ijqt=sV&tz53R;~H8Ww84+Lz89D`(z)c zv>qL1KM%8y#p-E}LW?Q&3^A8oF?%eh0Puq9L6p*Sl^y}hhsVWqu4Y0NBdI89)-?vK zA#}G(1p|UBvas+5KX%L6WKqfhY&5$&D}R;-&UU3|Li=hM97c^b=)#GyB|YFfVk^r6 zxn$HlXqT^)FpS$vSgu$y``mGNJSoRSSt;`Qp%u*yUwF~_#Bk+)7Ua2T~tSkrf7tO zqd)6&qk*ph;vUr%x7)|_c|CgHoGuK8344AX{TnmV_vh#DSdum*Z;S-dFNmQH#+B9~ zFYvd``{-q)!L?mLA7TAoT~yAn-n`c;Wx(zN^9U?kd7Bkn_6Tt=Ntty8yHn;eKcVw306tC0kPU?Eq9)YuXj}i`g z{OvnbzzUFt;O-5+?0BYXBS2pALA3{F95B_bFx2yZn4yGDd~XXoPOim0+F5BIK^sMQ^;P6OGSQY~`5i40ck z`ita$F_VtSScwWf1Qx=y6YF$r@ExlSm|%|VOMxAk+mjppTLi%=}wjlGpnGu^$6?SPl%S%oPTMkvzSDP-pOzxaMup#QI335kqBn2dkJcNNpUEZpC6a z2SYK|>PR3tmUg@MBkw2hF*GG70#` ziBUx(vHsG~`bh4^EzOT;skbC&9LL}E*Pj9lDI zJuuEBk|Aj_vTJU19<@>mAzB}~ngZDjdxavlU!p{)fJj&N&qYZCeNqa?-2PA7!i;<8lPR4@i^G(KFmfwE zbpZq~CiDNyXd6`W^CQ|Ud65u8PrCDR@;0A5zLhwPelm+Tirlu_240^84jVSBsG;o2 z1`I>S9X#%qZ^n-eH_OGC5XuRl+x>@BW+1gB`07Em3*hmXkdJ@Je>T`OR^08`U9Ye7 zEcA>TV+6K`dX-n0dZfX4+5QFawvGM{s90G3kZ;&NS*p5_&+Pgoh9o{1HSWQbdnm6I zhqdhe=urnOHP*lES-6eRG^$`E)nMd4mO^o;Y*>QpI8dh^PASKqHb^PFG>L}6i-8rY zAyicytu!IwK2Xbc!L#b|aG-rr!8onyO5ad&mB&p|-DVec?!kapbr6z2)Y1E+t7txp zX16=p{nyjIYY;B9V~otmaf4I`ROW4bk0!S|QIkXn1ZcwYvXktMT#=K6KugeD4L1Na z@k|E0^&V?0;m7QI4WeOm>+@!h6RA1Fi$|K>65v=@`+9?!7Hk?B>Q-yD5i#pkXVKYf zfxj7p{X^KsGh^r%`$!BH^}UA1)Gu(+_tDFX#L!5vRL0;P!XsK4m`D>$`C{M7MJ2%_ z^0(ISHLhYXSxtmSb@#Acbsfosv;jkj)X?hpeRM$<&GF&1mc5GqMr3>3g;=B0MVXZB zlos+kZ?!*R2<~j)$k>hQ&XAQk zS61kwVZ90wMHtO5#!dn%XqG^(+FuLWjqrQ3wr!GAK|EQ3ue+!V8GQLto&|+u@H(G$ zb`W57SR%zTtj!WJVIaDxbn=rOxM*B-P-$$PNR8!bY>A2(kWXDT4p%6-1c1tT_H<}j z>v%?!qE$EvFWkb!%sFGxa^J-$z%^5wm)Zn{-EmPU3$i1%m5!tK+8g>jS(zHz=5W1t z{@NE5UqQtv5ih+UmYoDQJAsED8T;iW4w*Nu@CY&6;?(WPaBghD!DU>rY(lg#FzvF3 zx~29BujwfB2&|wk!Awb%is?}8f{UTk%qQTgT=4m?yuNBE4B;4*484v2GQGZ+9id9j zRJ_33jv_!rrf*(~6a}v#ROXjl#*r~y;dSsKG@d6{N@oEsiWdq&GGCWt9LA*-J{V3L zyk$ot#Z>%8nJOUEU_@oH$_-svMV=LIVWYG5eSJ`d0Ivm&3B4c~D-w1xG$u+q`m2J& zG+!Ae+wCo;-dX;)#p4-uCI&OdTFf39*re|_;44znGsQ+6I3VOJQQiEg{w3zx{n%r& zR_M7%+fwPUQQKn#SSm@YuaGQJV+7EeYYUe1mFkZ`R}Yy+|19y=>duqU792FG16 zeV)xrWLL&v89-0j_s%AE*zPn(<`v}dI6^Vw1l0Lz=(x|W; zNw|mXk~d{i8j{l3(EX?VCQ~rxq_Qo)5hG{fC`*?~kC9|e+Ji?L6}k`I!MOZ29<&$e znqNt}VkK2H&lEC#M)OGQ?@%^mk+-O?Oso7Un#A|%U3D07(64x z64VZa!>=f&)xxj@lzYE_XaubQR$f98&q+ni$V{L5U`V!LDJ|p-yh(ADsnMm7I78}4 zZw}A0uO#s#NdjgQ1$J=t;xy`YA5a@lLnm>ZLWR zkGt2&T^TlOddMgnev{ZcDfJ7(Ajz|mtyBq|Pz0baV&aT3cyDjgpFOVwGpN(C=LvlrBn>EAd8t^qbzL6%28V0min~{CR9wXD`ox3-ke%*6_(ug(NZ|hWm@B-4tn~q2Y-7)M(U1hgjJB{HES}G-`&@jlsjgk$db`nI{ z_upjp8#hM!iC?(d?{@ml8`!Gnl4MC@S`vj&+A~tdB&naTgk6Hc$hKThuQovvo|O{Q z$y{wU9EKCeK^G5ZN^UbmcLm{4r3WOXCc8=_Y!);rt|YmWG1Dz8UW% zldqqbYo57X!K;E3gW4~mB@1;j7@%Q$VBkzPb9SRMfqgTsM2B1Sn7rzfn1Wxer(*X9 zQ8dKLIWClDs~jxIYT;@r;5E1qI~;XV$XVrX)x!oQHd6Xumd;%_bu@~?gD=Q75(-#Q z5DB4JiY)|GNQpQUmhu9WltvUTXpSgoCNFR*iYO;9Fh#m)Q>B{oUbDZokxpj9CFBb0 zUwf|$#SWpuvY^QJwH%El48k31tzdx)JVsrm!$p5U=aFyYG`6v+skcTA-N za98lk1US%M*53jKyjst?zp3+k_c0)KngXNWdaw_bCIpc}tpbHc8neYWJV*e}j}1jyDv|>fKCB)l6FBh_)P9(}J}lJ$Oq;^8E4thz-D+Z#*h5#~Rtx5L@ zRTYg4kY6o<@70quyxgKF?ehB_^XRV12t{FyCHI&*583uU$=FL*FmW4()#PoEOi2jk z?5U@v@9ge@QS>OK|XRdpvPYDrU{^$ zRmGeYceF1u$SulLH-3V)rMrRCFJ_l*1HEY34yQ$#w-w#9#$~l&Z0yzfmbZbrihvGS z?)%WXCV1@!!RQIwT{ytaxSn^&ztdbSTsrpjHspSkWDyJmi`BBZ06O^+_ed z_t-)=@S6h^r&sY@@%Hfq)Ilr@3(HzK`QA;ZVE0^?H@NM)r1iKBA zL1n0HqvXrlJ|?V`j@97%byskUx+@jdW(MG+plb3=F5!{qX}Ho^x+=_X@L%;Dx&8ns zVeW2Wx#M|A_1%l} z0>BQein-J|IQKKKl5ujfJYseAs@PN69J%hZ54}7%QHO$rSsGA>p1tKu*lgs9S#ju} z6P;6#h$9=i9~0@GzHf%4P*41rfR5OORz^m}!QHK^9$Xa{hJ!>ZXY9KlPM$RjrXdM3 zYS0&TJO>vw6SYNBYZ-suA=>I^D6NRLNCq9Kf?;EZhti1w@*}-eaRAU z9bFb}pDzk_gk@yTv#AnH2+->PA&!HEFf5nqB!}A`6{Wd+;Fg?%>}al3nqUn2>fIgX$ft-UIy(Q4~C~A{PHeVf7d&Eo-A-EQ8ni zV}S9OGs6Ll?r#oJv>GU+axPKTYOq1$JdZ?=4YpU&96WwR?Yt2luO2ss!SnyX)&nbH zIf36EH&9?k%BwdLuBZUUP(+2{8v$8s3XvXG#&V7IqJLhiv+#9oP&~0a8pgi8KPYMg zf;*umNxXORfD+nZ`E~N|)Tr+La5^*Yt2OV#aC(6ZgSHCTAlwSKut6-k=?k?Buv~z) zcRxi8J;fz#{MJ6=RhiH|!%9Hd{y%)`-3_0H?>Ky^V4zw-ZG}(7U)|sT^Tb}5x%8}y zewtuP2=L{}D6sKet$b%ppNA50b%ABB^?n8e=D&_a!r0TO?-qa?1l!4T5O)$4cP2jm zqJ3P}K)rnE*&Vvs-^)vH21PnqT<2`h;E}W($w(Ok1HaDdSEd=tEdV)h3wk84sT~sz+c&TxCjE`?!h(G!)PbUYfMbWLkrq z7PM%!O087(Y2(utBCzZawb}cW`3jJ;KGtkTIa(vFYZXz=+}ThcJ2CrPo*q{eS#g$L z!F3@h!iPPyI#zd5h-xcT&ZP8+s?}yJLN&M z=vB6~I*z2OCa{OV=pZ@jSugi)-l02D0aj`sWZs>~*qc!#-jP_kuLnt#@H`;2GV>}3 zmt)AMp@}`hFCYXgpzroUPdlc}xkINTr z)=}A#0U&>rt>^nlJQla_lz-9b?@(uT`k}WJl6+-c`cGfMkhg0MQWJOjCTcj6B3XVZ zMPT$l3@Sr|;lm$nMT&|Z5N}C_v>_#xz=TBZRH{S}%PmnlMt5)`9J>!StrXUKgCjg``FXyhw)unUjwP z-u=A-*yk*UR|kXNNFmX;9q<8@lGg;|@HISM636i$xme3(v<9J#*3Oj|jX)agT`u25 zc30E+(u*3F>-9v=BQ#hF#L{Ya-Frp*Y@q!%eYK0zS28&!ggkdOSw`^OBNm#%L1V^* zUy++NVVrEdcnEpDT)N|2F`$^qDiBE+b)C~?#F3^2b{wlSykFnR5XC79vGRG^(U(o0j&pwuik zgrKRa0Cb`^2qesXeb+L8^aMku-o8o%Ivc}+v@Y6qi}jawc`^{ycV{4as&Uj*M)``A zi0PUUYDHj#T|Z_MS`h3AD?URKTUv3;U(Z|h_qBB97DQFiFLW-8Mco=~<3_5KB3a_u z)s&gk$(O~CGYq#LKSPAaKNlonmGw`eo)L@gm`z_#2s*2&;@8t5GQDATdJaTktb- zE2+5TyY(U#dw+Dxw#+lYD8awaIsf_oK)gv&sbgBlChMla+q((rmI*LcF0vBCcB~BI zOrR;c**Kr=KcbXs5@o}4fmuLmf6!L9@>PX8=4xiUcX%8M7z!%kB#~Q2x#CiRdYZ7lNtVbBIK9oGTm{>hL zwRCws$r{P1;d)mpJsEs&!(lbl_~JzX?f80(G%Oj7@^T)IjiVKPoCzp z_u;$My8js}EqFdu{sKN}vVZ3kyK~07yrkb+&ig`ABDesb83oJpe1*l)5{u)C9wW@i zaKCF>+Z~$z0-~ho?P@<*qhL;Vot;>ZVLZPI)@Snxmu%dZH zncIXr`EvPA=eXa(H+>ng&7`bCXdGnz3dF&j*Vl{&3SZDFa95(s?(YlW4tv)A8hle1 z$Wu!&0oLn-_GZ%?suF^OsLwdx!fD0x=s64;=|piId{#(Bb1|=?+KUrAf247JwOafWa}9c-7nT(|?Qr|cc&kOJeHBv`<%yyadm9}7Vbe9cp1-i)N1 zm{39A31((Ujcl5l-%M<^=4qF1bVI#pQhJKyICU&J&yJguMi%&@s!gTsd{E$cgQLe&%L^D5uVG$LG`r>ppmE8~!Y$|N8 zd$#KKv*(rYN#3hxU;G8PaaODO{JJqUH(6e*{FbBIQyNfd>TPwQHxN5E+z43Jdpnnk zOxlzUa&5){03ZNKL_t(N&rM=S_q4vT>Pr;T$-aa2^k&+8KHWB^(LMRR?K`ej_*1LD zEMkpil?KKk`6ZDMO67i27N4oCSX%TNr|_kZDxQfW1V*Xa*Ix6WKdcbL^*+<)Z@Js0 zw;ema<9HuaR_8|(U!3dA75IT1>0iXC`mxNF`FCUq_;C|?!|sh}y4p_*?WA-rtXSTs z?zAd1;{oj`-EuX)_)8xHMnnwKSim?$L_J6rf3Mn#vpm!_d~g zV$vQ8B%Nmyg_GFtd$KG1*E?31TG4|-bU1HAXlI`tM;@J&iZkcTjmY0jqGYJ;9A!t0 z(_gB*MV^c5p7U4g?>9N06?G(bhnQPvpQ4n6iSlNXGt)Z19yet z#1abtAbjM*Tr49AZC^HjR0VT>ZsHM8^|P&r4swaNOwF3^B92yIQ}W(JS)o-)S71BB zD#9%le8uQ;Tw!n4`mRYjq8@>ztRitW5{9u^)o^A;pg7`8BxzqRW>sk$XjykFmX@4S zGGzhgKvLN;s^fl9R`H}w3L`vL)Q)T!u^8NuYZ}dKSf$$uV0wK;zCTo3oPl;6U}UYT zPzGzo9kSR&pdqqok5^U#-`jtSLRra~C5m(Vj;%TL079i0nvkl>W$jq0!R-&qRhgdK zLPayhRn#!G@kd9jt;USSVOY<2ws418aU5W5W*cc0-tAoU$1y#xph&kT?G;TNvKEBpP@lRvyh5MsU$kKKSCiDEX7@U1dfVCmv2xfXchqhDWomh8bqQto zF5zumn%CB#`7#=en)UIc%Z1wa(z4@))fkv^wuHCB*38V;gtp0Kw+n+~G*WYV^wJ#s z7iShVFc9cw>&2vapcFzojjtt*zJFT@#+q!m!m}#p+Cxe*1$c!Hk<*w*Y@ArDgwBPw zcW@@Sq%c@ubR5}Hm#@r-Romu&0)um3Nung7&9>u%*lLs|vtw@SGhh=&g#mLdEAzda zU3W%lL5bog_kr+#=T}eZ7M`Y68F64F{CZtE9cT*W{QRD~RX9~W( z@D8aJ#$)QD-O*I$q;#L7f&ixYZ`Vb7BN2)Cy|p^fQ#U7JgMKsRvTAe6>XB8qL;^B2 zW*7IF3_xbK&!^3)1c3GEnKbuca6G@Rf4(v8Wr%xvBO6JOs#mLyH*agUdCwp_&KoO{ zpUW25L0jd^b8<&hZEN*--#gi7O?iSm;nV4Jz1edEa1^m){lFZJI;GVh_e zYe7t)OXI;3shK1~A}_}Fa=gmScsCF~u%Xk!Hn|34l^!>H`{9y}k>Ylaxue>nj5{rq zO{siwLJLKS1s?wsuJ}TmY22IXH;G#KX1`RhTneExFgxFvW7tn|rw!mzY!2C{HG3Tk zOj)QmtU|gFcv6kvdU(4NDvMQPb%G?$Vq9rbB8Em<(0it0Wf$Ix-W#G;_#Z`G&Z_Gy z_hO_Gk48AW&@EWZT$Hk%sje0G>I;|Smxn84e=yOAHogqEPa?)LYQ!Nh5CLVKC22R$ ze5%}EUn{Z_8#FhTn>mO)7&w5-p+oL05HZSC1KUy1Ns!4dmG~7xu}XGj2o-pw3RcTK zT5U{dZ_|Pn0J0q@AW1FbOmV+kkv5VVH5tODj~E-H#CW(OHj?=C+ep1|@hI8WEjsq% z$m4<_$B6`;zXUGMXXOcjI^`pe)x z@OA|NDjE8k#B$2;Ks*xq8Gb~auR!5S>^@_uYJ|*~!E9-)+-_9&l}yncCb{iO?2T3v!bf7}0)b2R@g6Equ0$n4^2v9uC) zKA#NP{)KGit!R4|q9w~l{pHi}iYd$F7hs1;wiU=v%kHwJuCyFkPsABrmOvv-lv(`k z+d~uO<^a(hH2>FaDe?$b<&|OYrH{7SAy+K}TP^&e`ncPtU2T7MU&OqE1>K~LOvo?i z6ghe%k-liJw~L;dKHJ{|%H50der0y1c>ezK<42dqv!V!pPzC?ESaIAPeM=(Ws&h6h zmW3iqf_n(zhS87=8Y+V2(XcoAS1gZ3nuuiQK`OD9iW1KT=8?FzEEM6}(kd`m0Ohiz z!Ws}hTUFUR&E#yx;#?{XoxA!}=4X4!vE<-XS->&Lf_5>#@iMy%s_e>YM*vh>Ttx5@S!&ptw@rE%WtcbmdD^;-*CyMD#yGQAbKJ#rXYZ7@#$9hQz zEuvaBQ7SMn*^?;+uIbl#tUO?9S?b?j`OGM4(FC&552lnNCeCg3iZwSmzDBX*n_Kj*c}LW6ikJuXQGnq`#tyA z!Ac+Y#I!s?!N&e{oZhCVUk|Hu*Z89LR{Rp?NIqanBLM0%^{!Q>+~Jt!-iWjUb#=2k z))e*#VuNLEvVcGB$CsM?9&tr648|O%WDWY)@na)zv}Bovw4F+@4SDTyWgg*-c2W!B z348!uwqx&zu+`aiUuM5s%!0GA=;Vs>CFfG;D|=AVicXcQfRtzBB633(JeYVKWxHaR z5s{Q*Z5F#tb}F1x3TlW`dp9UV*jvzrSZ~ae87phg4pOD4Sb1GSyNOX{IOF2nmx^@D zS`a=a1Y~Wtq9V>k_Q*WUgaNU%S%og+A6QoOt2CE&>Z^Dg8mr=Z#?VoSU>S-gsR}vq zt==r!=Ft{y!^Wk+qC}1AMAdcl|7mjMfGicvrmaP&_&^T}4&=(B_`Nd)u4;R8fMX=o zT|^MNMhaYoXRBTVV*jU#H$gTSMg5-kdMDzP!-sY1K0B8_C63X~Nb5%rJ}W)xP{ zJ-jQCLEPxArnglhum!j;g*pfX9Z5}B_iY5p*$yMaURq0ockAS>1YOe^RwO8d?QMeM z{zKE*>n4szQG9FzvW&?Q@Iz!~W?248yuB0H3U$qZVkON57fz-*BB%&rkc%lnJZX!S5g18r}r0qFrx z5r-N?lJiVRGNsA^Ci_Rmejpnx!L`#u%L)Y&oaIB;b15e|{ zC$1XY4UN4*dA0Wa#6#p#X~;10EMl%cPbZOI48XJJ(_n@v$tW@fz=OdJ8PGuT4ZXm( zWI@l=jCA+SUL?esySIQdrt+{vioKG=erT^+|Huf4rljv2STO;dxN%!ZxT!lw>JicX zPOGUj+eE>WeJ=s#Om85ZHmOqZyIYXBG3&j)CVo3@hzX2L-36=$R)s56J2fJuc7s(^ z5m;S%vu|V6IH`+-Tr7I&*f?^d$0dBu&&4@K0%Q+uC|)Q_LusQ;70<|6RMi5gsoK2U zHY{|FE8{$(92eo00iA*yjXG}?oP2E5#5>U}*8uKF%GI_#8tvSmlTu+I;gE=_wm%ly z1TTKQyp}W&E@%RNT^Jg_OzdBly)SAN>;gC@Ork%~KI2bf)=W6ZM8Q~-S5hWb-|)eE zCYuUcOobt$EVwSA&vYRwrwbKUc`OljZIx<$B(|$us9~_#;@FkjSFpTwdov>EN%h4Z zx#@J#Z`y=w0zg=H`HSW7v2FNYLferYVUi6=WR>V^i^ca!Ce+K&N{j3z1c|HS&f^# z2}vFTJxwG_Lh2%9;x!^w6)Mm&v@?M0yBv-^_=;!jAT!mgQ~D0ic|N2XUqw!yyFNqt zBDCU7qj8tY%*Bkrlv_#gh9_`<^;hQ9fzw`mx}(U`d-y8COckdLoFT@BdWy>mIQw(| z3Dx_{Sh^p0f1!e^kcVo1JYpR#OEIZcv7(-@+7x>{W$gJJ@qwB|=Gi{JR_0bGWNb9SH?n5!Q4#%>>bV#n)H6X_m%;`N^u0nnqpQRuZm z8CUTBVf;WQmI3GE3W=7z8IZJr5_+w0s}-wXYJiRX8pTD3W$&kk;YqR3%O^ROFd?z{ zHEz3Kt{;{chSN--S@+tTb9nL8@N_k$fMGe5eb|Vt@mji$3|}t>$I}&<`ZT{VdtOfG zx9_)eq*rs)SB$EGRD;&(`*1+U^EKwf~(@ zwfzNW=RBYqLYzi}>CNC|@O-E6XX+Lly=QmdXM-C?)vS;|Pd7uCSDgl;z$cW^qPcV+ zoeX@5>$p)7Fc5t69rT?&ONw=8RQOw*{!~B=$37akW36=Ay>J9~Z+)z6Si3chSnf!w zn5lD6*GC>%i<%?T+${mh?e)BiBcHKJc#`WnoWYRXNJR@NS`|BvGkESx1%vombHGeV z9l8DvN5<7zk~YR>|J=tNZ|K8{WU5 zzjv{yaQ1?A=&*#nv;%KmkLaxyFF#&itIZF48$SF&_*`FCXLp{$n)am zLrIqg#1sJA)fjyjZArl)#{%f}qWoo_otED>B-h)?+Z&~YAI!72UwnDY;otb??7Olf zgnkhUjr^JK_-Idl^a=*%*M-8a3*xhwD<}HXbz1KFWtaY?6cUm=71VL2wh=row$09t zJ7*k9FyWG>W`@&c`PBva}~qm^;~<@Fn_5net>Q)x2K zoDb)%o>eOb4LOp`f%&{ETzOxljHH3fEIn&QA}>+l$^sR9WU97Ajs?#6G}?ZPSpheG zBvgb)CiY;?)vl4x0DV<)%$Vi5VG#~&&lVy-9J>Z+@DuyC87ai246iKs; zQ3xN!NZVWKOn~M(JTO+av%bSGzT&P67{hNJd0;eOX44+LtBfhZ` zuk61=l+p)nh=UqC6KEW$J4tMr28WSBXw9rSRWq+KWGqY}fXb*^a%7{maSt4pKi7z| z7cQv$7x&WGp!)D<6!c;RV1%K^P6m)yWBi7!V-~I1uKsD47H zwIYk72ND|$@1HbXUcIvtHeCI!%t@oZOs^SBUoI*Dmd|&&oKBZdq&JfU4bi<&Mfe*D zmb6*(`=_a~+xz9vK-my_c<*h5?1!g@$jqSWNy5YXue4Uf`Dk;lGHsW(<*82kVakO6Oa{<>%)U zimTb|`|R}mog7M{uLdV0xI+qqhh2cj-OVRy9Wdb=g+v>Be*Pwv0<)f)7hNcaU+NW{ zQCh13)PM3hBggXfE9P0emlvZNS@1DNx$lEBH6uyYtcEsY9o&*MQ&Ye})=$`b>2ht~ zQuU_Vtq!@2n2RWrUc8@z(&F(BK5_iUGr%d5SbvhONmnn16 z=?$zV8nvq zEnUG}%LC;XAZ$4NOGD@{^v{ZLelxPVolp#1B+S7}?W{$F zH=0woN~OeHg#T(wc2?6ed{6AswksPfzqYN$$rBz|N1=AaU~5InGYj*rbXQ<0byG&l z3uTIV|1a|eX{{8<%^Dyt5y`bxTYaFWYImS*W7oHA7Yeq&sxWM+OmbbtEN#JNf z2HIJH&qS)LA=;le3COOiyrD(71kg zpaxDGM1fVRXjJ7$GYsl$c~T`tBpV6()lJA+L{V5uWX-zbUnRk1ij(Z?y`K4z7Tx(( z2KuD0iM7$>%nqw$ROOz?q1q(9(uiv3RhRyKG7XW{{-^DAhsO3;t`{uAj015Yp^Uq! z;@vUdD&8ZFyV?dZX!)C>E_o}^#LG9lf14b{k-^En=G^e zY+&oOhA-FZYlu^9zHzPYVIE?iOeK zKrkEYqa%S*076PkJvL@ttFHG-IE8dr2F8Y7#$I{C|LmFw%%q(u9Q}#)JfRwh)c;Wb zt!?o%G4;LTFOD>XCRDOM^v1QqI9T(BgmvHqwzGpq+V=7L z!ziftU9dCQNsDpV({OogK--f@I+Vt0EtOTQBn_jy!6@$e#G6w9c)zFocYht@F}e~m zd05vdomIy0KTqeco4C3~@v)7OZ6pL(rU+6r!V*RiP$6Z6Tv*}-TzWc36fWFE6lqRg zU@D4H!V651?zX9JHRrwV{;iMPnR8|mLL4#yFR#7V9~BZ3G9t*GN{glLg~82#WOww` z1Uy)w%Q~#ypALrycD?qo2k`gFfO@bqF8s9H9rg#xk)XcR6z(3jf62+RoBj?cJTeS6 zpx!_%8$tAF&mD{nE9{D} zNh%kX!~N^%ZZ%r&DPp*XF+*dAudhRuAmQjWuzj5k7bIm7P>JtobpOH{nCnkr=T{-Fu zfEE&!6<6bGCKQ~e>Soc}H*@)S%D%HRQQ-17)QzOxgv5=T1AUT`DWR%%iJ!aVdnFUe zJd(tXiwR6`h9g&)+8Ex#mz!2hS2ajk+8R7lIoKNMxwwgQtjq-$qy)*alX6e|Wc+zS zuVX;0Vg?F%a1a|1$7RAW8pW+~H_7HDS5OgBh>~Uc4jY(o2uGAXPa8~ ztasT3!Y6xG9g%uN?wj+ltmgWzWTp74M|ImG$La7$L6%*% z##0)_QCew}9JrikwL2&YTFWgROn*nHoz%=EfAN(ThpQi+)s_t~RY==|8#1#lHu}qenu@{)N*EqwH^Ldr{CR8l*)IPsANE8%@2N=oZJ4{< z{&uMxbS;ob`CHkO_piI~;ZcKc*R+pn?a1(gbX3aK3ivBs(&XOP+#iJ}*amkBOoIvpN`z!;OLXCTT$)kvC2 zKVkqLK;gezntbC`foz^DR?4vxnz%Imk+Lzly|Uc!$~hU7XXk6;oP=MEE6l~Bz=hqZ zxKJk=1poySs4%e$8hL=3BpY|gLxuAhwN)M^;eO#Im4;ND7^(~}art~20OrDE1UI3& zj$-Mz;wH@r;HX;OVN_XUh-uW>&MBQt;g&ORcTvJ2pV~u{k@S*=n5iOL2 z2wfKbS7%Bas`c4ud3h%BS;KRB6U$%KhMjVmpV?>kaO6_lKP$BZ{`}y9+c$n*_i@?c zBB~l{7An;rUl`KcKSjx?xyQt1~N z>bg&UNNYnNrK4O7nMt+Gt6byfOA|L3fzfgqE;bi(qV?mxkV@4y=(qU!#+@=O)2?Y! zJCy1Z8bn=L8nwb?Imxq@%|+9#lSX9?p$xw%sW8p0U^;7yR2_Zc zbn2iubAPc?B`_Lc1^hVm6CPdSe#_|_2+Sg-+<>T|gi=bDwL{j4@^l2so}9fQt=tsaKolqNZpCO?jfAW1?qTn&!uu_i3T$+-2*1LH zmrI<%MuL@%h0y9%QI)UD8I8aOxROI}8A99Vjz-3YUx(^BVjcV+`*Sfws5Ts@MV>7v-3@zR7~ByLkYg3KS82yHAK&6-(v$2&2N?wQ0f zMrnW!y2!JJA!u>QvUNziodL=vm!rk_UG-Ts%wpsD1rz!pRj9l{7aKQqmK##5 z<~Q%{JMHKUo*Qpf6=67Z+yL6&E9rMr|7-xOSAHQOaatKWi4qTKQ8$Y;Sg^M6={njSkFHs1J@qSJc3- zRspFR*5q!|EXo~fGL$u%G3%+0omcVZfr^3yd(sB#TGBOY;`$qS&Co6vk8ebv2cT!i_O-;-Yb|gpDM!7PWF?h{ zJwTNqX!)dLrY^PFX}J8vl`SNACFBqa)h-yh%z!WXvQ}E`OLgXORY%t=JXVc`V#IZz z6iW`sO4hYFC=6HXs&VS8J_5LxoR|^ZSV$X1SJEpYXA?T{Xs?K<#V5vNqtc;RMSbv3 zp@hn4rZMi2d^J^11YLk*%t@ZC!3wxgJf%NncN$GO_8=NxJy*P7T$f-4NQ@4TdJut_qFeHK4xbp$?!KB5jfv@-}5sPPuDUT zPZHAP9pYt$cr@BE<4<)L#rRS1A-_e9b6~l7A zTHV#FZoR6>;iz5rAcWY^RX9xK)v{hLvoF#(P-6kJ>H&V&KzjbJuq#q0WmnSgH>0wv z)hfGRPOup*vv(uKvius&eVe@xXK%w9wj%;JKC=6_A?X`$Z`s>D<7Mb@OeRMh&y3gJ z598szeV!PKqKeKKEGv2=MyF+;e#OK1m2QUkRiPXZVrVQTV3MFSL((DkB0{lT(xl<0 zSTf@1TOv46M)y^kG{xv^FdN%VULm_T(}y7~grG5tUv$ww>;w0|(SOFGZ+-}b4Vk}r zt=3HfTWcWl0Kq6mQ!hcWblnQU{4G1K+%2GUUp5l`0ep_TajRtD=>=*GqrK7$?Oe_CLWoBrG!;rQTn%K zffcY)p$&W04$J#sTM;}-ltXDeh>>Nq1h5MB|sZ>{g(ry2GZ$^U2dlnM$cO+eYaF8D6x{^!j{;qjXh6V6XW4cE~Hoi z=c(#{$$6%e(3mVwpn+YLBckfdZXQAaBR_+tkPNKNp zQ`M33yi24e`dfVEH(VIhw`q2XlL^?B1+n%41S>k zaAXDc6}90&88d=jn+%;?-j&)B2F{>ld@?!HUZ{RRg|-_s(Q{^~?x!jmRlhF}cUIUX zmq{S)l+a4647D5PcIT_1SSl&E76w7pt^oEMD6_%^wCxchbz@-q?P7x#38j|keqowNl%!WHGb`|V_@z@jd zjXF(N{fCUW;joCY?24Lj4P3vSIuh9xGXEi{5-3($WoJ%yR#0~%M|zoCH^`kkHL=hf z2>@Wq2f^&ldagJuLN8bKdSzeL2D(c{PLk5GQXioKurcKo-rpJwo>TM7GWdRdXBQh9 z^Jk;J@2flGz{{`MYPp)LCTY3q&$6%gp$Zyiv(?1t@rvpO)LHgxrJO4;I9uLl@)>1A z#92tMCbM^j(AliNGzL4NGpR3po@H^C(J46TPu`ak15i>63#bB&7t6TW5(O?<~Z(_E^ zh_=-7J9&^Z>EY&8@@KA{>MklGWbu0|5Vo8BgCZI#{7qS{>`%x_5&i8bkW$B74Vc1f zFSlORoR1^l1xNz3N~ldF*6>sINBhM8o95%*kV04Zf(N2i;*T<+lRY3CsvT7o=dv6@ z5kh72xfXRvpjiT^*Mz`anSjXGggviI7S9WY#DP*GGkz|2cZlj}gL%5uM@mZ42f zMGF_BoRCJIlUBgEf^&7#>P{|VgT3X2j6@P9wx4#xw%8nri>B88#qjs#lSaM87VVQ@ zXoIF$Q{ZPgl(d$$>lROpsTm9}ichw#kA}epvQJ}|fHj65e;*U*u`qz8(Rab58bZ8S zl(Z?0)l4XfmRbv+iQ=FFxOj9zt&MPaYoCt`Nx}{VTk1<8sTHQ*%h)*SRs@~(En{<| zxd+3|w%v@?yRa!Ggf5Rj;&%I_yvVJp3QH=G3T=Z~^=b`F@RtE?o9E-o{=|IXlZ|?d zH3IYFg%#>!n4G-7yC#4Ed5sA6e@UTOj$jlshv+paoQUsL!Fro*Q7mA-U%^9e4kkg(^Qy4`(n+znL*ODk5_o6tuQLgf%Qxj~tZkpX)Bw=FPmy40z=Eqt3rO^W z#C?fl=uN(O)EBpZwGTFLC>yi7~zy$#k(DM zXqa-3&h*_IJq_u4I0MvCh{yLTMurUUKx>cu4h2pcS!JONR^xFpTvYr9_{v9|Pc$yL z$*@M}pk-IvUN2H}VmJ8d306ltgUMZIR7Z1?p4XAuj5_PlwPje^tjO=wO4qUr*U=vy zCu$s6+XXcjD%)ceX>1*7S8OQETDhy#XUc_tQbxGe0J;_i<2b5uEm6i$cjxsTqAQY| z4S<*HpDVtmdO-n`2Ck6d8CM&g*7KQBVntQ1>g@i@F8Tsj6$`B_ECg2u)9>@_zQz=6 zD+( zYDBC}TXH$_L}ToMc=1VZ>qe+jHo{7MEd?Xl)LG$K#Tr6H>MjDS_o}M?Kh^KHVscM0*H-diH zu0wt<0A?ZGiw(Q%!yzAUE+t2RBj>U$?z1bLoeyRpZGXRuoxkxbBJYejwk$PFJ4OLa;hQo!>HrMERAm5Rlbqt>E z`jh>sSCoTOF8LJ)0a91&uvDD}r+uh4jdD*MM-SsKJqqmq%Zg5Cd;abD!|rWQF+N=c zSc8*_f2k#OR?G$U1Fs;E}U|pda>&) zxaZ2ZgH+?FP=wh@x@1s5A4#m0ii~_EglIRb&<+`fC>;bCVdP#a=Bw#)&lRl%JCv4* zt4rDij!O&u#h(3ZCP3ioc{{yc$Hi-T;>b$e(hfJ=u_6wCC&862_lUCMJAgul>JZja z*|jlryd552Vxj#rp&DueW*OFC7PjNSnKz)&&7MP?OK7f*|L#Ic0&zhxxl{6FXB2dl zY}u6`DhPh79D!tKAkifFoRG#RZR_*NS;war;8sU1Q4A#db3>PK-ZzHT_sTOhH_tD<25npjrWI zFy7$j2bR6-Gqm@-UQ8CMA|&u?GeH(T{d+#yoF`|5Sd%lnmo>57I8jX2dDEQ_yYq8T zDbEJGXM&y$gBe5jhW3A5S{smZu@8m?8wH+pyRQbqbTKe*Hl!V5Eb8^Uueglvd`Nva zlo7bsGayBPMH-gMk&Gkv@8l`Eb4WFQOwZt5e=^fD7~hdS<4j4D+^0XptJMGgIQv2D z75N(mzr+97w>^8@55Hr7_+>z4X6IHO#`mG>H~Dc5wRw?4&^6D}Im)3Bcpro3?r{Mf zgc^PEp}rN5GNld=PJX3C(R_`KaOl|^nd*FF`HM!LB7_S=3pK9e5z!b=E-D2ak!gTf zMzKW)cuQyiY3I?=8w}ZqPz_?&tnuC$H@ew{y&ZX3#->stlPY!FwN-2wz%p1$-n1?Y zT92x_(O?-pQEG^C;TamIeM={Z5J|;Qo~U8KsI4JwsVlTQZ zl}LH=k@7bR2X`+|o`j`1%BS6vsu=E1<0omUFFy^P>zDhV_=*gMpQQGxUmSQbCGB3= z9Akurv=zTgvGg41etE--VK#4RsJ%K|04mJO=+)lRu-31dO%4%k*w z2&B?Nb9*666I#9zl}IC+I@s@Wyc&gw2|R>KiED3#oaTj+)#A~C>?|qui<>(*MciK~ zA+pfi8RnZ9fX9+p7pl|LCnF3~4?S1=uh$ZyK~9Ssl>5}Th&y%@e6>V0l`=$Tg;Gf5 zm=xOXhW-$qTDs^kyV>d0D){;FR792XtYjemt?X(aZOhUBSrwScNLaY$Lk$a==RwQC zAZW}yL<4dS3s%2_-+>fo#F~YGTiiDmI0yPoc>8aXa2g>xS&FS>f3!zkwG!^Ab1ftD z2c7fpP;t?$fsdg9J_g7R!V^?nOysV`K38hiaj#9UT|)5eMrnTsp)q9Y0S&$}L47Kt zlPij-An=<)mve<6ZK!Q-2w&Ca_;}nKZ}x_WTz+F3dgc4Id;Cd`ik(7frF=-cR6v~k zEQXr{sK~pbK@vfyBb6~IeDbJqas&}q23EqNHz2B6i(kN*R$wALFd?zkJ<`3fmrPr+ zSjTM#_8TR}R`)6cCV+C_y+-+9F`xn>(Qx@{|0xMNLb?4BMaHXz;DGQ}#Yv02qgp~7 z!7?DTc_TFt+T94m8X&VWl4}sW9;_aWC9j_!9=v+c z$S>MyR=~`l`Lg~SrSz0eVEbY)ypjcYzImQckw`Dra|yHFf!ql(8*BRpN3ejF0rO-7 zkRqG**)w4LzM1znoA=E`L+T0AXQRu1tNWMaE1DW6=YOVMdV!~Ry|Z?|D5Zz^kp7{9 zp+~^gWQqcsSu`zz6e@V)GX)8Dj~NoIyV*o=ZP@zCN*HTWcP6lX6y>Gy2u4iD0$!zA zZ`OZ(rM6H3l*30~`RcfF-n$=CUeV6*XiVCWdG`9n_-~B!jaq8(wWCiE>za_5bG49g z0c_tES~cy}jgpMig;acAlNb7=XCBB?INrwDHCD~4;FdEB_6=p`$^cPn)(pDBHDUrN z+5Z-YOx7b-zZgkIo>W8#L-BcvH4K)tHdU;V@gS+6J-e_Z_#bOgX>`aKQ;9wYC37he z5#5DEJ1ikwXlv~>|CSQPF>dVyPk<9ZV;G_#EV5r?!h~<2X{s(2Gh9O-Ln;Gj75vr= zj#aYTo=BfG5ZqPwjUgq(SpTrD9iJ}u;~Uc@1&iJ9lSIyjyx*8V8xYq|K=SUZVX-#F z%iTS3RYsz7`Dn6P-Hcz zuEC3tLhgD+rS72mX~Je;#w534k2@$ex&c0+)hVM}dl|G;_8du3B^vfHc6J<< zG(wbm0>bPV+yV$+bX~k zYyg<$`;Zuq0ZkH!zzh-%OjT6GjM@%dnL-b84aEs%mNJTR!ojhl6>h}u+2g1>VyP;3 zP-X|i;oQKJ>9RyrAmq`3bFlx&SsuHB3vz3JqAhD+97bD=$h;7-(nM4)@@ITb-VN*o znze5yPeiQ=pWFtKItx`nXvft%NL|tvG>!~ow}e4&Kh}n}Mu>AraD>Mwk_O8-umS4o zVYQ;`_rcA;2EiK!%i}UqwxE5{k|oa!vJ>*^b$|GnX(UF zZzh}h^SX!E$i-JGVt7CIRK#FkjQ3Ilyq*}Lou9eE4vE&Hh8})@$GAifAw9qb)7{~G z`n^X>!_csoSu@U}S??2QyULk_K0k8P?1whOL+Ta`aJ#hj-g)1`qdiKz*l2Kf`1tyr zA+y0InH*@J`&fqi04x${LOG&RqT zKd>0__^1+^YS*J$*x09(EH@5ienpHzB!~+aP`aa0>nhbPB$91r;tBMp+12)M^$U^! z7~lE_<;HZ6Iwf1Vgmi-d!(ScF04djnQ} zp}(*uNfP|7e~!5s>a4_OI|ioP{na!9TRs^uH(G4lBM)>SDG;l?ELF}p_Axd5cSM_m zLQX0>RB@%Ex2Kk*&8jnIEh}i?kW>^C(My%P_~{7)?IfeI)(KEqGFXquZn!S6vw@n!_z~0!?2Z zOONd4fKUSJ*qufyZYW$xrEAt3GAocHDZB}o5mTbcG8-BDoGP4ys128U$s`nd4GJH_ zG*)sKW7uEKN_i4m{Tl42u7022Q_fFuXr%o zSE@>yYv?JK<-1fJ5a=iwft+Cg=0qkJUJ@ZooaNHK92h`qv$ z4C*MM=J#d|Vn1uQ7?AFdz&%VDLVdK`_YtiN|6}RgbyG*UD15LnGDbpNWQs&W5tgup zNGha6{1le*0+gPqj3_85=7=KA@B*nQjuKuW-LzDx&UvqYe`{MBWdfMXBoi;Mz1M{| zTT{%?5*`oxyB0~%b_0-}w-iXp0NlRpSRpU;w(C~AjXjFYN>(VnvbHtISw%DXmdyW1)D3NT)1&|+eGt#Q*?888tlEE|nUh+361MZDz1orwtbkN|j!Svfy6~Wkqd-qKa z<$s;KkB?68;Tdbv2W-_)wezM@!4D!gP;Dtj@}XyNI_UM@?h#Gh-;2=VGaB4KkL34# zcG)urdiXOj&jXIJXBy7_{rndqEH=Zqk1z*gPofQJ^!$TW30h}K{Uou#Js(RKz4a)Y zKp|MEyN+1?dMBCA9083-9@ArAE0JNTpFIgnD=|gkh1%q*g0NOX2fH#PRjIQADNAuN zNz0kTeFX*hzr4gz+AAWdTka^0DTTd42LLkhCV#Y>I-Qav|3ya^`Rgvi{>E*Pq9FItniG+5}@u*{!$q20^MV6Si`0cNyDSDb~wOcB}F44*2%X7 zklsTk!rN6vVA51C@Q0_qr9i?dan4lvlCg(OH!XwO6OWs`W-bmQ*_q^FkoMW_N{P~| zytqN2I&K1aK)^n&4w@pXE=^WOd$GRKZ0QnLmTkZ_yvVp6O7u_A)C9I@_-&TK=&T5! zR}rug@NIbQ%N?xQT#^i19^}#R+4bP}?ZdKT4fcJ4Hu=2hulTQ3ZDAmL5d@UHXr{~x z(P-Jrw!z z4kkHc7<(dz!ZqN}#7Pdq zeBOO3`)a}M1>Y`qiv^LCjF-vA+N~D`ysPd9r>>-gGK6FV0`;z9{7CoO5duZ9yw45+%ikiP?vIkI| zD5Q4mY4UNDab+F*fEv(6WaaV}bW)sIv^*Q5U8$1L&T3VvnnGSI(o#;ACTTTXWIAYs1;YJr&*X1UZZ#&qlio~Pq{bGgWH3XO}( zEI*`|{MJPkG^U@hhN3C_u+Z|9uSSi16aRalve6in>{d38y z;zE9OcHq(mffhL(hkT{?%B;Nd$JJhp|U?D36WSExC5} z>PYexS{bWjA(P#=t6Wscp-~k^RmIcBzV$u$vypK*P)gzKCD@54LWgb;;I#rayK)?% zQk11Ai@ZreDV0jbR3Dj_jwM|QlU+?g8>mXR-O%JwSTJRQbgVy2;V_OUsitFH2z(3p zcy_Zuj@`H9L+vEKj+;hbg(!1FJ%kvW8HmAD`;p)o@Repu^h(YbvEq(Y^k~z>9gIiV_N~PV#6a)G*SXH8NCd*zp?z-XD0;1 zp0nM@k~RN@>9>6A6lJzhd z)%HB6sThviG!okJJG57#&`{fb-}?^x_cdVd)?R!;QFsP3cEDyb`+6NvRM`IGaRCe4~a8~g1||5f>s-M5;a zU4^Bg^X%@CjAvuUcdOoG55Q#}eTP*T6z)(p2naKLo&l{0xjuTG>AC4ZS}}Vjl@jUm z{q#;!s~(2lhr7}Ao*NHPTLV$5jz%A&8TO;j^V@w-eF|@H12oPC$6hozBGH-sF;Q3$ zMC~N<$MBX;anFz?2a9oWDETwxTlYlQKlYoKQ`ve*0(@L1zo0vopZF@z?JG{i;SX$8cM7B9O9oZ1yu`1 zwQePz796XUs2h6dZrarRU_LTD7SI%IJlXe_()k*YrTIIu;LS;PU^;*&>{Ur>d@YX} z1j9TpONpTk6@lP)2F4R|G)~KWIeGnQjQ8t>0LqPWpig$^%TlA~d`aTuPYs_9eM^b7 zi~yI%4edu8_b0LaT|%qj!za?A3qifn-va36z%Lnl^ZdO&*5ze0K?P0)1H$c%R@R1> zzSrimVj}I?GS5!0U*#p&NIsW#%5G&xM$_b7Tv*Z?<0lmRQ0eC-U$F9?yZPZJ&~-C) z78|}E6n#}RVmFMwS_GuUxSLlI#w6Ur45RJ9F45g88zd@AV`iS;RbP_*maA@E*}JO9 zK^avdzg-PV>eMJQ@P~j)dx#4fEsSq`W~Q_J|B-Zys2*3B)J?!)bkK^I32&+@LnhnO zU6IVJUJ%KUQwh7q2hd72N~ubE_5X6_orPMsB-~dkr;pYJ+6(CsB||Ie0^p0>zvNb= zplLlECtLL@Va``*N386Nr0E6rIwU#?Bh8zY$0a&U`A}k9FYsPqAh_}DZe61Z@R7A8 zi&7w4vs7CN%45UopdYCa!uj)FUJJnV>OjjYwGxS;TRLPLeFxr#g!D<9=e_38L@+a3 z_MNZ6^;Qd9WkfRe9pW#hrO4i7*bb@x4GpjUuqO`L?o!-GsRQ<&_z#C}`+d|;{+d(> z57|ryS7grivVQkxR%T!wAWgQYLP0rMrv(vh*?-=zVtG*y_!&)Up@xnt>I^grD!-* z42SBD_DX=>V@>LR{-36^*G*jCqWH0mkuj1LW0?XZ6k!P?1gRoTcMgA? z9-2swYGFWZ%yyB`FgP+GY^kRh|T6QD`&@*YR3}6oiu#XcyLDz!)Ve$6H{WE+> zu6)oQz<&7ge-E=a{xl){YVpAI87uH3!|2JBEDjt;E8#Jwqb@fdyBLxtQ)9o>D`?DY z;5#}$o(*!(AaQp*lJ^&>6){+-pa)$8;L&I@J`V==`0)$%f^-pfN!_5^cicy~tY0L{ zVvUP~7oPkvU>kg+z4tF&TuOtn`{<7iWyc=`WWi{02-_`}fn^^b#8C1whQ2t1pOsTd z`o`VB@R_izA9s{7#HvH;*wLBMdK7nD0K1}GnV5Ky23EKIPwaweLpRfsXHeJJs$j|V z&X1+{P{~UWy*$kB~kRdHdMuxN*afO>y}|P(qV(yPn<@V_2;sEm8@9tQFdd?lD5G91N^eyHB?=r zi-z)U{~Gz9tH$iL_EH;zH9qoob@!kzg0&iYO4ZSbC#F# z_8K#uUpDP$LBJNnYWpAf`;#(Z;b@6iE6?WCE)eHz9JHu2sA=8X%rjN~+G|~CManJ; zA7vyR5|t${c-B+$BM8f<$dk+^l+Sv0&DZ90UFl^4XYpnYp1Gc5!rVGlR*zk(D+6Id ztwFV21lBI!To|g$Oh(jTDQ^x{IoQFis4eFl)(pDNV`Jzt2ncqw$TbYoyM!VublS#T z!(s4LiRrx0)XAGm7-c-PQ09h4$BMinFH%WXV$JS)SXE}cNi%0kiq%boJur4})<}`h z6obk~q+m(=>s0{k*1KFBI0;uKerzX*uh`{U1~LGLqR6pv_E4RIScRnJV$95WV`nTm zjuWX%d>4vI>a=50BGpFD6s21!t@?Z`qLGJc5pruMQLz4L70WLcXU2?X-DEg1V>BXe4eU@0qN8kFz(;? zSq+2A)Dj|%?t;qTvT`h`V35$tI4m5vuR`E4ID9`E(<^9X_1BNP{~On3c&()9Fz@-+N;a@l1#f4**pze$qjj}lzFUrJuRBn^b|_fQ(F;rets(U&xQJsDuX+V|n+ z(XH|1`SCPAVP!I)Ubja)QJeO-xjC@x65?18FUbW)aik0BQ;Ms-W&?U$p(yO%5MO*) zEo7HVn_iipKJ!h1|C%lFiI!#Hbl;Pi2w6JAhFslJ+PoW%*LFE%k0?GhmM+`8chu^g zmm{T&(e7SdzfRv?$U6+VB^R1DYG`SW1}{pbaj}yN)_x=cE}l+DHVFpBu0+n`W7Mc_hM3& zMl=}ml?BS}h-*Q27E0l-m`YVKWa7fUs~?11M(Q%;lUJS*#cpk^Y{@|7N192y+HKhh z>;)rU4#4$XL=|^tZj-7?U>+s$)h&2ZBCyCMZ~%Zl?Mme5=vTKacKhDYed+W96qTkE6eaBA53ZIT#Gpt;D$t0#5jJs^rV02|UW)BDEcP?kuO6 zOMo%~hcQ+*L~$hOsR_PF8v#4S113ydmB!7DzXKhU&Nqz=$(78>Z=<|d@0)q@PVy-V zk8ma#G@^A*1l^TSO!bb)s>W`zwdN%o*UHer-NX&g?*tNZ+4HKZk#}mL|{5n0nEtojJJyf%)M9>s59E|%Oq!%-Ii+p*DSLOl4mHv}H{ z@9ymph@+oL!%`abfA7&>KTE&$j{@9wc1XrL?y&pO8Wto0cD*1Wf`fe5%qb_mh-uds zm(U`+zB<8qKrarQ_eiPmEQzof$tZkd4-q-I#QN1TRPOUS)=F5@yi7f-nX6||{2z%2 z+T=-^75;5+gXf}abusxp#R=}Sy6qJ$)vw5AQ1R5tU@CIX@pjUdq~@Z;VX@&tSliNx z#Duy%;@~OD;}McKG``oH_oyBqQ37ku@i;Gzd8@|44ZG2!RJ{gyxNE^dL%E|&IK%Bp z4q&3AwnyW?8!dE~xP^}8*61xv_i1eecn!C;o6Dcep;9@9vMT}A%kBE~dYVfMy)Fre zmIHXWwZC$E+9)2&@cuV-!Q~RQGg>bxxLE!g%07YEOI0Gmg4?~mD0LSTRYfGnToY-@ zuncBJ?AH=?LtE!VRL+XtXyq^hd^f1UNh^Wn8s98kwO}Fs%6i=XJ=rSv=GmsKx$hOj zQVZVlPcrZA)gD|D8)+9qM3Y?@J>wB3mV!V~^mI2>9W}hAI(|dsSa$6Oh#PI5=bu=_ z?RX*!oRBnVFCYmEwhM*5_7_E2U-n41ioH4-l=w_whXSsoz+w;%x+1)`3p>D(L$U6u zbPz$bcD@{^SlI=yc38%HY;$Zy;z9x{`RE*ZRc1NYiz+F)GRM);tN9Nm-CG@ly@v`) zvQ>T*y7@9oT4mhu_#SAfY^z=<_pkUat-ur#!;a(3ZIcymMH`tt)psw(W>nA7o6_Fd zUjlB4r5yDHM74UgXEn4WQOFS9>J%JYyV`~*chlie&(30rFa^fgfI7_0>?^w}Tv9XV zTgRc)BJOo`Wgxk;7euZL$(XOVQ~N^_V*X{-%JiXN~rEue&3(bf`anU;ywv3I)0Mw5pms0k0;&rZ_gU2G7 zcn_kh5_zDM=Ui!;%!=Aq-=OBt2(r=zaa~~K^ zg|OXO)lmG~!4GWA*1)<+57j&PnpP{c&$EAdI(yy3)h-H;Z9v$OPypElNGQS*wj!WH zVnisAas!l{4n*OCCZb4lxB)7PDB%XCm`k8ab>_al{jAM=I?^N%eomsq>s@=VpRd-) zfOiK!HkhTQ!HBS-?S$lw#nAA0G@%n|H)1{f{Ji@x@LYhjg9%SCGHkpUFr6x*V~1#Z zHkf=&XEUSDA1XqcO7d(xcB3Y6k4TI+4$(}H^8?z53V!>zW`yHN$sx;aQ zFE&Jd2Wkg~yuAm*Yg&$INKzJM@8Q%t8MsPz_3+e~pNs=HdJO~W&WR)rL)24WEe#E| z5z1&}RC(SZ4BQpGS7a+5mTG1@8BM5c@6n9=e4S0Z%CyC$hcFb2fAK?5avBIfBz{E2CCuw-DE= zIk;3pa8|krw#Z17NaLeXIn>e^Y%1#JnZh!`hWd%$!fta|@r9@>1H5zP2vgmvl{dPalNrDsS4WBi%Z%Ww*B2zvnTKG#zP=d*6YdNb9{*+!yrR-5Gv;g9Y#-@U zIx@Uo{#>2WUMX$EK7m3PN8{QD(P~EF2czkBbEOS2`fI{9&c)b^fQ5rwdqvj8>R>2V zM~LS!FBoPUI9H0nDsF(UvEm9Rvj=8tiz^}8@`8kGTW0o?5;ZMUFGUjclITjiu~NH2 zNu1?{j%8z&w>(}FzD>a)tar=7NdO+F2i#sr-*PfP;#>)lM4uJZFKlTp0-{qtO`!s~ zr0E9pF!PWNyJ8V!khH5Km~V-(i^GL;v|0wE27ZRZB}cau;qx|8N|yb5BYq?CSX8Zb z?KgZwt)TCAWle%q`vAw_F^d1zDQqGz+mDiF80q`60+SQUckzOnDQB_k`KEBu#UP~*Pbi*|CNwk*^ z))m>If+XP~VO*i`v`fN864CM(c_xq7E=WcxmoIm(BhR07A&5rSO1TK6QU3Npv|yWT zThaMID_rjrX1-0*UT_~h*F!~CP!3GId>9eYVMhSF{1`03wnK@+Lf-&~&}cgd$WI&u zR|%%~i7s3s!%^DOG?}bva;&1D25I0bcHM_pH5l!^c2Mlvi-dz#f^$lpNl9=8!I~-y zBwfp{hc&jv1V|c{Y}RUtFtM$M!=SD12bzl@)c25Q z3^bvmOsKE8h=br+^}yFfd$DfG2Ye;5t8Mg`z${e}eb$Z;!^D8Cv7cIm!)ep9x+oQJnky<1_dmU1{HX;z(09uydXN5zf&035QLlgNt zof$sYrq9o{iNdb_1CV#KDdOk}v*?lW+XX7Do${^*OrDMF&W!9*PWX(_YBFRJJ@hy% zH6QJ!gA)%OYD3)X4fqT@Fo}~?AT?+-Vq#6sq@te*xjJbuZTA@74nKz&e<>ntD8l2! zf_K>aq))-Hm-%$#0p*op>#5W4F_`W=ePUATt5FbS?X%`JUfbXk*1ra*pC_`d9-oBH zJl&o(XZ=e`2VH~6too>$AK&eX{rTtMv4=dX|0rt99vFu()c4U1NcIH-?76Cd`yIS!p+~=o1$U#C+(&Z#U+*VaRf$GYOM396%n4-3#+WE@82~Fl)W0TwLn`H8 zq%}>`Xpe)IVwAId+>EvUmFEb{FPY91u*Kzu^_!YhqeR5mFg8{EkOC#ug>DyNxJxQx zLe@i}m}pc$+uRd+V-|>Y8Ij7ZXL;N!;Zu~%Wd3S-S(cT|MdjIJC|8w%Ji!zNmANb5 z1><+ksxsZ4i~LdT!hji#5`>Qzf&6j!V4cpM**K#KumOahdtSfBvdQ1zAB z^lubcN3}q>Hz+SMvbqp!u`(veLu2vMBe06qnK?O}o#G_>2T|H~TOBe_v0RlK`=*X1 zM-2n;?eE;azjS3kx^h(+(%oop1cGCtukIa<#GEXRA8V~l{*?XrHY-v&V%d<&@-E0K zsQqXtn7o~172aZ+CaM2^X%29?Qgq4RPvnQ@tZRz+f-Qbr?9ETJ_nvFX2w5?b`dX+K!$=q`j@;C&8goJ{yl={w)Rb=0{@zt18Y!GZ zBFnD7i4U{8Qb{NG{K>>SlDru~7YjE?C@V{5BqAs4WK~Hx9nlA@j1P|XU~SN>8;%Py zBhUP41zIADj0PMH0+c7~eU#iwQCkvh8>SkoP4@M5;xFY^AeAo$Dm0=~kQzgHY1747 zn0+Cm?Z4j2z*o8UW_v|d60c!kjxOnMr$Ui!KJC^2p%zkHRofjM;^9vd4`U6REGJ6SePXC}rwIDJfd^d9{y)zyqCw0&&Ahm8QA9v-yr{TB%|Wkxa{DG%Df)F55VR`(h% z8*4@$Z3I}kSMP)O#(XY=aNlDn?el))vqNqNdMoZzS%ZQ3BXFyv=RToWPrZ(I#K5(o z>wK=6^@FiogwDVEO3Lc@9Eimk8%j6Jclm-v0+f@Y4_ft3vazr{+=v8m*6X zNY-hVV{+Kk&Pf_+kFdG7qiL?hpLe7Zw5aPEOfC$uB+zblR4BVo*Sb9;|R- zcfTBR%6LjH--Xg5iZV6uxfL`tRI5~rUOY9i2O=AsEYn<_^w7WR_mTnvd1L8mKq$RD zd;cKh&$#ATzFd_bX*zu_@9ramPM|q^d&|x*KYv1t#~6R##&0WT&>3+X%jFx^U{=E8 z10&_%ui4L|k>B%AIuX%AzY zz`Nlmdf6~zzIenWKh5}}@}w<6CrfF!a^OBM)mUEMgyf!C!v9h6K( zse@J?tT^OH;yw{?dbsq za+GfF0%V-#x`Eu4fh?C-xj{L5ZpmqvV=6vvp2t zr1U%V%HW9hH1(M(S>SH-g{zVq8LEV-iHpeYx_(CnB?_jNvXqEmF1HF&DSE$7|(e}l0Q#B2GcY-r0G>m{s)KF5eG7rXI6t)P2-Un+c zkXq{Ytqhn8S+*k!4NP#XtfFA0H<_6~X~JD~w||Aav5uc){%vnO9Rj z+~Gf>|M!uaUvT$vJb?{kC4NN)Jz7kdIYW$j1hv15k;KmnFxddPH(pRwh+UYuw2{#} z)iI2Ei=H;ZBg{rWxMO5c`5&N`W$+IIIc^b5Qw)rBxknGu`#bVx^&}}8i$bIa*@3?U zxrW{>h40z-YM1=P7Fe1r)K{|n+C8_ur*Enu)QT9V(S7d$zWju8+Av#_Xaz%)#{vI+ z(g%XD$cp}TOE1#XKU@pykH&=$DLW4}cR_n&ZClbn5{}TD!M%4O4jp~tR#|1&>z`S` zwS1Cto zs!LoE)Fx*nJ6lfU1zulp+HTRgkQpeS4Mfi3Re8S9#&vOk6bt zG*xvXA8ocO>PDI&1vA#N8Ua)Yg$k)Y`m`FZK`7j|=!tpCn$Dsb zTVGj!RrhOnOaH>qyOC;xUCE)J*Y$65p&(FRdHC`hEtfq_5Ia1T$E&cFG4t?k zwmKHGVyMJvcOM;Bs}s3cBsL>!u318>wa8fV*}kj{N@mOA__&p;V|iqt%+R?i?V{pJ zy`Vj*zVf3m{<+GTv{!^{l&gf5_<=dTA?xbUsIb9n7Y+%(i!!GtA}M~0_;Lh|8A$V} z2&X(q1g&37*hUtyOVo*abJqHrgJPcXr+;2hz-nyo>_K1U%aI+Ngyl8Z>>cdUwPJ*{UOFm(sE}K zJoMty=ZzYclt_s}(_2+syzEM7`V`%$NRO`_B-nVNp@``Q#B|$)M4DX4U(iO;Xeyc< zkxjYRML|cISB7BfE)rnJ?wS%G_o4>X1gBBonDt**(x>)i2A&&EPho!_h0d4_Kp7g7 z5W*ySFVS%nzLrXV|gqL`eHb%DxSclr>FUBRKtVD3& zB4&nd=ip@!C?vWsRW}1<*_MFjy_$bDQ66ZN9qf=Z+qXP{d=w9%?LEK1VIhF|PFi@V5^E@AoT^l_nqVo0ib$+KD z%DWrn&J-tMD*|uro<(o;YS7A3_{ZqoSnjwt8sEI$p}-m~*bWmt*?Wa7leG<@fpY|0L zM+SQA26|oA%GMC*k1X`TlX?j=<;1#MF%lt8KGBJ?*|on_BeAMMQceeBJ8Y4u#40f- zr?jv?c;FVvvvC1AeBs2#RgLmC@>OO{5zGCH3q_3!jjX{wj5dZtxPFwMHTsj_CaiYR<8{$Pe%sQjJXN1Dt+I}!gjSD9&34)j^0Q}{le;~2rjz< z*dA#loK@QVN@L|Y&LKbLBA_Nw1QW-!da zqH!JcDrXK|kWrPxwX+6bH71vBsA1x?B2f@c zAx9-g>t{5$pJ5*FhNI9okO?;@VrUoc*>LHf8qK#7T8O%gm zVXnF?c8LbLlWE!n$T1YZ5ee752SO=2`1jRTq);7#W9hq>7#dNt-9^B&MABqP%4Vp5 z%2>*dj+RkvabWDD@HFhVlW7l!Y~8*}e`b}%?pTH-Hx{QC+`&F#i#sY+(-prq#rt63 zk7VQ=Dj@ozSb`vq4Bj?W8yIA!SeH0U?E@A61{5-E^kUIoU+DBb*9xt3co9h^DmvJw z7dz@eSs2jTbPz9jT&F*{0CmJg4r1DpNQb5`fyuW*tE8YNdYO{MHaybUs2xlWDaOYN zgx<>@g`YQ&W0%7Tu=Rq*YGdyy+5`g^a}9zE8`l80Fn{A18z96r0kclA-MpQ_6pL-n+1yJ}%K)jmfFRjbxwf7(J_T zVLqBKCR0P*#m}4hXt6L-yg-iySyuP&eDNxoG&nt`8Hr5j(cA!cNktMdSwQam?he!M z2>a3aX3Svt^;J0>W9&%1Tm8@0w@1>XJ%%(6gH+bO5<)-RXr@dK^iA)(=GCzcX|)p_T?2DHE3I?v0kW)zxn$l%@uxR+ zYkZuxXNgd)ZkoBV?9E*b&HkxP$jxQMNW=hgr9?vwirMO5#8&`Us~4!vZB{qYdIs^WmG8^| z`q@yop81XS^UL$|>0}uE)d=qTg^q@op>jBevlp@6bv=B6`kr|HdiFBJQd}aBw%e;U z{^B7JeHspr*WU%B=dFDgZ{%hTVXzA1VuUV_QFT;^M`buVE6eTBa2Lcr*e7M}Cg(T9 z(FT4?(k7N7B;sUOau{;23%<$@n7O-M$Pk#dP0kFlHPtV59fM)GG$!ZssIUYcQ3w)gT`2hl2~kbXZ8y{^Rl!qR4WUpAh2?@+=)5aiyP zgdfj9RC8z-Ns$F@hyF~}bx0ke2Uta|>qxc)-w}sdAgBYQwIx!+Ax8=`ck`kJR@0$E zJF-u?eRHxb6_lfVEjY7li)A^wL~YiN$`JQyoQHeGcBGsnI9EiO{Tq|<$QaAPg# z0&R^2#j)hiaU1s0?I_B5Pu)=*Z~TtV2Ps@CWWeAgUy~xL3>wj&MKlX;Hg;@wwk(r* z4MDKVl0Npb5-)XIVH;SFm_sj>E4fqGuhKf0P8;O!mWIiyBP5%Pui$20_WK{L=nA~W zUWCclNO9+*J7HqI8|+A*WHU?($8tKI8lD=?8W``U-Q|1#`6v)4^r(W3CN4G0?v z1uRn#2_cZMH40QnM1%q&i73*Xyg(|7Xu=Cjk?yussV47r_O~{3XQW92 zHenRP^4fd-7@pF+K#`Fg!$y1;i#03X`HVOY`{W0Q(1&CoynHvd%RCzJT`ZS!A88;> zYzOhs6QZHl@00mxNCogjuA`x$yatVc)OB%`U<@_tG>dp ze%}0Cp@RO~w?J7};F4#<)kEY&6*R2Z?BboRTZ(ydr(qzLPhzx`w2$u+vq*j-jeiPO z!$?xP2#Jvdj>}X^owA5`CvrNHY`+0q^qo^dB0df7Zu5x8M0z1?Wd`>=Vu z*M|50+0fKL_xb+#aJMduHuDu zd`;H?P*1h+H!IalXdrabZ$dNi>^64GcG#(zAy1CmsUoY~lq5Z3(&&08+n&-(}^)7b4iyqS=O*wVCuVHFIW+7 zI*~>vRmrgg82in-v{q?SGYCCHn(J{NJ8OlN^sazv2*gte6}p9lGxZX2V{6hhht(NS ze+pb@;sUI%%5YQ>SY2KI2i((5B5X&!ZgLICb%nNPRccu)TFS)RKStL?W=6}bd@IJz zNw*h~HP!6um?zXqU1_uYk?pGwvbBIqZXl{OV(GX&br?LVOjgD__=p=08`1Z zpYMC;55aPSa7pceJ%sXOHt%Tx+@pSBVni5p-IGJffdo=Qd*_q=T!jpV&db?yu~bv= zZ2xERK6`0m{``S)uO@7Ts@3b$VjYbtc ze5E@0-576Y*+PItVAgN~0e)qWtXVSJE7Cb`C#q^t@loe@iz32t%bS3qvUZL-f=8o{ zBveXn9#LJ?Z>?6`Lr#`9z~f&4^q7Fk7nL6MSHxy1VR8k$BGMYmTclJDmcRWMw#Nq9 zFLoH7qwz`#tlQsqaR26~81X;6(sAKMP4dgR4E61A+vN-P@{JUj$0(X{Q%G@2lZ(}+ zTD{ZAC7Fp^88g4?W|{`>a)BMW)+Ezt&aeMdH$G~qEU~FuF7b4N#BFE_^g*&!nTdAl zH48Z{bD95Dri;czV-6^)E@uxBdZ;Y^=4k-fO z3;VxX!)I(SXr!l1T#wrl)9*=US5}~^OWIx&uk^X$#T|*1EI*}rqWtd&9J($U7CbNl zxj90I?}VB6+xv$HWY3RxMuh*SUs2J(*S-w4$9OcnHm=H&_qcuh{6qsicvJl3@l6ef zOsZkr2H%50UJtN2Z4U>O(Qo$c>f?na@qp(!kU;FhlfHNuk#9ygIsfhOjOU$!SDQP!@_GGwN=fo5kz)XWQf zcerq;-Wiyk3a-!$Wv80{l5tfs4JInfmltXkl*K5Wp0XOAnW+tPDwHM1lu3)TTREKw z(yEP3?{?|cM`Vwp%4(_mjrS7FmPmqijlSYsrL`d+{Qq1!ZJt6k{PF-~LW*soWiGJL z$3o7lPdN4Ptfu!rG@UZ5uUEuZbwr*BnRt**n6U2ECRdIw-BrL<}o3I4I)qq3Uq-(>?fR=aL2 zj2iz~?3c^=52aD=3A-{ZT^qOc5%g^K2i5d^`D)A;Rn=lK0%DE&uII0R7D}H~_3vc% zy8J-`C3EWGd~QhHnT!@A9Sa(d?910>>$THb%>NyAh@2$oYS?-0yrY3OSXCj?q-FTr z85;kko}vFbV!KOOA^K+NqwyrYD53Hdk<~9d0HYFZ3x>I^4p`dvOciU z%18%@u{iF?A5cU*n8_uzx)x57rO@R1S3kXz^J5yR@I0gH6|$h|v`bjixK7zoYD3Ik z*WPHe>FJd5cFUV=T|kH8T_%mJbXA$>cGR&ulI&f7M?B?J=26%hry0ls28VoFBF!qM zq%wMK{Z{l${XUct7>)ddN^Z89s)@=s7ObRg$i;Iv_#}|>C{Q#8i!wPcNY5DLk4G|~ z)i!9bixTT$^Za%%gA%gmN0iaTQ4Y4x16H=&gk<^=H0SS;8y*g7D#UhN+hb`Tt#5z? z3le@f(2ukwi-Q%m1X(ci?ErKwjsubRLUjsEm-Dyjlm@3#ZAkdDinq7?SQ}DrF9iAs60U^wS+LjA zR_Z@;EREJ0q1BY7DH9Vp&`lO8noDOMZbd@YH1+v#yz@>5_80d0EL1s&_XvBi3k)TD zP?`+$?J`e%FilT`@;I_YRN1V4nVLm$_QkoW3#PxqC=;_)gq)O)%DRcN zwu;3ZRlN;~-a@II|9X}L(wIU?hLO2RkQ1RG(*wEkkyhI+J9@6*jA0 z9zcHM=qXIjQPW_qa@q@K@__m*>XI?pR1#%MQ<9nliHHuXsERx{OMmrNB1f>U_U%6a z<0W*NaOMDLMLcDMfVr_9_r!jcMx&;;7$(??x>OWC;UNy>6>jqp+M5Kj1BZ56k19d{ z_X}S!_Mb=&Bb60afvOC{@Piq#k!8@c(sI`)*UGyH(5E7n>S7vdgl#FGZ~`N|Y6M={ zYkw#M4%IHGlBB>BDnl<0MiynnlwGg^Z*>iawEq!{;GpMTBCXRUHYI*Nh!W2uaA7Sz`n>&+Z zN#PN<9glO3oat0J4y1ZM;sdrDU&j9(4~~O_f%g~-Fm9yr!O-(=a8NwffU-i&zjp6~ z+)m>IVk;U3X9My#1h@`TXAeKsg>+AxG%75^T0~bGPeYJ(BhY;R@N@Qur&enZTL6Lu zU4{--f~`PT?-Ki?ZL6wK-z98#&X*8s4=jDAQei1pKp!IARqBp)z2j;aOw=~+--=Sv zt*~X2siSjBQ*sqt`BChIqLAGvaoGle43u50Z6A}#fRikBM>=J5#3@rgR^fUYBBfH+ z4KiCSNhCC!w45vgXGZ0u&z!U>o6h)HS{9t_xkUxHbw#*DM!uu#`zh(Zos>mWe&<&f zz*l0FA-KjlF&wS({a!MuYBwpq*~C^xkBt!*3WG-1oEL9zKi=LDT>UWCTdH8NBn~St zcdvi0faab3C5EFS!h=mPaE_^n&Lm{ZxdFC)k8c9ECOaYW>N?pQ*6szi6+IC4y^SZY z7@ijf>JhiEkZz|Fmv@y>3S8n9E{y>jP<`8l%g+83>P%AG64s zgv-bIEA2K}%qiL{e`xRdmM8I`fm{V#lF$vffl!2-QdGq*+EOwS>XNut*Hk$K1wBPk zhHgPk*j31cn6rpL)05=NB~AJY%pjb@brXj1nW3*QuD#`yHKHcTHK|@a^#dyC!qW!V z)2KS$lCf)FZ58pM6b{gk@1|}96w*>@QA5)X``aPHD{m|E4Q3;@GV*Ir(cAXgU+rj% zX!%0J1jHAkk^N-SE|b%N#u}X#V`XpS1Kx(3;55%pUM1sW$nbDGddJ7K8MTB!kCaMD zhp<++06%?AG7Y1#>KjnsT7reYu-)^LdLvk^GYXRfqNh?}p>$U)hZU98A3oY)hN}9x z`~Byko}srqBaS|6p^NmHSdQLC9%19RDg=fQ6UFh)M)>`GtpX$rzj%U|#7{mdj}r20 zcN!=ol74zxJhJ&+ESB@frLpDd6qk{a;pL|+N`Eg5ir0*ppYEneoj=K#Jd!^NJ3ca3 zHn3eA;xe3O$*c7*A(V!zcgpG*EQ}n_0oA)Tt%KAN4yFf#Yc&*VK@3744NtWrwnvN? zcMtb=rz>0FI0ILdT4O#Kw%)%CUZ&%*vjrRa-Z5AvpJVVMwG{=xGgQ#`j_ls!2u51< za}0FP#(&AMbiiwL|Mf6_kpPQG=)=RmG@$-DRw)wr%LqDTK!o&iNQbAYwdGX6d9EyV zmPN7zQmrX0Nc%x%X&|GGAz1w7lr*G&GHd|W-bRy zW=f`eLR=|PQkBgZVWDDODwQmi%sIkLf(VN`b#3>Wq-b)fvW!d1ew+3 zPs4OFG|K&MV$^xE`k?D!0=(}h6N7x(9*D)l1k5WiApYLd_eN!J%X= zGBRMebOF}}xjru7+7GnEg@Gavv|q~3x7U{XZrdEAP)L*r6KMb>sY0YZ3tQc!KE-Y( z9XMek20IrYX}_ja5COHPM72f?xP5nViXd7Qg9KtZ5j7v}9pI&!L`%};supxiRFR@%Q(qD8o}|U<0agn!4+&kGh6)w@L@f)xbK@olShAd%i1lQB3d2j#Dm0UIaVrxena&8L>}gvCMB61j`XoI)Yp;tM6$r%jTi=PV zww@DNaVK+W>Xu~xb-}r9FCGrJs$#-4Yecw52U6@bReB*#Anl3`nec{i+E|oQ9dMpg zh~Xt7p#wU+B`Rd3jjuntK*2{NB}R_?@OQuM+Y2AID5gejd-Ej0roG_>SFU||zVzDO znXxosS{Ql7p@BtXteAqCD-*i#o7yHu$f02_Xx&$H5}K^`GD66OS82n-c7)0sjo7(m zjqCy1;l|0YM(CaUOS+8g)_2cYe0f#<{@GK@VBhrv^I>D)yII1L4QO2%lGI(xeh=Fb zJK)FBa{UYs?qfFEJokmd2EmV;XFS40b8OCb%!b|X`(pX`^C#2kcjnZF%(#x02EHUe z8xKA&7M}*m3V61|9v7rtEuO$=!`kUH1|otv=CI#6?AIU~M-qx??7+rv?MS=-8E-I! zNFeQe`X58s7G7QsbTb$czCWmY za16L2rxrrL{B=+?);;&RX2OHa#2A79U_in+=pxoDzwfpugS(G)&Mr{{LRDkg?>tWy zU~=b}a(Q-%9%>wx_%3z_;f0oIcGe4=SR|@zO_y~@lyfTLCb~|IC#Q{a{ltff(C_S? zpowEw>>5bLlEOUH*IGjrD2wG}t%fA=UrH7_Iv1i-$0?eVZ=;xC0}9F-njA?Fr*}K^ z%dmRQplf6*rf7|li1y#m3jAIPfy{q{Q9tC-={QBw5KYp&Q7j44x}_hopwK zW23zMz{122T^7YkrsayBC@v-Jf6&KdZJK*jv~Sno-<7-y6<6&#Em9K58X6z3HQAsU8~KdH=csAOyULP=R^h0)b}W2}I6LWz z3O7-7lIpH#o?lo|gNr?-glm|(SS#a(o8cN~_T%Dn>`+2Xj zERHXF*CNJ<)o#RbV!5*M{<6mpbyYBQ^$J=is|@I2=pJl%8R|)fYC3Fr0ev+f4OJs-I7wwMWrrZ|y{$sIPQiQa0^&pPC_c&gv zbfM?HNaLYUdT6{hA0pc7iu(@pmoXZweE36ISaxUF?_;<3Gru3;0lps(^DdiVyuRG> zUhLP97xD9eYQka9aFq%}Cd(Ln4R>Fkm>A<+q8X|8@Pr_`J0SlG5Pl)(YVeaRXyd#; zUw$I70*KK+KWWd)zIWhvvReCkLWQ`oE(Yg_>TfITRpt> ztKDZ1)#(IDbEeE0dMqxRWTd!Dh=nKw6K{<^#Z5@ao4pi0Uyy%7^&Xax6q!a`gs zn9``z^+qRy;Xc}|&B?yZxRigW?YSE8UT;`q$gBjnDmhz8guWH3w?C^J2)cOMxI@^u zXn6*OGv7wf&)dd!q!qFK z`Fx)JC05Mt7ai8(R=AvPWm#r0 zd^wjhAF~Tl4SI10&(te%K{ocr=KFm9{5)@b@0*oxYkp4L!}c4w+D$K-+#7`^)zkhZ z0Qy8bB+p>5NhuPw6^gT@(}D3pVZSbZ1^ zdVdS85V(?3>#RyiHonN8I|kpU3Yb=$l|ibVh}CKlu2bcZ5;I*SMMcjqkSjAAc3&}7 z!lVm(88-?mDlt(*qo$IXt?fBiisR6bIa7|b`+8$_8zvs7QRCa;MAAsJJOPkk6x6C6 zBy$p&rgE^BGdT6>ay!+gm$|bYBn*!!2^r{g9Lwm$ln)7ZC@Tc(z=T{by(&c z7>B+c$w6kgR@0H>eGEcWW?3M3#2z@IN~qJ9;MuDn6gNvcr7^))C+KuMkJh`4)Jn+E znKEIf$ZUVTL7d7_!>&a2eoW2eG-g}u>*+>CrO+!(P)h7Lav%By9gA@Z?~?upu^TcJ zwX{}lhX&D#-D>R&+vosRU@qwek!M=9-GUS-n1hFF$z9ZDooi^%MfA>rLWW4xvO9)N z^&tG1dy_Vm7)RcDJ7FtCdIb&xyKG?ZB(?4v^iS^kOrax6iWmg9Lee^X6AWlKTI|C| ztN*SvDy+i>>;0D2yL~xp54l3ab`E_owL>u~wgLFELyFgFAwa>wc^NazkJrI!{3KcX|j_9lUy2_cEi`+>r%ypFyEXwXmt-VlFt7| zh4tFY5mk-5MuKyVp7Smrd#{uL+v9Z&pN;8`4PpNol8QC{snWsWKQHqCvKEH(qK&4* zxA*eEjbF4LHn1LdsSx(m$p?CY$M-0t@1G3Q2QM&L_%Czkr-!a_;U{%57}OdJ_a0gA?Ms^HvopD7XAAX)EoYGk7vAtf2VR$XCi&j9Jk zB$q)_lk7?1KsgO%rf@DZ&_1~x^prAvtWPNe(3`#M!f-R(G4Wnj)BVO6&4vkTdBur( zy`2npah;wjWf4~hifU<|>AGD57VEPnr$k3db3|h<3aj;{BoXm;8X3A3)oC=k7%Mf# zIKv^!%5;n9=}dz2tiZBMuEuPp0ZqYmA=hwumXK;AZ5#PnWKvQ(MN#mE z`l6e`Z;Ygz#d6gIaTlHnZ9jwk-L3bx6MZ!C_)J@-@N0_?noDFT8kPhDy z)3Q+Dq@yF4r)xJ7g^t}ML4Ymx3y!N-Fi{AlFB()2ssz?!MZ_|=w7k;bI zn`jHIizSt`1KfbE{Uv)tO5g_S4#vJxXsHHC=^;v@B_*Q?^GJRxvP!#NR=CEHjfCDw zKrN2lQus8D3IJT2I7vzg+fjelPt_=->;YFeW7_Sw`!|CAf{Q@*PRY~s1G5DNl>7La zlmN-|?xbGcktVI2N6eJ0&=i2d_eY>cOXKKc^ucaAWL3;Yxh0{~Z_0m3;%IwAgfEAW z!7h?G>)4XY`Pl#PEvkG^cEeB><&dvQgcZoRbc|NPyNEIB=vIq~bfgl8(6_XQ78~L4 zuJt>TVfdipK>*%pGWEU*UuK7^k_FNyBh9=?x#Al8XZvTjx(oUr#C`Mwv1UW#3Ezbg z+dFh+0eDL`M`$e8n6dqcd}7s7ItThIeE`MLUrpH)Pf=x|dVZg1D*bCUL5O9Ti=<9rHJovCU809@6(VEXgyE>%@SdL)wC+GA0$KzrStTI{7CpmwBV3Ilz zLbL15A-juZ&)D;;5nqF1!(XGQ`QL`&%EQXXbPcire$7d{8WYUXeH`~_6*L@W3!L}x z7m*ijfQs_D=U;oE1o#!Xl_4=%(JCB7tYzqn@QRkC2Sd{QUPEkq5XuF++UItkXdire zG0u9gSPeGAL%Tgy3=&#l6t-*kByUI)ZQPf_K|-%^1wS#T9t@tkT@pH!N;&*46*Mnt zd-<`d`Qn9r9CE`{=#m%OyA4qki^Nm~taeS0gv)@1s;VqyWA`!Cc$Z$I@9F>9rH6@+Q5N zT{y)gUS?IciKWTf8+h8o)?{K8oPovbqF!sCkkwUvt+T6rG>)4Y36~SN@`@`Q#3!#m zQvQ`dx7JXbs5P|8ID_H6hM{Sl*jZf6csgO6k|OuQ1PsB<{^h&q17kH5x;04J!7M54 z(zPSuG%tAtuXYdJCJBS5}~Q)euHh0f_$3{-OtG z$O0c6cbq5d*i*QAOAh;5fNVI6si__L-bYOijE&P~)tm}X$+@Bd(AlkQNs=#@x2=MqGaa+ry>}A=@fi zTJhwe8W0eWiOv$Tq0#pLXgYu0#L*~dV0W4*ie;Q zWHvVP8wti$1B{-U)JuKzF&KPoTao)#J{V=s=qWUao$pn>V81a38zj3Vtl4%u`-T_e zPjW)6)qXykueP)K+Ad~Tj^=xUDA$BglEAShXp%In<$U(Nciq1$rCY7ORe)sh3*wHa zKWQUetqpdUD}tRdEJ1D8hShImaZreaCwTgAf3>Cr$=GcFI_;_mX$&Vu6x~%Tp{VZT z^{hyZ{?s6Nyv7VnED>fbJlVI#9=X3_n#-SbL4(o^@* zfViuIL5-e`AR8s_GHsqHqY|Kg)|48i`|BC4)nxMH`hW$=xUCW6>$79NbN~;zcz#kK zhjJ+&{;~UX70U4!DdiZuk@D*qQyX#RB^`O zs!Ba)N9sBGX6y=Hh@IrAU+Gl{eT&ZZ*gISzz8oYHo?z}YA^;?Z^f4qCd!-`YiW~EQ zL8E5Oe$L_#jZG$tC%T+8_3iaKXYVJXMBD>~Npb;a8B@zIx?%$bL!|YkQbj{jD<|tx z5P|3tjkOeQ8V0;TmI9#2!iw3g-bRg_w6`K(7@8HVWOEfC6z}M>s5&TL7N;B4MW=;U z!Z?VI(lKvFu;9(>=H>6rX0v#q4|sEWeObJ|lp6vn4T8y`EXv!<#`x}+@}h5>;-!4e z7Uhl2^I~*7E>v!)h>z2)IKJB-Uv|wVXZ*}cw<(HSuCVCi@yN(JAK4*cg!_nSkVbwf zvNIcFxArJa8Nj2n{K#nC4isqti=~MnD}$y~i_$Sr%oXRAqP$=MM*fx^YxOd`r)5>5 zj84-F&L9NQHU1;$rlDw^<>WzrT^hKsnj9`cnBmvXv#O>Q16>vWg|R|DKw;$5D%uF- zR;ppeRbU|M)o7>GD@iaVqU$^tj^_$NGlp7|4=od$>uU(Y3-acG(xVusx}maHDd|OM z8?!r!J;h+zHx;Yp!#U_A8zekcoq<3MXU7>w=Ye*pd9!S`Nqir5Y4O}sje>oD2)kTIxZ!nAi{YL`Sh5{yN*20M z%1^INPBXe?X7O-idqLrmn5m%~4)p>eqD&VAor9!oIAIlTUXM^l-^F0r*FfJDGG5+A zsww)Epen>MtHfrz*in!OdO}A-AW6$yuOo*s+hH#fWoH=OYkx)%TD1%UsfO>2o7HtIxJrx= z9n=QVX}NAfe!fZqb{DLpX0Y{pDpm@7b{^jS5t%J z>6_Y)-ny>YSCJdt=~W)!J~Y_il`h~unUlcoxO-Oam4U4B;-Twb=n9CRyD;8~q3y%D ze}3veob4{?u%7MuAyHUQV6R~(h9dU5XM=1~pr2^@MM6C!!}94od?ulT_>HSZ&}suV z2tK3JQZSaw#6ks4ohE0dLtA1iHou6SY5%h0upL*!NRX?QPK*uFWdIXE?7!Q%6k4sE zG%ibYv{vSZBJ_BRwc--`Uf5(w@SN!N%JrOkMg=?t2l|1ur-Ay+t3-kML;*J1!PO*I z%1g?n(i0je3cZB2B+nW5%ecv2ajVpTRt>bS`8P`t5E!xWO+^TWGP?S7MAw`1OwR#d%yZbSAP|SseCu%0!>-!fsfQRB5M$QGRU5hDKi||F5x6rrL(D zBRO|9k1kTf;CDrnKM4tl42 z>8G2EK`B}+l>jqsPHHXho7(<=RjW|YfK+_}kueom^8S*x@|DFLq>`_^wud0m%6^Q> zROu@;GT6CGbx1NUF*&J}OcjWcDpiei(?;(FeqGtUz6f?slA1KD)I&8*#;Ga^!@JX$ zcBI6M`8hLatzu`V3lv_Zngq|2vWw+Ps2;GSk`Rjr*1apzufXAZ?qiRH=-*)NPQt3t zsiY;h^6$;R#6|P$(^YBwC&R||C1`_-1Z$^}ulsz@t%=Ysx7B}`5DbYh$_wM)in7u` z*}ld0?p}5T*Yyd-^IMpbumu6yZ8D(&=R^Z(U&+xu^(yo{9Yxe!%5Y4)HEjDX!$WuU zrF{18!!r!Qaw>)HzFHJ3RGKOD&hM!Q$-d7+k7A}?i{$1W0Ukh`Ge#Z^yD>`kwAeME z9H=`6lM=IOn626X*^|0{!I11KuJA+;dxKrOb$2A~)E+o+6@t5+0Tyag@~*g*EG$W; zROFyY4j!`Aa%3giQO9ub2Ay4`7%MdxsyS&Vf@{>3$SHaWqu*ld*o+5?j#e}VsNO*+ zjoPXeeUNqKb++QcJYq{W-#Jzy`_fzSWV`bg&v7SmeF`nPhNHn@zx@Q2CAGr!yS2w7 zZn`tr9}XRNcl)&MjGl=3KqKf6qubjRbLc(qA&uS>KsmFI=AEs65qf3d+?maB080mL zFuvX|SL?m9ppEyK8CC!QAOJ~3K~xH_G@xFtDPfo{XBd*Eo%MWcfcvJ}!I^6$B$X2J z)p}_x+Adda-OF_PvA>)`d&lH&P{M#H3v+N+^+;o~t*+YY8rnXtCw9%4g|KngwNpX^ zx>rNp;TRXu7%+Z%>?*CpAouM027fV+9(EsxS8$lXN^VEkOfTvRj(9S;vzd*=uB!IOuf>jO4i z{_$6vW1E6*B;pSlA`NupwI^HT$)_$qKPOiy7yTIVqSIK&gwM1}Gi07fS_v~3Q|8V+ z$44Q!y-G)as#_AA5x6c?&??cX2#S(5jDzU&lDetnz6=xuh#X4>&on^r`ei6kLofxmYD6$_Gb}tdqg$DtTt6T;8=z*R)5(CB6fE+fUl+&1 zK0Fl$yK)Ch%e)wE%0>1!c*_-lr(xuXF9!Q9Z?6z)H6OiDeQ4bH_L_mOEPM0Y;@(48 zx>Eox4GHhrcXh%&BuO;lv7>@DNUtn())?iZue_*L=6fs~{l(F16?viL$v_TZ&KtOv zl3N+GH&-!Z?gFy|Y8eop1^APQ1cmG}xkmY%jOa2d6UBFDcF{CJ$yuqvtzBjWo23TI zF`HvPS!yecWT=}-x~fR3RHlkDzNOA%AdJ$PHzHkhLc_hL49Xy{II9`cj;Zl5!fHn` zP%KCko9ZiUEsbkmTox^q9<*oVvN7%}j+*(6OK_`Q)SLS;MZjP`iy@uX>ThU-n7$Ma zih3gi-Pz%lzv{zvAg-$5~ah+Nv{0epCz!?IHAf(?3opWJ>$H;dwO)& z7A#{RVCYK_1^QugQpkrrCEFB}8TUq)9Lwm-yO@-E?hntcj8RM}KRQ%|Gmok{m_1t0 zyXRN-T%e^hAYwHlLtY#k)K*oRg5;Hm#RGWSx<-nxJa{{rUVPT9iVl(6=}+cfTRp#e zQyhoVHQSnfvzq->6O2(rPXze0_o-r}mdooiq8R^A)A{Qrj%Z{4MJA3i|D;a|PHG^Wpt;&n?|TV?-X+T1 zVAO2a8TJUDxpdpg$P~PWbQH4M)dF{CTvZAyjJ`x|=vkpSq1a8JqS!W z_&xMSthJM2SOaRsP*RM$3~oo_Dgs>vm-eYXeQ5}45Mf7^YQo-`!Dc2 zCYWP7-#!lQtnky#LbHvdqCiEI4Zgd`v>%JK=g~h1za4k8O4$y2w5Z0-8$NCq}t4Z@}m1wVwA0y8~0R7PE+&|qKoMRV)&h}2=HIr*CfBzv7 zt7jznpXz8Oswgf-CBJZ! z8j6o}n%-|nYCu)nwgv$$QC5g&DaNY|TX4#vm^FaLpG48G9bO!;D>W{YR?~egfc^H{ z@IR6&r~woJR#Xdti488<{=$$Fn)&jzSiRK5TN$1j`ab_D!Bt-|ltzY+2Fa5JIan*Q zIF8RA@=ST5@}4KgkC&5UEf?^_h0ioBVGp)rET<>N(dmuA$i!H>?jMfCY;Yx@4kO8$ zrPhMZ9*&1Y{bq<~$g7W6rD8Vf$}Th5bXRW%wasF$AZVONDq&nOP{uPoV#WOSCbEkx z3p2HHpbclGchmA$l4mB(#DTVUk+f8P^uE@m&r+n>J}%i+!}p974E66C5ZkjP^INuT zsu}i3sl0&0?x9>7cJ0~f$GDLSY-ZxV8}Z$$s)^Frcuc7p0__$Tc`ak>&4@_ojpOKs zRR`h&PuxfqTuJOlDjgvU;zA>7t`93o0}F2-yi9je_Z7*mlsb-bU-q&_A%)vL!$Fry ztE`^}*ziUQh*r}hHm&g{ae0(qv_@rg$?lM^J`(#CDibux7AO`BE0J^IJR`B{OVSe3a?6;@{PigbyfDbAx9)bFJQujp{KJv!D5M z=3kVkw?$tSI<9i!2m`Ly*O6ftA7ahRLfaTL4TkmsWm)PJvOT@uji85JaWuWZDk$^QroehSSIK!|Y#r7iQz>`{T@T*l_moopfkA3?J@h z5=^7Y`tMA5%B_dH>3a`YCKq~Yl-F>XSS-aqs~Ol}_;uR3yPgh+rUacIC;$d_4P85f zlM!dAFd11`g$-1JV{rDeUgNCd|gC){3c582L2MnG& zy@$c|>2z%*_~xX@Nz~50&h-t=zqAmZ2vVrQ5s(E>#`60CGya?CjeB(z zlF7mJS+nV<`@h79|Ilnk<<+6CSR+aKamNStW2VrzSTB8L)v2db9)m)Nt8`gA!9W)n zKy#A}T2Wl7sqE8X3S8<(I-R6;RW7MjbwOM$-|%xt)S@2rLeW=cx*5q~O%VsSX^4SX8|>Pk6Z@K+qd z$M3X0DsSZL;Eln?@ej^!HD@*|OxLfm=Aln2>mk@pYELd@!z ztXMcOi`PuqlSy((bdD9ek*KE7;g_cr{KP>biB*{V5Mzl@D$drDfgr^yj7G~?lzEQr z+G%rX=alfQ+p_jv8V+^7xkNnwQUHh!L>?_o`~}DvB{KcOPjTmJ8ynL(ybEwkk>W>3 zA-JzVYubHWUY)A7*Ixp%3=aP73)E+5E+TNq$ zN)oA^f4bp$w+71zlBT{P(X4s54l-k($yH8n7Bgce#<_FiPZcKQ2KS%8!a3DUT}h;_ zzTSL)t_g~h-?JH~76nrUsRXOR0kz#OJugj%nZCNP$^`y`^0{$E37DhFY_H}KgW&ZMUvxf?h4 z#6=sQy*}M&T+KR{*|J&+mCNzegWdKN5{)g`l~-(w4X%5Cxe@91{_m%on?LgIS_S}2 zzai0ed~fBnXYrC3Zu|>%sjRv3+Urr2gQGDNCjU|q99i~L$e3TO{p!5%B4GK8lssQ# zKPd(eox55i2dJ_*XKj>VUx`g@?5yVTLS>7#24=gF$h4IP1|mcO4hevxve__qCR?c~ z=-XjRZAZQ+SYV^7T69Rux`CoCFaV2$ z`C_-NwQx1$p495JHx`HrtFN*@O{4pLG0jEIW|uA_!>;3T@ikejjxWpApU*D_tEM(VR8p1kx|Z+s3lgZ({NjcS_B@Z!)PO}_fI48%O8 zCGnGedxjc^OO924QLTt6nBA`d^72cy!pnZ;Sy<@-VRwBT{jQk+J)Pb1Pl3QJ^|a^F zfuS?ns(roxuJ-+}mi76bnnBjPi`4TtkYovb(Igk{-=Yw>PVMR_JutQyF~U%UvjOg= z+ViCw(c9FQuT8Ba4Du&Sy%xadvZei~^gL3j_za92@=W!)F#)8?#Nrd|~5Of=*6u4ZRXd6l@azVcHB)1FCpAu zOCp!jZM#6V=c9Xpl4j77OGjRPR4QXqIh3K(T*FY*!;(~>oYD?D^8zNWeT&R9u3~o^ zd2>VI2wdpi6bQS~cvllB0V+JX9nb~mIFzVIpEd3Y-l5Cqrv&miE`#~ z&{2VWIShZ84JX05D^8A4h{wvMGeer3>4ar(&)IsNDTvx&`WHOd;PeNBke%Yl!a6Gn z`u{wgyKdro7sWr{kZmM1U_k*Aied>{2&j+}`A{I`1t>kIvPI#7W|V^F#q(GEva}yI1+@_I0~r1zaN7;v)acF0`X->oIYTCF&XqWWPf74-O!;>}7*C zmWmpO5HS2D-s*=(+6M=+`3@@A=YVH84DC-<`G-(WC8pHGZ;+d%Bo72vpfk~v{=3ke z$VryKu92a2(`nj}!oflf4sB>?yKJj>gXZdeWAH1N5~){sf8oWD;B~uLvhY-A=cgIT6t> z+6KQsd)L$Z`5O@&TjRfT5n&`(nmv z1mEE`I#2ud#ktoz_s{OH{`vQ;H&c9N&wx|fteMeM7u5lWM(k|Bd_L0?+@JlHQRxBq zlE%xu^NcU=XdOKN{Gkq{*@%JjOj0X!&i25@l%>HkevFKo9)}q_;DKsE;8Mstf_;AFbVJvZ{x>2+5({e`^*zp3hwaeNa zE9f3Q^ljtIVWiXaF;iT^r>Ylp+n`nn!X_W8XFYKOt(RrD@D2VjWpcW#l=!$T z9%~6~@Oe%D-(Z*+Ue%c|1FUodm6HQOEK^zts*!Y+Yp@&nn07Y z40(-RSAquXF%x5o5()f(e;gpuAvJ^~P#drQLVM)}2FS>zm0(4^Z+P{z;6)ua9KIiq zih&NVL)97EXCv4KkNjpzeEvFq9lfE%&eRVgqheDF{<;hex(QXIa1`4$L~LE$Mr$9Q zDi{XbOqbWan*{foZq z6E)daR&D$4$CeYA<800x;G*>`b-G)`AjbZx-CP=SA59_Os9T(+3dN?Q(xS7`C4&I6Silo+-of%nI0`_a~o6f4f5A zhdZ3XE}0TOeD}Yjr|K?W9s-|YLQL%petZRF@rJ(@bI0zSSf$(XA5M4^#?HWQB1eGp? zJeFj_vAfI;liClXX0DS6LJX>w@_6PK(vT94?nTmFJ~a<*^2;8ZupRijuIZd1HMx}o zsRpS~7ZO1dgg+?|3nEya@(;R(jP+7@P{?lEeC((nDt9MHFOnvMqLmBOSdqE>^i&!M zKTUq&MOy9X9fbX22mWg{K@t7yaRnYfKRy)>i~;3h@+hmY!TgHCB}_~cS3;=Pq!pC= z^!!Q>!!x~0#*g=}n1`i~#xqokoWqnM^oX*++MTN@Vk_(-t~%-)m_yqy-Q-;NYH-`w z4?QuWHiAo)BPo=Vj))V^S9ZquCx)F_pw(=nOWX32YcPD#{+LqVadKj^+|?0dY5Bm>a&-x#X677ucS$}khOkVQ z)v;wa-#3J_0KKHVKvTQ4X_Bm_m)NoD$Z52Axz;iuD#e zW!DHU1-+TdlfJ9QgsY0y5Rq0FLo8hw4kSsK0|_$ZF>*=`^&P=#wIYrqMNO*2$ZnXW zo;!mkItzT{B)|=%)psP?OK9|WX`yUSD4hZvM3GWy@eHxEvbXdf=U|L))xe6@Q>|LY zseR-sg#)GS8QKn1ODIvbeLmvOV`777%FtKIvOwaNwta@Q!By>wHHD!yV}5csK*+rg3xRIVTJK1 zCUpv0e3Vj3t%Z_I;rvBwCHkw1L`K}SDpbR3RmoBm`mW@N>2hVa)pzZH(qQAlL%(`g zX+x-*h~uyl6Arzla$T?0jF^#T z0l{xC_<f@qRD?s}u&K<-Gk zqnVO8&ZwO4`Ua(E16XeNFjCGHtw*!pKWPa5`wm^S;qJc>vc|zdI)}r(_BGZvc z-@7gsW#^7BV|k5W5MyOmW>S&5pnPbA+KzInZi+gk&v&d4tfbcA+NquG`1lzy?quxP z6rY)(gkE-BNi};(17xFY+8`QQlntY5D%RO_lJle(ry^nI3{)8gpPEVcvC7Mxk-ptT zb@lLJqmcWZVaduMt2tdxgkl*+Qv9MjB$a}XYCZaZ$*xGRqF({Z-0hT^WzV=fJ)ia;6PbH) zOcl?khIDD3U$W!YAa9{HFnO8mgzbXdpj$y-&%5qabgZ=1Q-}__R5nMExIW~@8I3wc zc^HoF>||!&H5jwTvXx9 zW&?7|#P|~etW~aob4`xgxTX>_%C+F&?lrEZ`jWa@V5zC;5$+;a_G`GyE4o&PF#QWm zwI!XpvDPT9Z#9OQQYy!8J}f~Z);#;MzTF_#_7~bs!;ziIs&FKYosb#lajaHsMANE$ z(4sitS0Tkh4EQ$C4isw@f4|+RC4&$Ll656o?`F=Rixk?hEhCpIiw3Emxp(u;){sUA zIdx;F&T>Vh#C&K(YTKzmpmH137hx!+`b9;;d?0jyI zoV6!ok~cI@e%2nC#=-3$gKad>LfY+CFlS>IvEqxYE_kj^Rr9ua?Kw+}|}*})IP+V_rR zTX&tGo!R3Vq4S6`2KcYKjmYJ=W7JGxp<(XhfFbpRlU@xwLj&rQdV_~QHDey4*P;&T z9ysRv2m1=Aue`yA-uBfJ-|q=GvEi^d@{%dD3!Su^ptDWO z_up85pcK^m)=3~eRiN-^!#mdxZ@NgIh)M!wznmD;`53h=<9rdKP12 z$b+J3Ksn4LN~!Mvw~k`8d1bV8{P1m zJ+Q1%JVFa$fV}$5kA*hYa`YN*t{QvYT49%;hTc`iAV6blXB<|Y!_oe)xKb%Tqu)?- z--rMJAOJ~3K~#CUFSO(3N~K#0LYYU4*;aYbM7XFaL_*Ij+muu~xL~MrgivLD2uQo6%t*cJN&mmO)vLN=srX)ptU1W4CLOvq;Nk>9r(Pj>*x& zOe~S4!Kqfpxk9t}+!+?xhb+8xCtwGZz1STq7JL(`qpp-&_s$sD0;{aLZxu)=(&=cjzZ>c5QztWFY+7 z3Hn7oF|-Bl6F@L=QG8zZn__>LR|+QDmh%i!hJ3v+;Og z40y67cVj!4tLFF5X#Qt1G1yhi)rfqnxjevz#iL)Wc(MJS=LnxW#*i1paEu6TJ|n;y zDROebX82t?XVNv!*nc0+KMY?7cY{6*xN~OeY)^PN8!`Sq==>tAQpR9ov3Gp~*nwep z|4h0S$2hs3B>IjV*kTvHqkKUvM@*eheXWLv5B;CRB^AK%U}Vfg0GeIzX}P?^(yLS~ z)X_gqo%^9Zk{VzH(Tt>r>SiFM^3-Q={X#-CimdzP%eO>|c2{5RE8AQjsjh3>rVr^$ zm#gaL^kwb`itP%QE9jdP(;iT(^(^e(|u=^Ogzo^bYUT^SAJUD9JDIVD`XRw5!OTN1m0EpzS_`;-39-vc@i1+>+kFjsy;t0|l{? z%s{|iEZlV-1JW#e0ZSJCV7;~wLR>1c>}^%5akxurvqr@rWgY~s;6u`@K>Ob=F&exr z8B||Lyb8J(5;mkzwx5L^2-Zym8+fQ}7~{dpg0@RY7<5#}BEPrZKv|UBrlpo!PH*Z+ z)eF)lGpCNazWV^EfLB@2?ruf2GT5fq#8)RFQIdI}SE3}>Q1+o%YOIKHZP))NkmB}G z;gq$Pffq{Wy08?C_VCBu&0yt)a8{au`3%Xad$kn87hquN@2AuYXtL zTCgV62!~zQ|0{QJsA>m4aIJ&nO>;5ce4F*OBny(s}wtYrV+x$YqVsya4o(F zs#9fXv0mmGyT88R*!Pr=1(DT(`7WTyZAY0Ktw#zLV)aX(pu&di0j>1fwx`qjXNO^L zt1YcPDpeJ50@=j|6(&Inc_m{iB^|J>+Cq}KLKPl`5>vO7`(ZF0LQg%mzNws?spq%T z#KAi5Bu}-2yT6{yP%h3Y0RfH4s;&s9F;=Ctttb!UtlKMz(5}PC4q}kFHNf5w)`4qC zfmm#fLH#Y<8?9H1*5l`-{g(-}Fqr435<8156A5kqs*kPlUZ&mY2R~xlmUgaBVst_ zw=j-(gIXe>7YiDIM}Hm%vjxqBY=9q;T@B7N*1XE!aJXxrd%k--|G1SUy;FB&z^d41 zrCssY9mw5rb7c52SI1jmtb=YxxjvA^N8i>I%lxJv26tjQ=EexV3`*NRS$U5SP@i!LywEGWsG zq%bz$cRAUrFe!4fSp(awu}6^a+++uBe6tI^c6Kf%tiLI%y}>~vUhIk&^4chD;YtXL zA|knwItFA(jbfmiLy5U&TIhi*34@#JK-)rLG9Z*zH^`$|r-MFXVft7R# z#XZ7~0o}qKitcQh8B3>9gT=bIFlw(L-qe#d`x|W37AjKxXCT zqKM|prKx#Le)&zoFWDS*p%ARHw(lvtq9Rf&;~M(POq%qmnxtp@4M$BwpGK7-7~rjg zb`KqM9t$^7(8H8*7qJ({CtL?g_z>jTHQhxVxDJ|<(G9RnO-R=bpvyp#>EIHn06_|_ zi+Hat1~bAVxvG>D8T}Q3l!oIBs9lAKn+m(CurA41nTi2pnnfZFr*Ed+Ja&-GGt}dU z%P(UEtZ1ul76v!;BS~88SmlT)PZAe#`~{coI$M#e^NkTw1E?+(8U>a!`RYJKx-<3i zG$7Y>i_Qa-%i8}!js=#nqBKw@%cdlfs^CenTxDUn=qr^G5?iUWK`4ERFD*5AZ5Q}) zlESZ5-r(!`db-41Y;T!kZ@%0nccY)xlGcmMe~*|x+)NrMw_Eseg~1*xX`cmaOxTnG z`E>`W#&SeB2E%Dzg$>*Q!fx6mZ*A;F?Ht?^5^a1JJ(u)Z9$Q)ee@vZEPa10*#$Q0D z!w^vzhXo|WFbNPMG&v>FOj%%UyU=%mUDVNZ;e-WANsZwotoQ=1T$suiaN$QdtFBJJ z*L(l2hja3RBFv!D%FOlL_kI1rWeXFke6?Dj*c4q^T4KdGP{ls)YY*0Iv9An=+wJy~$M#WUXi(dNt<@$9m~t4iN($XI zX~GSMzKw>wCJm0Q-X#VY+EuyPEVl&6hO&)Xa|Hks_G>Vo%e0wm#4EVi1t`tU!)wiR?FTpao5xL;zd(Uob9sa~LAwnM ze+_qxt3*V49Mc<#1`96#2n}!;<<*Dg z$VM1haVC4R&ec(`q&L|?`+kY|V9tv0O{VFsonz)!Bm4?5pu~453R8S1OHy%gstn?S zB56W#XG+czK}c&QEVjQrxHKjCXmJ9kX0c6xtkfuYD8;v7$_c#`TDkfthf2I5Vk?Bl z;`WO4B8kQq%PHaPMmXu!bTM%7FnQPS6y6y%+R*J6v>Hs?9z32>-2xe z3!oIdqe9&lx?{vekgUcSV4Xai*#mh^lG6azA_}gbEl?aGBDPxBpmRB2D*kA4B!$uh zPiM+hrnz$buw9GEazO?Y&KqOwr!_3L*Swg|>koD8Bk{zF2?dUw@pZ5F&>OQPiQzjF zy$HqGb)@H$676MVM6XcJdJm7z`D%i!2*-{R$w!YOKi}$~P0A6g5TyZ&|3-i$-G_(* z8JB1K&%Y(HkS{$lC`(EiW`+O(oj;+=u!_=oFM#80f6jESXe9JY2)%nSp+m#@XdV-8 zhU@j2wIOhbIV?^Ga@$RhRgulPhCFLubNYZ)w z(MiHD&dm(IHU72VHp3qp`)1M;4SbU=rCHpos{ABvKi*pY)JpLzCp^yVRqR01LLE#= zt(*oyF54tR!W}EgcJj}1;h;NR$z;xf8eXNeWS ziNPmb)8UedR0gE5q78!5cqL0p57hP8_#&KrF|3vXsR{ZXbKTbz*q(9xAKtC@hSd9a zs-BRoJ*yQhEi0PCFc;p;2u%uTIfaTo;`sE#yc$g#CQZeBw4D&;o$jb7H>*IcJ=bQF zja8uG)@|StVvq}gr%Z?$sfDm@1h*s|DauW;sy)O>kAa$vR>;_C`caBcE0l_|Aw=O) z-pgMI>;EOg%L{=`v3cx|X7DJa$r;@qz-F zos&7RHF;&|X|NVkLG};@qvA23vu8y1x$Hs0LYO;Q%qR6__n|)S9@Vj)5{21{-;;Yo z+4uJ+$|5{ExhDYW4F3(f&W7Yi_qO{CDe>8uZ*j>;%ety&L;W-Hn(NXV*NHk(AmJ+m z;3WpsG{Gls?7ZN$9`%Cq^~K%A>FMeD#rehV`R@7o?w2oD*I%w~uCBg(yZLr}eDw{= zz_G}A5CY5ltO~ugtut$lwpYfj)z-O58;dzR)c(c`hedGTP6tG(*|}jhO<1VsP?YN| zRLm7~h6KM1Y3zhw)%m|z*h*EcV3ltpe_tj4DOk_m3NBaxa$OkzmC9z4#6cNir~(xw zo(IZ{R)RF?521ubSTx%zjES#i95Ab_*eu45tW4V&QEwKX<=$5Zx}gSDtgY!L=s9G1VysHi4``ek#i_rE1+p*xqwz>_b(}ledji* z2qoEhsMl<$I3?hy=)9W6k!EvV`kz2{l#1>x6spe9gKlvs64h+ui;t~JSSlkI)8gd3 z&dEaxV&{_OozKPTa@1m1WoAXJ?a45}w90v!bHr(@b)S_UOheh~o;n+wDs#pW8HWzCvKNEx`*4t)WLqCBkV_rz1HKQH5xOR2leb*tzntYdabLhN_RC zKy$_nyS+!dZzs9A?TM@$>fKraliJVyCs{U(F&yU61Z5H?Su#qLDPr91rnhpE(EPWK z4W&~hQSB}0juL4*iA#$T&QKJCuU7BQ7n1Y5F0oZ!xT$FusH-1!Ut_CuRUlKPE}c8{ z(Q>??gM2c+KYRb)5cuf*2{rHQ{fSWdWP;ljrLL8oXRlaN8rajbw(Vy`Aj#qb64t$o zXLt|^Y$+`6j*n16*(+R*Q7NC*^XARo-k#mxJJ9uyy@LZD zAM9z1U37DB@NWC5Tkd>3c(=WL)D4$+?&ibCe=i^Y@ACb__wR2%*!At(?{<&N58eFu z@!zjMxPJb@&F8OQKVM#cy}Z1}0UlDxjT`L=&^y>HiMjgbo}ot{e&tHIE)L$}r%dT1RuqERM}I<^`| zUfJKFuht<*rsHB_Iu#L9gX#3ypV}&}r+0xZ)>!$)Ft828Q+ubSU1byFU`--5O=*Y> zB0xi`j^q`|I#Rvu@G*4dE&(JEi$zB?AdQ^kvjA8YS)oD-RZ(kNoJR7&kb1a;;+L9Q zcFZsw3uK-YQ2R!}A*c<@D{$@}iaauK4(T*Im<;LoI-5#nvPh9Jiq01zCI9M`xe&r_ zx69uq{tDJv2mFt&v-wGD-NJbJ5c!Cd4axu$LLdP`_(&>=4P}6!9kdM47_}!INEnb{ zP-7D&hlz?&XPze8u0jOM}dKVw1BY& zEoh9Ob>_I-o$1Z_!U3RmM29;bl@AtK67jGgJM01zDiXl1ZGDl3W!u0Lsno3)l4d`P^~CDq3_GnC@u>XLZ6W9P$yyc3JIx%&Z^S)DQh28olsrLpHxaGOB~M_j z8XbtU7)~9??v{(gigO!Csqj^JDluzT@G=CZ@R9HQ*d_YfdkTSw8r3UTnz`9U$F=xU zc3oR2lx4+{DzCtCrF=O!>>v+uc}Fr@z|tQwtkuhiK%G1Pl{_5iDx(yRh^s>fR*a!T z__vr=(y}aH9ct)VIwK+%CY7^vQp&(t$At}~OC$}9+ehP)JSa=;LR%7Ht9Q>RKg%W8 z=2idMr4V({8hvf2t3)52zA==2-FtmP$Y5H6BN7OE?cS+@YVWlASK7I8XxMAjF|uJa zNvG8_+gEbsuEB4oeF!U>*|F^|_4v{7 z*B-H1e7f6p4;Odsfo|@}?&1sXpLXh@p6U&5FWVQpyH96vhdiHb_xbehPjKIhuk^D0 zC@;C^;j&vFJnw(`idBP_1nwtae)X>v!oMG_{oby*?b`D5YJoMv8ta6$Uu%Z0Zr!fd z3!4*elS!9Vf~^zWQla0NaQ8M5_<7sDI6uF*u1KT!BXUORZwL)kw)zn6&RLWx{6mRJvEv!NPm_UwFhUPH@K&(?}Dh%xixFgDEo zQ?F(7w?&b9hLwDl^2cvgji-ySF5JQ4ZP3>;P{G5g7zqAk66)PWiM*40JoTDJx`vpH zHN(zgIp{;Hqdv5j_%7`Tm8}S$P(K6SQ*shrHsnN%k%xZ&&mS5S6Dq6@ouBa+c}hXM zK;gw4_z@1v(h{RAC@TIDIY-f7m95`dTKdJ>@{z0BLig*FsyM6y*{a{Di*q3F7jZ4q z;kZjr^2Y~OcEd)+9oichz>dI3|6M#Blxt<2neD)@;9XD?Xb-j=30gUa!1|qtRSG7e zcnzZ@@&ll^Op1eKBzX>U?Kd)rYmDpHX`MBe(tUq=;(o!t62KaQ(sh#im3=VupFOH% z_{@q*;x{BSX|F}Na7$j5@S9tZv9NxQ*ZrC*+hI}V28@0*K9ZHJOJHyulYuke2`dF{A?}2~Tnp?R zEZ|p=7e(w^5>WRJdjyd_VX+*Lh%N#sMA3-)&dyy3XvS;k5M!*AlZ;?62?N!TdMqi^ z*os@btl6PRiNtnY`7g3fr&6+WDT%NgLF~f3(BSz<6|A?2eOC1+1XpO-k8of+rK7*E@NaR+n@cg*6|8eJ!{hg)vR+w6Gdc5&zkgz}E-nko z9d7HvtLN3k?(;tFdGWks@%Pbgq45O!Y~9^UtqPX+ilvQ4;$AqbZ@0a_cepFqy%+Ry zcgffN{mDrc!oOO}(TF&RPI4r&v%RFe5~mK1Xn$bA#gyQf6^&5E!f-weqzb2>&mX>h zvyad2ZNr1}hx2nDo!jPuJ6j*v=A1PGk1sw~68lU2Zo_`-%ai`*=Cs?lWyWT=Kk4^3 z8=H-_NrPYcWYV{F%5<{UolNY>beSc|w7cA}m-uidbT8~Pu|>(IeQ@11x7*HOpI)E6 z{Y^XA-rSw^yOTB6EDhe*pLXpdx6@C$)5c`4@%HV+KKzOOWv~a+x7%;Gx2Mxj+k1`U zP#nK5ZR;`LcBUWov2U{m#4X{r$h+ZS61ZCm#Pu z*x$GhANF^4c5;dQA2AVMR&N;L!Jy6F*OYp-R^@gWuY)YZqLqNiYLV;=F=QP0?vMy6bvNF+rQ&5+Oeu?J zMvE1P=)`fQ*x0HhFtB1aJO~ppEXyvs*g@GlhwsFqa=d2(2@wX5?goavqo8-^ljc{c z32~9PKjxTiap(|HDcJ3U#GOByh0if(zAzZdL572m!j@@~DDatvY4z z&=8hVINz)|2*&NXnIASOhYfG(Fk{ToEM~8z2j-*7Gas%Ev8JTyoXLi=P_^=z8oaCP zOmm(|=9~1KNkqyv=Xp`Fnv8@EXlr2bJVQERJ~PjJ56x80LeX*-l!OG!S27DjYpz0< zcZODPzSC6BB~c`W80K1G8=EC(IcU?l+-e2`ED4lit2cC-*X0LoIBFF%s$s^#Onq}Y zoXVKZdeQ(nlzY^RB0m$N5o}@5w11=@EclO}q#rg<~`W!GZN?JnC7YJBo%= zGHSbmOxh4wwI`%4efYhC}*) zd|m5Lnpqx3KoAXz+?uFk5Dc)^YBFBR;#-4Ki?N0gV?jr2Wym6UDdL7E-7%Y(G;z$D z7(%Lvna&5d$@;;#HnE#p&3xMZwExupp68%rXLk3BIG2Z+6pnu0Nd0kk_jvsl9O0H0AqUUoQvM=yA5ckEMhKY-rTgE+vCp8 zUQm?|p$32@zjREyl+qVu5M2y{GwE6pY_ReeE@v3AE(Chzogdo1I6p3z)r);puD;gT zAFCJqb~{!LuldJ~zb!gFuS|2Pg@x2Y$~M+N@{&itQ7EMpBBZ-Nz zk+CPK$v-AXp31B6^5xU@^~Cy1^*Z!UCLd3(AX1PJ_?(pG)5?0^$|zg~Ng%em znYmXg#bPr#8OY&Gmy5;ZBp1tOb2)6eoQz6CFP6>8NGw~5>9UwB$yG57W-%cr^K!Y4 zccN1&;r3-&Dozz1U9Hg_4jSgQoxUt<>-Dbpb3FrvsP+~q$= zKQPk7mHDo8zsz@0{PzKo_kn;lB^Lmsa`b|%BP}*_zu<2VgpFVcLyDnaz_$fj3>8!< zA=2yZ_f}9H3_>iySpahj$SL8BZuj;yP_3{*`VAn0Zs@O2@z-njs`6mz+2NN~Rlxnw zU|{jlR!hrUBtkcswiFFzi`VpbM0>#xO|e0cM0+551hQxu2MMK(jL`sT!DO45y#m6f zw|3=kZt$Rz7{Ojlqa+wMZEGv+VL3;H7Y1*G%>)(>I|YwC=M;CchdW9n210BZ7NEJM{Y6d0(~$GUo@H>g*tX9xl@Xe^^Y zt7;06b66Zxij5wOdN6q%6iRil>VZr^hT2)sLc8i+K?KMwwLSdIfB4aaCSsyL0*Xr9F!-)HV!Ny5WMdTECn?IU&N286K?^5 zF({Xi4J~kvNU&T1>LnQry5WKLeF}n2F;E+bSTR=>MNX8;?rMO#2df&gn^8Tx zNsar})#xUxeLz>~-dv4rx}nR9yyH#ePn|@xq0p{CZ3uw65e*GRx=|Ah9;^VOyQl<4 zwGqmcs5K~7Ee+&olzCO4>DUCpC3CDaM1!NzU5)m11jLb0k%(xdqYlynwy$iL@4)OA z!24hNznzN5<2MuWI~T-%eMf!}7pjXf80Wn_+>YMf9OoSGiRW*hIzE_>bE zz^A}5k1O+o`7eJ>87+UYeo(zK*9r=^%2gCoxK+h3L9HuUEntOk4(R$UtA$HhCR~2L zyt=x){QU95X=rXD*gxO9b9TyhcE%lA^;k7cm30dHwA$X_{Y)NJ3q^|z%sV7|2DQPU zM$AMhemJO9SXFxfkrvV@^!2WHr$=j@kA@$y4R>_D81C$R)FG#G93CES>lp6n7?$2w zk2>Y>;>C-$&f%|)x7(Yt30GiM{{I$t#Mg~QCDgl+ciyd5ZV@-sMTQVjamzbD7}YjE z$$NQO+YAIY@p;*p_3bWemgW8Zlc2oC<>Nr2oFy$#>k0(*0n~LHe30m_JwS-a0KF&X zL)R>$ju(cV!T&G6e4!ZY{+TuyySfa<45V|!DBbe%8aelhwfEJ~%XVPP6W7r&D0tS(*XL-_w}^!1J=p5!ADQ zZ~$|5etteXzlfcjE-o%&%P#)^w(hSX6LgJWE4ZNH4z6oFfSWyItTVv9t*ESwpv9VM zWQ=!8U@&7y1B-#KdZSDLltEQpgUqZnT-CIUDZG#ghi@c)l}Ljg+6=e^`O#rW6E>%( zSU3!zZ$6}^Ffyewd|R}eYO_%AuH#PaR;x5#meVo5zf-+rhq^b6hsQ3apd zQNbkLhDrregeFuLd0_%05vzg>s|WNiBfYA{4lb-MfzvGzLj!x?%9DW%+9Wovss^Um z5jBq(;B6(%6;htTY$-sfg@q02|zV|>62?jEBhCMp4 z$LJ3aDGAnSaMbAuqa=r}q5dV(vJOdx!?>_OYomch{02p$L%Afd+SO4&hAQFo71R9& z1qTZ+WTm9RrDv^$AZ)#2;3bVEA=st#+GZUN!B8;^f?!XOZ?0t|p}HJPDE*|~0!TQ> z^6cX?SQJqbYlIyU7M}>p)~d1=)Egl?27HFpdIjUglAv)A#EC)6r-0H~*eBT{6Rtpt zY!TCHIkFELMkYY}BHEHK*o}f5>i2 z!Lb3=!Hpqm08?@hp65`sTML1dGU`5I#Sdmqry{0+V>yGZ=Wc&sIe}%MP%nrtXgTwy=t_SbH?Jr~T zyWk!FV(=Dg^SmdI2SHb$wF=Zcp@*^^m3)-cOaX={1;QD>I-8aRxZ)B|aIU3%px2J!)zP`BTc5!`i z!R@x4@~3(@y=iZPR81hFTBw**rF~-~-SjLowwQheHXEi~gEgIbTn>Y8=d$>yt>gav zwm-aR8~CnmyltRuVBo%NX!pm*$De=qd>rlh!1(y@$Da+1KYR9<^KFNJYswcX6!!iN zzxW>f<9mBMa38!wz(Ly3-n&9Hv=<8P70@q88^Sge>fYPi2o<^u(Ly0KG!%6gqywgM z$ac9SfsGAhENIaJ5*cJMsMJPeK^XN3ipyuEu2Gq(U%;cso<&MkOs3qN{N({na!%K9{s z1O&Ijd_m?DyfHxA#*C3V49zSU&Ik@?klRP;1wd-JF%!=Ghpp@TNh{BzT9Fk0|Pqs0N%n`WzT zO8vm0WPmbQtZ$A+!F1E~Jqm~bvlhWi)vTmq%&90qnmtJYH6|q`678j)Rfzf;q_|GN zuQSaO=s@5@6C+JFEd^dXRd>b8E9Yxq_^!9<-DR!wu1pC9&LFQp34DVg<%5BMOTc4fNOTrJ;GhPQT|b0*Yrrrc!rf&cB7i5*qoY< zKw{;->XPM*+Z_`!yTfeN#01O))deMH|B-vkB`IGU%b#PS!l2N$IHd$_70Mog)!K5@ zJFK`EcEvSIx8SO#5*Z&mbcw6~3Wq=YObEV>L)gM!dY zn?5RX;KQU~05=xjFHqbf&o-eNFE7R#i;X&L+P=7Za}q?K&5$XIpp7GH~>2(aO& zpAlLEs8usiy(Pod;w{jcX`|z+NOiF|8a6m>=&(U<1HEQkNQ?72K^G?iVL+*Xe8-?K z{~3fO$QnF0*h{E2$g8uG87h_PrJeT6jg~!ndU>I*A^#0^8+{RzFGs*UyaVR5vjZ#* zr;IhQ`j(jf-B1XKk>?4@oRbmTB;-mDFdk}@Hrja9LBI6Cx90P$uKCs;_Nie{reTKraGT9=P%T>1eT!3CPRBu6we4P-1p^e0`m9Viq?ul?#9b0B^H|8mO$$F(Dj)e#oo$ zRK>+ev4tPhv`fe`Pdq-)KH+;{+7{MegCidTNy(nKEy8sC1V@-r9=Bx2vzF;7&6b4B zvxhW4V$;$z3$xgT1af>>p0&)+XH$n|(%)=K+26xt3RIW&gMii%9R}`3iOWfF1b5`gJq_H)0Eqw%tk1{`sa5vB*dg>AmvRZ17@5(!j7~f8FD09W8#olB`ty} zx$(}y(kcd}19= zy6g=YSq?ME?fsn9`X1~S6XqOFC4(JI{?c~=ESa`}z)L=vV-7Gp$0FxB1EvIEIy7W5 zYzyYGWF|2I#5be3bkM3HPMw)~rXX}PGsDhc88I}a5IrVw)hRX4Z<{{(k@b;%;)pOS zGs2&z49%UC12^S$XzU5j%vPjHN#)V(2p=C*kDpZYgH2tB45iV8fjM4ToO5|kGJ~{=R~8F4>D{wx%g$i5OIm@Gtn~zo*sz1`;(4y(R3B2_cY}VwLZ8$Ff%umF)dk*tNH4kgQ=R0jo2JOvYFlM*>_0|)s+fnE&qLdsF| zYK3siLgvOYEs(AXD#0S@Ezp!O=NUOOU{7&rU@)eNbmY0QRGU+Bl~a!zerwdNuF;ff zAK!967W-~;X@r%(7Gdr^dcL`71%fs<4{-W!tY2Ju^XDEfT}L0Ef5Ol^G##kmycWd*}dT%{QeSw?|^tXBF6@X_bM*KZCxsFa4E`+x5Jdn^a6v+ zjYKvmjS)6l(X?~08Tahm*-~UJ@;2g+yj{h?YGjpB=e3A$;Q@HD&*xkC4^a6b?tMUH z05f*J_T{3@6EEyt7fYpx-(T`aBK}p}BKY$A6aL7W-_QHRTRbi9vBpSzqj~;Fy@dO3 z{5VgPN{Q8ke+>`eCA=hwQUVXcBkOgI`SI)=EG6oRV#&`VY*@0Cc)!CvcGVr8;k)cq z{Z;eY;=iL^suy<>^`#xIj&Qz|s544YZI`res`I~p=XROL)fyhLRBgA5RsCTURiV&s zkN#3jZd_-#wFu^r3G;5J-MuSNQ1(IT@*e;Cuyt|Y>GrNUblt@QrK^I4Yh@s?AQ@b9 zWzruE`Z(Y+1uK$^i@`;oi<7|sYZI=@2E&uB-#vd4VmqfGcYE82d(ch^xT+ymSuuV* zHN75P2k>R-G{`XWJdu*{n*}9b7w}rLm_-4rBV~Lg%msKRLaU-`TFp&(TElZKY9!7Q z!LzKIRt1(^23ayz&RPyFN7-q^how#_Q$n!Y`D~Q6(PG3bd@h^bUsIKq%_`eVE$HaH zB}pu2drSoUMn4uSc~<+$v`!ADAfhbc3@1)uoubd4YK%(Rt$0_3_1y)Gy~2A zRZxY&_fDDzV;)E_)4}vdnwbm!#4g`wGGNG1A38|sEHYgds&b#PGT$r4n~?`$@EK+q zy#;K|F$u>|Tt-GDD&SKip4tJ}!e^@a**i!Zk_r2$Hd<~A(==F-Qk`8N854F%|L_xq zj!4qSbx-_kWbP)6bOGzC*fpf`EeahdCp?ndB?7xCq99eln9E(ES|F}%O&aHhIIEgv zp^jB41^pR)j@u@f+9inEsK{iKe{9?a#GRzN6~H#XK{XEB)&}kO!tRPZ7%EpkvR2EM zr*@+1v~VavC}};p=(NBf^J!&^`ixuoJmb;vty~QUiZjO=O7JdvPQ!9KV5bqTf`77L z>J)40Tznt63+%-u5ZA?(!YfududH}pD z9HZDIo`4BF2C_Y5)GG9fG0jYb$4L#)A7Aw38(}UA;%$kDo12f{6pOt-e*5Byqch^Mqv*1UG#A^Ur(cf!=F2aJXODmT_=|sEw##9X z=#JyNuOB@+XrDMfVp{KL&wS)wEO!OAd?cZEM^6cOZ5t34>b6DG`rT^xqBrRE>iC`i z%h&n+q#t@22AeauH01qiPIWx4O*x2df%>rf@JGR{gL{g-sT6dy1$D1Z5 zrb&}Y7HdMXUU+uV3$tm`CR2O4^M9Ss>;1*E^<+8N3Oqi)pqAJ3{(e87_gfI|SNJft zd$HI)&*5*qKd2y=HST<+g3-PWr+|Hy8%GSv?>G1M$4ejn;`YvcABx}q8Jj-YbeRrG zVmj@&zY~c#v#g{mfF4hdy8C9>ttFc&<(dQn;XrEdbj$dd^*v*oaS=uuKz)ch?|Zr( z9Ps_#{QN!d^UvY)*8Bb1-QwLh14E*1nH`dM-nMKz@V4Qw2TeWu>w``n+0wS}`wd&! z_ic4s+|IJbLBsR4e%6R>%MQfh20P@O46ybC1G258t=vv+cbu&~wY?gw+n%SLvedTi z@pIp6H+VtqMz*JO_3b>_5hvx@Tc7pZF1apXDQD^q>~lblstW>+%1w_rw*zgL)w{>p z>dK*E$Mc6L+?e;>soBfZ8Twp5*bnSV!|&MzNRPLgSLo}7>0f~h4o~Ni)d9J-;2_za zZPVZT*Y!B2&})-43Rg$R)^O#*#)IZvYM=>M8dDsSiB%X#I$?0l)jzLIVBtY2^NK0w ziJ-J0L3vgNP3FEX(ZCdQ zDZn%WPs$Ffq_74idxI`6n4m(!7mUC8--DBQU}0iu%C}17Z%OQ>37E<(!)r-tNVaG? zKlgh+N3)R$<$Rf$T@nfND#5a+FqRA?8D_~F%f9k0MIx1rva*EEsm2*5n|^h1gt;_# zboqv+cTFsZ)XA^8V(xbT8KNi2$V_n-_Xgp^=&npR(iCMScB5n+p>C;xR)dkOIIzOX z+(_eHWmTSzB5TBpj4SnIEUD>T#S@MX15qRD(+? ztJsPNo+3~-M6Vhwe~`CAtyp|pEOrdF3wR1I6q-$A=7NE_Pz%>ovPIU>TU&9aHp5D_ zrv)_yEiAlzTIeXXfO_NapB5#97YGVwvY4=7&El#rm-*X8=li@#>k;f-v?YrSKI3?G zXK|CrBRYbo7T?xx3e!((*mOL9s^~(+6+Smf{gNaFJBktw3wIVM_`?5+CF(ye=n;iq zg|+*q|7SM$bbG_#WaKSe`hmetW69sruD0vzr?3R%#m?kFI^YasKM@ z7f+r%dpCG;-y}}=^t1JmPp<|0!AG06(*EN(D-TN7)=#>_?dn58+^r1B>*jQA!HZ8v zMz*hC`*{$>H{`3+i;Y(RcM!Yv^~T2R;Fs@C47mMdvEMUA_RGVsOXoc&h|$LGzVQc$ z-C#7DuDieg;_m$yf5_iIk3Ro-ZupNc-F^yl;W?v;n8-wG+}YUZ|A549Wax(;8KxMG z%cDvSN&&n4JgL~{dt=LY>T;+tvqBA!m#{S;n@aXP|KiP0uQqFY1Eed2^F=`+ zH`~6VkK#KMx(7$?P>39>0O;r7M!&`y_y5zQPAU6aj5`mMbm806aKjrYKVe%e!Z;e_TfP| zu04V5x=P5pHwR@dq2G|q*R@2WEldyT$!WlI?W*ky$q7LK03ZNKL_t*RYC`XB7HvO- zIu|~^fXmx4+?0Jna$Zf3A9IS`v!m%iby79R}+cXCV!)c_+w2=9OLVZO=U>1O(f*g zf$U9CH66NfC=EPKgKvhWUktJiLmA?IGnpvk&+#3~uAugzu{o2b9$Ly73ux1{x8)Q~ zfmKLNN+d00NKuMsO!CHeXw@`*Ef?s_L-K)*=MNZn&S>NrA1q3*AB+Sh?RSDws~9~< zq>eD{JE2l%1&IZ4i;avDdNRIpgi%&XU=CpI9+9tLM8JDDe>1ByKVXM$e2prx3qQ$y#czOe~u^{;e=W2%e^bJA~p< zVl`!eHgm!*|P@+h?YLmp(O${gQ)9Pf9xF0Oxh+}-NE zd-mk3?a%1jop*zptb>1D4N*Kle&TR%QN?)Mx8`6&L7bw!j z2Tp(6`!laYHl$=BrPs4}%gMahiX47?6&nUl68W)tz-Lc zEC0kk^He{j#3PV8Dc_DY8i0+pE5S9DG`}`tjwwAb7AvjMsMJ!&@0cP4G1E}cplmzF zWO)@Vtr@(Jz%Ct0%J!w03)7BjP*z#3*o3rjklZ7sFHF2v&vH!OmI^TpPEuG+D1+%; zBXux1i^E2+mB$=Q-d8~)4_h!bSVi^PZIhjhcdZzW*U;FLp!)m zGVRNE(i)h{Jq%HLnKDSqFXxKR}8pj{13_5;$WQ7S|`-KSv7J&> zNE;kyd^y=vU1-x7yV?n>3o^WlmoDi=O=tPrp%A)bcuh(brzn>E4_{aJlSbY~1(XV8 zt%9(LC{Z8`Qk09jgHbTF_>sJ8X0&Ns`;inQTScIV&6;dpZ%j;#(WIR;)MOI5V0+<( zAw!}`1uu91ulG664{W;^Z!Iz(zZqg`Ih^Nt&N-NW&bSFn*Aa^pP7rK=rCV`49c(sG zsYW8)2Y7I7xibmG(uO7E-GS~R+?UWc!D&92WG2|Y3=2*TGXh|X>%6`v?K|<4&E+w!ftVW6WGLVPZ!^1^tctl4fDeA%0Xxal4%5*xh8|^qj z&$1WRt_MQj>C`STIuA`!8W^3*gZb`ySdIj-5@!fv7#hRXIF=whMj0B0ml9OL(Mx0z zMz=tUrxPjPkS_mQi1y%qk33-xS+|k z!6%w^=>|759zS`a%g$94qUD>n9!0)>dpNsP{a(S;9;uQ$vLmJSaDo8!Y`YF%1p}tz z&8`R+$3r_sL#eIqRCwS@zo12;1Wl+bGwPPbAT;w~F@Z&weR^mBIRaVgr<_;ykG5V@%XB10S%LT&|KI$&D zI#WzS-7NN6_kWr{>|y_kJ`^$uUU%77;2cArUD*NJ#qrocTiRKt&z-IncgGK!W0mMX zOXjEsYMR8~@wsFWLL^alro+j(IiX7mj?osr#*$;fxuAYkJuC(43*`GuR0F93acymfSAp ziu6F=IjucsVC};w7Y|wiNjdNc8AdGeg<1)k-v|sXH&+m_Kmg3fT6C|?5H8__S+>qH z!A25s!rcR+J4{gfSp*-=Y;YqvLeB)O=>86DM7miLOrRXW#MQ=U$bdIy2z4Vo6itK} zQ&|%mA+TU!fEAgHY#@TcN6gkgIm3871^+8VA;FF#6!Al)#Nwj~Eb*~Rz8=t^@hd@)=9@>HE z1}ArXt^3{zAutH6b;vtv9omN~*y(jR;_&9c7!@rVwPN(y;jB0--Y?Jr!##4S(vKoC zPeT*j##v+pjQ-;ER$%4f<(@APnV`5bx)1an-3QO*2`r}&9HAX7hN0tV7c($(Pq+)y z&I52dhd-+c!JOO2A*vh3p#X=};6wnKI?z|H zyCfpVY{2h!h3We67GbU{lgR`i>&;{kf@I@BLDvTx>^j133DI*BC;M#W!;t#g!t3qg zG_Y9;g91zWuq}Z|2IMy&ej&A&0=lt1G%T|61g*%S-$GEmM+Ef-FrrMP6BAk|&{pno z%{iTjrY>2t8zqEA(-**--rL(>-8x1!GFw zM56t#Cno~l^Td$R|K&Mp_)^oygDse4=A$PbjzUUArO_GfU)(o$Pev8FZ@VUrzmC;n zaZT~Y_Ldr@?HfK_e|6Mes(hQ8?y%U}p9H}2v!~j{+vRK8G6uc#Ms4TybA#60Y^N3Z zc)L3Ap!K}~xHI8=Kl9xBGeie=x2u?k)^`>F&CRY!UOluJyUtzDulhvC`0S4=6X0CC z+RWRRCAM&2;Ri&1x#<{BEV6qI+@h=6n`9Ew-np^U;nUN(xv@tWg+3h~qpx4ENsmX5 z9t{r<|MENbXtP$Y9(iVO2^Nwg?RxCTanTD#*O)dyJk_iIr!UT(3z^zTw()Y%ZxDaY zJa|%7M{a+6(L~ExKVImHRm(*206RhEm`wM$EsAz3_O;%@`PlO6OjA``*5$?bvA^nt z>RR!NRySY9F656RS^dBB^E*RrjG|GBV+1|0qrARb6mbyTaG<` zy0dm^^e!*PibYfHcFL`R>^9m+iGiE&8p3+Q2<3YF5DLe zgE9ZiBV6%k#!D~3{pOFN%{-pXa&7uHW#?oCHoY?c!|GmmLKAUC@PetkZ*zs|@QejI zT{8zYfUe>V)%2O6*WCBnJYedL5b&bhjESmlLR^?@LNA1LCANj`?hVo2#sI672H2r% zvm1oB`}04rhh|qS6U@D4fX?(PeXtsZ__uGy%v^Vq6-XN#hP2VmHk6#PFc6wx?Geh) zOoBtS5kZ+b6xo=Z41FTF#q{$GoS;L9XqXfL><^*T45N-oAMx8se*`sUpAXWcsSr`w z3BT_XYRZ1VFP#UUMJNMWzmWg>5xYRF7vdufMq?rif?uoOSDC8#{RhZ0q7_c0F!-JR z1E<3`bb#E2A*aYeLi!OKZ1^f(!sCjURsvg5xQ3?4;cb_at-wYHn?lnw*1|O!>Rs;_ zBmj@{Ko%m9yx#bb6;wCQwvtE^ggvFx8Ygm1IBKO+aC_zihEWh;9*G`}@57@FF~I$C zmNAJDto|3onBz{S!gO^P;-h=b_;uj0Ph@-?a7T%0^6^k&TM~}B1!hk_(@&R)lvW&PC7g`x4-nVYo+3Xu+lc zp$v$#ft@aoI}=UjxH#KZxChiWo9M;VrxS zgUu${0^tupV5o&{aJ*t&5%OoHFe33#Von88Hh52R-VuaG=nc~X=oG+zQ_|%nEhB=P z;gM*M1pCKCDvB0xVv7J2A|X}_Ary%dfb(h3E(?LDJ+PuImCy%H%%ZhB>w!24`Gg5@ zTy%D$DOMt-Pdw2)>eZfn;sjyAQI_~J{{>K=>`AG7O1NI40*y&6Dau}5iD>?WFgPCi ze>&dEc1sLn%{z4ePECHccJtga&4X03Qh$5+{RQ_bT``39c!8kC_uSA%UoE+GSsye% zt~TZ^UAJJs+m>cM_OSJzdA)7M(FXo|;gPsYa|vL3yj{AxYbnP3f<`A=&-a@~P0=Qb zYc6HBxaJUdI9j?=xCz{m{WA5vpLj0k+Qn(_d{fD3i)%6%^6djRPUx{!9nV{_;+bMB zyna_}D}wJHAGQ0upuwHOvnn)61u@CXL|8t4|IB?HoO?rj6SGcZW2dw=Je*9@)7+!E zQ|6=)3(@yr^37QCBhl03wVSgR-2db2YJSq%({K@`2$3E>v4_IQ}aIW&vqu0nXyF< zhYw9-eR$sY`QVw5XeBh+_5EDFiv}n?N*d^=7xAg+K{CP7qUQmT$^Pa_iBC+#VL2Mf zj7((WBW(A5_wFz84D7#jHbu8bQgr7;D#do-zqaZZQ}zqR3mKBYU4l@;r_D{VGL|va zjyArQowv%}NnJTB9dFD_mtMcx<{0Z&{LQtlCL~*lqw~43BY!k13+CsSqs&z?tbQ25 z66~nK*yu%IrW{d|C#%xYkN#l2ay&NnnZ8Cn?Z_7BX^r(UOSW@2y`Ru5t6h61F3$~1 zvUzk&fLYok@DgL>l2Q*&u0CCr`Ysw9j@|X8ms5?)`ALFq?`FL?x3s$?)z!8~8x3z# z{rltf2EK_qYw=Y$A%@LKzW`oZ4C|OML(!#l7K@Lc&c!~~>*XhNvDj{19bLTl zde6Mq?kCS;&*pnH70tC0|w=>r@Sr9974j-# z!R_p0f~yIP7W>~^j$fP*I7lQIHwMFl9@GyKDi6YxG#o@x(lBPugK#RLoFO*|@iWpm z5O@`|4(A33$IYX|!=s!&IUGb57SUtE+VSDhFX%uDdJcmqMHvTVe?lW6V0Rp%tx>lB z9&!<(6PsaHNB1H4ijepdOi77D)vA$PVq?c<`{X&*;@V7^R99Qh9X+u;gA+#ISB zNbYc!w&(fOY+wq~W-cU*z@ao7ARNU~c$UY_ z^pps}b)*Va7aatufgN@U2e1MbjY&wq@xTr0a{fTU*;!r7^d}0DQ2u@HpL2a>e!y)%AMWAPDoxLj9*1 z>8AjT7r(!Zz!jK%6N%Ah*Oh{nE*{r^Xo;pnuMp5`tGhpLo2s%uw=t>S&zs9FLRUiX z%8{d9c(5TQOKcJTWeH~T3uI=iP32_fqi)ALL4X*4HxUQ#oJbKo5)4kf8zEfG&;=k! zXET{l1`mp7MsD(O;Ng8|H*;X2Qlz(;Ed6IWgowQ|b!72BfU62wp=j^c=P%U~VflxV z5Al(ScqT<36RA)t6sH5a84C4=LZMV|D3zh>P=?O;hN8_Woz7S<@o1FARE!z$8~M*R z!CG1IbierV3J_E9%4)}&yKAo^EB5lL>(<*`lkSpdvbUn%cFosWa}<>;%z0%YTozkT z0(F8rH8-|bQBPJs-e~r+Pw}cvwNPIzTN}wzb+D!Vwxv9OJ z3)7qSAKLk&nkM_N7oW{mys~oA6~2(l#}%1hK~4&R7OOSIXgMSh|CMFytjQ!My1S}^Whz)RGj!+ryqrNX#3=_JVJI_5^!3AK}lKz+S&}5NVEOO#WQSa1Jh}j^vEI#uq{k@^?Kn*GIISi zw-Rz6sEM6OZLGc0cOw=HP>afMq(K{5KVs@eB!`}UpLCnva9N>=TU|Ri@`q(t9o=@$ zm^2Y7&37YyQV%yU+kx#UL8o6-`61Kk5O>6&%oSMN$wAMY+{{ReNpxqwk0>mj1pa_c zT1OULaRY7f(}<~@_MPHUJ^52Cetn(a z(bJHPz?uX#7GbF`@5@&skt|D%`%$q=_w-;_+?kDVjbW7@P3Tzd*`a#_Rmh{Jv(?!E zQn9!!VW-Lg&JkFEvC0hqdI@p&;X=X$nyv|(vF7E4FCN3oV$7I*NQaI@zR%8r>$2Sl z?*Nc-IbFq4*yr2l5P?X~&UYS8<1GMMAbNVFu=*d7&xwD-(SN+X;^X7r4i>h5J65Hl zdbMDDddpPz`0erkqRt6Ld$LQf_u2u9dsE)7w;ZP6i{H(A2M}R3x5`Uzjf(O*rt!k} zSDw|wr-UH0V8ALC(KY)@UD0AoFaoz;#cVIbnle7Ww|tx4OS?q+)yei%;UR}Z5dm2O zd>`m=g}uS_$u-v^%A4LgSa8%6&BvX%Un_4rp2RK-fueo>djExGSray3<^A$qr6gdt zkSvJ90*7z>bRn@0tK?UXcV~u7enQ-dP$mURnu*5=Z$A+DrT7S!5P@$hp2~d42pG=X z!26Ck8BTmd`xgXRT+6^70sPc?B8}2(f3Ds9iN*@XRQ^~t|#+oNMf6tLdm0#wUv7}KGl6t}JMK4UFiA+??TBuNd9CXDyBUG(_HHx2yXh`-%?pD4 zM!4^)JQaVCs~-hvT?3W8YNgWl^xIFYvoIc^tpOPv>|Ih#zo^Pa7oxs$%(5b*Q-xDv zM~mzXeTDT6L`y3|EHQG{?TF<7a1)uCga!Uva;`X?L){n;oefC__?Ui=p!k>V!0c(j zY#ItI9c@X@l?Zq=pF>Bmr2*B0m@p@GCulC~73>&LJB9no2@|g5>m*FUoHrvuTD~WM zoK7(MSw}>No)o?-Tvos~jeL%DTE$=`1Ciw0NTLLJRTAmY0>WA{ovtVA2#WRwy`>}= zZ4il+!E_zQ;8#hkfH8+o&?20Ga4X;yR-5p;gd2N-(wa)(cq_!$C2Tl|O2R`5AoTmsTHD4;QN#v-s}4>qdG^GKlgH}tmkFGt;wIkS9$$r_7jL`OR?dlnXL z&|u+#Zm6DB^Li9lvcPCf=rofwFk(jXn%(T(9~F1wt~ zI`q%Tm_NCTZhvx9jyyPU)4HAuWTqz?&%EAC001BWNkld#^ej ziroj+3c`Ln|FtmCM~aFHHT~QCBO$$V_nDxtaN)1#>A?7?4+P}%zcN0S35UNB|%b9Tee7bN;C(>ErX)Eu)pFdp~YJk+v z=+oo9Gx`1El&eK)bbL?Hlx`x9p#?1S5LJgU)?V$t<1XUI{moM9Ebp)EtvfULx;a?A zkT(!+K3%xLpt>0xukPk&MyCo}+g(L_^Z>J8Atj>SVq;I}9OY79?bUA}DZ=)w!|)P1Y>Kqk9kr z4e6DWr4Ee3a{k`KAvG4fI^kKRO*(l6It_6!i_WH!P+lDt;UU4&Ar++6qm)`nv?1xo z^Z+L~duC3D-j!rQh!sH)rTmpkkGr9hLnTbC0mDNjJt1^BGL%O2RV0nQFaJsCb;Lsl zl5_(H(>gMq({GuSMW?U8X%cH-EvS+=5(L!=d~3rbpQ%;|8!{EKWXP3W$`DXWjL z3$6+3)`a7ZXiL7D25c3EEZ54JJTYg>s3aUb@;QzKSkVkTSYx-Zk5n0{(Ewwixx$Zy z+`^jVQi+t@1JjG-C_1nOR>ojK@H?}HStE+94J+u!wwerfqO9G71us*t1enbx)LmOu zF*j-%m`F)uFfB<`boTNyyp`%_6Ju}}sfT7UD%QE+!nQ>dmC0-q#J1PQv9nFh<6ual z4Va|CZAObxD2CN8G*+=JQzvc6$O`2sj$Wf;3u3Gow9!$RlCUoJ z#Jh)J3U`Ty?ryr=? zTFLhzSkX>b>4?fWQyG``{@@T0f~xTG8cxte zj7SdzY%u@}oem7R>M?S&3&XL>gYGsKBK1<&0mn2IGkqfhYAnbLkJ2%NDxHGUg8A6> za_@^?!U(>KaMz1+;N%b_S;<7{c&JAZIZ+x)asezSh{1{o5ssA7i9`wJ;RH0&5%e-7 zBWd&nCtwPeTgsr*jHrB-4j}QW?hU9024F6;HW&x3q4)?+qi#%=1}joPLmdNKl7t8! zA%#QE$Z+MZ3o5KYT~k#@z-AhN1#UIruK{084t+=bHqs^qg*qAgEZhKi?cw+p6t+V?{ zE6>BYs8A0?7O>C+SHgnj90@O*kvX+UH&olP!3L$V7H9ebLswKp3k}|kHzp*;#6(Yw znw(TF$X@iKv6$#)6f;--!}j}pf7rA$+o~K7FQ#eaInVdy^Kc)y543qMQX@%ipc@mO z^mcoB$Sg*n>1C=2LmDGf zJ5~ZsdJ;JcV=klsyF!yCQe;wV7cU~wz10#^vFHL|l6R3^uHUQttt;V;{K>>>-_?^F zi=*yGOZ6!i9ZORe{S%tnt}S8+tC{%xdZDiU|KOu^TED$^*%+O>)SgA!+U`>QYR;+7 zKhno*XewVXhSbYj4z)e{P*3ai*4HWO&d0JUQjJ=*FLZM<#mGy2Weq>AJr}?uHS3BN znab;BhiDq_);@{+h7MygeY1en`RHr|Yu?dzC9Ok%>BL3X00yVEa!LnxQdw#HrZX4E z^DUI1E9Vm)O#nESnNhj=Ee@;mfl@TR7pJ!#zIV;eyn4bO_|=b3V07v8SGqw5_&!&p z5ry#NJ{ja!0?+*F%+FkB($zgQf_cpdSDUCfW7f)uFcZu@^VKQN8ha#|W*B7od}jE; z8xmkr{pYN?&&l($2LBUs%PzQ6e1;vS`>#;^~%uD zr!`w^`Siu;gsq`f>Y1=7e^oT)*Q(3({O0sTxELsxPcElZSG75w#4%C?qaL&E-GLU5wPOGuNfk<&I19L1f z)`klrUC=sf-~?c-5?POh4r9+K&Jjs=yO_4JGWe<&bZV?3*&~qO00M#`!Vv?x;iEjj zl=(kTD+v$B$^m_78pyn z7naxK@RB5x(i%u^?olQ2eCXA(ChZl3y^f-hp*bYfSZKjPu z4o9+Z3udq@GlVbh!hbhibPE=AHx6boSp^IS>FaEt zk&JNq#^6cLS-^NSkAmj1pbsz&S7I=b znS+8Mwx}|LWC`*H=P$4t4>&oB5DaK~|3bmp@5Ib=7G@cfD`aQo9B(E8TWQSg`SA?D z0=h<$4wHyuP)ekk(5KL*FPX9bELfxX>@(F3JkFf1Fa~@Vi9q{ zjEN>^sfZ!zA|O{Hl2ES7Mb}5bH_(1n5`05)8S*Df36!Zr@WIH8aqYO6p&8@`Emi3FWQy_udnCRdsI%nQGhGEYCF;>({U6T7M2r zx>-une)wf^u~t`A%i^Q?rImK`cDH&;p0{>EUh{gXsA>zhu2l2Vi<7n5R{CpD;c_RO zP{a|oZXM9K>x(C6*Jn-b(fq~5WwTw2wAy5Lddph9Yg;c{`H}kWR6}D7bSH8lT@e$} z%nTNdU=*R%7&+jI_TPC_sw)`6BBj;KDK1ef(N_J|<7PhEBzwEuTqvI}-wZr62TQC0 za|#m5&Yh`fKHhrxuFj;}%kqn8qUV1CRp=pCkMB%O%w@*)_FC#f@G}I(O8~3hemx??N`hHgk1ESU`^{9>)1RImwTBwf zmpTmh)}yY8==`px+u!e`b{j9{$2MK;Fx8_y>J1W0tQT`{Tac^-A9JWPW<8>NqNjAK zetT{rnyIhqw#*so1kF@!G@7w%&B3+ah0FQ}Wqx-?pgB})W@}ZHuX(3fz`#cKSBG%< zg7Wt8uwZy_v3^M3-2*uiTu8KQt>j^Nuo+vx_U>8xF%MoL36NUJHV1wFlxsI|iQdatKH|Dlqs8ihX1k zkmz{8K>A#W$4Ruw`a+|vq_%-L@Bi8ZM*u&^BfUYx5qa+bBd|!P^TBw&mqQnN^T9wc z5;$N;M}S2*5+hB9Ee^-Y27?403&wZ=nm+Qdxe;GH{KZ42ICemH#XQjB%?L7q;b(mq z#iElj_ogovIq+<<`-SnfFq9I2EJQXyYcaNEAzSNPkUVf;I`n$IVlPtT!RJ5Jl+! zEPP-X7B2?VZC5vB*Dy=cTj*oZhQUlq3>H?Qnr%oVgu=_)ES2625^=Ul=KIHDqcNu`Ul7x_+e)UI1Q!IUl5F|;+~R~@nX_m&WR+m97hD_NNoqm?Q#rZ5<5t! zAnzGvXfYOx{JG+uq+pT@tz-q^3yPGaXYo`tvI$ENUy?f6{}J`(Vp4+6`dt#&qscXc z5}jm)q=#2!WcY?$RfUJ5LQHGsy&>|r39zsxL*wtp#>SCCNDmx$jU~olo4F{B9VJwx zQLlD|N;{;lFv19H;8$?5zlPK*)ewHr4tzTO2!Dd3k6^f~GK(F@FdzZry{+^|V!nwoAZx4WjVRn6Dn$!Qz* zfG^7pRXv|*sCsN^aVn^#zfWMgfpMf;fAi4s2~t>V34LX;c8ApW&eH$LI@_MK@-&PO z3N8<$1r*|qqci+pn_sb^niUvr7~xa8Mic;<_Jx*B_dijB?m7%WIXA{~s74 zJ9^^(Q#LGLMk8IN4Eg?($fQE zf9W1P0#~P}-zP=0SI7BAj9x|a1{G&5esy%UDDa?lL%&cKCwjt|UZmfdT76^WIQ3@) zF7#o%85+#h=YbAUi0)7{7Z$jeuJ)oK3;|w#Y84U+aLNgqq_;JT3k^tQfaO(TCJP}* zZ?Sm9DGXZVBdW9}Rk%jv4r1sTJ4AFrhrQ)>Arq_fLySAq9gO-=@2Q}q^bfa*1C9X2 z;_`I^40gDo)2$N6ib-b(Hj)>@4G8x|1K6|>#_|!5L7UuaOjvaSM9D1ZPIAWGq{(VG zT_anVoy)G2fqI4n$XVI8R_>;T}I)W!6IB{T|Vj0i| zCdZB4C1zw9=R)SMwA#0rf<|yO7%hvi!1{*_<3M|Nv9VT5e=}+{DmdU8LB9fn1I$`1 zB|&mIhmg%Krv&o?5(5V;NlZuUcnV8PH(T_A4xPjjLCV1SXrF& zSU}Q{+g+m1B<~nOaOX83T#*DP0i)COF7f%H}k7TAG{7<@*Dz&&uT+<-Wf1^&78WU%bA3ahpDJ zUqt$Hk@)gSOBGBnOJY7t;;C>*RG8XRet^UmVYc;^+YRD;Us8UML~M&anqA2qb4Srz@qr9bc5qp3@rFz zPDd)NkFIIZ10F!7nP;u0xeh%oHiY`PB0cb&w0MBGgrL;ZRgCzfzKmBln9zDOQn&=o zL>f+J(7*-j^~x}`9;*Qe($)+e$6H%pydVQC7LK5`1I@k7is~wD;4g%@x1%|>o$$|j zPhnfJgCqb`Dd+}NGi4W;=iJskLunYj-T3y*cl6tz$nK~0*+QoJ-CPJIXvksZ$-R9a z;u41K;;9(nEC`H@(I6p~U#=E?_Mk3m4WddN-(GD$EhIe0wx8<`#}jLSSD#MJ93Rb2 z9{4H_5_Ffcx&sy@J;^Yu8Aw&be3Q=?8}xUPD3_khyyx=qVbmz$LHmB21Sp7X8$CAF z{qXzoWVIAb+cCuZqWDO%M_Q@aypptmFBW1cqdSr z%vNPdikFN}4~)(qOj~fk_%4H}yCB8jb=tnphdXCSF-8W0?;B9-MMO%K%z z3xbxlz<>|(xSepYh(!{HSk0(tF_p!gUQU1ro3!D@27~}}YOuHo1?jMglJ>O!`5(HZ{9utAT(Of!6M z3y2yaQs8#m23cAqt%1b11p&Yq!@`(!9ikOTMj^2zxZq^f{em7aDQ?KTVdg?JUD^QI zXb&0bVRa#_9syyAajQ^h*37v`AudLTaBL`q9x!GFw1_3ta|s&dXpTK%5H#6c6UQ@P z6S!8}$QQLr+5-LEP;p;a!=4wNU~CXEOiwQe1f<;z!QH{N;gD@<5>-@)h3 zd%VCwW8j!XcL`_npiz>KwhH#M2i6tYNGp+l=HI~+lV^TM;;U#Uk2I6~qU3BHAB67q z4-R5T3n>j z^Vo)(ryqxu+llF{A+tlel3z*LLyC3$NT>40&+(5RKYsrF5vNb(PoF+re7Y!4moLg4 z=jHQ9AI^KrA0Ct+oKKwp?Zd>6H{$|H^*>x^1*su0l~=dNVqXRb$6{B9(3RG&N4~lF z$BBuXbb2uI=)t2A(hdw54GcVc)=EC^Mr*2kf4cPo^TvI*U*9kHP46H-K{@6)0#u|#zRS8pPkHxO8eb1M7C&? zGP&5+Sks-Rrgk|lR5yL)dWHVRFS#6WfSL4Gc52Y#>f_00^n0J9%uE`Kwl5Ty&e z>DfftnHP{cl-93UKH}jkR^VQk;Ev$njNdp^NnNhQ?$}{BcLes)HypPM2|2D`#g1=D zKI^_$pm$1pGi#D%rjU^v??xRJ&Ls4m{XNQ4%XSe!!~qN#M&i;g*;c4tDKJ)uyH1~G z3ppvBBDu`2pB59Iv!3N&j*9oTF=~8zH*p-)L>nd9vYM1~46-1hOd+Vjg{KDIBJL9j zi1bYk-La<0Oiw0`pq%#o=&VGK^le6WnIc{48Lh4*)(79;ZIk&8hOe-!$%&CL*AAyD zq%vaY`@b<1ydn%mmfhrlF}GF2_~+8xY878ZUeBJwjQ@wMtNm#zPovZJ+PMYo(stW0 zt(K+~N;{OYnc70>4rN%~0kwbx28kqe%M2=2i({I8Ad{HzGGU2Y42i@~u1+%X|Jdg|ze|?v)B@$+3;01f_dL&eDctKUHk=up$)jxr(Z!;(gwkT4QP9a1+? z6156tk}5%0i$yJKs$ff!=cH~}anX|`A)%k(SH;;^D%N9h7Nw;3BH_v)yha-REL)eb z=|xeYJ^>{)hfQ+bt@)W*001BWNklXp;pc{wciXJFm5E82ftc3#%tUy^`1ABpa(CkI-6%VDMxeEB6Lh4L3*d9O& z(k)1_0vvv2zXiYzfDk(;eDs=-xEws0kk%Psr*D9e7^uzFgap?UzJL`CNOrLT)=r=v z7@lDxbkJA~TSX@Wdy(h}rqYCq*aoK|oGz~b?fr>>Sev$CbE{1QcrkTG@-wtqMu(RE zgov}IZE0+O(dv*+Bk~y&W*etO!;A!Gh zq-I1WA}m9E1(fCF$pQMMQ&z2EPa}}m#Cd#W1ELibR6y2oI2N-5Y>1)PG7Zzg0W5y$ zSJ41w(!;R*a*G4L-zdGux1gig{OZucU>-#s19rj0Zdc8iJR>4{l`t1x;b=AS;5taK z%T*pE$w6N(FH=}D3sC!%}9VA zgC{A1n}d`RUTO3Fz6dy0(~-HF+5YXpojZ5_b?45%@$N1?@7}-r{rC5Oynp|}g9lsq zv-R87)~&6r7cX8sfByVsY=50$EVeHoYkyI&(&D=(n~wdzd^&b?Ba_KYPhX|SW@V|l zL||X}X0fzcDiM%0W;Xv+wb9u7$uwQHfyd^lj?6~m!A!^I!HrA@eJQ;Wfv?I`D&bd{ zJ|E5CmICKGHmVMOa`0elZ&hz^D*=3KV{>b3%}`C{P+#wwP((LZ_1lOtdM?Q4j<@b^+y zzXEP~1KeEGSEJ~#_IPk*u)g1a*1f)0*f8SZLO;|Np})`r*aVK|=1y846^ibb{8y*f zMqJ7HemN)iT&j)e6}e0ZI5#^ zmsgU(ndA1teE(`rcR|Wt?`a>WFJAfa+qJHx6Q>_`&G$HpUE}LZoM6QcAz`6Sa?=x+ z{f&%t-SpSf9n{L%o`;Z$9a%o9&CCTTY0pCQq8i`5pmx z7XLubbke2tBq@!H9Nxw7p40X(B|Tj;{sTckbK!Jbv5W4oR@&Oua9>eye6>D$yz|Lq z|7BkIKCbA@@AW;o6z!M?;n4`H#7mb5;NsM2PW;HVmNX-=t3gYB@hlvd&r9VU?1eo1irPkPKMxH0i;gy3OHQr(%`sh^Z{FmAK%8d zm$39FI)Em@a_#L9T@}*W(6s;}tL1et(yk!B!tj|uI30rOIn7mubR~U;c<3|};oDkx zi7Omuuq{Sap(4quNMi|X{78kHGBJT>@fEzkYUaXhOOlxy&*7H?hR&SCfmJY(T{ZT< zGFDco3Wk;wi!D>x&&aFPUC?h--&A%puU7;Td z#$W#RMDR@Ti=lJfFjmKPyhApd>PD-1RZMIc$ zx~fA1FME;PkuecJHO8@&QOt*N0;t&z2yKa`A}viVmU?=#L{gSi1VU_#3#L`6rg zG^N0Hxs_0`Uzn3Df)ay6(@Q9{=#ndtOGhmhbQwmj(9OUYJD}(Uet5f^wb*p0;0R}b z=R!JPS*n`OY~TOqcT-d6&V6%k|Kl4x=_ozV(b*|JI5jo(*YCFX*C7c-6}EUhq*bgt z=Yz4X7|V$<86H2MR2;j(eK;IDOdy)sn9fXJoqoNuv%S6j?AddAKBp%?p3!6b*~04f z0-f5%V`pb)a%X#YcXubhv$M4OdUy9VJw7N&(82N8_|Wv##b00k`ts!~dVBlf)rVKF z-oJnU>V2;8_H8ixpKLbvE+~k8?9H3S#l?4vrFW&i#Zt}UW@D+6u)leuvSV|zHPdmF z^RT*-vHjh^p5SC#+hx<|LoBvp$1egozEmCz!p*!4<{dEMa3vd&9-7Upa>l=ONF8+a z-vwzjLVX3pug=VeO=h)DjH)p%!i}xD%(C?7!=EC865!j%^5_4(V+$~2E|{;P!)mPY z)L-;hSk{U3D&0lQ%sc{!IS(2-;iPBj&=;M?6PNUpZBB$^EFTN4$=^;UJ%xrp{ICYS zRx5NhbG?T?3~!Tw`2$@TO}>y6YIe_d?;QfhozpAV)k z-GD7=<=VA}ZT1}8LAl44i{bUGm;^H&MQ4O-WUq^X+oM=I z1{}>9{lN7Ze|Mpf%Xtbv^gqdFv*#aoURulMa@pMA+1#>!FgMwA0|1=U_v^B;@gu_0 zB^*s%E~SuxOD+^wl^D>2Cg(06keT1=^X6vme9Ts7tHu+yjC0s5<&y*C1iHmYvCzsuyWL-=paPT zk<;q4q6@ge&RQ&-E(h_o!==Po8&24boUE`y1QtxeMgm}%lIW#_&JggzAY5TZ`>(cw z{YP2>%5<%f#n4bZ16sB45FsDy9wyTcE$309``3#3bBOB~&^d^Gu??wLxE>8k*zU5b zDwJlZMfI;kjHMBQRl)mS*o=7a93t*ZXdYtWm8eNV76+$u7(*YG=@CDvDl=&0IgKWv zk&uH0g@6WigenZ7abFH3X4fx4?*TPuV`*4;#pzcAye3wR!CVLoe?=KbRI(%KzieIq zPg8jol|tFJEL}={jRUqKuku=?RAVirv|1_7j!Ft*RF;vXST}qrjKYv9A*2aOkw_p2 z0){3sV>7HIvW_G&B1{&^tT?RxU^4!=*-YX;viIE21I_HdzCK>x7pNq1dhR{<9QreZ zKvXSH1;ad&P*+@o2tw>gdTn!a)WHHQhYTT=Hi{`>0@!Ffnq~ym#B%8&>n90mwUZKR z#nC8SvZ9hiVBC%lvEraziO8)Yf#RC=iXNVk7*4|MkzR|UGeVVMn}q^0QO39wmlQ>m zqaAV_5y1qq(qsUgg#3RgjgI*7$AyV!{bU89z#MQnjT9bS_y4y=vXMOa7~&; zSpaJKw18$XJ95y^j0ccK2z%-fF?V`PC9dBSV8X$Z+gk&-UlRZWaX&5{yBl#7P`rDT zK>3YubKWZ@dn0!Tz&d$3g!P=tPR||xY~c8z&yJrywsr2%=}T62fbLX(c<13mhqg9} z%?|W$y(7@w`T6nU{Cxc*UJ?mx2kAMZK53Jn=M3*ZnxB8D9;!GG=bdvCAE zA?)oI(k!krWnpvUMSYWwi{w=fQDc&;5#bjtCw< zW$AG@h1Zz?+qn`ev_noc#_+Bk4jN8tbyRN5Y!KoT9TAgYrE*io&I4_uhXiC%7)zwonI%SQd&bxbhJ}=sEj<$?D_H*1)j2$^*S&(3vax|~_@|-p!#{wH!f`yv2scp_rE9{`#Z~?JdBR$$YWq!uy zHdu9VG7=GBG=)87Y>n0C|0m*sT}Wwg`B8^P5@DIA$aSw0Nei@lPgr!o5v!Eb7%D3{ zfDqms#D)oBi!iI?DJ}BYfVx8>l#s)apolJIGVCEx2E-28?hWxkFhtNepNq43KX~ZH zEEHELHrp_1RAdAGf&wFF!G?3WXyd~9Dwp_d$!sAZZ?S0h7Uq_)D7x6jI7tkfE6cfD zd`7BoA$wiHHJYVY2t*;ou1p+O?=qeajiut4h zPG~47-q#popq1!DnkEL@G-AJ6wtd#9){`-$F>nYWQDsB6iMzm%acU4hs58X4Lu}w= zaZLQepb~RP**XcWk z=x;kaY$%G%$-s_K9EOw4?F!+l5|`nErSJgLnj^#}9Tq}n1O*c%ULza^!-e$~k`SVh zK2<;h9bmoml9(E@$niXr9`K_q&LE3Dw)C9ue@X{?h97dy<1<>3Q zUh)NM!hH(yWuLVNDc zBdy!#`UhUmCq@L)!i#xCu-^^_+)t2KgY7X@cBVuOa5s-5sTA1RnfmH%SRVx0Z@qq*5%{C>>XXfp zT^1}T@PQ){-<6&w`Du_HH@N8R z)4{_*@5&1+f)3LQso~Moa++=l1`i&#+wm27h~RzfFin7Gb*|pB+#Fu_5U`%3+R zb*FtJ^@4k|tMu*BUmZ@Roz~3gaN60qoPD*#0o}3cL}}*@$FcZPA>V8au~@+rGD z?JKBiX}RjitjF^63$B%~u9oGW&A(8*kWSr9BVr<>jC$`n8@%J^zrJ#&X|(eOr~ckJ zMcmgejJ5VE(7<{t{YHXLyH}eFPQP%mw$9ykCY8ym?W(Okn@W35)Sl>ao7Xit8S7MU zL#k=PdBdKL?f+9k2StAVxN*zq0Vc?8O-t7CFFbGJ++%PC{8C)%~0<@uLZUaEa z*rbC^uyVkifzk9rljDzpV8fBpc;84Q7}af%T?nD)&^0E8n+3TQMuClB$80t|XM**l zAIXGms2(HUqo?N2Mr3fOV6S<(j@SDv0fyGtC zkn>9OY#8qy8bZ0*h7PhT7p9b`J0mTr5UEIc5JnRz9zwBs2mwj9+@e|J3&Mzl>(Hn^ z6W-dsK|vXVMTN7oKw#9PkvN!_S4?}vYxAlK3yXlqfZM_TmnW3K2(_VZB`Jq zAR~c6Pn_5x5k|_B1kVJ)Yfx&*vcnt#(1w{L(BVKkQP02{pq6k>3EUx=j>jE=XuyZm1=_y@G*&9Y zeavmKgabnBjF3TJ7<0gV1iuzK<^%SE5r=(o4p-nD!f;4%X5mUnuzN>=y%kre@eD1+ zVFVrM!)P$h^PRGonu=SLK1V22ob!KNuv)h_i2(zERfL_No}QSPn125J`OAryFQ+G_ zCtgnc?Yr+DKK%C4mtU$7ytXU9+ViJu80deuN1;Dfu^I7_jCTZTi_fNZo5m4VK_A@O z-rhcbdULb?7yuS>PY&FEm*9f>Zuz{UV-Jtjcl629@hMPu2wYYndS^-)V!;8rdsmL->|FTzLO?!+ z@-i2o336N6kmJ8xUH?zh`5j&hHib3~(6qsFptiIHj&?Nxw57F8%r17Bhg;J{kif4h}UP`g(*$nC%rXAMcRvl{42p!Qa(K!LIkM0}tCy!JT z8bc#02_H|1()6^E&$Y)lV&`O&mun7(y{rMrdaEk;;^yd(!(V+52RDX3yL<6_5q*9MuAnOm(NS1+~Zj1sG_Pgqx?4Q zRqF0g_(W$K_4U|=3#C$Np!t2Ab*V4iTpBAaEj=6!^_9}$P&)j$G(a!xf%TU!*I$h3 zCSm*!!x};Ji5Taclo+cWc@^?Y3$MR8B)_Q6jn$3Swbi~uFE-Xz@2@Vs_s37Juid}? zhuHJyzmTH`OB*HGH@$QH=C6Nub9Df}U@wNupm0|uheO0%wt$D(!)7_XT^MkO@f1tL zHkfgkYt4dw=0-K`Yq)1*I0JZbjky-1NQOq06>J8q${jdTGR-h+h}<(ErNMw`LwIoj zljT`3TsbNOZfuMgX|Q3Wy15aRZJdLaRzOxceHZS7hQmF&mb4cUgA4=CWY87Hp>W{H z*nB8f(|wX~>uZdF1N(v*5@D2{GZ+O93X6sHh7bF6$@9X115jci_9zgXb;+JRfnY{x zFhCfzm!6bN1P*e%H`w+Y7a|$3=yr9%5G$ibirf~HkYX4+qdct)H(;&NW`b`PLXsG_ z&}O0+Gz8Fdm^N}LAeJQ)JHJHTHd8}h7%)sZT4bk*78*#SQ`{mbikkGCLRHkb|d*;B@P4g%NI7zn!cU&F71 zxeI2y0dExsS+vj7mILe;EZ9ubTjs6R;lsY24p}Ol5brM@w!Jv83ruxT^Gsn1T%PT9 z9^5!MMI?K%69{Zz5t~A2913R+fGbCS$GdZC4yij49qMpGE#{;k zTcAG?-E>A1M`}y&aCdJU_d;()EA9dCSs?84%r$&nnVx>N@JhC4&z`-SzVd2edTJR2 z8M~bSYw5op(h7oG%a`8Z1UQFmKi|8fj?nKfR+rxCwg}zFG)>#DrILk96$0>AUo8p) z{&;a^^6vKJ%FOn*T<&gfZ?CMZJdn$S6@JNOd3jl`i%*^`KLHH}00Y(G13f4|$z`JH zc?GOj)pq$RdG2SI)zW7-Zt%(n_3CEQn- zY47{JVdN9h^_k$CR^!2G1{NWtp?7PuPI;^nfE{+aU+r^13IQXVdMYROq3)xU6m}($ z<{>qS4Po5p&JFI>pTjhKR`geipfPzA4k-d0;!>&qgO7fac&O%pIXTo$LWtI7YkO}z zRKcdDa4Dp$mFCoAts=hom(0r`_C7c{H25Z5Z! za$HNLWI;=6p=2_-fBymbnUb1TIFQ6zvQV&=4-^iB;?~25t^1SZRPwM_)~rcufl@r# z%Ef~BSo;{~knpmsy=5Ml$Y_QE|ZA5J4Kna*OP&WnAdM|>WF4bAYZd9Wq zs5Qgc8PiQRLy);g2BZi3Y&JuLJ{|}#Y&1tA7(n9ak}rZ0VIP~qOe(a2%0{3GBQ|#h ziNu*;R~O<7eO*vT%cDR9##ah}gR<5G1orvdT*wH)MM3#5UDRYv2*zfDZGy+pJkKJS z&>ff!&{VQ#!rc}K1YEO$9#;>7f-T5PGAYqB{h%=vY*Eh8Zoy(op)H63o|`bScr8?T z!s2FUxXI;i!8|X~*J3iYQIF+9>YzYx(;U(jgwY~y5Hm@6rZwabq7&R=LKKn^+kA@} zSYpu{nA^nSGYKu~$LtE5gbNFPS{fRjLWKoRD->Bk8+=x<7JcD^Z1*ArsUd#^aBYHR z7F{?XoIa92LkA9}nT8dm5v>VGn&mqJfzjir?C%8&zwi9m$x9n;d&20{X3A+=BP&;5?f-j4{bMu5p)!tsk3F@osIc@(_&qTB#iojG)Sk9Rx! zX}=){!691qV(LQT;y5%|>=$<@a`5!%hT>`*K9ig>c1CkheEFSpqeeNL?$nS`I}`qc zzW*sfs|VqVwO9rKv-~VDDFA%!+LbHQSAM^+AP_7!0>BG`$5UStO$osNuciL5GYJ4D zmn86=zo9tjFK_5duJh;5p8Zqx-|y@<*g2MWTY0aK6M+8)0RD3E`=5V&d3j1+ZF+iP zdg0kKxnPs~yvQ~s+xFD9j>``OS}*^(qzpZROOf*ySgx?v473DUpt*S z@P7m28frMQCwFTc4!WqzXV=6QO5TIC!3rzb-Rt`{tLO#23a!&(Y<)*R_|cjEb%=tG zDVs;SPzYTGSiat^u2t{fN2}nCy7>fO)i-adYjS-VL{AZ5Jvv33O~|~s_sBmJfLhsVtqTitGiWn zE#9JeQQcjG%5DuS@}Rn<7ONY$>}+slgFTMjDh}9r`}+0E@4oxTKQ(+xfH0w4@Wwjz z;a&Op#&*;Rs(2M#aiZO=ja^;PSKZamCeNxLq`E6FT7A94KFTVd!|w9ZTW=p0FBQU= zooc7BYgDhNGhE`~QHSl6FxYHX-bXp0i&}CGRZ_5^G(vC#-7_lGc&{~p^%`pDZA?Y7 zWsRs2!^J~TF>9#J2(8T`9oPn;Gn>N7I*Yv7*qDtlsIZm}8`(xeGd!P-(*-gS8Z23AWav)td=KU;zy)4tPSt zGArnt?Gly?stW`L1#W{hD=7F3M3y~zaIYtbS~C)jf=clWFDz7~13`Fh;32|$<(>te z&$AYe0aN}A$urz3;fxh9VK8`h!ZP7-YWF&Ns(avo_#kd7b`af))?@v_u6~<+TAzY!X zfJ_ijlo4itfoih+7#wigc>`?(Hyc~jkR8H?(b}~@4P%Ug!F8*2m4c{@Y%)8t*P)r1 zw$Z>QwIXZck6mAwx-a^s=?njnp3nJSsN41qT<*-hbK$~-XP$GO^E}K0Lu7^4mb4X= zsM)h-32Lw}%(eh&7Cw?#b+mn@JQv%^-4vkPG$g4F(biF<(FSd0IV#UMrZwp{?GztX zOy1(=&yE>ZQNCMn*j-HK5muDKg#~*}-XNA%LWW&#;|T3i11zT)?Q#4mvA6Z8G7D%{ z0On@g^*m*khrB}emco1cOVygv7x19ELa1V?N0zaL)?r>PPZJDmQJA&@vM=tN(O@L( zDt(sD_xjZ5$~Qx4xnJ(j$iKU|e?~Yk`3wQv^NkC?6ucIYixG%K41)h^L=CS{KEsmbNj$|Hj$+Xa z{Wazo?cs2HJV+;ZtUcO3;yuu=IY-!1MuO2XFR)2XIXI$-%tVpE@rcF%YZG}aqF7Fi zIY=O(+zVV)GY-a&0t_EVnNWiFMuGu3;Hq3rRM@h=vT1fh0QJr!kYT{*1SbtmRR(-P z5Lno+;IHuC2M;dkvf?n=e>6Uet532=$U%hy#8Z0W%DS=o;U|AkK*g#;tE2u08e0}Qrb;aK&_XL2a z&t+#FTddyJ(MDmwiOZYs050DLu+7OHnA_j=Gz;dUz;jN<+3wv-ZM=nGxzVcb&!ffy zOKlxw^W>+efA+a&50lBv8{u{Z3^VMj=?f5Eok%*OGr>m;PYyj~=pFYrm123+kcLt- zMjK_=(a4)qcfV?`v}mNU!5)`NvOHstIY581PNv_!P_erLbtQkUEv6INu?x#|+Wy>Qg zvR+C47UkNN?9&(D3a%BF?=iMo8jfT_=&AB{HCA=EH14Tt+|$z7(p}Z^`^N67swzIa z23o3GS{grU>1?d38mMaQZjlE&O-jVa4ngg!fA}K%G`sXP`^C~ymXEBRUAnSlU$L)T zv1L;}uY6&rm+U1wZOdVDfE;1lX<4VUZ{NN|Ise_OS8w{jUIy6Cu9tTy0XL4*-@aUu zOOxxdQ(U-S+e%WeF_|(0c&Fuevchk}945P0l0QkZ#eE(!Vm{k`_3X@AsMAnhnD5SC z_ZhowR9*)>x%uuP{PZ>RFW(I$l5r!P^{~pBUE1a?cEf93FjZhWSJ*K;SWqz^s$A5O z0}ZADJS3zU->Y0whKq7LhKhzDx&%2;aYkO%QFL2SRdyg^&ed_?{5o35gUYURRH&7k zldDEq9UXNjw3sA@4U;Q~?NxDuAULtVgdue_qq@4GcVWWK4FasWxy^{4>jbA!V_`yB z*EEPZ2bJlD=H?E}Cxsl>)YPa!WlhtdDOd~16}%1gV?PV=Gx8Xj_0GmXPEUip;`}nIFm% zK3pJ(y_=Y$it%w;y+ExBqD$JaysFGY7)@svoGxh7{kvhsm6gs!k_lzlhC2r{!=Q7C zK7^AMqAY-xf-@n8Krz~89Xl$3JTr*|dP9rVTuUR7j_z(7-&Q%UW#}#XLXek(OHC+U zL-L{-67+qHG#cHN+vu-KbrbY8wpWjH+@2hdB5=OP5|{>dUFx{uR{Q72Ob~lw+SckP zb`aT#{L69sw(;hJ~?0+Ko4sV+B@F#e??f&&Kd^nh_F&q27fOZ_A4KNAC%bM zz+c0FTmLit+uB;+^O*qf+_lBYYmVezUkZxw<;{Gz|t%3@6{r_P!g5 z)Y`aC)sqtR`fFOiS$kzZlb99&zO=A`zYYWgnG1#jgPAbdd!Xi*)6)~efKQGZ7wFNG z-Df|0J-sITsWY)Is~kmtC0DEK5IaekXi=HvB!GE+t7Z3j{3{Cs^}l0OGT(m zUa~qeFRQqv?^O*m_UL#Xwj6;+A0e&|>9VPJ4%IsJ*SK)(+i-z4Ks-Al3^;hl=}_*} z>D79w(Dn6u>hHctW)gJS6WUzot9H{9thTc`eeOL+{3d%c+s)p@_CzLQzkRcQ=Is8^ zp1nJb@Mtf&z&d{WasA%zp0%EXJ9-X%SbgwNPxb!l!s>(j*9zCx3U?Il*wM42df)#2 zg=>X9JvzkQ6Y4T8Q=?*HI{AAh(tnl7%>UFV-<@TCbM?-~JRfW)=jZ2>^SpDgpROtf zzy7DH^4H|2DHH~*hFBEG`ySevbKAMF_YxCEPheJZn>N3S3Dq9xj_pQxFzqN0rW0mo zLXS@*=3hKJQ`pj}zL&6G<9k`pySDoJyPuZ|%~jcRKK0~$SMDuBkBADSCY_Ik)sRpg z)L63Db@+BM4jojI1*vm%d>Fwr!$~BnvGPfwPv;6Xs8nsTr=1pM>N!EKCnPA6=(b>DMRlPYK+24r-0w5C9H0fgb)fP zZX)nVtIWc5sZ&>+SMNzV1`+g)8sj#pV@VZiOey@ik{RHVKf!p(MyklGk&P0~BrK@d ztp=1g^HiQyQX$VDCvdO=omQUm-CYQ@)Tk25d$XX@;3@7Jc@+#OA=4@`!@guB9iu8; zG7cY>6}HaQk#8d6YTJgdrO;tPTp`11u7Mv1Jz)lz7&=n*)%Z=N#;SbY=6uLmj>-4g zQtaC5F3NG|c;LLeSu1k8RN74ZFZF2m*2ltxJ)Xlzv>?3TF*R!=hAyIb&3ktRXIH5X zA<6$3{okUayp}Urv6aMA29y*@G5e7%@EFg@8DO^GvOL-%CK9!j(y|5e_6s*A4=JFM zQj}E?V4rq-ah9|KabF}p!5x2g1uy5`ftr@v5^`6zNqsc#8R8&Js2@l&awh zdzT&Yl|QVmmHw~*{8&JqK}K+7%)3nGd@LYzcr1KXh%~+9lBWL-VGtrZQ2Pu9JbmIs zCY{b^jt?iVUlhD@2=L#8{|aeT;Jc7KethCwCNnWS{QQSe4#GYA*3Nu4d^vq>aaHhF zZWjfBFD`yFc~Q3KR?~BKI(=?9`TeY!12)Ct-d+LV^)-5nXa4va2D~H;cs`LxPJxVy zznc`;)SnlAKw6)e67=-MS9cVAHIcB&l%O~DSJ3IH3kw@`S|NSGIT<(3<(%x^z59+( zOP80VH)!iug;+)f-PilO4}SEUSXU$EX4<}?a+5&V-Po;j!67QeaNzQgVaP|63;)I1 z2tgui)8a)(ZRgIT#2Ti|H7 zl3nXSS zIex@=iQ$+16?;8i@7D9~1N6)1^J$@_`8+?**X#LuK34>PKQySD7ni5N9#9C0+u5I` z3@WD#LIX~^n*#8|!83=-Ki`s<{!-blu14K;@Zjy+uV2rtug|UD`F>+#Ks5wBOfkBjcV=Owe6VO&ba1W3xDt)m!?mHI$?EE=d(oS!qYs-YEd*+Jj}2GSrh zQ^F=+&_gYHT<~7QkDM50fw-nVU91^Mg5&g$iv_Qvnggth1|F#;v@OyeRfkGpxzS)W z9F3?+RzqD7!wrH7BUnvh5*?1V3ocWbj`|}}G8nL(jNrfF4=NF^6Lc2d8x|;q1FHzD zu7Q#>7FgjYqkgv$VMU;~qdI*=455R~6|6Z2+|{e&xV;Lrc*P$4x-E zs;3Gmv}1?Y4S6L_c!#$~{Ueb^qkGnoB0+Dmf3;Z*A>LtbRe{DhZzwmeQpBy?{KK+i z$0zE?v3Zkag0gaPEBdPmtvo+<78J8h05ShUy9>2oRHsJ>2#c-Bm8%&7 zZjKA|Vj~^mp`m!FG!zj0b=8Lg&E)>Z6CuJG@PnrB+orCQV08(wOv4w4=rX2}1e2Q= zHHf$6GIr24WCJ6B(%gi4_2W?ZTx@AB>mrF^ciC>Cwe>AKsXy=BnP^cVbQh{D*`bR^ zfzSfCU5nib)lP%vA!e2q%WBkB8s3}ej^}{BNj;*K47Y&y-OXi}FQeR+7aDRzuKY9t zsqw`AXAcbkcc#xjek>T9QT^2=?f>3Y1f~Id>F*c%(tqmAOi!;ab#}J=*n1Kc^wz2s|>XDLCy{NL*8($dv?L$k@V z8N+@J{7x!nYW4Z9QdZLh&R30R`cui|@|Pzx54iEfDHUNQ^F+2&0C-sWbnXca2{s*N z<-ziF!}*3X0Q`d_IyK&C3^-2dC=%AkfH6JblZo2>xiMdjWFRHb_--66*Nj4-*z|sn zYU_6Y(QnaLm6(hXKF$ocmjsxaM>2s(ks3AP3X0J&J@aG`sl-_rE3NC99*O?5njMO%j2 zZ~i-z(JgORF#A071H15FtH)X#wF(C&qG1BfvJ-LExaK3ZS|&{YR&X~;J_D1!9;=XF^v*i? z>(K!usBvrYIP6vka7V`k7%k5r8%-dCCrSVV>4Y5`%A`VPPqfu$u|z%Nw3?&A2^*70 zHrzc(WUzUH9xKrg%7TUG7K60GU_0|i?X+`)bx*=_BS_?Luntcw%&@{w!k9oa`zsgG z@F=cVJ}f9BJ`x%H?acUwnL`pT92Af?ew6-EvW|Lv0>wTbM$qntiiU_!1* zcJ~6tSY!d3rC586Xi5XB=r%N4-&R{`C{%k`SG)Fd#TSnLjUm#Oedex(3& zeIk*7C(F~Q?N%bRD9=JqxT&n7{mM_hC=WDle|88F*4csM>GRWlUkd;a=ZnvG^MG}K zvhTid;&i6~@ap3w!+;Ou#mrhvuKo4tm&b(xpBLyI68ycu^0;sMB4DflOb>YNRnEFY zbATHU+?M0xvux3!GpDmJR#rymXZt26hm-y3i@AdFJ1t<))4=A%cL8`N)89WoeE*g4 zp_H#r4?jHpLSD`BWO{yPX6*RD6b)d5z@`E{`Bu?2nX5qy0uN~g8V0OKWmQA3UQyvy z&W+mO{Vnzj3e4&|c@#Ocx^SrJV%l`E~!4BnGfY$LBkod5nzWIS9)k0H< z)>ww}EA@Z)?8weL)yCRlOKmQtK=1FJTV0^|+^_5}nYl$dKfeqQ4KskonyW+d4$sa^ zjY0gBFA4)rzxggZcxK;GO3*4SuKq$tVg-Wt9IJix-J1ov0x5RyS6bbl(t9ZbduNlX zNFO-6@Xf=)ZF_2SnGPnHVN2~-^HWe+{cqeFGJn?a@S|bv`}40d%cZ`H`TyO;N9WH! zx_WO`U>gQ(0Qlvr(}QOo78PZGp8fdnUU}`Gs!7Jd+OMWyyJktHGAQuS)uYElQ=rR` z>hFimFXl&1B5w`N-nu$7lS$=YioCM1=eq{8@9!~bNa}J~t+@|Mw&zaT(O(JtT7{Nc z1zHIf)M|7`tI*eRTL)5TqilBCoX};PQ!|4F6v0wqtx-);@TjB;0}Z5FNUAkr!B|Wd zw_BpxO7_^C*jHI>##0Lkv)pcX+N?qOz3N#>*%>8t)Mg1sX&rllD#DVp0gXpecMgvM zUz@E?a6BmYf)Si3gNy*%K;ZT|Y_X_06UZR&9A+k1)-?F2R13xmTnkDoAo~p53UgM< z+Yk-nb`@@DCk+_jjrjTYw^v|-6>&ERZaW~sj$Xf}9W@9C?!^nM;ame5Nbp)WCFlxd z(!zBGo5Qk)tmp-8h55pDeGd0Eudf27vxD_szr#3TF>2&feH9?;r5=sws?yP0+2ieT zdo_8mk}CCPhaxtG<{r%&R0~QvzLkz1O+b>}HdBgL)wA2^ue?<^p}zzzI8@JtcDhGc zZl#u<;mSLd3mZpEf*Y#TNV;nCCY#0cl+mMBkJV}sCTlCeOwEevMr*6nq#xlzi4~T! zgCaD;Njk4s_`q3OVE4pSze)NaHEB7B7!@ZHDyEWz*xGS$w%gxlBEFR7Q zRZEvbTkRw=v@x0#i;rk|nYJ-I5kM%A8rP^`R*wkP{U$)}!vER2qMxSnG&(JX(Bd{N zwSY-d@V3^!(2Eo$nlBu?d!?VP=)W z%y1Vual$I3c4-No(pIk<+&3+x*%!4^d-b=(63neq!fR#2n*hO0B?NlW45m4UH;y`V zB9cycTfB+%k|1p&CeRj1b*0fBMzc8L&0rQOnh9hCb5q_l$8`mUp|}#fT~Hx`&`3qt z1wI{_A^Xi-f(VNSlLHk1@W9MKEJI+%sBmS5>4k8igv}KT*&x6JkxXDFx)5X5!T^Gi z=$CZ~b!tQ@$+wfGLZu6}Z&t3OM|!{N|8XGU(8vigV1cY{fz3^*piyoHJP8dZ4nJb8 zRsi@{lgq0I1_1Zhjsf>iU<`=>tdak26^bCgtEJy83K$=(YU_o`$p>%V*4Rh)PYn$| z+smK*bU&ZJy!Z0E7w0~z2zNKSQ9{8Gmqns2?y|+9V6fIB)|2s@ z^;AjAUlH6^;bFtX5o_S#$5da1lnmM+!lMT28eL&Fg!NAFSAh!`I!^z|Nbm(ROvtB+ zGfcyMQC1EoU~{?BT(vxpll=s1KRw9UcxV-Y@b$)*D#K&h8(C99b zP&@-or(QqF6$*R!WMWZ?i7rE{%pSW7$O2uw4I>)RrmDkO|b8^>ViOi zHB}Lvu^^PEh$m@0Oa2PwNtRa>00V*91O9OTEJ`frj?o#Tn~}!%*6>3Yh@%B8Jsuk% zuY`Z{lBjv@;Z*1^J6Qlc-YqQ~;El7v67;clm3^p63o2d_E0X({Y$m6f*39Ehg#3=9 z+-yeDksTh<&bp^Cu@bO64`)iV%0@EVZ*dG5JXBB<;e<|PDq+yq%(Aq{>4e7ytv!@e zN249nM*{L;713aFs(B;mtCF&>K3{~RCb=m`g{m6bFdBC_Ew==SpW6LNI7d7E@W#T3 za1vHog0Zl{a-u4o^!PFToAf08VL#f%9*f^{(~oclw29$D8SM1Hg;I9z?DY_X;n&d# zm*`%B-XL#*1(t`t(Ve~Q1ot3(0e~uS+ap-o!z84em^$ihp!~V1sk5yoD9}r54&lqe zBZAQ2y`4Qr5Q}t_i3|eH7z9T80&FKyux>!^LbFik2DE?S!|_MiluuduZUAh-e38(g z)X)uC7)iEe+b~;%R0ax|84ui?ZEkZkp-b!lLC!X#0G*{VbO*&uM z4@TX%FTwlu2&6b>c~dZehVwJhk)l>#6cuS<#X^ZAaHRAR&mgywyM2)~)M(F{JOBV7 z07*naR9O*KgBHrU5KW^u3_D8Z5mmgPx|x}l1zKW6eU&u$X%y2&6#>Lp09MfQF^~?# zW-x0Miw$@OsIQ74^;fx1!Vrr!WteY(LPyaG&IBrO;%H$+A$!eGN6$oJ-Whh1mC67$HpdCgaPwmx{>A7 zPxtrt_V!Mm&0ju20N$9p0{~u`)8GE?01B#TVDxTlFq10iwH*QAAtMO5FF*ehV@OxD zYX^_k3WYTmpm%EVoC}Jo68c9f=(2Y8+i$6cey2*%K;S7ghlGDq*DwC$w0CgivsUK* zV*EGM_iHd;&|nIm;YEpXLUe$siI$DOcsY6$N1TW&;UXH_Xp9wa#GpI+H!7=>V|lJR zv~Ey3a?4*r`k^52XlqFC|As3H`U!*fH9 z{Py*q%ZsSy{(ObPsAblVp^(~^|EkI@7gV)h?$5Ulb}Q_rgjyaxeQy)hZ~~(a!U}&4 z4IS49HBV8sC1!7E8_PMNz?;7Z04oue@LwSC$Ptm$srPY>TeU5_#{qYp3}ByXk`b%Xcn2lYfquleCij?&{)v}ns_UhY=@&c>&OCYnM4Q-1}>j!15-v} z+VO$>^3RV$?+iVaoeq?O#R9r`AvM}Klw_-eEfzY$kT~1W2}URqYS4|sj_a9TNO_h( zuI|M_=&Wbe8Ri0*Is*GeI-8aANr)KaK6NhTLFuz$+6Wd|C@Bjwz;H11(kURaub#bQ z)!r2xhku_Jb?SsXIN?t4N*qH;OV$)J6|CN<)oV>eQE2W;d%G5_2my8{d@0p9cBKSo z(f*BMhRB8baw3%h6t_e$+>4YXw|9x|lTkUM94%8xAPPzLPsv^oKu0R63Q;+li2$Gj zExr~+A$TET_OkoSP^3T<{I)`O=g5puR!kUWkPkdC0PJny3^4dCfLMrcgr3kbOeo821&#k1pUI@a?p$00QVfM_XVP4Iy^|>^H!EbyMg6$pijo|CtWJE82ko@YtCA z8{-#lz*K`*`E^-aeR0~72%@(y%VX+7#-rXhuzttT$ zl#TSzF{+>ig)i@YPX_$x(ayEp?^cSO+tnUxs_sb9l~H@-HcEr<0r<{;{yn6dK~H^t zE`Rw8VZeo4@!C}~V7`0r)Ls<$8lq}dgVv8$C@gDN<#Dj$c+o#B$U99ZN&+#{kcO{c z{NxY5Jfzlp5|>3!gj^b6tlQvk5{!Uf0a`xAsk z0OiD&s6HQuD^&Z}H_Mb85lM1eRdB1aOXEDD+MsQ%uz1Y6D*<@#^3V2124S)#;5)23 z%QSmzKl4@?@Z$Ey#`;!it5npA+HMKTcugx7SBs_HQn9pgcVlB?b9wPfWiS7csy=rs z!)D;to6YiX0l=Iw+ad+Np#$)HUixb1l@5+~ba1>jyIy7qdh^LUg8>Wtp4~t6;fc^0 z%EeT6;G2sEDaX&V{l4yeL*e{Rb@omFE?m0l04z(993QQpisz&A`+af-AbX}zZ9*uxsPN;!_+ zEyAtz+c8$SA4c2X#_oO)?(ewQJYTQpmw1Fy1|(OcLH8{6 z;xUSMgqE}hI1&lzxULV`v8;z=g_6{332B5jqDFDq5c(_qLzy3z|kkdOvw>aS( z@=SssiHan6E-Y95NnQ)y|j#^&f!DfgpWY-@}Lo!aKRoyHQowbbaY9S!JH?WYkR0fR)X(7G28OT~u z6+L@mS^+Ff*dt7r_(_sD1jV9cWW^Tn_jb#FiOnRfM?ov5(a`9uh@`w5435N@Mkhc) z;lZ(BR6sD1yPJc93J}tk6zo2lqqs=WwQnpnMkNx`=fqKJfm1|X$zcK3u~aT-ijSy1 z>P~1_M|Z+(hVcvsg-XlUG}d1^b)=8YuzrPPZbWU%#D3W8;hb>u@Y1!PWl^3#``tV2 zfagl3`^92$?OZ*|>a`d9=DGXT)u$W3uQT9nKHa4vtlNdEs;>&g=U4eaz_=<;yzBa$ zo7W_)^T+EETABq-_R}us0}am=?sq{4tk-9{M_2j zA5m7T3=135#UCc~rP9Qmnacq1#M*89#q9dz33u_1?tHJZ?o-?~^!K(IK??wXT{Zx0 zmmulx*H%G~Uij>{Z+zY-0DKk;5;)s0xT{X2586m5G}>p(!MKpx&K}apj&GeBN2C2- zPAvuV>nKQQZ(~3ZS-{q^09{=Q6d%f^gFU$u9H78F^Qz z7Dzc=Twh-n25fe~b_bF+8FY31$sR$Qe-mZE^JW5VCc`i4O#OkGLYqPPOtH2DHcQ|i z{(Xh;swZ#B>&f>hjTqJJkHME^Th|N+p15zmj*Y-_xv_0Mf3cGQ^EIaBQsk=qqSy*) z`QBB&|L)>jXOG#_XS2gLs&M%(|Kn(2H<25{bP1Rg_TtkiG)rAJdqYib_mCX-In=f5 z_POa79CGmCFlYH1*x|x{(JNDC2r3Uaa0#;r7Q`LU=;%)Pu%L8CrPBKcga_~5FSnUx zbEdn=Cx9(ze!V82rg9L{3sb&MG}eGBuwcN1TxERMNxb3~MkIt-13gUx`-T28eQxR$ za9-+Z>V*$yAikX)y#ty;+1nI}4+s&?WCVQU`+FmC`F!d_>W#;*Q;-zz(csBUM{f@k zW{|o=!CBEb6j`ExVM+*a52+oLG(@JB*!T+g#+fy@ate(M@LqzUBj9gDLp!vY(8Upz zSGBGXxuL0(aAIm1@Exsy!@_OHTV0{QgoP<1n#OY!g4MbNWShBD9w)HrYG&apgt{HJ zE2MWtix|*C>#De&1u;yQ`{`I17fLJlthBqvS6nUQk%HaUzEkr`g zeSWtIg_iTwER6J-`Lef`Lg|bFxPGTjhpB_X`HQm33b6eWw%bS?mK8X~0$B&m{&dVA z6$sVGSQ^KXjHMAcdkhzrhstxCK&+W}YQiFRJlcdqpRUtWuI z&aXZE@h6&)bP9dpD?5r32K@E?dXr-9LG_24{7Ey5v_H^1%F1eSnh`WRV8z{f6Cpy{ zuE7hRee%Yqx%ZeelLjr2%Y?bV4JmYgn_Uxp(%6ws(vu{(e6s)0-!yE4O^X-qt5=(( zo|A&E7nb}2s8&(E!R&w4u;g?HJl^DA57?{UeQosyhT1z50bTb5LxR-@9DM)7Gu^iY z9m#*z7T{3=BAEB?y(J8I(&&2UV8Ed5iyh-#13v%{6!`J7oP;i#z45QGAzi$5qJQrm zJ9To<&UsWn(XCfolXLe;VYySdTAVKy=VuBet4&XXzy&VIxN}{8zV5zrrJo)oLxIW3 z_^7Mvvfen{;Kr8(4ihcu(B-U9U$+l%bU22fyF+9^Vof5b3bfA9 z#lUI94lM(2(0#7Y*U;HOvU9_A!DNTvC6QaZH7H99fEA>D1Ne!c-}EuaVR9#ZolOer zopLm@dv}HrH<2F5urdnK`oN}v-Bb+{v(bqrE0gIQ@b&UeAhrWvQd7p)`A>!03~S(c zhS7Aqm)mTM<2sKfB1`?g!gPB(_rsEVLp?p6%_L@ZEa@$+`;BYtBu#~QkMQ<3_qa^z zb7YFeFD~FnE9o4eIBCz#9rA}6bMrW7#G9v@RbB<@r8=1SXmrmVE3H#5>KMjBW*92E z=Vnz#j|-FiGOS);f!B~JJQBQhg@madQ6F%)edP#1$^@F-Ey2=qJfz$;+}hHtI;{5A z6#}tH-#8r(e`!{}WK*8j(5xd$c-sY%!$(@q@L5iiMTt+z%%j`ecTxE(KOwx43$jLm z++j_h^s^Ig@XF5z5gd(vbpew-Ni)(7&5ajw>u?f;CFEF;(5+a^QE*sC)o$H>VR1Yq zPdaj)A5+DZ-*0*GW2oknlw7A$f&fi~3cQx;QUU^{X6?&;F~T)i_)TiU|_IYxdJmGjeryn!^n-^7A2Tz@o>^uUml0;$1dEQ=`GAJqU#Pu5DO zlVn>Zg$h$IxETf2DEFhIK^X9Y#eVfJo8VYtHrw6J2wK=RnUJ$WR>x*jQ4%TTO)i-t zHpt2ymP?G0zJci%obCgZ`_N&b*oyWA%@(*;OPE4XC0|6_kdRk__KDnV zGB+DcMN_$4!XvCZ$9Z6HH*~z4@pEo=BylAEa|V2vB&($D} zv#qW2a&>LF`fTgon;VOjH91hJRM#u_oW^1o0qq0zF{+i{^cW;K|eA{SX5_b6WG{nNNQqg50Mi8}u>Zw2 zOR|dFc=+FIS_rIL;Io%%09>4zzF(>}8`s()w%^)sN~Illl@MVSr=OyRE^VDRE+k_D z))=e{qh04e|KxX{rry>7j+1IY`oN@Nsq(6y#jlCPGVKi9*@g|t@_2Pu;-O!Gt47m} z6mTvCOq4nHBYyg^302fW6=%9?yz?`%U`eGAM6-u8XXFIFb=%M6d#Kd|@ro&zCTlwjj? zAWq`=InVn(AL?s5Z)tv8@ZiW_QOoOp>`h%O+|B6#x+wJ7Og2rYv*|3a1~V(IyitGw zUp;c{xG7)Kp5l&?<2T>@D_za&2>P+9kIFt){5^;zHJRz#A+$WITi{ZDt@Kb(-lzxw zKlt72xw)S``qdVD;GVM@hkaZNjQ(Db7f#+-$jP7l`qb*gq^gE{59l%YO}eMc0iF~vdz9+Z+|LS zNGafemLLJg0=qeUl$w%!DGUK{;L zX3KBAnH4QCyrOF9UiqCd32QThmIMR$L}jTcnmY-=SnpDklt6uL6K+djbWml|a^D$Y z<{S}VCF(g5IT5W72A}lCXiEwzO6vex&{uGmpeuA%!N`eNBK9Q0=vj!caNB4bBkNe3 zx{Xq-dzT`biAC2@L}$y9+5ijQK(sB|ma2_VxghAA0-otW!qyuL)ZkTOiOW(~ptdaq zR<{a^r7oD<=UVo`&8_ALnz9D0On;bcXb@D^e5|9SUkSzv@~U}>Z7>VMyz&ZKp{|fdBroj@n10=g&_4uL?MjPsAhZk!Q z2X9qEC|&LB&cgl&p2fytKm3)i85OEK8YV4zQ9f~bhKD^ua0e+G25spc^oJU0A`JV< z$a01J;kevw40#~AD#P+Gs26;lfSwNPkGs_e$sKrvCA68X44<)H&YW z-H$@LpV%r5iSB3V+i8YhHJM42akT;WD;)C;J3GzvD|xhE71uN*jp;5JBT~EIeOy&p zed~Sk8=Vc2{|8_*igKM1bb(RfcBWFQR!TcNdpm0zxdKRBDH$8sD|h6x`}cQV-v8p# zi?`5g;c&-QRY6<+qhfYuCL?H${<&BMfrSBU5|-s2w&u_u2>!nR>=#>)RD`ty1Ah2W z-|lW3xlGQ;q_gFjg>qG>Q#m)YVaWTpVa$}}wz`^=+g$GPU1P?`{P(q>@5F>M>rb!# zcGuhiXVSA}yq)T8{YXfUVmBE^X5a#|$a&S}Y9WIK>v;&9?touRAcCGS0a#bTSb`@A z;s~A8g)dTQjllYHU;RuH$B~N{)E4}y786pwBS-$k#Mw>-r$Dfq@=cQmqs$_Q)vRjp zBZO|mJ>Wu#)z~;VDF1i-eLr42a>VKZ{>RPv_PCRfSE;B!ZB?Zn1(GJI;*!^Y!k|wdsN(L|1+Y_`-h)B7*`81kV(81Z`CE(^K7#uJ)Wg zud`vxj3iI<&8vIG!dl_L6qS8^5F{$k=hXo6f`v%g_tdRHS4lTfl#XQ-S1X#+QLjx5bREHV zlXjcKCXCma#3}4FGp*{?g_Q6mopzhboO_*MHuGs6G%M@14aiq$wwA)MO(k0_h))Qo zHe)A~NUsRtP-3hVO#;b6gAqDAdlS)wGZFFi2A6|Rv;i3EiwBrs4(%IMBAmb*j034x z$ZfCYU`2T-x`a+z8FDZZOPru|!5mQ|%hCoU#?B;kd>e>G)Ggc=jXh~=iv^Vbk~;~( z6>Jt-EU=tPwGt7n5tXr85LR1&VZ}9?dqquQZ6MWNX0b>QFGV`ZaT(SrxYm>@u+yaMdbd!k$rV(HLBZD63f$JOq7( z@YYN=FlVmQa7q%RYgF|tFsnIQI&dZin)^q!4~a!`GcY_!WHiSSVY!nIpMWf?05{cy zg0?=l0}GN|YB79vYYQQjgkHDZTAv~6>N_tI^V)4Yusz zm_W0~>v0HddfWAVCd?if3(}z171oSCm!=hHNs{p2!9fr3tf5#qeKGgSZy9z82M#ZK zcn4#?tiDP)KG-hwmC6PLRpCJj3h@Gu4g;%$CggIEN+h}UD8`0HLk~tFx~zvE#0AGS z{#nQ^Ig_Jf44UO@hIOh--t%w>0Ti<1kT726&T)b4zR^$!7qEaSNEo_t?565I)7qtw!LNzKOsi^rR~$3jS~N&OfD zgtbbT>9)|}P`|F8Lrsdr%*ECJ)EDoojUCcpS%pXfz@J%3SfyfSW??(CeZO231b(@< zQQ9y{%7rV%()~T*!iA0MT6M2->5}KxL7=4OX?;QxmH=>NVIiBzW-~tskZ00RALy_- zb2P4hvAJu8QGaDdaeVUCNv+>Oge464#ZJYTrGp9c)4hxkSR()pK=QvcJ3CWNXN>Lb z*<3YU6hO`xM!L9@+5VwiP3NlemYyp*IrE<3cIV6%c~`!ggJTIo5F{uU!G&^4EIHZHK9hN^QfRd z|9$A>1)AxE1Yi7;0IUm$qBZ}Dy|393tgQ@YC4(UI-#n^9loz#QP_IC>g@o=A9`?9& ze}jJ>C6>#}SV*10*a$qGKYnbIUvmcC({pGBeae(WYrEiw2S%h*J-5~`Ump7A4m}BK z)or<{-3a>m@&D|7#N=5RV>y4ofKAwaXS{35kBq`R1sQVk+LSQhm%Hi%J`1aE`C4lS zp_e0?OnD0c&aVpbT@cbcv$`smVgkJBw6SVkoaLB^tmdcIzL}frIinUS`7Sp*)J@y* z=HK^{eNIK18Lmzq4CN*|zO|V%a z>;&V3KK1;{-DPJY3YktMNT%#HgEs_&DIVt2V31k{VZa!W5`<7j$jD;G9E>g_dG1XF zV@R<;+Y^x`@;M@OAVrx$CxBbw#K9#EqeP}v8^vj)MGQ-|0IcAyqHt}XH5N!kg#@c2 zdP$8(kld(HTNpA?lt{3?ZCy$UTsJhc5T+6-5J=I0M6yOe_-?}_@syen-P#Hc;{?W{ zL?%{^3a#X%<{ISDXtF?C)B9V4L|TpqYE=M@5^J)dd9u!GW$4ng*#i%0_(sxvpkNfOx1zMObx1UGHHu65LH^&LzPzfHswR4{R906cFymyLmESJ zjjzoO1n#-#`JESVV|tV94wv6f4>0x-mL-@2DC=i;k{`U%=XAK8!H~E@I7Sko{Y;oGIUALDCY}$rU2l5vTx+}nQFA3Pw(fj{WJyKD&&6?MOhVLJ=*x` z{rO}vnMp^}N=KCvMm|!? zm&%buE@EV4o7OXla>U4|Bl%pJ4@Po1(Dh6L+jLo@2y6ZOQ2}1AJu5R3vpCL-0)Ri> zJKHw`c1ww~=&wdZhNW^hKzUV4mI7d|R8LIweJO5untaWT4Xo;HZDcb8sIXEd;u4Zq zt1g0W9T%Qeg&2OJTI($CuO<}UN*9u{1P{KP0#_hc!l7jbOeTE#6X)f>HrpQp8dWFY z*qJdE-ps0ihc9;NK045%**~wpWWcYQY-I*qS$s{TR#ydpvjV^rVLf_x@R<@Gk-bU~ zG@}^LECYbU>r=6KRKs^(%g)RcaaE^j2YPHKiR&j_H*^CKoK41d_qYU2!gx_QqiDLu zetr7CNOCvBS}ZL%?bcXYwrZPLUo=(Kd{mS-OO4Yb^9KiHu4(uQ-x~9-A&miUvPmmSxRQQ$?vYL~yQ=1ZXigk@{A9 zlyE43@my{9obn8tx`(QKmqiS*^B`nv|S`?f3B%re6(Q zlTyNV)vh4sVcY@aTCX(^+_y3ZtMgjtU9ky^+?l3eATdes0If(8&(Ya_x4E8H;N~~z zHfpjk1blp4#=%YFtRN&OHjQ%^C%`oQ;<~)%8^A0c2WKWNR&7YsXtmM>%t&bPWJdZ( zPa*iMiRdeZY_qZ-L|2jvT-0aHVk1RJT*2m0_#2$H z0H{HmWA*``?*iJ=y6XTQJ0Ad#IRXw&f*H@^E^a~ke`on5#&h@_*f1iROW1a&D|nOh z-i1ZJ`$dy(9#0$2@%r4leCg$v}HE<6q(cf0o%{qD^r zJ{AapoCam}m;md(vgF-7e;&LyAdy&sfG}MzSCj2aOGH=#HI-Jp6C%C!+i!Ad8b@Q= z2br`OemM%pfkFY6AhHJ{z}@UtVzBgP$Qg2NVn=)1YXU6(89aTsqS}yB46rKWmd=-= ziQJPHKNNDhktY=Im!bu1pA_=xbRji0wfCDYLIL2Fs~?GgItCaQ{Z%?$CIqJifOqGo z<{89sTLEyt2&P6yKRW{8AAgV_4po!D65?$=zV_INtVK(aH6tC@%J{?y9jEX_B#tfk za5PF_*74ZE?S%#M>gE3BvA&fJX+xq2i)YOP0D3gX1#MglppXnS^gf~|u<-aa~wDxs4j;KEV~ zjN5U%4GJsn`iUg|? zyfIi6M4ujf#fWsg;s-u{+kg3T^Oet~3iy_qOcIBNasSrE&$o83haYpWnV^h3POuXz zth~qdxZ3g#@G_AKUnge8bGxxHgE$TWz|(I@?6EWwa=@zMkS{&|xo~}bDjbhBMJ4Xx!AwrNDznABR8WUO@1t5YoeE15*5Srqp8cuPt;j6S zN-h|$Ngn!btXZ&FgteLkacd-?szo9v>FialM`WX0O{RNNx?o~;15nX?L5xV^TH0!& zF1ktD0x!&&<^)G;Ylfukm#*G%6N?p^B$%U?cBHL)%;}(?nC(f-mgJEE;p0uUbxfM% zYPCm8QFejA9=k#7 z5eP7_xwn@(Dv@A$+NAXtPbXB9AG7j^O@$()673ZeI6!f45LJQ8R7c}}CsDZVE*lEz z`aNc4=Wo50OV1QMTd#o=Gxm!9-e!(%fw*G##p{^)EY!GD)iZ#Etuu={tIlSzh?$W| z9k`~SLGazy238L;Alg4EfgOuJN#SU4w)$BD43upJ zI0L@Pf*lSgv5eZOS$dJ&4QvEv(3TI#?RLyM893>5?%91oa8KOx`TQ&-`7dZOzIL4Xu`Mbak^pcu33^QFp!+|1`*$Co z?;GqBf%62TpqX|xsQQqU`-mItIWFofNx~ZWl0Vdqtm))%*Fk@;g^CADLtUe})i%lB z9A1|;&;MNrS6P(5zwr19tuG@_Sc4A@UAO zX5__ND!Q3c=;trOvG5MQ*;+0fTMZ|Z$s#i{sxcYKadKdWgM$GBfR8hmi|Vca zlXbPfY29ZufQ`7YT^X1y7Zyf+UBJ}PN+q>T=xT{Cj?~81rc7ks7|fB=4rg+r3R?~Y z%dTD78YFVTDM6dVR)=Vo)lExFrY*~hyR4D=VXFFVoA$xd{(=4jd(Qdcq}u$(+f4;B z^||MH&I`dDPw%ULe9@@C(qbSq_xII$r+(pQEk-rBUTUeV>K3lb-Hfeny(HgF0C2nc zz929Fc=7&2p5OJ$D?SH&m$QV6!ho*`1D1Ez7A(CBbh#mugb5q$o}fD#+JL8#m9)b# zR8wwMEAm#v2zsIVx5w*mzSvP%vkD27PLs?Q8T!+3H^t6WGH=UYR$CXFfB~JH4GT=_ zHl3m>A)}zfQ$kk3g>_nm(QqULSkKCTM%b>t4S%q63Z+M2)cBWi7ApwHb*e%_lg>0r zxz8;4jGeBo3wnYTZ+D@7P&c!C!5q+eCq&U*+3WF+byzMDi4_looftDavst-}2cmH* znvpmOcol|>-a#}P3aUB-7)c|MLvT3$DY_Tr;DKnIk}A1^uR=CPiX4cb`v|NU02?93 zA{^Qmi$xrW;1EoP;tG)+k=Q^!62n5c;PG9KDBqFKS*$9LR)@c?+r=sQ~=7 zdXz7?hB>qY2Y67lfa$b@QP2(oF%UNowe&}w?XJr|;_`7bEM(Y=vO$lq-5$)OiM=kU zt43J7Adn6fH3By%)ygwwgOaR#54}nV-VjvIk8t-Zcgb<^8@W^&us`3!z3|x{mt3_X zivuYh^1!hf{kjDnaf>ir=0eZt7UW^sOm?BOQ)XmvK!7C=&mefi!aXo{z!sbQJuzb; zjA~$XF(8eDQ)jm_9$^xV{v*3x>lXBcyP_L`1oGEN38vu25bQ)>Arhcr%wVY?lB@(f z4Yxhhi#i$2uw&h;vMbRDEU=lu09rGy8hii)XiMm7Dx9oN z)PtxZ9M7EBi1AF@$b@o1P0-UFM1w(28#gG2hV)7v6uKES==nY07sTK?n1ghyFVh#q zTw2ig_Ib>JL6)(EMNwn=Fjew88fgSL|+U$P04DE8Iv74T5Gf6+4-f5H$8wa1H(|b?a2Tu;C(`!%KMOQ%(f$3^)kKmATb|ffW2N1em$_9g$|cx2ZdV$6a(hqCK(@AuLc5@zzVg{=WkO;F z12oV8in)uw{Q37rli#JjiW2CtGiu#Cp(f8`6a8un3|$taQ&;`eDUK9Y{ zUEm1%&O7Uik59aIZs;0=j|T^#Z@NbO9sKv5y`{~atu5qk2sxEs6MhTwYgmEs30B}n zxm3P|)w2LFGBS=U@~qOTj(_#Vy+)li2(8vD6u`3rK|ZO6$Hk`VO_T$co*sZ()#g2n zpqqz}gaJ>k-@pIx)G0vl8En4g*�D+Pf`Ir|*S|l3p)-q-CnsN1U4--@{V@~*h0WS5aRlt^c3l_nG_yGYp^#4V zln`K410wv2wMHE@h9sJsUgS#xDLG~amLtjoDa|u>6U!Bx`V`l^C?|Btk8Z0`%#p^Ruos^Q8XdN!tnuQaR|BwJPKuF_$UY;j>fX6B8)`` z9Be8KID7XLOU?W%xqxr=dEY~mY+2bf;e!D3+iV-Nv)L=<`M3O zT}Y!8eq6JDD4^*QDhreaP76O~1himpjbYD7ugstIds)rUQ)5k1$N!6F2EkxMGR(8fcl&|QP>;f$tb3_DY?GRC+@W^9Bq$hHcGP!nwAf|>K2 zGl#~t+|`Vh2qF_&AUL$4A%UY8*AoU3C&v@F<*KmdaqNqO#%-a(;rNTI=fhffNej-E^=(Fly-XNsCfFD1DXo<|H8 zWLU#=DA5kA#LpXK#t3(o9~~t8V zRQeS?Nl2h{qeq+TUkgXn7KTDo7Y!%<=*KU9ZRI;Q*8eR3dF*Kw;j=6(PN8pPE?lsV z-WVhTA3v^ElS6}ZumKRBpumgUy3nSX@&JMooojxSF&iW%hpuW_H+#z4P&1Q3}d{0ib%6o@@ z#RytX5)i{7Z?Lgz9jg=e-|tp&HX-keO0&*3;VQ{AE>%$Gf~th7gIL!)vw%9XG^;FW zs#kB~MeKh|7;*LU@2tQ6ZJa{LD;PwWHES7_BJ1NI!Z*yOnHdwToio=3{jlpbIcHGi z3w8^yF9G%yt!_m0FXCNjl_;MgR5RJv6P(i;RiGcw} zKLrDZAqi_>Pb3@=f{Q(H%ooAf+2=z#md6(mc=mD93_c7yZw%E))&cB*2Ur^H!j_k6 z=z^z!-XoMTfbR;`^|^eGk30;a>c@$ zOW>B;tPw9_E4c#3!WgtT4-s_FF}zmMK02HtCjW5UiAFT*I^e?clGxbKu38!uIe1i7b$LuQCj5JjJ2ErZ6iNXl7+GTXI|wn{q9{D0>(}lY;0zp8{hs2=izFq*@#Iv9gfWz#!I!WPV_; zm_e^F&{;Fu+yAc(=~QD0n$xywI#Fe(FFizinf&YLz+`*7R4U=Llgn-8c5**ETW7#; zW_rx*Zv4DH16D;yR6(bhy#Nr*g8>7b&*%R2pwXbDJ`V454VpgSXUYc*zDv3!)7$%n zvrn0$WX+!EDz;UaJ)2JAx5FhjCwQ4sK>XPzN5B+9pSXH>b)&9=&hRattI&X8pmsS4 zNC1jkjOW5-F^OY~G*v>p%Qt3MWO$vOy#bcC)tCW`|Cb#2s3O2J1Agxp`cI^Y@SIA0 zo|g6nMq&|ykFmB_Cc@Ka#sq<}Vft}IRLySwXMKs6LI*y_-4Uk?&w3}H`?S#W72@SV zZi}jA;Hydh!2TKmoD{O{sZy%?cRFK)RKTP*xH|I zLn_~2H{6kWEfk4oMQq3xY+zlvY?pF5yR=g&KgFYxF9NKyIrahXp4xw# zzFJw+R&78yd#m^A*RQ~Ub0EN!Tjdj61d&ldDwQ<%_<(SFi$8q!diKTc>KUmb6l-$5 z*x{Rhe^$%y)sl=uF~yk9rx5LJ)x2qD^3`NAoda&8};i0e|ny{f$${RFM+}X*0c7d+T9XOGiI{~ z(Pc6AD$FVGX|V%!IZiVdn%%&sL3~B56`t?vxYsowZtmc^wd1ZRy26B2$DCS}7E_Z9 zm6`ZF-z?^$FmE3)JLe!Q%PMy`%t9vSUb(n0fEQ3b$8j;R9zTDWlx}eecTZ^V}%tuxPSIMux+~!<1-I^E|}JXJGD7`1oje0HAxDvtDrG z0TSiWA#h|CApw>L)Z3<&N}VU!;Xn;mKXuRK!<|%Ri75Iz^!);2B@rAD?3(B52zYP@@s|melV^_ zv5%OMqKlgLBn~JQd6ur<(qc3L(+ce4u$7kEpibQuK8xv7i(H}h0ir|Wh6GqjInp@e zGiW;UF>S+lh2_7D%>W-rwK2_T|pXh4YoPm9APJ3o;Pdo35kRw- zaO|84$T}lKVtoBOJW-u8kP+RXSbpUIR9+1pDP3S8cAFRoD4E8QtVC0`w0N)l<*@1@ z{I>XLq8(PX&$7%3o6iK=IA$HeN{`=?wk2_ zo|&~z@JY?gC)Yp8r?@3~-%OY_Y);n9bcV}9&42&^AOJ~3K~zSny>)C+-AEj2m+iU; zYqeoRn#OO)0XSiJ>1FQ253gtO%^9ljY#V556|B5n%H-e3MYxN?*d}0SM>8Wjh`LQ-m!rwi zMT^jBl3zeF7&b{QQ?*1ME$}=K*d3Z@u%z-6H-)7LiR0UjF3?_(;4mYw)R(dhJv1a? zSm6;O^^jz8j5L1{o(p%40CWMqJo^HqmfGk!;PDWU6?}JYV1zoYVX$9-HjPNbbH{<% zfL5YzpM-CWj7rWGKz9`2+~>yyHjaSk`j3k)nt@o1f%dP7=!z;Uwie#@cMr(mm-JQ= zpxc=oJwWL6OF?kEKyNE&!ixF!b+_MXT?2ZzviY~2h9bao_nN<_eXU0Z!=JVa3gb4| zdZfyL!H2v1`~CiYN#3}_P%P5o<^I-(%goW}WLPCvo|z&I{))Yq=|& zuUAl*2m1k~!Q%UkC*pR4P&q=EUygOd8J#R41y$7nh- z0s)Ryfy5%qGW46Y|LQToo_LXhp(lcQblx&=%82W6@%?CV?DB}7T;^_Qv=JGk$2UXq zsklLkIyE^yH3|F$0UlSgV5P;HR8C(&wH^vx5zaixZY0A89M@x7oJ-bJM29r0pkpM# zV7?)-{Q`?0ks7nL0bs7j4b{>RWI~tTKJehbz`NNP1ON8>`>VU00pG}3+gyVt1;!gE zAXpZUp96unKi>WrBp4KU2ORhZXC;cVk%gr$dUvn=UNK-Qsfl|e86Yuy|4rtzvIJdv z^{oS$i^dnH1%9~%{ap#-u=qZ`p2`RXR^lBBaZ`z>39BsehD89bT_{!xm29PwtMK2} zRxa^CBv>NCViFc-z*|*tEim9Dt7Ji$GNx*+v#=@gv|0e#@b)Szz;)c>*7b`0)Ut|| z3)ytKtW?nNEY+3Ik_Ih_95XW~{_&$9|4KhLp$5GZLV;xpJUu<}fs#LeP&XtUIwx@* zvIhOwE1BnHbN=N;@Wap7#ViJ328zmfhB0tWL1Z{;ZBR%vY$`;DEqN!sLj@4e@qQ>~Tr`9fJN5||1IrYnWlS}N$L7vFyG(GxCyp?~;% zzis%OW=X66YgNE=8+F)Qv|Q*?-VFh$f>i_SPell>U07QE@R`MgPHIx6U;*;rpF6c%=x%?3yLMzg>j;aJaszm4^E#9mau?|=SJ z;((pT{_t^~`n0V~^`C!kYfboB#mTT2~vs$Yb>Ti^rgy}VhdRu}Z4Fvu?GvIGF%_t7(pKR&E;A8MW5u0fnV_Mtzg+k-wFIJ|88AhAL* zh0r-jLU3CU5wsVbGlt9_V{Wj`(trI#Cj>FRg5ANCE&1Xh?aN|MDURw9lSPw=r1$W9 zknT_gcX#JWncbc-H&;L)^5gpGD<%>#g=c1eIsYL zp}VS+qeT7ksE{0sz~TfgY1PIFn*r-E6-!1FsI-#!UM1g+Bvyo7+fLF=ESV(v2p~rw zabn)eUZFXmYBmvwJ2vYLW|5Ud_Z%1qAkUiTSrMw;zyQ*#6%065=0gBGj^--Vk+k^W zf!XlDESpG>^;$TBlZGnZ09|Pm)qSEgM$ZAPu&xc5vowLhBJUCU(|UgRWfMX7nIYvM z{*>sn%)N3@P-O%>Xpd6jhD<>vlB$~4LxKIF*};Gt@FLd=pphPQWwFk7iiP1m+Z49< zV!H`tv_%o}>#krfhY1H>&s@BDVQvsNjy6&Vz1d)v1tV`Rry4is?ebU$+MJ>3Ihze- z4^^^WarG`zw-H5X-dJuQ7^_=z;q!NS546#K?sA43<~Zpj(7Ih_zgKnfvL!DNiYol} zEDOHNot>tHR&_ku*)sy0t=<)IC)3j=!s_f1iB%krOk#aCJ!w`O2Zn@N+&HF%R7&P{ z(e=R4jr8P@Ed-A~m8M5MGAW3YurRbdeS_uS(a{<4StnN=d|=`RJ?J4SV0M6=J=Vy? z^S$YrG#C`RxADRndwz5q<*1F3StlQ)dj`wE9k8yKO#c&3*E37Cj zc7df|^Vpa;r#czY^!S9;vf}y-TTPi6Rl3{spU2E@@~L!&Hg`Jhwv$j`jbt+V5PEGV znZ)97_@)2TVBLS^Azj6PWJVmA1lH^IX1RW=LZVSqRq%gq?(Y7+Dh68*`YixFcjit2 zx0=a^9(?+fB_d$An$7%9ai@{jPf`8E-9c7WDsG&4;>;Ps7#w?B23k-4?7fy3^y0ox z{(kFbZI^asDPOU~Uo=!UI2425!BEFELqW3Vi4ea%A-(y)-rmvCy$#?W8g!5DO@sHw!h5N}2VWVz@0X!t zuUO8X%gaLvEe0Pyd$RwJH&H<^td|PnOu1HG&_&YaHwu+q-4$Piq)M&I0HIo|SE{uF zY%5jDwbeOmLEpW&?;#=%u(lXB^Cy#14WI2l`;E(BC#h+9t}mydaw|Hm)~lr|8alqg32`%Vx8|cJaDSsF%j4pMKja zfJ-;s8q$@g7ax3RpPK=z%sy=m_>=u-pWT|fc=2knQDQBvS{Gbv_04*%TB_((0d>3z z;HutQ$cw$@Vzr7=PhX{KwPf*7t;MV*){p@3?}#C^Ok|{P#~HVq4(l&7?S5}6m&V-$x7&A#>_VQV zl9|*&GpQDOyMLfxMN<>4RzRq11fhrW(UYCG=u2D zLDrV66>SLa>kEsRv)3@m;&^}9Z5{PdyAHk%h{a*r$XH>ah=#got*D5RI}e)oBop5d z9$2v4`C##;!P(Xx(%}9hr%v6q=E>Uh!Rz=}vZp+aDV-|4HnxCOchI zjx{75ldd3ePxm0SGH*(VOW`|7$viaF)!Ad+=1FWf+EG}chZe67EMv&Q!Y^3Iw{mFm z2D9PO(dp62=^m`FP-RUIO^@`LCTj$FGaJ1_;+P)pCHI#%O_N7Bn%*`c*2Lsc@1zAI z;rWa-xs!ch8}x3AhUWg5W+QiWf?z-#DANQe5DG{nl12TR_(}*qb}X}WJQbAX%<+`mR6*g}bH*YnIC|P&whF|#mhA8#cmH_Ki4 zqWp)opsP(9#wEZ@5MJIYS6fVd$MKieGh3SiXRH3b`XklC#jni;%XX0t-vQu)?JJd# zV$lLE8j>pp^RjDW+nH83Ai43Eb)2o$4FG&m06q_PVJ{u%`^^*U{^uU~>2qTzFr74) zD|h>VivvE$JlMq12O+WBPWn0NNPp5rVHaqn5&amKqd2s-lkwF~#x)A*F1Ft78^x{8 z^9{t1r}NyKkHTGRJ0ESiVci+Wu-AyD`@CmQ$qcyTSFhlHB}7_upgC5d#5(k^*SAyw zH^i7SFQuK508=j3b*Qh>W$|X0k!!Jhxh(vY7p{vu`j>p|0$$L!{`R)ucICuy%Ldxr zoHZ+}7r*)J=G<>C=wJKQvR&-B%D3d$+q9sL8qvUWb6X!SKJ)mA)8C(C7^&OI?}SlZ zx{0O>`Ns8~JVob1<2tYvd-IK*B2H;}O3?-*-@Kl;e%%$o4O@4zFow^sEH1u%w-ec` z%y#{E#?8-eEiEmrR&<$>UntZ|`ORvfRIG0n1>~|mUmfuIR>}pH>6Z)nO1Y?mvS?gJ z7-*SDo11J#Uz}Sq0N-P0<^{vcVY`wzIee)9P4a*V8T4oM3-Q$@>pN%ts(Zyq)xcO` ziHrI<>&tnvz?bwv%3YR~jM4-jdAjkR>xiy?F* z9$CRwLltj=Sm1$VyaS8M$ozZ+3I~W!2**i6>JW~Tl(bk`iL?l!JLYk`0>!FfBY~Ch zuj3s9FNY1nL<9@H;du*Vph0cYXb~B;bb#6N>^0~du*3%Dz~TA90rr8}6%MJ~Rf+p@ zC=d{d`&_gjL*u?9N5TTFO5#})ShXJN3+S$ROuxAU@fE=f78s0ztFP|}lV5x$T^Iwq zz@b63SSY<9Go9#Dmc|e|vi~kW8mw$k7in$G3cPLEtQXSaoQ5XL)0LzDOc_jSlBeww ze$SS*fb9lxz{DSQ{gK!&hD|uV;lWFafEDzCe6O;#qzP zVX9z4s#vIEi*uqByjD5rY*`WdK!dy`9HZ*NgIKVppNFy+2vb)1Y**M7F1P(&T3uDq z+ky2#55btCU79=UjvP87KN!nBSG3dLwAC!3_yx+8JQPFqT5BeXJ*p3FG2h=lW<_* z;4q!A#>Z0xFy2Nbs@Yo35WuV-LQmgU`FYA%Fyw??GYmUJ{kuAIT|HpVT@73^iG->~ zv%`1vqj!IGr4y9>xpIHy#i2pyV~k@s$s0x#vK`EgU?vhm9Uu8r`3o)ukd#>3GGd*X zr6GFLxYU<9?JX0Ey=Fh2PFQrK^!omOPV7A(Kj;HHVz*Fqep7WWtO^?f-?rZQ?faqI zGKFY-Tgyk}g3+qaUhSqAbYhf_CJTJBAqeT~nMjTSFPS@d!l{byrgczG$fKj_l_79* zaqH#q#HmN0{6flAoz?w?YBV_ipY6LT?eWYo5Sl}9V+ulwL&iSj_|n1@eU!&^An3^`*pa z9UcdD`+*3`*@as)>Q-M_0=5E8FHs8cc$jU>U`N*YGj?_=a3 z=c?M6XXxHny~|x$O^FNgmIAG;LQ~FGDzM>W#v|33vNH?My9R5tZ`6k4@6m#zhInO8 z(!P&>15~%E0!=V;RY_Y)ZEf`H*!32BzNb4Vc4<{g-wg-UZUtMya^28aJv+h0eMMyo z8&ntrQ^bouloeJv1CzKJY?xfG1Yo?|lye`c+^Y#Jy~7lXxvH~K^12{)DT3+!%<`Pe zlIAtr8J6Ykp@3C^+E2>k_aVi(x*M<)GimTj#yQ)1gO8_GChO$H}} zG24n*!Dgm5fVFfM z0E53*xtA1bzuL@Vbcj7+QaB(#EMS@$hkR^cEfBMP(RQllAZM;P3eB-ApZvGhz+E4% ze35_}*1&Oy=LpeY^~kNCI!JO2Nk$w)7cb7Qrx|6$Hzj=Dd8qdyyfHxmFG~ThtjynA zytlI2-~VOT4<1-MVGP3{Fc^GI0DkoH<@WZ!o+TuuO9INs2(T{%p-bd}n z&uQ)Vz zP#H|iOJm^na{?Fyo>^z@V$77ElNtxmiCsFqc-=hUtBHwo#}$xh!W_D}O8egzuah%F zqjULh@-Om>sinLCyhI0Pb~SJ(PP3N$^4S@BoPGZJR4Qu*u%L^jfQ=XQv1`K{r^Md} z=l09!QeG;xPgifGQaQY;@|o1xrT8dbAK7u-VY52h-@lX~cbCrgXA?Mii|5Ywr*Zn1 z%;e7BNJ0S1%PXxC^f;c1rw=Ahoa}BKP=Q|y*KB8Z>#NV~GDpX0m6|CC?-f}D;yoO9!KA41uJB`+Tc{wpkk6p;9gEWJLRF}oTb!tau*o7mRBZ`kU@habPMm$ zjiU*`ZJBkpHbMIKHZ{z)C~^T;|Lld-RTL693>-6auosHA7fhuJ#-aLNs@&<;)|Muc zmu+A5hH>OjbzKAa+B5vQ6tAsT(AP!PhpormooIm6=w}pqmP|rqnDW zk;TxlrGxH4u=dYf7p4-f8)Q+shPzB{(7{Y&pcYo-kts^=;{;X>jV1>R-CrgrLF2li zcr}D&!UtJ$)=Cm5qxbljc^Dn%x-TFuUx?xeYISc&0`h~uVT?4AI$||A1F%qXUmS* z!PsP!nMjObfXb9f20N}1`>M@BsK8pRITqlqZos~(^&kZS%U{yx3w3hLIn=HX&P#E+ z8Had>>}`*+_{;_{NFIuj*fGv#iOpbdDAsH%z_8f>m|oK~f`&%+MFW#T%4T1TR@7__ z$GE7ZJmCK;L4We-guI}~FV3g6@e#js|NPLxtA)+Y&E4nM?>t<1wYiA{3lFyzHdoHx z+uT|y^nib?f@#E2xLhNGH@^G+`+q-s2?js^=JDevPqwzUrtt%}wtrYdf(kx*(9EfF z4e7Z6OzdhEcrLkfVF4L}g>p8X&1RRDmUj?bP{6p1eP?_)1`1Qq^nxB@9(*RFB%Wm4 zNb4~Ubg`*S6GJHAW$oSMa`Q7rNf#t_E|)5-AsPG%G+Y6u5696zy!-wiuN;TuJtEFR z?H)OHZjZ@B;s^9D%h1Loi#L1N9R4eJkT~kh(lbqjH)H3(|RR0ow8Dknm=MdJ=3ca9* ze|hHZ3ylA1WcFS+AUr_S?{5TvuQOJ8d?t^DiJf2|;P${7-~hG6Nh)=LYCd7>%JJ?6q7ufx~|7MB?iTwB#0*)_V z_kF!wJ!8mpU-QcC|9t;s`AT{Rz0=d#`E>3vnbLFfn8P5!OX(}}43($FdivU-&ZW!g z+>@u^uNugwr}tlc`^~FYKl~^F{7gmA?{=Qire0RzS8xAq>(2br`m8+sVOqY7@MtV* zJLt1#H8_*<#IhU|@^Z;~I$bIVNH5Q)uPrlw=KTrc`SPSP;O7fR=ekcB^u5}*0{H5b z;c8#s*QpV=y}yd!Ncw)0RY^w4_&Tf92CR-GO`Bvh?5J|r*sClPEvaRMH8uSfB?*?2 zSWU&MGI^D9-}`PnzBRfmwrWO_+HW{Q^2U7wvo@Vt+uUSa*{CZtr3@rK8-X;Ko3YH2 znY@in%t(UKju!c%R!h=CVb!P=44NmI1fMew9aguHKpDwo+S)J&$K#F!S(F09g2mds zz%05==gpBgVEeLBE)!~umq<{TfUHDfjW%E*x!gf5NK-Epk*NqgIH7sZ!eiIMQ>=Cq z8aqh^aDo-EOKujQ3WfpTFxk+=TLlGu1*<7Uf*VIPZ^K7OC2l14z7!$}&!r8?<sxCy(7N#D=rUKR`nlb-B-OrS2X|3U*=;t9>`8Z3wOu%^O+eRjLV6*! z_I}+63q2+pn&^%DYMLNn-mkl10-(`c`Q5^IF(h$p)X>$&E3D=Ud>GEbfbPMdwQ{3D z?FmK|I!q2O#e@NS7D6mo+?4eU2JUKzmGD=877`q#97z)_oir@OC}fCbxlv4T^kDcP z7R9|A)wy#_x5I*-!zyb|If;sR;)unVNiW9g?#cr^>Y@OtOR%*I zQ!r`JBw4~MyM$uO#W9V%00Bo5sOMw=03ZNKL_t*X9HmmNivpjli64>P!6I15Xz$o4 z9Sf{;h4kY1?YK~Pp`+tgZ;FD3j?vcMTXn6s6r_6vhS6*-%Bjkny9Awkv&2T5I>J^> zf@a1nM7v{DqodJG9|#1S9te3`5M^O3mogbo`6@|R_udY2KHqu51aVw1v-irAoRQ99 z)y(hT!85!4Vt-Y5028_W$@K2O3F3J5f1~V6KW+X{_^+U^8A0o*oEKC+@$CJdKi}Is z+S}Xf`*FntU=hZlC-oUdsoX;2Yc##ed%ZH%wYH4S+ zkVg+)E|wmc^xnt!Ds8~RfrlzllsUPzkm(skbUu|%%LNeX!nQJCvrdKsgTbKhmadl9 zL6AEKmzY2^h9-`q*|akBUHal|D#GeS{%n#ePhb3< z2jxS6{}TbNAk;atQeCI+d#eM2w7mIrQo2bljfPk?<09*lZ>}lsf z&zZkWZ*On!@8s?P(d%y(CI(>U^yeZF1Av?V{$wtnn_txm!{zn)VxG59%jKn=nQe6J zMLFP2;&d^`w=Jl9SYG}7iB@RIKjQJs@d$coVd8}GAw3_^xUEwrh4b}$OH1>+LThIa zmzLzwF*3Gg`%RZgNQg_}Riw z>b2@oCkygZ=v!(2wVA5_DH=dfBWUT?Vn9LOe)ovZoHbk0!Uc@V72$G~?XTLFfSlQ4 zV{5ZJEL(EK(!eS{NuBJ+^jouOp^w&P1tO*4)4BjoTARSI5n5MmT1J9pDeet2!>6zo?!OV$}%O-K51(=&Y4Y#^Wstzb%POvhih$V=YP2b385x z%=oz_gXoGH2h_}MQ`!v7Mp(|olTS z;|;nZez-xyg0I~rtkyM7Ds+3La`0g#0~$u$a9KF87B};PR7vMJqXd&i8QSY8b%qY z#zZ04*^eb#PSc2_WWbNQiuMH@!R&#_qtvvGL8t;34hqcDm*nvWgxjLRYJ%_%4hDuj zcLT#IkKnW?3p*A_j&W}IuDs0oqmKx@3S_e>5IWjKV5M9cg%W!NQ*j=lb{>w7dWO3W z1ge2&f#6{QObAvq+l9O;<%y=Cz}ak5Dw}FL7#-GH!qlRm;XzhV zZ%l|P(U2Dw1%^jsV|C~w!tx-WpiPddX3=YtzEsby2X@fWT+$l3YB#oIxd}vM{x&ZVv_GN5_yaH z9`Atne)fFg)0$_V!C$C+3^_Bt2Ormd` z>F(+7`Niq(`qTCGJw4|>JH2;)@BGEiy>o)R1ABs0M@MImI{PkNdJDQ~L*ga!Ljm9) zUcdTgbz9pApPCAqC)dhKIEung^2^(WGVmZYOineLp`0$^ESizi@BhjCS*Or9hAKPY zlk$E-xze<}Oh271&$3RQJuK$YW91KvlnECEe~Ts4Ls;Iy;>2uQAbql8L((it+6Xm} zqZuLejo*CS@Wss@E%_bNL9~J5fq`Gj-(TSZR)MtX2kyMcP+Fk)59Cdfe-%(GaMa@; ztVZ(h(ej1rL0zRd-Rjdb+A9TWr=8%Av9B(6o~=Ny(L(>v4_v8U=rm;bteHt`5?1v` ze++fp(~xEzk2W92LCK%*UdV5?NZU|xeje0C^;TRWJ&f`pIV=-8A+UK^o-Z+m$n&G$ z5!glrEx)f1hI+bjG@-sCgHr2u1wrrW4j2ZUpEcM8_OiBp{CHZozzV?f4BLG(0RWpM zWfMes=G2XU6iOv6LnuAq9nynRakW$^A;2pXmf@m6<}^ELI+8v&ZNR);t8nd^{Rhf` z_ZBAJ{lJ*q_Eco8=@_SOzupz(%r!Xf=E@vGD$9bV*daM=MO^yE)T$>Z_PjjYh(DN2;)vP{H63s2sTu%>gx` zxfTmqZ7*^wE(6Ln$fhkfb-*Z;E$cq8>b7hMwJ0>yRA^$g92uKxuSVQ7D+#Cq=QWND zJ6_G2#Ct>_v}rREBmF<7mqM(Sgss*vDmHENi>|;*HA0yEC}mU zpv8ey+itQr%r02l8SnuMukG(A6MV#m8MtP|PI{XA&uo6-yP862t4N~3YN5J*JKkXB zxkx*0*pWCeCJJ@?4!UiAiW(HAnMNbQLS5ov#7xShAB?4fkeVYEJP!)n#c{-%*Uy+a z8}kz_iKsd1AJzcM?4U+t#bWs)`@zOOJ|n~RJyAuhGWARsmqYzUA};bM$wJTYxV znsBBn6%_^HIpQKBg&>5HMFJzj6ILOu>m-n9GE@PQP*1AVEWDwFWlfegsv<2f_F~gs zMC#wM^EuxiG>KxUZGLubi@H31&Ur3Z(fmaBy*XJT+L%1&+J3IYEjT*tRc4I!*T*V&IMhq~pqV`rZWS8#3Bvh;!e)b*g5la@ixeoGA;B^0+owu&g}{|n5saA!yV%tUGA<6{*EBKTuj0KaiS;3;lNCp zyZjJbItk^lkKuJN==U}>=t!F|k1qEj^qVJlBl-fM7bjE!4H!?z9VSAsVqkg#+tiW# z&wAb%K)3eXJ@xbH#FLFJ0pKBXBDIA6;^t=`m zZSmcM@Qp(sFy8{eKil8?)!y{vo&fNZmrs>1U4b#JT$#^qqQ;s}B~xglZ*BIa(812F z^=+ydb8R3+yzp#xAob%-;J5W6=3=W4*t8+7m=z*KFU#(3Gc%Bd{H|p*_)0h(`5W?A zb$wxh)Q;t)>_|$eUz$%N*GG;2H*C%=EwnJ;k3Z=+t~r$I^VJJ0`xz^eHZXK|muUzk z)97wwSYPx0XR%wFGpuj_L6;7j6@guOy?GAEaDo0G<8raWk=s2^6*#)a@3*%b1F!|V zmJa&ZK^qb%Y%IYCfs|!mcuxFws^bfl2br8H(;C3Gw(^HZ@pvq|rXzhYXMOYG(()4Z zyURMP7Z#`;y!dWdq03>`=9!Z*1>i(tdcUR9;7+B=u=HBErn2)tFSg^Ckzu80FKH5} z!td@qzVF?mYs>6_1)-lMrpr3dS&yNM)$=AP zO+Tyc@*;Q509wV?FyJRf1-)l-Ub;Kao2*OW>aG5?e8`Mt-+Ibq<%3v?Ct7+qt7V8L z$68k*msAh9Oq*gVwVsY8H}EL|AL_w@QG)O@gR! z2}R`!*}m{yIp8>BSI%m~2wbdL84Q>OGdV^UM}XzAx`Q=I@;X3`3s{}Ng24xqT=oOoQDQY85vEKRlCWJ^Z=(QhW8;z9@)^NgVxea=nnPHzpzV>WsVb0KOOMzT3rD_I zMg1=+Sn|afdB#*Q`F*W_XeZM}vqSks@&vHa$j|FXKg?b?)ZW{MeTL1Ij;b-@g* zNxCwXz(|=%pwx9QT@BSA$!&)J0@6kDa005;Q#2t}lo(0$6m#dc3dP+vBw8OC?{8b1 z<^N?)T|`sEJB2w>n_d2c6Aexb7RqOg!Fl9!2*%oS9NK{7aNaT44Nmi^pKv};L2nL$8$L~vB>h>w zynu8;>98CY>MMttNecmHo9odOjsm>Itqi{Lt2mo29Heyt!=RU(B)MhvJSva zMptvmTcRlY_fID#pKWX<1%XG*X+a=%M2)+0#?_%d&W6lEIa_#gxB%{Xh0h*}t2FKE zwKee}{+hdwTCKo$_xDciPwxo>KK(UOUcK=Hq;YGuMPbdBy*Cec2w64~8_2EzoPx1U(-`X6z$jyNmL0Pj)0}IPs zrWOV;oXpK8g;&qd5k>hs;{(?Dvzb0?Y;o&f{!sMEg_eF31q}*o)&`A78hh2=-=g5# ztrBS?#cFRq`X$q3xGxqvHo-XJO(>j}ev$t?=-$n~g#E*v-5X9~ND>sSC-8xxaZ$MDhwXSgnY9QYC&4!X9ple>wM8UJz%H;!17VyL5gf?%~qMe zqP1BoS1bTtF`_+&)5{OG{|Nv;o=ljSQvqOR@aGtp*MxhXZ^aJ)IQ=I6W=t31!xU}+ z${CFyaAm~;;7iN_Ai$|qI(9i8|NZxSi4WedkxviW2MqAa8|0#juIs+?<&ddBB1Rxu zcqUI+t^7?@3onb@LVFZtbQGDhCjLfkN|*(WZQ7ks7`SeyP}ruxn;Rt*+D@VdrlLTx z9jFdyQnW)eIs&%hGl4=|u0X5}h`mACuU(!X*OWTgpuM(l*(>WwWzm3dZlpLu3}voh zu%L2Ngi&*?91}o|FtBcF%54;O8zCB6aJgRVkUo#lf<$9*Q?4L#lePjkHwh;eEUt>E zLs+1;R!A-NgQkl?5Eo^1RaLDfbZ8W1M1i?MBodWw{_%9ZoVybL1`Iw5$8b zo?|Pd1S!fIxD?TqHH3EBoOqKQ3b4lUo1@oD^S*KF*cnNd%gox;lH~LdrQy;PKDjrd zXDvZuJnix@n=AEEJLu|VZAQ-^qN-l(Lqa3u;wl*J5>Q4QT@VsDbzRkrEP+yh+tV8= z5MC?%SdI)9gnBjGQsCC(4Td~wND@qvyLd}OSB2sZ`+Q?^s})X3?XL&3kx#9`io#xx zps!nlC-EumjNJ(aeLHUQuR?;s#A8iBgNa_&a4fY3`}}u2V-s{GP_>}hR>lUbi(Y?M zM~4cY89I}0W(V3{n8vgzr`$$vk6w4GV~+vgOo^aGUHfnA-PGimf^mJnKgD;<>n0~qaYZ5WA z1pOv$Dsf0ZwCZk7o{XKO5=UO3T%#R_+MJVHTc5K79yM7Uzp%2PFDH|+xc&KFW z>SxodF#+?;D(dOXhJ0sYX>$D6*V3`|)VBO(%_i4{+uaz}g6`wB|fJ;155( z;6G{_kl?y4XZw$r2?wT+p{&3A?D2Lb!R`I+e>{6ufV#g$m~hKq(e;;VAre8W@_|y` z_D(i2c@%s(*|8L8Hf4@>0F#oH2mT5hcKPp9Ec~9yo;+Lj>giC6WjT^ag;od#fNx*8 z2}Y_5xJLa*Dmt#|{O(ypzG>J zf5c;!)o)~WYX_*f$qbqoNRo%a#a+Um4NX^v?xia@o>BntvlnFoz^9NH>^<)9w1n0m z@H5(wVsGcaJk>fg=+u(=AYughyOuJL3G_S^IJHEFlswAwMB>=dny?b!b752I6o$;p zGu;mojN!16hUE~3dc)?h1)>gzkXpzv{vjo_4#v_tI>tr>^F^K|e`swA-*zK!#)DMM zoEkGxRCsHlU4G7uD&f^7adD(L8c?bmh|o2R_zQy)B)gC)_W#K`|DUGsJdTgjHndF$ zv}t3CBG+O+6)B4e$`|XcIqnDf;lO3_QkN`gQ!kakoj{gK7}G^hE}(=RD4yOI!@eMn z+m=i2PA{9X)2ZkYLV}Sc6E!jTciijodVl!h{3sRrDaByr`FXxx&o8BL;FzB?7lbIn8yy;WA= zmujOJVyj49Jtp9YAniEm(4=Y@*v-bmHQzIP7A`Cgi`Zf-lCL6(#CRo+qy&cGf$<2z zR|CFr9^i}kd|K1Lsg%$=x2W?ts0g)9~V`Zn_xB1sO&QN_+EK2a}193jNJzg05(QI$-&fyvNJ%I2v?~j>3=Q1W0@0 zu3$WHBa_Yumc}!lv^>8R%mhFF!giEQcGqeQRtQ5;OVY@nVbQg{ zs-I4FhlcENwqQPXC%Neq&=-nco6;iUkX!>01rjI0vNNQAmEMrm8&3T3H45C*glMYo z+S8})Pgho-J$bS!$HMc~C38GleDt@)#rgU9|J|3H`}Z5~&)uK9JGZon&9=RsuC;d^ zg4c)8eAuyZ&Nc&Yo$Z_LYwa5xe7|oA&(f_2cZC1G4FR_MVDxgD_5vqkudvS7O`i$6p{qkUJindJM%}y(i2RP0&C-PQ)ehlSitmR4th%wA!}sx)QZcfuS#PA z!%h=OS&Fi%lud8B9lGHxY9=geg5E)#zw&GeOh`_cZgUJ>79GL@s&!71DV>QJJU9_^ zVnAZ>oJ};>e;>=5&<*0DYwAdTj;P%z5+mM0=@`V0aS)jSPlgchs=*XGiEa2H+D0{c8p-|8$NbBWpa7CCYzjH5)2zAlHur6q*L-h;*70E6iO6u3ASP=ivim@Tje zH5ScB{PZD~l6p1#NR*HZ;F4Wg0^c1Cs*cJlFr3zbwET*yS4o$|!eeo5WHbsZ5I5bv zqZ&QQBzZJo<=G2+qA6F9M2@t8EjiQjP%^MmalAzYO2@Sa$;ynf{1rMZ033{yx?xRQ zo)oU6eB2@jS|B*7^+$rdIFfpazUuAF(>s`+aUs*;e`0Cy*$I=4$9$-(c(D;NV-cvjlAn_Wc)kW&0}%to2~4wsq>eL5(|p0?8Z8 zV|>7~>K?|rw7Re)SP#h0;aYm};)VW{))t7#&p-Wq=2MNMCXVZO1ae){|^iIFZ`Tma=-`FIW4I zpTF`Y0wm-}LNLFZQqcM6)H?30GhpP**l)(JoIg$w$3uC6+-o{3&vs;+(pNKv26#T1 ze<1&2lSHS@%v_(jK62;Jw{PEGUViz*56|UTU0HedWc3+Wde2tw_0fhze21w5ruDJ? z$4UJ=fx?Q1EE^^#r;tXSlq-aj+HYku^qXj~%pm%-Qee!+BQtYf*Z|yWXF>n0eLwo- zZAaRxyXLR^dXp6a50feeY~l zEjX7D)kaB%A6i~6-&#RONlxgkNoy9Q%?hZ-1R0qu#4LYWT|eE2iiaRq8BO^GgiR#m7nG0}wvu(koBi%Ymn1=09`nL3wI(tsw*DWFX-UN6vH5>)fA_At0`2YJcHV(J#qJid4uUvJ#w@ut)G zdbJW)EXrz+9RY_m~=kxiOUy;=i*?Z zWH1w*jx&b#P+jQK+QF#Gv7#E9j14Kuq8FuAGM~3BojV(!aEPfiz?)YOQg5nr+KTq} zT1l-V5-ep@wy0W z^Z2+;6CBrEJRMy^BfA90y1MM{0XB3Ww?E$b@&4+^a{T<-*TA>U_1|Y+ zCBP?siog09C+0fLH^H7kbF)(z@E?Bt?!IHY4*Z|3^Z#i&zvH+qrJkvlh)%+9$BHIe;E{H-f&W z%TEX~8CDY$v%vPv$8W~R??33=4fvJ>tUyZ6Py)vT*H$@cx^dfFmTxaF|M&5~9zJ~W zhxN6!CvP`ir#RWV&q07j?VghLvm^ILt}j1&_;7XYf$;%@z=s39R@#<44FLSvsZGiA-0aq8v|ixv#HGo} zrOBl+6%SldoHtwGD`%}!k6u>kk#f2_i<@L`o){}9X&N-Mk; z*RRf%?QD0gL}y~KW`x(!mz1T&NVd#;yF>6+&B4rz<#jm0Lf6hzI4d{Zn4j*^nRRYs z4^_dsUv{)R>^h=$I1o*x9fWA1cqWrlaJ~^WG~`#{8hUKYP0(4WQY_ZLd#D9&gze_< zO$$sTa;B0{h^-?(y+;98v!L@$N(b(u8bCOq^jGkg{VqJ0-rq3wz=G3)t-^~-N!m&)w zIFp7ew0Dr~jp0%a-yk2$iABjxPw*G;WmdotUUIRDoLG!-|GGU9x7vK&9w#+|Y<%@A zq0ZQT-N3EWv?Gz#A*A*TlAR+FVZCzQqm6=*i1}FT%p*EW9y)JGV0j3TMTu3MXLQb> zxD%j_Sl?2P=oznYIZCdtjw*L9-q8;HDhZY!xV>GlcP6(zSNo8tBea<;Ea-4H3DMa$ z3JNpX4VxG&VZ%0GW`=8qQltz+d$p;M)v%`A(tkt~gI9%Enzl#U4`Vhzl?`#Co#obG z(8!|&NBx<|r2TRBx_E>$L#mVZ5&jJH#(jQQw|7dwS67&0e=%77V0)6@VKV?CmyFd2%%YvnxNx2dn!u-+7S5ur?+Y7=3a15F5>4;`pSfrZ?;y1u`F z+eqgq&^AH>qN~*me1KdH0oiC@KPi^NhR>m=R`^9SJqYfe3x?P`-=cbq5@&C+jV+#cJu-`&ccjBTqT+*ItFMLadcqKYAq0dil<>5Nw4B^0{u_{Qc~&W@&o5y7*hu z!9IP8;r7G*m1;mTSy+}6i86+x7fv*Hbt$r1DU_Xxz{-CCU}RSqlR(F=!-aL7Bw@L{ zT4AlHp;!arxPj3)iy-f9x$=1V+v|ddFP^Wj{q*F`+qW^zX)%s* zeyW{THnq0-p<+7zA7R>pw|If%$`ZgkLH&VpQks;`jGY}**|XUJvjx7363dE${(4jZ zcy)EHMF3dv7bSFEvvCO__tFvc`Dr|8^Ye4^1oAZCE(`F9OLOz1@&u!k*XLD%b@uG! z(vn#MPcCgn!<-ozyFN;s=IPT{$%5Wx3|?)FxwX$pQ$H&MKg5N^*c|N`j`B6zN(hb3 z)+3;+2uo2?PnLm6o8qnpOVYGp@6nw*xAHkn<8Bv>} zVKSceScfA+D;OHngnf|wtYhcgbXp^?NX*i9B+Y(SGZKzq?PI_hOy^*gEzP)D2(CjI zautogrX)$=*7PM&@Qd_W=x(}dPeQY;5`1b5S5@t8tf>l9yg&nzb|qC*g-L;~si~rr zp(0$Qd6Tpc?qv;JRSE~jrF6NX2ssurX129J^RUoihRj73PItv{7%Z*$RPJzA&<*S+ ziNk5SfQt!@g!_6JI1hX75WGkUk@T3U^&Jl*XK+|xb_h}TGo+4+&8KDx`^OZ`bIZP8awEkC@y%Zvmw4sTU1W^)?rSdB@SFC=q zDLG9iFozav9LEm%X=SkjX0R-1%PK+WFDG%iGfbN^3F2TNO-DlpMM?GOa(9-=sJ!#J65)Z$H*x1kMbd520|@ z4y9_1(-7!ZA5yhE%OP+*8dUFaJ=v5TBaaYNn-tWWU2tDtv>@51=K%iX@TLkn7W)|n zTa`xdFLAerO~zvHtD4{Y&Yyo3+xB?-e}TfW?T={!B#nLF|HjLWjc4D#eEH`4H)~JG z(Og?we>N~+Nw5YKg|Q;Fu>+3$xu6cc^I@GZgT30rP}s0l&(L+a0T~u|3QLu{|02KS znSNx5deX`7zWfQmekm^zAoiO;I3db}MC-0bPFL-)=FCHX!^*U^<~10*J(99;)Bamn zYh_`5nep+jk6yTlOEpl^YgEty_4^1CX%NTkCHy@CzDvg9L-DfmUp3k4e)S%#&qSFJ zMLA0yp)%msTFMwov|&g zi+(6;Xs$d?M`DTA6$={2e!6>QbovHk<||juEG~{|+SQraMXTX*ae88G3>>^My)-s* z27}qGAn;x7Lek6iWuExS%1NTh)rr)_{JpK0*y`TE32j4SgFH_p^oXGA+~iC`e zWZJYxEPk>mfG^B{`Zu!x|JdaD&zH1|;huVpM<-^_3yxoXK0aQ%yIIqpE88phnPQH3pO56y%LijxGN1xqpcHYRcfb!!|60a+ox|Ar(B*#(%Z*bUdz==2%aZ+NdZ z9)%N-+{=24f^1kt(2Z08UpCTbY`=SJN~ubcH-Tqojj&reT(DXwEgG$&uzVu#s?=Gb z)8`r|Oqc>BxB7i6G~*co7Lk)=a}4RG*KPWfK6P^#Q)Jj}DTNE*F*+$vDXL~{!b9by z!cmLln}#qVITesS;nM`ZmbHpP!|ApJBS}fQyQfGwK)GUDE5o02VsIfBaGq!BI?Vre@+XYJP zUg5nQk)ehpEk{Bl4fuKqniPtgmCXVxJIizc>nn_)tsLMpji}kY-hi;)3|KEtjJVb` znBJqfAKZ;=M133vjJ7K2iYJBP#(lzUfm^}fZh=}q*;pZ8h>5bc9g*|wLt*6#`MUjr zy>fduJKzx8+^F0fjmv?4Ki(vkzXGCk79xA@4$6^He>52i7SP<#C+ORhycI3@A6?h~ z({z4^uPtpT5Mm*1rOL=4m}|Ork&+8F29!W_5p9Kv zY>XJ_MZqsuv&6e~OU4vA&pU5f{K4FBx*smPe_;Q>UeEJxIdl%SpSGVC41qpM(9@MF&yssbaBMczW z=Py2Lv-u^l3a+IJIxmCHA>wk!`$bg$1GEPNq~Eb0b>!_wxnub4PqROC-Y3BMENDux za_7~ySRGYiQW(zO{0KYTp=RYBepUR-1Lo$jKr9x<7v%%x<{5ZF=q{}ZM7_}^hqoqh zRY2U^TVFqLwYvJ)z%c-&P*qg?ebYGH+B!7U+IMnjw@*G!R1B3=dl%IU% zzAFq`jbq&U;&%fbN#zKn5iT4gP8$u~Um=HMfA`zf)u?R1x#k5$ep{KwK>-%-{8Q0K zzo@$Q$ADwW%PnhwQlTZXK9XWN z!@@><0cA)(sY$c|@ORJu@%_seB`gOa2hMSI?!TA6-@b7E!p4G7W`WyT#z$|AWEfbz zlNre*)s;^-5!*F8yYgvj;l6-wGJa_ucH;#WGR)2=GGxFnPh6%NoQ)U!7T|qO465_M zmo9lNEwU7V$p~@9Oc>l0ej|^Cx@HxHrDv&Y#rJJw;#wOU}w4i;^f@TJfbJgi=LXPFQvjEM6&CM<2NZmj^18b4m+s9Q?0~(Of zNGM?Zbqn0UH-N^1y-q>eW{jenT58*8oKECgVaZ!5H=A$NVnxjKt6Bt7Ru;E6G~7UJ z7HW+epwz-v7}IAYP6{s1)E3XoP?J?zJcG0jJaVR%1Lw*zYM(3NJpznU0$nL5xX{HZ zb{x?MtWu$Gn*>eErpu<0*<6Jbtg<=;P)=6~4l_kdF3N6JL66m047>%aHId9hxy4N` zq|kK)UW7c~t~*r*g%vi&hfYs-b|MSQ)Hz+%d73+57?$LTa56C#tL_7R;qMF4TUn^n zJ(D+L#?k_V{DA1N|3$_m0J+F&pcopCU;|2m4dt){!;^%(Xr*{Af-A|O=Xkn^>n-F^ z!ki>bR&9g1`3)N7eZN(+q7f!&9z*&ha?|<){`hCxS@BRLRnOFWi-OZ1%53Y&fAIfi!=_T_29NxjrwDJwhjcA8D z%Oq)D3&;2b9Mle52i*wr8^PJYew*a{nf#s=f@uZAgu&Vg_jMbBNi;d57>4a>3h zaJ~(x>+_lBtmjC2JhQfETwD7~(#;wD<&xPl7C4Ba0X38Gm(OC}0wy z$O}797B6l6K{=A<=F(~h{BHp802r`?bquNih+ZGZa9hbx+t7)VZM%JKeM3VPeQj-h zyF-G%eHFWHAD)!6B_$^+D%wt#l=Str4fh`C(v_<*^Z_T=(mN_WE0Y$IyK{eMF1_)T zusfUHm{aHWHs_SR_-Q(4a)QxV&OH?Xe);mn zxvyF|yZCNo3AvnbBw+_^Mi-K9qQD@4SP1{Ff>ynubZ}zO<6-ZhUO=>zZeEXW!ZSFC z%`Wnp0lg?rqTWiF>>!gk_yqYB0_XT_LWZI5Dj=~&NF_>=bi`u|?}X*ovRaB<$%2Vh zXtFH0DsKc<3!F^qD3v2PFgP#lNIJGN2pB^dJuVOolM=kXPE`JmH(6Rxmeh=x4yQue z7D%Fj+H$%D6~N<+plq*oHn)TSHno!iHwpD^q9>^Z9$?suPjsXeD;s9oXOM=4l&l%XPL^R*T`9<0TU>Ti0JpO8hAKwFvKL(p&|#U7Q3>i>)c~+H zH3-(40M({x(p%Io)RF0S0+Wkz%XFv?(&yUgPC;!!*5ayZ6W76T{oWMrD{L4UT99QO zg5y^J8m?b#iIv}%nO9)L*z=lT2{s|UvhI}JeH*)CRuaONB$T^u8kt#wzJl5a5hm2uO>H2E1@!Jk9x{b)#yJ%dP#0uCog`qem(mu|pH6PL_<<=Fq#!QfYSfwBf!+)!Ndinp7+Kz+kVgI{) z_ic!ND~9qdVRN|SXSLPaqwAda*MA@eYhN*)e@c!b=M-Cj(QxjJYA^KfYsGNc0chU8 z#WvvmILa{jag1l9DxZVE8&eQWOb!!+3B_{ZSEFVH$T$&*u?JXD;J|(q$B`rcTOXgg zb@u2mSH2WHs~(1doF9oBVGN-2YhYE(@DTE5A-_TVTG)d)!UT_@bI^|Wr|1c@YFGrL zvCtYc5U=qI^>^#pzpBWMuAKVnfbHmTR~~+I^Jq$`1zGIrl~0bVho?84vM2VI7*4!LUuO|~*E8Fp3 zVg&u!x!qAO>J0^NI=J^#8mFkkTVGvWU4QI{V@K=j>yb-ZUEO=N*IR$@hoiXNiC~zLTcL3k8{bkbB+U zdyr01FTa<~ewST;`utnq@2h|A%A169=XM_p3m)|X5FJF|<>vt43-Oih6`IRe;@k0+ z^Xgihcfkb@19@Ei&AHHXUiA3>4Z+{|+QZA2cY7&oPn^ zEMGt_a{=bdIyFbu!}iO#%F<`(U%*T6Gp0>Wcr0iq^b88(>R0tpWTDIm#6td+#Uj+!GrnqJ zO!T;*DdH)cxes=tq>#t|@^yZ%ZQW-WuXQXTOT$=kEsQi9Pg1QPm9&nkv12Pm%uqbo z?DQfd88gV0!3cRxB7$1HP}q$Zn}8EiI~cMBR+|L8EZap*2Bl>kR8B<`<;3k&Dd8KFQXxjucSG-v-5a_VDq%{(%^Q_RX$<*u$1vIOG8*EXB)+4lIC5wd;AO}h z0(eh#q63iJ=)frh-K5$I>0}70514GqEdn)8A*P}d7?G86TipivMgBZ6<|>eq1BS~c+`*?h&&3RA8{sg&EWLqq=feHWnePM|;b5a5 z>yac_Drvw09PsYYgcR(Fcq&99iUUmcf<#n0!W$-9Pq|oBHK3FB;IzcgM?BWQ1Y&s+ zL(-uO^~YL)rRnbt4r*i^RAr0;D~ARNfF{BqEntnL>uK@;4M6h0qK(*IP&$<%IHsbs z`hC;run;ZVVGd@zOfqzzVQ#uQWRy7jIM+v- zu=9-kNRuuPL)YjXaMh|dXp&dZ( zG}#+9yKQyaMK@AH|0i>A!*Ks zT_e9uAC`5a1K}0HtUy?M=ar{;3*@Q=$*rR2=dY0QgbMl!SaJHsYXj5Mz^!aYvuECz zb#5dO+3x~oIsD4`;o$`(V*$gnf3jb-Az$UJuo}6Nq<QnJ_-ZMmF2a#lZ|2V$C;se_Vav|F zoqPANT<_@U9_HPhhq~qtAG)J=>8f~W_wVf7fBF8-9wX?VeEbSi<4iu|@)tp!4F59z zCUj*b?*Q6PSXs*4R2!hq)56!zTXEgQ6!@Va9zi?2a{9M&njIYM9UScJ9qhQHJ-lZ2 z&$-T|m$OfH@VcF2XAz(F=HB)F_jW%u{`=3*zx?uFZ?E|bcyZZyHQt_LzC0!Ql`(0I@LtF>rBgw-Zuf5=mHr z{z!kAZVu00jd=~v{;PdamKQ$9$l0!Vk)B|W7iqBdMUtiDNlKC$s$@X>jEIZac|!D1 zMtfR%d7{K{U;CS4AWBbgM1O+xSIFqEGJwc^hW!Sy81>mj9aS?AFoex*_Su7s+h*&8 zLTBs2zCmNYX1x=`p9P;!g;{fMyW8x-ZFeW!Z2B3NCkU{Qy{Fx3w|VR`?mpfjs?1CR zTYq$|ILg!Fw+x-JQ#k}a=D&^#JC-Z%t6{XR+sB+!Ty>Ec+N&}o!{00Nm;l3BZRvOuq}WP6N#rcz9O1&kL#qK0iF`M$cy!hWYe^-&1}xxQ%lDA9oE-c|Q>R8u}jGvx7Gc zbq#Ip29jF9;_G0qUD4%%JmT-|tBMfW*Vk`fH3a?%a`_+4W^QKuR|O*@kMFa+bq=*v zvfgyqy)ek-32qBsNMyUe_vPB!&wLd$5hr>@VXsN>0grsp_5zwD z8~DO*NzRX*Qx)M9frCY#jU{o?HTP{?lQUr}J1pstC4^MC)=H0Q^Xdd(B2E?}~f&t0%!XFw# z?m_G<`Bg;PXxERVLL@f70j-1wi5v(-20v7)tv3|DK=xJ8P24hynTZwKNG-lGIir*I@a8G?TJsAf}1|v9#5uy zdfP?nuAf-dg>&7z-1gVs4s%!2UkA@Q!rL7}pBOl^0d9)#Hdp3^#{jdI!glwHyYQiR z9&i@$YA<|c-WOmAiTTK{-1vECdiwj)Trq=2Xmv(89Lj#y;CVsqNX`#T8rB=efG-T$ z?{*zg6}~%rAsTTp=B$7Tgk~hea~P!W zG3Y+r^G(gXAK8z=+tJY{UtL}MFJI^X()OLl@oB!0s05Q>s9L|AX-)Jr>mXNaOlKf4 znjaPg>9BBxIECQpt+gB?oWBf?LAik^r3&M^gWU?2jd2Iv(XoLDMTQ+xi1a602Z#U1 zy&li^Cu(Bih_JPrq>B?>hth}R%B zs=VJ&G^FV$+Pe_Z2K=xLZ85Y8%@SrbOZJiR*2Y{!0l<-v@!CmO#KxddL(%q}g!mea zZo-BQ>o++o&P_u&7X{Xt-)c0>-J~|{{vUqb0z{?46D71@DGD4kcP#B@g&XE}; zNCvkUaQLys>SyXXi{+I8aweyj8yUa6o@a9X6rbtx4nM_=14&ZWBfy#NdoW&GpgF95 z$$hctK;26agF)~xd4$0XcFwCcx*TW)K`SHr(7f z;*`J~M<8sJ7V9ejHZ~Fqeu*E)a!j@xh?JPw8VSm$5`T_ZtBXOpPXH27z1#{P=1q)g zd0*)a$2w)yaRX>)kgNCiBb{%dIGPPbCmZ$fH6Z zmRSe&X^PIwMOTdU8iapQM{*6%jY@@7!t`34 zK%|1P-a-|h$^`-)5*o+CivuI*blzxh7@2RJ3#X(zN~aUHX04FG!17LNVPPvTo9H}2 z!3%6q3)_2T1${SxQPoxfl3a8^452M3!q*Na#>Vi%x^ml4cT5R`DN4--w@PCm6PT1F zgIqgPRQ7L*;pPMtXXDU`F#}@sO^A&aC^n~M1ASLYr<7z!#RBO}b~H^yVczaF`g+&T zwsn66XfrL3p0Fz%pYh_jd|GloaiVtboA>NH9HlLLMP-lvy2`Ux zjP{_`8?|CF9+U>9;=@bxr?b&zuLTVJ%A#_*f z8^T(GxJ_KX^}&q?w~+iA2|jmCv(MK)WB^(&9Lhk_-px@)pq(ao^xEgXF#c8nh%h1~ z1K4T)Eck1XA`fdBdDFyY%pr}u`oy7d+t|0)>XKgvz+Nu!s7qiVCis%-(ibnCBm;ln z^!9tf2kT;&9{g!{09)w8jfc=l%DMLCBTCJbquKe-!;h%_K9oNC;hD!j|Nf7MUp@Tl zzd!zTWbAT#^fw;0RrwjrnY%FHa)G)|6ge(!&`oJcEIV2l7b$cdfQptNl>>cJGJ1z5Tu8+TpQn_xF#E zULL)C`Ep=af@8%}x8GC}p@yKl=8w6~!8gxs>kM6Vy~n!TUTx3Y?(Od%|NQgb@$r7G zhBxcs{-JG;4?jCPJo@73&>r@UK6|nAr%y`fuPSEAYLq&L^m4{ z=jIH86`VjFT7~COMDx*6tQH~-ATZX?(gcxD*r@Cy94g_xsEZnNjj&x=U}1^H#%Q*` zpUSfQqH`oaXtdd&obS5fg(eB~?X%p7u90e3FWufqKfG9G&jz&-mkex#*FT#RJ(f_| zu-2c6Y6vT9oOgzqtc-s!hdVThgSp}1r-KHnnQSiCKbU=*q1~I2>s3zq!1!($%Ays< z7g|;v85rB6<~KD>q8=jgk*Ph&)B@QHx8n?%875`raC8tL_vz9cjRmz8t0EXNHjq4C>L?U`f;Lt~V{ z3`t{()%sSXiHyowW4@H1#e(f0Rp(6(;RMY@mciR! z)hAU5bGndTOI7nsG;fhW$c$AgnNP|aE1lXh_%niRC$%IME>y#5`79^YEyj$)Kv*`- z#&?-dHk!=vQ~@t4%Fq;u4M~UcSFYR|G6*gv#%#wZ?U)QW3{i`>i-x&?^44v;kkMyZ zKuh6EB(Nd2VXR8o2FqK@W?6=63T|STPO?%*MB*DReobp zx%~g~q_ZmFH&mtH$&n4Tny`P>xW#^Ng6{EL3+uQPL!A-ohva;PWOeWjFON zyQRH-WqW0(y=A3TDvg)MTS`4Fm}=SHZYkON@$>HfW^Q2dZ%DGbF1*W+F|qV@ATT-W zGX|4W=pdt4eifh%6@8&-qjA!Zf5R8`H%|I#21hZCMy)#;if+icqk$l!1_^aJq2{si zUOKp_gd&>_z^fX6ehvod}r07(H#(HT3hspqJ_-=EV$hN`2APRbD;EGTZs$?nQl z&Ny$5nGHDb3^Jt*DD3Yae2Po73@Qf)2mR6PjM4}*nZB7EAq<1Ldj`lZn6Mw8Xq3RY zzTuhd49(zfL)uJs@ZLRA2ea9kKIe#qG&sY=v@KZe&ZrPQJS_K(j%HqT8{*oTj^Hpk zgNBxB5gUun((wh7`&<;EHy2G_aBvk%j$nr(30I8~cMEE<(Vzw$?4>K*u}m}A$Z#ue zmG?pG4y7WY<-Ol+YnNMF6+vjcIEbt_rZO~+SR*$i-Bqi%7t?6U&c=mZL7H@=8w_K` zoVKV_Hk7<=vd9baJsM>X& z0K9jN@2;g2Pw-n#k%o}3N&>uaC$+{j)SU%duTFN9kOC>4D9VnxfV#JUbycxAHdZX& z$`^0r#i53<%%af-58YAHf<4C)TgHm>Ll}A#^NE6CZ!zIKwTd#rvL*ISt|X87g#nBE((m=Y zj$S{{2-ZyrgRgy_q~eoASQn3{`Ex+?YY-cro^Er$^>M|L$SK_r+2t_U?Peg^bmhCz zy6L1L?`Ylj*^3_ZETK^VU-D+5ZPgdEe}Dm#eZ&-$6si+*19M`V@4k5X=*6p7uUM93?w)p^-Q9)mLfyODJGrwg7<7BrLRYMDk^;a(+f>gBxUus!47TIYO9z!-yWP#r?s9jtwYj;u+-+?>T^8_e$w9flDR-9JYQ)mO>0z>2 zto}5sdxBXO1<#7x@}q5I7i+hx?VIiPNwr-pwr`55_UCGO8qdhtpTA}g1`PNWLmX?Kx|nqb!ALRFneB_g88I{iK{+sz$l;# zg<3gXAOZ{Rm9XLTlsb_xB4wx{T*~zOf}b@Ff(BTTL}v)z$Y=&fL5OgrOa#X~i5=+* zBCJXUP?npydAT7OdR{2(Qu+c*66Pbe!f65}D|9XZtaLj7y>kM#zN3G!`<;u=2?O@c z9|?s``-CNv7ELlG>Z&xwzXGl3q@NJ^e5njsuE8y==~v@1BWF38o?z~*3UCW5PmZw$ z6SqN(^R#vZ3#Q`VmFp-H^a<7i&7?dtu%<6~dUDkl*S6pHa9eQKM*~tEyU`-tSwo`1 zXB@zbucu#+-%l?7692*N@*t!md?hSsD>tu9;uX;xI%FPvbiLA*aL}dU&+f2}q1pR- zz*}gs->YqeZWTRywXK)6u19+b-MaFPdQ2o1suWDXT8N5GX)6Lud!s$?R=~UEkFqBd zq6zGRnJ7ug=>VW%#g-M_C4nOvlmoN`_X0huN0Xt|Q*UrC8;JBi1l0R0WHz#I)hREe z9VxpTfahklnea46RutLK*3%6Jxobt7oq%{ma#J*T}ZAnlG6{5Y5^b zuTOTguT_PDd>`r>UB#BRWTBvf{jO`_pbD#IW)2QYZ%1;&E|?|;p!fNjU@2t`^dSkr z9%wi4i*-5nf|^4$BMH`yjHbH8U>TLxj5Z)?A%ylQQMgDqqA3EFqjHkm8I3BF=ieDQ zpMM)z^`*e~e(t>YSd#S>O5dxR|5xtSw{q#neGGcdgXn5+?~4UVq1sVi0jPUUfv}li zJ0~7Kb|8VYhuVjv=3r;$eCRBV4}sg^%Li+)`FHr}V{drxKibn_vr^!EN4LMgNPgJ4 z*F^vL>(Ar0w^faz#0I?Wq;V+u)gVf3BW%w)MGR^PezyHbK-q6lUiwijK!O5Og5=aL zd{iBl{Kfh{eSz}_xv1CwCx=# zYfWdo%|f>Mw7c->b|bV9`xLreSP_JaeOg$F-L_&Yu?2b13bjJFE4MM2XG&9C0cey*OD`2OAo-RVCj^5cfYd66#XZEy+Y6>#i4J=O0X0mC^ z(Po1`4S66>HIlld?UP6DX2+du0Q2(jpQk~fRfo!&EQ#!S${qgGCI6Y$-0ubx?*?=i z)xsM8OQ57csXrX{;59-arIkmht)~3Qump*9Q%kYnfQ+gMT64mKaJZne=)O9Er^tqe z=4vE|E`wcUP3jDs5NP8OCT7EhFsl~shjkgO^$WojItn+3QOiBIVq+;;m`_*4oU$2fa zBcXzZ{rbaRxfLQzmDVf2-{n!MGfHSrP`R()6LGs4HiOECTTEdTvm;HjD zS`ZBXb@T2%LSXckAM;T_4ZxHhp*2DB8HDvBJBh0OSLe(Ek?62anNV+8NLK>7DT_u= zt>_kqvW%xq3n4;h%WG{3zu3wt_Uewfr@XgkvES|WtkVxXF9(Uo67bEMsdIgoGDGq; z5KH&uspA=;(xogb)b*^8U*Wfc$*fg#SwOeGo?Q>@?`N-t5i8!UUuTc&qkXotR!OzW zEMrGA*QJt1Ljr_?r-H<5Z?y*);!E}<>60Z5=9s}HT+))lYn;P4g{cufHX1C}#F~sX zGlEJJNLfej+#^hSo#+l#OA|{;`lNhiD_bgE=jxF0tbX9(%a;x& zt4sKPWvo!F_-wYnCXd4*zm6s8kZthLp~1s@N%Wyf;OLkx!aPL`V6Xu2++cwzZrAW%RSzZHM?mv~*Hk{hgeRh(>VmO85Gs5fASqc{K;4YHrter9qE{M^An$ z{8;0?k<US0m`B_gNe&x4O@xqzzaVS;hn`AWRb08e`GhUMflpsk~r2Z)|2 zl0q|+JI*%QNnl3e4T9TeI?h%^A9j+C`^hM^I}O_)zFq?dmn+Y9hR%;g*X2XJRJQq^ zRlU9A?7BPD9I2bjjNJ2De8ktx>mdHnq@3tbAUXU!>-8g4{u46eR-3O&%|#yd8wCdg z7aRvA^s9ju9}NcK!Gzl-!0HD((J3MtR8J!j2=3 zreA>376f>O2=@z1IF?X63-c|M%Z0SuXC1u6Vpz_ma3Nij=U~GZ7nO2>y)e?N3Rs*z zBA-(D?FI203de%KnMzvYpVLBd=l?EXU0x!aQXqFup4WLZ6d1(41dK_Co=d0W6&N&O zl4Bw`;>2M=XhBXLInVp%1zHK4RD-V^kpomJm=x&w_>;Lsl|KuGr9EjpO*aw^g^=h= zpKmNUJEmbU&Zbwebxe8((UUYT_{Jdf;^cUY{AzM_(x;IeldG5VXso8+RqZ4s(h?!H z98}}5aSLl?bbRs$$~vZkF6w|igMr^O1tZp2N*66h?r_i}uNRHwkcXr{gS=jP2r(P6 z2#)Fy+6!U_$*cr+38aMC3OxJKKdV<*!}gG%MDb+6gS{T6$r_3qjcx@wW(nuDBL3cP zbaxAiZ1v!|z0*j<%25-Xi&%`9qo}g7c$Qf03KG{Xsv3xz)QY2=rDNzoqz>!~y&fdZc8GeQSVFYt!$E$zH5gRtvLLZoF6EIs_-g?hiJA7sWe zG}Il$6K8{g!7KZkv=c^9n4NIV420KEmu>&o4C<;Q+?X1FH#R)zF5Ue0B@9arlZoT_ zCj8cebpzm_?{LNN44ZDS1=xXT&OVdlSYLC~bCoq1-YBvoFuZgm6;upzTLP%bzBb|9 z3xs%m$(VuQzOQq^iN7e^ zLL?2wQpP~62H{%sEP*jGB_pB8ZYTn-lQTUZ3DpdJKZ6;U>>w3K_7)7JOOaYjzeBCd zmP!{Ox~--iDQN_~8>!VG#Vu4=#%ya$lp77ZZNG3GHHY^@5m=LZgXK$p|p;dNB+7=1-YU7aAALqM^3U*@mHMzEQwsG}lm_(W-IWi@E&V z?1k3B+0#=hf=^H93{GbY|Cl{pp3TE#VatWtRDlY@IlDWD8Y`>1qkR4(k1J`J3Wt=P z%~YCUH2Yt&oeADpNYP{{HxdKpl~i^mzmi=>E4{u>&k^y@pr{=KOP5LBz~7r%0KzE= zUT~Hp97rkGiv-RZbtayYc{E{IDct~)7apbFAO>rm_$&4iVb^`6Rd7fP;IO99kXos% zP)UdFVsQy0#;EiIW?!`|U{Cr1k%=TFD6wF|z%N?pm;(2JUZ&0J1(pnYkPgR1dsPuL z7~nm!E6`a2nrkr1!nar)Kwjx#7z_-I(}u8DmC>jZPuoQe?=RLQBhJQk2WQ5SwfG$o z@+>WMN2NyPa{8E7hS3o1bG$PySM0fHncL&eS*J5BpVdbO?Pd6J#ZdR9{p+}JyJC2H zl_|^WJH8rqu>MjAXj~JSRmM)ByKvZkiuE^BAJt!Gj)7G}Vi>Ribba&isC#JWd$`#> z+%*2XsVojSFq_{a+7{>|?80!{9Rjir$%#I$Gkj)O+^yT^Iks~%U8BdaYKGKTUY?bq zozPySY%h1r;JSRA8CQnrlQTA>fzy}VH*F33R>#@t_Jfj@TOj7dEgfaPRZlN;tc@wn_u7@Q4Q5-b-4ZFszP_} z?dlemB*WTys4Pm^e@W)JzvI%doI>l@Bw@t|#b_}qD==CJRQ@w^9+7w@Nkma1XrvIR zCJ5|^VVv(?-{0^f=MDd3W9mLyx}7{jiGSy`&<4OwWkHj>f%152wgm;KV5Pl~FcbSzA8C~U*7=d$s|!wf^NEK`G3cP` zokD_feYMyRf{Fhg;5fS{#1l5@PDB04zR&ygwTjiP z{)?B1S2M|QY#Z7d*=BpYrwlBkudyWQlacWD9-Cn>GeXiNTU`!>VX5e~luLPu`YJ@V z0t4ulo%Aa78Gk(}Xv)GAfJaWm-R1Vrr zl`k0MRUI&)lf*o)tSbadb|QP4ay1NjF%2&p%ATkk*kCs$3_c;GV|`&=j-p3)A}Luy zXe3w0o#|viceQXrcn8%-%U>#_1I?Bi4hh1tzi)(Ndo#&cXxq51iU}_hAhIqcMrD$b6=LK{de~ip|8MG%_rP3G!r^b6`Z*2=H(ar-*?CZak5$ET+p*wEq&V zab`?*SRPjFqBp8UJ1;wUg^Ou>m~Ai_l*K`%_;OSk$46~6(8D4AB;&;+Sh1n)cq|_< z{q}=$x}%UunRUG0?ZnfL0vUq;rY47B(7X=bd#CFIu{ zc8d)|nkj#v3Aju+rG3EFJ4sjvKbt)ptX;qP_^o$;`CV@<{XSHA_3_thYcJju7QgrS z@q_PQ7r-&iki7on3%m90*I!*f)1hbo{pfp-xX-_PezX7WO(k4+ip zcD=9Oh_K#SK0N#_@+(o``#U@LRSay1{5AvV9aj>(L?rameOZAwHr{>#|5dd4VtPi) zUK#P!RHA+ci~);;acDFYCzuAO0N+^`53hG59P$(B-)v0VkMv{1OR#(ugZ^1s`lj{P zgV|4?xs)j_Kl_1O(X!2SoeXG|&;8~$sGd(}xdBt$K*-{1=0Vtr+wu0dB&&A5U9nT( zZ66P?ffk_G7jU`~;yc4;zxVAcxKYgz6TNFLaFYeYyathRvR0IM%88}!A`HU|tNpuACjOOk-Y6ApRb4{1pFg`77A8;63#$HQgT7Cz_M$QV z`_V$d=gfJg4CsrU6HQWm@?w~XDdagxoegTK7>$F>luN$42yX1e&0uY^reQKdLq+_+hOpoVxLD+eLaf|3@(BE|*sUTS6 zXpw1+w_BmlP-aDvP5KF2rTLPqy@t7VW{DbLoJizvl$ta!)LN=2Y&9dh;4k@CtHz6! zMY&ok)k>=RHGaGrDKzrvuzoBw37ce)tUWJ5(2Wv4B_qMRMu1ndv=Z7+gJ#2G#?!NT zgJA$Que7YJrqX$AMtSl#KEXAzn_=^kBDPx~}1fGm&T6 z&(l-XQ_CwDf)%{6qJ=N1mG(EQ^k?+}6OFZiKH5#6Pfk(}PpM_Vu>=?!M&kwsPYI)B zri{=TTs0V1Z$s)tlWW+tk>N*=m_IKsD;dk4uYAfk@Pr!(6S;vBdM2Ed@G2I*1d{EM zSTwvH+ul{TR}u4fGMun-9V$7RwoB!?aYp{SfuPPL8n(*3I)uVL^}yL<1D zSgXuYU7)=Q`|TR(?J%A0j?2VA8?+luE)!s>WXmprl#~yHukE^hAcoJ~Oy+63qp`HH z@^ak15)4(^P|vPETYFvqg6F5pAAbD&KeNVk|M=(M8}BW=|EIOJkKetvN49_QdE&#x z*OekoXVIm{pRe_v{q6CGfBzDo{^Box{U2Y~_R?mahRv5lb6_$iF`*!9o`i3?N7b{R-EVbV4!ojBC1+zb@Df}laP5NI!?7hZ^CVTIZ$do^>l|J1(E z^ZufpVOd(5!{?`|r{{a#_c{E1>IG18c=p5k5C2-~q6T8`tauUmD)`~?SO~3&8gl;d z1RW8h(P(JYR>RRy)1b#0Sl2ZSrmdm>cx(`UtcziN5(P?{{aiIAhYHO-^4!OWoHR_B ztKgnWu+#vocj!Z^_VfWlusD3~;V(g>|9IhPX>V@>ag)?PFK)023GKkQIfm9kh6nTs z(}RRf@WvZET6eNuvmU88vh66_p=xPnrg*V1b%9D2mKT)=$uotLtKlsDMq# zi|o;`%NZ+xm<322(qhlr&aWKQYHBW0G*enxV<=86N5z(46||`te@hr9+4Fo zdO+Si4&+KhNChw^){kqC^Xzrhxqy~W=!-LhXZb91Sgp3N-nqXeV7o~@v(>VgdgXw} zvt_xwK|j~R&XxnXX}KI)dE~G#WG(z^Ti6 zMNlob9OTK!ghsxWK<_41(M=W|K?jECj$v&IIhu%wJ}$eCX;TU|Gs2pYi4{WfGn207 zGMQr+GB^Z-1&n8BW-xIk51v6hmN4I@kY)ki8MGi}nk*t@8YNP&=Hx~IwaG+E)CQ+m zi$o0;X)a=;2ZsW>@i+h(HeehT+zrfO1T9EANDbigl{cG9&c+8R4_GiZz=1*1!%9MV zKf+#7pOlIZg!l$LDdukgXrZ>kOgae)8^-20z;dH-{3pWk4&D*E7X%$SUnX5f%2fi* zgb3S696@#^cq{Z3Z4L5g$K#pA;#Po}9$_Rq$K}ou_0T))8Z0F|9&UR9)!Yut(*n0U z7)#SaJjwWIV75ZC0Q$sc3*u*Q$Z~GJa>_RdFje*OK--`*=(U^0)!oCAar|G z0*w_GLOLkEisAqYf&KLUB5JbkALmi32hwfpZMa4WHe3kCH-k7-lt~1MqD_ zrIoXDom?cFTi&f>5Dl>v$_)gVv%8(_Zo}@vw6xsq(u=g*!LS(|7z{X9iFF}$N8eJpz_e0zJh zg3a)DNM_>-CP@ae>7 z!gcT6^F4g@)u=k0{cdt^>#rwrJ z7L^B^r~217W-CnJud1KrUQHP=CDG)*+6RmzN_HWE1=niTXIn>mFE$o8P`H5o?}Lp$ zEsm{7i>k?j?3rZ^*c7v);g4^yPVw1{zl!2|(;xY_A09kjfz~nlVN3^RJ@|2OD@8^C zjZFspi2_SySl1Td+sxlE1Q@$uYOyXHcei$4vk!PWzoHo#3Xy5bqozq^(>h`Wxal&J z$ON;J76_@l$OKuMId3}8K`h>Q+7MwNt;(R&ERq_hZ?ugIc|8Bt*|pwihmfAnIrFqx z*`~+Dl~+8tfPfzBfJ^x4PhO0IyPj?Sdu{rm@Dg<5JZ%=aZ(#oIP`ElXmLCsWJaEHv?&HMouMsA;hpK33k&s>_AVFg;Xp(V$neCqMnO2g)Ib3{tAS3(Z3XGmR*4FkPzNuz_2R> zylrL>jTMsnF7_@U`ngPZl0b2W+uzyQ=FB_`f#q=uQ5$6}d*|oM$r-`eW-^sLLh*me0y*63HvW<*1O=A`TZKUHLuV!ETtV?+4hhnyxopRNZ)c+wfNxGqf3uzKijd+QW0bR5m1cFj zUAYxz3uV(Tg0Nx&&oJL+G4&PF*A5 zdBy5OT#Y-rceRMpBVGO){(GCk=Nr~L9zuVCRzi6+D&O78yd2ex5-Oc0PgNE=U2C(N z!BiCz4_TvZL|2BfA}0eQ)iw(hIAbMV^$zIjRSs<$=n3(~G1Fcd&ytbGLF{T{V9bw) z3PXB=^DC;N%IlaJFQiAgm{}C}RIRLIXD(R<+3+30A9X z;WjteY1TfFE}N~gUJhJOrpb%j#<2uhm7L$l^aCWmpKsTC?cVr8A`exVUQ8I7xj}Yw zZP0%s0PF>UwaQiyoYsL~o=Cky)YYcfLL7#x1(s`ht(M>(KsnSh1->A#2-yI}X3DN# zbxe(Nq!v@0k1=Ytgv@R-@KW2394#TigmUC-5XV~z<}6}5Rv|SQts__#_%1i$j3RIc zXO7FqF2+K;Tp0#lHC?V57?KcrB`mrucs%1m`iAQl;BRwgma$mP5ENSAzW8T0gNBCL zxx-W@gEC-&Qs}Y-mgiFg;lOi;a$oMvr{;J06BmVyw)3$^?6om|69fYAhBqU`hNIk}Gx!3cE$QAvMiV zW5E-=b4N3?P_p0=nD$KG(LJv)-4aLB4Ujh9Anq2?vr!t)KucMOf^M4q*rE z@LQJuRm%xjW*ZVHv3idD+6~MpGt9qUMA~}2H2u06740_rE~==$QH1|QXn*vE&ruF$jUp3Djn7+pc5ajIlL#!AQrF zUvxG)3cEstJNwyAL&&f&z;Nfk6{o2c{ILaaSxq}X1jGbcz?0k7xNbY+fk?{7S zyrGMJLICZ5*}A%yw(>M=OpHmytT9ctL=xO2&4-)lfKIA0g;d>XVV0bqv zU#-oeH|vd15JAwxQiVXh$dwmEsZgQSGFP3e{ipVQp7(dA?aUU(>NzKgBcacE-uL-{ zcDlOH3`${@xo9hghTrI+@Z(J*cq&wcG#5|>c*x*Lfnz{ml(MSmf;uHW=dBx?hX(Y^BrGxJV z3kP>Wb-#rKdWsUPyIMg=XYgH(h-Nq8LkhLH0|xcQ`#%Lt4ZC|FJ;Zp&@538A;1`O_ zJ5cJhxRvqCo82vs_+|Qopt}(~Pm$j`g6Qi8bisn@L{d4{H#ep_p0W9zgW4_2ffO~@ z#0|>?iM^%tR=^2EWhJhFDFGr4vBHd2P?#8MIhJ3lkaXl5zh$L$W6MRXMRl~UY4g~o zQn$5Erl{&EqZ&@D>X}*4@_VJvM_$WPuDPzU%4!?7ke$`E^c7T@tm-Z>d5ehZIEYol z)jTq5T}v}K&5kzDDTw0;&}al3zH%L@mBMKSi5o!% zWq6?3!UxL+1tf(Ux!jODdyrn~VJ8DvuJGlupzKKy+uh?JvL=~2*#ObiR1RQrh>#vU z23cM@<^UEz>A&h2F9X+8hHZt%8G+Z3;Avy27z)AK3k{YB3t+@-c(C_{>36hT_6X1- zJqyO)5vZOSL@8LBF>H8bbR;tp%LpSDkVOgy5H*&}Bu6!a5`9P$J28!mP89z$kx3R6 zafJXUu=K_9H^Een;zS?D)k(lK0-}>Z-&h~0FxJ3>6NsIRX_gg=7ofoEdxdXf453VT zhj5lTS2#F02%m5ap;%t;uvf!45)^1{_iZCqqmRNYp|8SXUkMyz*~`*j6er>9A@mNS zXb>%j2znmI)EZbkq=gH@Zb_8~u`c$~_dE0i$lV9~FDBPOU4(aFUA#?T9v=FkE7WNC zPN00I-U`hfs9FfRIGl0+g(Qj777?}8P>ZEU)UG%1$?v~xfjrcq^TSfI|FkA z#AYAymw8z7um!#Q7w(H2{zwi%SKJDRY2-EO(8#*-FJtN)hzJgc1!)iEpCvg6R7UgB zp)lkytiX%l$qS&rkwujH`g6I(uyEl>)t_3<3h2UzR81`&=GcHFjJ6`DP=6$tnyM~V zvnlLymFfzcOjXx-89w=|%V${dW-G1PGmNft%!8Ec1d6kVmHjp5WMo@t3XVo|g|(;# zVHB#6G()%?WgQZS$A!Y?iP$=&{>XYzM#gEh~5O7hESgo!VU|TM*8A;B1hwLvP_xDsb@{dcUxKB3P z17o)B?LGbJZ2I!5bjNpouEymznE9-o(o-(PJH&9x0ux90*Sd0gk(K&|w{ zM*Ftc{xUI|d6M#RI`@9&s@C54&aSF2Gjtq1+@um-j? z8q35%s{vTsfL|C42KhD2SU%eVzy}9^xqJQTL#-NoI0YFNOusBfy8e*EX*M*_3e1$s zZ%+|4gQ#a?saGVYbpnI z?)*88W6BXlJIH($TAla4wy8CWJ2u-qiUBc1Hb@dDvqYjK+&h#eVfY+xn&Kj^IgjFw zn#l}u)!u`zRm_z(PfkmclHxR+K_;n#N@m@mrj5VHto)+PR2B z@wl>Zc0A;rQU}XyVULdTanrX8z$QeeEe&5b8JFv-o{Fyge(Y*7NFoa%SpI zn6*4z^MxWP%ae3Tu7hV4ZXGrA&coEdWqi*d!;IKGvYPzWQuDQ&tNT2^ux7y>a>JpE zNpuk1MD<|(m>McMyW~ScM~DMzwg!8U<*cPg1W|BcUxVKYNc*6l3ZBR_9phTz!!FF2 zX+{bK>vb12&OVHn8=+qzcg8|k=r!4Ox6oL~vKpQdMm?jEkdYrAtc8VVAA3fFY#apL zT{=b(v?n-PW(fnf!=%5o_`(QWMlc69yd#<8r6Q)vSO#+ojEQye6Izc@e1v5%s*Q@; z#E{HP^vUOu32g&TAd@migRcNCtAQs_aD-xDL{9bVQ^uP;q#o--QdHgW5s}WfKt7QG}1%8*;pobPZoMYZb3f;ki!ze<^(z#TH!8V$$>{o?9 z3)Bg=L#Gv8%T@|%Jt_zr&H@u#mFy;(5}=pHq83yZ@Vh@*VW{&omcN3*s1@84JQngR zfQ(3v*0iwZX*u3v9TJOwA$JDxZE?gLRhd==e4NF=cycr~$k8=GeXFuIS;eLr7>zhe zz%lUn4@p>G*>-&ZVEMvc9k_Jgxhy4nJFES>Kc4GFr$7Do|2|e1$@7mp^Ip3%ch9cb zJG~$7-D?|wemgVid-T$_`^W6|jJLDu`nY>;t2fx_n?Zv8V{iU+TCz7b&$biz1|p{h6qcL7Bu)N z`v<4~sXc^*-iOd*sR3AUlUnJ&p8CV`mX2_~6JVB1IHIX=5#D?H$%1ivN^5{)2kv1n z!}H6hH%t_zV?Z*ZEcyJ+jq6{mf|U&efHPzBgL@^6Re>@`&Gb6NyJ=3LAw?2?3ZXH9 z2CGiB)>>(^o8>`+FkA_z^S3Nbv`}@F;v*5uAZ^-eQnr+~jJjBni-m+R8Lu0+k=ztm z#-D68<=zI`Ce+z;sEiqR-igVu3>mg8rJ;NkdW}e7H3`$o8~?6_J#JiuSSq@13VmPa zkGZZZ+|MM{QeTtGzw(+TX|hA`TZmKR1%Gkgk(jOX{|8z$BTe_?TSevOcPwA*uFgre#?eZFe1uX3+0oaEZb!gkuTg)o?5d z!8m<}qbY+J4q&dp?8uTQ0~ZpKIQUU6kD&Uf%&G-MaePAaU=j2eok)VVAjK0IdXtI_ zdQOfeh5k;Ad=fG&-zJd7kz^Q_oFnl?9wpc<6R_lRGywlQ=}lx9L^;v7gOf=CW9);` zh$M#-Z2N`B7o|vo#z>;{4$8HF;TU_81a>C`QxniX@4yBuz?wuSLu^|xb{nZ2a0f$Y z<=w{W_f>K*Hq7j+L7?yd*t*)6w(>OUyNS|lG`ZP9Q6zD4W7lX|GgoUOgeJ2sogvXh zMW;JUG7)1;oM@oJFn$pVLqV`Xrb58^Ap5}&#mPVmRm*(Z`M>r#=lMn3-4&W9_vTGn za&n&Myg)?-W3U&*cbGwyjD_xDh$IcX!=T7u%U+?)0@HFI1YixqE)1a+9KnF-eUM^> z;xU|?CGYjF56`YM8VfsM1dF<8`W;v-u<#cWdc<-NW(8E++tqs1fsL@$*G{M zjNAx?tVkcb1_f{hfh~q>2(t}^)~uXmhswx*mV4!jA=DCvLbiP3K_ZPxq=<#SB0B;% za3oR`lrGxGxk$N~ONNdwY-T}6+zC5jAD1J^BB0vV88!C5b|{du6FJlz*ptF>SwDzA zV7ZZ~A)MJRN5F8I#S!367#&5)msk!X(<(BVjHhfi1J9-A6l*8x`$Z`dLOGZSjhg`G zcwFljc9HZ<2NT08VE_gaPbOXhfm5lXoKM0n4F7VVhVH@(LFptK5ffm(^1kdEBPr#9 zp91j5b7WkeZN4SuT|IlY`Rt#+I8!s{iMIHbGT{2^O!HIe^v6Fp=|JP)QKK>QrQCS^ z_-cEnZqlu;+rHj@wDprS`KO!f-gqOuKGW+z)NtrK30C9j*iHHrIxo3dUA_t|U$qQK z!hzp?J?dQc{*<}ut>VDZ@>@NzXH37Ee#P|3j2S;?GCGM?WUgfD!_&=7sqWowUN0Y0 zDgEZpM~+inuI{0TfvmS=3X!ywFk2~Qvn55{ib;jmpGqdaGgLhih@}fjZAUC#fc*L4 zcO<+IpD+)ab|e5a+K?b3#Gu(n1hz47hUD4mTZ81Et|K%6TP*X0IvTkgXalAQYvr@M z?%$O=HP+{MQs@V!pAZXR0Q60Mdv)~8nHbsAlthkW35?w6s(qK3vq9dPRY}u`!69yB zK`xnnffX*Tz%7Zf;tx%~3qmI=W?a01=`db|X;jGMPzYAZ5}|I~7<*fuU^6A=>>A+z z%A{YYe9F*ryw!>>e(yLj=`CKu=*P4iQS(5^ipLGkDksg3>kd1cWnflCx%|j2y*E#* zuTmNL=xvP1w*+~EYNfuFbCWl3n8>ZHnxZR;?G#~!I;p`L=)i2*BUs!8E!84=89bi* zGz%@dprjg5p4(ZN2iCGap&;zGqks&{Ke|we^qQ5wP&fmL=jAb{g0Y+j5^T9BnndCTn5{v~;q9{2U!gyJA z&p{5GqcP@TK{OpZK-M$qE-p@jf}^pMA7jz}QIrP{ffNtLMn}V#C!_LrCe#ihkaPAv<(*D3Qj1aUE4h7fuYQ)&iN@_OlWCM7!>B$27hZ!Fn%Ylzj}V0Awp?r7%%&s-Mh_}tC#@VWL)1L` ze8>1uD$3_p$dY44`77xbq8kYnEsUN+If2`xrgd1v*%0d&LJ~!QP8n zIr377aiC_`*wj`2Iwp>8q_TZ_Za&>z8eB51)UyY4e}GnO>^5R<}k7eV$I#pWbsCJ4+2GbN2Xc zbmm-TRiMzp^!B?R!IoKbm% zyp3R>YfQ3vyG}7l554ITIr2e-(gk_Ncj4&(NZptsI^!jRR`P~6Y4%T zV(3;oA_mnaPegyk@$9YPn9YJhZ!0aU(fEX>d8lNJM4!C-)yC~8;3GZTMCGtsfY;@5 zp*rh=eZb7bLdzi5z0s&(ax4fu1q((3777~>zX7(4dW5LJZ#38w zJK)+E*gA-F!eC?lXkHl8G-$e$AaG{y@8HivWBvQ6KN{>GJ{VQ;mO!cia1cf;z20x+8Vtc$2zz_R+FUUHc67;iH5Z+~LVjP%KezyGCtEy_ zfyJIe7c|iQmvu;J7lajIC$pz*Jq)t0a4M&;#dg zm2pOB%*BP&?#}H({R|fp`Lf&-u^ynz@_74V5~)~;Vi_A}Xs{EtR2f6*aw3`H7Xt)k z;)D%{^JJnt_1_HmlVXHMFDAgv`ru#B>y4eA#%Q|X4EvWq07|dY+vgwQZzl6;XRvE? z`;q_IS;PNTJyUng)PNrRMi-({G&mSKri6cbXaJ{?_vs4pJr^CAy9}j*J)BDJc*;&|+ow zNQ)t|x=MG$9{k4tqV8=QXlC{*Z+cUuQhj}?u7OzC`7(@>yI!>b^VWzVz7_3dz;Wkj zwLgCL7s#wYbyvP10R|C%!sU5 zcIlLe5jDIg%Eh2sw5r#i38ZV>q-kW}5c+`@FMNI*5N*;qaQ%9IdTIE`;g)y8Bpp{& z3&mr=4UDH3jEB~g4VaDr-DR@ecH|YqDzoZ9QghPAh6YYBqJqr0mCMX~(J!l>q>1s0 z_9C$(i%OUlX}(X zJn#E_AbYZ<09HV{Bg7a`4Oj62WYMhvl~$B$3C$HehT^J|U~eaF zF9fv%c^61`0^Iu+i&`+3CNd*~qgc#Ui?AhWMOc$c#RGv|PNYkPj`9HGhn6lCa!A9{ z-zb1aDy0zEToH(hR1P)(gVH7eu>~Y^=-3krp6(S<$FLWNWjHQaT$I1h(81u>^}RRH zNCRX`v?A&L8R5NXIubsN@Q!2&s^g zry?pqPM82Jf7~2EbM~w@#4|QWHGmDU2f3nlyVDV9(RakUU%_S{3kih@ z``&siDHg=fVUNoZk)O~)Lty1$)U(Is6I2G|qV6cnA_f6wUpvBk{IG)_-!MjUZPuUq zkO0J7EEjWtoY{zAt1p7kt9F)&eL`ei?QBG@TI;$5dXZ3xhTzZLb~l5f2Cp}hil7`A zVH@&cIBV=1sWk>f?|ZYysa^z)N12FVuV8o=6xQpFt_k*bQ{H_83*Z{!u-M6vF<1-S zLox?mWxRO=aikEioMGxRK0py~6mJE7dj@Q{h<(myP?%7E#e%@7GU&>63m7Ta7hyZf zqls`aTH9WXLJ?g@$`$2QdCr@6YCA9^ffVBtP}}@MwAUA4rVSXHtbFtpEJ!RX>@(;i z8tvEVd#cr={Ve%6M&$kDOs%H_fQRKjdK6dJPT${su_ZKiSh5|JE*~`xA3cH=dH9dz zkH1?QY#N9EcK2v}aj7~61HQODJ#;DQmSEy|NtpAtK>FRmk5l9ER#3>a?UU7~VAd=} zS2rGQY`hl$9&eWSZC{K_=Vnxg!0_p(pSLc`uBD5=PY)ZL=P#$0PReEwG!b`GZGJ5q zQrQ$gH%!kjRazfy2Hu_77B^3}9^E=DKlx~j?(UY8k54yM3YMA1p~lcn^}K2Mk#@2C zwOmNe^3KiB_PalW^2Q#la0C2+tw$?&V%HV!USCm;;Mg5{kdOtvatQq)vNj-j;HZb; zGcJZevz`REn5w1FMX!7WAdOK_*!9af%NV|~2(Zd$f2_3V|Ng(o^HNeF} zcU?)9RY3Grl_YI0ekTkR9ZhOjY!(MoFg0uCFB6Dy!uq7tn7d&i-DUs>ZA{Qv3jl+3 zo53IE_!z>eNm8`Jbu$ZkRz+Kzo+5rv>~G~}VfM+dBW81G-n3T6s<`Pd>f1e;!xWpU zEQVPtyjEXbe#hqXh|l3*1XU1gSr6b7od}x416Qv{1IU8X29Xi{R)a{(;gGZJ2SS2i zA%c?1BWzh?gRg_291OgLQU?+))*abVc0?i#H!#8}9n8OKso+XbXGT-nvF;V3jS)0v z(K*eb9R!5xKKxIhqp{==T(^U8X!)>u03lY@j)`b zI@c-4LG}Qr-*h0vDi!r2`hwrc%T6I#OzTLVOc&z?NRy(iF=8J%^3`~ zkPwdW4QBwBqku!Xf1zo1!V}zTwUGPlbog3!^bUHQNJ%rRlHfN|2Zi!_*n@-(Fmac+ z_C6-gV>F!tJgdlCp}YTrCOV91vv6A~MBz}1Aio~PNNe7GFkkOJ_PLlBchL*H){Q`F zC0L#6dfVA9H@w{Q3fzW~AMK6ohr3>cTL~B5Pj&Y**)Hg81iuG)lzr49ea1Dyll#~S zXAQa7@UHPkSJ2joM5A8AE0^_AMkvfTh5fH^;9j)XH4uQ+tD$KDg@8hlU*Q_0LDm+~ z4UA+;c##kt$t^CDsvx-9;VyU^Dy&6}pBEs0uAz~z7G01J*-2=|OF|xvF>{^AD0t4( z_R9%#t#*um5mRotN2s#{0`f0Fw$S*xA>X2Aj}W%&Q97S6Z+`E=vy$KP~xAzos`PMqm{attx}fAWAihR*ei+E#cXf6ckw>FD*7UzYK0)de=Cy{UV>`mM+Zv z$*ZKjoJCV>Wi=zIY6hej(vpNR=5S%lz4&hB&QB}!`3lb7h~2sVfbD~%zjxR-yYk?A z%nX8#2?k$3L=-FTIK$Li;VzSLt6qBZu$A$-loOZFOdA%)R%v_+{7!gV!0-c?Py zD)myGLQI>pX3SJ!t8Mab^Qt)!pPdlrzc%TMQi^YAubNh{748Mh^{jOt(KNd#%s1wC zS1HkepDMkJKn!f%<^0;Z)tKndUMrZ!cUm{)TPj9tT>!W(|A_)pF&4&j+3pDhRgJHZ zo0hQMfCsxgr$Y-mVgJ;S?i^r52Q<(@M=&ku={R`k(9lT;EItT0;Ut1S3+d4htJMHy zRaF>{v0g?OA+x8kK8Bwuz(){;git+e*z9)D1`PJxVeJt(F!DS!@M3!amLmwTa6!6* zwqTStU`Cxz=TssG@}jZ+)dX>K>0~L*ItJ7)bPE3#z)b^yA<}{*OGhN7;4)^=N$RqS z$cHYLSU?Dcb5id>kmXL26eA3qyq9L{mHU*EEZIwU-bY+^w3ey!OdJcghyU~U;GZ?U- zP>}qdoGwooJ5S%IKe%!ar-W>fIHRY-VSgKN&uQP>F`CnGu9J{T@IZ%Z+R016WtBcZ?I^clXRFeYFiX$12u&VG;Pt(KFd?6i}=PF&^mjl}qdOJ{?Ru zs7PYXVHCC|IDB`&c=N}#I#3(I8$!1;0R3n`!+@-4Hec%>Ljxv9F+Ud|KF${J4S%

AIo}_;GY{LDv9!fbW2}dB@426IkL3)Y zRlY%1`W5bgJ?c|hA<#u&u|Hwvkb4&vV_VfHFoA5kXnQm3P!I1#<=`2E~%82@{5dYF?xla`nccdUQ#>g z@TaScm1tz$2v@PIsHWHJOX{UUE#0h!)gKrINd7`yPcyb`Y_$pRz?9m*M2o)UPlI1w zyGmulbE{T|B@Q<9i}NO3aL86Sz-APzom z++@`X)$NdYQKXnLQ9d#uBZalE%W0oS`4O^MX7dmW7@(2nd5iPN0BrzTX<`9`iLhv3 zvgEySPs|EnMSB)AOtprMwzKhwMlVWOqW}OP07*naRF;D4EMxRcVzj}%V!a_M8AOy} znzMvL!{LHUiR`n;Z?+;h@NH!%NT=cD`CetS)BIDb1ZqVc-n+%S@IHkSx$SY@cm`1}c<>176Wy zbR6O6*K7L;h)N&&7`#~Lirc0C4G@GSk~hS?qC9E{Mc) zz?UIY%jQW`X4mkk)MrI564%85i_!NP1WN}d(F<8*%Y-Jwo zXBSK`N6#j)z7%3Rnu3w9qVzfe;E=BrLk@tl%=RI$v8-mhM+6uD$%}c0qCw!Wj$(k# zUU7D@;S$56R=(iQqqNXLOU!~o&fUbJS`oRz&{@7V4Ixtnn54tAzaJA3emlB9igLmj zE0Ri{eXBTFG0!n9g5O3F%?gR~?z0s*nv0^>0rCtemiXFSY&RDx#iD>-MWfM^5F9c` z&W_kGoIEq4g-4;2>E&1mB@4NjXxSPK#4$ipc1Mtq?*80;@$A{13Lc;R{KK<%JRI&9|Mld?4)9u_N?*(rgSQjsou7nirQ{}70Z0LRc)>nXZrc}xt?x5-b^FoJfLx; zuPO;?d|63oR1ek%*vZcOr#KDXyVc`(I&|ao^3I2ROG`OJIbV73vY>Nx(M>xJT04eH}TarJ8)imqc&U6vk@0rY5${e!qz!D@N7^l99*7 z#6l?+#wQWgaIM{}iC?Yu`~6Pd2p_k5+g+Wj*t;ETDx`JYFE*W z#Hz*?K9Tj*=; zib$ngGl3n%XBZK$tIaU3fYtI^F|X>U+UA<;QuI3CdR=_#xu|tqFJHPp_G<>SQlUg1 z`3nZ1(|?`Y@*AW0no6Ph4gU3becOto60@^{^P+jXIV)d1P4gHc+u6uqs<_0%4k7l6 zb*~+&OQF4q3SZ)_U|=DyCRc=KNDyAsI#{yuYz(GxSY)bHDrKB3fgm|=IWoiEvU|{p zob(|dQ-)nfBB(@KS+W%(Iz)EO7NDO+gK-;tXmK5u%OOialEXhK*7>@hIF7I`;3LJ`^SbjTrDLw*z4A?4ffjb7T<7vgyIEg zW5c@@^orJMUJ^1;%rN{J<7h7w8ZE(Y9|F*BpBP{phsYw#aJNWlVO{KF5yNNDq=!Fe zz|{z#wQ$QP63v4o;5kq{3}gF+&A##^5;s&W1MiM9;(2)*?DH+!zKp1E85M!fV27Mp z4BP;%8+{CBr~QcWX8<@vcCAojvL}Bl4%1{)!HZr$xvLKxpQqnRT9CM^gja zf!Be2o;6hX{>IoW${1q!KTOYViapKLV;E-R(TcKt?AhGRR~KT zcv(?E|6d-3xeqHC&3sj(eb+b@GLX;tKUn7c|MH~sXU`_k0U!eWwtxA zfJgfLDD=4XU9?|o_jn4&%Jl6`}ptA-rZQ0pFX{Fdt~l!A4LwfzWIIZ$rE{x z*FP*Y>pSoFF81yorSt0OmnvLWVQ3wAvuE`tY94Mpco?_xJq`T|G0Z+Fo64Tk+Ys*ub z+aJ&6slESnIg>tL&OG;Y^L+I|%{H!e{DUB|vXxZIWjE(G ztrti)hda^D;@W)A>CqqgYu(gG{oGodd-{uxZR(PNd8U4fxSx%@Je7}ptGM!@7~DyV zqi((}uFQNJ@5mF1kC# z$ep=CmWJks#Q|H*hfcebJ%lJB1UV9`+6r6O%>YIsfn_dNoZwN}okvbHItaM}L@dh% zsg?JQpi$6;gCjAqENT$xt)K{rv@B6nl>fTS=vSbvMPsllYd0U^h&b-D*v%X>J1N;> zek0fjV^M4&`H}%F0I$%7ghO9TIdNEyl%0pJBv4qcY%*)%b{B_5i7YCCv!cO~BpxL# zL{P>P=x)&B7F+^Hk_U-0GR=u(JeU$cEMkp>6?j-kK#NRk$wVrm5jh#eFj|X)g_Xk9 z(l84aa0u*GC56MtUwKnrFC^R7fbe=7;*}e2n-)BP0^@*KT(3J|OL;ZT%K@}_T5U^% z?Zv@xaLXp17}AVRK_sTpsSp4KtAPPC$_ABf&3I{GaqYWh`w8-kF|+8oFEAWvpzqhs z%`d@|&{jw|s8}`-v3!cMu?1DlECR=Y^wsyQOTrEqyew5f2w`^f7MP1+Tru4c%ZsLt zo2-i#9hTQ;cC+&)@TKx1ZOB;>e{1&4+mW}b*hPQE3ICU^tNm#zPoq*=rZ0lDr45Ug zK|p$2XwltLu&r9{h&W?fP$6K(1h#CN))pu#kln__gq1}|q;aU3X6Piu$v|XDNnj&r zBxEwinV5-*6F-S=vhn}e=RCh#X3TCe(B6An^$X{o=Q%IvKr(U}gABoH^fX}Ztj6^0 z8RpLfvQS+W^SwVd#G;J>zF-)DxfK|GBj~dbjir)IrpHD}OK_{@q8JqnNp%oKn;^up z_S4lwd5PN^HSG4)uoSuI0_mzVNh0VZ;>cTFNU%39p-U!+sKF)8IxG-HU$DBzP1sr`yDoqAbZm53vhfT z7QRHHr$MI!%ze4i0nbF~62hPTW;wo6!g|=shU6tH{r!G_8*)N?lJo!hfV=P9xN&3R z4u9?JOiUcx-k#Vw|LLitmo6Q^J^EScf86}zxt>k82!fVBK{$UAsU>;}IpKLP4_eeTu(fHm&4!;umXD-acVADODaGIxDu2w>L#YMnZipBol?n)5i zs~m#GMS_h4z~H)oR*mKvkXMZ^28@HyPpB~&)$(1ds4Ub9=*7BNOANR}jGqfJSbIOX zA&H6cQSoeV6rFD%20Y~s&CM0~AJbn^KrggSOpVv75`=Pn>miGKvghn1{U`gt z;~pw0WMw!D^)shQ(|Z?y;1?aGu%faIg7BGFd4lJM5{Br%LRNFai2n1nbH5Kf6$3w z2ZbjbR)#Tc)(;T24`eWaCLkW*y>Ev3u9JAK0!v{;ZFtH+d&{seMgfu&(r2z@P}=D& zcD=)?bl5$_fgPwos^v&Z@y+4TJMViO!j;=%iT^or&TI3d;|DGdL_i68kJfCH-=i2V3H0* zh%cCWRcL0Y>(x9q5k=KPb)`Z}gCtD95uk9Lh}oc{b^QqLAmlV@xNDI3uXK&$DW%6& zb{R?R5tcM`$|OfqO8)*j$e_6dc*#1AV;UbUNdEqa50P0Cv{zuj1a}d$Z^>_MlA3%G zEQ)=jz9tDd91?Ob%%c&oVn5QNQEkLubYKaMN8YC45dvO3ptTwyA`A;sn|Tyz(3~pC zo?to&`%;_F$6djJYn&$C1j7-+wGc;n4g2Rds};&E@L}e?P(7m^7`CV-R4Af4*y?Ng zI0>s@243FYzH{T>uU@`<`RWz@dG#wjUcY|*^Dj?+`S9WG+xNSRZ=$=)@7}#xezSc1 z$n)nrJKH<^;{`3WKw!%RKhB^3^b!I0(IY&6g))iIsb%@lOv|B}!*5Q^)gwrds6tXU z0W*xoS+NXf5&LV)DCZT7lNtYPpN;{|Q$5(m` zPb{|0&(E%B4Lutcn>%aCHS5x$%`X!xLfS1ybJdH;u(^7nzdrdpk+j7oS3AiRYDKsIb8dMnhR9Fft^qp#Ke~HvSDEkpnR-Pi!*sDYgA?DG?zh~ikRCDcu+bFpOT`J*S>)5Fhc~2a?O> zA`VP!wt;9Zrqgy#cqWc4ItUT8fgBE`QexvPJCUjgj|qUQQ!XLDLMc+JHieFcYG%r* z6dHf&P&Efrf+p)yV_?2IrnvL;-oI7B?Mu*FTg&~wCEO2;fM^4UXBblR216C3&bSC> zr7BLxfS_t3(Sp~KlT2VY`7&EkrW$zdgC}m?3Lazh?<})SpV;mk`4)+nEH}<+Z z=(xsMk%b`3gCh0{dMmo94@C|D_|{f=7R}haPZ7q@Sy9}nS96E7B8&;NTFreO!jS}4 z%oe0#qQOYlP-!`KL&edPkZOV4D%4soStwSUijlX6@*~Ki@q35GS90VALa}-wd*)<5 zBN11Gb8u#^k!ybIOwd=+FQ&Q(&KiwUT`wai!7#{g#3b5}q3&Y9Bq|IEHHOWEsaPP>XQF2?V&zU?|1`+(DAvZr zDUn_YlkF&?I?#jUCk{;jNJLn&E)g{Pr>95F5l)~IT4g`yHU}_JCM0eP_`Kc#QlOCq zjaN`p1)r9Y8BSjUc7ei4W9&F^MEynX*Z9@^anWWQS` zQ0P8&?D@{o?ep6c6MvW>tlv*REroXn-O0b42XOB{b?Op81L4V)E!{009gU5LI%W>d zG#);2_~glx+)M-UPMjC9vN;Io9sF(iTaaJTp?DIiXcYSjwN^5#N}Mq~CAypI`sBdp zo6(KfCl!hQ#X<=KCs2ms9|dxRxQh_eXE5O8f7!bJpC<1-e*H$;BBWo|#w%+lZS5DJ z1#_i^7PQFb`Lz#dWZt4ldu^zNA{5PH3^6eQz1v8%F>2O?Uee82ayM7xBFEijbCUhP7VJ=P&8eavbG;9!40#q~GlbF@5@G$znh72L zF%dw=)_Z$*nvhrq{hu-1J7Isym$9{+rg30LXllXei2i}BU$*8@@xUdJUU;# zI8Y8t>njz%w067cXsBY(JRJDw*lZ!+cW5$4tiMuQmx{@WSOTtJsh;F07v0N=SZwcE zaejU@Q1R!+#}viHM$_tod*#^0rGj57g`t0*9Y~d=j1<;RSo6|y)3J@ork=3>17R{< z9b_Qo$`i+R&>Pp9ztA)03;UN%owJFBi2&B{c|=*$55xXkdSYSaqM;&{LL)WIt!o!e zCHqclv~1Vq>f(AHhirF}tw~59=qeR#^F-TV2Syf0K-2=ac^Gwr0jQusa)ZGcLg$o|h^;3SigE;2Flh4t zq*-GX;(;@)zeuQb+Cnon90vim1u=~dIU8|;gX@!s#}Vv+1wyw(0N#xaT-*yr9BJ6oXu1R5 z%LyGw-DqJWFx1XKV{qLFR>pfcIGT?9$t16U8G*&jc@G581l&xP4fUQRLxh7kG_0|s zt13=?MlB)1E>T~ove=J=@ifYj^ct0!x5M05$blS4q2zufjah|gTlj(X7(81dwRGp8< z%V_dt`%;!blYW5$D`|;a2zq_!Ln7{b(@WqAB*#RV(Anji&RXIKu>^O;a|p2GJaz6P zEFVYD5&e$&B^Lp^xDpA_OXvH>T~>l<#$DsWr^{!RVYr- zibXJwp{)Q;!qG{Ho_k_Fv8mW(&(z=)os4>dMvEGgj5MQ(aV>mrXFEEAW zGQus#A;ThE_QtJ*uN_c6dohp(=31-bL~qCRG<^kL%*^||Xlj56E1dYi$;%{oack@H z^;h>FT%9|A{`@F^jE>?_+(!A>`O&$#x$|_NoBJbuTzU3EiU-~N1h1FgZvXxM>iut4 z|M3lh^(x@{Z%>{)dH4O@?Vot-n@QOVfe*tIGi{Q>^`!1ZgKJJ-bI3{ zQ|I<>ZTD8y7ydO_WCAv%)s{6*4Fm@ zt^M||-EOwe@Ec~KQlWQL0@g}xg?Mk`@eeD@31R#dNgO$O5M9XcG!o)dzg&sLyI>xa zhWjQQJ@bF&;v?q2=mb8@O$?%qp_e1EU`9H;n=>jgq;4;>`3S~3jSItN`l*Hw7&1d# zlxjI9ovAVXnVx$|fWKVLV4h#E*AU8>``=|qLW@;z1l}v;S!>RN!_L_-#>M@z;nkmU zi*kBdu1sXEq&=iB`niBeT59^v(6T1kS596SNLQquLp=qz&@@YZoyss?qF*?2{h5py zX0!4+V@C!?zWi`hqJGGVOT(*!F z*;maebT24`t{MAU1sabOtjXdsVFlk1NQn}{sQMm3V;a(FH8CS~lukjDAuLAp8h4F! z6eYk2w`!&nhET_VU=Ah9j?!sn!^oS)_SnePhd3E~UZT9lC<3lLm^&j9y3KSBzg%XUBRFf3Iv`a4my}}5by>9 zDVy`DC&0CXGY&X~k;}no%wZj&#@mR-Vk~aF?Fa^(ju{6IghCD&kV1&zm}#^H33~ye zgs-gFYG{~oK-=tKMfCS3X9J-zmkMIIOeYgBwuuU0jfeIg`L%+a6#vv0|8j z8!&k`HFEOCok&Zh@K({bv&y3v$ z1BXx2QNtHPfMw!MuqY^G6#gC0HK58HBGgSQ71}flp%n^jb(Jaw3Xibj9ZKurPg25m zq@ag;AijF~DIxIHYBfr|5}8<_#}Gbico~e}Xo(4H^*ZDZz~sw*V2l0?L92!>MY!h2 zd=BInnSDs2)L9-SRTdXo34Jy$6e#`EI>8xeN-jp`&X~83S&|{iIeHs<9%6O7E|Xz zFZTg+q%<#7`>OB}6V&<`7Oj0*6a{-xg~0mfj%f^}2dC+|aPoFcjU$87DqO(vSd7qi z60qBYv9pNhzy=q2&{aBbdT3-OlM7AgLZ`zW#4b>RAC0l=d>w+}uY{qQIuG4Ob#yj3m2Y2Nxq9^q-5xx6m5`elh^Dr0UcPkc{j=xq2&{=C>@uU@@*g^Bp<*DwF|^5w7ZEAM};EEB>0=i9~K-o8Ek%c471A4JO! z`Q6vA^G+Mkz4^)Ju3aZ~Z64TnVAqLLdrzI{f<(9r{E_gpySw|`Vmoo|kK4O%weJ6z zsCMhEU;5qdTes|No#mTN>sSB)AOJ~3K~(9paJ3Y83XM3*uyrC7yTK#p`tBFHXNaM> zf)Fs=eOgSPITHF@Z#Mz(H8b~sSvYh90jw^S3RVE-y&OSv&zAPEa_E_QOV z`P*5$f4wQP=V&b#JJeAWaOMvWjwExUC^*mG7$$_=BA5Yj#q>2%{cJ&Vwp=Lmbq?hS z!bS|s*@gyv|uR$fcES3dh=U8vO|lP(EL8yy3VQdl)HpLjT|DN6Yt%4d%*(RD=T79iH0=P*i{ z4#WQBw%3_4$481HBlZUqmYarG@bxc^8N(aLKDxNDY?o@sofSV_Cfp9!yAN5_C1oV> zY$nke7Jwr^OmsuJMevA(UPpUkR;MyHYt@=&c9SSMh_YGxlad<u71~@lnpjQ_mKRO!Q3JqZxuI z&@EsXK`?&Vh!Z*x19#I*AwWiOBya~vZfD%>7$Ihfm-`8~ON{@=y`Haki{7DPp|wOH zJU`FZ`}ul2c@3EUkhr4jh$NL189l(B>JS4r!e~VDg1o^L4sJ$rc>04T(aR9-M+t+2 zZL-HfcRO(S3+rnF3=3Vq9I}#-wQ?b4<>~JS658RqgJHDf0@_*fn8L8VlF91mLG^-% zw|mJ8TZIQEsU~w9L|2lF*^_R>xuiQ1_*hoZvG_p}>E|PcbGWfy#0e}nM$?jHL17{J zVaT|f_mieU??4qHS2Q4i)y(`3XHQQLsdMB`PsBt*4RU3KcabbT5zMb~Ky0y0TOixq z3ru%d_Rv=x%^Vs%eYvzP^fkspuU=mc5_C#~z%wFNS|du4K!VnSdPR3)C&`#%1Qtm# z*9R!B8_?m z0|_aqHKx!$`XNPHnwA->;agQIpu31!fvzFb>(vt?ge z#u2XyRHZMcRFLw1W^c`*fI&v}f=W&qi7eDEpnKs0S_YAPM)zPK0SuO14UkB4RT3Ff zyR3@tK^4oo3H$~Ll35x!vn54jSKAc_1FJIt8HVuAi4azfiIiAELih^f=O{<8x&j=M z=96SH)VRy;iw49~qHU0@aH0#-W;k7JJ6%xd>L7uRBxI%OKZzsiL}=FmzkX>u^832W zH?|?bEV5@mybhJ@8|WKg4JG3{a31b=SCk>ctNH&4VP(HRdHLh~UnhHquNPlnmm$^X z&x<$C@7^;ouw9H~k$ArM>nArpe*Sc(x36zl2=zeU@Gz-0CgOd4y}f<2y|WmG&yF9T zq?hr@`!n}vzMh%EIQ-?y&7Hz=aDfd?w@H9sY;9~j+uHiiv#rO^c6O$APW()2{nNka z=jZpGnxFr+uI?mVG5iw7`o#A;&xW`r zdeL+1<~dX`9AV0aFuf$RwMYI~%Zo^&qVUv_x45H$Yl7by!bu9&02Ewy%3Ov-qKof( z`i@8Z0ka|O>CuHMmtw;Oiv^{MTk8ezb8QjDv0H{DR+Ea^XOX|+TkHMpm&UH;i#@*R z*sBy-r(_b#!C6+jwWAN0IHO#ZeV{oubnCFayK3R+qt%Zp@*_?0?kX|9opLo@Lw)XO zVS|>7d>LjrDo|HgR`MKO`0^u#3~T#HThhPue%VU6=_bgNkg#lCDvP-fmwlQ4#(Hog zKXUBmx}`DL+|)S4Y3UAzEAud$K0;n+SzI_+n(v4o^0oPs3r+5oGbF%V6~Q#fduM*z zG(;b%LGJEsxYbelO=y4n968tDu+DafD++OqkbJ$V%w)+9c<3yESJ|vs9DaQC(h>&K z3+=Id&ArIG?}nHB3;W0N*~*QJ)+vF^EM6b*>uiCzG3u`@7BN;8+_A`5or5%HHB(IGbkK5{w)E7QYTc` ztD~pza*!HIiyDXWP$-tc9xyyG^p`v^ijOiOx{Z-CX|K-f4eNABYJC?*@Yx%x4wBf0 z_(<4GVv2{s2#37YAa9I0f-!G+jP%xor6Wf;=yjkCDIE6nD>~S4Vv80+8$0+S+QLtA@}UIG)tyCZV4N`nXnn6%biH& zWPejBx|-9cfW8v#NLoG#F4aPWjiUJoQ)m)n^dzB=0q&VYSNQpY5SG#QH}<)<3Z$*H z5M$J@8OY{}W;XoT!O}*W)R!UAB*sRC9-+u-a=K)W$@``&MAO0uw3y8Bh>Ru$Lz>YY zs9|Wefxkfl+nPpNi^STuisZARuAWv^a5@0aYE>YgGAXl#p1dlpF=3q{pP9^$9hA z-lKRlUf&gucjoNzDC!8i>|N+OiX$2wx5w?#9P4ZXMM(j1dW`2LWd_NE#2REvIPILB zkAqdjo<&VCKKcdvS89DiK?IvF0TQ_Y33ALb^~Mo!A)Gv4`-BAeejgj)vmc&4JAUQ% z;GYJs4i4TP9K3q_>eZ{aZ(q6c`R9NC;;VsOE4=yUQSynJFdM%77O)tlIhvy-Hl*T z#n9b-?(&TvC&$GJ_M!3d*~!05-v9Le%*>}V4`=@T^~;wpfB0c@VsmqI`=9acAGfzT zb@s2t=gZHxww}G(+1YvZ>gN~vpI(q;A1HJo;fFTou^_?8ny!nP_)SzXkgh_4&x!D} zh(rU8Mbi8h|HXJpbOMt)-(%7_cYWCq!(#OLD&tvCpEiKt3L^|kD{L`$F`%r$#=j84 zI#pW;TK#_+(!SRx!TWX>l=juGXWB2hu5~kW3Wu~=5zqA>s48F<0lDg4ZYW!4c(cE1 z?GKi<#bdFl%B9Ah#m2@BThm;3WjCWU7Ctz9Zo4<19;H3rU#l;gz(HmI#pzM&-?7DPxDQ|4LHs$(YdFgPwN6{a5uD#i7$lMM8 zV@qUZt*mUV&AwmT?I#^{FP}NQ(jl4{$b}|{Ovm5XPx&_*Jdbq`S4jM$$C}E9+5{+r zL)kF9SPV`kvj=vUfVnJK@Ir)Q^2eNNZosF&zqmhC<8NDUz4(jN)WUw#iP7Y8Lv_t4 zpXzp0@~4r{(lL2YRuzKLeEOT^_;zuKohZI zkjaHHEiq~}Em{uTz~LIXmI0uwe~7rVj>T4loykK3)z5HCO?kCO8~`&a8t_V#*^!3p zyeUMXk(ky99tSz`mU0v`a8W}n)>5>-A@;$bR!-;uy&{`yX3jHiO>oa4>2oGC!9|2# zZe++*$6`TL0S9#%Y$s*J3KF)0QD_vN0H=eDt_QoqW30fWzTX95g-NNAuL_|DIPAe* zl9&8*I1}u5IOv|>C!Qb{kbv?93Bon zdt9WJF7m-vht=c4AleEzhttFbz%KH@lH-vCZACWA$(2Z^Ph4POIo;EwkuI(vWa<^^ zsU#>JPNyl-V=+Ofp~aGD9^}+BZw5P=+X0w##A-n&u*DGpj*{IiDYBd0G`bj|w{Gky zP4iB$1#@UYf_A$1;Mz;mVotSaOSEQfd6BzV-qQAkH!P_ogi;u zDHs}x_M=WfIp_f}%}nF~d!q|Lj{2Nv309+aABUm^7W%)0o&QhM`5njCFOXt)tWet+ zupOhleiK?VSrMpNE9eZ8mTnP|(}bpsN@>AzL@u1=t}RGt5G;oWHUT-dDVg9f$RYwa zm#McO{K?(#`{8o`$6n9Z`%^s6OIA?0wv=9iJo^*Aj+73K9ui4QKbXtScBHF_2o(>k}S^vd^b(n|GxCu-?MbxB^;~nRx z`-8r1|6q&NZMSdxd^?utvYlIl=sT>Iw^s`!$7X+XDksUrW(*Rh=2bOuwgLOG$> z86wQByIhr;sB77Otwl#St)DeMyF9RG7RD){)4lnqa$qvBsk!*LvVNBkxw^d+EZ-Df zXM@O!G?)d>5kSo^BMj0OR-vJZZOin!BxmvML0G3;I;;x2$Acg5rJ|vn-JWXG=J+wB zLI&=1D0D(`5wRFh^IV*>y<*}M`oC~bYUL`i6{IK?HdZW{C{<-j1W>}i99Fe+HG`@Q z`@E&43#zg(y~*2&it?Ap&cH8W`Z5&~I^+N)ZwG_83mh{^e8*uhj9cMQ87FsyLb4DN zu&_ZCRuZ&j7S6u{pc^s4Zsc@oybwSvhg49=U_~xvndQqyIY!T1KG^6W@G5afhlTVn zDhHj7mRep_BD%h?IFL^XSYsJDL(CI43ue!#04Dq*>WZDx4&xUVto>Hg z?Z!GzzEYzosRDT&C<-WsMp`Y5KZiE+ix&%x=N(kj#{(DHVfK4T~ zMq>r32;40aTfqw?i*>ArF-cQk_ZM5ga#W$Bw}CMHHGc1Oih&%Do$2=xPv(jcya6gl zo|+IeNmp9wO*^Ya3}r;CwRLveIwOd<;*vofOwcxOgaomdly$_`t$TWiOM^)?n{0;& z(6h5P9F-!C62|9lTQ`x~)bE9Oj?`d`Y_f9FRX-Y$yb&Hy*AUdE(8W+g$R#yw0?MY~ zj`9){y>mU zJYxr1oYnVF!+q?4%=kMiR5tPX8@4}l9u~rfrA;LFU`I76;0p~6e}unT5oYPDpFBGbeepH6^1N&8jC}Ln%?^L@6D#nQjF)6S~u)!>*raVJFWw1Z?wQh6&kKKRr zMASF%i})k^y02?@{r6o;-yqwG0xY)_1LC=%t>9xB5ZVrU9qD1zE}VW;|E_(217Q z(Uud_3GeBmK0o@;ca9=R5B_M9m`DO#VzQ#43t&>|NL zC&;|DOjz#WBj+CRxG@7><+#UnD#S#}WgNhvl)WUpf~{pRH_JJVvR$0}5=3R#z{RmI z3|Wm~NL!-v0x3`u!-%ZHIj`s>EEUA%Gh+;x+wnKr8DyerL52_y8Dg=(YWl`F)x{kx z+`0rpE0s88wuD32NFp*5VM{|{2lp9rJT%c&W(mn14kB+zOrW`cq0Skqts4x#Ky1F(Z~nGXdOgFA*WkG2E%8CGGV5xh1gpAsk6?hMk-}3VkW`d;#y3s zjl6qAEUm3$&1+N>im|6uZLC$-p=i*E52RP2c6lbP=Ip8p44vuj<=k>aoUKGE2Y{%HiV&b{YusH(SFEvhia&ur zs)p@QO?odZQ&UaETs@R;6IiUTX&OX87S|F&2RCzTgB2OkXa?5vhEk1CzIq%hHxF?& zl4nR{MeD6YHB)pS)Gi==i>}c3b325$W(wBpsVOU-O2p&1_!CXQM_)k!-(>(ZfeFCr z&y&f&CNsb<6LfK(_?t-qha zgZcKzdY>pilH{-3pEySfSe##rQ|K&-UHmyXf*zYV7;zVfe0Ac-bk4HZTl6A{<6o#? z1K~I~*ybEu64tARD@QPBZa^ppxLa5~I)X4PSfG!vK88apg(ak~MG>%+bXC&H)+;Vz z&~Yp@J0m*zp9ADD!I<+n6a?T4AHHn^ey0pc2wsW0;_Wz+u(m6rLG_>?kl@`NGyq8$ zF^iS~0A;r;zHaEjO7Nz!B_5BTK5a|v`KoqTo#&mcg9)b1YH6@LZ!T2u8aO_g`{_BG zLM+pg!i{&8zc>>$<({^+_XX_NqK?&TZI*mM)HN7#q4R{$)PUB#d+DO8buyMWYIXvB zgJ-AlO#%pXCSA>2LwRS=lUmlFJ(O#THu(ej8?Nb`wI$-_2#r8bU(Ap&7#;;HR}&`( zst1<(0&aQ$_ZP0^m~cz+J6=`9%sqwNNU3>PWNHLBFoPGPPti5waizP*uybbMaqd~3 zUSTz!U0#mL{jt5)GkXU1X>+-RIVOhW=G%c&QhcV}E>^rmf1)|Y4{rvDd;H^ClCv;e z$%wovImce9Fos5;6|Bny!?0`tjw|jaM7&j5Sn)r$&h@9w`-gjAP(v#csg#VyG)vW#IB9N3Nu#JuqAjCD0SR)M z(y7%Z?cKKb{a1EA=l6tG(`+!okNr3ZiLbxsd@pT+kCTvF2cK>;c`nf7i>vt9q#)|# z4I#qU+vFsuq1ha}P4FbTX`lOs8h{TL=4^^(L9==2&#(ZWK2NipK9o(NCih|u0Z zUh_HRSY9W}?1%&2_66Yho4_}qtfqH-C!|;&-=5c?XSoSj4Hwr~)P;OCGL`3|#0Ae$Bx^!$HdeMV2sL-!WYQ8$#^+tDtY2 z%i(PCILMwPWm1j?Z{YEDxq?0-prN`!&4zA)52L&aaY*gIpsgySbyQ9GPtX-IWvEJf z6P^$?4Sp46>B!DwB}>F~SeB<`m4g=XlQkGAYJ#p`e>sHPx11;? zSA`=B;)W>rEn5n)mcOXLoUp1@c?97b#j@P^x08uvd7D{umG!Sx6WFd6i?j$QyXJxB zu7?87MN?IX^(QIRvW^E>Ko84L7n@`n7pNj6EsGXli%{qyJ%u%0&Vr6)@~E3&j)A%@yh2z#+$EomW== za_Q2gmzVCpe0l%M%lmSQs; zaB8|aIO86?&7v3NJ!xDUnuz=M{pV9>DKkXC-N=|%A%SX`1f zl-Q3v#GZR7EOF@yn2m5L81hj^_~y^q8~a}I-dFWVb{WI|*KPTgA;DX*sj=AdoaRny zJ&@7sUN*@RY77=YyVo;SpBoiy*}K{LcH_=^{it{C`GLsB+;Z#TBeyljqB-zk`;HxS z43>hZr(vP**|I2|8$Ujr-&$)fkM(Snr>>6feHNX$FtR>&_%TffO`)i#(?`CToBLum zdAd1y;O*Au-A#Y%^7QGJ0}VSTLj}-tyvo**){Rj)Ve2#3!QuY?3p1@dspYZpt?tpM zoA>0U?mfCUI(nzCGLl+9aANFEYUI)L{?yZVW*?8v?Y0`}dRAp!wi;S@*{>2cy6qxC zl{W9)Xq~yRw&9wJHFt8p=WCBn%x>M8THI{B)8}iBnv>aW#CuJKmMLqr<0yCA3)zP2 zYw2tDH{_3@lkHsx>s)9qs^!Tx*D=B|1S9eKDnn(@H;E2{7RsOf{c zP8yc04GkLZOo)bZUNw#Ccp7BYNr<|i;z>{y2|v~8|aB(ObQc< zl|ir7qr{k6V1~-EXpC?UuVC`xqBrJ+3kM>BNJJ4T&N9$@0UkdID8J0sUH^hV^nNT)E`YeY>F z)uA-5$B+O3AOJ~3K~$-f@MAeRq0yCs&fcg=!jkJd?VS_tCW<3Ulx2H#0w1vaGJUQe zo!Ua^(vkBq`Uvd^EZt~$Tp9@N(uyPqF)`7q#bO4nUBC`u$3)As`wg-wCbt8}qYkG{ z@DK0%EsvAcFby!iRSkTG`y$KoyFk_?sw^Z_p4F0|aVb=vJzIBbZ3Zf6~k|`R^u#W zM9(L*r$O;MSsRk8K(rjKch!(RllTnWGIvgB8Z?{UAr)dN1Pdr$6ilwu#$X1-@&(rs zBItTui;mLFr3cYfp|2VqGQpH`^1403M%jfaNoUboS2%Cbd7fc)g1xYS@el%P`N@h8 zi%PgT1L&LXqLM-0BNXS0h4JS9&|kUycK`Qh4FEs5bnXw|3ILz`@>5;@3h;uyPvpu7 z`uyJnfR`TZ*|X>U_y6(BN~MwhZbr~QDUG#vz*iKqp|4MXV8P!f4-5dG0)UMR3F*`u z``KCkdX?tWhkUs~q@7Xih zRQE{NOjJO!xw+GrE!>+8^QeiU zR2({ed)A>TmWLmE4tbtFb{u_oC$$mnvz|4ddm3wkT#v@%ThB5_8l(M#eFp;qq04{F zZmf^LyEUy?X!0?1!`e9E>rbWD+E1*94rLm?1ASdWgELc$j~;nC8*{1DoqWss^7xEU z-<>1BAK#hYs7!pYoSlkp@bgX2Y13iKbV2Y7)4&na>qHjxWmQ2NJu|EEz1;%weUZq~ z@y+RHfum#j*}igf`Ou!3gEN&KA<N6u|*zv^r0pqkK8nAB=ud`JcDA`}$IsD#VNq1hYC ze|urTl}fyz)ktiV3%&6U(7BR{GneiqiG$5AiO`vj0>y>QoGUra)yPr;{Bf4%!3-{> zY`ixY>lG-@aJVNI&YIGrOhyeznIDis3oM7jSvi=~&IVz*S94cm$f3hDH|Qjq)L8yZs{g_}+}Vjpni2(XFsUlgkoid4>1O((}cf_!1p&^52AlFH?fX5EEYg>7-fJtQ)AZc z@Ki1gi0G?yolcZB}(n+UhA76j40=l)Z2_^`J54f(oSH9qfcDd0D{woR! zFn%=}yjaX4!O5_H(h+>PH7H*!?t4newO7-X+WM5Yag_80L^LI6a-{DLVN_1umFhoq{Db#~&&~P`@zmMl<@VFZd|7(sTwU)Gb??W! z1|qNTs@CbswmueX7FqqyvNGEh0#NYhKG+0=Agtnc+}w-Dc`5x zVyk>)#BsbXPaxggy_{`yj`kiu=J@UE8H41xl8TAN&RRrSiRNJp-{b700!VXmhKTp> z8g{5x6M-}PrV+=vYxm;2NcBqXv0N=I3{s8pLOrq9V1#pvJBKq~seOqD^l<^gM8pl* zJEbAQ%nI52h}@v>#SDn(Mj|3y%(XX!eMK-AA?-+3K_9lEuR<6tbL<9OzabFZP!W__ z9@vOEGYj>;p|YD5H_JpUR+%RVXa}q1#juRiHZcBXftJYi@F2zmv{<$bC@#WMxFTfY z>ZD@XS04C}0L&(OG7}d!AcfKdkT!8cgT-Q64$9EMKo>hUz}WW6pkhW#gZ;WG2p_PC zn+Rb$qC48J!-+&t3>-$vh6#Bb=x8`%Vft(1Dh3FznsLp>sgrhOQ1Xl!NtKvP>zmd3 zx@Jy-J|b+uToNp|)v4tlPs)k!BAkPJlH`caQo~IIyV4OrDzRWFs?_SqamHr3G>yhA zS)(u4&;wv0A|Qn_%LSKjHN3rup_JF?(KlGFVQW&&xSB|;n(Ki%_i7x)3Q%M5PS}N| zaCLe4-&`)Nd0mL2Byh#3xmp5f?qDeA8##xAm&2!O{=fpR@&h4}9gcTEG3;v`WvZaJ zhXSr6sI1V0#LO6^muawyl~*Bd5Qp?x#lByKxS>P~hj58XME!8wJjX(dg>NY=!1ef0 z;z)W>U&yiOs2SY~LtQ)wBaL}y70f?^{9dq(4bB3KbwJ21C9K zP>T>UTZ#Q9I|+Lm)-ip?Aln?PY-j-1LJ1wCFJC)TQ?OSIrhPGAWvnx4O^Q0gHc(!o zzGEl_Zu6OwZd3qU&DM1{M$}-yV^-g~53XM;S12Xj9E(K{zfADm2{TgV*cdTzD?+pA zMa=wKNe+sRS&{t#{d6+ffPTVc3^j$Z&gIiTQ$gd3_vJhD^Z&VZJ{sM)czX%}OvnWA zg@B6qFG1*!0IaD?GZS>hZ4mDy2F$zT6~UiZfWL1|po!0> z*M!X&aQ!`ZAUPAFoPiKHeqw(9)r4e+!peDVYD$7%f#_hsD}qtKe#++s4t(o1{Lal? zdF2mCO~4`wi$7}P*)fzcaPzN#S%|D)`fb5aoI!bl)zLjwgueqENm+HGWfo~~gQePf z2>o$UF%jlbw30(O`Z@GU%js8O$o+_Lg;}^?i4n9Udv1NJknn_L3Fh%L*D;7~Fb=ow zsE5zh&H59JM8w*RqIcdavcWJY4P%q*pY0m%8|gi`AnRI12Vvybi~A={c|&;Tpkvmb zF~k@8{(Q8%yIZqEC=-sO#sNvv;ec@QNEL#Oxd!#7*J$*Qmal%(+da~yPGt$-vUlEd z4EHYYuxe?4vahdh({BjmL*>wPCFsCe*$&4#8eiv1(f=zI+X{z`i7o5HN5wa6s?{8i zb+?KRx|Catq>m#tn&d8ijmK?|AWUD?T6B+`;^B>=3_%1-Cq(C9yujPxLxLt8(rw7`@KNo4aQ+-atNo&u^r=89Qo?-r65JYHMq~UN3@Cn_3Pxd26rM zUhUyaQ=yD0+b*t0s`Ofc2W1 z>BgYNQxUW@+rfQp0Azcxx!L2<+nPOgo5^AV4nuf_skFteMo6X21U(ke)@IV%?AJMR zQmvo7jx{fDc)5`fT=s}<(l&|2$w|N|{K4o1W^~mv{G$CAoxVhcZ%oQLUs5y9<79+X zjuSpt>nG8@pqK0QlSsNE#*0NUY`xqrs0IbbK3EL|hG|FxqmhfA)1lj!pKr9S%{|&y>2{BC-yrc}Hu@&rXjK?nUkVRDdy%VX;wD_pdou+=O7N^*H}9<6r;D0?l2|>;Cv4zkd+=2D=kV)v zau)Qrch5(MmM%`eAON1Y|H<=D(&_1oOdNs6gua;I&RqC#Xz9sqV!%URJAYCRYy^w` z-;<>ab5}l{p8ER)M$iI&34Nda$oRYc;KRAK=@(OLL&(vBdx@KjzQD_W_b(#POSh*9 zy8*!IH)tv0B`<+jBodrXuSKKhH#Tl95d;3-=`YkFu?yHw0Q}Ln1^;kVFyI+J9k|5f zaDKv>OK&a=z-d8%i2)bf%JleGuk$wotbZ16BqU*t-htbw6-9)EzTC#pDiFDc1EB|c zi2PPb@z4VpLbs%p^u|_#19K7Ylx(&08S5#nS>MiY-7ghPdKx=c!D64 zb=G_Lh&N|4UV_P7E*|daFgA7=JG>dM_lHC_P}^~}wj)C@dAO;mrQ`4)2_?NEaZ++0 zA-Ss2c(`StX`l%$8ZE7?QKxexoYwrGt?T_s`_AJ9z7PRJ6aqo)P@sU~k6=!%BEmQE zi9TTKg*0bx=?=?9d$YS!)1a|xf85%}-mT8L($;3_nru$9>$MLqm+r|NYliL3Tuf%} zne>wVBlmi}KhW;Mp@3fnRNDCB^?tv83`*IQj1%H`2IJv)Jd??0!|7}$oetxpY&zak z&$s%P-KMdY-TE`VfxFc?}MyGSp zX)CiRr3NX=WUP=>BH?a1eJ;cbh1DravOG~{XVL9TD~~?SZXuz)+j>%GGt%_5M{X9? zhuGrF4CpD3XNG!Y@>l{iT||IM0BBPAk_LtVu|p#Rb7BKd4sfL8vHySTVAzc@en-Xu`+#g~(ld(|Av zYNXX$nn#8Udfql47@yhV^;up@zLir9}56i_rJBD z=r#XUGw9pbWDES==UZD3U$21id+)It>4K^OmP-kx>>v8TKXX%1mYSm`6qs$h<~oxkK!~Z0f`5{3BLcw-VbNnYu48b)gs*Xstt*9qTlnkntl3@zdh}r z-CUR3@p`kLj@JwQa_4t8-`>PO^DH$@lpCF(ni|(Bb`P}6UX^U}f;0?K%_YX!;neW& zKp#moL72fE1F2y^6~IvvKLde|<9)aYbc}*grep;yGB2D1fpZ;wc=G!CM$f7;i&6EY z3d`rOmKlso6nG{a&&0i1ioUb)YzF6aPg6@zPsBAbf#k2gPa)iL3jQB@8jVE0>gFc|6@DTltxw%2^# zXftv?EqGdF8M{$wl?~!eYLw1GPM`%unG9`|={3!}27?wMpVlOYgK8{8URoONCW^A} zHENDJ20n8L9V7S_hNEgxsldg)u;373yi5T9s?pTb= zUp5XFBhoPlvfQnT8Mp?PMg;&fuDT;JjRk};=2CW1=)3{u%NcYq;%7ExSB&%KSTEo= z=|sA`dxBo3Sz zdIk1;iP4kbx*R4`rDbQv6;QOmWpQ(%nP25Pcfoxsfn)(sY<;(@BGX7&MdRxKR3`AowZ z=1Dsx6&ml%hdy>!mIy`0vrsA^J;3TCW)Rrq9Bw=%D`7rJbh>TM!?E=?V=Oyy$JL}~Rrky>Wy-V7tt+@M z=f}*c)G3MbNKmCNS&*Jwzuf<>D*#R}-1zaIV8D;BJox@g!0&tSs`Hzx*Vh2xmoEXp#r`*~4!CINV{AVE z6oB~2gXQJL$;tWqV5s*WK72?+@7C5QTOVyL5`e$QcR0V#@w3uz&7LilsDl3V*2-6x zuK|E3S3VN*T!l*c=$^>Ah?)0f2P_Qu@|ER3&tJdwcU3<4hiVw*Y|RIJ{`{}#rFyJ( z!1t;%?dmH6LGmi9U#pFv!GFI41HOI>KlOb<@I9#to>f6uH4faq9{pfq`|3GKpd`#n z;1%UpgyD0XLaSzAW>=jB4Q4Q<*L(b`o8l_744cXrK2y9>In4hknZ=L?!cKkGw<0{mAAfA zO?kv=lrJ`@JyVkGa3%v9nGJ_C@p3p@#?O_F^B|t}W=ep&bUkpeWnm$Eyy~!3dg9aR zp0OtI&Jw#!5};Qn_b04Y17YliH$~WeXciFN)7}X5MQ${u|IP$9crcoLhG=pZ6qzyv?P+cdhT?(r3msmE*(t9LG z-N<%frbcT91=yT58}mO%QirC#K#NkH2(~m1tsTk^jH3yoA)*x{Dulzq(jzG(Ohg(f zie~i@Zb})JgVhQ&9*g+^vmuq6XNU`kF#h`4$JU5F87#}|=IG-?j z(qd@<^>seMJ(fR&adM zDN|+!ShhA4&YT4G{X+J_xN`xVx#72XjAM=TA4#&6fkDtjStD66{`J9n@0v~-3^oHk zVn>5iAQ{cJI@>8D*TD1w^F_U}PQ+I>vs;oWfw?MCo|#uH0zQS;{6<@d>=-C3P7LW| za|`p8A|x{_7R0oHKTl-D4CJtmyT_lofQ{hA$u)K>a4*b>G;ld*b%p3T8n@Cu9JN~Y zsWp(|wW&2p%*ut5qGV=8gS0S!A4esP!`kMF0=(HL7|rR{=riVCwMpUcYTNcS*Thl1 zE$aCnSJ(T~RGLPorDY3D$WVqxaX^M5Em#n<$#zM+yA%+qL z0TJs$77=NNRA;wh?39KuyI&SJyR)-Mqkxi$2@^lbFbSD2`&aC9&U*`HFQt9&?GKCM zJw4BJo^z~<=FZ5A1Q@g{M;%_z|^?99MRG!g$MT8NYnEO$Ara2aAu-7sf z3NiH8=X5%+18{vIpC^Pk!Ul&|*e+5CiK{|cLyHz4OgcgyD7>J6h81)OMQprUu%SUY zb|}!N{+iSmm1u`&62@Hu>Rth1Pr&Q&B0-|^;z1nYeg_vKtjN~N(4B77fEV@$csS3i z*zhG;Mtb|3=!h_2LClZ4N8*Ckqto|Rh3RSoNi2nrkE3u*xE%jh-s~s~)4JC~@Fz?%`7R?d8cfSv8$}-qzOi{KAJ#hff}EJ9_wg6uk`q z03ZNKL_t*Kherhg+hCY|{(K}NsOb{QdgXo8h5~LLuMnG|%n|jojTyMFc5Nej?-))Ew}8rDFHV_uv2W>ecr4tL>k@ z6O^P^=wIG&V`%l30OZypuGhDSk^kKQN^0ASjg9p;yAgShF1lg0XrgU34*YOyX(7Qa zo>++;e8r;CWlp3;lhGtL-pbx@liGw@I6O4OOPCj=ihQ+mW6d1n6X5ME5s?tA$LJF_6jK3(pTysd)5hEX0OIJrh9uW-z^rezn=V*>KRUxeUOz^b{B);8 zR3SRPs7==kY}Xq6bAW5ON!Hgun^iBId03fIA{e*^#b#l;H7Gonel=WPiWww<-*Ol~ z7c>1A-C;9)q2*#O&CW)v*le!H3@{qP%HRqVS-9$O9!HFd&85TT*|g}$gDqugo^tCb zEgi_lfG`*`oj8hx9G97yRfvcqL1F5(fUn@b2ns%9HWQ5H0#7X2KQh1!!!yL1W629CaxLI`BIwN-l zpsLEb3jCj~2%%M`SWrOwLQrP;eCPo?$$8N)w)D#?ib>zN+Oq zDD>XP;qLg@=$aB?HEVIg&7ZV^0e=&nx&uyob4csJUWI~rMCB;Ssc&Q|9F~(|7>-!c zXo`-c;VJBe8P_H2DLA)`@EGpLC3DN8_zsUG(*nTlpH^w?y;s$uIq_9d zHG4OQZCoL%emSF}t*a-aHT_Uv(8Gm87_fobXnIH*OpGJcDZfb!C4twrG7bq{TnJwc zC{OD!z%-AJvb)QmYX$!W9P8-nj5S-s5JfX>5Zz&&s#)h#aV^)a3{cX$X#!0m?B=sH z^GSE54zyP#AE7f`?ypthNP@V6x6nO<2@ASbBlx$r)?F&277V6IRc?kVwZMwV|epv#jb942jd29`1UqS{Wr{TcgEZi zYt7k^Sbc=#BQs4ovXO#x1~uq`0hFg14g8ctNdn6QAE3#A-wXpIv|95~fi^J%NhzOO zWy8?#JTMhWNphWUlKXRMN{MMUSsC*|fZ;qjFO;_xRs&f~J2fhQTZ|jgfq;QXw8p}x zeU-xiKMpwX6(L#haz~C;sBMRETh1iO2~6-8Lg^XM-@-tkD3HUWMKgf_s4uu}j?G?F z#0g);b8YGi&!>8><(k*cTrfST{&afxUk!mr3N{sz-X$z)o z1#N9PNaOYS>=w@?IVjN9VPi6aBNSvdLchv1vRD>FmWI%E!CZ?lV1O^}CqwX~^fZ7a zUv~=V3P4*dbjyMfhf_`e+EA#5D~Bpe<3-``(eL#I@xuU*C%rJI1mq%10)|-qbfiQg zqP(GC?eAv~au_lt=(DNkk-^t-_JAL)JsMkEdz^T-^7z@_-cmfBh%cqn=~&`fJh7DC zl)Z&`dT*)w>I=pZ z%9DHE)*%fECFt-pO3?exVfZ1(M)H?{$K;67-SJuH{W=mQRrUHX;NGGc+wN6{oi+ zgipQ}KDp%tP+ngrp(LN&he=diAMMTU$qnnSn`s0*Z*IK#`9@^$aQhX+4wa~2UvK3r|gDR+&S2919{&6T61=l9rkH5`L^{6O8r;>-7(?@ORWOA^r=Fy9jAXuw8EokT(H2M&5X z2@^+2ol;;+h_g$9JLvFGSE$7da$5?P5-P$H!tLQWPb3`ppF#VXXhF&a)bDFtz(6al zz^-BptR_FJ23in$B&JtU(x0;erBQ!od0G8Pe!2#s#95`l z{&!-2KBC%!B%h&}rcDmM!=ccKkX&Ln6nnvC|HvrgW(O`<>b(LolvVC=_OQG0n%GY1lKU=l3}|8zJN!)zO)UR*k=;5wDCyy zRTL-r+(v;#0*88h-Kya<0hI`#2ZkA_@e+gn%Ioy<#^3v?J8Y2xl;o&zT!OGrV}ZzF z1IPqn%^|mPy2;+a2`uP~^EWSt-K=%z=m9QUagwnt@0{GFWN;xruXE<){LGv%VbEFW z??Td2u(e3om@*p27QLXjhJNGKkq zytPoy3o0)ynGLWdlyyHF>BETwW-p9Ize&p5lluFGA3}Z*85~-j+>Utq!B_jk` zW`2DCTUEdZBCNG*Phr5#x`5iVCo8p{0B%=aal4(}-Xpo)dDPu)fy9q`9OzxTWTGe! z>GbUW7oT0d4+Gw)*KXaat=!t~w!7Wk)pny*-)(hw+k4%I^=_-tu088q5(cbIgmCC9 z-=#`eZAksi+O3t&%gt|!2{)j?2ek^ucJ!{DCw;juKWpvfcdLIe_9GNng2HkEfQ13; zkowk2^H9`$`7n!8Uweh~kbWgs!l|2tVv#xhu=?(eR;{-3u>s&Kvvv{(Y5p2lEcEbB z+upEE8bxG|ojW4aMOelr~RCDpaAI~SAw#&5RIbR!YM zp^238Wm09)NEb0HIn56E`=^cuVI4`r`X-msb_BnsM&Q4Oe)-#xn{SVg+aBN(b|lnE zxj*~wXT6>24c7Gzvp$(ZWPFQ zupxPZ2W<*xJtZemSV3Vq8e1h$>=R&(u$HrHUO2x!o7Qi_dBv)9mz%J1oIYHCnU659YaGEBhM2vOuazcY9 zqY1Xd0?Zhagx{)2I*TWGg6ONPoTd`2Og84v2*phcU@~ydCZZ#EW3f<7jlcfo?8qRE zgfS`?XbX;226af;F%k5l<<|`+?RJqGFa$qB+LKDua`ni=`xa zv~oVAE8~!Sg9Zi~lh_%9%?6)GE0eS&y@cd>z$tIk?gfGZx%cEPoYN3tc|RqvD`eQ| zLTRPhS1f=%&|8nTBRPHMm`|G;7(k=y^l4e4>PtMI!gf(c69eRN(?{+$dGt=R1V;QE zck851x4vjaX@|)RM0-JEuQ$A)ifB23?5pIwoH~;XC#`v$NJ)@7DKBxi=`Caj3>wQ< z!}D^sK&&Mv;XJx6WOqRxGmobzZ<&v{cLBqZm0vI8J4#whmi2gMDM{MZ!c07$5~`Vh zoG&jxb@S!?%zBcDDWW%+QJ2eQ*scl7C=kbyN1)7_HiEV}RaneV={HhfFGP1nZWgCu zyo(^~6c^Gtv@=)$xIpWXN}s{fDZMwX?ZRY0r`Bi6nmjG!I8v}QrUMljsgpD70@UUF z6i~dRf-oy$6>Sytouf{qb843hX8CZa^E;Jd&-EgV8ENT6`_!|?RvYjBaFJ+Z8v(m?Y7)o?e^+z9YHGr z#*6gEnfDQ4eGLFt+vHWrW4qg{jZUM!+ilbzbQ+CDr~9DO>vcQAteUM(>tP>a)oMRk zd9rbN<1fTtov|AU$;A52xwSR31Fk>$odEFBF2u`6E(bXs2az6!-ATfLKVD%3z47JS z8oi-?gov>)l#Y+zNxhoMzo!mhMcC7)v9YLF_Z&qG7wAF~ZjAd^!B;oK@84vy;~Vzs z+tP4c3m8yByXWF8gw>f8cgrukbC@;;p~ms>+(6jt9*}Ro_sOYmC1Kf%;B$w3_ox_4 z8-Y(9`&;GBUuADzxyT~)qK0Q&RH4vGf#5S=|54D@02sB)8`t4|5WwpM2CWv;35oLm^N>lK*r|vLs~39;j^z8LBFoq z*R!)154)De$3OYd{J)t?b9?*2_V#vzzOK(7e7;#%;lZX#4s4y??~U|+wYIss`k>LN z+7A{0uU20?Uwi8nm5ymb=Lzgy<90>xeQZb!nMuDwF%^XR;`nvw_}LNsG#C(m!|N^E zU$U|sri?*ovfjlU9CWb=c1;khL6&6>r-~yOJgZMgx3CVV17~SDQrnV2dayr7fQK9s zz~6%LCQ1V?9_`TR=VGuZu_BqveTo zaiVDQHxk(dOqucpQn4mRGOzd$!62J>~dxzru_FV+hKB^F$8DGcuxN# zi`Qs5niZ6lgLDEL*;OVx0^?;mjs7Z%V>ss5JPyLJ1a@QT5r1r1o&~itGiqvq1*HAR zt_Il*VV7$HuixUf;I7($uxn_+@4qC(U4|$Ac?L_ zvLmL9!69&~4OsGzB>(&f<{eH4WrPDBUwFXhAf7|V&;bzFr^lVhwG7m9M1uZ7NBkyH6 zZOzP+Fqup)*G3{iWn!lB;!so`Jp;MkOmU zWtEo-GX=u16msouLE*d5+NtTqnMI+%IE@N$;i>7=k}iKg66}^DLk3k) zE+mdaLcPlN8Uv{nEmGB7wyG@yjfN?js2xBIOQv&KLEu8x+|8H=JM!o)P+vTD^kRG4KlTPN5gSM)WE{49^a11z0>Jogw_*2!Yf`zygd>0}UtD;4 zT~5$r^Z^gbb)@Y}Y=DI$Uwhg)P|q^Lmmv2z7R%cIvK@(QV0kz2S?M3%YrQebH7%=; zxUW@RL8Ah|vDw!xU|r(ib?GIx8RJG22NdI+BS5R6@R|JPk5e-<^=;i;t_r;0v3hVn z7Y2MZ6b5PvMsBR7o@A_fG)K}F4`vVKv%-tVQ?Hz=c+5_vrtUlPN4yRIR`4q)rLweV zZ?7k|6A;U(4Z#NDF5v5NFuM545Foc(5ny%`TA`F5epJ%$ zKm;UHjXY704Gv$2CM=Z^lGx@J@ePtVG;K9%honklL?s8(aQXs4L)iBs5eo^HG$(-+ zdx{)UEr8ZRJIWQWCsJyzetD1nKka3GL#D{ zSXLR(LCB-sC?OPp6?A@ISTWp4?n(jOno^waK1ppf1kW{sySQ6QZjbNLl*o*`L8=q+z`5k$+r|0|{7i z#b)#LyMV+{I=hO?@ji+HG>p9tL0V)`+7!Urpo)eG*hVc@2^U`FGzcRoy8KIA{(D`F zn}l<(GKNEFFETYCboP%luJ}i4Q8b8fs}&){$juUVDq98CqQ8@4DhrzV&4Qp|#aYAf z7d4~&7i|n(=v?UPLLPK)bH^B`(;dER!fb`{BBLXWph{uOK0b;e9GFqd2_3cM#?4Si zk73)~+vW33c7!K4A%ga!3ZjRX1;XQdoX~7HBa(6~^1Gk#0iVbC7%J#@H%!w=0NC=w z!-a!_Stz_S982#X6bjGeKzdiG@WSw{nSS=p)#on{v8^oV9|~(6LF>A3=(wIt>Sh7d zH<#4c3+er|nK8G80%xvX{n{eV`1$zKp4tH~q|)ddMhjvxmo{=l-W{-KGbf0fPv}M= zxtvcXcFeqK=5uL%UjTUNJFb4Y0>%jX`sn!3%+w~5ur?ClF!8wj5(r<8yHe__xIfUVj#^NtO_&(S9G5LlNZTv^3Ct91@A3!c?U6ihNRFoDF06e(Nu`H zs)eDJcLJGV;k*45;M;i!zV-jV09Hqiv!E}$hMn-=O5YR!ZdY{yO?Bg{25G#Gg@oVa zUnjb9qDpNWdnp7eIb`4$1yk2d3M4ZXvl!#-+{Wx${_FOsnN#(ryOnTRnQyT6{P*q# zFi@>)Q$Wj`M}{u|m@Yt>i2)=@j%S4df3qiKy7O18E<&-rFxK|x8`i{Gt_s$+m$#Sa zEiQTliJu-pBMBOxzcvRvWW`_!Dc>hppHp#s5kODTdo5qNp~ z2!L;XdhCNc{5*11DFAF_t*^uao22*K7vCDFqtv=dRTHxPa9obm-Mw9+6(hm7$klIS z9#*lCS=1oW&I>1zBg#dr@YjC=d_9~f+nMJ~5VqUNmI2fPosMDzWx4EF?8?h=2<(>~ z3_^4Px*E(*5y4*Ek8g0dcAwva_5>#Bi$N@yq!2^_C# zLW@0uvy6ZaL^S(qAYcz*Jsi;*S|TB)Oh%}6ZV^@-p#=%`MlCfFAZ$=>BeWwBXsxM% z@u)?R_#{dRgRP*!SOTL33HJplf)1W+ZIDy%5p)G{?*W1>%~k7(KeGQ<&O|pu5Jq7) z$SxwC-9e12fz!}n36j>7F^YqsS*-kh-!0IK&O($k2;2(CExliPg6b(jLjgnK$AC=K zA0bx@%4(ItQ93;>2kw_m%Lir3-%IDNJPHXNXK6vgj<~dX`VqQ~a6;Lu)oz4dmHn0| zOK5ge=Uj$8FisZgi|$|{zYK;3uf|rmvJyLBM^RBfWOl_59JXkGKXwWZ`pGd}W-F2$ z7a)#8Y=wodEh?-RxmTD&BPEMx*|09Qm6sGd{U|ieSIM%b}?|~cXG89DXr_v@tt@)o7I;K2Jq8}Cktj`zmQu_ zo9VT87q*mui@$%pcg_Of4MUI53vz!Ek0%Q9S`F+r^qe3G^LUs503ZNKL_t)ou;^_e z(&_D-Ag|zPGM6v}nDw1sTwVJ9qVgYc0?jb2wwak1sAWpY^Wg>ci-!;OtRQ+)*Ntp? zKA+stg`4Zbqj!uvK7r8wtTCU@Ez2ib*OS?VTtILK{6ZKnQ=prgu8$MQ#t}u?^>$$M zhH%?9OrQstbtT*v?=4CUNwo4Ku^tK897CsXILmQK>1sr>8-$7F-W5!NyzCnx2X?VG zTTP>_7`YO#<`UOOPZiZ2uwtK&Iq>1l!$6KBK(6>~`px%RZuH%OIJc@>Nrk!(9lPH@ z!zP@qk>)^vg6o|!zt!83s0?b+Q+MlrlzBF{Y>aZK(N>kNc=LTor&>Js3QPk98 zrbnRoEz`wmD0_%xmTdyNC7Oz<5%jtGp*Iebu=-RObk&tBfB%>~nIO7gF<^@V&mSg+ zKYUp+&o~(NfFu%$^-PSt(M0gs*zSK8Pn~~*KI6Wox<0Epi8AQEzub1&s9pAG4h@Ns z%zQ@r21qK*o+t~3c1E*1idd}x%@!(=(7OQrw7l**&>#rf8x`OcWTk`)u7lhEEQv!7k8&YtRw548nn;>A-!5_gbQIoSC%!jhU7MKu_A(|*Z>O@w?v@F`X5_Y`_tBaM(Y=lU%Civ z*^12KIhb-U)UZfRf`Qx4ioZ~4OQuDUoJFz7T*YK&O+b-B7I3dfKuT1H)`61bRs*&g zr$VTzs>PkwMZu`)(58Jzt9@FP57GXQJ?H#PUZf@@#`ev{AjrArdCrR*h!TcwrcW~S zxi>0YSe}Rq64Uo9a4hf1eH91YhYV;$a`erhp#fkHcfpm!CM1u82n_C< zYw^(hi&#pR>l+_j!7a#%ZaRXI$bq{-7aM|ooVvM!avOZeAZYGy9*R%o`b7#xtxN0syFY(7k< zz``|c67|7fP09s8SReYykJJ(V2kezeSj+W_aNym#KycZvH}>qkI_~W5ZaomLvQ@1< zcu-rYJ*d_$UVQjG3z}J2U5|e;ef5WD!hqoe1_ayIqinWr)pyJG-Rw=%-jFlZvTK%I zuU$kL1A{05!N+!fHhuN$trMk%8louW|9tF_*UQ(e3OI0OzATplPAw=7o;B=8C*vWQ`1ggr?k*S+xBg+iVXVAA^_DLznzuWI`$# zT~PUhKMg7Y)(fQ-yB7}b1M-pP4)_RTIM@gLg&%E56Fpt5@9kn*2E#K1I48cZPN{({ zkZAkXOW4Nh$R|zY5qddmnU93`acqmdFb2F&gPU{Y0KstZa-d~<3_81QF{)2Gk;R24O;Vx^BBE~_E6yv;3dz5vE+&tIiFVY8)U zmRAV?;1YjNP5r*Q_us|ocORd5n=#WYGE#QnuAYByy#V0m2>Q`W40!&|{s>xq5uPZV z2ho!Ih!L*&i5n6BYyS1p8i`q%BNxgiHIbch{F_?2UyZ#!hw zy(*)UQCY&aKhB}^*Wq$}vsLHA&6rlaT=YK)CAnvNjd z^0S;lo{G_J1Y8#Qj0C`g8O8ydQB25iET*!pIs`^zY-teYIsir13Wm%WMI((8h>HA4 zbOA%)94MYe^fN1wI${H7u_MOT82XoX_RV9bgZk(}`LS z_=1sV+9J1T8Km*Z;R4{2^g7W33}3J>i09bLAgJn8<7UCwcreJ(o6ARj8)OFqgRwA| z6Hbe}N`^HWS_;BZq=&qt*z{_82Gi$!JSZ3|v^bL&fX?gQC4@U0LXqR~{HVNv1CK(M z6))%+)HGE`gDAl}sQA3nUdz zB=~>@XmN}jWsnxDQicT5DG_%?_fZ(-g=wyM(L@*~slLJxOGDs3VN7c20_4*|fFXMp z2%Zd28VK-$WV-)HcEHCEKQCht04`VRTfpEw8^5fEUEkUT^wO63fL7q;T1jO=D;qFq z=gC7mzk&}~XlzN)O&FwUT9s_JJa5Tamb2$ft6`e8eCHO1={Po0y>OmS; zjYzB`9KJa=w(yq8jWV*Vug#Y2Spi|o5*}O;PHnGmV4vKu!Ol12GnK~$<;}+ChFMvw zH!O&^=KeJ?(JW#ZXB#kSUeCS6A9{`JgTG_l@0s%>2Qg*lyR;mkkB|vjgCnR*XpW-? z4`26YGCm0SvHYbQiOd(@?f9;S1+T@2{y_?)TXs;x_hoy~=rX zP{kL&a3RTir{6gLmyQ$f_y6&@LR^64hpMUvTA}gptAbR7)P=dy-A8v`8t*E=1jLc~ z3GA4h8>`*tT&Y(5_UYB>oyYGq)1`2Fvh1F}eM$j4LH*|TwU_bt2~LJFE=I*dA-Qv& z`XvE)=ip(2m|X4vzK;KcKCDBJdnm#8@Kmv{Epvlu}`)vP4g!hrv`xVUrV z7_K_H#u-kfswf12tF-;X4JB6<+t2a$k=iZ4%Co*da(jko=!O2qom=Iw znoUM@3Ljv~B(z$qR5&A0S}<2At_NdkLGoNqiLvCNZZcs92h6I<0hVC!Xn7g|Td=;QA0Aw*Ah_gWhh6h>f#L3alHQI*SqU9gbm6}g>(UdtavK$bt|pDDIN9F4%M2znKS z0duh%fj0@s%$-F)`+^~urUDDG&Vd2MO9uk}VgLlVRZuk`7`f810s|7e81NU}NX6C; zPMRUELOW7h2g4?d6gvmt8fN51;Ov0vY#3>69(LP}s(Hw*>47y`?q@c$yKgYi>3OBpogUl~S17lI06n&!Q9I(hjr zxbJY9ejM?XQHfuJ7jxWo7yJ4GC za*MN1WzPZRP5H09h<)Tf3D8%r_KA0;x)z=jwOWc88N$1VuKBi zu{zBe#38BG>|&E5;06h;3bI8slBH@0Ll{}cj}wPTc(pSe19808xGOj*vZg9(U1?*X zOPjRQlnW;9YT8Y;|6}KTe-AHNLhu8|4|#F?dCvFcoR>K$;9Op{l(Wm9WgjkUm29P$ zfq>SsT2sSq9z@PpNM#ba34L7Lt^5tby1F#fk# z0OF4xoja!|5cVG?9`)-VDZzVKdR7_1_>#%b?Z5e8=;P~y3;-Iu+O0-`dB{JCC}1_| zoKBYtha*P^dUTb-o0N@7x2=RAQ@X%EDs8`9Te$b^#g#rfKuL{PIU#qydj3;RPKgdp zH?mJ(m%s{@YK$0|OhBrZpL3=7>vI>y)KXEbd+ocDnttZWPl;qaVdj1G8$EccqBVGp zu#D%*7EW2+s#eQ&0q~!BiSVRvTq2JK53M+XN-E%VVh2~6)w-0Rb^Uv&vy~6|>j+lj zn*@f?PM5ULGEzy;)xZDG!Y|KU;OO(A#kPbbzt3;>=tHN`D6gi531I2I$>*(-J(bwY$be|?5hNDM4G@*K{MjkYy+ol0C>wL&>m3+R~&g}F_~Uj zGx1jCUfIgI=a$V@R<*zN(I=~gR@AMccH1Kx8`AcbIjs#FWN;vEi}*q|MlcxSA@2Xi zdssiVGQPn)%(<&|W*#v?*z8W}L(kki0t#sq z&Gldg5kdybqRd^1?ClUk%1=2I{YE>-_T-Xn(?F>U=o*zBB@54zNoX<{ZIHHYf90Z) zu^r@fw2Kc17m!ZT{#oJ)PqhJ`5XH`xDVctfgO>4Dn@O`)b>uWD{{_@?~{vT5T zm)Qf>G#o%lsr!Dj3)rPiQDK;y`s+P?ZE6qv`L@wf+6f=7nTsKsj+Fqeq zN$6IT(gCIlmef75*Ptq6n{aP3m1>rUcWGvg_hq>A6ff zEHSSbOwx1`m!h+>6l^hZ0f}3`Z8E3DCX5$)c#8j1OeW{ePbQTU^wFa4aqm|G82XRG zfoYIMB47F3{O$*lyR1G-lzg|I7q4oucU1{G$5G&1sc?chs=s=0JbWZ{BQ&{%n@$36 z+yj2A>$LQ3`_zgt2Y>rs?LvkoO65`=XDz>8f!E+o&fKTg_&%*2v`=`-P({tK-S2gM+7sWpbU28YF2VpIy$>2;eGvz(46atFAhj zzeJ;t@$L&($6x)C0N#JNoGF&lD-ET7*#JK3G#{Ce>wgP+16ypvwQ6pql;6t~wmEd2 z_~F*Qw|;j~IgwmdreIu0l8XPM^CrHALh~Bs1r!RH;H7!S4C{n1YWSAj=5`;Wh&N=~ zDuNGN7=>hzjxr~#;v$OU8?7X6oPN(XmbLNWhOL!eSP_U^rHkVMzQau%pk?V9OvZ7m zFBE57a3DmRjW~pEDB>Anjhe8f4W%a({)Pu(Vi#-;$UK&cS_nZ6_sAp`JHyN^1bE3= zj$W}49hOFM55Vhz=;i7!Rj|lox(*XqT}ocu(EaC*@?+zWmWTj`U()hE(6O7 zlT@RJWmKz!JHl@mW+eOwQg;GRi3yHC1FZ%%Er2J6(P)^Mz(M;d!={PB3oT+CZG;x4 zJqK@$Z4QIc$zTSD@}lHK762^y=6_q@@&a>z8`-jal#x zbPIOQa>d6F2^y55^=jvcv}0)vO+PHqFZxxda(E_1p@HWw30&v6_sgTXk+~q3f0-0~ z^D!ZPiAIw_rZBLqEmi3#hoEuC4f0s_jYeh1h|bTnryK#Q=Y#%ve#78nCO`z~BGMV0 z=M@CSa6peE96OW)6(zl(p@8#E`~ZYFzWjXwILbG7YkvTIYujJax}p5@vH)0L z0ak{RV}qQe{;v#S6}5fJUoIellsbSRT6e+TT5-F$%^t8gM+$$hpZWTQ>;Wg!iM$ZF znXeQw6eJ)p7|X}zi#xUAPH}g;+Nf?<@m4RDnDbChuO$EZGc|=JhFG!){EMZfmue5V zaAz4Oxl;g!3)9nJdZyW&o^E6^_)}ivZIfa;2mPCGR^Q9k{w?0q!jhbiRVeN=1~3{63ZYf!d(~cI^{VoS)1bgW^u%fyy%o6 zECw=A_F#_$)t@BTJ)dyKQn zeQG-Bs!C@91>k{EHkT3A|o`)nU=uj!64KK?K9@*W)j z`!>{hVt-Euu+HB*Cq}T27LX29K|p;EmC048Ce!u8az+Dyb2;{apFQbQX%un^fnOXI zU{>;@4=uK~78-0odV-}BHhOBb&qNq9N8#EwLz`bF6tTlgL#qg=y2-LKaoKJZhe zczpD}3V*}=g*f8}8L|)xar#PxGVbN@GLBsm!T=3B#GFA^q^;mI1S=p6#mlO6in^Hc zHs!$^6>y3hzh>G}QU`m)L_;DOSc`V2Qb0Ml>2XPSml+KySFejNq4|wcsk5nW&}pirj2Th{Bqxnxa*jdQqttx!Yf{=lT9j5;T&4 z-*FOjKIi$qJdZ5-0$&7+c8I;Xb9UX$k#ctnVF*%WQuh#gD^17n8E0>|rPd z(;C|1;*SoK7fhBY>lIYBt-5SDd(;sC~r&n)PQ+JG;#^!7?-Omt0oagBBcId^TzL z(vAblSdKjP61cz~m`Cz|*%zZFA2clM%s5B^xgarvkfdeommCJVO)?pH)aMVzxO60r zlajOG@G)o*JdW!!a|KQ8-`SBVt(Z@bbDP*$HG)Y!BE!y*$#GpbB8Cq#*Pqmbaa~J- z-$tCdLM%2z-1P!x1XlXyX$FP;>} zCYX*C&~&0!GeBE@TYTWmBAL`!E>DJn2`v!_2CcsU4M6h0`}{~6u;BAV$A#;%2Mhq` z0APw&()R^>!26|FdpT&}&r}mwSqi>O0H1$bMW3XZ$Il#P27pVf5<@^|vedx&>>_Ug zL&4wOLV33`ElyaR!oruUbi!Kx@v~DYDAp2w355mSI3i{CBa#p4f%}{!8KF#8$4bS1w#|+;P-@)M1O@MAK1^D?ST>TTf3o4=p&D5GDcIf?%d3Iq=)< z`{FBlaD)$iC*N3Jsa2%YO|Q+cYFoe^P2q1EKKP{V%d0>eS8R_@Nf%fgBS54Z8{kwK z|0@rHp}D+@s5r#Vn=vejt5|%p&8qEUwp1vtPyqwLkDqq@wOvMw#o+Py49z&8fKyP@ z^NYFS%EH!>3iQ8gA&~j)6qG9Pw^yZD-hFwn{P?5riR03!o{`9i&2K9!MM%{7(ne~b z`gUXX{?T)UL;lKqbrt6k8R*(F-r^qxz)ugtXJxdDZdhyhPlP^gKlz;~;QY-+0GNEo z`JyU8;~PCWv?e_?DOG#Md5MeWqY7mJc#Z%r(`ux${vQIkR#(7T$l44A@Dzpc)aDfn z=aOk7iNmPXjDuxVqzoek>7l{-=tdlDqbgd#B-R_xaa%p`34P2ltf;`#%C#i>ps3|Z zmt+a!299Cz;ZZ)sE?wSew3FdSjU%pm*2Z-yVh^s1$|jX3O`X=my0+OhDGt!4PO4$< z2Gi^VI=I_9$rdozfSJ%h?TbrR1`^U7T6ThIz%fY*cXbYSuCGHQ(-)d43|+DXe5VUM zZlecuTQ~9C)^n$uyzR!Vj5?C}=-$pwE++NL1T;5*dwTEO=>=b96IjeRXr7gZ29|y= zoi@1p>-ByLnzlLHz*3+%?R56GamlwOjr-GW>De|F2HfIIx79h1dFy097(7h_rY#a! zC{xkmhINdFk{oarXG%I}&9*+c>lE^Wz^!}=hokG5{!4dBC6Di_h2R#BP1iA)VGN{g z7<(WqNiBV2O7Hf`j;|y%@Dm%(5Wh5rZlLic=b^=j1F9LsW;yyDSM(lFt0e9Ul2%1A zxJ-6gKf*ODL@*gD&Q~~2m?V?|;+8|w7Rx^f=`h4O001BWNklieb~}zMvUg;m>41&fN*1>SuZageHGzYUR&I`j$|@2I&!c|OSBJv&sNrW& zH{ytpzpF85-54kvaroT+hzD1hIT+WOjO6e;;>`T@fRoh35rex%x-X`Ce5>?}4*DW7 zyow_>s>cHUxZ#16rI1a6Tt2P`CxPrFuIrK}I2wjBlTxdz5{Rel4{e?zvY*KZ(2V5c=F53oXDkFQ~U9=!)wE9bk4xv;w6M&G5`0) zELkZ%;MZN?*E3ksV5PjwP_`CsQns$ly{nwCE?nT`6v-6)*sttFBN1zdX41_!k`~hLxMN)EGX0F*gT{-<*F^O)XUqcZpRET4<|+qVLzT zGz6CU+*WF(n3>N4z);~2zx~&>NIyLUfY0Rcm!bkLZpq5?mY9Ty z&(=n9gLxma7tJ)J;u(5ziEXL)Q!g#dU`NN=GWwh~2!-xFm{O)*A;+BQkEq*=Cp6bhuPIIBJr1 zt&8L}iyJia>KdOn^5vQAFc^)FkjZTJ4yybGcAc&AoaZLtG)Ji$#cG;wh+9WileLE& zh6H8;5*<9aTx>FNsEUesaMEREIl8NRP@)-da}SHw^rGw*`;EaaPFis%n1ff8wmm&W zYFDrIP7ha%dH`QMPA+hrmqXD+GtDNufoVXPURh4S*-H}+Z}+E82?cKUaz@MBtjsx@ zo!)dhO^1!C92bxFg0R0lIy7Fyt@Sf7#5fYjrXwnC0eUvVTNt z$yw#%fjfy?W;k#ixS_9=3~wE4?W=2HJj2-RvDt=(x)wDb&Em7#NdkbuRnt8&^fuGK zj94|}hlDk0+KIdB#nQ@7^*dsBD{Tz*YqyNB{%oQB2FufS@Rp!v&lm?22dA@SB#R|z zs^3wDp3=0EonH!JGfw^M#hB0Si%4v_jV_e3t>kd)4)LfIMa&j3ZLn5x6JQ*3=!U~* z_*Q|`xL=GnIH466Y3$I!Y!BtIPmirawE9OG0?f2R|EfbG7!0oe`o#WOj{(liEtIA* z;O7te^?(k+%j&Zcp)xi!M<^J<1-}?y;VA(z#RBiNIF+dp58l?KKCH%+{RycROVR?U zstwWTs(*+OrtS^Ul7l|b+K{+z0He1#e}%jGDFo51X^*%H94BfyrbXvVF_k8MhvJ4T zDFL^vH-`v)>SNZZfoUy7Bg(j#b{NL(&fjky`bVlPBbkDx6_vyhR`)1<_krDsxo59l zJ=+5;cVA>mub%CuHgNqJE>s|g#R=;O#McP%pLUBlJQemRVmSs4istv{A!GL;sXZwoXkFl&xM;rxsLzx7URC$ z?ucZ4iPr{;%Un6KNlDtl1%Zgo&T0>r^Q1a$rv~w7V= zxzG1G=Q+f_NSiULey!W&LkG{6BB5#Vd`d+=ptWdqa!>8QT zx9j91sp3lC4!C%4X`uAA>fQR zCw7slP#~YsZYNwL)0K}E6mW+M#0)#tAPWv1^Lg_Hr-=X-2$mlf zGs(aCjXVPB*oG7JRm_)3`BaM)OCikyj$;{LJ{ED3gp|yul2GEFR63uJ$Q~!Cy1@`q zk7f;~fokmuYkX3QAfyN+IGv8Q2)t?}12_!uBEL$8(vjZ?QBKCvEyM*U;k(UALFNvO zHs+W=BA!98v^f+q2GA6sBW4~+@HGNhKO}G~g<5N>CD6 zz?e?9ggQT^D=Y`$&OtC?r}E=gO4I(1Fm_kSsQh7V=Z2f*Va-Zg!&I+Z*GJeP1iDW_ zxKDLnom7^?og;o>xY$=}8gOfP9pRNV0ZbcsrWN=WV%+&Xnif9wm2`M*xVSKPC|fG(T!X-F)>lhMQQXZ zG?Ujr+c!IrZ7cT1$s9BiD{}62`uBQP@VQr&(7F8_s;D^rR5`^#Ms=t5g%bA?CJ5a< zgMbQ`D}%fJ{a4Ni@}kI6firrlGxUVd^&2LPpR{(1$&W{JO#3XSz+`}#YS%ZpApB;KF~Sf?b8Clf__zm!>gl< zcaP`q9v)Uk>o1-iK6>>I?1b_gYW$G%jsL7=yFXlu6n!xhvj6# zhlEki1Hkg}V5ecmkN`|oL4)0&JdlfF16W)IF{@@8$pEHosjWN!f@`3qx*M7zbV&es z`4g-1EEs%A3Gm>+)uq1+evYrL96`lR8GKmiB?}-;zw?apQ*- zaLCfKNXaKbAxLN9&D))boEYo^-!=|2S z{HD59>B%m2-@09@9LzI1wxz?uL_3tM0ESXYO)RYxBOQ!dtXL_5i;bhQko7eTKA!$d z0GKZIpt@9bDKAy2*jEqau#zxf>gkJSBzV!9v8ot{4IH>;Nx%eSjVpEObZMz)L$)tb4mi>M;pJiEG=+krpy9s4Kk4&gE9nw$lhN<& z!i4d7Mui0e7M=gk>B%HfjIDi{;upex`HWgqKju6P1?Qb~nVrtOH}A{aGG2%;@xvKk%;`%(eSHK5 zXL^#12B&c0=%HQg%UiA-^1%FUHQ;~}-_9gsJ+Z$gW4Ki2i9HgSO{F3sITAOkSaS^j zXH?IaPr`Lmp^kJ%golKb8MBk1B=xuwn4O~+%wUnw-bgysk?crD=GH^PgoV(CA~PM$ zb0L*ng<9zPhWvPP_*+`$NNX$mv=V8MEUWg>xF1=js|ZS<{ETsGua@YLTo)2dMo;TilV1z-IF z&EY=!!K!}7#d4%|1~cif4gu2>CJ)%V$&2bOu(skgm$y)peEWs5d`57ETb9NTGHK*- zp~BK^LN?hwb~vxVu-s9Hcz_2gL3kaMwfRKY|`9_Osu@M~>ZtGTpo6uk+@&@B$0l54JMQV`%@$j@-Tveb7MtKJ&G6O`%yt&xNkJRAJ57W#a=Yg0?apXsGOKkf2^$B z)n2T+aa@_oX(*8Z;)LuFTDspG7v6gA$~nPcp~zRLMw>|_gjVD-2m}i>GYZ^xSvAfS zq&1Ha(%c5|ZRllB+J1#_c)RYYe7)v&I3s7gsJ>PiR)5Aodh75pnhH$n{Q5 zv^jrr>woIcsGv_h(K%pELpm;(kIU8aLH+pnxO)G%HokIK4LN=>jwGSb zbHJ}RfxF}!)Bgs5XKQy?Re7~go1!LsPau#_i!iHB@R}O1CdxGBEyIY2_3Irbz1Y22L{+uj^Nizd%(vW_5 zRT;3H4^6e!pS7Wk%@+7806c$)u*)#u13BH=R^w$3yGfXB5WH0Rda!%a($r9d?m}tQ z-Sy$QA7tDgVSm-GM$ZF3SLY3l14i?VBHDnjPAQpy;PyA(M@Z+l z8*qCtpD_zg6=<0*usX8_5n(C*nuhP|daGAp+}{3r7$IXwpZERvSFw*K2fHtJ-R!z} zv8#*V1R@!*Z~pdAv$F?ER<}x(Qho1erG}&O9+(N=B%(l2Q&uST`tCMq&3l5YwS(Ep ztOD@T*?|v!BxhF1ujO*l{mmm~z<;R%o#aqf=#-k-T+45IS(ZknBYAcAUIOs+m+yT1 zrUhWA-MVhQIKAAMm#0>vqGB=AibY8wsms61F_BT1QA_XjP|5MuWq| z2MYt1S9jA@pzJYZ*9e9ol|_?E=pwmt$m8-lHf2pGsOz=6HU)p}4vj~03=KI7R)5$t zL@*(-3;1CLnp6VqFpaGyYxoH9C#=^KK%@m3b`J+Mav=~b2BLB;B51+w4vZ0a6!Z`S z>}pSJEZj2Gh|Y&I)~VO3C27AQ8zA*sTIW1z9> zT|~PWk+w)wS&$5$|UNE~ZBKIv?;GNfHZa&H(R+mfd0MWt1{ zn!1Z=|Ht0X`!$e@nqd4pQLy}+=Y5|aIDsiwh%^De3Dj6Vx(FY@Wr??<3n`)EEIDtM z3!$)Y5Yclaoam4j5ERGPn+p4;!_$$_bYfaidpd!6mY$?^RI7o*Y+u7#S%?6cpsY`) z8ScW4lbC>zMWvJ6Ni!kENYT)AG?`3m4dG03MtE(K+>Mw5a11UysMBWV%}GtBj3owU z2%rS8fn!o6qcd6!tVvljNu6oOs4t9a%fePVt$aI{2$@vOL|7w0ggpy2pTrvlEe{WR zfAjRHK;bZm<5%o}i}TAYT;!zo3FT|JKU7bI1^STpLHgdzj;)ZfC&iy zY=3WM<)4Dxi{%$qmcU?mb4Fi52#t!N^H#~Ol!Q$cIWXO|g6FwvY38-6-{I-a`En)h9;TF^WW@}L1JK&eB=T)nydFsM8~^_5@_Q}dfxbv`hXv5 z(ODn8h-vPF}_G0kvE{0#D_c%782Di>u}J;5LBy?c6eNg@Y6SE zSJ%;LSq?Jo@&r}@8syJ>YzwH#|)xv5Yi5cb)d?(r<6mwx)e;y<=7zv%eLN7L!nLNJ;7MS=@(6FRR(HD0r-T2{X9Ri!HDmEH&^kbclDFQg8(ihVWKwQk++-~6(Gp>GGIcS% zrg$N!V`}7Ik84Pl_I4qQW*f}Jo7P~|&#aU;1Dd`e_^S+8KseqTA4A$Kv{(&CT>{g+ zz40DK(86zfyjSCb#=Y^b%^rM8M03b}YWHpLB6CAvT6prQ94x3mzD)vkMD(wt8UgFOWSCZt0USUZwPs04Bw8U>mG zYhtmq?DtN?o%Y7YcCw#ajoXMR^9dS}W)VRH#H@l%G)JROjD-fzZm9ZdmUf0#<3}>q zqgjF3e(<@`xPgyzyKq*P$PnAs4YXYJFbHO=^2$^Jw<-?T5kq-G=`W{`8)wmAL3{g! zAve;H)PLf5oj~(D2=oGDo*?nhp0UT?dTN0KL7Zvz1e;O-TuT_V$B*XOgHDeq@IU+55AeSppxkQUfhiL^W;Jeckfq~3~9Fc_ZRLY6h1_%xCT=~6gC1_sP_Fp(yV zLo+cV0?s&x!pSt!Dc~4dOsKPv*H~0Tq6ycC8R!)JrIc`BCN?-QGaw{5iF{eGS1GMV zRYHH$gGuc~N+!3GQRUj{nChPi(bBKb;7n4`K4wPKBvB^uKnXt%kytGpJ(@^QZeaDmx`7&D?oy#tKk;T312#wA$f<`f=;C=0<`?~zfVGPdAMoA^WeihumbIn|Xv|3Rs!R9oEg{N6 zkA>X2HylLJ|CrS z0K24MT@gymVwmsyjBzy9s#c{85kH5Qn0^Ii9~|>(EtpSLSboh)M-HuS0pGC>!+?$E zS=)Z!Ze%#v1fMamT#e;W74+s^Gk7-JNlm&KhHYMxBd*1qVZf`^z2^Z`n#;>3uS)4A ztJ1Rk2G(?LtSac0SLc4$*=b7nswB9xO#oPTz-yTuflkCrWv$s|u8`BJ3jxqv!O1Kv zt=YMGjiNlivbTTf!_Hx}VQrnAo!t+gy{SsMvbI~KG^1jY;g}fO0L(f~0GCp}Kf|O%60z zyvcQPvNVKJPMg6V5+>oj@tSy0xNeu~pX264^i?nQz-)2B(}YE?XB%~?b?adxKY=mZcECb|Tj9O4BvrPm1xcQwu^j#V z$KR=ygDoIf<^!h!=e{$LGJSGbZqeijpg)qc;h8qzqpl_ad%Cg#%~qM-32 zQOHp50e@9FP0t`%9E_p;>Qd4#t!VHI43C&Wv`^#t=#3dM+7uzX9V2FSrd}ijS%h8* z7>9jiJvW6XS@NbPBl0-kgJ$8v5kXiQ2nB@6#Og?-h_@1&i)({$?`N9GSM3e z1kb>4BqaAvCP;r)Yf^YpqcOzVQGs0OArAUX{)%WH2% zQGEf?p)eZgkfvS9%?Q9|gz$zETS;t5;l$P;jm3kZt{?xv2>QMA`zykL%Zu8UJ5fd9 z%ld~4m#bIJb-g+@_0^-d!k|gQ`qAxM|N9$*NBByP`Z-5FsS8Edbqk9-E{bEznJQ%R zncS3SL91?AzTey5uLAIT9+=z}^nOwr-4Q5$d2eU5z$`j5FMurcCNno$(ADtjs5U07 z2>?I8X+ofXY4*U^j)FLTV&w^=Tw1vIgd`5r$+Msii5C1)J5rd+tix{pJzoJwDCj z@SEz96nR(}rmjGp(ZY zg4sq^$TXJX?Qi#P?Y+A4;rMt}#MCza@ZWFbRTO~bH88xu|7Yv`f11wkIDWJrNWUZvZBxRvN*Lv6ve_L8 z3}N>S1V>te#bD9ZVre51D_>$YG}{@;w0yW#)M!cpS`x3cm%$SZ47n7JivpW;7!H|z zGi%=#*0@C@nr4E{0|YJCxKL#Rv4)Hpct~S9pu|FUX#%!{>-GnkJdY1)=mtOx_^Jvk zg(Or@RA>}4X2_C)8=kx>KEh*XpTv;0c32wM-w<0N23 z*zYQDX!RBZkiFs2ctII6S(8LiuFG}V39rCwa)P0<+4V4)ABKg~(Pa9V5^9ASmUDsxD`TeA*8gNd zpZ~`BH$VUU((IoeZ0@c#m7cHE)}Pb2m(+ODuwuDfdG<;f(mVKoPhXn-;ET<9{o!-x zR^BOf0-e)1WxKLfk`n=Y z*=a04R7H5XgobZter;uK{`vjYKiu!-^y8q$Pv+$@^2o{L(LNn?yNaG-(GrFlK*-9% z*5wm$v_?ES9}X%NzU^VKjOgmN3%QjFwgfsgtiz%cNkckX)F0YHNxK#y$<-=yE*6VG zE8AVR#a5tY$dY@rjOSE5`>cSfufX0uayBe&H6(IFex{!f=%I!6 zrmdm$EseVpSXSCQE(F&ShMOjeQhNydaQ+IDQQ64oKE-jnT;^Z z-W31n1n$>;uTbGs7nvMAW*Z!Z0H;ZQ9?;gL0jAP@T~r|Xqd+u4&{&nC8+0XY2ty80 ztrR1dgIrj$^C zb{+Gt;A~Pi!@^}5O~(;LhZB+EbrUhU?wuHodqnUo06Ir3iNx6A8d0kNWy5O;pSu|LJxKna3Q}hyM?~&dy zmFxhJwRDJ?FQ7OmKuGoAVQPMdRSXRS&eA$K!{m87_g)S^5(s-jBcTyu5y6q0&Z!tn z5O`Xvky!RlcT5lFPIOF9v;RFTH|b#3EmvGWtk=V_iP)MZ9!uxdIW0m;V1we!;2w75 z>za|-_y5|Eez3YaJNx&4{N?KYSNr>Wd(WRefAPr|FO2OMRm$eBsj}CS^m(m9y|T9V z$^uwm)Qq47fUh*+8x7OB$^YQ*D~LWx5JxjXOCa;WQ)R%LFB@l@n?h>u%$xG*pDH?5 ztDCh-z2P|Z?Z(!Yke7v(`Cq=QLAv;kPN21n;T~Dg3k_w|q#HfFQ+{{ecCZw`yJDiX z&aDXA%bi`Bbe^Em-loZz!SsApUUr=YP8jwz`}xqtycWHxja1$~ocNIyxoYyQ49Je5 ze(uB=+-XG5>Og}0c7n;eC_eDMNq{z~SL+iT+$t^9d`c8on3G1CLi@sI&7!BLJ_Y2T zDFZ&bK{%Ui9IWHjR z*i~vO@MZBXNZWXzV_$wDje1p}w6ZMNQzD#uVU03|zs+8H`{@A{VC8jtt0E_29QC8t(iava>sa8vn1Zfg?OvwvP%ef`K7lH}f#MkCg1 z3ZeeIvmnSRz+1Xja>|0T_LF6Kprvv{4i~2(@Y-;c<(8bsoIq>|tT#&6?8ove5dJGy zLF+3!Yubh+0Q{z^x6hI~o$o!X2aJ4v;q31R!zNjO#1(W~!dB@5Rv9#yI;52fE&)PU zafH-nY`~U!cabf7gzrLw2}KHc7#^!Vg`KgGZh4SV?qj0IgBW4h*SOR2AX5sjvzBvCH%We8DL&nE*Rzu!NA*@$os;lDi;B1ISZ_F{~#U!pol zj1FDauEE7n+hyEE?0wt1V>A!?yEQS(9~F>QbyhcIIYd|`sgzLz)=@!JaJ73*SIF&} zFWKGJjVm~&-NUNcY9rQaj(Ic{gY1R+SA)#kMjT1uNU>So5yM(r#ob0d$~{L1Z%t;G>7Aanq#L9iO2-)3{YUS&=UoMH4sa-Fw8S3^>+8cjxsmy9Rk z9r1~THYZKNZikbFnPi8uWudgme{psGKTY3x9A7OXg%V=nXgCoLDQ627#wBt>Ez*o1 zjwL(r7ZP?C2pk6VN^Z~*N(diY%fW5E^rOR~LpH_SiQ+=cC7YPL5Weh&ZZn1i<4=BB zV)lRB>+$*&WLFj14_F!{Jm1gP>-nX~8y1!u0bYB&nk*Ue_P~;Z)E)T!cS1BCM1me+ zzkV-S7w)j|(g;#1lCiv~p@acP{242frfsN@3cIh||4{n}@g5<6ZWt2i1$+J2lPopX zP{_?#TA&)jtd&PCA^#`tlYEVq;2rX@B10IJ!X$24X<2H8qWxD(fXSY0&+j5RiWOU}w)rtZJ&#-;9loym<8at@OLm@n4MZLg`e7Qop%bO!)Ec_E>JM%^3hr zDtJ$2=ZEy| zp|<>p?vJAFipToTqM6;CnG!O+X~tH@yBCDzrDAj4X>-%alrdz6&er_diiB>*2Yev+ zLMt#!=5v=uP9lcZTxb@;y8Ts+w92v+ijVx2+M`@6juI&5n;zAbRS4$MVlX|Qs_!T# zmrXFq=(;EdfE8t}CGYQdy+`{>fOoqIGijA|9sl~^-H);^w4;J1FA|7oC#`r;@Z#L| z99TJ-NC}JyiJXipRK{-Jpl_ zfxdg-?dvbclXIs0W3R{=W+7!H7$V2OPeTto^C@{I2(lpMjHQBpiVdj)b22Yc2e{8) z3jq)FG+rKMkM6s5ej&k~D^3Blg@YU~CnUn$dAOfMMn6bW-7x&WFRiS(3w zSH$9m8SP(GWkVuvC9|<@8NdCgak{y6FJxN-u?8)*btNJ!LDN1>o6Nt;PgB|k^A7|V zFy>#)6{-`U4A^CJI9vy8R}eze?we)H1$*%**)^h)J+DIr%i3?GTVscdK3-FOnPo3| zmA$nS7V-)U{x8m8yh#|1Dh|~iVkumUCzzZ`VY4;Dgazr2I|X^m3d&S{PDnr0qx}u@0#|%i^+( zqen|-vuCpp9x8Vha2Xphi{X;86KI`JK#qy)P{S|?tQMq_?1T7-k$jcFdY1Y7Zq(|+X06}%-H+DpfdQ(7&;RNtpcq=jo!1W7XV)bpK|K&l%F^~dibY& zun?_tC#o!8VUZAIs$_(|!hdrhxrM@*Jp)uNT=WU9c2YYS@`TZX>{B_`gHR|!W^_12um%ZPK}6Ah!R+vZkXPl-lr?xm0$|>t_l}@#Siz0`uh8B* zenil!KMuMhUMOe_>gb@Cp|RT?32P%Di0y9>)C`iZ(J(Y*6(NDcCr=6#Gi!Fchv2#` z8a9dLcPPYKHxdjA6bt(mlqI85o}bpE7Jrz8=ny{Ph&D2{_%t1wFAD)yHXIDmRUDSD zFAUx7A8-e=c12ii`_{niO-+?eO^54G)z{az)^~LjFEws$)NM5XvN!Px4axpTUUqaCaJ@slMnr6=30NNdsjH(E7zTP_zPbdq+``3;t*8FhiTT}Qr+Bl-qu=d>ofGsX zT$nr7>esHBly7&+IkdBo@iUv@FRm&56~0@yPl2V@qvE>8;^LphL0hxv4q?C_)m~_? z%7jc|8Nw(7BQ71>z8^iGP6!E@Sy%8LZc7uBz;QIyR~ zr`q>|#$dpDHZaV|)pbfa=GWuKOnN!BIX}N?tVffJLQgl1nW?jjaj-F#>|bEHpCEBf zD107!g*bx{uCSvkQ%kZ2$gNk}#{u)z22X`-xmj80qf*8I$8#wEK_p9A?~{ z>OQ;3=`GdYJ*8`r#qRE9g!DMmg(9!eigbQF`t8e+W{sk3A}X!4$&#aKC0`^~pGt`birNG&KV5Zy

2b|`-xcs`iQ^;1eHURl=Y2mO!qJ;Ag^H>@GaO z!iXItueh{{flOz6Zl9h1SelX!kinrhhxLHbGj3oMSL99R=1_#h=Uio%MG%%;Wa3;T zZ^@#!>xrKyiwP&)b--!%i*ePuU-kA z{`Zq7JFnU@eZVka!QYXe9zXo<^*59r&fU6yYc4(aXDev~UyOjLMlPJUauTq&WRi)v zczZ{aD2KINk3k znvUcUiZy`aBtz#yEB8$mStPUObP53fx^cJfXm8b<(Piz$Lf7pT1+x=ACII}Gtm{<* zxRt7r(pDs0v{qGC2?I{fr4sY;RdZcXEN-p~VCuqC04A15%-mRy&kJ{*pG@6YV2*EU zCa5Z>{_(gC06u(%_Ibwh^2C^Ys;n&NNi&{UjjijZHzv=&FmDKbX38s+Qvi5VSmgW) zdM*Lr$6M1I8(kC%ozX(S!OC`Fzyjlwca6^y0*#yygo$={FBtMNjT?f5go@skJINS5 z8(<@P0T%nL5~8#rJ$f}gomYHJskxjvw4+Ez7^PofLmK}dTj&4NbbiP2^$ShEn8ud1 z!6IDOk5VKBF+;1RdUgHf%x*|xOmGH5!$qQyiNsW*a5y?Nb`d>9@k^rBoE2lxTec-; z(*qOZJkRq>H2!qk{owEW8}@p<-o?|~ffm|+_&@^b^YeVYo?jLV=L_=!w-hi;2=1Po zLQ+udnOu|~d1AcSQ#>i(cw$PxeNiqKCd$QPxuBM~@kJ)kS1%mG5e);rxw%rayrgj3 zZl?WT?XR*s+0!}$ZctZ%&#m+2KBwL3*KjL8(a_{drnJbn4|W@HqSfjP2q2?@?xY!s z&}b*bSI(9q`WXQgqeOe}7N68@ip&ZbpWx*5~w&V!B zYM^_8Jgl4`F69mKSX1+v247p7u--^p8!(DPSdOa~z$GKPt$DP*B}M}<+A2Y1O`(h^ zGAjj+L3Sgqm=a$CE6)b;4-4z{1!G4jR{)58wJv!&h!(nDh;H6D8jRH=W)^HcB5ayC z=-?e!9y1bdULnQ4v$_k`vLsiYSjtEqRdh7!A_Xh>rAw$Q0_PwJR+=IGr64r08N5>q z2q!gG(j~_v1*tV(=~I7{qCCrt}B=&y~tG!&A8RfVL=q)@6u3Gb3t0eia~Xs-yu z>T+O03c0Iw6{aI-^Mb=mj}=mV73QKUZ*LbSCED495;K+dS{|>K#t7_M@oL7)R=n4Y zn?3Qn9-+Q>`+GgU?371@{Kos!R)09&3#E;RtrJ$LU%0PO-He6gc|efYL#rT3 z9cd6)*z`aeQ5Kn3arDmW1m=_jfO963poB0HrtF>~qDR6*&8PWXom=+)E=dTYN!!ahc)LC942ZqGtBn{ zaMh(u9%dpvHylZ%O*e$9L_&@4QEqr%b8Qc2mrb z+U3obU;X)waOs<@Mc22k{$1;%M~~JmtXSA4+*vVtLHP6D3Ip!wJ_dPSw&T(2n{PVy zZusKj58po%CVlVTtJi;fefh;7pMJal+qt=~A3y%)%r|e}zJ*TTx_;rpRyM;oKApM# z1m;_5VlY7*JC7a2hV*V5y~Lv5G3WP~^p7m+Bb=pX>erPk;kxX1AVd?Vu@oPJE%Zmo9wROp9WJqwOl)+?SDGclXO@CSbo2|LqioA7NS*s@1 zI$9Gxt9yY6YkcfzVWKoifCXIg(#)P2LPReeoha?ueP!yXMw-p{^psh!q8w*#Oda8W z4gd{6^1m*8T(iYg;0~Uy#A|KWqJx=}=+4WNlZ#q}H8xe;eP~K^MGK{#-R1L~N{u`- zhl_{S-g^D$;K+lTm8(|O4H}vGXF7tuu?Xl3H=RUCcYjR4a{7{-W30SqQi$)-!kB!A z^3+seY+|ukq(p(AkLhsf*N1<(4*(u{@M!&J^LGh9?qd(uYa`T}&2=UY z3^kUL?SF);oX);Zc`*$TE@>CS>UQ?|y@Hg0Dbwea!%ld!U)ih;$uz7Mk(3`@l?@Pf z%F#~ZGG_7Xs-DU}3(#_$W<@iJ4rtJ1Kohe9IW-ikvP(r>fd(X2DzqYyL(RfYGpoh~ zj8dx!G-mOe6F%#t1*xS)o@@3u<<1EQXYU(ma?(uL)CS{iYYCu+PBr9&_BP@973ypv zp=l{Z2+f^TtYH)}Rhyt{Gm(=mP+m%qS{icH4vxl9NXN9LuwJlO&^gi;i?pG925$v! zg$qX_qm%^8BQC8_8m&JPYxbeXQid!a1%O?&CBc1z#+Fon#}^YCtYOemKvytU*TS?G z0=fA+!h<8hdICCXg)b)sbA4Ele9=g)22skHv;&x==p-~*h;=fUmqXMroKNo3dIlxC zQN+wiP+C6S6(s688C;Ge3lfaeH<{1Vyr7*7QJliGC24M!AhY1_u4wWX4mvv=3{Lvw z`bsX_oI-}FerEq~>$KaTx$bIPmHe@IJGCgOiYREWrexW@4#S6W{W7I?&`Kx=R9CsF z2&SgN5uygw8`8a(yu1hx5b_J6stF^c@4D#?so<(heH%0(dAj0O$P@R3;-1E;yVY=8 z%jy;8+oeg)Rwxsq842T2Z>Ikgv*@lkyI=sAiF8+-{y`?uK(6rG^a)EFkTQ*T2Z(EI zL`)U7bQZ5c7+U54}kL2gV&Ag7Ojy zcf8M)D-^gxOBp^uaAmg}HXPW{VN}wUu*gB)2}Rs%2GE>m@56Hs>_uV*jL+8)MrH%CGlRvYSURo{x%<#MT zR4u>)zdF3sI|Olr_ockIA-9_}_)5jln`+iq+(tC`l-&v*v z7}u{Oq^UGrTzq=bWmR%&xE6&QV@L8-9lutw0W*R&A(Zb`5`I_`+-l57-S?vVw&pJD zSa*%8gjNX)+-q9n2cQ0-c=&?gS7CgzXV0QmHWtdedx}J7PZX4B5+WwVQuv_&+?4J< zuihvMyj_3#=HSSRohxe+K;4f?<{OgxyLm{yfjZt$&G)l762yTWc%q=r`6_V0xuZ{{Iju|j$c9_`y5VN zpL#cqv6m_YKZ9i*B+`OJ8*iW6@1SDP@6VBBfUOf?PT8m)B>XBRoYx+ZJA_iE zQi|2WS&>P%Gz5gho@;Uftx9o)`8Jcx@laq`waswhmWG&o?L$zPxpPZXs#*DO4heL# zlm0=q8)5WqA?J$l4fz;hB`gR`RF>c|Gv+qMU}7nS|3(-(yXxD{2mz*jVKn9&b)EG= zhl!s=g+<;Z3DJVVJ`;6C8B(7643dFq9K$$|Mp0Rf`XaUJ0+uu6Beimqr!QFR2g#{) z;WaXr-(X%<%OpJC5iBMet5z6uGGA+=t)i}^>YfFSlfWzmg?W;lQCii4wA__jS2V9_ zSyAIjit5oIv~Gt{N-Hw61LoH~OA5HVlTmb^U3;^H{bB-kXa=Q?)KagV{sqV}ebZjI z{cE?w?$#AA2uy2(T-hVZnzds+Vmb}*R%sTr7uTa^aG?3n7 z2|^=)77*_BpmA=z3-#^yc={1M_fw5zg&O;qYixUvu3T%O zrG-lIeyB=6w9t+H09n?O7!qAVMpH7jwVa)!{X{o?yU9N!0C9ayjZ05F#kH@#oyklx4Ry^7(zqvd-6qxH3~Dk5Z$lBzJu z<0jHq!Do`7JOY-yuj|^|uU>t9^myOV-uUqbf!~f(r%t_ivAOwT^S>`9x&@pCtGm6# zUJT3C5IUcafAY!Nn{S^#f4=+0?yKFGFLy5O?EL4^)2G|dpKzga9^1V;szyaU!Jh*n%*FA1() z2IpKa3MeD}>0zM=@6f%~oi(AY@j6|5l!3ljka!@8uHD5Frn+}$XW1k8`0@1mc#%T% z$2UvscjsA4g>DW2@Vymbz%v_98j=IpAtx6wAkSPA20RW-)J@uOhzT~zrBD)nI*)vC zgqvNS21{0X)yVti1iAnf^gRM_ckfYea)B;rs-XG5_3Pb_FHHV%c5!|Ga`0#Tm7?G; zO09JSzRZk|^Vk5-&(j19Q~Nsg1y9#z8tP~P4zg_78%#2BOnAKa@2z~pv?CV-yi{-z zY}7(WaBkUz2Ed%%0-;q--b@X4li6rM+XB|Ng1*Z+v$==7Rz8<0sgjRngFS1+=aNw` z0yf%nnmyz&GKB*x-X2ZpHP*ivY&+oh1x3~zJq|dV5IiZzmzDsy<{ZEnk7CZMMqmwq z9EmPz4y0}A74lAoc&n#%HX`DW5kU2wsm1O`&NUqAYmY5c@p&_^)G&mNG zg<62Gg27nsqLM){8-^p_^=K$+gVU%5D(DylS0KGu`(799oqAATUw=I&&^cv;OUY&< z;bkPH@LMRQ>#^L0RLg^AhDt!O$B7NG)8?zMM2eQ6>X;8TgdoR=*6^_($>!$*83jo2 z6(M!QKP8wuhCpa1+(xwso%8@yF_uPVhsTLT=fjAv6#Vo6V{gcfa01uD5Db5>uwegZ zwP^hnC_jAC$*nK)HfquS>-V2I$*w{qQBu!U2`SdE{Ag@&zGpFOg19ETfNRcVF`(@T z|0Doeivi+i%Cd3>43;Y>!?N@sAInq?1F(`^Ss0B~t<=vh+K?)YrYe`k3PF~&N^tXd*tk~k8N28XZ{PTU8- zWjZC4OQY}^rO>~Ctuh)2!{GqhhJ+In)?hq><2O7+I-CIDp-327Xx!G?DY%zts|j~< zx(qBm*D56VtZ?0PZEelXt&m`W`+^<&2G|II#(EeoVRRwUoRsKntziYy zxi*yy-OOUbnxPs#A+$FzDq5WqjM6BDr<01jf9oC6n|@~}ybqu0?@F~!D9V~Xh|_x{ zIlTw7>4Pw>ptg+F%K4j5r_+0*>^vB9*%ORxth|oM2zG|D3fx)HS=}rL$f5IW2yALv zXnLLWF6bGQjN%{&5BFl$-92##R2u5B?j!Q$CvvT0BJOU$sQc@YkrQv~pKa@*j@qXQhIM{1B&^)d5bN`K?MVeybRYC0LAx zVEBMl7<9vdC`yIF<)gYP`lB*N!-n*6==LzC&qK-T`ve%+AV%3*&cI1#Rvs z)M0Z1NTz&Dvl>?qFOe&h7hi;EZ3R2>KRpElj@LoBTrL3u1=VQn91} z46vp8d~cpdt00&v++K5q6=g%}5G?O)Z=zf(NVfhQJK%TdDKn|%IhI)0p{Oa55hn@q zpz<7rnqDk$2do2dNBqMeii(09kCO`v&)%g9`XK18uaB4imRweWz;mU!l6oB&>voeb z#q{3ELt#~3hzpa#fZa14UBLw`*D11AWrUb@dx!sVR`|)XP#6pBL3r=1lK0A-CFjTq zzM7UGO+9vKcn9$wgg8~G^FX2_)A7$AquM{Th9b&VZ!J^Y7qcNNnw2~GDYok%ojmj zuutVuM(gWCzItYBKyn59kuQobKw-|HeN)lcl+T7#N{>&tu0XaAp&q;nzY&DamDklq z*yD*|?du^Td;IJH#uvs@V)X1IMP>vCcD#O+Bzb58Ms;AN-|rESg(X;dgb|HZ2{$id zqQ?&3@O#Dps{S#cs{p6m_Y6WNE1gW1l*2%6KLW4-(tiJEB)cbT73sycSdJox5{4y& zU#WcPlV=2i&oCMKJvn_+;a8kF+k2pK&RHx*g9ZOf2$)3F6`jEBWw1aQjqx)wpQ})! zWTF9>MMwZ-i;?NjKwP|;VAZA4eoTlYz`amQC}^#lGSL5m_a~Tth10s2$pJDf=0I3@?juwk1*oxN^wl7)3QvXG_ff#wm>3lF zg}ONKHEf8Qq-TU(7hmasG&%2TB5E!8|p<{F?Rnsh2 zwfArRz|!}}nDDh9zb(Cw)H=52(+8+8_$^6pUY|6padf(Ty*z==>xfJyO!Vb}6KbfO zCNz(*b1AL7Mk?=F5oZE!INs*};t1#66Ehn#8yinHx({{4H{$UpYiny?XRf`?2qkYCW(G93h#9Veg#lYq zm%89OLN*4Fwzp4(P?m$R=uy%Su^h?mPF}I%oYHz4;s?0$uzNu`Wd(;oFalSxy~G-} zsynca6Jo=vY8`;x^a1Y!@LutPav#xv1f?_=#l2sg`T0+^+nApRlR>ytRnWx%RKZO< zD}o<7>jSwl3#MhJAHs&3Idl3g})Rj!om)C;#6Nd8;qI+-TC4ScoziRX2<1$ z3Yg%|ahk0j2R7ZCm-YHyLAJTMhea~rE!dDYd+U-&q8vtV;6Uch)(5jXB(Cf+Q$b*q zL!2>!N0Xu z10oG36EZZ6J-MZvNs!Z&LrpLG36!!1^qK4C?VAnPK@!hCVaO=i$sL(YN2RL>`SCef)NW$N14eX&ad*1 z$8rj+P63*2z9}Ka5B#{*`Foqk=d6rjyj&~X*N;L%(B~UAA+G|X@_V(FzA0a&?S`|G zK4AX?D6nqW;07M^39&tFV+1r)Ddh*uik%OD#U2}G%zl`EQ9~#csb(O!ZkLst?P3lRisoJ**>a>Pb+p7@ z6%b7cYo#)ZAe62F%2vwMAE4207gLAYX#}-m)pj$f)2=4%f`4Ss=X~GS0TzYu=Jk)J z7V&w{dCqf=KK99nm4f@eOw|JHHir#s!!03=95T+E6URoxHcpIWz3-697!*}H5X7`c zdKw)Z3BD!*L(-cE5?3%{1%knZf;S9*uPCK*kTI}!f$iagVT0%($6=O@?7gNz95fLf zQl{-aCQ7?PSc)`W(6nk%+4@bBc*Q#u4ZsGy>4tn+v6En|Z&$7-1-8%VK&!LUJT#{jAnOP8A+L+DzMYQkn&2+St1 zvE9-#AZ&=WY-G37$&}C4ZlO%qZXrP%A4YFpM+{zv>-O}(j@v(~Ne<3Pl{O;kc9aY? zdkTo0n#-)=xuWsNu=9BX=QR=5=Zzw-38`5*vQxG7wJEpb+snv7z5cxTFXm{@dyPnQ zc)WVIFhx(DvkQPDir>P2MIqCa;z2sb*$s*3%l$Q^Cp634 zc7jRe==SYd^;PD>6b7@Xw1U=cpDPpHQ6sj7PA^`1@x}AcK6Cz=+Xq-90>g%n?H_0E z>$`*KWKf31`**(|ZGNCNqvMMQw0gAY8W&W{pvB)|?9qqig+A;ygh$VA<9Zm}4l92~ zHQ2#z`#p%+?}c4&+Al$DFb&-eyF7GVr^cKyV(9EUhrKB1SvTYL39na>H0(!V&GuF4 z<9A+uN}D z?Nit213r2G@cB#3JCR$*N5%fezatC!hSP8blLAVIzE_=;i;;;w$jdhczz_dr*FFyp zyr7Omw@^F!pRYmrKKpe9SkQRc6;^ItWGrhxnTRPV-?VI;(SDFI;8R{-({m3FFr6Kp za8EnlRSMXhYb=m|cH^@rK7e1n5EMdP*hPYdSog0S-Xu&MHNakp>$sp#+YkBev6J@? zTv}L_5TJw;z0RaVuYQ>c392&Sdb&@ymkAVhBxX&u6DL(Vqw9B^!0(bND}+qkdb#4TXESPfLK z2#~7`o?ZTxLtkUT)Eyb&4XF$XOIFBjAK9s5D?wLMtFmLXw`gc=IQ-3wYX+XN$LFU* z#hvL2)eH83Y0^CM(~~okc{&PPGx>^PcAoev!`fnAM-X23ktK{HOYVjd<4C+xNzu1p zC+vne2%LWxN0wHE<3?qT=n9VG*?feC22Rt1H1?WWkv0u=k)Gq2pzY47k?h8p;b%6r zxyk+BgXmHQY}7WM+Q1+E2eO_cBVa8F(IaGYY%t!qH99HP}a;c9Zj_r=* z#zx$I?6D4hjR)g;j%-9o?!aM{0)j^rJ*l=N!(t@o5yR$}Q~T_$T0_d^o=V6eKqquG ziDxeuO%5{lHO6~15e9T+iXJp%4im{i+fmeIW6@KH)tSG70egoDT)`b}Y&gv7l31}4 zCx<*IblMfJsS^nTT(BD&jhHrs(+bB;YX_;JcGOsdb)=!@c6zAMD3lxF!m_=0DT5CJebOQ_28z4@s^xfV;$8!*>O z%l37CzI+b3xm2SW$%r%t=}typ447{j*X&5|HGWxA{-gcr5X&*8>bhST+#w%n00Lq;@!~( z(vgykUntdz!Qv;etAzrw)+HAY(&;5V0DjVVReyrmK4F!9cHI-N0Z^dR&52j~=b7vZ(WPSxjk^wo{R-gvN?&;fSwUHs$l-tT zQFotpEmYYTcbg75gQnfpgYC@0RaF2l_!SH~Tu@8igjb2Q`hMe;VB>S)^rHB#Hh!@_ zJ4>`izVs0K(UckzUpgC$k^P3Utct;~3c<*K(-wSVkRyh|j9pX%97~gt6-x)x>9fBR z-g<3>v%Ubmm%rg3&w5kfS)wRk`o-kuOG`_xpLRkPXm(ZYxC;Y5;cL7f-oSbU?m+#v zR97L2$>h_pSQ0ex6QJg)Pe1+#0DS!4;qoJ@x4qU;p#|t3P>ek+3R-X)#m&<3oP58@~E1_KODn$xTgwh3qb2^y(f1e*KLz z*ROB=*?|2A{DiUpzWUY=hi_{{Zd=Rv*}{CM%T|QCHKGlVGpith%ELO};48 z`AQ`};|duzsX#J@9G3`P$rj^d?@DY&Z8oq(ZpNl%aBZwr!gLlJR)mct<#EXV%$hGq zY=A6_6{#DWh|f7=zj5QQ*&IE=#)L;`4JK~m5IaY90}0R(W6AsMR}*+9;1m};|~?=G10UNfy0f#baUvhc24dSW5L@oN{$6xd3@JDw_;<;o(-=Z0*r`laD0#k`FM@Dl` zb%cz6dvmftvs<)2MGN7ax&_I-T30#;Fzgbb;l)RIIBQEsM4*pkddiSislz%F^i-$T z^Jc%zIkuhb#@b!R(zG`jC%5laA~6M}*A)PFNZiHPgc2HqhYzPOX z3z3Ai=x-TmJ8^Tai)x+mIG;H8^6KKBO&p^Xz>knEVS0~1o z#`OYU>W+Sy849(rK?mCdZ51p8f^6Xis?-FxX++@7_Nd|}14k8G$wtzS%7e+cV(x3i znZOLJ%!Fel34T@pRxw0bA@rC=hIXPm9TF8#Q zOLFvBh4Mkhyd?O1VR;~s{tN-zJ z_CIaiXB02kAluPUz`}~sf>PZ28rLC_MtE^d>xur*ZIVHnDp8?yW=6GKTMeKJstN{5 zRH7gSQsxDgN)_2!N?+(EwOX>NZs@iy(zG8Yt=dnU_OI;uobRsNiS!LbTMDGamUQOiBQ2BY^;iKb zxCP;JpaatD;5T55w|lbn^GIuFv9+y;2}wxI?EwtHksSpIoS( z8x^)!6=T8O(P$vrDluq83oj}PAqR*+`J!&)!|^QySKZMqW5y*!RlsbC{c$+lmh9fz zibttih*!dKuM{qYy?Cia^i`pt;d4&XD`Uh{N$*|~RkJq0$%27xC9Yf!ItVFg$a$4; zR!s}JdtN0*n~ZzFD^ z^+T@Up?m|5hkOk6XV>|rYpGlwYOIIz`R0V#;cMBAq}?dn$6U7*X29H72G2JDTO2pv zh{JNwoA+%`^ZMvdo~yoyi}yUdSIFzbuN+dc{Fc=@*Z^YjV2r>GC075$ZSP#5^!6q7 z06WFi^LT*KWIe|Kdeo_)L1qo23939b`qOJ_`fAg)Wn77Gg(!O!g|gB<7$>1dvVFuJ zga7~_07*naR71j`vBgh?LlSAV1+Km6dIy~isiAdl22q}O>tVkySTgBTKQjjWgW%g$ zjYSm?0m${w+QHZ?Bj}B#8tURh2XJ@x?;dT#fBns^k>6clZbjI(sl~0K=F-oXUjFd! zmw>mY{qlKr0jcc%ZwA0Mdn6QCt8M^&jK7XWs+$=&zjGW#`IGmbwx@N|MRxU%{TdZC ziYu-O_V#^XJknyB=Yb2U?jE+jtA<`ph}U?Qt9S3bXY~2q2mgL`{r;(^dS+)u{d=4y zfGzDuh_Gtg_AmyvOv%@-*f-jI%YNe3y~BOouz7fR!!ARN`Y$ap5V*2(v~lS8HXN8Z z%3mSndilW@>tFn9%>5lmU~U*(rJBKx{}^urH-)6Ms&^`H5`B%lyM$79V({GQB<;B) z*pdktY)-aj>d~9$+@PshQMZDwQxUoD%=VZInp$L5vfe^(9h+{2R|vUjnQh7#uud6c{h?AeqsK zqX+RKoyCEqUGU)PzFvcCXHx1_2=w3yBfZPZ%$Jwt5Jm;9*sNX%Zyy*;1m%fd9reO$ z=?W&T0U#wHGZz<79z)He(Bgf}It@ z$p}=}Ue1!q=#~**2GCocXCxN$k(Z-~Fd3ghoK>)MVY63?#gR1IhXqgkHwy;mj8J>I zO0tx+50z{znN4H(#bL}4w^Xr5T1aOrUT$H*8}~e!YYh{z5tEFS9oKUBASM^EhkbX% zsBtVdXOuN<=i^G2ym&dCzRVIA1y<}bNtEO2T3{t?uq`|ui5(bA9?8y)Gp~*{Iv5OT z(-k7Ir0&wFJEzVE$*1kPqz}doa}VerOkcNKw2=0&M0sv?olE@acK*99NJC%S`R0!+ z2OomhuQA~K@l<)}Yn1ol`<5G0>3s7bU-oavJE^ol*RfwYl*$bq*1VR^j^&m$k3Oc# zWq&~o<;@=>ug;sf9OAp>37-^K1;}NMs~?&|H_w1t;qJWO1zgqKd16A9NUCIbGyZbX z``94&g5dR%Y8Ou7Lb~J!Vm7LS9$9|i`Tw+EeQyK>ebSVYH z3QS6e3bTo<%`dmVU_5Q1`{c!Yg!le-W8g@EI z(r52F=tM)j=BC&yyPDvBVsE<*HSs2SQg^rlFa~_z81U$06F2<+4@U`PA6W zCtNfJ{C`4^|MBl%r-<=teWmusp8aU{LvFmdx3+c#%ks1x*rOj!Pw(@6>wD8Lt*&si zH@$K76Mg{3&?Jda9`ZT>{LEwh1boiAG9-Un!MNlPmm{zllAoDBqhanu$V#D6QK^*7 zlRH9M{^IAQ1-PTA3@pRcTZW@JkJugu!Cz%U)2I+qv^42iOs3V1)Y+0jhGmFuKu$@p z{XxZLEcX^lXoF+`JEN#eG*))p>QbUfz6xd%ps!@qL7fa_25u!>6EKr$pQ!*)O z0zDH)kg`^)5b@L*rxFDPtq zk&}H&m;{Hl2=47&?rR^Ex{9hn#c}j;v!O21=HKUNrJ_fn2Y|w5!Lkt%2Sc_dMFw*vy3Sg(s>S|wXC+O-?e>x4~wi9xts$j%Z zi)ZL{FkXz3vQescIEIhG2_ z8h(UIjt<$p?b?m@g`!=;X$V8pg9#MC(? zxK&KFabbkb5vI(}gk*P|V)r%0X4vj%V4PHC470enLa@lswZj5ASYdc_Nm{I^7Y@e_ zJ-fq3atr9GDh2dZUiX&q-%`9(2x|jM9CYEJ@h?8KA#EkZWo+85n;_GQ}*od%ES$OWk#q7u&%ip={+ADiTm9rNOZ!2l) zfbF}b$4R?%Yhsr_O$l%;yO2#9JXgkH>UJGq@5xy9Al=vjHw4c4H@_2$za{gkF}ThT zJv>crLUi-%B!zA&of|y4FPi_L z^UXJx41K%=!!t8h5t}~|; z`Nlj*mieh@xUImQ;!XuUI_h**=g&79fqnYh490rcrF7}jA3yub;79p>H4&<;M+gj8 z?Wz6)5tfnFZ8vwlu`PMi(Tz>*J{4?1iN!9cralX`5RkyQbdC}9YtKCSR8RlSC&p$c z9L2WBul^GTyszv=5#SZ4yE53Se^TGA@A`UZbk%R|zXt>U^H=xR@1Hj;$4*=oLiYcT zGKNhfx4Tz1ruVrHs9)Wf-dkD0$aMH(ZEdA){~W%!VMN%NFxa@uESj=}KN$coy;uA2 z!GG6Zd*-hf#`@j%x7s6wtlD$^3hr9tIUT-4R>;Z+YfEn!@m;B}Y}PhzkPZF8YORKb zdu{W^(jn2%YpdIbdy3k+OO3=fCMptAYnSh@pMTt~*PQ`r*6##Hgf$*T9~F$WbnJwR z#nv6w3NmI6O+t)=ouNp}jGYzzh6N+Ot)MFmxiz$t3EJzh5nksXYRMF-_3fC{c2{fS z&KaD=A(YQ#M61{rC`WZgNY;!>2)QYfNQ6{bXgJ+jEZ(A;K|5qzO&ON~ZD4$hLv&k- zflguXOzJGnzZq2lr=YblK)PlYFX#9e=S7LX{yxw5#l%32 zOvxuu+a~v%Z*ZMs z6B3O{DM-~|42x1sfO`F0unFqRWIC54p^^@zCX$}larJ8P!adf#^-V#4eeNFhf^rKg z$F0WzEYEuH9L8cEpJQ5`Q}S#!#lhis<=gNn3M&W4v=7+ha=M&@njnrPSZ;$J!Cj9} zAbP{6dtZ--xN)JmPZ&m{#qxQ~hwxq1Npn<#{JB8|(5l2z0$d9udsv{%GFlNC*y61&`4cE_Y)h0kY{{R-#RO>w{chVQ3mXSF7H z_WrD(b(oZ{^kin1KMO11blsbGzCB9LzK{dI*sqj5egb8;$IXN%bEK$gX26^I{ z0P7?fwqaMt)K$5&jl=xROx9LoY2t=y{AFL|56dZhz&@2_?B% zgR=~w2aGPu1WuY6wA|MU83v(S&D2>Dxavl_5&GbX^#y`wMOTf%QrOkvK?A*t!0%}t zQllA3zwt|UxF=jS%{?hxht9ljSl*UXO4|X zjb<)==D42F&f*}Zr?S0b;+~ea zDm#njuuv)OEG|MY7j}x3!hy<{mwt84n0JK%e|6Nu;?}6JPMgiL0C0Y;yaIV%sZ?wM z@$IeR7LgeOsE6`Qx3$#1P@oMdzxzm&u>RK5r({}p)y)Hc`dR>ZVQ=sDL818m;%$)o zKrr$^p5tI)OK9r>lCHI)90;vmSghU5D$IBV|vO z0dy=*c0_b4w3oizEU0Ph23XqZI((P`Wi`3@;+_!@O=uX#YOXnzX+!h!e z4Y+OvI$LgzcG8K|$w0bIm~M+uTsdOV3kC~(cM3)B5(3b2zaxtSi;^50pHkE<@T}h6E;hb+ zedpJCaKxXB%=1XXu$rPd1zX|13fN6lGPrZ=04lR*`JmW0rrdX(G>#_Z&Iqssd?P|` zHE1$;E(nCijO4j#JxAd}E?A$-#oYCpjRi**E}g>;j5-UmkwCAyhjrUKOevwi35E<# zt5X;a^l+@{RNa_kFrW>To`AgBGVQ;PI-e$FZPe6IEe!?U@Oc~?wN9syTe2zTabrNO zMo-EY4`i5_4mou)ny#&b91Az5prN*w&IPZAR_avR%bR{po+K$KCJcOit(q*p^t0C#?O%q+l(N%-|4C z3jilfJupuv=iVe@=W%|-TD7cp^#dy{&WvX!?=Pn{sxqA(pTxLCLi8k+gUFCs^-c;x zG7!#$XSE8DR1BQB{q1V(m784cl{3nK`+K#IL3lAo)0#$!1sGv;m?j3fixNYYyCxM2 zEXHU={03>0`ketc8|H9kHfe`lYDTo+zm;S{tx1&f`{E-bcpR>K&W7}VA@>FNY)_Ua zs^J{px|TI+X!f^8x!j#S7B**3>bvA*rV7Fn)nWz(;41$;!GKTDU>k&WHa*ilak2(U zsjsr+8C!yth44<9jwD?hPwD8{2%d2w&6puH0Icg^jhh^pGD#mMdQvm6OdFC(b!@)V z@QQEzAvqftROYO;g95;36p$OWgOEUIAe!|rkGas(`sq-ud2cDW%RlZRM$WZ@$3EQ* z>$I6=i<*Ny{9C8JVMtY2L!W*Ij+?o&O@JF4Pb6d62g;81dgIyGfB()~ACBIgvQ0S6 zrm|?N`SfX_Y2Dv^NOK^(vGRUJ7_R{2LE)2&<$_LJ57sV14>g3b{NrLlL32q^v#g8T zZ~pzWw~x;DX}@l3t8n1c#sT~12ZHK_z1w>Shd=q`Pf7Ic@8!OM)~V)Jb?UZ$`StExWpP0uwXn9fxUe8^50)NpUt83=LBY$% ztdI|{tvyDQg*Qsj)Uf#N?X~T4>9yU;14huVo_$%Pzl=j@s`Zk-je59A_eNf0O7pMD zcR4QR=jMteq0JRP&dbppU$y>&6I!}x*5c=gO4BQ3r+shp=~q`@rE;m-jI3IDLQmwE z{6o@*7uPwamLctMWurIf2+#v80669WL$Ub+kS@f|&auECLMhsCAi^{dI(2L75Q2Nl zpEOGf7OXJs`_bV!Wzg?m(nuefHn}eI6BOC!CDu+zw{ubx;k1$1!UuGT`3() zcm73C749n#9O-NUO_5_o@hZiM++Y=~DIA!S{Bp_Nrv9X89Po{DpJ1*#g3~C@yqRIN z8`YH{>U?~j;st?g0-~8TM|1vpm1X&f#0r9^n!G{1kzjGqFNi8%=h^eJ>5aN?3J%8N zem8*XkJDpBD?>eVXYFo?#)#y=ilhxkK{I`h`Ex-5QP#SQkz;NxY+xEKST3l$ZYZ={ z9zR?kd$*|`ml4zGVZUZz48K29kOgdH_R^N-As;jAUd7OhTPk?NVL5FZ!g2Mq~ zkAUbC&!BcOpm%m|jL{tIsoALU(UQ~v+pQId*5R{{kZ6;%p;1^hgm5sOh9L90qpvv) zyunv~OfscBsk|OlGwB7Dtx&DTY@i#35bH{qU9i_0vbX~d%W&Gl6^syi#2OMJEAZ=0 zjtH`j2;7bczfD+~5jMFa!ei6$UCRoy;T71;AnM`{d2A-6v*?j<+S0`?I8A^>W@IwC zoFuY?ioeVx!)IJRI`d73b<8{+4o`y9?aSfiunMBuGxR73Nkv~Z3$g;ma9{ZhU+#zO z(g)nHw%=)i*IpFUc!7Jv=X=%3E7$EYHC!0iZ+c(re|7td=-N!V88{2^#U3oA*t$bUut2201zSvz=A*sPgN+bdwy%~0K}O?hVqy3H)wuwPr8b$ml@ zHKP|4j9YEl)qqN*Ih`^oSj2ivL4gPE_&)Hg-nDa|doF1GQICOL!->^-Wb|0N6J`nA zGw_RqS7TNMeOGxOO2!6Qn@BWR+Q}L6daRI%V8w#O@Q2(Q5~M>{ZrDrTp0ic`)rl^K zGuqN{=0q=&d|Y_=&RcIf?oRco!noNGGu>2PI(@wrA8@H4babIio8QmLYA#fYJDU4+ zaIjKRvbraShm|e1!OUtGAF~6lJov|NRD{)coxhq(;G2N4;JPqi=(0TPVX?G?WO(7X z3zhs1nbLB*Rw)-&aO|!uU0Yn+&F}6$`p>_vUOhSz1}yB6Q8p0#<*#?=O69HXt@7t( zWu%`|B&nQqbGIZ1%0%-*MyZ*kz{)=TFJEW(+thu=ar`RV=`6>_QRXae@B!ONZ7+y4 zacwhs%Pz8A#Mve!GYQR^Ct1c;leiI}z_e+aK+w?ufv}*hkU>hNbf8@fQB4|^7^CT; zsS@07H&OqOJ)h@y@&elCrm>HGILQV0>+kb?Uxb-{Q(LrF){Fm|e{%TH`+7}X9JF-? zEe9{x76f2HQxZoP?2;{muRyGVtzD7DQ=EHALrMvs6xz$TON5LI)82ez{_xwTj*)m1 zG;TuSujp9d)6`9eo0b}f(|J?1H1dubgaZfaYDt3C1RZsUkR8WVP>U9bx1zW~0NV)^ zyMykjXVf9Nl@|&85|V{OIQT57V`(_7fN8zXovwGgXJ%nF!oa8f7I?j*^Sg2KtdvK$J{Wgab01q(uGr?c7RA)&=XOsI!& z0cUgBq^5O@3^A+DB@-qiE1QdH3n7-^WOBN&bZ$Dkv?QntTNVn;OX>*DY9w@Ah;L#^ z!?7qw;xL|##c=rwpVi*rrLJ&Huy>@7Wm`sl0k+6d+UeWaWP zf_$LT@g7?E|o{q!64vD43sk#JZqr4AQsYdbz(u+iG2oOiDwA|xEYD8-qmE}o$ zJXWLONm-9m)l@B#Vhzk@xCPTKryGrwCD__%lmw-*`8NEqvgb0#C? zx2QRj`I+%?+k;f3tZ-bjDCMY=*VQmn>^wu~Jh0kR)F5aOSnzgS1zF>zJR0d@IZq^J z1`D$MV17~RN26w$0C^3ZwAuF08ovhh6qG_9@S(b@2hE8J0a1-y{3{-A^Il|zW?3#f)6UjA*2KtjS#UJmCERERu)eGk!kS04}GKGh^C15&`7NIi?t&Q z*FU;;?au1z%G#YfYqwXi5ox`nKA1gZB6G9&eQ2MioEH2Qjy`(+{P%|6=W_i@(EIJC-U@qa zy;0MFnOCo4p0IxoS2JyxB!vU**9G|R6CS>D``wjCYwxaodu?@neSPb}nfW)~mX9I2 z2RFq_gQlag(*LJcM8M7|jD~pqI^$#jH`whHnnN8DD2&|7#e1y0zY+@F?Q}ae*4aHo z5+zz^@+t8%`AF#S$rVYw5(JfNIek!E%Ihe4sMnVZK@?cJ{#EuW=L_%(o(qFj-!PGv zG!J&0*|qwP1c-AEchYU_z|%xT2aPxY4M6h0E2*W1Id=j5m6jz92@uQIa&D|Xd zJT_voqZ8<;5^RDKn!Aw*Ct~rK@Z1C@q=dkxGG8Jo;{v&IuO8rVJaO(um+F|k+WQ;x zqLgOyE9b|E*?0&y_9h0fB&iFDmtrh@NzVw=1&m@E`4wo}1#QJVBs7@DBw@bZSYH@X zG)7(lUzJPCnW0lgW2NDf0~n7m3oG+gYp@qJ7Ru<5%A=V>hm0jS)Hk;8rlan{1FYd! zLWLD_NuP90IqMjbw2Fan$texxaGFM7m&>;P>h@RA6_*hYBQ96e(BS~d^7xHFT!1$s zJiy1=i@eFIl4br>mG>hZzG-%SRn8NjXFwk=i7AUaqrPPV-W#oPJz38{l-Ut7<*0zQY zcK`G1CzeoN8$^!sBuaVC?i<98XbwR4SPOjZ%g>gft<|<60bu zYnS9_EkK$fgd?w|N3+CG3Mdz;3Z4-zP5CAS} zTW3o7k8M%3=5Couw5foQ4-kUDogS(RaVQ%GJo$eo&9Bhe*A2jvyJWVxv*1-UMML%4 z1@z@PyRUH6#6mZ>bzz?QU157DXusqj(IRFG46>-DGXfS(*XK+Q0c zBfUNt_wufwnn2d2>pK9t0G6G;Z%|Fa?Y@nbK;_*H0GK}D!Gp@u2d^Bge7XeyA6d`= zvBILk#?wdk^Awi_h>zGm;{NVUm@riN(fXEf^z%>t{ucY+qk~7~w`eHNCChUH{$sy{GG2v|Vm(Y;7!UY;1ha?fLW1XP$39-`xDi=9l;1PVxW%AOJ~3 zK~$T>g};0$UoZ6b#aI9Q%UA!NpMNreaO_Iu;NX@1pADLsyjFAmx#V(A3AGL0bQY$% zeQt-#spUux+(3ey1X?+?%7~)hWyNL|!p>O^uUyBRbK(iRvy6M040 z#*h%;f`b4`H_e07w)2=Md!wKAVc4S+G1sKPd$lwUW ziUnW2@$9*W0I&e-$kIb$$6@xs^aGOv%@{e{m!P0QSZ^043~|*y6Z6b@r@Y}Ci9Uj_ zC=NC)z+DejDlJqvgf^OsUGDv&4-*0zN{HT(jur|3;$Lkuw%GCYRDYC!u5 z!^pEjL{^55hgI_2caNYC8VtumKQ^wVv9W#fL5w~uS{V4WhI8Dd!O#c@d|G`J2ta>L z610!+io<^m1nMr$o^(YF04pW-_#zRe(}K-W)6Ecw${9WvE)1PKTc|y&ej+&pg{!Wp zhC?%fMh@-Q7$AQ@`+OrcAyjske5oQ8ZBd$gcIDD3Pk0LrLXurQwzxTI2WCSNQHp`D?LVV3zb zCM1own$74Wo1AF11hYQ=I8)@I5@=d~h5D+b8sg2CxySBo$SBBmgvcWv>q+TnfF9}# zRjl19>1lg|I3{1Ey_5eXe)5&_g>4Gl+!;0RZgaP7NV}uwJ?9u;-f3(wlVuZVsi(*j zl@r5Xf0N>bH+u)0b0%1N+hZi(uNt3{dVdvo=T!V`j`%)0*WAN`4HdSf(9LbERafxb zw*5$Lz@{Ei*TDkHgSG@~&Q8Em|L>qiR?ab)wo3;p{eK9Y?5=&nSlMu0Q^vsdxA&)* zj!Y}z3Hb0K69^3lZli)G5}m*28hYhljF>Kl8uS-?fXW`A#Qd93hn}SZ=}6?)w@^Xr z$k~XX|3lZczOV;Ec?NTD%lxriD&LMaOQzkzpAc#F<(z6hY}Hs|(UE^H=QqyuV}Y%+AI{b2(~g zgHN9KeJ-`<0a!u?eU8l+w<{B?fBMTm3~OC1(iKsWRr$ok;RkaVp+aZ${WMQ+r{{>~ zO;6v4!07(;b%B}Fi+R8t6?71^b?fM4JR7Se>c>l9%;?)H2;aMQSMF;kK~nF3%0Fhb zjzM&Bw2l$8Zm|xSj95Qw$9Fy&v&*6JKt;rHunz>iKCBiRud`?;0ZE29RU88ovt4o zt*sG`t{?6aj=ua4db8-$@rUDQ$H$G2POEOefB*jE-N|y_^78A-mY&+m&1<>W*-P0? z`ns9T<*vr)O+z+EmvQ=tC3paU8HtGc&_ronKTH%5Z|z2|k<^XVFK>0tC`Gd9B_Oj* zkA;ywsS6`~LBvnuD6?om03jBz7f}uo&%x2!+1P{v-7I z@^IR%STi?aNJ7pA7YYK1nI)H8E@3k-fiW>$$g(as-LkU#$PLR88GK?DfRdxgOQsFseE1|CvX6NjRkrn1=$}W zuul)0h7loHc5mA2wLgR|nh0+%at(Yoq;J@X)7p&f-a)(1k622?Z1j7HE4Tamu^Pry zc@ULJoUnoRUq2!8gb$NuKNvCHThpIL$OeJ!;0UJ9X~zhnEz^$nC8ox{8t9uZX1lpfA{V2{5{%oS1{Y#zcCW$y}us?Q8IgN zt1XV9!DyUL*}h>xl^`kEBAw6g5auK8PNuq=`ih6oLW30-4`B?=nrJM0^FnD6 zODW)2`zl<&!urbrS#+-At?v-he#QKmKIUzoNxf@DTK59+TR?76kx)YyaScPC5I?g3 zOJH+L+qZb(du``lUz5?sfzNtSVCW7_+=0zLB%_H1he*pJyrws?y9*!pyFQNzklN444OsK!zS=RBvL+Dw+9 zvyNeNZsF_*J7D(TRB*sF#?bgRKdsCOCd#ywWy1nUah}@%?c7+Hd-`W4p5GC6&h8(N z-y4s$M9bJdTfu1-j}Erq{QBnAo9!jS((NCafPT5ZcW`j<;NWQW=*g3#qt(O1^~0CD zZx0DPKODdP*N4+*$Mf^2?@v!oPu|7j%kOgc=oIUmM8+jb4uuRWO3$|MS`L-dmx^PX z*=(%1I7ZiV^y<5kja|KZ<;s=f;-1)MPwlmy%FV0vj)w3T?&_9G@ju(wnW#>5_Ek6Z zbv7jWs{2Z-8_Mau*`!E15e!(2`m273$Y@jNE_GC?TNqwB1vfRk&p!?6cm6C+^ zP*_={FfyU>162b++5o8)=T##88N=u#DhDOifEJ_xn}kCl0Co}w%!XAugBr8ODr^V^ zRG=xMp98{&6hPmCs=}e9hFmHR03SxwBw_LtfvC#pTh9TOAiSP>SJ2~BIFypWHCX5Y z`NjU%qj-WLWeQzN;Ivo)2RR3et|4NBj<9m{75D!lSHq*cK=FbH*&0eAdxbf=gD_VC zy3#EtvEodj%QM51YAXiKZXvQF?pmnKG-Z&*p(t+N9KR^J$r)Jm2|lDkw}M#c!Wp+a z0~ZmLSlH&GL#c^FIA%bc;rlINXHtn4bp=Sq?WRH^yti%={k>IknJ6*~ux{SuF*N+a z&k2CL&Dcwzj=`eSOQvqKY{3#(XMyoo*6TRkiij`lHYqr2Sx z(C-Hg=5|7_AF^k{U1U%~AnipQ^uvCl#Jv%SqPY$U)?PFs`Pzlow;zdE?Sq4a%ReI9 zD#DMn4=(v^#B=>MULQfKgZqEe6HES)bbAf^dWn+~*tYv3M2p*bI}ET!BSQxfV60j} zK1Z1M0s_VMHUgh6v0x6+fi%Mq0k-Z3vh|CMF~utPYeYJ4^DC_9#r!Ih3oM3(411VXcjxul;ZD0 zS~}LS)=PL>GaAK3{PTI_||GM-v2coyD8s~=_t0uqhdN;XTyS&`f zQ~UaL%jWCNSndkHQ3C@d4w@a$;d6{Wa^lrPH)2`7ftOQpB8m>iGTtE&wDY>Uysx$s z(V#_%hR#GoLt?qSfk3pgG+N!+*0%h0`D9xgUCN_v(I{OiqLcJBieBLgxK)miqBz(@SUdX|>tVvw$Cznz8xnzW%A)I5xpg6xVp$a- zE7-7(r_GQ}hb>_BGtZp412_zcl}ew&gvH4KtiJ@%su|H6Q%HbLhLhZR z6gI0WE1(0R0LIk>#-1=tNN@rZAc)uQ&4ANG96SrAxxd=kTHVMf4ZF3Li87o)hkHn@Qf*AV98FAyuoRe zF4v5L>R%@s7YZ}5BsrZW$fLxr7hD)Y9y2b5qoARQF0mq5gCi&r*Z~sUEZf;k=keO9iZUqEc?1C|!2Jg-AG8iVN3jf=l7{;}xPo!>oJxH>6z0m6iUBH+u+vqKs-U1bU0a0PS=@*IKzoig6Nh}v@V&q-P zdNXG}W7Z6hFz<#0l{9*1;T?I1KrDj z+)wuss{WU)t9@xJPoooKBr$Gi5^~WP(=l&1(L^d3t$EQf?m*n7i6DWpP>8D#G6}TF z4y7=D96A&~tVL=eFuPD@pfaVq3o}r*FcR9j>`bRGRQ%-B55xW+`<(N;H(FY0W4yU) zLpA4~=Q%He%L2RAxM~LWc_F3>hc8!!{yH3uF#C@RKDn(5D#H|9ts;6-uPTXiK@Re~ z0#dFtA;d)4ImBFM~O9s34Tnt9l{XfcZD4YmJ=3ZzM4b#^!|bqUIpC)X?K? zv;`+G3MMZB|IpC8L~)kTUj#r4`U-w7UA>sSmWBR#Y3bU1tbwyoVkt4Sh8Ez98hV0r zTo7MG3zEF&Vi$YeHYl~GC-t_*dSQGYCO|Lo!FD@oG!{}HeNih2va>WX$%JV4A3GoL z9+lq56`1!Pv;Z*BvqVMdPoi9h!_0vEs^?0kYI5ILa#0fMg@cwditkkP0 zBSwNj)iOAme)y-~ ze;RvOPB5rh@l+rX9V-#fn7>HPEd$*-kf-zH9O*N+lM zdwY8?BSNG zDT%HMBNb|T;S#Sh<{ADqoMt0Nu{d0rlQEshBJq814${kamf@LR=||wy1;+ zSeBFl7?Nl=Y)B{?#8LSMsA_NtV@8Ul8{%jS2Gka4t%OvW8Z5?lVC(BzgG38;gXndj z>IzQaHC083+M^iqvE)7Xy{IIdKtvWICo@w*k6BR&t+U)+V?4($QlVpO@@F^You-5BAT5f;-^1oHq+>qmB@^ zUwD&tFspV7@twi^IrxR#3<#y&L>lFFXV3%Wg(?dxUqM`Wf1L)lj)pL5Mg+$w#9Bd? z4x;b~%UoEHu<5rjU(n33Q)8aR;`G^;uM;pxIW5484yhiaMhuTVruf56vnGot?JclLW;wVL3#0l z`L__Sh8?xGBV2IQ!jEbUdd>+xgZdU8#r4`PM@?rFL!(is72p+)a}Hh83vJySt`_vR zUQ6asL0Gt-s|v0PZ*1sVybwpCBVst($=WSQj@vmcp44u&?+ehj<88=|+c-#p9m3xn!num>o$51+JgfUUAEdVRI{gXa~M5VSK-gX$(lwBFxJCZ z@^PCucDwLN*!O_hR~0q^BMNJtw6_wi5P9b-X|pVeWLOwi>nks}xi%|xSYfCPA^Lat zs!X3`In1)$`}ifBy3D)#0m$hlg(tAAYaYML)fG^TXrg;}!JPI`Xm#xH1D#$flxklgN%Ow0fA zes}f!(Bk6I%jv~S^0v4tH>(#`S1%0*7)05WYXm{Gh=6GN%6Kuow z3}h`El@;c=9{TYz#s{1#^9hzCDrSRvz}lB%1EL|Fb<9{X2r5Cdi_g7xk0 zL2y+&Itk@f)$Lkgss>b6*!a0DckS+#b@+Mh0?f|8DUPt0{KRVifcU`*zqU6jOw~Hmg7-TZ&*@bXu!Ey95>>@|QZA5Pft|FBq=As7)mL+(Q zEXdh#^=GEw30_0;o5~;zdSU`8Scu6& z9_5rAVDQG2fN2V9D+G9iKzUO;N}7eR=TvMUh+t@e*c6ONA$X2ruqN#Y(9U4wycuFD zwERK*#*D|$#-uxdVWG)E;OreB^Nw@VgN({iKZMS}TxhO5{t)XJ{9g<>HxUPoxpZ*g zjsWOC{D_)_E(>Q0&vnktK_m@yCK8{+U>aPR<|7>8>4L*p245%Lg{=rfXPgH)^v5db z*+Zw%$KL>z7EI$zfrWQBr z2m6EoTZ9HP2dhu*eC423B|zH|!2uC8)Sa9=gXGfgi$`ii0mZ zFo#9~A)4C;5ekh~La##@akXYc{FUP}5f~&QPKHpE4}r1rp^n-k;l5$?E;t$}+2mE^Ju5bhTxjC3 zFl9J~k+p$6uuk07t(Ns9&vtWFJy+}1Aq5MIJa8BnCnxP$ttyIP+T`;@NiY7!< zul%9&UYo)hJUz>G-+x~+PAi=Wd+sGqnj);y>9D%zRjQkNV`bu1o8gwhmLpMNH>*N* zsKI*q`t@t!Mz2A8>u1Ezy~^KSDs*q`Tvs8{M)Y&3WoAIP4A7lz8H~7T_lU=0O7JgtquRZ8!$8i=>ASq6Y_i(eCQO(7{l*JF-6_c-h@o zdlJ`SFFxg{_6a`1n?SVPP_m7dVZ`Juu%0QyjOc#L5c;RmLg&qq)T00GbLnEvraL zfGUzTcv@mCVcMM4t{zVm!(n`0#DGR}SK}eNp@p_a%866-O_-B{2+Yk!J8^l86%J}Y z&2>7|ECOE7DP}At$oI9LCcC=Xba}Z?mnexzU%7CSnMmL z!ESl&jjULn2{Zub;SN3a5854`4DWAo9j zJPL;Eo`{hE%iXp9naoq_pkq^R9Eq`gA%)mUIE;3tSU!jebSRaXiG?OY0>c8e2*nZv z-3d7%$0D%}LItffRuE>*Y^I(DY5q<5H-k>U2T{;L#$P#u1DhVf+K|%|0@)1>Y|i|j zu5)>9>%hWz^+b=-*>JQcRF=~ZAn*_k|_G_ch2`X zotZl~##$#0IyqNIh=u!i;?(%7G2i5Ac9tCI>^H`8We(2Lku)oO#;mkKBy?7U*dr<@ z!bmG)xCpaUXEcjJSYvDHo;?^^`sFM+l#)r$`(T+qBmg*@WNIzLk)iDb4Z#vd8)s&d zJU;)9rqkGz#wT9M?WgROk;1IDkKxzNYN^As!mn*N{F7@(mr1{r!XoJleMfW zV4*GWJB8?pEiGA8kJ?O}FF|CvfQ`i(No{X$HaAJ3bo&v%-%u?BRCgKP%MHw%5kxB^ z3oPD5Nv#bqjGC4t9>aSIFBvvZRUV%ij2( z{qo|)&p*HT<=L~sdS{fzF|z)4#Dj+y1hgKAX~@a%DqkLZA(pd(Nh04Jp%Uz0(m^!Bq4i!~tFr|fW+dF_!HXk&ZS=;rMs!ILZMs{&0O|`cVJyQA5 z5U|~RTxlL(@&gozUZ1 zrhHIlBT9l9O0(p}`n$;~?5-{2Lil3Rcuc7_2QouOX3HhuTz z-L*USU%PSb-_L(B`2EQ~UOay`R6hH%*TGmB(Ve4V4z!HD!v@0e%Ft@$aO*SZ!5|z; z`v_Vq;I6VMl?EL~Z`6DRd^8AiDBXxu8*YKU@m25GgTkkY_fz@L-xKCO2#bHi%&Xf9 z!}8rQVl2N_W~AT~jd}<+Cy_E^FY_3wtoC9*F!ZhBhu4h)V+CNTEle4e`Hw!Gc7gNs zX#IQD{VNj^j95)cYofqAU%&dNzg+y&&>^6LFf<^wC2_-uP>F;1)1R=_xylnUvg3gjg_s!1ayt(eb=!$|{}r*>UGX9&7ZQM(5DkmDy#G;2OG zmJo_HFHjsf8|{V!y{p56p^lxugPI`RABB}~w^az`;x*wXPp)4Jvn4rzpf4T(FO%BWBr2W&h{K#>BSTJwvvF>?vJTo0ql*a;6}OnhMNRVMk9dn{@A^!A#Ma!Gt!$M zK+=7fP~3G{_NHsltTl2Z;)>~r`hnro_e6Q)InXdbUG!X%jy z_C@N4IE!KXp}n!35nmdQ8oeCeUof|kyI92cOV!auxv^sCT4o!(*gFsF7~-qFI271^ zEtb{CU_h-{=rTSfRL}%-^m>NBE9Wb7_3}#j`^6Qt64n)Sb*`KZsIf8I^Ev=b^c7!> zBG)-YqiABFeP3LJ5TDi=I8(E5I>8rue~U`o$V!Hl6fPU67L&y}kTf}?mIXu6bFFy^ zx|*dQ33*m>PJ7^qzbO}MHamNgJvqV8bROUMf`SHv zRRdx}UHd$btH>js?J%^{vnR=SRJUM&{SLHvd?HI>FgH2&LVqFHcE?w8oLn&+*(bX+ z`jpp7>Z##vPA?@xUi&A2hBdr?HPN7b5zsmy|c;up1mubVe>`*jQe-Dx|>&LuaVw- zVy}9z$C$aa*M#_z^jtkWtTsu`GDP01RPCDdV#88Do zMU@MbAWglox%|jD?+4qP>SFjn-AI%YzQJl(1LEq|;M-PV?(y9*j$#a5PlWFQ3$^^ z#`Ib0{lw(gK6&=?U*Gl)SHjZ|eDo|W)-(%XrqK^SQM0udAhACw?IOO4B~(K~^cyeu z#BRw83+=w1R)^9#*L~5nw+-+jxOkg!hYgWZ8W8a=k^Eg`|gI=JQ&WhnL~GV-q5OvlLNVS zrqXxt)(pBo__m!fu#DkDiez$8`9=u43gerZ5bu-z%$w_&7Jt!bF4l|Y?m=5+GK%d( zi;Xg05ZytqLWJZEkLO@K{S?sEPI#Y8=P{0mG$LbEC&eR;3&dMJ*3c38jvCCguQHc5a=c1P z2M!~;8H%fMMLrw;!kdj1uPm;p{KyFL+)B^zwK!8>DNB_#S1094@mO=GE5PpRT=8_K zPC|#|R}>D;6|<*=T73vcCqd_#?kVarEiz^1J60W4^ts{|w zV|z3*Rq9P>8Oxi1yD(U_L3k{hu@~CZn?g2*f*porAka;jg%%;9Fbgk2q2R2$$~WjD zbW!Lx==nY8e{H8tJz&{a*S72^dhT=1^O8mZZ3Ngbc(r1mRSkbXvoBeN0GG(hB7d^v zA(VC(09;A0Nt(5WrRg&P?1jY^Fk%)t)kuVJmV*m!MH|<}JG-%m`iJM%pL(AR*Y@E5Y=JRJ)alMm4Yqyt@PJsXN z%s&?Pm^|~uSwv1CNqvIlFs>x_zO(`xA7zugAsJCH8&(Rc%IaTa9*Rswew;t8lD=^+PwZwdcMZU<#hQM|7W4V@=Rg0u@D~97&fdQNSNOrc06vSmko;3uTzOoU zcP<11%-H$F(e~tC4ISDS&O-O^nFLyn!c$cehFx!HL-G&~MQ}_*A4Aaa@DhC79(|F0 zQ7F9qNJYR5m=6v5TkllQ{B}hqYhh zLN!xB6#Yn}>8yN7$tcOTCi>*lyOr-f0e&1zz^;qFHwe2->wN>@55`}$+oFb&{2u!} zUBS?zk?cT?v()-N8@c@D-)N+wLp0k#?6vq)dl>%?rq09Ej=drx_qX7To0EX zK9=XPesj18+078^oXXp)=^ip@qc*@RN&8HJ4OM9r1XZENEN6pjNVDiX=h6r3;T#Dp z!1NdzAY)fi{)W83DS40jsGd<}NqCh{y+#>*q`suYnBt??G&8(Ld9~EA^H>n~?ex?h ze&JM}x&`C93mr-cd&Y%(OG^g7#(r-NlDkH6yB)i~-|gqSY=McrT9-NLwj+q`7{?{4 zLnhxw!yt7$?xxlo3Zv{ObMm%V9UJC$4V0@LLa+$FdR3L&stV7&sGydv$cnUzA$UEl z0wh8yE9jWX;mEBUEU#V|LK*&MNI z$S!L3Ol?fEKnzxvX|qvb+JMzSXveOy6U8~#YON^SY#E^AHNu}Xne1N`Zdmo+u>Lhx zJZue5YgcTCho{*aR>0@c@NhzK#ULU@gEXsRQ--6W7Q`r`ht1~Y;ox*YAjjN}3>A0P z@-z6|K1JX_Y7|QFCfPmlP4Q-A<}*H#%?G)+Ss_uc8-f6-=^W#_rJSg01X^_=;ZW4FtldS zhRy_0j$Hp7i?UACe&i)cXCVmMp*OgXrosg$abGOHh+1Dhl>+O)$IMTkzOTp)&xIxr zTJ-l_MR7cRYPXaz*p+1ViaAh}M6f{0)#4;Vs%Xp@+q-*#xh}0yW5WL)G6iRAfB2Ll z2Ky0O_&$E<0}du&(c;HJq{aJ#FMs{Z-{s%J&rme6x)g6b4yfuiK?05GH3McJovOW0 z1Lpu@fXwum{i|UjXBbNPC;%Sq9NM+ObB{e-?an zyX;%sx(3&dW_5266y4VFfnBXc$@Oxayj(x#D`3X_BHLN$d3&Lh!#jjQ!-CDqbadlX15kK#C91|REzg+G#OwCdq+(DveszYGdg z9VOZK+AXCEhM7#H@s%trEZPT03rF8FS$>^Ak}a5bua5v;LL)tma)Hc_M5>>#cdrd! zzg4;55hcNtDD5qX`VzW9tfe7n!lORe8*TuOZO#lPL1=u#<N%7- zJ88Aj5m&Ane5z~VViiXbJlOC#XAD+U7aXppX*8ZIRjHB|#m&vqrO(_7oco%B z!j)3U$Px-Ox29sy4$RW@0;A7bULmK_PUfA1%1QUOS z3&~rxP&+Fp>rozT%_uT@F@yFQ%uQtM)g%*okjS+ysIUQujeIE0GPnRMUi8E4!+60d zcs;6KjIOd-m@jtWW>h#d0=$37aJm&m6ABxeMrnt&*42>a-&XT5svS;hi_NS3NR)TN z8A4kV& z8+ViFkcD*?OQz#4h7*NG`P_77w7m^S6KeJ035GXy`K)1)l{J25UFs zcn;^lK@071&^qV~-e3U^lB|;uJbC8wXWYK`eZXhVeb3?*u!hlK?r2($b2v!Cie5y8 zxA5K%6?jGG!fy{WiuUXc%77)x((Qp~Mo<4(uqU&;MfQX)Tq%r_m}g2El7B_`U{7r% z&;{?|#4{h+wQ831tWP$GqVzVxc;@`xg9_ls0d?x909eD)rM-nE zUXF>_z$$ELnn)$Ygq_+ZmQo8wukBlYOVNTI+@oFCU>#MLVQZ%Uc`5T|E>B}a4szapEGXpL1Py)+C8W)UzRPb`N;7SRy$@;A02x)) zOo}Sng4cju+`RN8k^8(xhULsa*S^&<3>o_{??7h{p(G0$vGi|bR$6}NXkq*xzRsq# zvHJ?+(VNi=h>?WMAXmcpYJ6pnG|j?zY>gb0xQmcb%bS2x7?6;_I5v#!f;Z!3As7nd zVmyW{vgpc-DMO%(S(L7lkI*mCML$E&?>YZ#J83A)$X8dgtigkx`<(NMsj1ceD-_XJk*Z1GlF#pDdXpgzE z!EbIqjtld~dD#O)eBTT;M3yWo2DkV3#|Gf2lL*%^0vwUfF^=}f%Ih$S9G`X(ZVkwQ zj=S-^!7+@oOCV&&Antgecn%qk;*LSw@o-*UM)AdM*A8f6AUR|ERMkk^7lcD^yn6Lw z8y^xkOrwc|G-cVqn^%$C>nz{$?~$z4LFYq3HBLuhA6 zhRwp_1E;_tcG4x!cT;J>@QD*&S_y@@-T@4zcsPd`Q}es@Z*$SR&CP`H8pnMS;x{%Q zYyG>aUL^JRN+^vE`rzA~&^A*3b6ty=y&O^o?C!ZSXFIfD*NS^IlNcDQgCvuS>bdcs z{-R!`d*ji^cQ#<3Iw#2d@$Uu3_<-Mi@w+d}?~df(S-}nqBV^CJBFt<`HgxF*S89Vm z#3My@XvW+2WpTi&QCN;%I&lm|_rmH+$E(@MZ9IYWdI6&RNiJ;G$b03|6Q7-XH$zL{ zrQ3H_Tps4CthP5`9685q%IahgzI7RlM!b|Zzq675Vm$8}ioNA%>|omtt7?&2G3}8D zg7MP$j+=qwt^{wANWGJLpMT5}Kh#J(T@dflTFSh-gZm@tzeYx>DXD1w5ECughtC+R z*~LAQ%}=K{q+gZGHx*ev4JfB+sBdLD(VV$b$@C3Wr+t})`1@13a$}(T6ARsZIe35V z%d!V%5#8_RBBQf!6&kGsN~Bq3oJD8Gs7tbp+W_ns}UPKbh@5HM+{uX@V{$PAt78SFh%U+@}b zNfQcwpDCbY?R-h*q?WRw$(=Ns+q+`7YZzRj59t{sxOKjyv<{?OOV{UXuR-R9fw93a zL0C)G^9CE@^EEO#3{jCqqs@A)I$$Qw=jR5c#)TIod~TdIm`N{6cSS$L^2EWUuR0qz-YqXk+BQBW_CyuoT%6xcABf$|)RXoxN8(ZoB?k*o0>+%7#b2u9^> z_p6+HL>=MR3krq4HqJ{{2RT?@Kl+3E3Ku^@sF%K(Dh_%|Mp|Z95zs{}zr{R4zH&+- zSsFQ~b6%B{pNjYz64wlCsSBnQ7%Vk*TSFFIlQ${PKv}|0F79*M3mZ}wihIU>-xNbC zZhfyn@FXx?i2iA;7uH-LDJWOy)b?2pM-er_H7GK&=t3OT3^r?Vp(BOWcpSxhQ5?l% z#8tE_?42HhyO7>t{DFt!n1Y7Gj`;d73-mP?>Ke_WTo6_gV8gaI_K6(1& z7X;WS@PF2W+sI1`yMy?7u&w za5kb_kH&WWxhFNWEC9sAczroo$BBLJh*hbxnKb8mnO1^$G6mNJxrpNLL1S#?{g;fI$|!`ytOvMVW8NVQt- zD;Ap9EB6^=3x`vJ^(SDN zH2SL6BDG12n1QdW3!b1MgkB^DOBhYC2L(uWm&A=T*I6--ey-GL&*IPnvM})iR5W}< zh*`Rv;Wy7!($s#X8RjE29~CnS#>x{jxto)wo_az$3eyI(Y3+T}_Gz)36Tf9eY@Z`} z5E#>vw9ksf@8Am)^ zh~7YRqx#-Bs?m95=vs&2UUWK9r^Cj0s7S1MIELBAAMDu%!SjSiUfjk7HUECNphL)5 z;xIlO42K1KUNne1w_QPS=XOXz;VF)zi|$Y{7znYt`-8)Qs&^^BgrSsJbK z@vqnVCWhjJ2TtIf;QI|CrGgVodEFPoC1qMA0+u2irPrRCU-*eWH?kH zW#|D8y@YN_BJ0^tON5oEp}n5awa_Q~|F|Fk03ZNKL_t)F;27y389ob*fm`k>{Yqs> z0$_uhzgE7f8w38_eMnzDdFgiFO`kz;Cb7_)NjAqzrqz$vzeQ4*iO@FGBjdF){?-(@ zs_bXdW{M1b62Bgoo^^FJL?MXdu6!^wFFf|<-_T9?@jW9Zrt#_bUw-z-$~*R!Gi5IN z_7VoFQ92{#O95=VdAAdme%W2LjGAXY0&crfsjXG9*0@dg6FI|lmGX)M*z8hcXJ0sb zf`vmio7P$TPL4IA9gu4qT))8?tiIx-AOQ^$J5jkI8Y?3Z zHpoPaCBAB`HT`2*u!(=Sj4LTk$)KXHC=AY~lM1A)lw0L=-;lRL_h3o^meXuyf{07B zy04e4^!s^c(-UeJ3}}I4#L?x+q`Zm^7*JkDAiX?!+b8=9LG)ym&9JfLKGBoQ^b)RS zCkU-pmzP(wy=5Yv-3Qz&(M)K()*i8Q2Dhs%qr&~ACCV3;uCA8QVBtVAj7D|UJ71H- zx7Fk3yd@j(ob=J91`p{w&U*&GuS*;?Xi8dJQnDoZ&#w)vOLHxx&46`7AlrBju)Z(7 zr)7ZY4hGC?Y&VzvY`^>J}E5GS59C zivy@dho#OzDj3el-XMwc5y8-yl*pw-CJh5tSs~V==ZeCbJLC2Y2xok~_z|;>R9Q=2 z`(I(#T={&ZoL3Y_7UEl$?m4gIXXT8$4hxE#FQynnr;F({qN-e46X%TN&CH_hF5H*$ z1&qPPTwSRgcIgi^*ObJOE3zUh*6UHdF3WJC)`>Eta}b9`9ib4nP>&65_oMy87+$=u zvy{AfNg);@EJq)P1tYXXV-d_T>_lG1&@pO@c{tvGL;caA!S3)7Ef$HB#*9Dg|Cg@w zd2RbX<9MxKSQ3~>LL$i62uafq&k{MfcH$^St5ygd(>IraJ1EG=LueAz)*&Zf3WJeu z5RYKzv>iqdIi!a{4>^>bmOr3>!2W?93O($;=khSWyf@n_eK&4mAZIdo zevx4r-+la>I1gH!*bdu`-9Hol%t>Ygc|&$mI!aS|H0eyzSp}e%DFRdeY8l<4WD@Cr z(v4Iue?AT|&<{KfD{dpa7jJ!keG8fW;N!pj;+Ma=`X*jgZUt`G49i~vewwIfq55`-6jb+K+qqg*P4vM?HR{DOpxi zUN2uRhn;Zb=~msXcmdy(rwA*uQ1-+%RGugq!l;&8v39JfwYE+TpsqUoP#RVUwbIHv zURk@^YAcTI*wS3!Q3wx-B+x!_=TzXqE(}`+pH$ZqKm4r2Q#l`XUoUcrq!F4F+UGSI zeGL!S6Vt+zg7ToR6vLreWAOI^s`hS6(nezX7CSE+-Q-&8t#mn|t6`d;+yS#uf^LO` zTtx|@DGf(SfmS4RD)ExstdvnH?SBi$8|&h`8*9f>N~cgi7d(VRVyw4^@&Kps0vnMn zq;?QRw+wmRja2CO4R(8dqBo9vklj}QaHkKm#g%kSKX7Zuz_!;*_4an?Nz$yjB~7zE zvIQ{r_O=b1kL!K93cVVszSpwPI_BSMy;aZeRkttq47Xmd7Wb6=e2(9jl`^a0s%jVVnY!lC>H-ElYb15#)d%b~gsg<^%c@~(?J|=& zHvm46Rao^5Pct><&_$$FY7ABllHu~^Qz$O!Sv5q^nM=9}rEeDM2EH3(>%pcXII7Nj zH$MTb?GCjsKRGxkN)62cd*b&9Bwe%fFY1q;tn2q@x+cl9fvgeSH3rT(JF!bAlgVjP zdMv|UMAA>Z@+jf^V9+61^e>BOKjSAacJA>zjx9wR2(@?fOEGwu( zEeq{gdu3ppU8oFrHPK8OCDtqZ3PIMJAq3c9`ORQOX0+XXuoyYQ4HmQ2f@F?YuR0au z%}B9mLK^O_p4k@$&cG$H8b&^!4R%ilTIBi$n7Uu=z4RfC=mp+=Xk^$;NZv!ZD;Kav z&(t7|j318_gtdEWNIg<1Fd5NCXorMlt^~s}``VKm`gZKj;QnB-E4MN)P<6nZDU620 zjUNVajDI5W>K3&A-(aly_?@oc+sk1|q38S8p5Fk*F__QeOiKIrI%Vol|Nidw1o|tV zLHoqn`+wt1=pcD^-W!)5dHvumA8?4{SkB`D24HtS55ZVxOQ*ed2VnLr0Iq+YdGKVo zLB1r7B%>IDyV2hhzc1%rf2tAlV|OF5t_=<$>7?bJ33F%P(t>Gz#Tju3u4wxHw;Kmx2=Vj{ zE*yqVxqo8yWi2Byq~YG!Uic? zhlg}6K!?#^VNFV1ZLsE5!!JM#8@2;2(mjx8fxU*fhvCmL>gU2S?MNv-q?hXVWfX?= z>Jpi=5n-aPK-}J*QC|6y>gTi(8YjkNl<(s-s`gqC-xuhb;k(>>&$Z7ico|2N)RBKt z-_Bq)q9ci|?hEx2ZW>6VcRn{-OOLQ|UJ0i%Qe6@344pM-CafppFYjD3kKR0BAgu%}L|FM+@v@d-8N7+N2x<(+ zE!Mu&Xu9UD3s3Jz{(Og7x7&c#(m?oCt)>=+Pl~c3)!swsoG3`$OyVjgOx~bFr3aMa?>Y_oPpc)21>1UhS2MZ<1kzWaPc?-*6`YNf*f2lDLF+v zBlm>lHo#rsY}PAbz}sx2G-)u1Ho%=Qp_|Y^*vXQ2RX*xKeoNFUG&e!T zE8Cf+ZUrUuLPbbygrU78M2|+QJsRzfh86a~u66cSU@j#>k(|0daLeEnC%cm6It9*?i%Cg-;{zw_HANnsSd z^bn!t*3V(U|A_(k3n2I_17Oy_o~JPmi{H4D!KcmM)iAyeqFjnCQ^0WMgg0(Q^7->k z7)KP%wF3_IM`z1x`|nxY3atJGeJsPkHgbj0k~XCK<$rv7*9XliLt^oZk#zF3V7+58ZskAP0u{jSOjz{$gW&&g|9XW z>Bo@|oDI1yx+)R6mO_WzslYo!J42WtEBQlc7KXmE;5IKVPC`P5kA7XXENc+2F(icm z;ZY=$aqv(@7mA=%;+9Sn6o93;j>uy|JWIq+IGA2IM*F!!AgJAd{fgm|?UXEM2QrZ?8Y9Del zQ5^QTM9Le3rMFh5Wy+xbP!CV78Mg9509ce;J-gOIc4c_oCk*SVP}re;aOd!9XXh$K z#}O2Fr&Ulchus@k2Aj7LU-f&bRx0%`9suD5gRvj=RRs(iHc|}PeX;#w55;urMZX1e z-rhDUt)Pt_(&z2|o?@>upfRo`Lu|X5E@8ycMsA_DBDVQG0vBexiJdgg zyOGpXdR-~dNzI|@V_+4G^_K~B$=*}c25j#-FUh&emDD><1YcT?V9daTbCj~r)2c1E z%cD-IT_&6o3Y=}U8B-rUXXu776aSC4`lY0^w+UoCG|{+jcoN&62=(MV>W zX-`H+N(Y(-6(cl=7~z|ophlTeUhUYK{id>@A5VdI({F8Fvmtp2!*U3P{%m#m!*A|C zxS#&cbwy6sBm_P>ayhiCj}6ycjfIg%D_Vc3CdPZ-3p6qOwETJW5Bj25+fSy#kVEev z;6)>Kvf|F!maCFnYULiva|@y+sd_`WjkZc_6?(a^M%5 z+9}2MUhoG8g_q&-xE18d9wF_xT-zQ~Jh&%mG?~#dRLPq)cG1<9hg!A52E5|x@bD{m z#-=#)p8wse9Z54?+jDg^{~T_m&=N8JWrG8ZP>!qn_%fzNJpAq^I_1Lc$?-LPpEHy2TAH27&UXa5T&=$iD+1m%{S>Q z<3fUZBUrEsfH`(ZFK_{;u-zCkpT>X0^&;S268Ei7f%)@Iho#xgFugu7_Ll~vV?g$sCd zw)!G#On8Zwh3Z9ijpU6bvEdnsvTnYZ^OE0SN}5@^FeHZ18nWM1FJTtMb(?TjaT|+J zWMZIi5{iYvX#Mqi)&P0kSnz9dE7<^N4ViBsz`CgxLgh;;5*lr^(m1kMl}L~_?0&r{ z*p>L1Z7`8o>mTr6L@6u@r9vD2B8wiTJd{IHz9?_BH<2N9gXuCU97bVvC(`FsKL65= zW`KnRgxDe^gKyYe$^RYYA37P*b^<#?m{p>y3>qALou6 z#v+b$r8pL6j^nsb9`r#`xmpMNrC9w6ar4>1WfMd`jt|6q4;V!w#WJuZ9IJQUjz@}s z?onpcY{cbeuHPJ$NBy!oe;blPH+q+smyI__v-;r~oeg`cCdoZojnGML7;K)RxiWhD1t#E)yQffKuLy2yDZE3AA#Njz7JS~kL9mvr zNjrCU+N1K_5oHX_p-8F(#>m!9`h`UY`V(yf>L%-oA5P1RWswr)ldip&Gh< zb{0tS?j#LsJSieP2@xFb@0A=nlmmyfN!LW5P183fGU%~_p^6!Y6y3BM(7b!M=mnn7P*weDP%HxFcgowCvEi6 z753YjN_OoPysA|uZ9!ycR07loa$I9X+^S9V#F&C_-QJx41Hak)=IwiuNl!yHr7F|F zSZ5OoqVnl<0OyM4%>3MA`$_+^#}A^3_mQW2gq|bObT>ea^;9=sg)hOlF_x5J-0sJjAEFLb)-rmFR-+JQTGj4ljt z$*4pmt?(^&s~thfnT_4e0Jg6h3pGRu+&&E zTr5Z^uU<$By|AbS?-PVtPq5`?iFP)cOr4R-rsh-Z2{DC6TD3VM@iJ->f z6wc1728oxrgY7VBk`e3RJdu-zzZ4D{%S{+LW|12y^$Ig^r1De6Za6d(Jjt_5`Ajm! zwac<(wP5qBy7HXANtH^+#ba#0eC7_0kJ*Nm>`Kl_N(tjqbN~DO1G_Vhi{JMNH0U>S zxxPL2*?Iq<*^m*5GD3TBqa+l@6x?q#&yO4ZH?%X95j`8U8-|Wp;u>`G00C@+cEQU= z<9q}KE;o)xk`uR$3pX2>k~X||7lAUB2?s!CHB~1Y#reDz`_YQSX$K zfZk4@B+a&+BG~uumoIr>^Sso(_>|^`ke}B$^MS*|1Gi^f(jSQ1SECMGd;aGO(SPu*2*LTEY z-~BrH>T+6*Bt=&698KK7fKFKYhEa5@B`{VEp+=TxE!koC>Q(YVG4mbJ8>Y{4AE|}U zl~^o*9}0!N4OsK&@s~O5?9x1!N^u6&1E-)x#i8SVr;{_2i&LHqXD5^qJtReHup585 zvphd_8BLIQUinup!b-yb{=ujDA6fxo936$m4kn&#OlU;yo@2479n)L+ zT0_ngVOCNV1ttuYl^UxOx(mYmT3CD(8iLeA1P;}_B`}0pwZd-Jiw7$L#Y!Nc0H$x- z#k98{&wupM$AA3zSHJn~>gwjhr!^*cwsx&7HO)tGI~1zFndZo7ueXUr8>t%dRl52aN0h@HUbm!u$S z{B?|yCY8*Shh+eoVkoRwtO68vsNk!F_ajBbL#J^Qy`81q7g1JWK=}gFDF(+w*^Y)= zOqB_*Oh-eocgRc`Ve}TUSzB=G(9NK}-*j@zuCNion4!;PU$R5S5lozxk|?qKlE-oQ zcQQE)S`BFnbpv7wkkU-0>0Dr3T{qyZ(|km81Ibs_dYT;Qjy+?gW3>0jmBW?p^Xj2N zFpL-jaF;#?N{ra(8VGlYon$}UsV*5eHb{M5y`X5J%WXu?#&{V!uh9-XL-T?Gt6eP^ z_g$J>P)pKGbq0ovrHG^s${5s|gua>3tObMZIh7R}_-5zU44a=Yqt^VIItEn*6MvOu zf^3%;LfIFK+&5<+jlg+v!SMIO0DIA`M~0G%uNQAhxizOS4wW{*a)I=l1V+!@m~qYX zll3Q_^gLsL%yRg~`V+4SR`!O0@8|2vie4lI>vIOtA0!88@(M2_JM|h+|R zC5-hBiJ44AslhOne~BI|qV_kTG9)E*Xyu!a5^&!X4kUUAA-@?k&r0XW?B|sTO$;_w5R>6#b$*-bS1B$+A*6B!1S_&Z%;s?S?U9 zihzOI)A9yI4R*Y&xw0U;*LJ`~T2=1RYglfdU&<5QHY&W+ciVA~G4~rI;wt}zKA)=? zScMQQsA0nW!Y8i;yuYly+WndG%3<^5&hF3X@b0u=!P6#BrbS4*lM9De*IS+JzN>6d zkHTaZ%*EN>tq*VAyY=+xtw+k?m}s#6=2t(tW$A2ENjS9~1wEDmu+CuD0^41$UZDTz zB;f8zfZP)St)y6IlSmFh@3jBO-Zfnitr7-jz;Xji6+ITYyPA~eyh{K2AoZ_Dj~+f+ z*2LL!pnU?(miDol2sMfJ4Y2;!@BuU2Nzo=!YO3#u#_I#zd8iGU1Qp{@89eDJOy$rc z5=A*be?9qXezFe^X5eMt5wEU(wi>)iPYrT}J{5<(%Kz9ppVzkXD~gXKTS(R* z>=+yWs6C0L=!YYlEENBgVt3raq!2wr2)GM_jSR+(AhrffV6+)1EiQ!!OcIzy7p04= z5(=~MqD(1dmZ8k1yY6N&tN9yxKj(g*?a9=!W$EcfvJ)pq=ic)}oqOs;0%fcJk%}tP zo;HfSUS3GstcEa-zL+1`Sxk1Dz6ACWFiu$1$Dw1e=>u$^OUJw5xRmHV&(~DUlyWy5 zI$7X~#D*x#VsPm;Z{41J_UsSOo;~IuGjT+9zZiEcXd&Bg zM&29|yM$)cillG(pzq(F?9qn42Q!yOWzY9;k{bn6mP^w@t)WPC-{Y^8-GvWWPGKEv zMs617sjAVN!y&kABBM^%1eqFbB|9tdS&}Sh?lwEW{5D~g1D=0Hw1z_~eqVWv$cY}< z&M;6WI6Cn%p~uQQjx(^NW{}M3_N#$Z-hr3|YCjEfJ3?rh> zN~1ZVIE)?F?cAw_IZ@(SWp|vvBZq^i4TIfM-AHg9V77zQ4o*!0r*pljTu&%mKc7opGm03ZNKL_t){5IDPYXoNS5_KIQ!Itl^fa%E?%Qm8yHJVz{T zWVZn8eNHD~WsEiOVY%?yDDYuL2wbpp88TP!9i8oMb_)dvZ@2N}@XV;?6Y3bK)Gasc zfha_(p?2OxH{GCK3F-6Z7C;9k*Ia>2B6JzeF?WoQ!*C4*UpE@B1-+2hEym4H1;Mo~ zuLIsvLxYjvr|Y%#aoUpXByjim7|+sigUGD$bt(>5NTyux+Sx{v?WwoQMs*t?e&cM5 zT`!T)wej*VLg( zaH)0KKG?eI2M#cN;^MB({X6&W?d}?oefN_bjz5V3|JZ7I$FDZQCt>Iu*1vJlk#k;$ zUeDWbi?1WFGiBcb$8u-|Q4)@2kXwz52i^PY9Spj;q>XUD>PZgXg;Nb(KVP*!9UFYJ zyXx}iiF=N*6Co6ORYPgbqj!~tC0u?y(fRYxU?GKy0fCjhJT+uB&YN|XJ2qO$($6p& zdPqEwvY`AL`*&3NeQPz8AH@>ri8y^j=!*^MuGb|64c6UTU;g@6zf67YepPYCYO}9u z1)&yLcH+TPc5g>`V&HLb5PYp6>d})mB9G^A8&JP`8LdHHW8|u3HxqXPCI-Q=Qlx-9 z&4V=_4zi{=)mipmd6Q|3fGmUO_ijIU#@mBWKAxQ1c=TxF_U*@agsqpoMyy&7A~!@e zo4)3C5i}1XbCQBCL1*{+7ONqEQaN5Bc)I9&Yc)B9eRt>5`^5UYrouogYO72p?@)|53T0FR?A4?>qe3HU<=P{H-(;%Iy4YAN z_(`-CDOg68*QhaksXk#cBgLCX<`Yt5$##?gN)s7m(MYZ27$(LoBP(;(Tdt?cHL1zf><7 zu{Bt>w>g%=7=MihqtH4Bn->v6mjLMnV7Qb6Z5Pj#&0)wqi&ZH%C&Ta5;_TG<;%rFB zT0mj7(5uf8H96}g!G_HX?gH*nUv%0d<9RAQhX9Mkut@Oi)GTXWx_=?ecJK=nSG`_t znFy?D2r}zonS%{L4QSs^E2xrtc|V;dUE|cyn7KCf4a@Q%ani71^Gzjb8A_7`eN%=d zt$SZ6Z88nbWnIjad3iX!EDn4_J%vc3F$yzzUPifP7_7vskJ>5KY_#*rV!`ywYcd3U zBv2Z>ZhH#lb}~aaR`Q!nisUN=Q4&E(@$?WMgRtWvE{)h|^@wF*kBGMQJ# za=V;k;9J9QWY}w@)E?4q*ABY^xUxHR9ggWWq8916L9Z|CSRj>>!F9QfYFL457=H~= z*GYw5M`XnqdVIysk{D}6CgPQ@>IRuX;|tcF8FBNm!T(nGxLZaXjUt*PN`f-G$7LN* z3|FBxe%vJ~vyr(Dz^$LRBDFr~MQXK*KId`B1XwGp%-@b^Dbg5>25CvhtD(aBZN^HQheGwD*KBupAIG%|K7Cdj zq32&o6RpctuVsjy;`7bA?x9eo^ee0Fi+<2O0vgD*SEMKphX{q!hM0Wly)Tzm?_SxD z0tvpFN3#KT9klYG^@$Pm=c&I}A$gj-O1XTXO(sy(7vC-VD!1s$V!2!aUzC5v_FIUDAEx3psG&$ICL^-$eSXuGeJ5W0FN5rzS<3>CEx_it0RFQA338vOV&qTh*7NxdlKbQ&5V_!@6qwsW8 zI5p+sm65lp1_`|snTd^22as2OvFnWktx2zT>@M05hnt~-pGscOh4vv5sv9}Z&A!Nmc&uKpmrhU5 zP7j~byD&{+pSW#w=Wy}<69bLWz{?`c{-U~->dET?m) z0B9PXE7Ov6R&0Jxodp{{-<)0^zClp5N|e&mgg@VuTH4?kYp{L#D50)rbXT~?2a~h{ z1GK4jvTYYeff+TYUMbt^Wgd4h)L7%_Ar#W7%yvFC#K2n0D;{CcI5AO_Y=2408XQcf zAiCKd3SWj0gGz2S#86J|$5BGD3eU4tkyBni3j0-2jG-;&B>S&yXRIJSX=N{4CNFv~ z2(q&HeI==?RQ3u+hBxhUvwUboc#kZsO0BTj$i7DBT&Z-+g^NnrNMqq}^Kh@r_<4^N zG4R`PnbldtewSUlC~MqYYaAN(RVtW}RLWq?c4eFmFhky&i>SJW%1~AnC9nrJ@HCv= zq6BzLYG<_1PiZ+agnbGC!**+$O%sr%nqTRr8!KC9c$ADxGuVEzX~2x3*j@{4(L20C z>_=nsnCLC4kIG8vYS?c)8>a#3!oJKW#(-;GOi9}xGT_z+@~i9BN7utCuktnGn2qah z;iDLhkCv_~3B5qD6(?dX#S$%@rhV{H=f1Gy;l@LfuzvXA$_H!=`1}8=g-}(%AZqJc z?~#;O-o?;~l~yMqk@Do|D9(M3rCA->frY=9tw>SlDuPnUl(7if*)T{fi?XLc$0}X{ z$zRugH<OgdTIA`Y`POv2`}DZQpksuO95_p@_(uj3Z;uvuyul&-NTptxT3W zwMuC(lU+=TddRSls4HZa*kighmqMYK6>MYTKwx7vIpi=l3N3`K^wx99VaMHe=qb?r z1^c|--|tUJAL7K8em}`i5qj(W`Me*T$Je=jPx(oD7?}`j;j;qO>pf>wVhy|;3dlyQ)># zq4kJ)bjERCk}G4N=uS5ptr8fmduH!vfKekw2&ghKMNi@ori2iqvC-K~C%O~KRIL~I8E6g2)(uh;;whrXVnXwo;O5YM^!}} zmSM8t_xalVIP7=6P(HWQg$cC zjzXi#D4Rc^1h_!SQK2wxL>T8Uw1ovp8r5a93mvxms&@g1 zwL1-m#-gV+yhe64UO}cs5XX3$!LwZ;ud)IPPgK;|K>6U6N?HTyN@e=pIR$5F94&?P z70`J6%1ietfbQBWvuw9ZVj4MEnZ!=j{?Aj1ome(w;2DXgzJ?9k3%8WofbA_N6?7u? zRWuJFhX0Bi)0vcz_&Ju)=sA&RIE^xd8DbPhOoV2wUCYmw`P8vawqivyd zQlcVhQk6)h8YhnjMstlG*9?YN?_lx`?7*Pm{Jw+6k-=FFGAz#7I12969+3gL+CcX- z*#x>9&7*;u5GGl|9@l6C-kL;Mb-O7E)|Mgb(RE$E!w7myVU(*>CMg#S%`|IagKpY_ zC)L8h+jT-c)K};dI7GG^O_%(^rg*R_$Tn8r_WVb z&V=;ox0`P9+X`bSN8yu)qYO%?b5PC zZcK&cz`y+Pof~gtKJ$8KBf_V>g^(F)*;#kJwjNTHWg*U24-GgA;UxBS!4W|h+|l!< zAC(ojn2Q<7uUwFFUG;=co8sMN8;M6Q>@sQ4JPBu_@voiu`6A9UGJYd+ z3aeikqDHE66Lq^0A}6DXY&NQbB!gE_T=ci<+JOn^Fv1(D0<cl$+zlOHi>dMNJE+fn`pd}EigFC70mcnFWt=nDEK^uOql*=nn z+cmq2A!!{LHl|EjgHhjEhRm>C1LQQ`Ut`ByQxxUhd5xsg<@6eTgR|o-gJ&lgRF89? z^Vz$0c%CQ@;MO?qJe7o$A(23d{+U*!G{{TP^LS-?4j}%gDhfXUn66l`|dt-!O33g+0T#TiX37%p^g=uOaCOWUU$`mRU zjh)$jwR6c-F{Nj!HmT2swfK-qXtV4V?J>jJy;6`rX}3$peGQKr^b)p{dqKNlw+!s; zqtfI3QgMHu3Z&9wJW36<9g(kr;;L8+jtokJV$JZFv2;)x3|1S*2DoYfK00bVLcvsm z76)3h;tD1ji#W>3=AdC9O&r#w!FLIJu8%%Pb_!?PO{HL0B#)fXCU zS(@-Js}yN)6#L`lk0;Qr%^#K${-7M`d(o56MOCd(ZFQOX`I~Ql+1mVgxODyR4_f`R zF9(15w{Ca##TRFxJ4xDT0rKX^qcpQ<&#u3H`P$X1fBs$+)_?w{K0-~KT@{0?AaoEc zah0Dkx1PI=d_u=TKimKxhT!X>u(l6d)Ep@e+MAB-nwT#wNQXjQt%ZfVhxlS8v~}G9 zvI8rT;z8o|V)AoVz%FFtrYk*ilV^_7KzLL0=bK2fexrimgHMwAF-Y)BrSxbuQHg^2k^~}jpqb7{80b!?HjK}Ki7EH zvA*Snu$X??4|{vA4NzRSCp2>z(2gRzO)ucvtGjRs&1qdBuZ!YfoO|HxWQ0_1gTklI z?yGPMxs{9~pZadz-m>ctJe~30T7JKLS&>MYfnPQFefr(AXWu@1_MKty?(Xi!t{R}G zUU4zb+q#QBS|v!7VM)|CWXhUM6HfSI0%%g=~nqOL7C1W=R5W>UOp#h!x(TGGCQ9ZBpb0^N~iCxEzRC7gP_D%%~D2~PNQvBD%R}X+4OX} zTv)>oY)9-PjSK1twoB-0y9|K1xnWHn5ED7_Yel?KfBs6v`kFEEjl zL&^&!#xm@knDa`kiW@;Ix+NATv_%`>NGyZ)iYl!gN*5v#(yp)otAN1;bAZIrXiCA* z44V@`t<+el`{YvM2hQOZrkaqz0g|xBa!!hsR0Ll>l`}+cqm{<@Yb-&gq+-dQo%W0z zkav~O?-hA=;xH%dls!|O6!UvVVT+BnVQeY6r&hwEag4o_VrfvS<=FujS^XNdEgc7w zcCr!dKMEQ}l+XsokAl5MO=9Lin&@Evxb`@(n;YW|nvh@&Js50hJgN!fN``zWuMDS~ zhPq8@l8w4*1gsulj79eE5v+EL3`%8PF>&5ny)DzPuR*e}y9FoSlE_M(M_@O6my=C( z1YZ~1RoaHJ;(=18sUdDEaI48*gLx{0nS?hd?`S?QkJMoG2!?F<8%(C&xZM0vw&V-E z*EcJ?c%ttuOQG3l)AtNMpID!*z4uP#XTN@M_U`ZB|I?dGm#vRqdhh+$KZ6-}UV3xl zvNf7o_k93In55NTUcC15)oXh5Gw865;nV;9chr02sIvoDzv*o$XhT69Byc!yu#mZb z7{)&LeF}$5!h+%UM;{Gw`v-mq?WWJle0I}kO)y1=9pd^7XqQE4PsNvs8)Ny;r^59v zIU8>&?pZ=C{w@N|ei(hz9a}v7M82bTia`(7BZ|PNWN=|vDQ3_K0j@pVNuh~RhMh~m zlE;cJ3wktjX3XqUDSZjURM=8DszX}-=npqu%VI<7F-}z;vgWtG$-pl^0k7U@W2z~t z)W*xs8SL1hGun9QcHp^i;OEnLe|+1~cHQ+iND!@DkLRJ4_>*Q_v5`}0sTf#E((IjQ zBoRXZee0Vi-#xR3!ngJZ2)5T~yKJ`YSN*G3PfusUu0t0h;=EJRkIi@?)oFdk(N=kN z7hVl-?U?F;_dZMhJmd4IXFTZ#M(g2(nxD8w`I4JO|DUY$d2RbX<9H=mnk9p<>_~Wa zEj-DSzEWk^Syb7vr9_F-xeOv}D;`Q9Ak7BFl~&6d_%dGtff6X#sYwEc<`8noz+@O2 z=A~t)?hoi;$K8C$X@|n@dtT4;{n|?kiGN74q9nH7dOx4{^LkHP6hNb0WYN?I@2}d> z-W_#MyFE#ytdB<7%@sSk_zz#56TK(vPta38G3Lcs0C1!~8lWUtjH}#m00@J~vro~K zz&9|nb=6;TTqLS|gKQ|Z27Fu`Wz$#BatU9dzdqU*L|FY=st}8{)(6N{`%q!lljMZ} z*NFj+MzxD@@v-7LGH|40(Y)w1r?&$ly1Kbgtw98AQ;J2e+yA-WQUgEouP3NQqt4P<-q?U-XxzzMOh6-t-(?bqokqv&~34^ zw?Jf&|ehLQp9f;_7nGGdf0+tVa7+*dxz5t-Tpic}h zh)Rl3^%4fpJQX!Y-F?VFgM>;`2^?`1XOf|GAjS8@AUJd+!J3RaPQ2M}$D2V%>_oeu zJgm4A2WOv6pUAs7wph$^T6}Lf&A!n|x{8#R+b0dIZdQ}fam8STk!4nZ8ybIZr>ifr zg{<>}adWk^+$=jM9kzcTlnX31iS5-aR+XI}*pt;|6GYZ;L2-yF)wNx1BjmcW@+d_k zmljAt(}c9Olvvp6Ef+vxv39hy)bF9RJ+_w?mMKBf(_p!Sg=JQomJ3=+xpaKgTKVGHXV+ie|ICqVvKLyjE9o=vh7mbR9ubS;q&3mrix+<` z&#_((+C1=Ar$1t8ONXUR7ss*fwIZ41dc{cY^w}63dhDyJs|l;F?H{>k!(y6O6_9n- zI%q9O7~E|)1a0$Xv%Fnx2iSID$vJ}n>+|*D;EizO8xdVgJda&=*M0AJitH9KAiHcS zSv-3C>u@?K-{Fwks2o9K9DN=SRRpOBz`pH%6r@1;*q=QJ9bXp zFx9oe^xWCUbHBL%r|Z`O$9k-qTiv)KmbKD#tMoRylO(+Njc6s#PM2WGUU49*v`r(Hk^&3GY_`jmSb2opf0=#zTqxW4h*R+*E7%9Z1OY_*KH>_;YR*7tT2n99G z)%3F)eKsGwZ|hk(MR4R?#`Oj-F)A+3!@3w;ikKPT+-gNf)T@;)5HMbK=sz9)+6M2u zx|n>LmFLocf89T@Ua$M2foMR}H2@7j^1nR28a9KKqJSbQ{i?B0D+g705##7%ak?aO z#27=DG&hX>WwIQlJ(zpZ0JSEx$Zm=4WvOV9NjD>BpRNr9!6HXZq&i0CdVo`DbUU_~ z7yp~jfXMPGV-mIoo5L}7k7hHom|ybGtrp>E-4Ld>aCRWi8nE^NXTVhEX=o6CTomDL zrHZ1yGY2#BnK)(|2q|Tl`JU{RRRqt7BTfS3AQfG-{oi8oQHsOgj5uVHTB+2dWa=PQ zY^BEOMaob&SVW-3?}FkGr>c;wq0od_VlvRE>kxK%B9)wg0Zn*0nVcYw#k?7M)($+Z zR0?5+!1346(3G9h6p@3hmIupmYwZ7pCM7)Qu%vFU7!9cv=(| z_X|>k_27xATRXamBwuoiCL}^xQ?~&^>ol5~^@Oe;4G)J#Xl)STelNx;{<>eeEyM*l z`qlqu5mz6j(i}eEjHBz2pEY3xg_7Cypm<-pe}daT{RAUl-O5mz9GJlDvr z<4~ZH<~aKpqm;0TibjGBrBw1n71nxk4uu^Sk2LJuB=anC+zju9o1E*?%8+iR9m;>@ zBbby62Pw#i5^F_@S5Rp z(D=Imk8-(ZC%}Cac8fgpLQf&lxM$5^B??PQiC*X}f#P5Y{UF=xC;IwDJr1Ec2<{=x z)x<)7iB6_MwY=bHaWTVkG3|vHlo?jVHYXgPJA!_9zFazwF#m)~c|MP>)!y0}cBxmT z$jY(a=;5^+ho#rQI{5oawpRM~P%b;VS33OduOAvi!w^}n5bKtb=xODu=f z=gaoSfE)~;$2@^9ZKdP!@SYa_#?zXAc5uW^GKWFN)7eHN93KqZ67Xo+&jHM+{tE8h z+Z0W`dUFwVKLl6vu3hPUvr*K)}WL!r*ivU{I^joa@M`H3NFg( z9X50WI$nYX001BWNkl&wjbV-gGX4EPUUEs*1fww9fwoz>S$*$EQ zx_=iv1a{No+Ng}D@4CB9PlJACMy?Z`(lqO0y&j7~fQGaYdqPiege71WlLlf>IQbK^ zs`)H2tUL?<(+A~h5g3R6@n9>a&&yFwNJlWWPjm@53R@DK7HYf>bdnMze(4G@^J~Rm zX<4wAENB#3%aURP8S7ILRn8B@^12Y*iXq0@M@acXG$TG3{KiZsh9t+d7g(%qes*!- zKx8>DvWrE=@3w$O7xSr^Vus!$F{nT&;X!9akD*b{pun2C!UD^kAkoQjdKkp?%GG}! zFQ$^(*r17MDvna)%7KISrY)Gryfm-{T1a^vr1dT&~S($vMw9VYgl@Sb)zBcHyTzs=H0~3 z{IHFuX>(w(j7wHNhwTc>b)xekyrKD>d2k-=3Tq1ztw_Ve%7)evwCFGYTmE`98t~U~ zzwC{R`3(eofhb8Ue^hzU!Dv7^S@I%|C1G?ozzrhGf9BM;9@K3kc9Do%MIyG-$bzsY zqS51^yzqy(H;SezgHqYIO^0=*Mk5`D7$l})w3!CTHyRgv3~i z_nLgp>Tg@~Rvj_J4M(Aq;cB(*bev{3Ey~z;l*Hj+dWl6>b-AdM?Q|$hQjSHx)9!(c%TA))sg~1;tU6pnZV*-mV})8jkWWPP5^ypKMbo{fa&-ZdDX4pg(dk)q`6n_>4tDYaada1D`MMMPp#bxkU6v& zIMJ88cp&dz6vXQmls#hjEwbAN?2^Z}{#FXQR;$(CAwj>Rz;9h#d#eq})!)rp>BB#| zSKPjESUS9P?bS-t1#s|X2RELXbd!m8(^qH347JsE)&OZv5=S*R?P1-o1NiE5qJp$R>E z3&3;M(clrV=H||JlqTa!u zv8~stcuu?2E7HFE8cEh7U&S$6?;p1@u!dIg>d2d}1|wjuB&@(GEbxC z>z%a0PScufNhYNxF<+Z>3TBg9 zVZ10_cu`md1!pSW&Gpcm{R{TOD`AAa-{+j?m%5I-mD(n65@RXvdC&8lj{z_$Xv5MI zIyw2}4X(mYDX?&0{5I@ z=2Xd8N#8ac$VqbcJ>~8yLDNNeNuR_(Qjle2YT@!Fx?)DoydE(>U>yZK8bVl+e8RzL zA7Q)AqTTyYi0ER=UT|`zYzGs5XrrkJ=^R3Ae`?v)Ck)IK*2~~$8y3bGHB;F9px_3q zBV_~FjgfT$$yWskoV`q*9BCQFm9x-ddyW6X>6>A ziX`$`D=;OfOxP6$Etm>jbRKdo%QH%i^jLljq0kK72##%|`B#8+j9(Oh8G1Fgjk*N^ zSNVEV#m_>WncM;H%e8MXFNfsjO(aL>&)6^_aeLif%tyHLZ`oKn=mqV?1)IRI!{KzZ zFj)VP124h{jB z0nG{XaUo7=B0CGMNJ9~y3tdR?|04P-(ul7jXd}{Wlp{lkgBH%)96}dTBo5Ef24v5| zdm(Q|cqAaWn4nxbg5F;oEF+jQv9VP~AyRxb4RaE}Dqe;#i^gC9T#ATcJMwP`Hm?fe zmQiz9-UYCgL0D1!SHXkRLV+vj2i{0?oSYWq^b0ixmxWq+t~1x^z>4H&(O`OZ6N%9p z%`wXWN{pigy*snB7(AytTbpFio15va3OX5Pi@SJXvlC`87RJo87)F;#zp1E>Pklb4f9+yFcX%~_cTcdamf z_RM6iQ~ka7*5`*9P1`T7eP@(cni1WtY16`iz2}{Kmh0Aj*g1Oj>W9PbX$EE6^bodn z!K?e>y6Fe*4!~Eb?_dwi(=E5Z%;3;bXZ@gXtLb`fN(hkweTl_LH{F4cbC>NpdXm48C<5y#p>!#k}o!M;gSiY zoFEA{U_5c!$}lrC7)W3E;?CtOmxTeB6sGD%^9f~0{DuJ zX;(IOtlMq&Rtpi8>=CrHB7w<+IBIKoM}{$@mRsIMfzuXY5`~5+8bog82wECYKxl70 zunU|DemZg33C|EJhUK`M17{>(wF+K)4Bk?#iV?VhG|K|xH}4>%~|)+zZI9z@*@<+zp=*niYf^3-Y3Np$F^@v#9}N zW&vA4V^2`{ue`**+@jX1=Rxij*sf6FNk()aq@!mA(0{}YFdB^}=|9>J&`X3CBZOuJ zp@04dGbqP6M)p{UqO`E`werZk680_NEKsQ_96^RtYN!^V*fYv{V4^WnD}xr3pWy+% z8MH~ux!H=P`_sXk;6SSj7(@d+!hGuU<#$rrJdt0dMws+LsXC@G{a&#D~gFfoPbE z62+HW@r~6){AHQGBtcfeQnU~X`Q3;l{PA5Ox`M}B0GnKZzrR60sa* zfiJ+V0Bl0lP3Rxw%C$(1G9||Xj*vwci<|MSbY<%a9KztftR3`Y2;Bh&r$Kuwb43&b z!<94(&o8FQTNQR8X$dfZ8wzLi7y`%zsN;gq7_3;pSl&b>v1zo> zeiR08lqto6ODgRjzjp9Z{n2|8{66vdgMz_<@u>D|50c{Z@%3P?pBULa&Yivb<8i!t zH+QF6jT{bMX5kP0oUs$-PS?N4!eUhPdV50P*O*#Q%oO^~ySFD_)M`7`jy&KnxBjSl zwBFC3d-2E557&SE?m)0MxB1mtr=}qsimkdNZg-DAxqbcb=jL)bt6Hu8=61Tq?%zQd z5^cX-?Hx?Apn>CQLT|FG0UTyD&EDAhNnnfUj5TsRblI3OC=iQkq+yaAx082a&4;Ig<+i-IA8IVb zNVXo1IFM$A>`8PBw_;of3otvpa2I>QneA?@ilLWg2DR75EwEe)c+vgK%xHL)1X5EY zG$(nN8Mz@(aH0swi99SMa$woJ?0m4CEjVMbRLUuA7M3I@3`f%s3e(wGAv65|cBE{k zAOv^$J^)!LFS?Inh{sYaqhv;9FNQph6w)fQ7&BA-?8#<&^1a;E z6Cj4l3ihJ_VmLgLS&zk`G-9&?2!Vz+I&dGgNJ@PvgZ6j?lC?R(Vy6+9FfyKnAAdWB z!UoucE$E(+%^`r?^RSU{%-RRR#k01N#*zQl@>qF+dA0$AyCVDx;MG-9OF7(Ell%9I@o`cW^9HeMz|&sLBDS;Vpxs%J!40xIWd;$_OD zdVtfF4qU!K*$Qe1kq8YPbQ(}R#})BhrM!iP27&D&GM&qeipJ{{0q0uNAT*gaBbt(k z^ZxW46w>kdE(X*L=D_59HZAW({s+ah>u(1i&6;Z;XH(W{ANr4KzZyfI&aOdm56^{j z$5+?Bxzk_x^X*U9zIs|a*tz=6*{3>jKECeI^vRqy8+CIgU88H%&?R-4V01hGGawk} z+n-P55veQ38v6YG?W6Ac_tm3om-`C2g22zKcQ|%lH+hr>WNR-zDZF@o_TsblQQ1GV zuyz;hSTML|cy8TnhqZ-49lve!nZ#FZWncz$()f|BdlBpKUmF7v6@nrSLaxArDuASJDr{a`u9g{pthEp1_keI7lYaK&$Gv62r zrBH~Bi4B3~BJ9E!BW+-XrVD{VdL8y(>?+XzVDIPo9x2||xvs5qe4;q1tLHrL`~0}} zB5&i$Yd2gt)-~l}xhXUtd}CT}rScc@88L<4QVXF<7f6Agk_IA@NYH}KC38x}qA5vw zEJAAzm(Rsdjw7&q5|(4OI*uBN>chIIT+t;+GNmp$Mb*f>EB;#c zrAtNEl{tyj3N)aEmx=O{uY(4?e{A=Bp>qB zcJcFn`A#&S12cqv-mDLa@op~nTku#pmgO4CyWiWzMz$0)U6v?HO~u8!HpO+f*Dbnq z%zQULE@A3A{@NvyT5*z!`m)pY?kIrLg>Wk2(#K&1hPY=_5=nU|wKqe9V%{Gz*q^L- zcpK(oWHz~J$QmGIBh;BB0y>BmIY9_khYmtR!&nTWYe@WkKoR_>hRPk91>1JCiX~}N z`stI7p|VmslBa02k{wpLt89A7%IbuT@e-58c6Sw}G?Q%V2T6j4@U8~r0QPu>w%<>f zWB?69lRg<1lZNCb(OiYu3loPGAOXu;ARfB9u(05HWMvs9dnZd+l`5V}kSf*o67g7u z)KxEwNr`Z1W4a4oWv0!nc}X1Dt334}!0m&=($l9NLTDqx?J7~$CVAsP6~TtN zL|tW%3rkVHnw=nygT}#$?4J#dQ&EFv`Fag~3poSe)DoI!2y*>ghp`@ zUxktwesLlJyqokdggOSq5dauDR)~H=?7zV&Ji=N4hth#5N|9(~h^4jtl@|#cFE29! zTRYEdk-amE3lYPC3Uo@GSQn)cU>WM7vWjnQ%^CNN??mFaOB|*#CB@_O>D$C^81*&q zH5NRN1{&lo36>l2Z|xx~Uz&oq;~dm#XSMxOV|RD%w$Vl^8fyCu7e#5;oZ%66R^beN z4hFNk8A$X#Fy7dg@ogw;4*&hw=4NAM<^M>Zp zml>#o!29;i1mC^;BNc=HlSujB^XcY)4x?YhL38=tKfS%Y{N25GK3o3y!5FoOC<NpTBW+==P_2q?i%hk~n*6V&2*04Mr3EM`qUVlT| z&5Hn!-+Tc6;d$$(E3{lLj~W2`uJxhl7%$&Le-!Se<#XQ8q-0W!r5DhruA#+$Py1zk z*9wIotnR8E+)laZw+;^F6L$T;;C5XiEC$%E;jmv`AG*Ooy}a&Xv&;S*++}0g`^|fi z1k2lCz^SSfa5b4sBr$m=V=&s_WCAK0(3>ntR3gz^bgD8sHpHhvqr9QeW`I$$i=K?N zPrObLZI$phXvm7qHz{1^6u}-H4m;uCCTWxbR*HtxCzIjWiJFtb;Wne_)ddeJw8v=L zK6&4J_mhypZ4HDuGuO9nMregH=@qAJ0@#U(Fmdou&h+YRGv!aZn{H%XslbC3Q?- zmd4i@la>r(qXw-EnhE2$GZWQ$1LIr)t@8oG=O}GSg+VHn9oVUqrqHt!ScwNIW7HzV z2B!zvK^6}aInc(LwN$pxvoL6kz$}07*i#I0;>^xYl$&K4jFL)AVHhyIMyRjAcy$h< zY*yW`xN~l05Eb+q;^uM}|3YlEg0OHP+2z-%BSaVQq=Q;M86@@jGz{Rz0z4+yiqb(j zkUGIc@YK#m&`GoVrGbG92*5(=j5~=^LMfsXY<(GFr}<>(26w9#f8`Y2?itjgm24;Jb8|*{dy{ zfypdajVP1PyqNhMw42|pl{R*vy0Y(PRF%N`wqb~ee0edmN9nIqG+)L7e0go{lTY}> z(pPq*HIg$}@PfLZ>@k2|yPVlzLrl(wA@shB;@G1oxR%-5Tdd&|-ZgYyJX>tcFYaf~ z43BG?hcDLbc3@*4%FZOZR#G??W~A8LcYkyT?1O9b1pz*v#nEe?YhD;5aB~#O@$ySw zH=EyG_)=H{c9CYO5; zE__M~)`M4edj1ZWL3C?`zs=UD_^9QZjzoBMkXQV3-vwY1Q0U_RTk0b8H>URkS2K}^ zH%6kXD{o$LQ)q>8i0)n+2UKeMEE)9j8pb*U-gF}pw;y1XRtT`B;t4vi4Rm+rB6DD` zw!^m-SQ(Eb<_xvdrNgp6Xr3MqoL?Kcj@}qAfHk9*NZQW5`sp98zMXj3?G9ZHp`R?- zb?F(1fMINPZ9W}yt2<1VP%6Kk7nL1#7mk{gl$;?_tk_8=u zNnIAQimk5a{jsw97nWTts)fSM${jP;EtYIhXs1DDIj5bJ%kC%WJCaqao_Cwzyeo=w zg0HStz%AF+Xn%+Nvfg1Dv2)U1IFre6r$ewLOh!5)?gA- zF!@+8pO}$k;wlN8R8U8UdGu*Ab{Y&PpV;g3_h_*&6o(aRNj+iEl?E$L8WC0?>?wXS zFezPhI2>frOCd1F_S;W-o@xxktcckGPrB7E9NBBrc+{>K@>Z(h)oO(*hOj}bS2gG* zgkynrh7*#Zy#g0wNs<(+UC{=3Nef?XhM7eh6+W)cEUik`T!rMa5-t=xM$r|bHVVhb z$Jq*{NClKw(Iq8Lsym6Ur0h&ZOWtUOu7;V319Gsk2iT3WUllZRo+0AWP_=NN_zln( zA`Hgnve`RXM9tCEos{cKV(A-YC2ao;2Dt&b&qQhDa#>l02TZ1CbL@ZZ3Luxp1){BH z0oIg;%PT2`V2S1Clo*{Nfg`1jFv2VXC|9nphymxoUqU!$qZ2E$QG@CCuV1jcvp|R5 zjZGZkK||tLB8WAZEK_{I!Qg2897+TOn~_-XNhowW6-4+<2!|>M6X>2*2n=pVKwSG0 ztqhI}M?z212~`xb<(-leG_LtvBC(_KTpA`!HQQ8r9(rrc*a+|T?F3014vOR3b6aWS zxFrR2*n=tiV5GNUSE@+?_mK#2ys;w&T$244;N6}tWsqYrcqR^O_wyPZM{~7#m~Lr@ z#V?7_86N4av_ZrL!Y)HvfXS@Dvm?_!TZXvBnY$N%)s{Du#GO& z?7ORJflX31w-|Oqkbdj_Im^-i37s5IoX^!WX!YA$K5rl%e?0u~v*qSD@7z0j_oKV6 zE!gljaqAH{eEpTj3WWYQTh|iXRC-3^r~H^^{205zAyp6@%4b<^xy9yR-xwdM#c_ROEJeSZ4%nKNgvOrQGbqc2XKN`v=4 zI`@n6qu-8gEwvwC|9$P7Euqx^9J?_%V*bX)v$6Xcg0<0B`!5~9>;3P)t{px~-Fz(v z%8{GjDf((ShsI6z-_W&e05PvMIH6fo-zf1sgRmeKH_~hne|S>IY-@)ih`z zFjJqe5rHSBjVSt>`hu|_UcbY)G@3`U!fl~;VD%SUk5D}b@+$<6wknQRK+kCy^A!C{IWrCJq*ZiGe#^(eHKUXoIdOBkUgZp0 z2qi!nh@O7?uMYw6+n;l|Tf_hGNud#5E-)VHQ|t{ilm(>92t za-9PkLiyHiU*3r!b~oI`(0QB!=`amO@;%)`gE6Qc$G?Fri}_b!8imosfLv(S2s0In z<7EJFcsWBqQV}ZX8VpH-r*e6w;9llLx|m;1=8Hm)vFt@aC6vvjJToej?A0a+001BW zNkl%{ma9XNC8*OEh#X@O!yI_@;OU&X}wqX3V3W=idTw?8RG9f^{ z3(9OIAbhq^jwHvvMI%zMh}J<&mn{p?9O!EJHjy|MPK(8G0={5iu$NX#LSsJNAhLc%jN~-I0I{i0b`7u(5gYAv|#jAFL*7t$-wH+Afe-9x$+nQ z9b%?dD8x1-)FkbF>J3329h$6!5ZY0JXILJiSPA~4Z{#r$8O|knIyUZb9&quC0d%+9 zb!z(63d*v$^L08M2Yg=%q#}yL#X1I`a%3kRz)sAeL5^bx%L+sfqR8opA{+|~VSgYB zkd88JfN2|4V<8h-$8jiSU=qDQnnmN0d|*K>jl6nFps^iG3EJ8!dG;@6+16mMVFMh) z+}R(a${F2*@B?EXTyJJmfX^k`kK(p1#4sCQW5H2<=|PjV!2-uH@YI)@+0A(NRekdo zn+-5shP9{3X9(ZmHn?T8o41ZY$vPy+m;)n^s?LmN2&54nY0t=sxjL-80=Wv-C9wipRbJdv#P+s8zOseD5Yk?hODBY`rDmTfeTg`eE)+2%9rb+nNL^cO>Up-`k z)HhMV(6n#Gs|f9iH=8X6ZStkh1TG$Zc=9}=v+reWyqEtx(mbz^X2~c2q+LF``Sp|U z9^bfEzP)gW(5e^K>+++)0%Ta#tvi~eQSNh{s}&7>T?ellM!eo%{nJ_b&^!Iv`RT7t zeeu`dO_3oVUjB8teK$O|-G2OsOIr*3g1qGyf4On_kbMi!wjQ?Gfy6Y*_68==fZ&(E z{N&>8k3D69*&h~SrigIVgJk-DJ6gYR(tZRiX7F<-2N3Re%oEyybNbjgf~kc*8edop zyg2_k=gWj#76EhTYevpIhPq%poF-M?xU&X%mB*KjEh_NBZ$uwJl#AYI$`$pXbi_k5 zo&~k)mO*)*++M3amFcY23()p@+ z_o2v1h)j=yy*L_|0~@N3W-NyQI&T|t_^CT)|KH&hU3FXOjtS$KLe1ion$svn)1qV@ z_RGQc-B=(@I2DfT>+aK4f=DZ7?8Cn~z5>j23B<1OBUZo~*K`qk zkYaWdqEQ&TT@R8p!YehQL2i^YP-hhu8tg`l7Go;qDV11Z^#j*54;u6r?ZIKhXfX&H zXF!5alCdyX#!*h2YmD6}AR`Ns=>6pkhSb7u_lwIIMDGJxGj7x`$k%*L5Ea23s3$Ds zA;uC$Tv*O0q10Mt2uBIz7+_lnYW`#)nFz{3Z>eO_epK2PXiX-V(;>f+wo$ZDx*&hH ztz99uUeH^C+UtaF zQz(}w_aedL;N)(EDl2ayqO}ZysFpx4x{t8S1r`sygGhw}s|pGg@E5erl}d0R*c%zp znuKoPNz^i+sE`%H!g%+D_(me3t8!w1L=Jg|;EoE$(VR$+(Xi$~6R_N?jXQsII$bL( z2M%X|*_4<}yX2+|GG}^%k^PLC1z(^WU=%c!(SpK0CjvO+l*cEx@xCZZ7_bUv69aWv z@)Ea$Q``m$`{ zm7v#C%9!GedTv23EufYX*vlec87gBIAI+#789Uk@M#D3#PcRL>=rXFeAiSCpnmdEx zbDV)3cXaEk%B-Gn;9GOJVord)S0#HkLTEMy&#`0)jwVKXXj_BO@M;eNY09-8fbMP* zs&Nw_uk2|L8t5i0Qz(yUId30+c=!7OE7GX+xBXu0?}@*c@sx_x?eg=FuWwzSe^dVB z{1MJQ-#Ygye<>p8o^So;-jipC>upvUnQ8_FUxVX)CB+-^X?WrE*(fGN5Cp`pD)=e#8%>eub4yH}9ka}h{ z+k+$E20C_u`2YUt0}S}TZ-0iZ2@#_G3y?wUIGZ;`tC*pi`eN>_83_VOb#ADWZvKo$ zwXGDj(;2dCff8>F1cnUE%1x==Op69NRbFj$jItZqTjbJ=7Evd$++wIUfbcE6885&j zdZf!wVjhR0t*?fF-|-cfqb39g1LzfCF(gz>Yz`x$((QJliqJK#D`U=-h3V`=1ud-h zz<}mBR>Z2Eg4gJPy}!^eyInXbAKUvJJg+b#iM|V=0C2mWoAI4+5V{g1TBzNb@gNy25ue z$z9eiBs0)d2`L8fVqc8xjbu^&l$a!0MDYToR#qXCOjwx&iwcuWqb#BcSoknZMREng zHK2mF(D@rIAf7`&H6hr$od_njy@Jqi2nU(Z;ngAZG38oZ@KPh4v?58kd@TXlPw4^{ zIxM)n2d10gco}~sf+%A^B-ZgBRap^lX>zbPSphZ!yw%Z*CgD&Jqh{oIR0Mm4>SA~u zN+3>}L+C*W@XCQSBv_O1BWWoEdVx8Ko~#Ts3mT3z3ZGq$0OGL1T>x(YU0N>Ra&vUIFNmryIZ#W*62`lV1PWrHMyq%declz!-k?JNfxXuHGtbk5H> ze__92_jTRRW7@z6qXjw|!%&j7h^o{D@qikM?9>h@i zh3iL8)^GGJoipu6)H=wIykTVF5%3p1MizR+=)u{ZfVuV^kpM4POWy@M1RD2m+Ad&u z@a4^sFyLQ0E=XlZswQIhFQE}#d+Z|0H5kf_P~$dVZR$h6JLz<7w#Y5B14#fbut+J^GHD2gSf;?M;FS#~ew0f8t^TZ96K5PC+ zPN&UOleM*UkXr8@&dwJ#QVfn?VsZnMd{gr*F}$xn^S?ySq&w^jb{rJ7`oc9sGp^(W z8WwWXVc(!Yug}4)E!qg3s00pfqx}~M9Cm*T&#w{m2?=&PYjQLkO4?~CkSjci(kv&4 zvBQ~1B?Fx-%$k$~J6J(uB;5%MF@|6o6K%+>6v$8A;K!IX=T!kMFF@qntD%uF3>$C_ zsgq&YeF3}(-~jF}V=7&SBC95di_FPZ=3!;=W%PZxJjw+ZQx06k!VPqn$w@H`+(EbFqNUa6emYc83&DAzuR=w}3K+7X`)E zcoAagLg9U35*MC)fI@{X2GgLy&G_55h+4)rl^SUdq~oQc#!bboP^wassTXx7W4+i! zol$cr01WVDGKN4atABUb;_@5#yDLz<%f+yOFcnwSLeriEr_rV$_yn(yS4;J`$n#h$ zk^N%zyV^uF=&-ULj1^V6Vz1D}HcsR`d=l=77Eq|s03v+29yB9z52>HGD+oP)I z&V?08IbiRIuyZ<@#?d3wF7vheeRXF{L~X0j*zP$*TnBcHHqPTzYs>-Mig^g4w`OnZhdMb8se&8FN_Ja>pG+oszY=Mg38j zrNF2Xbas#(U85)~_|iqJ#p)20*Fj@Z81+kNXb>Xo>~Ta5>MgHOj4k}RMgvpLQKR-s z5VjW1WB1ERH14_c?j=+g3K7Pv8RbZ2Xt9=hy;=p`3}N;XE-&@U&}AjcctMnCu1pjWF+O z3eT`Nt&-^w1zD&c45d$yd4=f7WE%44^psUe2!~EauAwMeIPNxN+nedkL9b~OZZ z7;<&y>U89}pvysM6{ZVev%`Q7$%W=56fPJ(J|_F6=ou#%A6T!PTU;viq#M}pip6}< zJ`opgNEZu%k+tE6m>LedapW>yQ>B7Lq*+1>EH{dWf7W%BA9)lkukD?u3{L9W-({1cj-DZbI;k zG%O8(9t$x>G-Z4j0_U|&2)8iBMj{rHHW1Jer>l4*jw6e}(CAoczZ_fAm2)cEdzF{wbKlS_$tU?BR{H&Nen6qE&h`BS^3cMn=&dYx_ z`nhFs-b)u!i^NwmDm5CbYRRLuf>54Yz57MwH;;F#ulC>Jp!1(U_~zXISFqvg(bN5B z0B|d7k|`UML|Ga( z!N8yh$b1gX^V5wr*VnghJ%kg9h9w-%6&rCVVOjw#e??Z*5r40;OkgNsl% ze>R$hdoI?EZh`muyDTN~1B&4QCiKR(=pF8#wH6laItJSZeEDd>ZYHD~$tq;XJ->J7 z*Pe@pnpf2^3&9cdt9C5w3=O&zE}6`V(kcZFsj&NQ?cfR>TWfr@0O5!=2G#(UtI(W1 z{%vT~R6}>mBTZe#qr=bM2YNSuf5V zTZG-V$^%S265mYgtmtH&jRP|1ZI=_m=O6+oot+wC7@5vtl+Phq!{>0gI$?)aEI4Z0 z?rk58yn>;pPGoEZJ5J4^q-E))-f;`9g~$u~EJ0|ZeHd>S6mUcy2NuI}n?GfBl4d`n zED7xlW#m6=f+au~zm|I8GLZK)$oeC9xp(Ro^mT`qYRt}Z2a)ugXF;J*-tQ`)#l58^ zp~mH28Nz3{i`>f)VhKB5s^l?ePHABhyuD?iy25w!!i#&$*a9Cf%RRRLGC~WJXkoq; z$7sC&XfM{I}M?&cbZ2wIrXCW^~)u7QKW?`iTt{Gk#5}usKsyO|-DPp1J ztFAFWCFt8`wIpj8VToU7mlE>rQLXmj-)X@&}LYQ|BtS#eQoPLqtWa1 z5=10L#+4&amSjs-EVW%^%atXgL@rsz=9?|7)ymAQS3LB~Qqwd?+Z!1fpHIp_H)$wuqgj(sKDiX-m1=XuV{g)+Eo zjc(wXivV9#CzVI4I8-I(%G(J1M&+9F^ch?{l)E$CdG;*I%S^TEy0rIvv+w_8Pd+EZ zGLz-6sb5&0n|*0=barL-_(Xqku`+GSgF1?Ss76qTZ4GTlEi-1;4hFLTHc1>U9Zb)m zL&20asMb|$k6MG;_kVdRd$)CY=^noIoc;8-PMv;z0GNIC{4ZW~?=5#s>hmyYvfa6L zC^#5=cr-Wg9sOvoqb4M!znVO$aNN=*uVtLS(@e%vv6aP4N)oEJ(Fqy9s@C?%8Te*! zsS5!9@yhJ5X#sJQpv05f#qi3{)rG`1U~`}L1y`h=gw_fi7}le3lA9K293V9e)65Rj zop;;k^18e}h@oAMdfgSNzSlO>=V21`FoFYv=TWMjl^Nr1KftVd(z^b`rB_{d6fsOt z(=>O$R?K8Fs@|wcMhW>+DrRI#-0-TPiK$mK#F|Yjz_hO#=_Y2-jFx7qWs?Pd5NmNt z&Fn}^s|=dP>144R0c^L4L9_{*qM8~$peO&Q!J-Na04z^7c~ng+H6hQs3f8+Sm69LQ z)>4E@-_oiiNU?~X961Ztrcl{nac>-h<%yYQ78)uvT}7`2*n-Uec+LZw8e4+H6@lR< zDvVQ4L#QiFW_eDhbecV_v*}n<8;9wGTD}~Xv*lT#p=%Dnt~2OyI(A{xMc5GokA&*( zf~Ha_<$%!D7QAl*8wReTI~ZPFtb5Py3W5q{hD5dmuP^4ts01zr*(=E6Lpf7pD9suq zwkyHfq#7*bUkRahma?|sH5*bnN!P$8mRP3(?Q=B|SmjaS&X{t%{+d8#bgkeMND1uLm=* zAZ%!?*bCi=7tz#!6pmhqS(0&LFxI?9jiiJyI;21ycVi7)gjpCfYf|Fkkz$c8gxCXz z2*3eopyj`64IR=#gV#K3ySTbS5GBH}0?5M(_|{ncYv&f&We*GV+Fc&)26lK*?ThU% zP9DB6EJzL)@Y$tiVDuk(5HJtZQP`vAqcBSvT*;)1V>cfraWo%AP&9p~S+%w>G~qUt6Fpsdf=#X->MU z-T4`99mV9&unfUeEZa*84G(opItPtON}pSEH*eh?2oTG=5kX=a=^97k>M($$D<98>wS_M^7iw z%)cTO8$%K(Z*v%V)nqFnI|PWxCPVmU@KiZ`YjV^qfPutdyOVq++npRnL60gS21}lM zHzF66T(lt3t9y^4s$C_TVCP8xv^MFsK%~?(pH}%;jaBH*?%Ps`{(Rp$N+q zB%Pal>JCO6$Kd*}mrlAq<}y^!#8O4DRtz9LqQc-Snr*n*)G;feEmo;$NR-vKhJ#|} zD^44bqoymR1iklV@?;8X%V1~@~Oh0eioc~>Yz6VOo=7y<2uBX|mFmBN2>DE7S} zTvyn$@M1S&vZC(ZcxZ<%UkIef{aa&+EksV@)97#fZk7^`lkbKEc|))w2_u%9Lp}MZ zC-;bw`HuGzA$`HRSC}u>zLY+XAsB0nF_lP;?g<|Ifv8YlvFo>3WL+@)OK3;B8iG(7 zl}ONEp{3!7AEGOKZ(+Rx-gxO1-v}KkzF++5Az08Ll1Cb}Tvho3@{IAVF%;UTxz9FX zxa>v3OvMAXDTK}WJ065FjDt<9U#GBUHV3N z-boAi()}1lTtNhh1#E>O7tY8R0fPmF!x%`1SJU;nAZs|2)B@m0GQFLyBitE59A0mA z1cEDMZ%_*j7)q@weh^jFECogcCQM3lSbvl-mEQ^BFxm6dmn zAD=k3m|ASZ2+VP>W>_hdg8sG`t6^GxHNA3~LMu3#1_Q&7_kJ&b2FvZ%a1lH#M%w$) z`SY(8KWu+=^z`Y|Z@m?2(Qu>R}?KwF_@#Lv?jS*RKPrijqES2g)} zFK}u;b59k|09sOAZ6`Fjlsv+g21uuPe01(zJfFSbzsX24xf&+th5rt-XBIW64hv6q z24neLk!@U_MgYK;Zhtk3V`xGe=22=s)^HMS+(@zOuPvR7+%d^f70qB&5wkWe5><>R zSHP;NJej7}zB+?6=E|&yr@0la0Oq)OO{sTB^PG*p$D})^QreMVQD+Q-+NYXWA3L@v7j_fJC&)HwBC^Q6wOT1<3J|9sw>fF9m}Ufd z(EYw9ZN-Kpo#fck*lLTJ8%+wsQu^??>Q^!yGeyTuHXmtp81u9%`fIVw%$f6OL4R7l zV!XcSyd7ptug7WkX|FE^#gJJ6Qv=$*AovQcjgw+&Ms3&~fn7Eo**!vagAOcqQVt-y65i*|Z2$#k;qDChwh4x)g`>1GanqIAEyx#R{J(=8IPuACy$!aFDo`w`_H6joU zl}mbioe>-I7Wpq*SNq!5eMYAj3rQZrlCVf+TXQ5?FOKYeabj7%*EZ1x4qJ0wOu$_* zv(R0g%%X9;;+WJJ26aZ7501%VlR`5n3w0?h86+d=MuSO{CTyu@*vGYBLca#KzhKWf z&rhBMQ7lWkQeDS5I`=%!c|k06W^Q9b;8>7%zOazUB<7GVnMYR=g0WB+oL`_GTA(*m zO3YdL0;q0&UYPL0f@Lk_1!$M79Zq#EMpZ6a3n0S4VrY>`fD?-okQolL z+A0$?%8QHVjE;9TZXk0B|^DL0Olt)^K;Qd4yoefoPf#(v@cRzVu^v20o7Qp|%V|Kc&B`=Zr z@WV?_*Up?-U&nQQ{lkkFFI>3r>)-$Q#*G`dZhijf#fxW8zkd3Ua|WEh`TpPE;_}`3 zC*!-jyDQTt9{%vs%83(4VgG$o?yS6lF2cU%Y;$CCvitDiZhMR=30ef`nBnr-Ml15l zQDkmt^rX4P^!vOne9v!wbZ7HeqjBus-J3T*_}!nK^R1|7Vz4$3>Jdke6nSkFl?tmA z8k6USPF-mObxgs4HUQkI9WP8hAlaQ%8`7aelbkl|uz8jOXdG5-9y!&gWel_$v0ams z=1kj$e8gwuY%|jtnrAd9txo^}Ri5gCbGNZW0#Qk4{|$|&m?8xiKYu5HG(F7r4{7DkWy zgo$(*;Af58xku63E!wu39B7KA&YP8C3a_+X?dvU4qU8vebpHF=AdZ)N@}r(Sdi2PV zBa>rBzl9yHx{R=@)g0y?U>{e^O6T`OKkTfgQ)cab6*SJK8np0Y{_MgG%(N9|X}OwB ziKt2W0cntktBzuI7E_yNlT%|I%!Cpw*Rx8^i%>y#3L8P50(usZmtXhRgLSxl1rt4< zI?^b;EKcw#ISxj{7(04V*nmd%FC)U9>qxZ{hFkH$b@Uhm$_RRY>qOmJ6cHVDPo>Tb zs|c3Af~nf=TZz!!v=ymrdD(+RAchy2vung)3D0F6lbC|fM{iL8S+85g8RzBaRMp~}R?J;4y0>?<&5FEz*8bMd+FiKG& z9f)Ci43G{8L@sMFFc4UP^p8TE<+)`*s33N4`)$NbcD&uoFTo_}-eFCG?xkTEg6P;V zayU8yNau(R{{ma#;Vv$XyE=X#sEOYd?^LuNuA>qd;sKnT$#K6IXJ^4FhC^fAEMyou zKY*||>}&hdvmLApw0cp*Ab9Kdsq;t>xf3QNZoW_q?1kY7`B)6iLeDRBo^WG?3CZz! zdCBKZH&P5x|*T00tQ6ayJpsk|-TQJ`px{wx2un{d)d8`b$t(Gl;Vqozo z{JyLY2Gt!!>!2kFJvyqbM-~9P1j8}<8LIq-s+T$EF7q3cZ*4JA$_xCK3OFA?nS_x4 z@NYhOUH5R|8M;F(+1!TPypvhw1c?MB&ai73(Pz`z5_HiI4Tp%&d8*(bmTiCfy| z{S`3oWj}uF_)pvJx!TT$S-N9JtBx`G7Bx3QI|7xY#af}{7=0Ip22^7?J*wtnpq5SmiuSP&GDveqt-1#;;K$xb9j&fW zym5Lp1A6r4j;|(H5rNg7N(borO{QW2 zU~h`Rn~bHB46sVKQ+b6(Llz`~<*GnBKyDo9XpgmDUma#KLlU}YDy;%t$-wPi8jk{W z_yVD?3r_~wbe~+pq=)mY2JR(XJ5df=UZ}V;FxsVjT#`8pfVCfW(a$ zdkY15mrYdku%NO$k0h*m6p3e#@r!|6N-ljdERkon<(FbR>YG9XaMbGwd)nYf3WD86 zgYkMe%&;s}ZN;Itiu-(>K1`c2fQ}=GFAROOu7g7e;|R5J7wnx87=}U=)ObS<&d?ai zCZx7dxHGf?(1kiBT$mTGfFO>}0--rH2mO`6Y-S>Zmu0vFo(pYk0GjXTLxr{i-Mp6< z@)P$98wE>vFCwvkvGN~Tv@0zkS|bleoWHC+NE243kSHYP^45~PMDT29X#z{$r4m$J zrBYt7c85@0ov1D%I@)4y?*i1$6f9%0Yk@PPiJ@dIqW7pYTCOgZbpyNz8!)4wt27|( z@F7c)8)D=&7VIKY<`BB_TL4Z@BZuV-@f?fuXjHB_Pfo!z0dac_L}mc zm*;vj-c)R6{M6Aag1yD=BV%J@whg6D(M7t3DLpdmSHm_M%(>F#FGbJhhPz+WgVZom zBUjBxPAmQ2L?GfVTNrRTcu&z5HH5kd=Au`qZ=dO9z|+u11A^sMhc?To734N06vEI3 zgjmpaW+px#(nvU7wF(UXI_T09iX0Embl%MN?Yn=C?0H1*ju<7h(LS3|^qYNs#gE_p z$dw!bNofXUFu6!C~rEPpg5# z>~=ND1EB314-?O0xQ=$SdJsRA&EIw+cM|K}DHhlS8I!?EBspFYDE0(B!g{yiN%BUb zeiR*HSh8^43KX)CTnVrBA+pj_LsUl% z>MRc-nT1LIDL)s=!jjP+3~g6*s}^Mt)>Z@oloe0SAIU|z48}*T;z#HPA}NLO3O^RK z1qB`u==CFn5?CxR5kMZmDuWSrAt^DV<5l>%Hy0x50+t z5k>;#Fbb5QtwM|kL{~zLdxrtR9seWiT6>#3%xLYzkuQ}6ShjMRO=>5;q)tfGkc(pz zZ$|A>sW?@X$z4?~5f;XarCin}5kd_Fk}h0%=2{G?^&-0uMrpT}xRb!UjdLD%gt>D8#YY`a@d(x)r zN(!-BL6$dwPRmDCz0q2Y2oCf&Y@lBlM7VmxbBGXCD;j>TR>4>Zq2={a;w-_Lmx+WI zI4YOFnyl(Pl6x#ByO9HpP6lLQ;g-w35wm9GU-4lVGNDV{7CyCvt_xU?m{jQoOxsvI zXvx@^O8^TJ3J5W?bGxqLu*JhyAmn!Eassnqw=LxA>q91`JU5v+A_Vsc6Db4kK=PU` z6tY2ZWeZ`ld?XnT&4k0(1cO5X_7f&;AqcK=1E9RZeQ^acITMbCa`Bue6rG`W80j6r zIn)lyEfC!})~wMaF?NU&WRwxMan+h)`H=@jf`Y>g%NS}~3W4=vsN6yP9Yn$vbkI@S zeh1-G@~{dRZAj$1todyt!DSf|s*$t^xQ(_WY<-b=*(NLU{2m_unuoqA}20WEFV5@@duH6OzD-`Q3 zgCHBYJoWK>zGb*}`s)k)xG8-2E5PP=4(%BOZ~ky$L1)^J&mX;e`|h=l!F%@(?!R*5 zqZ=#tuUFd4u|nvH68GOFf=huUEr{(~)ACK;mj_`w{`Tz5VBmxl*LnV2<)) z4=`9UZYm(xmbd&~@Yb!;XA8CcVdcSgmrV;e0lwVB0Eab>RnAFm0sOx>?PbDry9Q4- z7J;~See0_s9kuF0LM=n&)XUpn4X@0l*KE3Tb2ZwLn@|(1H?r1{0B3B3;waz;y6qEi z>R?@)21O1hoa;0vZ$3hE;<19=}xz6r_& zIU9It3H-eh;Q#&bptG~H=e0)pxt71E=3{>DtV*&8?s~@L9p*Bc(`oIH#NVd!bt7X0 zUv@T97;Y(eRSjL^%^GP|8hCB|%Rqbu)mTl|XidZ?qY~QqrWF4p3h)VSx`6mB!o{#K zU>lsc0Mb&fU5}g4iC`6UEP*!{M_3c~vj9*~WnnvJYd;=Bk%AS6VtS774D=kCjw6l| zh-#%ai}xYWQeamIt~~EH8<0$RI&!nP4Q9=QnVM+yF)hY~_Tm`t>}UR@U@3RMPGoSz zkTuz`F;?2mYC@oR12kCu!8*oZ)h`BvvAX6ue@rkr26&DI`-SZWkxVI=TNeyA_t(|q z`9hLOc~;9|mH~VHmA<_Qe)a)VePxw&0{a}t{P6gWmL2o^vCQ@Pg@9I4 z3ti>VYNRrjFktn23?N;Njc*z12&>S`0Fn!;jCC+T7La>>6#iiO@YYcww}R2fD0>Dl z!`TaqFJh!ys~j6t0xfr8!mJfY=mExLdJ~(G%0P($)<~mlJuiS<{ha*tZX`P55rFfM3nPpYrr;rLe&cZMVo4muE*C4{ zjF`P;quLLt#L zKK=I1hmZbq^5Mhu!+++Nm)pN?ukE?j)YWxs{MOCCH;s37J->N#W3M5@f;w9WalY7x zWB_qwIPKNxGsCbV-a^_~QAUb|>~eg*UjMVGc?EOl-nV+!hR+mVu?QF&;a;6is|pLh z%UcH7Edsd};8$MQsKT~b`oemz76G%0#0KcK7#-M1qI89kgvBkePM@iIu3b;$;2n5- z&8SzdRR;W1*XIRFp>)4nqZ?p;Q*8Y)s4C;3=d>;uLCsk@eE?LN-kkQTs##g2_8xG~ zT&O8VJrlpUW>qVbL7R2D9Vyh1Xlgo^hEmQ^6{cl|2nAu_)V8PU2uXndD+Kr-JxvuA zO--FWJ>|bLs(sZtgukb-V}3`0-3$npo=28**6=YC5~+2LMCS4rWb)eivX zV7k7UBWAxKx3K1huY&cs-S8EHHY%IZM%Ykac~sbKy}vTpi~@#cta$4QtUd%;!sCn0 zaHS91VW6#C`O3Hk_I>O}jAU7}1JLTP@|8h)B?!E?%EwR+A7s$g4!;ml)*hi42^hQy ze>hlMSjBh_wEQ}bf$BnJwZY+l8+eqdl=9$cHCmK_vyM@ORB{PC3O3xz#AgSVz-6rv zWg#CLoeWS}jkbee@)yc%Ur^e+)r$xa3gr(4mEg!bX*Fz0~OPF^GCMNC6( zoB4{tE5l?h!C4!63FTsU0&ML9!tz?;VA*WOzSj(L%Loo8b7WvZDzQNMT!OeOWMkpj zVr4c5pc(Afs3?aY$zl()05t=1Bs3)ymVN6vO6=MDsr%Ha<6$veV% zb4car3%kO7eQxAu3?zjLhmHg^{TW$TeOwO9RX{*Dl#}<}Sn!7NlsGC3;+`cqfaB0+ zp>$yc)96q%8PZB5H2%VBglLNqWIU#r$-(LG0G{CC&D2oG2vk#Tf~0LrC@5sNZ%2Hv zZE!G!aLKk*YEXU&-Hmq)MhDOVjBG4~Z6F(qRwIyMc^HFcT7Xm3R7cVFFp|Rhc*KLW zO9-H6JWCw|%*Yyo+bBB26lpl9)W3wUYXF02*Kf`}J7so?BwLW1GxO*ivwRA`166u$;sJ$lM}NO6BCCIU%dFffb!WhXU5j& z)Vm(bXD>8PFMp=I`N@g(t~E&BwVQ+M-3BTXnWspVarKI^Yd&=1em?K*yfyyz@;8q! z{qE9*4=(-bgS%fo7HGb6?Hjp#`|Wq%eR}`?zaRbU(W5*Tz?!%bQRk5{jgF*^NREh6 z0;@7%Y=L!wIhUBrW>r^vE`~Zn6+B}IE;P6oA(R|Dv!9_{<0*xP8geY`fICncB4>

t+8zv8FNQ>=v$|ge66>zlYxua*OyDYbb^WXH$!XmZzqd|-zh9d`Kd5+qbA=#q zMN?02e&x!Q>n+}F%O{_nzVXRP`Cd-$w>S@8B_++Cym9KZA&=s4Ji#1j%Cl?!Qu*sG zufHDqyk78eVzpthxIxb+RPwCSE0S*RInu@RGGpV60!D3| z!nsSjrsbf;>HI%e*Y?xqeTHjee=>IF*-%@N5f-uuK9obEA#lt`<^kKZrNLyAkh?09 zEu%Ti5WuU9#LS^4$pmT*h5&&~IaFapMeC?Eq$W!`x{c;~_q*K1w2NKrFWCD$zt3qJ zbMV?x{@ zvY^dwlRIm6?l|EqvM@I*o3+Rbx~YT(b0wTxYJ+IZqAdv1a#G{$#tIq_Ii*U=w7rcx zE!)D3F@es299!Z@es*UvZlbkZb)I4oOyF&ELX2gJA^^*hVGJb&(69uvY9Wf?=nlbF z3$mdxh>oI-uq_Zki(vq8o59q%vpZ0Na~LA5XtX052(Tv!Sz4gENQ@4^o`g$KL8FBM zwZL#4saPyQ-%>!qu;%x5m*lJ)8mvGG?%)#2kB}tU;QNh+O)y~9AJ8@(MPEr1(A@Gd zdD18Jwx}_V5)DY3m_Q3`3y5y94!DWf?9(WJ7Etwbx!Z((Bdyrdu(j2|4KR9t9b2v@ zZA(zKmwmn(X3e0vTp@GB>|#f-(Ml*#t--{E)GHMT-J%3sEiI2>3Kj;e`Zsn^LuujW z7cQf^tlNehEOcwt!GdHSvDwsG1Ibr*lQpZTZXJivax=;X?GTdKJ&m;fk^$`N9H-EUJc#c~4!&R=RY<~(^E%{N`Fvh4guS^$K8KPd{RvjV zi5vne+u=@9#eN~mpYzz~3i?AA+r>aAj&*o=W{R3JRy0XDM)+h~=3+9b@QayS%Wf zCoDjZ4XqY*+ulN6#|sx|j?#^pdAshsVXbQe?*ITG07*naR50M`8{oRv^J>nl5}RL( z-Y{fXDmBs=L94~D{GMH`RQ|eDUYeJa0Pyniix;1k=a-iRgO@6T&G$|!8ymmh*nhOY zf1qHS*m_tUpGls({gp6awKtaA=7ier-Z{84JG(06c~wa7!osaLPl_KKbXncdbu>QS z`ZWOfxeS7slPV$=a%DWGCAMF39N}02f!$ByH)Y3$f$yx^zXVR(w z7dWCAAdM*e^gU`DnzkNaGz3`Jl=$kJ(S(FzhKn`OrEuunSt_H)V?pkB!xTX?bpzK^ zDUX^oH_~Spv_kY?Rb@$Gdm2<&j#Ae?i@X9~1;k2sb-ot;eBMxFT_Fdi4> zpBZfd^vi&~K`T|OW0+8yDdbL!sXQn{-3&ESL|KVwC!%gDsiGE*8V1t8WX%Z+#ZuC+ z94pY3J7y*@!d*v_a?f5*B-uYkLlDC)`nhd3*3)Qe8lxVp6%_biWWTQw;4>G_@cY7* zYTtLdCNJNtMvi~>Zr9`wtj{CW{N%vUui{4_!+TSs-?dc7c=SXS^E#|h{rxDRXns05 zq-mFjI`<|%jBiIv-y8jm2M%gx+}x@ZTkB(RUty!m-Glrilg+iiR)iT@$yRk77U2q9 zS)lv-*}2@>Y#=stf;~4q&{VPM$cACDX~zwk3Mni7z|J~|p?5Gz2E>{yrmT=38hqJ# zWQjXZ-C3x#*r)*XG&$8y*(P|p13wW97Z9=Gjtl-~5lCsXSZu2H7mDXN5;yQ)_0`U^J?NS%D;XLi%j60D58d73__6 zbi^~T6>&2x0Gy$p7t?6L;taYMkZ~304EWnrAV+{+Bq*XgHajtBcKDGK%`(Ccf19%U z0%nm84Lug)H~d0@nF8(OiWkx=L1~BF0;EMtQiBirXfzN)8?7}N$&y|dp@?DYwG^_6;sCO0Wta6rRgx+q*&9xGr=V=z-Fi;!4B{LI<%7D|p>kA?JV zLSnVv$LRWXH56MMs2W7Cp?o=9MUvqnqBmShlJ!^~BXHhZ8%E=0S`cdK(pui43keN` zNJWDeEsF|EJLP=xRuMJ}+6!Ptz%zYrcBF^baTn|a{k45*RW{&8#f9tb47w%y%Gr+9 zu3{)XSP@%;Kxb4D((WkmYgQ#N3@l(U5OCItz6H5Scy3zoH{}WCkZ3P>ob#-K{{{s! z*94tm_ss>FyiuP|B!I%XLO7@g(ToHma4uX3>mb4MU>%|>J(1HxIo1aYIri2%3Bz7J z#866|psVMEMur7&^D8K1fcXc8;Si%JIc{zT>?vz*A0n!}gXlpRtl5#KW5igDlVSFS z*9dwn%Chhj$g#YG=mrK3_YGnitwTqJn&9bJ0+0?skM+SNJk8#P&|m?ZVM4yn2oFr8 zvBWMERuT$(l@j~OpyKeJ8%M*#-_l?Wf5Ur+$7^|5J+I55l?rRP$B2}CN9};$H+H}R zz)OO`Wx?OOK;Rd5KbvLUqlb?UxCH*?`+(cORmX<~fY0yO z=&sy4`>{M@zEZ{)PL;~y$q8rL4VzS_YOdu$tI*$8!(tOT z>KM?oPuZ|Q$un$6h7|f5x4=xO1Y^DUO;Xm`>J;K*Qg~0xTiTko6L;|*Pub;N4nFLW z!_go!I8yfdlpwFN38xwx!}l4)@hW*kq44=vaU4bmgQCB1CtW#rF8SN51DEYj*(0c8 zp)iJKe3OzXDGM*DB1&?({+t+7N;3mvkThjTdm}vfP~+of<(O64Y0hM4_CCM=v`79- zd&hFx8x};bJ|9dgX4*RbC$}$sJVS|Bn_;Va79LEQK9H^?u%Ou^+ zP$^@)Er$lrCx80q>hTXppC@PJEq!zJbdP_Dq#9DI*iHG5M8^8Z#^kp3m}8#WaN29svmj;Y3*)qa*;eKAEKv7BfU^xABdD{`vVbY_2y&y%anuaD5y#=&F{4<)3Bo&Kvh5&j5=Svd=_z(h=+Ez zWsrasRfP=n1;_tRwN(a^=*>)LH>0t-JEBP1K<%LVO(+)Vl}83TyGvAD$vF}yOVLgw zb_lISHitm%W{00R-I>`80AvGDMmvzs;X??Az_LRF4`%%lyh?tyGc*_#g$)5Db2Op& z$kBoPNx#Mf4hW^8hIaT!ZA-|T#8BDcFE+qzgsdzF5K=2{F$bDL=wk7Y*zv+uL@{;I z1vc!*8W>AqRx!9V=2Qy&`g)sOLZy+6MM8_31`L^tV7bKHq9!ohvgLvo$whgzJn$DR zMM99rTQ(bVM{y8lV;2WXESW=z8fm*-j;|0tS!bdU%WN}QVL&pYl92IMs6^t{7t&{# zkr>c{pHrI(rnG|E+7L(y%>7a@mw{Ox=5Zi&K;bYXD%QqeBeDq^Q=TBnFarBLxfDgD zVNWQ`YKEK;V|iRoet%J)mb0)G{$CIBon?B^XIpdBJ4CVrZSwp_|Y{D{L|dqxLA6Sdsg^NV3cc+ni?QZ!8f*Y_qUZHU)Dd z+ouFn?V&;32c|paRYgcKZ{HL+aEzg|MQ_Jm+IHiUHz#xgxJ7;Jipge)v$n53VaKGI03L zKPM(yuYC2B53ar3@0yzhafStI4lG)}fxa|F{hzCI{cY+#<9L0EWyh)&JBvk~*@_%v z$C2%T>cwElf|AIZA=Xac;B7_s4bDRK?zvufr-wO(_FP5e>bVJ(-r;3&ZSRad) z=(%V)j*|7#fMUJoR(&tbt_F&73iQrgQM_8+u&}33t9fa#l3^c{T2R6@cYE)%E z+A6w8jKIocR9LirnLE+pAypqT5Nc^LdC={R4T`&7f4$Z~gs8Oi(1z6RHOvXVYqBHYTkc zM-^>->EHU!zLwQw_xU%E9{n(KbtyS|W@pz}m-icCj04Mm9NRXw|Gr|n+JOohD218} z>r>1)h^cWXyi^2!^>ht?|NHVqZ*T9$-nTaPZXEpP!@ZLaAI_Y;8#_Dp{@tbJokzaz z-_|}b{%~cMo1>}Ki`xUU7UAc=Ys#q4^l!NG&aak|-J!i-!ujvc?O0A)CBeqM1g|X? zYvUTTrM_qrZ&fh2Dm8=AF(U%UO&l{WXH)f5zcVo?E&M**J=46KEK2CFo$g;df@Gf{ zWZ4PHwNchB@~&>vreN&9uxibplxzJq0pIwdO<)!qvG2LY zaL7?Q9B4qw6a5?~HahO)(|9T4gzlzGS`3`=3n)7~wVH5|sA&94(PyRjTxTcI9bj=j zBfv@`bVj&vNdQ_9I!^oVTqZl0%?gK3N2+N}gbsO`LZ{{FsNiKflJ*K+Rl^cWXD}E| zG_`|TDNF(f(Ues=wd#$WsCq*IZE(0#lwdk_inq2sWbCn8L zY1A|NtF{V4EZDH%ZrlDQttWgR|B+m+RCs@robrZSeo&rs6Xy15B9_nLvw@^}cE1|e zf;!$!@P_@eHX>QIgu8|95)RFgMu*bgMr}xPxINHawH`SdO&%6RSKe71I;SQCi|B!i z?7VpA!GeJni*D4R=5}OQ&E!t1W|Tr;dDnvV3NuCxoj8OBy4~Zsc<9hDDBIF8tiIrc zrg0n=&>imRYfl^!sP!;h?&!JQ(JoI+6VD-3I57lRU+mE>a0=#o7~OFDxxNkpu}G&B zeCtqxn>v>;XcwGJ2uq$!p@wEROY>lA3%grg1gH89CZ>Xu%2rdBy$Jo40`P>XBMhb{ zQky2WOm9(W=6I@qqMzO)sBaL!l~eT?)_yr4kk95g7`)9O z8liNMw&LKVkaPj!zTotl04D&Ll4ILJ2zVP(arJFY|!HDa+ExBG8@OW(f;IU8t^3NM%$6>szhUafy;M_}} zUHk0XM}J~h3=95ZNh7d|#tLk80oQ#<76%TGYX+ryRJ9r>Y3#sZvq}tyg#mAItkArm zlV=luwP(FSUaO+ez;FElq#l^iI>I5da6#gLyjiVB@}u0);vn43(>yGdOy~ytDJjdsoMo0>9bz-qv^D zJ>R{$Z>+WS!HzTI;n?RbJBH7`+0{Q9i&ebr( z`Q_lQ!NEaf(7kUZ8@fER#qiW@F?psdJ{unQzkNQx{VLxLbrP{+ad}&4Hf9jFX4KmS zogT|A#r?fapBKBmd%up=l2bEBVaiDpG#R$aj;s~A{8)r*Sf2^J)XG8q_K=Xr>TY0b z0gN~xSu>%W1=BcO3)ed?MvOsUrt%Ml~cG^_)>{AX*GL}`g;MCA74Sm+~CDlT+0v0^I3>=rZB!GJ(%fTJ<2wVSk#T zbY?Cuh?&W6^$aZ(lWwmB+j-s zoepJaC^X(9A;v^f&T%{%!R31*M4VN+S`}E0R0*$iEkp#WvtF+^+A65rhSV8funR48 z2-x%rLlxeP4apl?h%jpQ5-u%(`jyL7k#oH2IBN4^1J034`4y%k4aCY(#t^84h?rE_ zv`f=8S_3&(TaMv06J<~|#2*1GbAuBM=&C7+Osqgoi;)(TQ>zEbrO8+>dJ1!p;WvD8 zOGd}9&#gJ6_T7Y|5q#xtaM+MV^I_Sv5H`5&_6BV%q{PV4U{e}Q45i~S;wm@xBf_v6 zfaw-fM+iDM>XNJFvApSUli%Fv@F0tJ>s>!ml*WtlMl?ims=Ni6{GcHKxdSHL!X(er zBeYmPV-oFY?-*+D6PnvY^@0F&g2gX#tHg8y_)R2ILUZA+bTRxraX9EX*VBPHxQ{M| z>0pPk8sS6g8BP)U%<%a(?jy`QL9+ptD{iC9N*#uFB5>-_vcWzSQIjbGD=`c8O!iOW z2}b6uX_Ebu#;|)>VD~(I3>pZnX;+<*}t|3d$!30A!+81R;Qgch%(Hek)!2u^I# zxadua(G(LRuvYAyKF4uJ&*;L0!za|cgeW=zWD9k6AHDm!-Pe3LY6j5VqiapS-2*>$ z3S0d~^84qhRN4Jja()S+%z*B>tet(0FuH{skH~1@;LV%S4>kAqDg#;tEzHsxpaNzCr`LjIC z|7&V0Jox0v@4x@<#u$TVOi>@-`U5X;<=(x2-@ErWH6J6{y0K(*&ol#D8I(y%2{jeE zsNDjja0m+NWKwe)G}*~yVyR;#d^fuNeDebRgR?mS{uZ;3IlX4YK-nDIOT3(&;&vegbw;x_vad+)|aJDP-aA0+2Mb7SCo|zpzd!#z6NM$rj z)>4_Bspdx;OAiy>7cYPK@jvDl_`9ojaB#z5?=E4%gG;%icknG2YsKZR&ZSs)%iC8I zKMOoGHG#a$%r@u1h^b*vV{gIetr3FV-@EnB>Y1&P&jl%$yhrZ{)h+&#|KWl)?=V*8 zdW({F{p!EeI7whu!?4nSMdF%qAt$X1V)e2`qg|_w%${ww#H-L>$P6QAMVsf|EjYH8`t;^GKl8cNxsq zdSSaVVEP#@<8Jb4KQP2sKvrE!&*@Hb3gRx3o)vfc?IkJ+1#~;(88pak zRs(0^&bT}+kSeSeFqTg<&q_?0g#ee*@y={#oJq57GiRPe( zFrJNaoZ3N*ND;wP&7_P(1%thjcqA~F4SB0+pqPdvnh9C|2IP-wG*k@<3hQtg|F1U? znF~edLRl9}Vj;n;5p^mBTB9JXx9VaVO>Ki*9jHV!ha)H09BNw#xU_JAyr9`o;Do#BK&jR@jHqlLxE(jm?y~dca-7*N{&F+(hy4TleaZG0?DIUI zZ#gfPq|k3mxgz&{`g}gm3nM8vL8Xp-?_^mLlV&Ie`ti?i?YF@-ZioE{5iVs;8`OPZ zyH2zHh!be5liOgM6Xgt*E{LNknYIZBmXnD+2~CN^S!s1b_lZDCbsur~T+C!>ISmPe z7R2rKL#pDet7QBYPFe(DM_tM<=PsadrC-P`G}1yL{79X|!Js4VNFirK?t;!a9)uV= zUMUET(es!aNgBOTVZH*`DSuqiHXe8DA^MW)Rt3Dr0J+$l!fF&9bl05^M@>bO8!G6r z@aQ0&Kk;aI6=9HrYC~!xv(;-A~hz-UB2 z%hgC5=fNB_V z`0^W3&@Bbc)sHQ}g($3S_iG)%LW;L203XgzP6+@XK6UZp8M4){ftY`hj~nNvxCB-P zJheVGzdnEYu0Zh0(PKAn-FkixVEgYDh_FsSxB~{9zqxkvlt4OHzdFdqEL)!Q9GNuP zG@os9eSV!w;T2V4aS^=okD;uwf5+($AH2AqKUL6f<-y1az^`7dnO5Vo7kWXbP)BhwrP1<^G_$l&rR4WO z)em!M9@)#eGxS*+39TS3AK8xK&i8|l&8A>4Y z$Sl2ecp2= zN7B2%*IBSQr=bp$-%TjZL@Z1L^j%jW!pqFK28B1$v6xv$Q7E#2(F?F2-=f^xGc3Pg9{1gS)efr8SD|TRw2Y?$ubtQ+mHrajyfeoNcWSl7De!#7PcZ` zLu}OmEXKlB`fxZBQ&W$zlfYJta0V65ehx;0k?hIRSJ!={miPb#OTsm<@V0l9Dm*eL~ zGyuzi8u{iL9X?|;P16$Q((FHC?p3wf{_Cqok6{H>Sm+K$Do2fSSwvyg$TO6X0)qp~ z6^OAwF39k>kY-QGRout4N`cmrR{8oWGP5c`ay`hPtngqpTrw^+7kX#URXC844Lx4c z%Ka}i(c^zG2hIq-LiC34=GJkfLE~Bl*7thShEL^k%SK%mM$iJpE?W{T zSpF%U$?G;j-Qr}@X0=_HzpA8m9$~pl=dU2JjXi~sV1fI}VPVZKr_+!5GbYhCgmM6h zFYzp7gZ7H9Bp|M412LdLu(l4A0R~|tLuZ2iO3s}juIj}&8bfEGuaIG3zd=Xp63oHz zXeJtj7g+Gw@m0owo?md?AjHnP_YDToPKYD!L0EtVp9jxlH0=%tX$gk5craQw>P9Fu zXs>%U-o;vmXkA;lZX;}i)}Ls&P*MapuiK5*zz+J3Fh$1XIm{lUFmI1CcoOE|F7V`z z5sb50lSCVETSs_=O-iGjP0Np2b)$cfl?)t5Q*bRmc9aQNN_Y`~MIJ1;kM{+fNh1kM z?y((TevRI46ag0+ehcMC8`mw_jcP)bXl1ioK7bGS@X`FOsXu;t?C8p6n2-RJlwc7x zbs~KZvtu}sCNIzb^|D-6xBv}6^1tSNK2H&r0Q=C^k01OAvC?a|1j~=j=GUjde}zTg z&C-iH{)`U+;6$wH+tVL@_u@VUT4!f3%+9WSMEC{%zB)CF zBcQ+DO5w+Nv{XO{NqEJh!WJk1*hvVM@qCjABfLG;JdhGwnox zA$1OEX@SN&c^8z;(S}1#h!OUJnYHLu=da)mz&l&KEtA#w<;Bh0=7bR+8eVD}@I6sJ z%}KSf)N^GSn&h;hfl((yW`Gs3en^=l1jXAKdG=34puK$eU6_CO1B9D)H2voB zTyxJ%sL*h%#lo7Br7mXHD-?WHY;jb_av=dbrUPer@r(pXq)j(7GDx5*0|}1hZaZvt zYG}%+dzLe+Fibnc0)doCwE803+3GB^B%x%c^%o0aA;p#?;v+2)wh8uIi;{wgR!fA5 z4Dzr(3lk=-Mdg1l*D40kVu9Iyv@8_$Suuu&2)alfh&^u-o8O{7i-0z_%jMYqT5JKd z9U`v7QUu5EwK8N>Mwr5JO=xm`pga&@B~l;z80rP48zPZFV>4F6g3I*?i}p3v3+y(a z?Fe1L0Su@c>mv=&Wd)dv1yU@uI08*pGrnk6=Mh3Fn~{svNQssYs^j%p4@ecP{D zgb&;FPX==kc+~VS2uxVGvE6FQqJ{n1uRCcia$*lG+}Gt&RhHG|(rPufFgRI$WQX7r z>tH3mLW+z196s9}ngiq_9YA*~%^H54$q5tAz&i;G2U>use~t@{g%S&s=M)6cLW?s3 z$aRj4KU0?i3yx;u{__w>2ZQbm*2HySxs{oyKb%4W7O>RskGsDDr3^AaG?)4yMfPi2mkz=(-dJrGIbeB zXp&3jKId1~Zr-_b=kDEm0+Q?N^YfGI>ysDP=ivqx0L~vhwsz~eK&{DuPqcsh9Y)Zz zcc!M!%+DS>H3_nNW8?BQ1YNwG0SzXdo~JJQ9vJYiZ?5I@*a2e%y#N*Tzh3+{f8hc} z&%%Ju{Q$sulL613y}yiEvSvc-FxqSGf6ZQ4vsPWp2ovh*)H89R@5eA6HVOcLiP7=_ z;48DQ5K(nRqpGNjKCrO^7A$^%&n+D(S8;D~amv-(i-hMOymq|+SjL*mJ5NV1)Dgmu zQ!b2p1ckAa>4i2cxD={-L-Gs@u*$CV$lj)=0t|x&4~^_%6eaeblsSPS!W0}cX(+Ri zjRabNw_~81&_HFFmDom@(A;BzvF$X;E@&hPD}+M}F&$>(ceY&7Gfnlhk;v5y%p|-I z_w9Q0*{)9C7df)(A^gO-;Z%2s1xX=(Gjb_I8sNdG3qz}!jD&ZKAn>=}fAc;1EoQ@ZP2)iRpoo#q7+!;gg?qPyeiQ&z|9)w(d}F`e5ff4T~`5#zMC{oh=$?mS*Ut zRzL9F)1%=-PnMtdZM&UKEFEuHM4%O30u!M%QER~zIh#vf{+bNad?mkuv|*U#!G`W4 z7QFfNoyAf%E_j!_ zxa+)`+U8gU%nc0VgL1Ng%RP-)DOx_D9)rxpi)8J$}6c0fmYpsr8nwAI1s3~ z0dB8GcUUIBqoLuNC46`Q4YSMaey?F`()wS5Co4*ZuQk+t-=LG~hN7M&_?i#sGMY1) zOlwF70=k07Xsd>`b3rg!(N{RG^5Dxk`WSTboTs`Wf^0f>Iik30gRm{RRZ7Bx8yl~9T3cd*v&@y*8q*`}X%Xz5fzEmwA2EV%RGC&(zHDucM1|LyZs69| zmZ&C6H+qP7h68(O85CMS28dPt9E@uR1A3GCAT8ugL%i)DV*KVKxt_VRubLi`mnbH4 zX=1R-)HC?fDFxvmgJ{9vYROkl6FDiTSJORmT3W7;muY3te!^0`r>B%IkF)S)_nQvI ztHOH$Sb^DeyuAE4CDeABQec6t>SG#@7*7j~rLsMbvn+~BP9d)VUP?e0GEDk~T&U>? z(K6#=X3r%ASKK)@9lGDC z_FuxFd*uOUd(@_+^t%UHm|BiX#wL|rPBD${?a|H%oJn$`x7LQ#_tu>G?S*gOn{L84 z%}6y4tY###pjCu*V}9Y1`hnl1L8~{(NuY$A&W&m%gM4g1*xo)R3|P7D??*=;$({Cp zdh&07UXn967iN_KuNd+x$jc~OF8`(A3n_L6+E8GH;Pp}1^umg>10D{3UnT_-AIzd|@GwgZ?gsli29*`GU|24PY z&5#-4Gs@W##ah;g(O*Wy?8ZnjRPvz z!L>wwuCjScPqz)LFv^{ghR!>rE1m>)%94#}pPODpO&x|g8@dKMRt!*nAmZOct zYs?5kZY0~1{Hp@FlTi-M90FP~_(tzEMjsV0A00vg-DpY})D|2)L>gAKpf$o#ZheOY zXqU?Kcpk{JC&1vjP74`aY;#!+yXntzd+W*Q(BNlMDZQ2FCIGr#X)uYMD|+D9B8?Q3y)+wTuj&%k(2JCaBv81k8UUC^`@#^Z2fU)*=GEH73= zLU!v@#6qW1=%j`JrqY@>8DEZL_O0qbI!#Mb+Lsz9)k<(Uj@~()Dvg&zWI?Bd3KNJW zUoWSYOM=Gb^f>juu-$1mrGgqA!UC*>LHABiYcGO+uo7nNdY?94lU9WWS{oHK=((#i zOCrYkPPlK^WY?6o5rU~^4~+Q;+C0@uT`;wS(B|y8PLWY(g-TN>t){!ENJ{Hq8={Q} zyO$E+(Ea7EDO^xfn2)A-kaBC9RF13$b@gPc5crb+{o8L>E|}@_*jt9Awj`fj*MHJ=I=E~yi zz0uJV_fS-;>RDyb|5Q(tI+7N@oLyL)RRq59@{;iDZNXiE?S*r!ke?nqmiXbti_Z_g z5&)jtnw|Y}WlrGyHU9qh`qJFyrI!~r=avv*Ioc})-U*dmIon^>ohFK7)wq8XVdE!V z%{X=I2AsZ49_VU%0;;ML>9AJ+qQp}FuL>6xrZPLf>=rtBII$!GvNayV`yy zp_7(j`L1V2KX{UP8Y~n#cQ%s0_^Y++4+|Ckf1 z#vUN|U&@bx!4 z%0?66webUiv2Jp&zB-Z{3)jky4IicFflpt565R-gZw@B+Jv{EYZRQ$bWv>(3Wn`x1 zrd=V?ziNijF!Idm2(=9kGwya)*QlpQ^ru1MmPt5Oh218HLmtz4zt;VFF>?|=iNn+H zsx-)p>Gu^c3C(H>Vrx54*Fd<2o0ebpw+taQj=#YhfDjYv3bix(}o8izpR5R0a7}Oh_x)*k*NN)tYib4XTkA0NHAk&i#7&J zO-F44sniZy7Ce?)Pv;}rbYy!3ryGSWx5VsN zYrci=)aGB*S+HOByn?gBUa19^FJd-hV>`ySmkemdU(e|)b__|he9MeS^ERS_t+tKe zSuR@(jd#fIXl8QPAbdS>yfvMcTTg&EI~J?TMy zrO{Zr4lWc-LvW*A&^kf}Aax{$%hN#KhB;1g4RR3}tu!EicB+wFj!FweRtP2)3k|ea zgDAV@$JH2{}b0v|SC9ZLJ;rAreG zn##fIMFH!S%1DL#rkc{evY=~ym96l2%9kPzE9g(D1(-;zR8JMKWdNO49ac4+CRiiA zOc-T}OiENt^bhuiOd#|)O0AR}W8{qGM~-OXq%`w;tTOyLJ8g=KA{j_WJgTQzwk~c4_H#(4=Ga z6##y9gN(_)?;9KI?@$%==;-GBtJzy}&>0h-nmchy?&-mU&CRXNt*tE~yq8|ST$#V{ zavm8p7wmx77Zzq$=2V1r>{$4RJtzOz%nta}mM~@jc(FEs{vTae-_zE8MrUKA*mNG( z21H@kW%jkPEv`dV!i%vR&!kz`W*8bJ^IoEXjK-URKo%k;WRNOpL`4FILKIMN$r>fy z(yY@KF(6I1ris>lfPS7m=lrg-^^YMS=K5k8f_(0Ip7R0*{QFfo`VRr%yD%ZC^bJe; zObN7d`$kn?faU*H*$}$QqKK*xe_A~c%s09Z?Gbpp&V){#d6~h%Rt9VO98yTE{sCz% zcGvm_uu^gRd=YewL@aS(E(f;&HY}_{LJTF0dvc}eL}{=K{a~&~hEiQAe%o4ZKw=(N zYq^1;JeXGRqe~OV&bjv($!zFl#gtXxNAgBZREh^c^RN|W;XIe#9K)u{u}@^b$jqQ` zD5|nJ49mImc=E@8i9Y#d=KS~fHnpGBj2(V=X;bc>ery}7aZb}Ud^a&U)h--yCCki5 zc{usKLVuiPw}OK768r0pgcS;%L8|25A5K3M@_pxccl(u$ zqsZ%_QK+6CWn%3@OZDmNW6o(6F(QwH4nl+Tcl_u5?eO~D(M{jPR53rXgzz`aI0`CC zMEyDp4v{$*Fbty{oh`VUHI#Te#V2P4U+Y;_8eHHJOu%t9BR?3LAq;(UiA^?$P;kRi z#AtmtUOWX>;q1lM7h`0ELE0glLL!z!$PMPiHY90i%8TT&KgAhr6Gou|$gRBW<~@D% z9tn9xnPJ|R7}OYyl^5=WvS001-jUxx?~x55&;VsJ>4ac1<4~KIE=sOB}74?KaMppAlUEsU&1CB=&BMY{U&;W z$$D5a2d^_R_c10A5__h32YB=rAn3XfIU$U#}8FdpnqP)iF!MFHA{tGM2?qV0CzB ziL(N`0OV>kCe30M%n+?6+}Y%cAwo>VPiuB=GP47z`PkNU_|>c2pTZ#0_~NLJ`i8%L48nqva10w?2^}_ zh`bQxaybm3*%O0K26-V0B4VRLUZryIYy_Q=0pCDGUeSa&L~_Wy8h|2edD-Wh2?leu z!Sr$j#v(ZuOoQ(R*}RahO%JEXlfmZZag-t@k+&fT1_|_Hq-h& z{EiQ&Q8$!a98W$FG+RtRNF#T$MZhkIId776fHQS}PYVrBcBc`;0UZ{wRN%W)O_{r= zgbhzAFR)PHvmmrnEy9RfkV=WXNkB8Y8ZdtDnQ4J~3r!B)$xbE9!b5j<;w!;*G(ey( zX@*S=!jk1NT9Tc~W~!s>(x`6glBX{Xg5^_LoVN3UqtRL6p5@zb_Au zeoF>C@~hA01ppaASz2BAcxP+jMrmuew7T`|99;l%u}dx<@H13c8#=8M4;D$h?9t>18xD zaabs0Yx~lP%)846P~;k{1yn(j)6`gHsT5M##bmiFsPxs1Z<)x5eX(9h0elE5%2}(k z4tYrVeFVDDyK5jxa__zVhkEhh)pPIc-<>@cID7SRAxrVr=J43BKL>%HUOHaA&&Up| z?|=?sTx&OChX@so)+tTxe1CnoGC)EGFqjEQg3cv&sErI;Uq)N+iXu& zBo%X;fx?(ggYdvDMAHza)Om-dk@aW}W%|WA;J*+nlU)yTPR%>)`FV3O9NIbpfx+8QFFO@G5&6(`2f zWT7GnEEx$|=nM9vX8|aT*bRU##?DYv;pRHp7G{x-<(}jV>R%$U*NY|vIfu0jO`o7|K>&9hGOZ4@Fm%AFRE-t! zCm_f2vEG3M=wBcL3uG9>YG|gvCzoh>ts-wji}Z8(gUF+LL9WzpVIk3X2ny&5TZJXW zf(gk6~X=0m)Wo|9D%(kJ^r8$g}?9{%|z0|bmi7!-MEln_=f9{9o>xl=SZYy z9C9Xf94*peGy^X%rp)Oy3wK+nGfwh8gkd3-114X%iV$@L4c1w*V9S2gLmd{>&zM0Y zM-pwpumO`ev(pg7cc!OD&=WlkAiQaOQ(fn9l7sI~jL6FhY(9}56<5t_h8`%k(+_&U z;b-I-*0~wP(cAl-@T>0>5{|b2ZyFZ994*%+5sjyR_~k#@h9nGFAb8=AmoG2utj-Ja zZVB?P-rK!-qjY2b-s;v@JNE>LpUpq}Y-hf7Z}+R!+q*a9tZ)9c`&%oBBii-BixNlB z0_CgsYlOWruZpzUO1V;>RH@-exzSLKyg!=1`TiCF_`*S9+Ngi=8f{1yg#o`W40r_c z?3?g3{gpo8orTL^fB_e|{Vn$|Fa%mx36xd}7F*|ekgT|%wuuanQkEIRI0$5x?E4r$ zvvANd{bC-?Ff1fro$7i!)WzwvRSaC;Rh$Zf@z%n>&TN?h+Kqhf2#dYkIaf~ZK|WlC z{Mox<5k^2X%Q$_J?KeZvKDUNGE&F`y834`xg;vWAtU8et0*6`)-G?)8x%R1R(o-s6 zgK{B(3PZqkXlO_<#UNB#?Z+HeTizOi61d+AGog@zrIIKLLm1g2mjW1se&Efju`BXh zJ^1-M`c5A*Q7{_CU6)rwjavcM8vLp`>tx6fK#2FMMO#~z(F zescs@8eK<@7)+PSu53?CUj2OU`QfF)olLBV%&vp=)7sUk{?prN*Vs->o*!$x(yLp| zODeaTv|88yJ$61*bKG7tC5wg3XUecLaZGvL+sFynk_>? zP7~6Qii@^>9z*G^Q-&I%vy52Zypv-Br5()HsxE6?&Z!=MXG#J(fJ&eY}8#<1{8<;PLQIDh$mo0<|MoY#L zs2_|2piL;T}!L9D}jiD7Jz*sS-Jrv>rjDRTZx!u@xL` z^CEErF5ybHF*JbBat6)(E3(`wI({2Kicu3-RoOIKwcfE#GK`iZoK)S=D96zS+}N}Z zwDrOuj3z>%#Q)*y>U-L{&uDC8aPy>-lfe^zSKvRc045~6&(;{Jk z=D0YuK@(IN$Tu%bl&lVz08y|K=Vo;qLE2F%h=eH32CdY5hiU)hi|je)cTJWhk-@&# z;H1>&p659)ZVrP*8!z-67(#m;F1yQOx7%nE2C!nf z4EHa)2<0{*w>I_?+PyZjcF^ZbpeM=6eK0*pLYEOW>GM(d>40<^Q zC$N@){CQG7q{1M{nhzspEdj!tO0{wwi~^+Sb3x}xO*k{qSMwu>Lle-AMN?W>i^iTa zSVOQF2<(qWbFCOS3oOIt>(_w2%#)I54{MN0L*GO#lwbH~O!K4mPqp;Qqq!K$WEdM@WOGEId}jHtkX{;))H;|!(DeWM)w7wQ1tN@c1xTy?xu{u;1c8;j zgt=(n6Zt0cDije$j+bC_Of^J6GA4gbh{EJE`+F+r_a@NqCeEhl>d2X-VxT#Ko*hg7 z?aLb*1mHqR@OLS{wY5|*g!}H5O2#&*aLF+CR^_hH;XB6mUTL)~f3|hKY?O@3+k>q` zfazgRI-NO15taaOUcaW}*Bzt$jUlYrxPSkV&}NLZ*A^BQZhvd0Ngg#a0D zzszKsKl|6~KVSHz^6l*f5X8q`;-OG|jP@>to9m_SK@RiGO;V<L(maWDPX+Z>a$}Eg!yyWuJjQuWOI01zaKnNEdZ{Lp-)u{7#Is}im*t8 zKO;oP`z{TQ+V<7u!+>fDP_tfk8KISd9G~%%a)U%j!pneap2)xm-OS}L^+qZ=n*Lw( z+tVGbCe^d4t_?xM7k@anzv&*iNmiNO{UO~Je|BzkU%upif>PO*A*JVEgoEknHd7&>w#3uidJhzDI<2ZG!Rn%gbIO8dLNHpC z3)ZnC$%=rhDQc;#AgF-hI)qpL+z->I)e1!xmcb57%{@8n0AkxPb4IFFT?<-cnSf=f z-$2jrJxdJ)R{e4meS5Q{UdQkwn_0JcQM661Oxcb+DE&$w75Df+mwmp|~KuSOa%-B>PbV9O_2*LQD5g zAr(g1eHSFS`)&)3NvLAzYylRxH+H~#)CeC^qv|0}TYXo^M zE}Q!4uwvj`PZv3`cN}Ec!Tv$VI5bx-hH@x+OpLYr@G!MlUO0gTR?*6Uz#oXDy*@aW ze8|6YIdL{F{nZW_RY<}N!gj<2F*8V@Ipqv5Lu@5)UcN-C)u(BIQs7)bA8dX=t9a4=M>fo)<=igvk-~OLlMy4h^k+TDeEr~H#!{aBiog0i9TFA_-7(> zFG@T? zv<(C<2nZjRR#!_#dAqb{?BxY@-);-?mJi<)D%&N&q7{>UjFXer9$+0Qkm# z5X5oY(63%A{C|nk<<+HYum1U00bsb0sx81&S^;NxhgCN!lYwo0&5UzsJNnJGd9?Px z2kdxp;moP?%(ybEj|6i+;Q;!)0^}2l_$oUR>InOs-sOZ7gS=^cr520q7vopXVo8IQRf$yfsF_cVX@$WKV$f=4YFzo^(+8XB-HE@y z*bEF^=Vo}v^2gln500)yLB>tn$fbL+CujGA3bB}`h3`0!VN(%2yK3gZA#O9%si21D z1;Gk#2Fyf_$4}06{if+*Pkh($lnEiho`?4NjhmYYw9M>Yx&H9`XFGAuhmjp(PLc2QrR#VsBTEr7%bhVy(uls7J6`YHVEX(orPX zh+S_zmb%;x_uqp#RNjcErp7Jk@~yvDXH!n2pQm63=Gb`(6KM;cRtMT#uLM|N#qcO? zFuHO|kQox`sTQ;k3S?U-rN(JVpmY)m9Z6xeHE3)=*`WOC#{?QDw9pUS-^tL)pO6Wi ztU*;nduI)%)19En9n6kKDN;L{d|N^-?IFZ-w6`M)tFy6FRU`?#B03szSdGG(1#1`o z61p4e?(c3~gbE8Q;qHb`GxutdU4#vt?vOjQF6XY-HY%FT;WM_wya7jsmB{_zz_3C*$@nFXmYb* z37cLtHU#E9)IrZfW91<&hQiqcFK`ni(}4g5(d&qxq&gZkz#cH-Ca`4>m~z04Iwax5 z0YTxfq18HO9iOsN0u7~|Agc-k7c%T(eKgWc8BK|U7K`miVZe4&0J|)31AFCD`?%Mo zM9(fOtAOox=1;N@iKvTgXn-!N36ZtTE(7tdA&28b<1R}A7{>D<;WCE2)&TtAsETVZa)~ri7jPbKt7T<<&%0QZ=alTx8BQu~WrX1*<07rmLw}J=Olf z^jNhGscJ%!U$g14^vTy>vJGjikT2!)d0k-mK)-M3`R%>KJwsnw6(HW;)=L#2FaY_@ zo-pH8L#VKzY2~oA4Gs0%;@DW*Y5IVvf<~dk)vYBV)AG!{{6WRQQ*>d`dd0}=g>pXs zXiwMoDte(J9}PKN&X>0GmoHwt`1!vxnc(SP{}wyoq05)Sfc5XzzC&};N2)tXsIV~L zB{E>(Yo^UC0cIf*_P^6g{Tw7ZPphOx4olnACXny2%>XTVE8n?0lKpX?K^*7N2P_cV zd_f_vDrQgzPFzrWWyW=!IkTCaRE;9OWq9Z0hZcd)u-_qhLr__M1AY+`osf%4JFV|t z6n5Hu+S8LN2f8YMuF~MsEFUy+*Gz&oeZfUA;O8&RmIZTQ8duFj)0v=J@DhTNeN_#& zqFk%F*$lo09flugg>q-P!xlnfc^d#O{sH)N{PEPK-*>u>k96!m_WYNrbM0yKKErr? zLOw(m#xhE5u)ub0LxE9+gw(MO9o?302}X+|QB`3ud!qz24y#zSh8WQ(Q=<`#J3<>v zB~&44%OnUxi9Cyrp@@}%YS_5 z@~VQ-8brRfOPK8BJOK~@yqN`@S_8!4Q;WM00i z&3`<4^khc9i_L;D>k6(uIc0u$rjEE`f;Xuk#wtp+YkA9p)G|=NWP&DtS4z z<=S$&P6OMef=e2*KvJ9`LRZ_6e?CDR6Aa2#9XQo*Cfk3^C7h%*{E*~ z7$2~(R{|#G_6$Q}Km1tOj#FzHobsDi^PhR>w%z{nHtXMj5*=gnCD5|Sp4T)SQNw_a z%c%~f0O42K!+=xRHU&TnKz`2lseCVle;x~xZm=Z+p6)YYgd4mKFA-QCC z^bL>;9qaBB@|zR}tfpT9WK2rQKCL-Ie#L4ysh*?(-3!Yje9&DKT47DfipG{>Dszrv zJBkWsV+w9+3J&rAJgV#cE24Rlnx5+zVFkNjR>8;`Y=+SBXUrr z8OxIvHo$vH!a@Np*ozwp`4zF2%`MGGw!KAN`uYR(A{E`X0Oh~(&&WX%mV+&?odQB{ z(P4AhO-2XMtIXG~Q0!7ow1BbOYu8nP$EO-R}4=@bpWLW$#OodukhdIW#7OH1@OWQT&MrVzF&4G5yTyzo$eTT*DID{sRaZqL zl2GD>kp;o%Gs1%BwfPtGFF-8!EuezNe1zU=UI0}X??U!WPZn$O$k)P}m$ZZ-yM&Vo zr4QEe$b$Zn&1iJ=$L9?ju(bi6X{e${XRKK?x4e1f#!Da+ z0ImrJ*H+87b|!wmUM|<`*CxIxuh**rvDMZ6dVT-F7v=Jc`U`>46@lIt`_)@3)&JF5 zz{GhNL5CVbW`>EBK1))z#`zeXM5_lt9RL|DRrAN={|F4ar|=hgf2@O`QvcB=Ke>uW2Y+*c9SVx#wW zPSYl}l0oe+M*rId>zPYft+=o?U3_+FtGkXyyPm{O%-au)<)~3UDDaCG%jyKyq6WR! zQez1{-aL)ZNE2rG?D3Ke9g_bD4pN`xzlW}f37hc-N#BTj1u~p)eGfFE3 zt(*|#ya}pkaA0fE$whg#idu&Rp$Z0x3I~C6KRI#v{Vxlf>FA?Gi7dyjMw);Ahvn;x zhQA-q#G*ED&y#{YDb2&?<;>u=kn37BQ{tT2xUz+|X4||C=*nB!Q)WG^R$aA@HA0&O zaw`ebt^}?o%$LX#H{XdrH<8Qda{0E-w$6NK+na4|Xa9XtPM7$&^fsG%)2Dpl!qK7Q z{bv&jyyk64dk*P!1zrsF=5#);Z_L_rl|sRE0Mm;k-%-BZvJfi{%fXv}@sPst(ogav z#Wn6R_fv<>zb&Y|?X>$d0m;zv;k^BT!21uo(0$85IX?MCoc?Dz^!~*y{l4NLPwi!aCGw8eoU+MkzJEsDO zu4rGd-_|Y$0aikv(ONlG7(JE5ZDd^rmAeDInQr}zbptpT=8R;@OI?x-AA%5;N%?kt3Ugpg)pTKc!;Hn^TuVQc1Cl?^Z zg1f$tSr{v?jS5b~g`2*m78UN)e>c_D{5%U7{0Z#R#OwDhP z9GFed_Gnqs5~klJ!D{leXk^GPFtujxYoeb=O#3f+lPS;_0?Qy8^Y8pTsaFcSsIib% zjbIEOF>%hE^8^CL0=hsm*&J#YRz=pxLaRV;t1#f6C8pcxwP3ubP54&pg1)pc^wh8^ zXBgIat!$48?*f3+UP}c%`r7yVdLV7(bIi=l7~z$Ly;c~dVa1~}XRk1V{_ump?eDJ( zx~;DZ2JcQx)a!Tmc0QQ6R;}0f{y8zRQ`@iaeK9d1bhui5F!5on{9=E9XX2aH)faW- zRQIqU9eV}9;I9BMn(Fo1O08NGxV=>q)+{`DRgrghzg(@>YPG%fTYI}T*mSMFzE)Nh z^nV0^`-iRoz(4)d&ATfg@aLbe?bg<+`>QK!w{~kByYfl(+ReQ?5MYuvOeI4j0n0T0 zS|xiXiK5F2V(7AhfO7-@%RRZofsUX}$_7064NGZd^jIbg+Hm2Emo6D8mYnX4FtpLh zj$msrt_GwKlO571gWixs-;=srX?c%1?(oJ{g{9@eAy?0%wnh)(t2j!_2;2~5y-Mcj zw|q&bgaQ97{=^EUFl5ohLXzQBFp{c9B8IZwE)9aN7*no^aqKdtUDG?L0ySo~CG`R4 zOo2fH1MZ#c4%_vE(bD2qKb%r2QX(;P@c8csi(qkLQ{T|dDT`GXvTl7#rsiJ5AafO+ z?rPqr#(flE-uiVZ?!jd%szf$MTYfnCd+tB&XUE?g8ajM-{KC=0H=Z3HK79D_zYibY_~@e>S1$f0 z*XW|msS{dX8C0*75{;Owil&9Mn@&X>T;>S9O&7q3xbFPbWiJW_3RMxTbdL$d7X7-@ zb@+?A62{Hz^dpsax|RDfu@*qJZ9Dw#0FQ9EZ(~5x_CoAQ>LhX&NoBAFZfAgGdWHik z_F}{wa8IG6ayscZg!c;63K|oO<;HQm&7?VC({wF7!%ofAqLL83Rt5!@(-Z*%$pXUx zC%P+uc1p+5g2za*dbF-8Vo0N2XV<$1o4;m|1R5#=zY^mc#nN!uKkk zUk$<1(!r>n)bUHSMsM^pAX=_q2KH&vm9I~`fP16izTU8@1LgqXu%K|u0QRGB)FfWX zjWJ)eB?2dA_iMU5YBm2iI!yN zm?Nd5-b9E*Oy-3q($qsmYXz)hjiNeHqWqLBlcN3~d!P4nZqqp-7<_gRvhKO(eV;FK zG?)VF&d5O@kzdS}Q&;HApd3x5f~gsyjphK3AaTfOG{#$B-mm)oDZ}&Tv}1k-Y9{%PU*7wP2YA#l1dHlgM#tEXy{2TKu_j>F^t{3%tS`|A9AO6h&ee-+qMSJW4?1)~BW&MQwX8}2oYsf| zzl`(vnH|67`d<;ZVaR0(FGM{aJ;F24oDqJEGjRw`B-gF(Q-8F52@RGQJM#({YTaJO z;|645iSG+!7E9vANvp?NO&5=JHCc@mES~Ss9U{5ci4u?DUzCXhebpP}Z2Bj7hG(ZLYTVlZ5gayfvFuIEN0Dx?p7gry=j!kmj zNRDUh+#ke&7)is&BVshLGv-8SBeyCiepkY@m1AL6TO7XHWEsdYk&T~E#tqMsi?g%v z+Wcy89EakeT#~3NkDNutE}<#?jNu%l$YDZOVz5o2@cSJ-?}vIqN1?~+>Fw?49cgJO z!C_6j6*-kHgDsIr%i+Pufym%T$95uvbZ_UQuOnYyzI^#OtiT<2o=r@@SbXvP`OBBz z{r9`=2j4$=^5p5Gr;q6N@X^El{f+(o{fC<`2!D45SitQyV#2ua*SN;;ib1(cY{T1_ zX0s=$+@ABpxQg6u?h7o170ZiG|PF`dME5pl)M z3t+y)d%K;4zg_Lbcx$?AI-Nw3o6T-+VSqc>*-hBpyyWge1P5l%PWKW&$IWpaPP22# zJnwcoQI%jO=;o>$U;|L7)4{;T){$U zTRmrD)x!X6LCRG%2Ggw2vKVEA7O@YueTpl62alhjdqzSoA~`C#bpaRsGR{5qm2`d@ z_Fyc>g@oh7R-X;Mzr(0>8sDXA$1{!sC6Da8 zjtq{m=r{tOQP2PZG_hkDYGxRfJd!WCA#V`MdSs6zrKI2t0Wl<5QAtRxBt&8bH!zs? zPx+8N3BnnbQi$hB#fSo@Vo?H31b4*x5k`rILaCpQnhFq|?T=jn)-v?64QY~#8DI-$ zEi~YnBe4j9`w?a32XxbG1Y*Q=L9YYEe5d*uPuY>=p9;n{xFQLA-zx!#v|}5v{?d;$ zLzfBBDS8dg&BR6+o+|&0up#|e16(G(2IjuTi_etNcVa^9fB7J^At8tZDrimDbmG6N zo+lctuc-lUwpB$QdpsnLg8v*b$xwxWp4Dso>p9ir|8d%9K>M& zFg-m>fAYJTOqLEJC|8w>qj&R)UepSgw2WFT>Z^CNX?-tG%$kstxUi-#WOWrI=#}T^ zr$hfbY>2QB#KC=tAO9(<6YwhObVj|skYCGx%m92|sI1~Y1Y$7}h8#F98i3>Fp(|iS z%u88&gz+t4C4@S{$@=Y)hO)kj5!dJf9uWFxA%kuhF#@5nCjLyaTF0uP`G=LxgP9Gs zEF6S|YfUa2K^!!6T6B+HN)DN=!Vc?Z(`yw-1{H27=U}xE#p^YCf_Xp806YK-rgJ%F&N&2F@X$V#BRFlMA0zB~)&y)NXbp$2d9QVZn+Q~iu#Wti@GTc=x;FB7 zWMt@ZOK(G|p;Rgj4$|MqTZ56)rNPM0OQoIT2X=M_OFJ!*!3Kl2{-^E5^u(E$FBfk; zzqS4SgZuX%+<)@-r%yK@{eJVwoewXcJ{oeJ_}l*ezrWpEezmt(+$$D~e^|%ucPlG* z>D_r_<=q>2m#!4|pMQAy*icV6X~b+Kk=%)E1+37MqGeFnmA(Ai${E)hAxx-~MlXd6 zNtH+dad|)cOSO%w6-*X;C3eA_onW$@g|URaM;4;2l{nEdfwiDM;Tue=IR?4{D(MPH zah8!D4W5gtqbd`35)zCi@VSp*RZv~1m-|c>Cc*GC)h-($n0;^s6SZANWs<$>T$QLG zv{xjMc2(Qg${5~PwJZu65)eJNw-fX2TTaxrCu$L{(TecrW%z;s5J2z0TifmJi7tZR zDpWCG=8OI`U=u#%U32M!zSP_v0mDY%Tftc9i%kE8y2ef5^ZQE46KMkI&T=8(6l zWs%E)kuzLLnB&P?o^cs?YmHh#e8%LDvpLHtzXupmQ}#r9zI0LM^6D9wyvE)4)abK?KPC=C-* zS&?<-#E*oy+>~TIh#~Yu509Wf_@Ho`$gYkVG|^LRgR^-oT(z|#;cpSAIKc0l1iyv1 z4;2chkO+NfZmw|XBCNcx7AL0LTFOzBs-h^mqGV8=bYb-3nzpvKIy!n)%@^_cMuuLt zI6AtT$rGO*9lfdK^}IfJNloXA1i-&3Y)?;nxes`Ey>RvFO-=_{01wV6e@*L3mJnD; zXVr{4cWHf5L_do)F#CMZi&RQ6hK?JHU{2!@(`O?9$ty%m7)IXfdVA7xPr&NXfav`d z!{`B_zT$5T4GDT&7Gf>-d+KEygD)p?(A6O^U{qS$So?rUw4)LQ49KQ&Aom>2NIZdd z1UJJ501M;MaYJau>Z{Xi1}?WU94{-grUUQ3^E2t5OSqVYsGGYLLjq#j*kc7xE7qqW ztU0-N&?Sb@F0PdiyF|K#XmDr~8B;tphJ!fFf?rlN#lx&?3Ikn_5_|3F>7Wm~-RT$^ zAc*Z5>K*BMe67^`xKwIrDT&*Gw+x?({JM!LQz{bRwh9|o!nt|Lof>aD!+9q^GCY|7vi!41e_g)qJ7wL7{L#X7bWQX`JLzuBGLA;hn{MuLe)= z+xhlx9#-^KY2PAcirvTW!MV+&jvdOr^C`YlEGaOng5_zMU~5w`O8i+___Ac0_K$?1 zNf-*rLKQpR4nbN%<48RNU8!+(Y~$JECSk8m2Milzdzj*vQHAZ(P{?+@0rxU;!9>x^ zNi6nt@jBK<$wH$3jqBRm4SHp&WjC=QOgU{AOAqR0lWh7*m|-IXF0&X6aiEx3W-=1H zyfMyPF{sd5YkvFXFtF&^HI6ONAVgO(eIw5g%SlQ0B4f*%;2{yqR(t&GNc)qI1Oy z8Y)(T2?1pb9k47Rx0IfthnYsmQZ(r4bvUL}RB*;?^tvrm873ncMH@pWGo;YLhOvVJ zmzZT-VFhl1tk9|)yyDn%ibl^CamMn9h1QhEZSho;PjP73=&(7$%u+Jap@Tr>_OC-a z!$#Jjac_zP&>r9zS5o0$dpzGz`8uRR9fknLYlO*OklNZ@oa+L1(QoRvkK`!$r@WR zLF^PKKGxi10T^=F3}j1WxwE)~(!lBKa6;?`oY2E!M``vYz9*Bv1)lZ=m@!2df+EYLY}UUQJez zTrC4kNNR|-v|Qn+RWdRF=r$zldU3%y?nq?d4E-pnmP@rg;Qd=I-`6O9Jr=F#+w*_p zS^e5BFizWtX+;SDPfliU0J(E>StwP-V8D2JeqJQ-@9{o3bG-lvzgGZu3+V#i>OkVc z2tBTrRUYtj0{GKBo(B<3U(3`$;HD^ z#{U?b$O6cmYi1nbt-iLZ17gJS`3LFr;&CmG_~`MWLzj<^(y{CE)rk|M*~wEQpU={W zgPlw$UHV{E_I0biZ=W)Qu2dRPvpDKzzfvlZRo#j+Oe1ohOC5pfJ0zc`j^K<~Sl)WtWIHkWL{|7h);S@J4$q+O1 z*fsi9vqUh+Z?b8-p{e2O)>bV6Si`V3owe)8@Am#OagF6+S7l-y&c;JKz71J??|m)txecEd}AV z*0r@gYkS^U!Nmcbtti^=6(IuU>7e44$s0$<(2bL%EIt|> zK1ieJi-jRUu41k{Jg&ZI9Ov()$HC>9#e0tiPY>ViY_8H4hb6hGc?b0TIcWwrt79?E zvT`$;QVveKtF$RK6-y{q9+eB9IrSybv-I;du+d9i>go5aBXj{q-89IlrvsKOe$p_D zOTyxA#q@-BYus+&FsxnlF(Av%Al`!w;!H{5e9mMGH=g2U z-I-Cpxgd=<%Im$}4BNdy75WQ2L;G?|$(sop#dy+^DK}<97G*VQ5yvcdh}*tyBPi>Z zMPQn6aIY7T248_ocSda<1>)+^U57M^7TN!+a{ zgY_k9(uy-y^oM3Hp^3)O#f)VrE*7UNrz~D@HPS4FIqmI;-UJ-aGOO_wUvZ$ctE0mS zDV*?e1GqFw3ywqpf|w}wl>*OQcqGBPb0BJFQbVA(rlw{9Ky@*;AzIVXOCt^tH`)vC zM(b*N&20E`?I=Q%jcDD?D7eaQa0`GJITP&#f5qjBS~Lp4CdoODC`ZNhnX5-N5y?+z zV9hv58!E_B?)pNrHZ{4D$s^oDI+7GK4(i_I5gEW@Gnn?1bxq19I>`iK`d~>Gu=0bB zBq437Y6p^aO7GH|1A-Wb0uw>e&MDreU;|-(^l<&5fyPXb9MBc69Q_O7?-qzNTE=@oJ6Truh1KKA}`~W%p z+rw9XIB|6H)Tys$+q5lT<#r{ulFIy0h12h7R!CY1?fuelO=hiV z{d`b$dCRKR=vA58OggApQHnYyg=g!0X36nlq_tTBI?YaBl%xKoB|eq;)#WVqiR_i~ zG_G_}Aaf3yVGLWjgIksxWo54?vt%>4Ra3(}-|zZ(??=6}5>6{Y12RL#{;rD8(^h;$ z+P4XYRUDGm+HKw;;Gqkr=COFLjrLh*tM}}D_uV(P{d{NZ&TR+wZCjDFgtE@+&ZVWZ zOFhqbJ>58eegmrY*(01D{rRWw|MI6NUqQD%e*ECGh6gPVuiU)3YQC4dm;+hw-&wx1 z`h4(q*=_)B;a>jw%ysEnTmV}63BJ;ag|r+Qr%U)aukaU_%kVKG?rCyu}|Kwszc~Z_XVAm zPmvg51Kw#l%S@O`@wsT)$|Ya$Qy-7nP2x>yWph|Z^7`#olR*@(K_`*FI)goqFZ~xO zOOq^CpW~3Wc1YVs8gzi;%oS#7+Cae!G}qEZ+7FD!xSGU-Bs>;_EUxtvvyBD=^N$!y zSa0y+A}9O5pl*4zXDdkER0Vybf!>TmjXyh#9@zti zxGi@;^>U5K@|~@Mj+Cje!x5IiU_3EZQ6V={EJw3KZ3KKhDNaD+(o+$(NhTpf87gc{ zR1$v!-aY<>BiJe`OgaDhI;!s)gKd#R1r_K9{$=nO8FW5^7%ym8MhY=&h@-nO@1Pj|F zn=<9WOsWNTXXZ1zcJ0_$j62LW`l+KV0sS^ zvk^)s8~*U<{}QlHS#P~|P_v&+^0S4>27Yx%JU)JN&1k|87l+irVq!Qz-puLP8Jw{yf!THnHMV;5Og4W{XMGfX7`m2sJhC#ctjMd&mj3xh ztC>9W@m`mvRdyLG(kE%gH#CLd^Brjr5MB&K8?=FNgzhh|H|z3!LEAjhCJWv2ue%xYyq%FRMv|bmJ8>v{yO@kUANjMhNClsOv=LDPSXc`#o(@T z`zxKM)MwC;x=hB9JuBAHn3R6_kMPzPFJJuk>*vq^{{6q@f|lt||6(Y-cYMrL`1s@= zGvQaC@9%&5IcH;E8RA+K>RMY}ReUWr7nPJ2Yp-4^Q|;+_vJX%yhE{-C;M82J0JA2j zRN=P%m8i4gOi{iU!Q_$#rp@VnrQ)a0Ke}~8{>he)VZaqSK1#){qobqh5w(^py9e@z zit_tP#Y%DY?yteL!t;TTjQmNH%b9ua8is=G6@WU8IW z=Nx*J2-qCEt=45I7717bIM&-mIp|~iY$*IJBM0lhIbGYPQxjod>c3;KL zO@F=bx-T4;C9i9ebZ9M1qJlx-Qb?_UZsR0~dZz6Qmb#>L2)}J~U1}2)MQ1h1v{_Ks z#gdqOEBTl-+u=)-^0PeD$gN0`o}@78eJvuC$2DCN9^CeZTX5H>?r!aa9`o71(X9lQ zUpu2|ho(%W=l7 zJ`AtJ)8bu(5~Bf?AHyC*p;|_$``@sz0Y_AhWC1kJfv7rzujf3e5zmNF-NkTAHY?=U zdIr21%}3!Iaugt8nTJr7=KWDFOD|}hfqE)V2lbH;v3f?w1z<|27|Lg zmD3Yiw!rE)p|KnctU+9a&YD{ZtCn8}0&6m5Onx&3#IayP)1M2m1TQXPdKctHrV6fL8==XU#a)!H=$ba|F$7RogZh5lLq`0a0Dz<1>czA5lKE$0JO9Yf#IDnog#0?WJD zkcLbQmJXdQoQrCOsItcCkT}BgjHI28Q9g@-z&Ji^U7%s}xtw<-x(h z!KQp3Z1MSEQ(L$yFku1X(mo?-Vb;qh27m=;OU2vT&hfX6joa1orlN0&-y;n81P0vo z143+iuQHa{Ox_4;hRSFq(5K!Z zsH?rsaP4YZ@@q@dn%_4pH+S0!pZ41Z@C`$AHEzpE8?aU%jSh^_NeKSR*EQr=-Ohnt z0ayBf2L=eaaykK0r(7fcnPNftF0f1%M=$Q9(O&1dK2oB)djaG=L1T1Sy@I&iXZuF` z&voCscaHfqQt7ispT&J4*1gz(r}{hC0}~@j8gvJ{Ul%GXJih&nQ*46iS`a7>O?9yP z?Eq&PI-fl|r74v1G*mD!uNHWn0<#IZYWyQ99Ih!0NByjNsT)KcJ%!H7buUEphJb5Z zQwNzF%&58LOe0-KL|dV6Mgwgo(UZhes&E85^84_!A+)l z(A5-r{|tb9NmW}E5VoBm#)ESK-5zt7dWzq$4Ge4J6{2Up>bV)2q+?!9ON06fk(JXq z?LPX(?jEL|P~)IA^AytT_Il_HW*$v9Fx954f{CBRfJD-y+=Oha!F@f@;!tU*gQldG zu(?wXLym^9M_I6(|9hBAJLm(ZO@^JYTozG7D=d4mEm@BMui&iw7l<oIvCLmt)TjXSzila z)2ihC?cq`Zb+9TRvc`5lKF7jvD|L3|)Qvusr*8_UW{sUHM?Q{Pf|& zg{|!}GU)y7T@{*s1@WoXY8Dk{0bIMb+Kdfpe|h}o&3~FY!Z~)pWu?AVM$iJDx64eR z%PSTD?`$3z1_g}6fg#hS3-U?KWbJV1!z;i1RvB=uSlPzYRJ}c0)MT^yu@+J`0#V{8d5g;%brHpbQ9BTj#TZD4uNDOJ&X==RRxjQLPwvak z*3;Tw(?Zy)OxWVSU0MTN$7C!?UB6k5y>s==?4eqSdJK)#o`XRe1x)iV%B#Vidak05 z-nBcoXUNn7b(#lew5(xCBcz7D->;czE`wg>sLDtUa#k#yJ>{#wt$BdqttAk3u5wCZ zD>KDsFF*PfWrIV{pEWC3n~8EoG4@~;kbPi^DYtfaS9W)Ig}xpw&>dZ+Kbjb|a`|ZC z@yb?BBf#er;!Dl@haca%{MJ(YkHa2GqF-vHFG|@slmD_DoLLQJ-T# z`{SG%@yq(wuA!8ejaUHN25feGLw5Tbh3g!5843H{5LCYgXYhw~>nm_+v$J8g_d5JO z#L%YNNbdU%$rX{$2)2A~EiClgP&revo5E1*iYm3!?^$BUXR!N6PanECLhzXR52m~+&4}*y2D(Y)hz>G>)~t@`7SvV+TF9!l zU9Qgq+81ncpohHyxNjgpK-Sm2F3t1kb#*Thl*M7-u^=cK>40lH;0<>NC?@oJM_gJ+ zI3M}^k&C!!ufQeI9D16kb}&5RI!U5)Slb1mwDaV2jPz=-N4Hf$7$BpPP-vmTBVLt4 zhqd}hs~Jwt2eg?`50LvfVedRA54uAha;#*wygV!JGt98(@0XPMI!eNDX(DuVa0NCb zBv+nJtpJwWtr7-1;m$B(9~79RA94mf9_>D*aUrNnV2TPEG8;*j$0QNJ4!ca;}irJ;+X_0ETO*f zkl=7U(G{x3+!+$G%IY>sB(<0!kqrqRGk4Bqv(-={#JDCw z7UeDBotm}`-__}GGM5z?#q3Lv2AxRywE*Z<2GF|b9Ul)}MG9?^U@8brWTjl0izAyB z_%(}VnhoX3aaCH6YJ5ipn-ghU1XAkMxl$#HD<}N>5DKpS!~)Rr{^3?xyCt&m!%Qw7 zGEtPjqQ0}onk?(uHUYMdnw_<}7%ZF8?Cft}DFYS&Mr{1gwXbfjeYH2WU&k`^*Qv(a zM&n>_>S^n3>!^9Kez03_2~*lRI1*BPBy34gd8fSto*dfv&Qd|QSRoTFy}J2kQ#tkW zCW5Sb^XRb<;AV60i4tmdf_H&n0bj<@i{SUu=K{cg_~VU@AKwcA*Y-CxqgpU{^`<$k z=u~@idB3JR;7Ln=rRpm@NNPY5RN{h{-N`GHic*?IX# z-Q~H&dbr~fhXo7IdQK0GSs9d8AFyUnl1`~G{0YY3Ap^ihlXW(9=A%D{o~t-l0R@J8 z-inmebtS}pPJYEn%bKLRBW;{85n00e&x0?P&*+M-jh}t7a15u`(6?sT>@j%qjTs#) zZ8hBW?t(mGW&^8pV)J8WSNrNi`L7-L>1e_9NXu>VlN3Q)AFl;&6>V47)*hJCg9qOT zkA1*`VNFnYvo24Tr?qx%CHH*vzw0+Xo|x$S`MplIReN>JfaQla_vNo!)TQ#m!kL5b zf4+X>(^DUwm&bU{%HkX_@Y}9f(Em0AvC4xr|JfLWA;4yFd|b=`05b??Ye(>g=>zs_ zo4PFzwLuwO(uuR(moGW|ez=cMZNMcv8fLb)SdQ+ON_n5t;muz@+PjMGq1VO9_>Fu z1a0$Z4yCYQWLTZbg<1TPlEutfuIuRR5+F9@SI|`u7$LKuGQul|5MQ9x<51n_3@b6= z2MABx26JQ30w}Uj-C&_hAQzKSyem;i#4lw*V?oilJ6nh)1a=bz!C7}9k&Vq{Gi8C_ zxZH!Ao8{U}LAY)rk%?sr+3bwKZ`=fA30T95;~7EQj39KijHVgutQHc+lksYXFb=^p z`I1yhvN;5E1rf8FK#4GF6rT`m6mVqrt2xj~N_xk~D?(=>zDjuTa*3*2UY|&3t$bxk}t3Q#tPzC*lX@L8jn$7E$>eg zQdQqwpRTXG*=@C^)^}UGjiaYnd3WEo)~A|s<8EVpdUyAiH&zhGtOD>qRD@NpGa)94 z@{Q#o63ko?&RTCiZs-Ks+98^e_FbK6>xWLTpU=)se0u8D^?w7t0$ig203ZNKL_t)* z3(ZZl0fzlzMv^~DfCYfpYXZQUeAP48V?OJ8Z?dg>{!v2?HF9DC@Fl{c&uWU-j6+S4 zdKtMeZu{0Of32#cF)Itp>R%W;ZJbD_3^6`^QIoLTq@f21<3Qgm?=ur<{0naN+HpNC zods4dG%!#|7`#;AI0sqKRshzJmLFLLU@H*I@*uT!(2B%ELuYemKKfJqOUsb(Ae8qFih2~YZrfcxB&q7_55%IghP+H=@@_^yas#)ekqs) zb-w|BIT-+6U0z;3YCiqj`ntudYm19-f7p06cD`re;rk~ledet}8-N9YS6BBJYU)Vh zeCAk$Wy+u@OhH87!1)1_7lz@;R27=HC==}_!U-a(C$ye$@{W1Crc;wID?yx^LT5}$ z29W1UKfR>Q z!6|Gvay+uvPN`u9eA5jP_B-oN$A$yJx03Ge#G67jag@qYI zj=Lk#uwbe(NP+J1$bS<+g@*k+(`}!MCQHSS|2>WB;PGjx)9ND zEP>u|7+~&psW&(fj)dohG>0QXg}(-xbwJGmm=G)wcw1G^x*N8TRdBl(UaU*tfXUtH zmZQA*fP2-MG!j1fXg;j5&m*dQrj`LNtYR!VYPgz2&nHilur;m!_U$>V|NYF39_25|?gK$=KsmcQ!!72-@3mRuwMfLNGuLXAgme864AV4=B6#M~OZ0pWci zh#O-MEOa=Yi7};qK@4=coXAuKyc35p>_^E=OmMj1F2@DU%83}T1twSHj5rN++55a+7xMhAQLboQ6W?h-wZU3S>f8bH-By>#gJvK;s0)_p9kwg0n1wL1?0% zN3Y`jJ%k>!J07J`iRL3?11^WICUfPA?thb2HphT1KMY7SXHHf!I)P>q&c7q0Ih0l1 z2q!aT06AIh(l(@DZGew`zzV*zZ5`He8kV*Gy{3Q+Bwzd8jg9wMd8eu7l`})&+Gn-e z2a6v(snvE6D(`%@&}=pu&7JAJ^!#9zrqC{9mKtnVVE5Z>Y5GA4#Xq+KklWiPY4jqd!X%|GPwxnCrExVYe zP3qOOT}=Hy_I#e-YZJ{WV86U}MS}c&zt8hMoKn<1V=1v(8gl4HA(9nGc}aap0>Nii zFI>O)!)Lo`)49;90n95JEir7ZG;a{QVR{#+4bmP175wV;hc@uNYb7@Gd4>Aifq(AR zESjqLy8+B@KiM`DV!16YGHzJ9zXV{|xu#LTGJmO#m3Gx-h3>YDUoCxl9P= z-#(pc2(9L3>Hz#w3Ghp1&G!X1mHf)<835LMu-PRv^9KtvC*tVZFVu$AnqGZfvu+Il z{)YnaR&8PGiCigsvQa|?Ee!a}uRrg{FTEnyD{O)_#6*+PR2jfDUIkj;m;nL58Urhu zmZjG?dcM(S4Rk)5@Hh}(xjz95f2F=AnfyKO8TYwXSzg>c_*#!JIk&rLBzOQtF zT+Vfsvwd2e)R$|@QdroX$aXc!si>a2RU8fEX3gGLeZSqgj_#~4n}})~0|!XkK)}3? zev8D7^^WO|Y0bEj6Qa>Bw9x3V1Z~NkMDE;H7PJkbqVfqlWn|s$>u_~Hr5!1%0xO)q z#5+f$PbqGQZu(SqC8&&XxE<=-7A10$<|MKw*(E;}ES=nJcTGlPuw?<0v09+%~!v+%|{T&!wDQ#n5)QpsI}vJtqraQw>c1 zhSnds^*HL_$qT@K0_vS#AI;rg~4+~TX}U4 zE0{V_)F8?p4Wkr9CTvo3DSI@g0{{l8wV44VzZof<$IyfkNvn|bn4Zl4u_sc{v=6Is zxJQ0~%sA8Oh=~f(CuFM00tTjnrg;@Eq^d>3fPdU5VmQ~p-v6V&Ci(e8O{7%ttuKjh zee>dus-Q>A?aIiTH*-`lb5??;LC$uN}W!Tie@S+d10V-q|8tYYP?h!S1aa zo!|TN&h4wOKfOLx+q)+`nl#G0IFKIvntMb|-&@+AS=c*gk>6Gm#vxpXJLp^GO><>f zvxpUeO=+J=BgRK-fiT&^&wXcq=H6|gd_kesgkf=CdGKW`|ElG*vR{=)U+wK(jf6aG zcEfSawlWf{ko@jCJ@NP`E+iawbTSNj)tJX=Xr%|`oM*pzr{zp8G8$N{1L#gu9As&E8B`DVYu4gGx-S1V4MP}`bQB8% zHV`QYDj(Yol;qFLr4z1daJK=I;N(5Q$^D(J+MG3K=5^lw@1xs4xO!@3r4t6cpwnqC z>dtQOze$0?-vR@|kZF_6# z1b_vB89^Tiu+Q#nObG*i{U1bF-!(sPXMJX$Hrh0G0jDj8u>4JQu4n`Yq`0-ylqV_~ zwjwN*0iS0C?eN=CGn1PE9sXFjjK3sA*uml#rYnH!2VRBX(Dv$Ax3DHP+jSIeN3`X) z^~nPT*nn{9rdQ~$++Ksm=%xYPKEJ@a-A@>nskto|^4g z&$)86`VzL`Q(2bqUqRjIbWk0`9ojR9Vw&>bsGKa+_ou#1!D5~OD7(7J-B7ntblMf$ zlsnz9V7hyK?TWZA@K%GaVw1u4NqI1dFF2@O3_e%hHMuE(|Cs6&a-k#rN4$UySIi~p>6fp#&AT91-3Xue!u_Fmw2XQ4e6P*>yzopS>HUZv%3gm4i zo8T|oic(3#NVT2NX2Lie&XQfb87gdl*#x`)U}}-PsIfvGl+r{~Dgzd%by^wFByTuy z{W6Aj()S{7M;MU8w66(8fCz*J2M6O$%8`Z!Jvb;s$v{C+UgL(<+nlB;%u4 zf;~xR+%uk97T`soH8h%xrwZ|;fbNi>E%}u3WU4SeG#-gl1zae~m!Z)J(a^+Fri$am zq_AT-pj8Zz;z;r^qD2c;_%0Au9M2Rp$!DN(Qa~}TW9W=_5cOzB;e~kvxoE7kg7Ca% zVIgVO5@7CY1~ggF6I#rWnE)%#>q59k!zd@P?<%t1BzoiK1rtWugY4@jSsw=6nMN1T zKToLrsGyGIapvLZui08>B8O_4DijViIZJ+s&`-W-q+Dsz#!2pEqjKRSe6qgxRhia@ zW*B|zy%%@>Ebovfm^)^0*L+xy#>P&txB<)@93weH;Q3GIZrn=uQb#DaPu7l+T(P>n zyRCWl=_~}`}OaIAwh??7iRWWP5kqK;kSkitNCbn#q9b_(i4uIR(*3Fu=F*W z1FfLd|2%f~m)~8=q)}txa?F*9T%5$ zT+5}VQ-A*vA)b{afKlp@?v50b`GQg;h9r`{nw+Kar3H- z%3{Fsnic~#6X-hr>dRU$T&KVrwYiO*wf!9^_QJx^x3^zhm4CrU52xPVLJPmY(Ewnj zz}r&`wU-a>K3=QMOkLmm%OhdHXWn7jOnV^%4}jF9lCGG=uI|Q-n|eSIcsOlvSVLP{ zN#$HgtEH>6fA>5~UQ?VdU&z+*67lPH&^1@F2^6Dhw(BaG+9Ld)_E&zdy;O17OMHit zLEOUfWVc2G1LBTKrHqA_BxyFrG$RR724)3wHR3}vq6N$mLpN!lR;4M>MQj!`XX8Y& zCFCgT=W@V?{uvq8!zS2pSC?{MB+KO{=E{i#-rz)8lR2;?$^9%2q&_+c8A#{)F#D1~ znJ8l|N+eJ|1G)moeK{%y6?oU#0OuYi6l(={JIdW%g0!20(t^=nDK+k1Ph=HXaU*q4 zYb!%rn=gyhD!RU&g&@0J^dkvtC38ci(DERs6%FKB1%px7G$GEDLDgRc;ltBDL2f#I zr(G^NjAELy1rJRn>DL(?Iee@7Ab;jK*d^xXaSa^@xRg=~3ldrCP zY!iDgL+Kbmod>U3>o&XOu&FG}^Jg-@=~FK3YmVu#nyLp*X%?1D9igyWRtZfcsAv(E zYNG8n2hG4Fr`akjd^MEAOFgBVWiSRLgjsev1<_o2O-BP$X<7@NbQLm#4!c8eWf-s{ zv`qL$7)w$(yv)GOG_k45ipD~DEGNc|T|?fJl0~ASv2hFuB_0YrONEDqgbh1W@ld=d z2pcAVg9&sfu+MlNKG`f8wv~?QW zTEfNIvK`Lh+{YreWU@eMu0DM_Y|7M zSJfc!#i^;+hld9rHqn>;13V2fXbCFD3vA6}a2}rX2z;H)__``wAKd9i9N|kcVEIQ$ z4tkC>enA}kXL z39=@$&y;YQl?+SPoN{eh$v=VHOhFM|?E6x5=9z`t@LAl`8aVl}?KMRO{8UeJj^YFS66i!%8VNObVR*@L+I%0~Z0W!L27VxpnHa z1b`K(Rs@)fhP@iB?lYSZJpcgz72wGj3YAx>;j6j^=~CBbbQ8lw7N*r0n?#i! zaGKU>%FA@S*9m4D(hD}C$}BVn)0)L_dDhELgHex&1wGU@y3S6d0>cI=4pf$db~sou zf5E11QBkJ*l`#}YgI4basE72_M%(1^AvAVjIIWALj0_3|pcV|(+u`tUSBs5E9m3t` zh2H*TgBzBO)*E_E{f0CvN_$Z7Rd#oT5ZB-ZNTWf_PB8KcjU7S1zXS71s7nXz-eBNI z_JF;?P)LB*Kac)zFyJo-09SbDkb{Jpw19I!5V+2dmakh$xPk$<8=SYoiv&VJ-Z^xG zgJ82lk1O2FN)ou8t3&=#1!~uGLXd-$X}QbiIPgnh7W^hF2*cKLN1*7eo6*5mx<|Vq zqDHaVdYAfVs;_8)C0H#hf|TyFZa7XN2iQSTmK=mlG%cYWj6-tVW#+HLdJdz!7zRe} zAmSO$3G6FZN(3>Srmjlh7iN{`icVv6xW2w#?pjYP4mxmftQZAodBDT70AO5l#cgWZ z7odvjv%zMk>zy=+W+@sz9m0KG2xhRr2%2JOmHrFs zJtuV0PB;yy1XKv1P0T6BJd(l1O0-EBE=th1(G)iODt#`qe3}r5)Q+(v*kL&nW^+|S zz}V+Z_^Mps$39e}T`rhxxY}J2$ekmtVV^*3mFqS@^)bQ1{#xnEdVmniTh?^T1$CA^@haelRZwV-v@+PwV*!)GP4$~S{m+xMy_$0~#|v<(gp zPVMb~zOnb~#;@;={`>a*&+mVE^9G?Zhlj5YHaEXtTU*TCz_jLQQk|p~EdSr~p}VI$ z);6`j2nw4AZVjK+joL|_4(r&Hqq*E7`^zg?u$;*pTtDRbuP;9Di8a^me=*nyBaUQN zh|(@j(Yw3JYty^3JW1uQJ(833bY^t(4r3UU1vIBj;dGzf6>zXX8I+ogrbBUOd|hIxc7n)P#AAugC$EXVFgh3d8@P=gj4>;v~TbD-Va z4lfQ@Yb8|vm=Wfm1==!|u1X88Qd?aSEspTG(p*c^tJ2y60t+h^0?a*X^G@Q*XCL)F zP;*qwBO-b8FhWrC6%n>J3!!(9(hg|}Ncj{74Yq+p^oOPp?JvJ){drQAp@jjTB)}R{ zviP7;U`;EfF)rS7H2<@j+4dS@a<0N$M# z&#n(AZ=eS}wg2S?-*fG))^Jt*9(XjlGrm(*a@GpZcsXZbnAYr3zS?r(B3Enzz#zMV zuW_9M&SIM|mN*84^jr)mHX0yUmVE}Df!Z5eryi?1yI$BV9I?Q1bVdXz88Q89)TwH= z(N3*1h_ao=8${?h(t=@vr5C7#TQrjljRNjA)S_+rP$zt{U_JR05ZZ3{8aaf7`m?Nt zgeYVF2rXhv0AoXVaEI*i&Z8jRp+s3hr2lppgLZEK&0jL%AP)%gqW^1XXQ9R#!8ouN<{Tri&9Yhp);jL5D+&r0 zg9lrogbtRMGgQ!8R0q$h5%*k$0Biu2=8^IdeiSin5Fx-;nql2_p!tiQF^7MP&N?a} zipI)WT2g*@lTMThmGQW9a^&t!E3BdG>ls0a^j|BRzyh^5h3tYKqk;{ZTLdah8FW1= z*hNKZ?@h;PIRw5fs9Xf}b*MX?tAB_PVF$#~vR3~ac&?c229`?naee24%@8l9MN7Qc z0%r~YuHJ<3Up<167N~nR7%V!2?BW=b6Hsk2aVpr!7$g_WpPg{Ng%O9zQfz638FVGU z*o=WBv&GVGh7Q`mDGUpfVay~3=GNO#hx%|{@;L=yX@@0P3)^S2xjo@B`%tWt#Rc`1 z5I%Edm7s5x`G?A?$PYf4QYM7{Cg8ULkE=>Fi4h!#HgM!tRfJ|65y+u$RfY#J?(4&h zFYGKD5;!KrGR!Kp;2<&_qJq3&oGO{M+zj{(7O*1$I-%VQGp z2-MdD$_fixOeECOfy3WM<)=3PdHaM3R=((bsn7;iUK{eHd2mqU9Sr5m&F?i@XM|Na-?@_+t)D8T$-^WYWD zDRcBh$PB;g?(dI%IaRwhN(x*6T;T7dg5f+OD~ilx==gGTQXxPliOqlh9P9D?aer^> zCDV{r(^O!|`98HWIi|)|wyv$Dp6mjEFQKMbt?^$~j@F_W=s-!&MPprN@j{DX(g^cm~Z2>%59*IDf}? z@SV@ug};k%jjr$^hZBzt|E63;6PvVcd~Pv(=0`BJGW zzH$nam-3V5e!QOBO)ed61LZtgywF)}??m$smR8Ij1gl*@5HQA)D31|<4I=+2=!HqvTsb_V1OAF&pkf4u&|b8N)nw9l91nK? zkE^r$ZTdc=c(D^Jj+y1yvIWj?)4bWq62{al3B&;pa{-fRQn5_#1(K~q%d$iwi6V?> zLJ%mON*732Xq%#zz&b*P7)-C-%<{5;*w$ z&hwm?u6BEN!q{+JYhfrX99X8LfMO_L4m8RM%;q=Y>ja2VOp}WhZ=7vZA43@8e3wkh zdIRG4Y?uZHpAst#jlo$s@hoZ2@vtx9I~fl&+(pqP@m2kmuy2+w1qq^iPU1*1q+~Bl zCbV4}5@NqShS7l@yL$!F+~5mKkJS@b3MDaEYm7eNY)2$N&t4Iauo%R`)M`gZBGlxNE3vG*~;|TJN?9`B>g)HIwIv z$9OM!8xmv@J!wEoLS?N2vDgAfoiWKT|E~K$*o{m1Sb8*#GdOP` zJU-n73a3X6dDAiDzD>8LNwqRih7hNd;~5nY#d?zz6{Zyc$@+Jah-TqkCQJSmpxH-4 zbgVCCq!%AAuA*N01Ic~vLuCcnp2*69G-+__Ou-#$MuG?1UHcIO-@cfO$5^_s5mJg$K#b2PR{aYG!h=UGydyKc9}Fs4oZ5001BWNkluvMnXb{qt*z&N@crY5_bQbC z*#kR|2$WB4+UMrxu}4R@HopGm>+ZL{dh+C>FaP+?=k~J$$7VkL$G7Autr{>NG#YZD zr0yx9>@OFdqVIwZ=-|RH%6Ht2^{)nu0Uy|$+4%eK41kGZ!Vt5*az}2MwY9bDYb)0m z7q4DFV*u=OuUsF4Y6u6M-DbqSvBD6ScDdHuW`!X2YiVk4zFVklD5`znJM^3A4Hvjk zHX~6zI8vCV$S(NV#q2n|T&3quB6rDZeWW&H=)a zTF7uN;`gWDKP>*c!vXHmmZzSh9i{JO8MF*Z+*ywN>fld1ZjjxD#%yAjE4W{BoKA#x zL~>^gtp+({8VgwzwdnG(+M1U}Ty7;(co2HmJ3j$*sy(j> z^m}E)?wq0I*^3t!*VY%#to>o`>f*YRu#Bl58A5ISCjhv3^RIJrmshyqcFGRbkwDLt zMOf!67uL#nfFCa2e0bS-^TNvf+|~JOr9YQ|k6j~g83Vq?occ168wwH8uNr3M^~E{t zNM#lDfjt|}Y}7oWJaA=?^gH@XW=ZovKa&v!db(*e$ze>W)nV*9ln3mY0^n+t%HClL zY%m^qwCmj_Nll#=!-}&4i3vR-F*^A1w&CDlP%12Y)GJ{11PAwd8AKO`gJ^WnHrL@c z8Y~cv#J-nBFw0(h+a3;jWGV6}5V~rcA*4reybnIS&!Z3yg0JeTsvyd!uv`>~fv%xx z!7!Pc1$;-^`?eRH*x3LU{)^(dP}NHEMgc{%TN0CkWe5LO;8qv(myK{IwqMM`twc~# z4%|v+bXTI4c3&LAM040Dex-yF=f=iF*Y3n_C1M#WH+H#ntj4b2k_8=Tbo1#%VmEcb zT?AAn5Lg-9hG|`h2f7$61I*#XY@$+)ln8YCI^)2sFDwalB2gcXHxLvZAa{d#v_6GFO%B{$1(u~=N0Ib+FRSX^3B*hC!#cvqK z5%}COY4kV+Or~8-WGvg8=_RM*glYwmU)h&5#ThMc}~KDh)e@+xsgb)+34>m0!)Q!<98NGY3) zzId;@qH}ih=86#de|mx8z}?OO4D&71;4!1Ec6GL3r^(X634NOwBPgp(m+kAsfKm>( zHnui?{MufyZNAJUzzqn5a&f~|A ze_sOT;(F0>t%cH_dEx&rs}Br-AGtch9~QBDUMR;y$SPAxYC6N4?(Jp6-w~oVTn1J- z@W@SC%OQg!&82D}B~LaR18#N&eEnJme;7FQcJ%|znO*8tX%u~YXlUp#WSBhYA z@?8Vcp6~91RZh6WMRIhf4<7tp_6GbF`IPDcDt}=IFfKA;WJGQAveLMMfsp}_M_<_k zJ54m5!u|Vq!GISieVqT`&IP;SM$cLRKLjV|&c9jq3Ta3CUPUdXUG3b(`L!ZHKX>(m zReN22R=oZ7E1Sppr`Ha+xc27U{N+3BfXldE8FJseY3EX0IIFsL&Cak^S5{m`c=36X zp3f|-&YwNI2mqg1fBc`B?L)>+9RQy{ckz1hX_T}J?JBN6Jb(7;_4PBS*ENDZ`ss7b z-_<%<>Ngr;v0L``G7MsP@MRgv# z7pxiFRzuMZGzVX>zJtqy!|)!D_P&HwqHx7yR3~#0OI@SURdqF=3?t$qIPsL2h%tjXkHv=r<5qXHst{B@R#j_Nu&Tf~ngriu%Djqq#mU>~WYyb9D3<7OV>oWO+7+Onkb$%F zErsI=)X=jeV$qW1Qw&GFLZcnxV(MiIeFc%#NjyksqZ^StBb8#5z$J3j^=9Z^gov;jj~CdF)2L0{#+6? zmSz+qhd*fu9KB>uiXetg+GEM2Utw7Ho7l1C4S>fHWTlX2;X)#5BSW`BCN+)X`4+n8 zROZ$6_-KYO=nT-CF$&2PdK@Frt7#_H6a&Yy+35_mf9SV_#Rh3tL3V zbT&IaPJESGdZos4VUyB5_Ziq`)rzE&2GCZ6=Z+IuwFU#hy{ZQWS`lwyb(&P@RiFNR zzD&}T#I6`^w4wcU2T2?Fl~Tx_)liHW+UUB0Ht3wevpk*gzxco@uf|@eWKouVzhm7M zJQm7o;OwMV-OdCoe0`zY`GJ91cYxz#?rJxuri9V}vTj!{WBQz81#9nM6BA=ohe3;@ z#||9WzVpcTou^(g#%$Nk%~RWl9&Idjf5V3P$>*PcX~6u&tZm+tS#1iOM;ttC>{TFU8yZQyr4G5oTE7cN+5vqGYZ9%*PLuxcq zY%ckLmxx^0Z*R>X#t;2^@Lq}Sy7r^vO5JF2BCL`b*kwYuw3MdM%P}U;)E>#%9!bJ< zS+h_>Se>)05#MSf#G^bKsZ9~Y5jA}F`q=^RcPY^B`m_tU{Gn>3(n6TKM|ZR=Hytzv zd{23r{r#>^!pVr-t+xHTv(#KFK9=ODU;hLH+5$^pWKhDuUX?&x+WuLF$+L?v;A;;{ z7pH$N@!#|1Y4Mv+39y#HXV0BmTstiQp1-`xY0~<)%QHs~@3+%~Ki{@juDC{aw>@%t z1$Zsm3;p~`apidewJsD-lO9=laTnYwx^yC@7x=$So!d{__Zi0P6S8q-VUR6m&n~s8 zZ7A_l)h*O94Aq;|TofWzmAF_X5J(7tgkcdugf!WtMk-TC1Wh8CCPKP~WDIo|+tRgC zXp}?Os@heQt8}Tfe`N3H`TmSbievwL08-@V_q^|OI5=-723t_wmHlTIm)|#(yt#R1 zW$WCzbL+QM=s{WtXLk1a*^OK0e}De`?ip-I|Ni0h;ft@lkr~QljuJ?_Y2_GoIUC)K zLWbbBgHyPK-3Vb2d4QZ<-0x1~GRhPGvYxnJz3yjON8Y4F&B9{8ZxU}OQdZwRVvl@8 zEiiyKG!D>D7-Zlam+lHr5`mLJDh7SHLJ>vVTW-)7n?y%V5uwaZBDmq0G_;_p5vVYN z9v@*FaR<^wWkH1l)oKuxbWjUm3LWTVP&JaT+Dj=z;aas2F9dsIK?74eO8-J{tXD}` zhQ}CzgA=`U5f-WjyZmwPBh1436#p&fHdzUCbF)%_2~+j^uu?8pTp(6qwKA~^OJ=8Q zEVz;@lea+()>*0vEAsr>$7)N(P&n(1#90!b$%4+Na+{S@OEkBt>shwGtL?c}vO5f| zQ)F@wmX%$~LXDAJty1V9O;swY<#0jiE*nL3c5(?#CQ#q_tgBYzD|O z`+mN(M8Oe>(CMox09K|m+0maf+9n2?h^(%*rIxO?_I8<&j0mI4qB;p`+%NQPS2^%+ z2&Y6X-Ty*Z(g1QO4R`~S{!_72iew1~aAS# zq!VX3%yq6{1J4mL;F*P{LTdy_1%nrOoI_dtEvz+WJOT_a%*@%%Id{KMdCm^Z>C*eK ztD|#s(1-U)qcnCgUqijFP~h#_>zJ1^5JWb-@AY3_?Vq zvEPsM%nknR;>FXCpM3M}=KlVt|J>QK_ijP-8O89gt++`4wUr0k(zi-{r`OEjRWoqc zcG7;g$0O4uOy2C>YkxGAk!xb?o2g{A0 zm5Svt;bsQqkuLh(&g0vWx8MGC-!?zS)X>xvKgkrn8LfG{T>_X^ywKvoDVGi{ld!8j z%8U+;djB9Ut&<|4D+^CPTVp$8g-Duh(6g|& zVnBUBAIOeQx%Qu(UVhbZ{pN#}wF4vN7cSk{+1=RPy-RB4&aF!uJLm13V13;Hc+C@G z9d`aa<8>iB!8?BGDG07YC%ZEq8Frg;`!-^7$VbUQXgC z2D%?nuVi2x!}%Ml#;alfl~)PEGAJ&WSCx;I+Kd_nF5?fb zw4^{`QnAh&o@UP)12zT=EN6jXz%?CRBDKSqE!yZ5nO4yjp)?L7QYh0DGhhowxs{G; zhZ{|24SieMh1P0ZXqSA7y5OaL=x_^A%Xm30`BnOAe>$b{blQNqYe}^W?OFx5r~BKY zs&vpIINfHfm|6xZkT3&lIBgKz*1y!Hgy2;%UOywMs6*;6B}Dq;vo{v05SgBWN#zo&(e!E{0yS#aA{4WN|< zt?8Sxa@7{hwv68Ld_v=A)vAs|dP`W0m_tV{vl1R2H{>;@JN?CUBws2fr=hrpu?Fb* zQi;Mr`Uus>VCX!J)z^S_3}+H^=6bRAadG&zAuXi0SgaHBj2aqlTdNfp>l#nngTTJq z7;f3L_EFwTBo;>pB!%u%9;N2Pjik%lXv_~ZAigJ5{aZuy%z_0@MJS`!^2cp!tmzE!kZrOYV^Dybu@p0!a~^@N0Px-@OQ>B-vx2!5x`b} zD{SWZa}20Q=YZWAT>`m6UOPC`GrBN0$_+4il#8APjvH4VVa43@^ySRcp_gAp+4M^1 zD|=`)`nd-F*Oa-lw+b z+c)JQnd(u!0O`iU8W*$JGvxIy^r)E6)!<~ho%#3ZVyOG8uGjyRxann1GJx*%k~cb) z66slz#DR~$)kNbDw(I$hQpjyl@*UIa8cZY-c{U~P`_PqlUpc-#{tIKk+Zojb430`xrD5`*rq5)GICrmFj+neMmzRr1 z)9R^a*rI|eGcM%#%G{IR!ZeMiuESv04sPApxN%E^;R8m)J3Evod?Na~x2Jqc7YD6) zX!~?I&^v!L06tJ_gE7^Y-XFBD@DInW&;4cn(iS%uzp5w+j`^^n7&!y=p)` z>b_>X`YFUy+5`K-*I3|A`r~SuyT_C{9BYk*WC{)=z9Hd=x(2Mf@`mz6!%_q|!BlaQtV%(jZ$i0Ok7Duby$qf)08jX;6ET1FnoH&| z44#O`)QyB6>6&)E@q#_F?1G>RAgTH7Ue|j>_~eA~UAc^02sFT) zJyv~akCGHCiva5(OI}4plSP>;*hSXGaa07x1^JA!WfCY2PjgXk3|&!rR_g5LYN`Uu ztx!iu1PArOsnjYww>`UR+&Gsb|Eh(iLc`=V36xza4jJJ^iKPa@tg3@sQdj9jB3e?P zR0gi%Ns6|ox{T}J2>qv>hDKisy|#Q+;(+}8F&JjSBme;vV99Du!U#5ZKW57!M^`4xIJ89rs_bphIe znW2ON)K0^LJ7h*O&KtgG?;7@~fO8)Kv`}EBLEG)I4q2A){W5(HA)qoEe7U2QcbiZ? zJQi}hFnWIzN&+(0%zkXV#6ArBT88jhRmr1>{yM}KU4N!{)!+E2MMPN8N+rY`AbZA03W``G(efHn&`Y=(@5lVlV z=+?CKt@o7%YP1$9`k7+DqTyQty+B+@Kt`7 zv45w6o@q7>9tB{{G*wuxcF*j}WP62Nv)+?#32%rr&f1`W@akc+iYRGA8yfk4X^ zG$+|1fr2j_M>VWU(Rwk(S=%g1o21e%s$AtN*(UXm?0ug17&RjH@i_(sg8cY--{*tG z7^q8TEC5_l5GD%qZyrEQ{LKTT0mk_XN(1FNIKZVm5c^l%^ZEFPp?v;T=GEC(uRc2` zuY}p({PY))eSOS9HfGs!`xNr*D^EY0oczz5eEGkxzyJP!ufbhHYPN~z0^ag|~zyBX4!*DOzDGtdqX{WhCL5Xbv}vEM)KTexbba15B~R}^6pjOVWso)wMn zkIn@kdmaqfU4zKG!lc=C3y$B|oZQQ?FkU-`KG@LkZ6=CJpl;|}`uyDFd1PCX-GcdE z(M>Qg`3m({=T!{d?Fl}A{?Prw<+oQ3Ls_7$B17DKM=_KI!G-mT^VL!&qvL06d}&n5 zl)(GwTY^e0Lknyvp3j6TFAvrreg*(Hg^8jfP;(x!t2a9qSPICbEX}++C9t}cmyhPg zMu*8&Yuzm9Qs^Jx);mY*+c)b?j)@T{edhrAqpf>#&}yHY2!m}ljn+Z4(|K^vHjI;2 zW5alO&oG+C<4+y~PjO-Gk2^c70N_dao(?}mZUG@2N!v(@9lTni_sY}7xe1do%#cNL8Vs&P~p zkEV8$W4oF~DM%eo0i+Q-iHBikKm&h~OBvo3)(nYslo%Z4Iv4%HDT7W0u?WTo z8k3OYoMdrQEvjc7$uI)2f(~^7N0CSAp-xL^aMjOsFcT%^Gs6x~@b8WYrq!NE4V6oN z_S07CHwG_A-slFvYfBwcei?bFBSg(ai8*U_0S}=T`MXc$p8{=mx=&k#> zbF-UaRv;ESX+m$&?$m%RX8?2<)9Zkfu3xJaIxHknf&oAQ4M7S-Sc23-hGVcIkt~1! zqr=<{b8w$4=5j48FqC7_wTR9mEYTJj(t${<(O6(Ha4QC(X>4wgVUq&0!g%Kf9}T8w zTwMPOHseZc1{3I+(R5mQBGT=9du`<`f*DlIuU>ls6 zMiC*zS&&iZ5?!0G&b4!tc`alAyOPsrj`T9aIF#e2bLsv>EQg$E_Ajh396E8sRASBK zD8eeg*A0L+bD@<0mrtvImGG9k==&oerb$VKSY>kwtYc_ye+7+sYa(%3No|>vXGL83 z5QGMnD)1^HR_e>=fCB3Up}zvQ1YiQQ&}0_*;`8!lo<}T1C0@y^pemk6$ACadHv7)m za~Cem&(BZ3c=6)W(<@J&{6vBI`t<>*pG}c7{IDernur5^L+0c)6Y5T&L3*={r^qS; z#yEN?^HufT>7M(h$=3{jp4SJM5Kj)PIryqMd>$r74}38ynClkMI@WULr{ z@W|%4h3FYq9~02s$fjg4`dr^)`s<7tz@fFk1Km18)0xBqLerKc$Cq&S(EjreemQy= z@1{%+g>IYPUsE#_GTlgO0S4e?LveFQEZ^>jal~W|v2YI%oP`7}9)J0egJRfvPIgQ` z*pIfb-3mfQ;Z-&eViB;$&I7R56R6V#H#-loL*7~a;m!4@7qaqC`MQlw!I8jdqt!Gz z?PjOZX&tocg1C)F`@pETo5qH~ZL8C2*X2^%sLR179vSV{CZb0-Zwdi6SPZg$c8jrFaKy3yFG8#e*U8}jdH9`CFv06!gm2Tn6h2ID9M?ZEPV(`jU; zqH!jIpP=~%N@yj)*r1zww|MEx8M_6uL=!cgRi!W#NFf2+BVxm z`Lu6u%J+QAW*OmRS~tZ6R|^6=3VQ;um_0)UJ)+?p2%tnYu&;>m%YDGM;Dk1 zO+q|2R!D;9%BiSOWcV401%;Kvfm9B^zbaoE0_ZbU zwi7!1k!lU%E1rh*D(DwH{j`^+BY`FTUhxzv9iFb zSCh|rdh9U$3KHA*tyW7Ba11t#unr5nNr330K(PH^Zh5N3ZM9gec2*RE@gnrf%|>AC zfLRHQ5wsvK;-G0oT96keyetV{o`dtKZy^ABFoK)K=})f+-Aqige-QNu z46H(ZFPn{~nYaNmObkZm#`Llv_w=Q1}h|&P4{mXfX(eNy+>rYrskP=TjqROG5B;S4KO7jbG=Khs|#O@pmp+$ z33f$~6^|>5#pX&Fr}LFEftS=b57Ab|1Ze;;u^1{Upt7bppJFsnnkgG`-iInY&gXBl zW+3$H?AdcH{^7DSf2w|l9?9f6oFZn3Rb~O9FkUl(k{}EtQs%43`+o|2(Ov(l*=S(0 zdrNB)L3#M9nv^Kb8o0lVijkO5TY*_O{YP^Gzk`T^cFp0fBDgO6?I~-}{ zvw3{dgp&QBb#TyZwGNKkN3G))t0K`gDF7@`y|ec1n~$Dcz<Dae2;8>n!g4n^9z1LrM*G2L1KV6f@K+8DJb(L>#|S5_8yy4cYBJ!T&1drQ z*FUUc1iiJnDb#vvduyY!vH5ttzC~5`=4PXF@7=YvJAeM}%|{Ha3I-AeM-ougcR#pYAhv?n|cP@(HJPPaN9ybo)(RA7M(;E2Sm}) zXXD9{a8j#-r+~WS!LVF#pjaX5fP5-EPL9jvu7GoRmvw~WW;cVQCdfMuWUPVxMiGg{ z8MU8PN?^zW!ch;}kx*6$AFu#uts0CVkJ1xVd2`s0z9WyI^Ig9pvfM<1ptoU%ns;?7 zjUlq*E*8Fy$OO^zjAx=+MTi#m!Yn@O-%ZzFrzitmT@Em_G~c_h=S`M z$e>BFz%e$p;!VmX71IZ_NK-PHEg@nguvI}tVfOIC)~Yu+4kQIX*pB3shOzb`ikn4f zS<;(X(bu5Nc#26` zEEPsnrRyz-sWR3%LEB!_?k!OKcb0fi0)Pbum%el#nM&vmL~}5U(rH5w7ORn%houEb z4z7fqjJk3P2XMHZHyucXc2oOo<1`u}95x#^!RScEbQ%s|Tp4B3Mo>^#KpB!O>Y;_^ zF38hUU@rhO$0&BX*a@Q{7*3=>Fx~~3vpSQ4OG`Nha0teRb0}R1#tVT_FDiZm=m6$k zIDpFB0&mB2@mwza^~VL~S|pPx@0w6#_6>pZMw8)!H|br&;Up)}DS~uPJ`p8I@ZLf; zwMO_&3F>nDyK3f9M&r0W9acbw8%gMJ7<*n!rNb%CspZZHuuP?nQ)qXHr!d&oOMo3r zJTZV`8YW-p!~nd<7*$Wh^_%m;!kj8l0*!CG;Pu*|f;M}AFF7yeRF@7U9X6ZESIedt zdf8;ZCJF;aXI1M=!izEUqzbI^%ewxh^eT^qurk|Ou79~5&YPSU2Z*$JQ@rLXx+S)-1yX^ zqYd>;*-!Ab;+qi~C`dd56R^Cza9#b>{rCo3k2qq!)hBd&UXl3L#n$)Qf%TvT^p)g}pCMK0VYrAf*ygEjaUV3Q8N&We0ukLN3?9eVj&L z=5ri5umALy(Z`_*wN(UL{mGePT+s;QH22_C{$_m@=1ZhC`YGhA@Rx$sIG{L9@mhB9 zcihi5%G*L6PwR(=r;Vn(MLPxt!KbZi{je^eh(U3^Su;+Wheq|VUaXze$!beyXIgjF zZa3LpwDIQOyYJ3}IDXsO{N(P&6FJ;&7)G;Ms~N4h{(-`(A8$cXxEL`MSzd_Ed1URNiSccFOWszuvyLzkiP# zV4=elVePm6c^@k1FYtqB-_K(94Jc58v&iUA#HN$L!RqRDSm!bhb^xPh5F8lS zDUh~+zCzXoJf?ivqQM&$#!bQ=Eb!{+?d=eB2GC>N4CFR}sPDkr;Nt{*eiY zpd%BDXh(V=oHsV^kI3~HZM_kJX9jFw**iWy6!D{eP;R0U35(wmE`!mDG(>k2Duahm zjr3rAWNQm>91*~c^gqDBdMjeT66x1;O5wT@jic;GyKn#2!8#Vffa4*#2rv%}9U$Ne zhwXys;I_=Y!sP%v-JyP$!0Wnc00yUZ(IV_}AqIM&2lMBiVFIol{Rv+lfG}eze1OWM zsVVT`D>MPS;5l;jXm*F7GO{j)EF{{QjQ^}Qr<%aox$V4!X)qxoG5h) z<3%*I1s#Kqj&4Yw9o+l&IvES?a3b>*c~@xt#d?>sY23mTTBxxN30asz3(h)hCKyA2 z1#1$Xbg=bB4Fg^Th20dNPzUPS>$*9LtZ3GkV`K-NsLh7{7$Lu-N%=s4r3`xuqXEwn zS_c={Xr2^WEX;O+l?@9^@zMAwHoro01z>~0LUL3%?lGDd;$2I@Tp*W|+qqyN=uM^q zUwdIT^1{6%R1=F}Sb*htfSFgAJ%>5gMH-fOO~|j1g z=T(}K)~4x8!rORM8yYZsMq~#z#;al8G3;HX0a)N1`B+J&d_d|o&AP#9*r4QZE`(7N zELY;w_;!;(<^U{9@F#^4@|EPe+KbA?r2GA^CQXa)q-vp6@NCvEfcNrno(|v(2Ao%j zUg4N|cG)x@>E@UGcI5}lkt&??mv2_ofux-GV(Lt?i>lme2q=PtZATK_^WBQYVNV@ zO8_{?v}YTWpt~SQyovt@LAOUvHFZ0Kd=A+5JkGu3v)|~-mvLBqmo@z4Oj}+nwt_^B!T_3xkZDNkCVX4XMh?m#v`k7C)=J{`x`$?$aQw6;-D}~?bp>-6|>@E`}}#`XdX6;Z`$>`(QY-3TDA2YXlv9kHm)^WZA_J$ z&^|rYNN7||w)R;^_-1zZ$MZNH`1X&RpK!Qc6q;PE7Ue!o+n|gIFtrl`zy+^705Enqj6Sm%LV_ z@C)Kv=C~w=b*Mu>4U(x2u6PC2wWrWQk+U_E>CO;mq1x&NLT8}17Gy;xrG<;+#omX4 zv#14rh;Zm$0b7f(TXZih_IA?*+>7}#W1vwEJjMpXiA5_M!HWXHV{+K9i5szr39G=c zpOP#;El3zV%XL9Uc|Rrq8)LvTsu)0f$4ACMjTfP5j>t9GlCbd|87J!<#}0Ue!O)S9 zM(8_=Y>k-R3|Iq?+l2}DkH7{j=W`UbD`F#8$PXyjA&pp#*0SglDYDnu{gTNVcv6>{2S=|m

7m&+RQmF6ff;%a9jVFa8V;arrGiJ*28V;b>w}5m?bpM6}$y^+2tz$qfD6k;w z$K=Jw#|Ywp3(1>9yajAY0eF1lNWfysa+CxUHeA8q0#(Z4)l_Otz7~rI;o^;l!GRG* z3GR#aue>VuVhtQtvoP`}IeSLlB(zyM`Kqf3^AMOtF;YCL189h>!wlmnL?OjO{jWg( zbo7`dg$0<9!uS?bg2M3v_QOEnF0>&{PF@JHG~sG?_UPH~U(PNc0gUf+_I$D5T~;Ts z25ii(sJ94W=UEe2iOy;4eoa%6`jAYavt9(bl@trgVuwrdvrd*(@2ou5oI-=)$_GL^ zh7PS<&YJ&+?vnAQb@z);1>4n?a44-EK77MlSxTrTvW|dlavi{)Lc<_66cF} zM%BTy<^iKIXok~hL115HX6EJk)jxC|G57fbaOW>HSc<~j0h>Y4`Z3y&JZdUpyESys zcAsoR$>7GgVXypsDfzW5KQ+xP$BSE_wR8?fF64!<|qdFT2s){e|j z39?!r!0>4jpwlOKLHc$4sCVun%?q6@< z+j#~Cym?YC)oME>!QW!lDDD`B0CBs$Q#Ps?7q?5>uMj6`7^R)YX%!_%rR`HWA2=&- z-!muB)kA2fKR@|?_vg3X_W2&4Gm7%Fv(KK~{?#kBC%?LT7wO<~Z+WS2Y;Jts`sV0^ z-M{@q{;4qukkgdGtdd}zlK3v>A$ppIDKjSv$oG7k4;coP;uL4F0!=~UMHI}#>Oc^O zpzI?GupS|GBNKaMadsjp63wq2y^ffL2n=!Se~G&OpEUD3E)QT4GFRjv4Nk(q!UF@- zWtyNN5WzNl-#ZY}tq# zxg20zK-_F8jshfi1gqgJqBIagnS}MoO|ez7loj&ZiIk1_o02V=j3cW9=A<}a7#<_R zW%(RjOHl+Z$ovL^EJ0g&P^y&7hWa+*{)j7u7!F~-LSI!hmOoSq^d&KAj--^M7e1wh z%|Pge%a2OJzyij~2&Z((=Lqvn1zZ945hnd1P+LN4JJ!B_J`xgWZgAWE;KTy1{!Nr3 zu?Pt$?VoQ?3-Shpz6#%+KZ!@USU_2UuzV#rg&}?J zVyI+05~L}S4tC8Wa-$m*I4E$8JuhU^xTm|@6-*2KcBRwoZ2$*uGk=uwb9Tdt=9Zrx zI-ptNfj~8l*E9rf2+_500BwOJOB)CJIy;>R!2;}BGaZtg!BzNh;XZr z(BoxGgWViKV+cob%rx8%K1Vsj>}8k`jJ0`;=*?%WZ9P&(u&#ymK7N+V#opZsGG`ETB~15ps!MtrK*8_C?(9n zyOg727`;e{namxi4nt7m99j*1>|>xhx>8A0t2t2bOolat(0n0vTK;-0MPiYY{Plfs z0?Wgq)jWJuhB4gn$t%^nFltu)atM9&!R1SB54S#lINEC5FGW>!A&rvuPQQa)Q+GA3#>~oKG^@6}V`}nD0z3^URjXcp zOk?gmX3DF0jH&4~u5k8@_{-T@bK$EBSXrtNn*!>}VRi~tHnCZrHkojY;a311ZhzN$ zIFwcq`)c6Y({jT0nm$mBVAa+a@QceKY=Q@0xG;jI2l(Q}^QT%0=mAv+{B9qND&PUr z5qx@JU@rk+b%vo{2qSU>dC>SR#!E-$Lo*+Xzv?*3{|4d76Gc>pIepLGKlA?%;M1qf zOe{*E<(;TJLi^Fk$f*%zRgRqA^Pc_HN0qH!vsHopf*|#*2d2Z7GkFzcJT*Ahk`;mI z_iz$DsHz*V0$wwtDSGC<1iURb7wa`hiFXBLpYApVWSc+Kgc8?|mt%PwznIN=F{DKY6ShC+rNB&NWS&|pu<=Yed%UxM=-m7ymGT~c=%eb zY%eyKZ|yf~$MyRDt->KVaBcreVYvx>Zd@uXFVay&{N3IClVZSIw|{>AC%uD5P(d#V z0sd-bXaA;IVfgwrK4C>z^zrfIYuB&ed;GV5-~R5*>7Vwh>GGhGr^&y6h${)^U&YpX z)$hw7qOJ(eL!8?8j^SIx2ur$L?1*h-!1kkyz@8Ha)zh9&HR@5k>8=wkirh6);X;!;FzLZwwg`;jf1EV<() zkl$=1DNt*B156cqOMenVuu2j304EWOB`5mgDXe?n^rhmF4Pm}nc#j02iOE8e1Kb7s zL3~rxRYCI%B~~OAU=k%_u!Qk0_yfrW-W%Ew{Pm;oD3II$$z|qbh>c0YiXn6+9xu>m z6zJMOAeO)`?tz6V(0(ImI**{of)@$%XM|WOJZA0{N*M%91tmG3mK*3Wl!H*!0K%{4 z+k>w8Acb5w1kX@0lq+0q)R?}B*$Pdjk$Gt9)XqE{v!A}o$flBesq$R446p= zQSp#&qe$Lj1=EEh0NJ9fA=D5=Nj)BZJM41t08?nE#sp|;pb@}fcWRoKgJ%x{p;-j% zVNH@9O~DSYmC`GxQ=V?Dg2~>p6Ll|M#8z6_k~#qnV4r~fk@LACOiEtnVhO#~SLG>6 z2lxtQC>M*U{`H27Mei#58NB6a)T0+yi@NY#9Zg7r%kr4A2cgi$%&Hv2(R?_(8ZPUG zuMA640=(E@X5~TE@O2nQVy2qEn?HbKNf0fe3ql`&=~e|;4b~0$jJw0bDv}vhz==E- zvvBO@6Eg;c&k4ptjA8GD2V`HaIS?un!mpB_kic@M^l1IN1ug znx4*GwtRWvvsZ2RN7p|+aWs18?jsJCX9>0( zCKI8#{s>~=#}iZ)d$>l_Kx%Dx5(LO?RhT_w34qB=$dosQxryX2RyKMfNU8oQS1{F*z*=U z!XA5gf_~t#?hS{Xv;-^RgTw2Y5CEPC+pQh;s3-sIyo$g&ZH8Xa6+Ck0oe9`n0=N7~ zrv#YSCqF&=;qV?aieqaG00W#dwYX<$$P}IN6^ANilSC5->KIdwUy&$LkRG0qb`J2t~`|kM#s2SZye*}_%C&0q&#q`*<@$JqVUdR z;il>#m+ln`JKMGGmBqtC;a)?|E$tKv z*Y+FR+x4AGg~P^cIkkW5@*#phz>DR}HkH8;wlK=Yedw)1wVMWA}*$++q z6#%$~+>YIA*WZH*`uD&7{>jhSIyo3at03%HYeR%rrgpN!(bPKQ6^khz2McD?1qSwO zsINpe*5Hf0SA$d2sd>g(L+EzctW2P^THcb_z`TpRjY%7(%MM_wFycu^=L7hLxdcRp zrMx4?%A(nX;IKr&L2cH!fa?R+1S76PBN%I)4BBub!GT*|;kUxLA(ggKj-@JwzgZi(uZ?(%xinV5azjo>Y$Xh%g$0*T8=UQnFdGZTBLHw8 z%t@uv1`3i=S(uGrMcN2Oa0!s^!z4P1_r6r0Ttoj+if?@ZwFORXFb6siO7;l?3x!UV z(PQ~^6-L~_~*$977gIgqx> z(~;b;t3qJ-f3XP;dz@Ae68gLtETgI%TViBEd-Mr!krU`}xT6d>_Hqm@7iB}A>ClT_ z$VtNjzD7B(qa&%K2q|<_s4*N!GX`oI^kUQ~=JR^AdXQh03luNRB%-QqFfSlHgCwk| zt_uF-)PdkGw!|~hVH70^C{|gNgq|WHz;}o9m4uPWaqvrGT!nfWwMBr_#MO*yTHx}x zk`q|I>SG*MrGk)+95S;q5Luh6;|$T2<|Fy?*fC@BEL3?Icnd%lbY|2gUIA39)eQdR z;i!=i#tu=KoV{xx4->O?D72{2iZThSztwVN_8|S}?E2{5^R3_grho6mx##`HFShh^ zFaBsvUApjR_xiJQZ6BQYeEs3MZ|CNY&Q>^sR_RvCeWU;uKymKvKGtkx4Vf~M) zv;S%9zQT9`2mb#-gKsF2DbZz6Cwt9Vaf~`(oix8Vs zMXTdCWt#X@pQVKY3<(*-rY!dje%DcB$>~T~0Z0L}|22JdpfC8_p%Bax_-XU$KQ!Gt zYZV_E5VrQfXWOmeGrlC_QhIybu;Y6-qN*R{=^b&xav3f=C*(=q?On(0OZ%6G)I?eZ zqSpyUkC^`w&bG&hu-e;e30P(b-P!(L=SxVoGNMm)S`|rm9mB)#EI*AIUsa&iH4z|G zQpeJXS_lV&_t6bgcw{;Ub^E!&bqP~?48m#s!N}QHiQibQ4P6(^7)Sf@ZQ?m zv$fU9Yx_B}Ed_}y*K_e{buL z7@<~Qe0S-Gzn4phZypK*HaVFuOPX{OonwMsJgA(ejNu>hZG7GNV}9!?T}7m-7b)oK zyJ_zWGL80RgaLnOw`)R&J>x-PMbH)C8s=WmqoOQ!!W0|Q4NQs#8faH$#qa;npV7A9 z75|EGY8<KVT)q-Nk1pxGX}DX05fux8an`)`Iq&7TNxudFoNH51FPi(bze*BLv) zXFEjLBmWR_(AbbXp);?v=*1M$I~tMX*W+kV$$UKn5$Zdz8M$>FU2i-}a_QDE)}(o- z4u^ZDRproVq{-lD7}NeEyhfm`fUs9kRXYngCOAFCI@m;FwQ4y`tGB)h1y;m6A>7z0 zq&F$AR&qDe3iZW`#8v&|3IG5g07*naRNT37eO;*SEUqNF8OVQjKJiB7M)V2USP@~r z(WG~fg2IRZZqf;(ok9oQ7F8>7av8tTtl0!7ql3n)v>erHU`#y18`!qazDRLE#ZXDA6qwkFiAJ#`2p2hl`790$zgV3d$~O0EZSc zXdCc|nKx@BC2L@TRp!#HhevLhb?}?)pEdg#$}1<|P#R3)hGt+b>-<|T50V6QX-wCk z@hjsI*7v1WwIP}JTG?R#=C4oOg%7{_^ZrM}r$0XL8{TY~dzzkqJa@f+bMyV-!~RE( z&8u^tUmQJrD`GakX-ipU1z=sAA2qV8%}s${Yh-;ft?Fnc#-rb3yfu%J#d)oL@Td`F z>FxQN#@VQ!jkIdi5?~pzRch2a4(07Ixy1q1K%0@Xw%^uvzsC5xVZ|x}F)^!Du2yzr zfpJ2+fK1~;ZRMvztf8R|=FhJUDHI?2Pyeamo@PzLZ^v~3+}VDt#L_Gd?7wG^y};Oz zk_0_BPEB-!tLp@svjdK3ysERi8*#&g6Wvv}Q!YwPARNOWRMOGEy-n|t$=T>U?f^d3 z`F~=p&d&Ev)w+>70pN45zHv7}j%31IkwAHeOxrKmi@rM+NGA*ys}l)%Q9?)4iP6AI zhOFSM)}`3LDP#CZ81P!Yx+5%Dus2_ws}>K6ySXdnUtTB+EzUwu3tIxo+1Dow^Zf6=dL1PDjH1Ird0&9ETG**pDwX~H^3G0K8?6Y~ zs+21PTJCQZw~n$$IXaR`d7-lTe6Ey}?yAbyQfD`@(>+A$|3AJ9_ZMkX9n`bBcYNNLdapehQ--CLJwddVv$Q(uNLe zioz6sNd3Zrz+szLV9}U(>lCqzp+%?IHt6n{W7;h!3l+A_wA9UvkwD2q4#DVKfc?O9OC71sI-Z`f z-5L;xCjVKW*hUuv1|-{bU7V~At^U=Cvs-AaoP*{Hi!iPuVYw7D0J^>L-gsQs!yLt^ z1o!RLzs#BA(>-xQIl`1QU=|Kf3)a$CNZ1Dc;CLT0sbG&u;(!e^Meg+(<+I)wFg9Tv z!3;RdINIe?;PsJ~C4d?ZXI$anpM8D4OwfmiN!V^rMp-dNU|-PZ*#=oNKHg{0sD0a^w}vziLEt z(>+-4CiP0o33<*m;6QTgszOu68>}o!S{jHPC-7Ot&JFdA-myAiz+MGoLN`nkF!_{? zgb@(cp|&Jc&zi|$6emofz1qs47A4x)nx-b!HMaozz-v@DLX}7>hTy0Z_AnKhl0(r} z(yzMZr7SWy<$W+aF&lkA23E8!A{gxLCYCa?kW3B=Fekg)l2Z#PpxFQ;iax2nU-rIg z^&y3WFbf#)6Q#Q+2bUH`l1u7bQiqUWT@oQO_$Hr{)J7!1N|16%twkzu9#MrAJ|t~q zpp~#q*Sd>HvQ&V@V+39;E{`lC&Qj~Ib`T~PX&I*7=;Rv<0_WPtpekrNjfL;Xh!F7+ zVZF0t;Uu^v8-Tv#t z!?wS0;PCpyV?&NH6{!N+x39fw(`@jWBn9LK0=?X6rcscw<9T zop3fI-`$`zAYm=O0~)@OGUEu~QtTEg*nwFIUBU2<{6|NO7@8zx_C9Y=k zLOze?CNJz~cLmM_ZL5Nx!cHeA3j&n8*{y=yC@NvSRv;_7B%oZ}dnkX(t40O=-K7s+ z7tD)&{wbN=JJo81G|MV)G#;6^viu?Ma!*L^kxrhoC4qARV8+^|D+0h+n}h>D+^Z7* zvHD`3gsqL#(@$3~mrK+{+))PnSBB8f?pR%h0>I_dg<}T%ZOkYEAh#Q;gC>hboZSc_lUZ z8G+p~wtiy{p}=)@8fI08U|G4bFOd8ZBYEp2UEpV4WEfq*Yf88yb2Hg^u16|L_!fJ6(ce!o!EI^Ta zH4R!Yw97USH~Ze6uIIg=aBtT(bU8i%)dhD7$R~wTMU-1`15)?RS z_iS$m`|Q4qD?>7L7(7OSg+z-?vl{0G(gy6xorO(ZJRIox5Y6O41chXR z#Gn_!LE^;+=HimOT$UxvepvS7{c``v-mlmD11>1`+kRUgQv3S8-tX4~8X8)K^g2k4 zkqnKqLvsjbjR5H4Av8*ml?z}Wjj2JNmFdTaGs;P(~SMG_^jl|yJN zEk|yxV({V|t5rbO=M)wUhp^o)NBBZVp|@DX6~9}E?|{{Z^8v*^m(}G{9jIzmpcO^* zRYY)BsDsnRVnSfCkmRa25{pHKUFZX@KB)>r#?(&;EQ$z)`^JW2Y54&c5*NQ6>6k#X zYMeogDO;)`6H6ZTLokiWEgA}e#2q(#Z^|QM)LhlTGkZ~?l=F|J(y4SUCP+%dZ7PQX zUJj83O2_bXj3tA@fzgO`_AIx*HS*mtx{-R$=1>nTPfDYQu!hhMFk+x>O;|L{!YRg7 z=9uo$L5LPeje&!sdoU*tjPX*yPZ<{VUl>$Fr9IX`MV8QEw*auJpLb-?7(_39dTP&h zf92}A*St(12+5SmM0PMvvtNIR2Gtor3mT#Wc4MX3An z4#rjG^t8^UeMNiG8y7&14Es<3Y#+9>DT$>e)84V?M-Q1g!V`w<8aI+If)$aEAKJIu z${+x2`Rxb4_Adoy0IW0AmX)dcCbV*=$+AVW;N`#NOjgc8%yCpVVSw z0t^0P)vOE{i5}l~UH{=xxwP7TdQkuvxsw9BENB7=e)9#4OOr?hdH9$+U;yx!`!i&_ z*#vtAbz70pHwM^lp1z66UgE4D&@LniF}MnDwKPmitsp2cP@6y!s?zy&W5+eyc7 zV2vy}lGUZi!jmAd5~#$I(J4jN!iyAf&^y1xeA4gz!A z+Tji!hF?V%mcpm`?{C4klE# zvW~C;fgA$O=UZCCm^%wHYc@18pXX^L5)7tv3kF}}u7jDCjGmMe9>JC52t5L04za;d z2(G*mcD}-kg#w?1FF53A5(0cagqj9us{ze*jZ6ZE#~Xx~`5R7be6iTI+`}YAZj~%< zBtN^g6d1#1tHwJEE*A<;%%1C6@+&aSjA+JRfd~uLWjQd8?W_f+1=4MDp$FiGWGgBP z3M12el%`&MNJU^ff;D(}V8G>e6$NIs92nlo*sv=$J?!(M_&1I?tZA1IEx<41{zyDB z-78GER}fh+xGEs*7ep3*8@m~k6Hxj4GS(Y=SxrZ@xn3Tt#b}>JSTyWK%zpOAs(3h! zo+N}nrv(0LOu(Q+7oaO&HIy>|6S=d6!b(@a2)tq`tYagufiYCGP>F1JJb7X97u-UCJg=>+N(2X zUGy?aqic3lZ~-e}tZ~)hOT`sy19ju8VMV)qSXEgGP3i@)rS_=I{boW#p34lxibgf| zic4Q`T~oOLlPrgcnQYWpe`m641KuxOIJ^juZ<=tDa*Y?CF{1G(J(*h6RA>3~j-3rBddvdGg#ql)FpZF{2JGI$ZNn zZAsRuTl#c8A?9JSnrtt)ukl<+JzMPkLTYk47s1?hmto*{!qYIHYR2m!sF&{1hL>O!zX*~dl>@KPEM$2cs;XcR?6<`+FV7lxG#_cf+P8tJlF&Lc{#ko~*@@KL z!e9U%cl3*~)ku>~D-dul^%QUU})pV?a z8|6q&2%Vi?RwRK0%PkFO|eaNH$O z8}|=Hs%dm1#pIN9uRJ{sTM|^n@pP;jhp!e|E1GxEfh3S7aNSF#G1z2|wf6vD_-_H# ztV}>xLXJ~n8hjyQPSvoqP4yTT5)M;-CR3uEA;-hqSpn8ss`i8mXzgM^d^Dbqkjffr z8G4Zc-Jy0Q;BKxb%{nC5jamQe&mk9D{%9b_xK5B4sXal6X1eOv>@4qRult#TRU!Cx zjj{k~w0|`{ba3fa-;INRzWUSky7hkl8DYxnXRcN%ClAkZ)_nPsp}rs0ePY$pg^^J+ zf7Xb}3NRM4=-(V(>aUFCubz26>Oc2vBtN@a85uQ6kt)hE%U`;91H{}4J-?%BEJ_$< zRYG^am1iIS%DbBHUw^RvTFy(%RstHb0iSPFN7C3$22A)y!2Do;UP4W*?26-#H=)R* zn9b~`ci@7iUs4}XT`iR3_?b~0N{9Dj4ow?U)3F=YC3uij{!GRT!h2#jiSmF@;sZu~ zWdM1z>Y@fZf}O6s$pO4}-vIv;xZ;SN6hMZg0X>{vd5aezzY=DQYtEbkuuhx}2Jftb z6_pRMT>1E+cX5=fh@$LS3XsXEwkTWHs}e>?m@5=uF%{7}H3I?Ve~irHXueD^<`qym zgAp|N<<4k$C%d>dtnJ_$v%}VhW?;N%?l^5~HUeR(>G_c!fb67a#xQyX!wb zjXA`B77YL!2!4mX#CIU@!<9R0cizgYLYFm#;WKu*fZ|DryKdipi&tK}b?qX>T|YT0 zf9roey>MY;3jFttsVBzIFYdp&FDw}8(aRSuK3;tK?SCd`Fz4Y~K&in~hpJp8N_{9P#3TLll1XLL{4EiyJB#d6l$ zsklM~9X@L<^)LWqKdyw4zBZ0s1=STJBAkS)Lr+Xz^vxHuR?Eu1vbq{L)N zTBa>hED!{dHehwmw5HqArbVf=08M~|bxF$FG}4kKsHv8Qb~Wqe&Yo6ah~)(bEv}*W!Xk`=$60 zh7B~=0OTmWA>+8&8UtNrcaXQyi>_GmP1Kg`Ovz9hDvYg}m82|+ajnQPg@oBbf;ebo zFxleS@XG^=xm}kd=Hag>sOMWhk2#)EdTq)s0yikY@O72YS=wQO43~ z${LLEmUQB)t9YG}g0Hd~oNhNTrD8#oX@VtV-B|INNIHkNG6 z7FryH?56ErbpN&sMClwfWTw0~78dU%eG=%Uh@mrP^ta&wkF&c!2vXS)bU9Z5FGLrj zY`2WrRv@rp1#(na9qwEUJ8rD;^BS{f%+1sik_2scBj_qz*;{GIc#B6Fbun~iDj$K% z86vSdpF>CBPcpP%#0P@V*fC-NBEE}3dJ4alpQ>qX8~Ga*N z{mmG%0{(y+2$g+>yTq^3!DeJ&S+J-yg3O96E_(r zv_4Ltf!&&9_8d2I%SKXNKE51JoW`1Ux-LN?Rx|@^{PmTts~hgj40kbcugv@Vh`O z;lh4rsj_<+j`lAY2ktK;`$`6;e$b(@p)Vy!44aAAD6o126XrfDJ0g8!;oQi%97Tk% z<^B0GMMwo%o|!!x8#b8D_22C$3fgrME2)yLBZ#;vnhJOOHJP^4$zwZ;lyp93yV0DN z{On2+&Sv&)q4+MHxi|FkORHXj^S8+By^8gEDsNPpunTzh;+uE1;9_xm&%T%Ue1CK2 zz|1dOKDbxhI=JM<(^1dwT#P#Bl}nqPPC1U7nodd96e+O-L`;kpy@G}5sI1IhIO7;6 z-Ky`X*Y{fu*&iL7cE{zy8kGY}erR0Ke{9}r^LVfFo?Q*_u;94ul)P6bT@Ax-H}Jzq zAl{0rf3h_h#|ORK>^#r*pNQ4E0O_l(q@UaSdVo4kMWJG{TJwMFdfr3ZHaB8M!Ug@C-9hoSPiO?Z|Lw$BTJ5b5Zv&Kf-v2#;8CT?yddnCvO!dkYd9W}+ zR{{8&cfWTMxAA`s+TS~WZFlT^>;C=kD!_QKZew${hYQwatCE`va&3UDB#ytnj|Oa? z$Ug6n58Jo)^`9wYfcCz9=jof*zxcxN_w8HvB?DhK1pe*qPtKpe@uz?O@AY^8G2A7q zcgp>ONIUO=(z@`L6|ZVRcB?T%YWqn=-OM_reumL#H8w2O^I2X^gnm|mLsLX4_%?i~ zyY$J0Y8VW|YeOsmhiWDI86AG+N`HafXX;C`=iznPpqnPB9;C^E-QrrIwXfux!pMx* zS`CB~L`~M#WNA5^(j2pwTMSo_s*`x|U0 zVSi>jX)sM4a5r^?2C3a)bm16T8!>i`9vHql=;cFrE{vJ_gdknO##bwvL$9R)+jfb& z9VBbml|i!R&p~Ox#&R=Qvw{Y=;owKWbVqweSCvYpfuLyhB{g)a?Key}Lnfoz-wcN6 zF!)>{fCC#=<`;H;?{kgv2l$(ifL;Cu0WFd+0NshH5YuROkkEuT?Dz(%uYs{KTKrb5 zDv1Zz>&>UQNe!S?5ghP`z*>V|zdiL3$A*Y%dL}k3jx^hHcmT3GD#S8 zB6pXMX)DBw#cI;yL}WHcYeAx{0(%#EWyEnl*AF``A5#?}v}!Q?*_oxy zgPHM%4-eFiug*mbfEORlT$($YJFz3*)x|USjt)IJG`pz%-m^#D+_}1agu9BQ=S<5c zRM)@f$yQ6l&{^#hEqXPBdec>E*Y~W>1h4bRE>Un871&!rDt7PN-n{tL=GLB{M4Aq~ zy7OdD2%%TmR&LE`T8>kVo_ngtodY`MK3qw83a?J!lX0ofUYhTU8$*+;;8|TIjjHxn zz}usDT}}Y*(jdC)No9O#C%=GN>)alcF73Zg(;2_Q0an>$-ycj5WDpxO~y3*GLJK@VWS( zYYu>SN5rDOH@?GFdAW1@&Yh=E#Z=i8f}!G9#G-NR)NtqYCp;niq%v@8Z_A(@;f(?VVSjult{xu5C)!mNvTvD5{hrOueP*q zeAig-I?G80&V3lOI0W35)|og{!N6sZb|kc417>-yK->X>u`p`r*WIUV=nIq;#zcJWbayOk*X;v?!q!;KYbT`f_o}g3BfsLlN|>bfh*AcUEH41i zss$#|s(}c~_O%OkuW&4!M&>mLUh4=G&|w%}LFdhofyHak^D&2mm3Clu&2X6XW}>P( z!=z(5Yjn7?p%PTcWapX@UVCJwqagz_Gg>B;gW6w;kvbYW!kr4;=*W;kS>ae%O@y7; zph=+wge%Wcmqj74Pk+3zbT;MlO-%Vh%DX{4vXNgzVK18!61>dRE-))iZ8={DAm?X|3dc|9ZNIA`d)pd{#g zIgxk__9o};7~KuY+~wJP{;o^1Px4jp^-*y>^q2E09Uac=JBp})v;b@R-l#j`tyTIbGI)nC`+EA@BL z+xA_2rDfCLcJtV4t6L}fT)CijkcvfhD@eMh);aDCL3 z%sIL%`fC>kkWuabj)??!br}$kb@jl289@)9Jn41)I^lQtWHkvIdz6<;2@n1uD8189 zWLv<{7Vn^=w((?hQb8QREEAx3z|c7ma9Nar*4Aak!8JGMwqKCod&C)`cUO^){GY0G z|7r8S!gy_L$C%2)fTIY82R5}av%N^AgqVwH9VzXq#MY`*ENLTn=>4DU8| zN7E0fBb+o^=i>7HV(EUVxO`YD;XQ&-mzHO76d&SKB0{5BJd|e_WRGyxhmdorWqX1nHO z*)qCPM(bryB9+cQU$=QTe9vvP05gKtl3)Tklm6sLQF`twHi{1 z0@}0?68Vf>I9NN4$ZA?A(F~s1;JT*p`?^*tTtV$%!1zl~!=nm*3V%_BPN!Xugf_d@ zAiH^C%7j;GCI@QiH4>*AH0cWTBnG;nZtaZL{N_ynmQrN~*ZF*&1WK}>T`pF{v<@m0 z7UsJ~@T7uogJx68p#shM{A)h!M^t9{v~R&p4wlEQ7IB4J2(X~4S4$SMS^+HA)nzJ) zCXeG=53wC~bkMkz*!fzEUslC(H|8TO!M%*7%h(GW`s-KOi5!APg?v73X7CSsSb_Qd z&DEbPREPZPn+$0Mk{mh+Pw1nzp-(%Icqq~wDwC^-dXff(6|?M(^b9g^W)M9RB9pR5 z-M=G)Bb`(dqRJu=Iz}_n#L1Hp%)f$J6Oog0uQ1BkZv~0J5acE4u~YjPGy%F3hZ39F zu?fwn97BYK52#}-W)desRrMT=B7mlaP`)Pt;|Wr`Rrv{*5v!E$g+ zXWH!@s(+^If%NHAJAbJlagXsF2@H?%_8`Trkse{q6D+2CXfvjdA=Wb?5B8`JShK23 znIO~X;XA({`lz|)&D~t=%KL3?RYN};9&SJX&G_(FL$}6`U- z!^fGDCcBvtvjxhz^zdbQmR#=E`R!o=;G@jvW3p=!Bwy*9k7QT`QG%#O@2mi;bLQy9 z%jcd_;q$m=Bbt6()BN;=QYyi z+l|)m-njMkKz(;xTbmKpfU-@7`F3}Mvj%l_>}H=vmKv!)98 zW1U88`s7)&9>$hrrBuElAiNt3X?l!&_6gn&YS}Liq+WR=>GYea4k9h|4}Nr6^2Ssn zDdotCXP2x6u#(>kM;2hqePqQ!YbfOfqslsc`mXJrcP@|KB~+2NW3$=rQpb_1jOv#V zHV-gwRV*=sfoRm4I-@m`|K6Nd(WedTL#*~fqbOey-dDGdC&hxlB}7=bk07c#EJiT( zC8k{vc;P@eaIr9{O!arae(%Q&a_?)@@6tnTAM>1 zzHYDf6auG?Ox8qZWymJPQ^ZsnibT+rJkIk_^oz=hA+=^@L6hya4O`OYeXcRm^1R*_ zD0R|-9?Q3$Rp}KDBmvy4SB20m2&GBj@Co;g3&8fT`y9e(9dSnzs!JReyjNJVz^o6> zOIHJt&;6}QJs=U3+wqn#q}S3q)0HHYI2;bP63)TYInfW-MTtdYgC=DKNahIAmZZDk zz%)Rsd>B^|1r4=eG*>IZ=_#ST)2%L!W@pUN!Jw*_U29IK zLC=-7x@m1lqI@BU*GM4Rg-Z$R?zC&|k+v|bRRE&3b?QqB1jubh=Uh>R>I%fJ3*@U@ z1W4vp0qv@-Qa$t;k~u)=Jn@qaN`ucJzQR_VudI~YCNrANFlm+Si3z?uLr_Ou!)tb* z+X|z!3Fq}`?uJiUt_L}u+nu4=sLah?!|mCysl>pODZ?TxK&2jyrSzfKDAhrJbkzsk%7py91_Qga7fy(}7X9RarZ*^Z^=yP_yFyO)7 zX3kOMb2Nu~&_0(7{gsnjZ!@L8A@V5w#zn4IJ7Ms)^UD&_r@=u+!*>Z09#gEI6Dld++&lmFlU%O;>4}Y;ps@34jX!7d ztyB`tr#g$Y%!s>|G=rllYKna==aHT@>(d(R-1gzmFGiye&)rKu`S8;p{NzUZPW4~j zuj<&P^r*g3h0hAK?D)D&97ne`gl_s_cOyPv0pQAWzX?57-SZn~4GGqTuk~@tasnUw zk}j!Rc=x2dN2G!<)JOP+XK+vp2;~K9;;zv1`B%O#j9UZKTV^v@atsTj#H zdU0#^U}0IapyvzEUtas*EsQ+>=9vp6f+AOMmjp6z{%vmm>gwzku)Tk^FuOQ2_vOsy z)!PE>bAr2{6c!e*FJ7NHoL`-t1Fo4r&&u=eD6s$I<+az}l2^sQ9_$rpC}vx|N^Nmr zRW1dgz1%i8_BQ_@4EXP_pK2tR1!K7m;+u>zPu{?!O=*X59hnveka%EeV4%s=Flb#c zAs%LXy!6!|t#IaoxrFcy67xx=vTv06G!|0MpFTAS+cFz+o%K9-P&)^(YS$n+3|YZz zA+1cTwOm2dJy`GhR6V`n*znH~ByXyLHB zlag|D3-f7Qz{Ef&!bu~GHbqE`n3MQ}`5IR3l|!(2Jt0`zA`DkO!P<$$by7#rLUF_K zU`wJU7!Q9hP>ueopA<^LUSY%G>FIDhATXS$ZRrodiv@&PAGZdGqofj;h^*RHLa|m* zJjba4CZsaZS`i12S2X;2Dp;ZFtcrl@wSq3e;Xp;4PQqHDz=)%v!@+ z&$gkCBsU!kY%_dr56K*KG1%QgbL}KPYy2dclTOX2WZ3NVm#IZb)z0eh?M3cfZ9+Jl zAx)e2gnG3ZRZcoAf(3fngH=1roqZuWP4&{w2i}qNLy&jO3#d@R%n~XYPjSk#hvFkjdvvw8KKga z-Px@{>Nj*YhkQAdfjcQ(1WhEtM5iKKym&6&vLE(?x!?A`?DahFPrag)em>MMSb09r z>-Btj?t$i1s4U#U-uQEQqF`<+F5Gs+6L+L0;wU^4bn-?VV|4ryk|Sf!{Q}2G!HNL9 z;^4S(7A!DoBa2Ap1a!!F7~y6%P7dmigpo+;XUKCH(457HI-5WpVTMh>nQX?-w%?vi zA_I%CKP*QOM(LOL8Ne{$S%_~ogI|nE9i+qXDER@v2)shpmcyacUXdP_9zk>UoD=YD z+|O$X=(6Gyk*xg9vY1sn#vG~f?a@&+ey)}Z5|6icRs>b&ceZkU+dV>lA6=Nw<(_su z5@!4I)bD@Md;aCU-Y2>A*4JZct-Cj;mH7Hp{-h$seR~CfLk+tgrIVo(;~^g{!qr+M zmFrv$*WfM3U@I+9gDYEphVu5}`~AH0ob5))x7AhOm%e=R-u4G(tI(0l4PUB9g;kMEo| zgofLDH9u4_YEn!p)^S8H9U))F4B))8U|eYh&lTJcz*9+Znn z3LPw}8VO1VyPoQ39F-R_`hev>h$S^^#9Z3WdWOi8v-|dG+h0|7q-uW;9!ClA@iqdl zCc-+dL|AQG)~=&_GAsNl5IlWqor?yfX5U;|xso`Q#<~~T#u|_ysgqNAVZ*~(kCH-b zAfLR0nD?mK7ga%2uIz5>`CfWC{k`O-<-X z5`YEz!fphIa03!1SwSfD7xfBq8gu13W<%drB$k0#0-R_mVm`-#ph;lY#M~^w>lOi4 z6-$pOOuk2oQC)qs~ z`z#ZnQyyUrBX(~ibDmumj~70q6wF3YLkl^Mq+DYo7H`}ooHvD;vw${a&vB1;M7XZS zGvbOvEbW;UB8(=&$VeQ83j(nZgz&r z;_q?zY0wP|^%QpcK(I2S0wy_wX7>?p8K!FBK8su|rdcHzISGGo;%0(l>(87>{|&zepPueZr)CBcWx!qmGOI{O46)Ct+Xx$&Y^+Bq0?O} z>2R-cG?yIJ|7k}cc3zV|Q{{{$FD*vel2Jy~F$XC@h`m-Pv_*<)hO+ zcja+%^w_bjtsAy)qCYF4V=)!^tRR;^Ef0k~8a%K55X#+3Nh6@aYLC6@&zXE+v~o?f_H z1kRSuly4Q$dyxNP6C@ZIOuf`y1ZI?`Hs0p0f8Pq&dp8b3Tt?B+>LQlF3+v_0{IUQm zz*UGV(RC4MdQ_3u{8WCbYYKRZXBG;$n*#kU5ZJ-2W4;%!H#SIo^Iaso?{CX;e0llr z%lDV>-+%q~odED355{7+9s%Qzp*qT^Iu?9dG`5dl1D~2lM+w2&Ri4T;Y1ZWRAjpp` zwN|=C>g)Av0EP@&U$ZnseGSSObo$yQ9iSC#7hSJ<^PPTJjTlsEu*&z@K{;t&>aXdy z_Um-W*nljD0NafTG}4}dw?hWxVL_kOj|v71p@$Ha1>G|qz`VrZ4xOQX=nYb!kyi-~ zmKD0JZgvREqZ$~2tpsJmpuj8&fejsl467V81Ud%M!ax?x$PI{}(Yp}nuJ6Ej8sS*o zL1DhmZ#x)*1qF04Fc=i}ix6mGzyiXZ?Fe`77HA%H27*p1qdNh_LCCU@Lx~>(tpTij zO-QK(lqwe7iNFoKZ)uW~!2phHYAX|>ut1ZWuorGY{VzbZX;Sd`LW{Ej#lh%BsuL_V zVPD)J)Yr)fjV7jH(dk>)bfC%9V!BY*(6Ybb!sPA!V7^FrMnp6R)(F6AAlJQsrX=(y z!SPF7)qdn%$vLHWhTM5C48tZI*srA1NWj7h8OfG=;Q&4WixO^f{DUQ()ojHwUoS6- zAuIDq5tSyFT3GlZn?na>mBL@r;eO_9K>duIN}Q~%)itt^ka^I!fG0Ln>^xv(Kd`#l zaT=;Ex%$^rih_PZu6nTmmTy273Pe*WJN2M0?#37ioszc^yU<|a6-a;v?e!p51BFKj zp7hRoK#@Im7Z`BdGUD~P#t=sdp6ilBo>`B;YuxTgVK(iFQ#mb+76}~@#%n+eO{-C2 z?7Zd<&6rb3&-986vvUEK8s+QtVQJZ{rS(D{4ZTs6<`Kn& z-O>5;zsp74mj!^22B`H7ojTDMt(*^r6zXE#+p6Vnyx#&VAa0Gdw&sKif7$xtwCzS? z<>#R1Dg)lfG%TX7Cd1-rT9ajMc^U^?jV^hCyI}u?;|MaW5f_~R@|tJ0$bgs3SPh^p zwWP}O%6IJis!g>pRDHfxHvB#v`r!MmaGOHuO3jfYdom#{`3k7vQ)*uFwYg?3mxIyQ z$`4KaB{C0dt|PZf@WgxAV&$uu6aX$vV^Dmxd@hgu?!}9*rq8VvFBJt?OJ8gX-Mw_> zV)@MUOcCbaVyRTd9J+XGwX}*k@vXbXSI^dGggUP+=BK9$i*Fx(_5Fu2`O~~(6lI=s zV!_l>-d4!Nm?UTlq%II(aYNhSG^|Eb?;rCNK1;Z-JX4;(`1XI-fB8`U#{XyPT7R3o z&nUh{zO-%}V=H|Vo5Uu5oz%99a7nNoV_~Gytt4(YHd?J(EJyQL=tx`?tjJr1gfaz{ zk~AS%m{cw!A_#?M61N3Ph8Psu2t`V?PwV)=KeFeX-|K7+3cg1;#^*iHb1wIvFWk8^ zKQAaNr@t=Txbav{ub#hp{_NSa#b@`{*4Eb7*Eha@Sv@g6{${Is|Iq2HEWVxn3Q#AN z37C}>N-&O*3FifqObl0zN!gvs=@z&Zvk2GaC#c|X3Ay?5`3M!OywqSbgDU=H4A|j>DK-3f|FQ6Bi zX|xfR@HuV;=$g&eQi-`+LU0MeB)>(9pyeqzamJ1pcw6MESAZ7#U+jpv`z;pH9gJ9x z1oArQ42~n81Kmd$Gj}0{ayIc#lqAVzYga0f6e1j9S>bdtC=?k%SMg*Q$Ib%I&|4uM zIwXa=^$b%YfVAzn;>=18bn#R69&gH5yJ@#*O4p8JW4QLHXpf0TU?BN zmWOn=F{*=6lN?2JFpU8;akZ(tX|x*^Np0O%+eQUjA!`=wJcB2~$ZysmCtP;hU0c}IIpq&Mm9HP*5WX9Cl z!s9$vA(;WNPP-3cEvITGl8-+X9-)>(%9!Stie8p z)O#sV0Urhud!fN{L=jpb$Xq6KxTg<9k*Gnvv*7U&SdPk3hc7yi37-?_4VTO4TbMXE zBs>@q(dArJP!wC=iU4!QuL}oW%;@WkqOi^qfk1RJx{E8l&O7 zUl151R*#cNLT`@?t;OSkrW9e(qBI;E z9?q*gO9o*Hq^A8;cjYrZJ}dMk z{Xf~hfB6{6ZM{+-%paIN|6|KiCtP zdVhK_i>+_AZU+YQ-I*l|Zq2rm0=H6{)h?G;es$oq{mMaO`CCuh*ivM59B$q!BkW*_ zAQ!{SI-^t_ls)KCZ`8>^4vc!j@+NmWpo4~r!RxR&b$MT-G8p~XP(@^J9qcd$&m9I5 z?^WAg=&|13y9L6i2R4GSt`rXJ|M-h3(lnzHibp2dom)eJUSlrZkMyTr_6~NcOyjH? z;Rou6E__{aj5G2BHn%6g`u5vDU;53`mtP8@{lh;5WY2ys5d8VlnWeLLzq)(&?xmTT z%RI47fySbFY+~tGx;8HmE38!TR)F%me~tePB}B(I=f}>BDR@1j&=r9E$N!#LroH#MQt5vDw=^7U#%?8x2mj@}m7)!&QG?|^Or&Gc+ z&H5zrUq-ed)JtB^+ZiMSnm9RhTJ7cn0u?A{^&oW;b7_;?Qn1iaWVgAkb4W<4^DzJb zAOJ~3K~#-&m*mD0D6SjxYvx3IFkmKH+wDkvh9=8x_ShNWAppt@EZ}L$UGi9GNqNog zC)PQ)XU<)UkP}-yN>GhqG#VN_vngw-h~P<>lmOk3V?hIrD^Us@NqOM@m*T9lP z2+MLM}30GPWsTwsVZUB=tUW>j4^ev!{0f5}V{AiWH zVZ=_3x?m4x2uEYnHw{_?oJtrdw|pemcOw~^DU>K<=pKa@3pS%}h_1RDpuTE?6dI2P z7e;aiS_$RmhHXxG)k-F(9F*CSh4qj=G{7rN;BwUFVJR@~20@h_y-5}m_P>@nGsn** zr_JQG*u99TWJaY^g=0Z}rD8XZAPCxfgu^yLUK{{q=U{vX;slPixZ1LU-T2^Dls9)s3Oe7R9>b0l|fMg&l2v2X%mVe z=ebACpRu;hsLBP5n;CwUrYRUXS!&-aXBKO% zA>X3{pXC4`m+w(zo8i=c;pm{qSOT*pDFe_(z-FGSZtpMd8}et>W5h_Sx87=P?`;pL zEi3_;8s|N95vjH#6%tv`wCb-H4=QaHlbuzC;GU`e3-@n7xOM7w=SbhF#!uUBso>^g zYPH)>4YP6{sfu6bI4icRay2LrGN#b|Bg=a_16Q_NR+*ql^NrJiuea|WzOb`*kxKc=-sPMZ z)0+WMUWX0!T}Q%Y99G&`%Ybus)CA+dgd==T{yRjG5v>k9V}JX^5Lk6I|33|`M`9gf zG9}l)#+AAT`~S0k(PMLGwW37xGM_$XWOq@sE%rURn~6ab-+QN?xi_Gb;5 zxf(F6Q95<;?AgCuo>_w0`O;-U+dCJRE-uV3&CCe4aubWO?`}?gL1V|T?LB#tuxb$3 zGyEDO1K#mYR^Ah*7RCUsAhM7#kEw6i-C|{XlFM2=@662m7#uHrCWQ9JjT^6Cy?Xq7 z_Suss-{G{j{=@p_=H|wO4N%&>@-J_HdcEW6uGM|7tyWj7)#~bam0#m>zWUzk>S}ez zjvf1U?RazFpy;hEyg(IK$ji`96F3-$;yZ~GO zMUO{Fw>c$G5HShLx>>p)7%P|H2nIbyFA|Cu1cBX@Ko^k;ok(>F4=yIUVE&y&?JqsR z#YiZ^MnXYn$e@vpB}_OZS9B$`2*Wo(mlM;|SoKB{T7m;;lohg}0Rhm7AWcb{3+vy6 zavQ~w|15kLl}8vf3l=BiO|>Mmu+W4QLe3<#R6#h8g0)dCgaBv?qiZe}EeKXOHPnOw zpO-tdv|!ZC9Wft)l&kY0n32#2JgQMrP2n@LHLeP#vJJSYMn@8uFJmf!wk=RjkD}`r zkyb1uY@+>_gJl?$a6<4^-HId(xCzA#kY2$Jd=)X#AAte0f|9W;aE4=C;q*Y-Y=%Lc zz0&Rin;1~?fv{(kA;EVf?>3>vW|hTJU_zF~YheMBvw%hh3)_&8!{PPu5;nv(hCn;m z2}2Dus>tC2R(dRYGZ2Rxr9M=suY;55Fru!Yw({vdoi^Tb6e$}vUH1zA4c`lgedRLX zIXWP~8Wuc`h6ivLzh3s`^r2iC92i&Y`p{4=nu`fM6KOMf%%ICTp~e+|*^j;j{K@DO zdANaNdPRX8ZNhN=^hA5oxkaM_p$7xud_Jd^x7hg(bM335uZ##RVsV<)z?d@&!X8H^ zWe+9I!>}bGbdp6$FdXGUnbQdNKnaq7JuJlOiA?@Djt2a&|4z_1Tw(4NX3pFk)1Cwo zcPvwh4aE>B;u8j}5Ven7w-1*NkKROf>$4XtMar{T26qy*}SE5ou{FDtz;OeP8eQ>tUd^6)GgvU!d)Ar)c11 zY$OnLYFzPOx7N!G6rM_#i+bf1U0qYK7;)(AR`HU-a%C^%Ry6Ut%XkaBOWHl|X2v8x z3Eq0wf2-@0U6;SvxAbR>L?7;pq*eN}3QsI5$0bI8Y4xByR8$#?K%JO2d=^Yis|B3^ z@O)G3lie5H;}?#+_s6et^MCp4fm8dsmz4{N`e!0BZ-n}uWd1YXkOSQWN!G&?o&Pk> zmum(!tI@9{xL5ICU)Dz*7QtDb`D!}vXQ4Rii5i+rToz=MO zIYna?o7E=9>fXo1*pL6FxU2j+@M!f?s#X53@vm0|VzHyW{{D5L%Ac;Rtl;-&Yj*@; ze-Vs*^7zsBn~yd(e-cLfoNV^>#?NoI-n@GG^5u)|v~#t0-C0`S4^TaO76)}ITXcJy zd_PnjI@EtCRYG1#ug{lt4!8!g+2O<4*7)#M*VU%0u2uw{HL2i@U@=bZJTKyMUKI`w zp<0}&C2FdY<_efA5YC}BqZ_yFF}jxS`%x%|h$?`tUN2-9_8`Pa>N4QKP)dQZkntds z1AG~`a>s(=BXA!Z#jwJOZORv{H_)C04-!p8JX>dk|3Yas21v$(cD~!_OybPiM&LHs zb%rtQjiIt)cBQ~DjKKz!Eg%9@K3&8D*v_3WlPLu*)!rAy3(#oM3ydy?QG{VZb;Xb1 z!Wb_L-iAV>)I@hg!caUjkg{V`sB8xmS?$&q451qsN7)eOMpzKGgVhVo9pO6oe#7mw z{D#9|#m(nIhpiud1o*{N87pD1TY$2asaIhvfaR^dt^uNF)wdvzS1zd7XDdn>Abv&= zblsPbJj>_RkXLE9U=*(oe!TQHnRjqoKks$DVecX#iyn<{i;8NF?6 ziRhbwHb8~70Fi;WaFs);r#Bh7_thCI0Kz6c2hchwuLOdrwlX1S&!RD06Uzr7f;P(C z3I_+wgkVdJ+4#Ni-U{RpI7VnsszFweiCbVtz6OCC7Kg)Q8N&2=uBK+rJZJRJ)d+JK z$>*`YE>5JClwQxZ3pVQOk@9FWwk0j3*c&Pw065^~qA3Wgh_qZ|>k?T(Np1pMD z($>btvyH7=aw^*%Ufn*JDwTK|OO+1oFO^E5TEotP!@~pKv=Ti}slEj4ZOfkCpjNIh z9_-p_3{<|}ph|EqcM1mSdC4h9@3@+bYSq0e;!2TRue+<`z0={&Q_BzcnS$VD4|Z2D zn>gsz7ImDC7Bw=LQ#r;k(hxd|-g2h1TX7coF#m@=^32_LF3N)s>UZs#pFeskA36HF z3q`1|kaVR=kg)U(Vi4VgakMKJ_X2#IVmzH8@zN#btAnbGc>TZ}&{h=eW&H=e)nhP{zC}fP^(ZF}JEAQ~_9M;NzZCewJQs z>&dbP6<#8jWIrJbno_5?-gd^uWr_pZzt3s(&2K-wv$FPd z^-St8Vo$anJ%04R$D5l^6~aEhdru&Cxwu+?@Ee)q@Lq}4=o-eVJs!NDa8&3(SC*EbWW_mC zPLl>CDcHEaL%lj6nYw11-pu!cBWqmaI=@r2CEU$v)BME@Jc6> zebiuEtgxwAEW}hIn*&;AoqchP;Yv1L1Ym5inG8zij92Qh-8G=6FoMizsH0m(Z74hv zOa|`SBlb|lK<5!Ukw9MUm^WkFjEJm|A%rDy3oJ>%S_2(Nup)&!kWm>%MInUEVGN<0 z!Gi(3&F#SI_7>z}v8^z?Ab*1S8)5b>K#_$UN^E+Y!@_pYhr$b$VJpPa&2_+RWMwsD zm|eMmMQ;O=uz0>#dD@A%n)Uc&`$`X9(AAN#TNom0v&i)tuHfVt;d)nJVay;c z4H%rs=u8ehH1#aJ)GWVX#71^A=$X|)8jLIs;kls6$bCjw7Q-l!!XdYOS5cHE^q~p~ z#wglcfypx?IZ(aeU@PGex=~^H%|l8`_eM<~Gitv%K_K>z$a7IFfQLM{{dque!jtgi z{nKWD)I-MWzwP&r6lw#3LLm^%M+-=!6grIV!Rgyq5`pPNf|4eG^t&rUgh6|!scR}E zr#WF}RuuKX%xcJ7Fm>nu#=OBgH9?6OwKD{j4?Cb5zW!Z;H#+cP=?Vp?E2;rZa9kYBETk56d|tn@&C|CuvS*Zy^rLKV#Po(R=|Hs$%VXRlwsncotA z@nUs7wf@8Yv%Yj$!Ynt32M;=X2f!y>jI8jg6)zpW<6aJ&$&7=!bS|w$H!IZ@?fc@F>Dc9sY2xSDN&bffZ#Dkw!YvTm z)%u?gJ1Mzch>HF{>$3h6FIQt$ilI;dHLz{d-pIZ-gtHCOlp|w z?3ddwx3lZ(t4`lBf!O`);IRU>CAsZSrGC?&8XP>dj{oWU!CvPW6Q zY4s}IV$d(giyCE*BT7^0skrD+R~{<8`GxYTvHv%wt}x?vY-2CBnd^_nf_%71?AX4>cp&m&9Q!84Yyz!dPf^-bYE(yY z6_sRll2s|HBBV()g;6QC!iS2qRYF89O4U(mpb}6cYs^IyRY;)zG|CVBBYVzyZi+E> z?zMwZeDj|7JkNQ~$uJ!l0GwGzDj`iaAcWp8FzRJA61Z~TKnB5seGzD@1gRq#D4uZ$ z@{4?=zWrV=(Rc-Aq;4lj&3AlY&ehtb`2d4t|dYydA) zO0A~Q0?agq#vqeGX{1N{!Wan-c0eoLv#eHF{th6tU~&*y41jn+TNm>gAc$UG_M=Me z9}fD55fAJi_ER%GeBIyq8=tLghY7fY&5HmWIP3ujxGq9~+k6gWOwT9-MzvWW+2;{P z3vIOB>2dlTGYAT1{sI8G%>(-@no_C-v*zZl7GEA&0!RqRLPj z6wrFI9o@1@0?jg~yS);^1hC?BViHQy5Ge3kGMcQcCBo6!2mE)$_j(e)#e6lSNHY0OvLKsdDA? z>Z*|C?Y-LvUmG7kF^(Gc)UkcX_H}i!mP=m@7KrDS=2q$BTqQ5FOq&Iu>qO%c7XOlA zxogDc8(Twi@>+v2f4_Lt6GL)VYijk?R&+!5a`i5JQfjRb3WxY?|*!{y0>K z{o}|TP95EOWu)<^*Bi0IXNPXF{=5^t06A7~S8vP$;{uUaPEZZqd*_`)pN6h7b787~ zr|vAox8IuoReug^LJ2T|Q&V@t?C;8T>m>XlWC0UNvX7+dS*~MvWL4w{imXZ~D! z3qu@9@g6i+JBfrk^?O1sHxPpKGM~Z9V!)TzQiqPb^;tt%EW;L{+O-lI3#drPjGb)? z_+LSFT55=;Hl5&vu;Z+N+e}(&4GW!NCi?$K>bV+l!6>J{N>japtGDTT_d>e=US`Qv}srU>VW)gOhd&4xHz#pMC?Be1wT!MU*3lW*`pQ>AOFed*0|t_;F$O$PFqgIH2$nnp z*hTSq2L6;bm|Egr5VW>=Y?rO529R5nqir^NK-;J7(02s_Ia*CaOe@IRhN?2ibdDpx zKDt{X#vxGl@f0a>ZdV|V8KldcGZGxmK#?UJSYTMt7lXgTcymxRU(V(B$9-t`q86RX z+|OhLfQ9>JQlPylbbV8tM1mKzK=C?42_u*SPGL9+_$-jz5eMsK6!; znTCW%xnJ)Y)&wP&7M;OxF}Wo0JnTY_k_);k%p?JUQLy$yhUFCiw$C^M_A(j`@Pf8` zWcNfH%7D$$hMk*_;g%S0Bh6(tgTOI(tj?IMWMx6z}lFc3ul++(#+SzU=bK`4bSl6DAs_q3j{vOr@}?lmw}Av0*4pU zI(0-F=-Nmv%siwbxbO%~p^FR$hG+{=T!hF9Y+6T%m$K?FO)@R$zreaRdd>j%ba5oF z!M|xlN2GO&AiO!fBwK^IVi5)NF;HPzj=YIz1xy<1*o5} zU8jHlu2LE6nL?P&hUOO0TGHG;z53zFr%;&668qCn&r!j?vFAXu)!e(X0y3_ zbab@EguaQvL4jqKn@jB2G7^xQDwVfLC|1)$wG-B4;$kom= zcrL|W<_MDdVx|=xIi=^!8qB`>&+f)Mr>-{6UNvLi{PxqUfB2vgGipcfysP3XYYtc^ zfO)@w5n%Lx3-9)J5s7cTb?9&3qXd0;YC`dK!t#Q~NYa!Q3~V)k)gT%w=rsMFk>xdu zD?c>3=1#zBrrlYACM!fprtgMa_sNhGI>QPJ(TQl{+bMK+4_oO+8p2@BAc6kwvD~jt z=xaQ>IeqA;0C2aZfUZ^xhDoatmKtcXSf|1l0Z4{|QWbulV2h@e3T0@Eog+5XM;o_B z9#HM{!w9s+PoK(X50Djvz1xrrV5srz=RK{7{#L8mBzrx+{Tk#>*rFYjt77-=y`y^% z9vIg>1OCrYt-Xh;ZNcp7?b=7PF@f3G&nAUWb(5JH%tSs2+t;0=`ka4!aaYI!;1;?hkAEjX*)s$J#|qfW2ug1UoK6VCi(walg=wy8z?Dt0k) zrdq;*#w1s(mUCFF+p^568(+H}S17=mVV@T>nr#7=5!=epu9kPr*y*e<)WwFP@(dD! z1Lc4{fB{d)t>7VP)AS?QYCv!WphcrN=Yy~d5Pb!C!sz(s(C9?~u+Q!RL1wxVG|}?C zkW=%HoI)EXh3(V3kb5LF7rxNDAi5F+hTuxjnEhR(AH{R=Kq@dJ=nL^xZaN-_=Q4pl z_&`s~5zL@dnacp)cqV>7mAg+h7D~{36r`OV;8RLS?=(3vQdbveTG096J};$Mk#$TN4Fm^RfmTcCAi{tF%`0TN9r6yr zQsAqX_g71P--Wsu& z5@_MFm>{YxEC}}2iVMZsc^X{-e1WZDelKAdAq=pmTnGbZi)yuzUtoP2+Gi-TA)7`R z1HP8Wuke4%Q=OF-3>Y44HH876`|{&6pWt@p%ts%6 zOvt5h29Jbe)vRs|X$cy7DZ?CXuC6}(&xY`zi(g*6{l&({xy{XgJ-~b=n|M#qz`OR# z$!9liG;g%98gI+PF+gRB23BT2f^(1UdvDMrtU=CKtjcKARWfF7{pF2>>lLSQ?@0XK-IZ6rKKa+zZw_sJaJzBAw5&JG zUN(F|dt*8W+yx0V_-_}+kWBN|+X!Qr&;UZ*CoCnFoaiU(B^gE@5}(u&>+Tq>o}qJw z-<3-Fo$jPFw8l_i>^=pClTl(WI`vcAKVW~w?%(yibWu*&FTufu_Wa zCLyEe6y+rcdY8Wb=Ie9ctV3h%2|a%J+=|l{KgZL1V&&9>Q;TQMx}TIMqDdQHKes+} zd->YAnas@8RA$CbG9x42aVMXt_r9!q8ILYwxpc9i#t2W;&N(dYJuD}x+u#gVZa+|%Q99ViudMo}F&Tfj%R)>~bZ0OLp zq0}qQu2)MvSMkvx-K6CDka`>r?3H_`*e3xN(?bkN{+oV@Sc8U~?C-*|6=C-!Uyy2r za2tHJ>o5d^-6S5#Qe-zrI$aC3sbL8GHwY|oy?|QhR#;2kls`(yIVzq6`fA)3WuxW$k}WPjvM_Abqq$6 zN0~y?UN{&{MJv%=^j0a=G+;l|hsB5SAyEzN;-5o^xDZ(l&(h;C7IMTF+B}+)K%D}+D+n9l| z1Y;Z?Hl#kb#`D+dbd+tj7RR<7h^;|={jLcqj+VYpGw6tGW-#VzclJ?I7!X%R>`bcy zjYoYTYF{AW`WS|=CiO*fL{)OHl+I$k2^PPJ7ExH(GE^4hZOjt=Eg-i)v5DU(q3v(( zpr1@X@~<|VO6DML5<1+GgGtx41~X%#4=o3*V%Z3o|vvB)I;BT_ktQ&t!yb@!0b9nv2c%4$7g6AMXRqA-xC zNEcjH_JSyt0Bs1&pEY6d!Zt3XGJ0nw%-c2lql@)uZmx-Z+WCU#Tp9AOS>{+UWv(A8nH0r5LeDTbL}tE-vAPoBGM0DMDEkv(S~`L&FhPdxkH zjT=wCcjI-p0VMU{)}x1y{&V+>&%Y7{-eA)^v%i1Y&95IkSUh$7%-L~!&pvl(2)4Yu zJaZcy6dUDD5rokGH-8j>pI3&H3?QBeHSY*;&)fZK99hE%U+8Prn(t zZaAw3LIE+}U%~A;w-z2}C#S81neZd(%%C1AfY#ON6Lt*Aca< z_8#$E4Nw&!VOY`=;oZ=Mh}|^Xb;q04j3(1e6Q&kVoLD@uviM+e@$C4aJs>+@&_uD$ zvoT*S0YM1*r zG-uA!zH3ix&udY1=dyWpUxuj33ds09C%HiNnZU{cx35fk-E9%7bzS)VWTrTplC~82PJ|m!E zCe12h|E$Asxf3=zOWk0QeXu$jVlJ7|2cu>H?NbjDJ%n*um15y}cD-w_2G?R8_Pu_; zp>v1Xbl9iPLc?!BTAjhPFd)nVY|%eY#C;@A;!c_m`V;~^ul;XZL|NgJ6YZdjgRW@P z8KVWA;>N+7-v({x3OGL(YGP!^P*+8+TMXmjHM<${L#LrSe;{e{4Cs>)! z+mdRL&#|!G71}PrnW=9`Cdq}KTWHdL#59|pU>Gf#9co7c>&vx5SMzE0GXcbNHHn^= zw#vx@nVDtI5Ozto$Rke{fBB(Hj(kS!*SU*sA0FS|fB4Rg7s21XtG~GVCqj6C|NL)X z(~tZ2U%UVOv)psluK45iRWHoSP;}(M`2OX8{q6PlNJQ9k2)rjp%8UAF4@BNOLS<|# zgb6;nm)A#@XN-@sjCH+5m_uA(K5wuMO_^Q1Q^QRmk9?WV&`Z(48+ZTmjJ;3) z_^r=^Z@y74Z9o0^)6ussX0Z9D>lYeo9CUIkL*Z*^pGORonLcMOj9lZc4<3Kw50UHZ zL{EwXs}9M2Kj-K#QY^udCeQF+t%>h#A!kk$BG}pw4iaA8IT*_UGEr=41YHz7_eWYo zi376X>;-RJcg+9}Kq{NMHQ=#$xvJf6Wb4Is+R5|^_ftRj(yiatpp)o=a z9d8=PSK1|X)JrbK$x|8qKU6V)G4Hwikq@eI&CyGL;#bVkW@%wdb(ezQ~t# z?c;G2uPWxF;eCBrcmpP$cjl*bso^3&cxXMTw3+FqU1FxFaL=1%_t@=oJKs*2*h z^Q%t6od(h!K=Z#)^Mt;fJsuvptENorxZ%X|LVhRhK3eNCQl@Z`Ww%~cd3{*lNPDA} zhQ4upTQ(d%+gEP%oSvHhV#Arv(=MJPUtcZVDf$C}j`7$?rxS?}7Ttl8^pBmKOmuleoV4GrKGCSsD0IzZ4i8z5+F`_p}<{){x zZPd5zo1bPPP3B~Ka$-^~4J2(CG8Y};)0<0DEqPjGNxer zS=}9-g!bCSDnZhiS<#eLqq?HB7?DW9s=lmQbfu!sqY8w$S`7_4Z<3)g86CSY;Zdbu zr3khf1!%b%(mY7+bJQrZVQ(}Wie`6T39;Q3D65@;d<}-x(XnjQxt5I9l6hrBl~9hs zQLMh)d}WZ_j^Saq@x2n2^>xiSyjj>UTA5 z#9_4(t=v#Q^p{@;#)vojbGcfgXsp-X!g8B7Ek4_eATgaeymZ)ji0g@rVV749N}He58EM1{;mnY>BE*d1p9rjAhhXw9YB0hbMuyX0EQX|&ySyI#cAhUW`P zmj>z~x#+A}46Av`KzKpHSPZPSm@Y4MYfW;ayJ*Vr3n#lg@>{q5$JF`#wpm|coWypN zI8zimP1GiJ*2HdIJB?X|A&q0Z*~~?E5jk4a5lx^Z*it}6G(;#tZL}XSK$OwCOPj8} z*rtuHt0p?oq=~hKQc<#vae)BsYKTc_|HsbfIp0(itUB-eCUwDjA3x_jKL+Hc8YtHe z{_v)R&!H2wvwT_JywF~RJc1aDZKm`voI^()7r3vm@f48oQA9wzdxw|jC@X6O#FDto$ zUk{?i{;qN64~;Xwd*olA{_OKFKECyz-#zzS{mbp$`|sSDIed4|;X6n7%+1a14%^i+ z17$FB#C^YV^U|vheQSD~Aa_;WCrOxO6m8ekQ`+%9^7JFQOh8;DRw`UDU|CqGRu@?M z?qxT*VE@4D_KuB>-F(ad_>oENe)ns+t)=h&-N!>A@cys@c0Mc)ynp|#vX@!g=fuVS zgZ;~0^Vr+%tNH%EY+w4^Vpd_$5$4c+U2&E)=itW%*qwc~+q<3c&IIqTw-4HZxtSTC zM$gRzPHYr-jz#g?qYr)War%H;9*Etlf>kMeG^uLNQzR-v#FjI~l#dexrMg09u9O>v zGtvi#tAtt_zt#hUb4in+Gm$~IpVi+VvmM-b^aXfQ+HCm zeg9CYH&f2aTdiir)6H_#FtN_D;@=7DqDR7U-P;s>1nsXm=d?Q~A5ld!c&EM1@Y$mp z6nqHya^ac3e9`ql((4jJ2Msg>nr01$s{ zHE1p+8ncGA;BsQN)U!pi5!l?IPHC&Br_>e|j|SD1NU7{+qrZhj&yuH5!hT73HYgTQ zm!gK2B}H>kN64(&VA>dN$yl(ej|$__%_Z?*W5W3&sGH9p7$>mOLpE>-tAim=R&-GZ z$C*0k58Nvhiy2#qMj^+hGq>&W5$!7wHD>pe6~_-3i|qWx(8##A(z$_@*Ja0V>}=tOQCVSwkHP zon&1Md+iubZYZU)BROFJ-K*g-Q|EmX2F+Zumb|#HW8a&!5W;kOf!MX)2|Kkm(aYGn zcY<2riyjJ%BpM_hLXY);Txmp%l3CVn|C1H?+~|y4>WRy3)YeY!Br?5-Vof99FO!v6 z=w?9r3_8b^fTc&glN4wvt=>nfHGioyPVj~y^*qH#%IJ_SSRI6MMM1OwGJ+eE7`kgw z`M4~9`xmo|X+!6(S{A;@wm@bjUa{a^DGQBxNvnslhrExNPNeApFxbB7(Ddp+En8cB z_Ldh2D#Gfyx~huyZXeYM`ix=hQ!hUS1E#X(rI$p1-!uF*0JbxN;H&4A)r_qrmD{_0 z_m$^A{?q04^<;$2A^0nw ze0cRiRn(kX_u;kY9<85Ji4CR}K>1lheE&%ngHh!hH$MOP=KsFD^5yk^Umx3^ymM#! z`***6c+b&qZ6BS1l&VZnEEr@RQO0C7wEK=!Le~N(rEwmC85-=qj`l~7jO(CB^v#(O z09XrPu38v*=SPpe8oPq!=(u3lHPB+bPiX%;x%d-k?5;2-?r zyiZ*59aWp+pZ2$HHXU4AbqAPwjt?x)G&NogOLR3fJF*IZCPy>g}5Qp00TrS{cKCTt19jzBmSM$Ik6#<@zfQdbIDwdsTuj1=pI#;T6jp|#SK zh+86UJ_c686kXnBz0Ugsk&1d0GaU}WiQlvc1z6*QRdpmPqG_VpmGg6&z*UoS+4m!E-_p9dt9;!7W8kB90~y8dq?FxpN8MFZ!!e z=>Ya#yA)rNofx$P<3vN34iq+*3}~a{c~-uK0*tkAPm5j+r8n}$;!^QmQPj4eK7~zE zur^U_Ks7pTx)z?`bF&oXD&81}orr8*h@hx`0^+vkxX}5B95+I7(0K83e|A}WU_;o0*>hcs2EWs*P}|jkWnj9DAR6|2khm+mh7=Ctz9$S^ z=>rzzYJ1AuwpLzMk_B7T*H&s-B*p_fzi{P>6HnJx)rZ6;wuVGXY*%AtiJqsz?$?V6 z4Qv(40Rpd_R9~Um8CV=+PQuNE2J6VlftorA@fz3E_Pe6=XTy8XzqIEklnA{-2uOKF zFIC>(GRkLQxqJfI_LL#=^0T)bcD=vXOL`|^z@J>bcIw9ufs;=e1E#(8JtM#dz%by? zeswC4<1?4fw{q$)VvSq9`yFGz7??sz@A?~O19%I*^`MUZ?AZ_A3b{z9&itcZ2@AW- z!uE{)(O>`O!n#NMuDhSqA7?y+&^WUkQM+U_y%w?@44APk{~q_tCg##lKmGL=pBq>H z>MH}~iqjD%wa1Sh*5dTo?qd%>eC*iuhsXAgEr6^okDCnCHyDnYOw`^c+q!;U5%szO=mze<>C=a~z#QpHe@Vn#h&Vhivb6!lSuWktA0BjZ*O4cjL0OSF#Vo(8eHuz3I?OBG2~n_ihPNT z=R^bX%@%ERs9F=c?>5L^;Qp%)h0Zo3yp1*~w@L`3!P|EDZNd|;3_%;XkJ?qF6G_NR zj7T~vQxj|7#u5<^0$L)UqiS#{krqu_7Cxk?apZ!hUSUFNQ`>Kp1u#PBe3Ui@ijVT8 zEn~*{P`i*X0kJrdmI_e@&rse2g(ZXFQM-hItRg8LhOEUrF_d}mxX8r1XplQz9NlEE zTNoT4-lV1h)D9k`@op@^o5p{O2(s)e~c(#au>r-w!r@_d@84wTZkg7NxxZ)}L^CWn*S{tl|fP^)7Av)eA&Kw%|= z5mmrkImmw4sH}0@-XXNp6KiWwVyN+uFqYOrqOnxOK*unYxnqK8j$ZUyjH#1rFl8~| zMj}BM;YTE?ePnMIcDsae7|KRm2OTGk17UP~8@)*FEQb;M^+(!bS^*mf_w`5S6F~A?56d9uCDdB$@`4XmqflW zYmQ?pO=6G4jxUKFB_dsJw&P(wfV9Zg5Nb9lBB?E9D$%gADj=2sEi)5QAz=#`f0z>1 z1(vPRT6LWm3K0hYusmNm?=cQqz<4$8jL$gzxl=3#_Qzx4_^DVf##OL9-38`muH*s>?EDQ2;-2LvRELmIY=2RQ zFh0USN*IcS4C~~1gdm#)7(?mIIB0l}G?fx`7@^T}Vv^w-<0EF{ThTJ$k#s+sxNV#GHq%efey}irteklM<`4(zoFQ6U= zcYb(F{yr4$eCyIO;QalK6`f+ATX|a0y&LGx#N)HOFaEf77cs$zc39E0BvaXniS>EI zj8)rp?wo0KJ!E=a8-?nJ4J6n9vbFW($!pFAIe6~MOv7tBvAs8aeDdtXvB_hD69?Xy zJU(%}N8$6tbl=g=zBdJ3F@VmV%yf2j!euH@+m}6g66R9^aP}kwSUCFG50CuPcip62 z2?Oq78Z=Ev!S^r@hs z6Pij9%qjp1a*$~1YS?I_yCMx)Z-PM+`frv=%qtC5$ujsR<51B1SPnLlkToER|Hg%a z*_W0%f96EUic{HC>AXk57sQ|9T6t$gLbB56&ys6f*_>5XsfZ;rep&U zd&rL+D8eaWZ~U}WgC@rV8J5>((aI!ZDzY`K8p~l3s?5wueDV~XzjzwA6j3p37rYjh zJZrVE_Sf?iHAz5U^$3F#V=WAhE4;R3M;bJwSICMU^H>nm;T;o&~AMUmHN4

g|Ut3u++1wJUi4ec|% z!I(&+BY0TgR{)zfB$jQUc2F6v1;S_sx5$IUhuH}L*9FdtvS1rnuFFPg7P7B!gHT!< z-`T81?0^ZoEHQM!5A0Lfl@mH>bQC(91bZE5gE2j9F3#xU0AVKx1Csli{HuNvh`6TL z&!HA+Zl($KgL0zq+VB(v&X8u!<%ACl0LSJ~7cBT3n9HS+01biGy@m7~R9V;?qx=`H zUqo@l*%*`?K_OwTqTbm++E3dNayHantLe+&q6?ae0fIR$CszU-6OSVqqhgFm0+5&= zW7rJJ3)K}vC{LfR1jZ}qGC~$5n~~TGJRFG;@V>5+vI z1bt{6NF^^M9rJR*f5@&lmWDqmkdJAf@j`lpg@n%U-)C_G{?2QrRUxsxHvs@%U#ZqF zE-!EXq*^D08vctF@IOC2Q(f8EyuB$HeLcd)B5vsffOi4Ftuzn|yq+YP{ngjg zZQI+A2X_aL9hewA@W$i8$w~N9N2f>MK6>;-R|ZrV%BxOwAqgSw>g(+M>$h9qQvg=} z%O!Bz=zb)nB5s>D5sqqS(&*@e+*Fu56CavG1bl_sx{#jgn_<+OQ*&o1$_mT>7YeW- z*g|=Bk|L}DRaY6p%Onm(VyK?mCIx^e)ecP8_-5n)03ZNKL_t(;d_UECFU zM58I$ghDlju#DVRJ$b?yb}}Z-iL^MV3aB+Iu_B4Ap{6V$(B*D~(k?={0AWIFl}&+C zhERm>sH0mnVj$p?*Kff@Het|lO@Usgyi_6c8bO82FimC9XcbX|QDP0+_lPzm1j`wN z)!@28ll=|896T8@zMzOowbmjAkrTm2yC5zkvl;b5motK_S=EGLOuvT93*%o48bcIV zy-}QHASt6On28?|22yhWjZLx;@%cZ;ZFXzXRXVeiII00pzi$-OEa(*b@YEMyy#Y&`9KTW~ijJ=Zk@WXZhZz|Q?F0A=RvwXhfMvgN|kGkEVpEDa8 zv*z|ti#xQ0jc$ncBVjxAOITv zq+y~m%Nkm~1wozN!!dNp@>Cur9wc9(K}#MwwqmhpvwB=b=${=fuwa034Q?ctMLrg| zmh*g6WI240LN}q8P#7!@F>Mn3)(5>aQn3W2k#q$W7ADT<{q<4m?Dxs_KPn1iep)f6 zoc?&&84t6t9J?`>Gu-5(16b&U6Yfdp+!R*C@*dkYz;8GQvoLa?b2F$MOviFb9RGdJ z8587|_o_`Rj{_fw9bSAKQz56fq&b=2EoZi#56 zuAaxo-u?3Sy1*hT&#To#7X*KomoMq`S-yghV8E{c@CFeYFV7P!P!$X>_f7PCclX7U zI?&Z@kuO|C$vbKELlE(67+_z$`sk6M^5(|o#>P&)zQcy~byLc&gKEBO1t_G#8MA1UmpbU(Dgg%sdJ*( zx(T|%rY2&q-v>E_GwupIr)K8xAHau1%DE;LKP3OwNWq$HjGP;>lUhND+a`4z3^f)G ze4IM;&W}F0p3$I5#Drq&OQWjEElFfF@g!3~90fP20x+3!wh%FkPdQ#*gn&hX{i(vuY0l_omL6=5L7jp*f96EqO75tWQJ-A^oy1TzMKNp!(- z%PN*8^JkM|R;TzRz_^Hrn7%Eg+(`5&%cCywQHm%R3xtt6z?<3P%W zoJ+K2VzdydF)Mw*IAE`NOK=(qyOlddYXY;gXeLC=C|9QJ1+HU}RoMhLLhi0#;+mN`n)T!=4>(G3;@dcd(e*hbnE zrg9)mCHjsDGCkmDO`M;yAGn?kKJqu3>030j!ZzvKvO}RJJ8b5c%p;OKe5WUUE^3gi zq)@>BrChH0Vd4lSuYNqQoiTy+2SXva(0=U)+bQ*ip+Uo)Yzz6vB3(4bAVUXPIZ}I! zG3mA-8^floV|Ko4yqp4+)zy|lc9Z2)>bi&Z^WK(o{4Bq zQ1DqKyiwX^C~^5^MvJt$$+%O=8x zUjExhW-agIfSH26fpR+eee^H8e71CM{+-3e#od+P{Kr-1N?72+b6=m=5Z3B0x;ej6 zedppL`YQpyAqOoLH3h!!aXnU-{$2yRE30v2JVV$cNrh;e7OBtyy!01 z)J?wj*e-YN^6rkg6I_B#z>9T_4L*g4?WOn#3RK0kQ;itj_`fL}c2>8)!8)A6lq zus0IzUCaST=m0BsFaph-%uRdKXzwoRwwMVXYibJm3EFH6M1o-7WP#hp?3S5N+db-r zmpkZyS0i5YS0hsys2hqVoR>pT}V4ZSIL_!^G1{DU3;7kcVDX7Dh9iWF(Ej#^IQ{P zvmk=Fr>bebHT?ri)6;gP(7pCk`)coh^1*A)p(fp4E4BbeO0~O`TTp%Zh z>$uU)6V1$6Pv)f1OiVLy)!4u`QVufZVWF{1jQblW-ZL}YY+6iF+7z`*G*xSe?%YH4(IHK@%~&Njp3eN)8a(mI^lzT9VW4H z>~fY!!h}O}DCsEfz*q}?+4VRUIh;sn;tD+uCoX6|7*q!X(uoW19vz96tg6xpyzOSz zd~VnkrWvGKh=t8MC(I?AXfLQ442a_b84KZ!e23Y6%q6~K>az? z=Kr$Ezhz3y`jN?UM34?xSZ$#%n`rt*2qz~JMuX2P$LS@?Yyg{*W#W>k)s+RK)K-U` zF$X@1gnLsYusUSJ70qs94})^6Gd#Sx%NAKGtH!Ll1=u4>75CgXCDGAdhY}0c()Pp@aYZ#02>JKisS?Rj)1n@nUsl{_(}d zOV0YLfXx!|C3o3gTH5&N=Jv+w{5LhXjKXB{nXjL|{Ev^fPl~;T0v~@zI%_`qhQybT z*YrI|e6L+w-WTAVyWVBTUEehqT{RJIo!|WqPeSw7zS5CXFO4_{yt}(wt^R+-y4t$y zUBOY4He03SEs4JQ&u+DVDMO>YW`LhB9JRk69Blnv6&R@y(ujH(pZ;i zZK>pC8FYGmjGI|iE+ zxZp)^mE5{{9na-R9Q7jopSqOAur(>TubR7nB12|L{inAY{NyDtLgn*MI@hb3v-ujz zji50ALI)Zes6YF(7pg=$jXFC9G_TLOW}iN@8*I_q4KS^>l{4RM_BN24Box@B*^H`b zv$@%vJ$_Fk1JL}U#hU|HDHt?S42{@diqY@szyyV8Q(+U~i9RI-Pk^HAB?1_o&S?Rd zO(b)}IaB2IMggI<5G=5Und4sJCQY2x1WtgS?CI^#ewFR-=x0XlGLz(FE-s(E^rt+WgkAdqlJRAnb-~!BsY=IVbcaoM=fX15;h5d3#m-VyJ`n%2X0a$pD+x)Nz;<;YPWS>wSi!&W zp{Yc-xa{9UVdr&Y12NIBlnXp(#&=*YMmoc$39vcsIs4oW9wH8y+~5H|JmuJFAXfY| z9VnTE>q(LrM2AiW1;$G9OF2lvqQVza_}ml-Xo3l4my^kN8liCF`AvWK6VvznTyF_`=S4>Qum|+HsndccV zb&ya6g)t~&p)#XLLZ+*RPcUso)3~C2B#PIAdFHu>PgE#C533bS+EN8io5@$~kt%eb zO>|F0#pB9HHAr2lz!GtrQ1(w4%s4n@wD{w_w9EVJOcOd(qDXl3>!;6a3VLPx&E@4C zhMmuyJEw`Mdf9k&Wn~p}yRowULic{Lult!}Ps{<|zB#|Nv22#Lx>9`;&-z(ifFJSu zk(Bh({Uy`)7vP;8g-NU;!uP)yGI9t3E)1P|;+BooOm3|@NY}%cHv6@>qa)nzjp^q6Wx2oi*n6R-%Yoo|mZQ8BSdMrwsx=PJr zII2{0^=Iy1Z}4h>Yg+H$%!KP<-F(;om^%NTw(C5OTUvUBMnc)zEQJzAE1v@8OJW^Z zTCNUr$z|%eGt1#cb2P;ekDVZQ0WfSSdyuCYj_S{R)ojZIX|Fgf$&GdZvp?)0xQ8v`|ATC|$LUQo0fr~0Y z=s=mCB4*5pt|(OCmDgTbBbq1sofVW;1!XeSl{qg! zQ9HcY7gF(&1XvJcf7xF$NcB5=Q5AwLpP_r{k=-{SIaMGO$T8=}-6TmCElBDP&KV@P z8RSN)FdXR~qraGajqFOGRkxF4@|-goOv-aEw*%&Ocem~2G>YyZCQG%yhPoYH2ESPY zU{bM+6L&C}Rw`DO-XjC^ZlKwYOZbooeP%X|^@v!G?yej0?&ek%CQ0PXyg92>=-^v% z(O`+6=@#Z*9L0oH!hgfvGy#LDRQ`susG(btS&`TgbZ8qE{SCWz;MQhxDCrcO3D3A7 zXnByJrds$?v(TrAO7^`>m0ML+IMYD2QA6W4+u_DIL*_7P8$qd^=}1EF+~T&sGl-BzFDAXw;&cs390tN8Y=hIq^_5~e zIi60&^58E6<+R5@+Mt(`BPtmTQ)x(2OA=#S5;n-^@RVcGk26VeQt-`zf$0qOzs65j zV5r7KCu2i-mw-hJ!xXaUDa6fcBNXK|)YZXMzw0KPH27r&OdkV@(Vn8P2JHI|OwrQ7 zA1Brt$lEPQyH=$7a?OXDck|SEjw>yN48?~$ay&S1$Rmd%hSV&BHag=yevg(@5`~Nb zjg4s%*h!@C57>|lfZyGB`On9p9C8K&$E%x$f?HSa>}vJpf|&;&_DThP>C)EX(&hQp z1pxT6va|js1vE2g=F!VHFYjHs0>NHfUHzT}jKXP1YSR-hzWvYt{dw<`)!C2N*48#x z7q%9cmo$6U2cz(tmzSN4OEYLUg8m8Y{`jT@E zf#deRCJ^7_?O^Lb)95Wo@kuGWdVUx@-PFnGxwFtIF|<+OrdLll9scIYtJS*{F@ir;i8FXrW~UKIMGCPyd(?eN?1clPk$+Z8VznqT_arnWP0NP1j}`-x0$dhSVb% zgfYOU38);ePEH+OAmq7XKXQ}jQ@zI!tmDd3_!yOYdym2=&(>c%gLZerDTc2efS)Mq{Cb`y!CXP&wJ*>f-5 zzy0~-y@dbS56+yK?791zLA8pM$Ieso(SE+*M$Jy*r7$t4HRn6xfxh^;=l2bVzNumZ zr|>}ZGh{xKhyhXcMTU*CFla0rf~tX`j<`XHa!3sf>~e=4|MgcX_sSlY1JvuBY>MS_ znPIaJJCiZk@2GC@(X3EqCx(1>N;%?_O^Mww0n(8Gg6T-kr|^xs0KG`cz6!J%^iq0c zP+dnB2O*OZP1luF%up&B%Z+p~Znis0JBXn>j2t6>Zfn~q<=V2j?v4^GV|Kya@+YYy zsg3z_bDMqnxpm?$yL^ln_UGG5m->#X7^?!crM(?QP>e-x23N7H!S%8M*S9AXBfQ;chiYDOw%@^__x#&9%2+|_h3KS10? zej4s84OVPw=&ts-F^#5&lo~l{)Rw}9{-JBvoGCb_6iQKILYxK0q-snGXJrGXjX}d| zII*3PnFhwE2Zro>L1-t2Vs>EQZ%cIP6CoW+o6G=9t$7Yy6Gv&ZzBP!9IL^YR6MbYmv#<@uC|Ke07`O5YER#~&2k7Nd~ZKz^q{EoX)m zS{Gc^WEZ*GXPHEBnevXxe677E}4<-?UkLXi^@=4qCnJL zCk$#Bo@l@RLBs3y*Y2eb=U)HS!f6)thKg+L!^*mZanCOT}}l~ z9UOe&awba;$J+*Hf=Zb4k;AGd2 z<_Rw1MfqYH;{WGhK7CqvhTezCSj?g1;XEj zu<{yNEmMC}S2YYJiij538D;P}fT|1aGog}^h_uoQwyHJ21a^lbkZsV_1zsslE8>fk zj>&IZoxK~h8rNks9moYbc5-zQA6-ZWwrwK6I*d@okn3nedu5+XfgFuUIp-4YFg(q* z2K1;7q9_T6?keq+6h4U-E2okMGPAmoNE^v5L516}_u>Yo9jUpC=t`u{kXnMEhW}LGN5V z$fN8uG*#h-W;G-UhU1Xj=54ILjadp7;&cKB9l#Pq+0f9e*ylz&xkUr%uu*39{I-Y$ z2OEW|cAgpw?TcU|ESIHkkk-OJ2G}!1KLf^LS_lE)?LNXNjVRYQv^<7@UB5Q+RD2Ox zz^lr35fxGo64!D*ba*lyDd);yn08-g(4lIdG2b%n3n7Hg{%`032{CMz6uR07G43Rc zzf=O#2&{I(bwyBej$(m~2ZW-oh{16AL@nCUBrP%a3boF3Zo~+1bTn=Ek1}|!NsbyH zj#9ml&U?z$O^X{F6Q+*A9y>wev$yW8OCLS%d7~?axYH{!Z@L)sR$#+8eklUBGcyyQ zFZ*D{acFuQD`tj@#)St~)VwS0@sKo627%s$;o+2_E#fH#$}|Py<(-TT2u=Hyb=7~o z`;{PTa==Zc4WXwp14_0UU~4={iy=u^uFQ}fu3Zw4fn}UFGZd3jtDjmzgw3eF`c+_< zQ7Mx$EAvCsEFxq%bV}N zzqx5&Y<{}*_sz|<#gFf7?r*+3Zvc7cOhGI{o3N%AUwl(O;8|n9^Ghx;x>DPqT0^2J zsc64-a4_pe&}$2qzE3HGiui`79x@&N6czOUiMsxurt>>|h0?S%YiLV}DYSu7`VCqy zSp`?x9s!mtw>!(tsoWBCH0?t4;6S%nLt2VJ&RCBMmT&41%XZ@C&GRxnl$#ec&LuP1 zFI)Ea?DahFPmw5o=m*M&r1E^8*X#LmXPy8&b5NL9B5KXZ!~ypFg2sWF=}}xdxPNf3 zddPtJZ*^O~LkVi=Qb`zaQiVDr&8qF?`v!h+RRI zG)dL4TH8{bg=}qZW6=VX5V%!6RVkHAA@5TYwB{l)8RKg}Zcr~{oZ3_A2P zpl{tshmsB)7HVl7q*MZ*MnrGmm#xa((4iEEMkC~FWa=&dkYi&E5@)9Ni_6 zsG>HoT4o9+!Zzx_hOy?gjzDN-(QoK1Jh0HuBoMrACBy=s0lIpGL<{^vuZ83*YuX2R zM$M5m!ih7w7;3$Rk#v+`oQ6JHXz%N2I2}S1bX0h72w~9CG_ofnJ}980Gzy1=7l&g} zimjpu$BMcmIDE}|V1d>ONUtXvf=ifj&^!%&bl#1na6asDzm9qYEK$Z#5qQO*T0oXY zVIjS!QNTPpZ;R4~Bv|bhN^6K3(9qy?!<1BU+VUJyo6WYhH3O5O(USyFwY3Wu25DCG zR;aC-N}KzD!Ng;mqQFjr8NI&3X}<+XLv>|9ztSbvG_sol_rm2bP5nrA`dCN6*F zM0;P86LzFOy@$F<3`(HCv#bl_&7dfns=YcYp3%sFY>qmvcID3o(oHdZ&S2z>7)m_M zQ;vE&SuR9ab}(Y$xD5!~pu(h~-l0OU0KKePXh8h}{g4f#$R$8_C5CbV*d+sSDPawK zgB`zq^dSX0#}!NPJDxr09KbHk6bRTm(R6eJ#f1U?fWY$D_%lBPIRuXFC||fZKrZ|Y zX;^~T5Mn(Tzyi1jNgX{y@+sF^S{^8MGyF+d3C9uq3>4&imy1^*CwS?QFy^VD2M{bz zGkQZn5;@PR)d<-eQ^${!>0$+ZoLsk`_zP54&fk9OwdAwossgE{zaPE90>7A117)W` zx6%9{WSUpO*k?G1k0XF99-qcF#aThvA|Ld`r{pp}ClwwNQjbuMzI_JFduzoq7#|*c zbMnhC-+sNDE8Qy2y(+w#`%9r%EiT;@EWYz_uUOsNn|pPCsa)MF76`zqMGo)&_eKEt zzkm2XH@jOd6w0gI;&NlGO|ff#)!X)5Ve_C=dPXF`csSYC^@aevn#+~v<~PeTv%5u2 z#HBn;K;aicp_P_eZGq>@H zYQ4%lkJ3!8v^~Fh=yWCmGq6hyzVB;}CIR3@Z#Ra{SpNcklil)R_p$D_r)QcMEhm_C zb(UIZHWE?{-Gu@4DYh{Xb!(m^Ik7LV%o`{=LevJ-&*S5!@xYj{VJun@D${6c9G5%F zh5+U}@|t!aadi|@=!Pi-adfFoFO0tL;y4aNp~;O;zOVFI0P4r?=A$2OU0}48)_yb* zOaW1owXR<_$CKs;6$$42l+r3vQGiWC=;pIxa1<*zlAnZ?^i)RtqtZJJ$=iWbae(32{-`$BT z!+lSles%hH-+gn`d>gvxL=tVlEOkKWwHMvS$;53A2BA>vCP-Ffnu8xN?LUg*;sWMb{laMoI%hP*T0sH3_>^LLm zj8T3U>qi8kDWH}w*W(78G7P;kJx6FAL>{y-Ux8<*J4{KmP~g1H8K$Ti(`cA~x#9J=^Ou|+XT@DX520tx zV^~v!7_({QTN&~;PM^(aDMZ$!0U1}$Z_SLhGJ_a{1w(jclgC@NBg9jx@Mtt7Vd>l6 zddb#qwxQjqwH0N*C^<57(riQ26)GK?T7lPG54Y0(+m0e6(B)Pqnt*MsO%zbK_PwXl zznR;e!9)b|z4{DWw2*)$uM#6;ur`#Yz*uj!8|&(8J-|R>mAt{}GYSZKhNXoKbw**u zEGdK%OK^D<%P=xrf^Z{4vY10juf`aap^ni;`wgaKH8|kSa0u#R89Z+CJN%s{MsNh6 z!*cjdH~c6i93Ki7r`E=Rq(^YxxSZ4?sd`|D6LX;Jdx?k`V;5-F0F;>aP8TpLOZhV@!jNHp1%A#AQP)96u z84R2?OrXPZDJ>|En8pPU;0poD*LtpDIxRO5hQ|pN5|vdn7Qx7W?qU}7`I*^UWnsYb zRwxMkE(!B}b*Fl#D0FzP_)rjdX>N7)`x6@avb68z%gew2H#Jn{`T0V*SgclW3I~?wX1sO04hYI0+$EM>m(j*W0?glh;4n|8RJ*q4yUg zwq2U@S5e@zKRc@=&s1S?|4R;x()l0aflh~AUbhaDAAP`(^N)?v-CmE^J0>?misc4$ zjA50qA<+_V7a*Sgu1lLYA2M8R+50h_NleI6ZNRKU0#g5AZa)8$trhH8RWh=$%#`ZX zO)jhEc&}n?NoH^?)64^cn^om}7}icOe}Zx)uNqe`Cx}6OJfS5xsz?u2Zsc0o5k|dp z_v)3M3AlH9uZ%_mch7-%W9Xu;1glz=9*IX)gVl0ETOm`^MafvOmL3hH&+>KqWb!vV z!PMhk*VfU>N^m88{>r1t_8n!F;>=q$C?LieKhSb^*@gP2tWuW|Jv&qmTaqBDL}B$xjA{b+^6BUX)b999hnxgX&&}OJ**Ag%pGI zFXIPD-Ss0i--0k-_Ah{!GUa(hz?DJH8KY$ciYy_o09a25|4jg2E< zxTs)2uS31E3PYf!H&SB-oV7wnt=GfIi{=NqjVRVaZIX`P4VhS291B`zh}c%^x;3-z z(=m!tzLZntb=ZyMseJl%n0`aTf+O;vRR9%vl`%}3g$biD2^1NME5TeuR04aUxbnq( zXjc#bb|d{N9Sg_O7%NAp(DKEg!t(fp3!~DIbqtXZv{YF4A_ogPElRcA5yWtyyAb-S zd^BHif+nM!P*AzzcB&Ra@KXdrI~g~LkJ%QC(2b~yi}sk!?x-1uX5qJPXT_XHdKNGj z?AGSaLnjSEmhf1o&FqG@|{IZpFCf$*YojgY-+M$&s)PHU|=`o zvox`gP~0>2z{n_lRRu*Bm1bjuc}z@l-58v2U2C1W^$q})Xd^V=X=?gv%=`|~p=A~m zzac9_CJg|ra#UkQ!N0=arm;+(A%_x2SWsdDppArG$43%Z&Y(B#Ml~HtB zfhdj0`eFu+d9>K$hDuYozPz3d4I;)0LkS~XAEpwcG`Kn(uC5+ok`isIVRxj#G2hTI zANEz_u2~+_ptOV;k>kW+PNYvfbA?4o$yTj&lf@d2)Vq$Ur+7mF;*4X^%HvGcZRY~ z|D_{WyHDkox z|LEP8_gS}mGVuPuxrd)~i3$Y{>1BiBP@SQGQZ~Y(O9$HedNqr+?vao)8&VxjL{Npk z9X+?iqNVHolc!p)cE0~$d9>$L%g?Pv3caCEv~|^G*f{Gy*lQ~|CcXMt-ARbbGcmcIj#({yz_K}ND)%Sow65rrd#7lX) z`lZ8UF&b6#!eG=Ct$=)*&@YI`P_VEpXnExez2z7$GxCYYTi(GMIJid4w;VAh@H9*q zM@J3fTaAEt+!MLQ2lg@wY%y9u(6W?^u+{G*#+Dl1$#rBvHXG@(ojWb#}K*+E4qd{;CYXAfV}}z3q=+^2Jfm99lu0F zx5EX?4|xr+&*E#_kG(1^boJ3$3T9D;&#|OJH)?=5AKwY zvDRtc)kc%h~|6nnZh2l}K_Eu+BAAl-oLtqO0`$(U@4=9wdZy0LLBqM0hW}Nn{+C zSms91Hps!MA_1$3aIC5x{KjsF9#j+7jWt2eu?`l$jH+O9!c}JSpwG!Wi33JG7C@pX z@!%{P|16>i{u&uPGMMfGaV3A-@U-QoTKQqZsR01cBBDC|uPCo6Tp30Quu1H21Of~|hv=*+97Y7vlYXiCia<)3@Rw>O~gHYxQP}y_LBWf`W4EPFkY4~fYYl4Ppo+~jiMz_(3S9P z1__;JE0e||!&^zOHHKaW?2NtEWDFYZV?5Z``6!?sD?nma&A0yJdJcGeVnK{&p^z#R z3L6(Lr1w*)xzxmk)l@+|aA9j@YAUaGz-_7oRvv|Zc<+n9{#U=DN>4$7H}dIxzK~95 z*3zl99g*_2ytrpkL0L3hi4XBY~6hM%O%67e`vjO(%9|4IZXSE>9!(Kt7Ztr zk)%upAoj4YC}N-qzlb|5|L&)w@f@`ELI1sO=aT*M!{vVS5(nYrcZK|=oD~_;S$~$a zNL*WId0Zws86d@~#rc!oRmjo0IQ!=VjXC)WAO2CkYsr0QIyvxd&T{g4_xkdOXLGpY za_UKDUY}+4m9Q?p*#LZYAfSIM5fA~cH5k|}h}xPmgJBTri47kEL_?5Kh#&VXmY^OS+H5v?7JauaN5iu z&x`c7gMD=uDPVbjB!t`fYIxsXPN`YRAoBWZ2qJ8gk7yT_zKvGkP6Drp;1G4~uuqBx z-+t98Mww})4!B}^TZP{cWo@@j+9xN;h{iM;EG@JE+b2aVd9Vee+c;TeuenX7wl#L) z6w5Ax3-j6qSfyxfT^Ag$9kXUck>F@+*oXwsq-dwQ%0djd5lw`=b*`D@`mqe6!}vQlSa9|n#SQ{KSTxr}?4czSXms;TSiSMm%e5vG9%~|rP6O2QLh52cH1T5PiXpI% zf=f&WRMOg~*i>HSd9enL$5r(p(!ZESvsDo5V1$l5RA1Onoo(37ekuxOteB=wmHXP?J|0m#DeQ9I^rEsQ)7+ zzzgHowhF0CDkTD($`t>U`erI!*crdDH8u6kemXCTj4SBHQ>g1>`|ia+;1J3fzFsWO z7R6f90;lqs)S4*petsvNUz6W6YlYNmMy&K&CY8_cXC`LfwD^@a$|rgK19QL&vlFTG z^mKY7zryMD;$m?@=S(U<)~w!lctbg4sPya&rPg>aZ05rz`w#8=yuVWyXz76i8dLk6=Y5|Gp)PoE>+fv>ej9Da zmphj#^3Ag6mofHs{l$*k48RxJ7A!|WmuJx!Q=bM2Q5`D6)E9K!h_*pTb#)w1aYVk+ z9qS&Ddn$_ij`}O24ar2P3l3Dmf%$}I0)-+)QG7wnvlSLu^e_m_8bT>s&674db4FS zKuAnyLX}0xOOQ(-OHive2BL4-t;8)0gtTh4m$R_EZ~zk@Rs)djE$soq*tb!l&jiEP zXp23{5m*>Zd*7n(2&$|G?|Rf_cM*KLtipd};2uIRuXw!>URl@WR4lJ3WU$-U(LvbG zhF^@GtzK*Uy1fhDU;}++{Z9ne&_EO3c447w6&(zA4M2E~TMDgoU^UNy@Y*qqM&uQb zkgMh(hNeeJn34DnZAc9q%>iq$W)AXZ14lvQM~FBRl%CgUl5)_bh7G{H+J)kZGba&# z1*i6~u9s7$*aPk+`9(u0S%h78QkRQ?FV3x^fWh%X z7p!$Zb;MWQ=bjQS$H9QzI)dCtJn|xPKT=HyJRTWsi?B|bXs&y-8z5ab&WV)48OKbW z2z^8VWp6OTp^r#j4zeVf#aV5<_r+=$X56~6eF&S|Nv?1J<(+B!8rjc)Upa|Vt^^kC zz}*)_T_M7vf$Ed!Ibul`9oBVsqu>FEEO7RMEO+kah9A?;mCzegXU06t`_X{Wc+l5?V`^l4U zA8ylo*%OsoPNguQhB<1MD~3^WNbh%NQ-%5Lz4?vQ#xY$TjL;>*2tfEZZ$5gN^2*Lql z0CzQ@8GG`Weh0&9y@;LUd!dJB33SJMZhS>JlA4=eR~_;l#btAVK=yEHH+yO})9bP*QK+))UjLL!b5 zy}u$!OZ46Y-$RVma(9*o<8O~=;8c0 z4+j47qL?Mu$eSdLCRoPK81;oFqf5z#Un0-g0lSQ@C`V)=3`+>0fw`>CqVv?uf&tfH zyRH@%J*(kIa$!0hVEGmB6>%G2x$SZbgQ!A65T&=p)fM%E#DePDqw7R^U3Q*GbD~B& zI*^duVYha5t*;Z!1sJ;w$mwAA+lBAoJT4w=XotMYj#MlIok~axH@7qKBG)Kz4-)4?@)>GPICFscB$U zbkczO!3IdHz>}M*nhZ&^CfQ_eFeDqAl2ripDg!iDe={eOmFHnrYC;kRRMJ(@YgGZV zL7)*zi8?~DmC(i%gRrKd=1K(-G|aw(gYX`40ii;RD>*ts5{n9fSW0NHR9nzpfzV=I z3}rO;4?+%&AP!8Qb$YfMXPtyU2;s}T|3!M0Y&q(#lN*3pe$|aAEU_W(Mx^8g-Vf7l60nVQ$~IPK zb)#^Q13I{MkbyQrXguD=MkU5$9)N?g)8}!dUXAyT^W_4vH~9Q1E=;5oMt4QH1d^S? z+;ux*Yek#}M$mT;bGg?i0)c-{7g>;%J~{dMq_DrgQ+Qk`U5wQhtV_j0@m{)+E-vJ9*_FacFEmuC3K0|9MzHTB}>Ft>t2*VcCOMG3?OO)85^E3UIw%wjb3u%PZe{0lb{S(Q&1o z9|%0Y-T?r<1_lhQ42PiHb;_~LlDEGylQAiuFHM*U%KB=8en~TwIsM4Dcr`CA`EKp5 zd3FsStNb2|Bw0!mzdf=z{obD5X)IUSd{b_;l4Vj*D_a=;Lel3wr7>h&eLpnxTx$0% z4KPv-KzJ1@*BFT*wsUMi_=ecy16mp?hkLL#D2t#1rJhy)yF_MsIx}%zvH{?6KDRL0!f0%i0honrYvP}QJx&}`Qqu7&rCu3R zDbe_=;ulS$kvDlP$I`ME3npGACt-mI6P}tdfkulG_cLe-u?axwreMR-7M#7%P!sRn zV#O?W$6Blkp?C)Ja)bw5q#W0QN@0%QfXo^@WBNi236lV87C5V;h^nMNRBb}^WPlkj zzUblz4$-@y-h|xtc9H3@5mU&nN*G%N#x&#&lsbr_oTS2Ox z(VieCs2fULavlS{lk+aSW%0NDykyD#k-Z+TcUczF(tg^0AV&J^^YwauVZ$q=H{vI- zqn6RLAhcf&HE0Nyz-%nyr=E~XB)Jiz1lV5-%cbR4b0&$?LZKD2)kbDWp>)>zFUD$X zBmS9~H==^9m_}UD6Ko?GnlvmfwKHC)05Po#HvC9ffCX}Guv{-Sgz_}%1m(Wm^^@`p z|8>&FK=iYbM;A*O>TEfKv?3_A82-cJ;p2?&1 zP1W6|`nO7(2q^?cJ8jc0LP6?xSoM~b$fq$)zbg4+q@>hQ0s9@WSnjZ%u#^&j#UQ$r z!a}yZY=AAut{6D;U@4nm3-Oa!eeD{9rMBNvH$YpV6%1~Z&7sls&|o{7tB^2XH;xSJ zpw+$T5)Pcg5*a9$yFwD&g1&?D-W3SB23-MbxjKXYO5tF6FzMD7VA>jByMn!`WO_{P zN9hDx;IXlCw9sk%NP*zBYsqWD#I=M#Y$9p2&j1#|97#$W*!N~KiJqh<8K&u8JN*P~ z6Pi&e02|k}YrEDDc}RQQ~OX(OD_RWPs{G+7+%cI8FJ!wb%84u^(6 z>+V-6a@eer*$Vfl7YV+5TBS)abJw$xm##T9UC z{`tw*%7CXY?9A!(dTwrWXh?8dPI7nX`W%G1@a(fk^SRC3o9v@U^RxNs=_id!z)#B= zJ{Rm~2i%PaixP&}c|l-7U4iqwZj;{#8ZWGFWf66C})2Fq`x4P?3!qcz(xW01k@w8#UxRZrKgWCrgUO&65DzDZ2 z&Q5OO!SwaJ*>AoP7{B$l9^+AUwNl__`PRx;YxNdUlx9Piy~%N!fGv~8dG ztdz^x`(X&`2ou^1QKP2^>DsXLe9?G0nftuaCclWd{G zUGA!?>ZSc))ywwLOnFsO4qxZnbA*i5yGubO|{nFmtU-=bJQrS zM~xTR#AuCn_AebeH_`Uu#IfZi*U|WkjT7Tn+sc0G8?cOzU)2PTemO-~mj;@sPryZWVT0Qidnkf)PoGttJT)vanZ^eJkXqRnQpO z7F%Q9QE??v{A(xH3L4~KwmdQ*IE@o&z)|*XNyz~8RyV^4uNX6XEcH zDdLUkXt^?i3QM`JpSE9Uv6pHj0ZLM#Bjj;_yvUtz%8M!mpKWAv=oKvsek9U10;Gip z`@BRy6OlDz6V}XV+H1SbVz<)g6QK4}fJAgOq_>g^VH-tAl{TMWHO)Tikkp4{t7WeX zQwD9R{3VytCj{B2-d?8DQ*~O|fGmqPLSr*>Dh^i(EFV%$w2yKI-_)VHx?d6KApktW z$QkMLh=T2igJi33F&^PU8Yp#;c18S#{SG7Oy?Bz~z83WsVL(EJMcQ+PIc8-VU2Fn2 zNNm@+vz^^R#+O0+6IYdRb8*NrbIdD(Ugf4xVU4zO1d{0~*zXV#!`GM%kNz$)~pq!YX z3W@ZqF#BPQ#Dr0YdnP@K!yf7*?ahuiOgCC&Tg3rr#1Y5$P}fBXIGx2unZ z`sH$)f}`w!bA`G82zxCEAzuGp@J#@Cb!|-mxJ`R;o9W3tEzqq&9Jq)CuX6=??cB=s zyu3c2d+_Vu2pkr2JD&~Rnia%c$PEoWn$2Ih@b`YOyX!P4eBis+-~DJ*TnpLkd=?U1 z*qoos7Zw)yFt9l%+;_oHVFl#bobYI2!}Ix7hT7Tex&SkB?FTz=1hU`E{+SWzW<9|*xl7#9oQ{tFdn3$4{0mt3b_Z73L@agLB|e71^@ED zJ-tZODk>~@O8yv_kpK3=fDOhnbw2sO7%a0B#&`rf76x3bB!m<1+o}S9 z&#NYhjAj!QrRcVOxJ4o5#*012Up?$Nb-3!`UwZd!Kkpr1u7?8lZgkKys>r_L?oZ0ei%u&nLH@$skirk|junD3!b zr*586<4E8Ce}uZezp>tEnu;yGquNf0(n$+@HIb{cYwPIo7x52D`ZQJZ^0~+o`YN?W zfsOl3Hgu!@IE@Pd{mprc9mN`pX)bbt6!OY~u1`ry0W zEkBFjt1+dHT{k+5a&1ld(4BI>{-VZ^#Z&gHuIv1=hdyWq{c< zh)v|>2<;CgNUhY6B$$i+NbYqAvdXX0z=<6l#A(U-G*rt$18~D$rNwaJVMmj>-7qX1 zSb$czFx?9c4o9@3Nv<23SowC`Y#MH$Vxd7Fj0g}%{SC3En7lx)S@=@?8;L@JqyDIB zuxL6G6h=#}O@t6&p5brOu0ns4kmead-<#S8d{KZC-;qBms7kmM8PXRcLWg5sSg{wB zWj%}(+Q#JBS?lx*B$G_(_0DK3p(?e!8Za3FrYmQt|3zOV#Mev2BvLG@kfv-GRdq#D zw4gSUXs6#hMdpT%oSi;zRh{p)X&vOdN$#K#m?I=$X-R`mVYiOnL0B_sn(ymRFY=Q+pEmq6O9gx{Rz@Aq_p)0Hdb_?NGLVHU}QDND2 zByC4#g%zn(6QR|cMCz5b!c8(|nj1)=VE-HUqDI;cU>l>Z_I zEhn9il5*aX7Pa_Svx4Z75h!(~1aKEqX?bH?bfb9=1gs%Blt`sLV}xL3Qb`>`r{qX7 z5lW6F1MGtZoSz6zB|{z)%JC$V3?{VCFX0*U1eiX11d}}>#WNc3<Ah|5y)@;Xd!FY!=ggm5izY_L{taI#m`hcZ{nGvA$D9BC z^}+n;6M*Op2B4y`M~U|nsmz3IZfXhD=L`zrm`7H{XhB>uWT?DkvjX?2%vO|uEJqxj z6z=*TIXuh_;W#VWzI^%dhzcD}M5pf0tUXFUfYj^36I7)~A$T5RsxT&i$AlZNOisPO zFTd2+3b=2S{Zd=oR*MjZHhJUPWMSjj?)dDYve(!iJW?TqYV?TS&zcbygwkroTl*{$ zyo%)Ctiw1f7okN)d(j8EuAD`th=b^h4?8sf2F~6Ys|2FoK>I(O-J>NS9Z;i4WWq|w+*;jXg{66X&~%6{ml{D%Lhfu;mXThsmgDPF?O0^eWRjwUE)(|&N!!9yl6tgk) zwOq9T`viJy@PuiR6DRC^1x0h!a3{imG1{po(WUjT&b+{vFq^@m0%3LTJh=Zt6|Kwb zWMVL}7!+2o{5N1+C}69%VDMNwZ(~LnPS0{iU(n}Rav_n{_gUObA%xz_&71}|^v;++ z(lLh+_LCO4P+|(H*R3W1D1w`vSm1CHx@8!Cm}3RSJA`Ex@Z`@K+J)hM=GS6PBOb%}h9 z3n>^IPEA+I~s5YDTO68goZH7RF62M9d}ANpfnDxl{^Y-tOD>{ zlgeXY>XB)DToCss$gEJ6-XTwc`?Jt)(_J=+<;UGpP5VsytR0+PDy0mo$yAOgh608Z zVhm}QkYpjiz;c0JJg*55&xzntEi)KKScnO3D&6}H49_emXXxmKrffLS#K_IjLvhuK zMz649L#{HWRE^$T3ZeyW7a(nh=@r;;4h%R73vUPFLJLOr0MLn~^cwtqEu_TAXF2HJ>wHvGK z{l#_%qLA$Nt5=(m$KdxDU&Y#fhyRTu@-x$t>_U6x8`x?m<_cY;NIC)oESNY7>3xbE zAxr|h{8!Zw5+jff7e`S1Mee=Fg)(n(iwYd{aL|ZVXvKe376a&Si)Z_87^*AH`Z??g z%PU+U$%n(rxiTz-*5jv3CDm0fSa`Su!sQA829+)sWnN(qJH+9`I67#`~BTY_e>kBN)`@G1a! zH9h~2^xPF8(3gY)3x^i&j4+1RT9!g01LC~2G(+eH3r;NIrE9Ax`H_C~Xf2gm85@0L zLuI(aC*-vD%k~)3lO>|Byli6a;U02od!{#Myw4BQ^tz4O+()w)GMA0NTtqp2Wby4{2S{&l1iP2_p@P%DHlG~7&!@(* zG}`WSsu61^H?4}*){eLXt-3x4tiVh<^A<4L+h;a+=Hg76Yu4$721!1fO4$tu4*Fn~-f{}pTnDfnnbujABI^n{7`h{H183}@; z1Kin(tRsPLOQ&UlD=oB%20aEIvn7mqUo?QtfM0!0FQ%3(`g=JrcXkWT_TJOi6OViE z)l|DdcdOkfJlEIg1xYol=w391>rj-20akr)WleQ8a)E)h0<|!@Y9RULD3U;ObuS)4 zlNWVpG=a| zqBGVFNTSQ>kYy@hx`K&Zmzpa;FvA7~h#N}E#|w6-rE*g#BNj?Xgkj%Yf^M-1Mv_=A zy$kV_kYeGqz}3-Y=gWt! z5QSy~)Y1lpta(HsF3NAQ$L#MOM&E_mxHj<}SZn5jZx7yYnWmP8=C584^xs3dl>AitfE`O!{M;%^QuS& z>vNC?C7{A|`zI=>sfL@6%9vPc{N?4aocp zdwPTdJJ1Qn)g?5Cg~$b_4Hgtwaz$z2AA$UZ2o#?#tP%zc7c8ya+phUgg79|Jl%u`9 zTT@~k=oTW(z=rIZ-K}S)2T(HQ1QOASc2Yti-GP()Kfeoh_=i5+-sy>4Z_a=Ha3p(l zFfQ~o9yt5hJ7;dq(-MN?f$Ph!HecP@{cylb+YPFwLP=GY^=T_eDU(6p%0Qkg6<*vcO&e-)_oXg$SGJ7>%Yc>)A87ipV|}oVDG!0R^Z^Q(SZt|<>#R!} zoq{14*ix<)4Bo&{SyC<+SOMLbY#MUc-9Qxsk|kM^R3|Lg0?(2i4+<8ekPsYL;M$H^GYIM|Cd!RlTde)XKv{wE zmYg0H9&4~i5uGIfEoe(omlc4@20{aqpY5~;W8hq{Bc4N!M{&5x{;ZA(l}LcDD@31J zaaYcQM$3BQJpx0~BCX-OM*e({4i4?8X4GtaphNx@3Kq;-EeaSIf`!r}+;~%?Wdk90 z#K^#s^G4+)gu-7z!7(eg$#CQnw5gtB00io23gbS^LF791jO2M20 zOmcIp!X?8jT8OCzq;u3@#j0Ll?1sUH(H0z|(iwe6@>rfQEf9<%r5JTw%)CmW(I}O7 zp#qp>mJ@04a=DobPw+wjubJS2IChV>Tr4t9sB$C-xm`#SiQt9T%%seg+Hh;5=pswQH{<}HB|M|_C&VMTv zH1M~+x9h0ok8eMGa}_ou0bu$3>*`8z5iq;BQd%rOL6cLZbf;W`giG*P9=t;UZX@GO z-$=I!01M%-uTKjEUq85b@~-o&g4HVC4l?%{MT9LZA%p|CTh$V_sP%B>kX;NWXTa<< z4c%9H(2iHsJR@oqg}`iLz&jmp{D8c>hvdU)44NGI*DWpo-+k0FaJl7J6FpE(;%E^N zK20=MDIEv)pHqaT5~v6*V{G382Cgq%x^VK>2cfB3dgsNRN0&6lYj=IGe|Kv~PFw1< zKI{qo<$U`(i*FkiI)C}p*KoVzLcZ!3;uyD@GUe+-!C;73${F;-kIpanLa&=Tq$5w{ z001BWNklR8ks}p6_bBO=dwH{x!?Kq^8uT}LSfsy9bSOME*(EqxBaw2~izdy($_;)9IQ&Joemari~a#ib(`#ba+#9kqXqXSihaVVtYxmG{5 z($Hu{IyQvd>H*6XZMA|sV|5hsDUb9pP3H458c6M+l^ixY3dXv}H+>(BD}CF>JuB zVc4>$vIa|IU4b&_0+?-q79#@#qYdtVSOCxllpYx%hDI-g1y5ptiAbH5VgA6SBq$7zo;lL1rCGR5>$Qv9N$Tf|>$_4}O^wPYW1A9K{4GK}Tdb=P6}Qsd5D(Fq@EQ`&DCTQr{He zIM1F144fgw3QutookC?W;yIY|jID2;cT=(HFbB~o)wIOaD|uZ(>DV+kyeb`4zQ+z2G<3T>uZZvB;>b+_qs3x* zf8^cb+}A(M6=(M4(B{mau5@98EYNg4eWU(p;3pAQSr{xwMdf5DY`+%vDpK#6G*7otopB=#m{QP+t zaU1A%D8lF@7Z~%E;#|2h|HIsTX+=o!>f+q$UU9J^2)sS>e4(ozq?Zb47?8TsT{q+> z)^>35%!1?gDF$Ixlb^d)8N*MK=l^}QR8hM7^@LnedL03$Tsop*#EXl~p`oM~rN1cn zLe{y%;WazFh&*==8IcQzZHv6|$$*cOHiTObD5p_%;(V%QpxTObdEm4P=8*rs6$Wfw zy4{0CuIm3IG(jCKFg1CYx^*Vmw{y)pJpAp;OT*D$y!0Jh{MC-&>e6qm>kXktox_LZ zdZC@pzx{L4x4v=a+$0@Es`s~{+O?~8s|^fc1dn|B(fOT*hx$&>!Q>U+E)_6%$%}DP>iZ~?x^8RU- zi_>&lcboi``3k?&)29Y;X>+=}8$b59pUKDNdS62|`wC-pAIUy+V$D}jN7&!5hKUcf zI!(V$h4w1m!iY&6(!olkF*5gA!whKbgUyHph9QX_UkbJ4s}Af)4<{2h!tf;NH9Q8O z?H9-vJVo$iwa0zb7Dv%TZCnuBW&>1fYU5fnP`6ftsk0uPN!$rT|EwQ{*%!)ZEw{kH zVU3M@;aXN6VPC9g(uRO)t`+9rI7zVpY|j4$KpJ9bkInx@EA(2qc7G1DX93%Y-xFs6 zga5}?jFshEu;&%+W zxf_@`H`ZB^4-N1I7cLkIvx1ky7%$tISy^DvB;?Zw+AtKN@=yVzX9E+Z-S#Fc@S89T zy|l37f*gcQ%We_g9E~a|7D@~4btmK(gMl-ywNRjenj?6PSSW4O7~dcs8a5&`)%C~Q zU$qRD)8aLpMPp2Dq!|g@;5PtXhkP69ui42g4tRc1Oo)}R1Dj)~$$XzpNQi+pq5;@s zGJ`V65ifVbW=!nlHg>&Ur`MYeIQSV)n(qK<*=H^uISsT73I;TUyUJV(_PGLK=E?u`uP&P&`BVto%n{$1a9qvbl*<@ac0d);EExrHku72uaQ8 z22m7dt}(I21c)8lolA5+Kn=a}=^rMM#PI)1pp_`hV3IoPT<_Sr05KI!ZG?Cc{Vn^)$Y z1VcVCjrG|c{Q5HbfERms1Rb3Qaz+sg-PiZ9j~z{*&Ja*1Qwg^264%`Ui4g46R`tuR z2fIX}4=jQK;}yhhqk!P37-Gj5duKUK8kx|DpiB~x#z!hOu`oNEqPy`~W2ry>rI!J? zC-Jnv4U}gOk*}IgFq(EAB@#XH30Qx7afT6#4GylyMyCfxql10)g+Gk0_YGim{cv=p z57TU7!2Llnb_VD7(SZ-}OW*sQW9d!$QOvon@nDD( zxQ?uIvj~1R<7Zrj{@<4Dzy{Y5a;zIt;99gA)B|Tjg!LwMQh1T7kj#Qtw?8RayLb45=uq8NSOUBR%Y=L-SbyQxHUp?XIK5Z zb~^ujdT~x$|B*~%JfU)?_0ok01@jeaSTV>Y&>G`IkkT=RO?Z08(pqNbm35-Fm!qqH z$D``HF%f0SLNV?f6b(f@H*e#GEgr^<+|4D}?9i>_ku(1@(5VPsSwR2A!RjM6-;v;v zWh@T}Ww-OTA2cm57cBp{?0@;vIsVh!&(Hq*{P~OL{V(?Rc6TF7KkPmKad`N0Q!zeE zoBOpk+@0QE69bl1GOc=HOQ7*H<^ZPeFY`(y217~I##5B*vN-q!>1(a(np=!dw`U(7<4~JVxF#2yls=o`8l1M>%v? zCH5k)VYdC^+E`+-6RCZSW6YN68AzP0z<{~}{$4_2I})&r4$hxMu%xac3p|(r8T=QF zID>9wA-F?FkAV3K9hQSI`07<%J^-1>bhnX+F>z+Belvi^Iz(+4Gxk@+McrV)gq&GA z6OyB|(2rDPG{K^T{Af(8b=@WtkFA9W8vREm&agycR=!Dx&<+$8noOBrXM$PNGa<+_ zWfB&@rHAxRZJ11-M5$TS9Fk*Ep->x`0@Kd~U2FA(zcRW;_H%9SR+}n4Bn6kTU+oZny`oNvr6HSa5zj1x2q#8Sv}}Rvbu=u zN>WE|uGQ5cNgfYwkAOIOU<-C(z)Q@yQzC|p6h|nW8#Ga@683+f(Enm z7l#pqVjYU?%deORr_(m*Zp@{HI~WAG2J2k5EfJbW2sJqny0*59x5S*d!Euxz-B?Q3 zbP@&URt8izu+AB9i?aj|^w{`nU4-ABj{QDidPb*osPoV5!C;UBBj_VYf0~=Ckp=zx zy;;EM0`bu3=z5g!jL0x%(0!@c01t#y@hGOdU!AHBiVgC49}GUkfWJ)C69C6Jj1t(^ zC!l+PQIP;NHIEH&GP#(zn@Fzq^wiWr1;(pn+sSPaMY-4`0zimGk8&dfy%khk)3J4k zq!@xz0N(lJDkJ&oY9bK_8Yfm0xJ<5cIP`34HhJYr{26Pfs*#{UpJ)5M%Ue5y^6@w^ zbDpdZjGj9;(K~?L>(!pq9cloq92Dhz~A}3 zW8VINlLMgBZAhk0YC9=?~7lDm%#&XdGZOe6p$u^XQYDNy+d_?6~aqnRmRI zL+$AvAIwn?BB=^pe10dAv2Im%Pu)LL`GI0;>gdNOlyimm-oMmO?D1A*)?8`nRLGmP z>72V(yEash5%jpj+v$gomJ98LZwFkM=dS6TM;xtv^3lvcj{W8j-g@unk&FIK%ZWLfQg%wXMz;wAp+(-K6uQYIh-)&gcmSy8Ft4+ZUJH+s9u{&Hd-+XSV^f zGcR`ceuymXJo(p?f8Y4_)uUG{D=S|m=5Ypj7ryZi6Z5Zjej46t$}1K!tg$*ip(qsV zYM{IyBWO9d3PNB-zc#g#BHmf8Xw*Zx8X^W83Qek!J*W;%h6pLuXl$UThh&ZVkh~F7 zYdun;0j3ZO-g@RKgyN^)FN1R)Ym89jHW7%8ptLN~Hz3T+!MJj}qNW52K~fL5N%4 zijpJFfQCT{wZIh?rM(1`W@5E$NU{^k66po&t!QP*Ghy%z3t+d^XxCY|n-GB;1h|jO zIW()ta-$W7-x3rDV*u^I5}1yViB(Z#G-5dncM*2P4u)V1r(pngK#s+>VWeO=igb`Z zV-}qO4HnuMj5muML~@Nrg66CA3f)y;F0Xh^NX+^c<7dQA@^%-Y&?chL85!LKyR5;w zY0B!pX+qO4QaHGzFarlBBVFY)z+y8@;Cna&60A&K24@|3ds6lih+9LI-PTr-=G&;!iPF$BZe zbQ}&~XC_JJ?C^#M#lTjMsPuR=gt6EbTg?&(t|#1K)kq^QtBW2Z=p~ZdvDD?+kcg6a z4!I<=%jN3m2wQVUTx>^j5fpO^Fc!hChAt?Yh!5v_gu9mBUkI6LE9!V zU@dmQzB~q47CobkFepq&N7DDAn8BA9%p+_(Qq_EKB!}A<;PMR+7E3v>*qJp_INds^ zX>nNizN)2j(l7ya4ijZFf;f1tEGm$y(tQkK^((?Rns^JGeiGR5ozn*{oEbVb z<`(q}EY#&yXkF?3{(h%_JiF3xYR>WQrP@>NfqJiE+`V?}!x@5*TNg5k0sCjZ@ODq? zDl_i%UwVJdT{>>KTgyvdLK#klDlJU69;CYo89M9SQ`a^&?>A(aiVOSDz8ulT9%B-p83gWTS*YYkFMsuT+2*?77{U1~3`qSopNAdWA z`xt8o+reT6EMjA9OrU5n#4(0C0Zq<}f+a*oy1B)1Qbw2-f+`##BM7Ci+_;3>NTxN- z#2k;295wRj%lAJ ze%C-)kxrv^g&^t+z)pyxVaGCaT!hnFWHe~HxItwn={P!VP~UnrMFmPUl8$%X_tgu?-2Sf4Zoik7RxM$ubQVT2nQjod8~wXF{rlYsy-fdlCM))xVk#iP2gSm0na zxL6Ei2nNG|aNvo-U@}R^8{ndE9Za!EHTt?3$8zCHbsY-JNo)+e!O3zhU3Zt^AJXVEgYAd(RC(+VdEh2}R($rflcRM%pv1T5NwiZeVh{H_H#z;aM*V$E6X zZ80XeDvR%xDIiBNq6@L2R91|(Z)I_ri3n*#5*FL`6x0^b3Ai(QE?>d{O;LiCZLfDyp_NsC;9NWucrp9>hlR#MPI zAOT2}iVoe=3#W_KNV7d3idtaq@t1Ipw9oGIlL(C~a@6PZ_-Bzu=tn-oK(x;f%0~23 zwAYW=-zYMJMO!foE#?-xN4_3k-_QV#BfcSD6ybzGLL(d45gBm!91k#t<-p{yXxosZ zZ74DTnWLCFBGI-7u(xQqir@{fIm_W>A|oAQT9Gi=jJyR=+^ce+aFn6JbKF!SixSBS z5Zb|JLOR-5p(dUq#J#5Gg9pz+%$wUV@jTcz$avwwwg`5QLix@ws2d@i7+}vAHavu1 za%de)pkAY}0wlU1mSbefdq z5m1*ek1S?K((7{~LHLxT!+g>;^~oENwnZfIa=vMF^y6Rudwd*e3=p)L@tZeSKf8vZ z>KSk}#;zYq@6=+R35phL-QIqfUqezQXdahqpvp|vr8$~V2{LU1_%n&E(!dA6swgo6(-!n^|| zYEkIWmRk9Jzu~9(XD^G-dr%H#e;c|m1+6BfH;dmn_Q7;Vjmq(DIX$QHe33_g_g6<# z7dc4vE7ykZ=`zL?-=cxGhek*llr zuPZoTRK@9HiXvLTHL6>S`f*EV#a!q7?atpd&EIHhn(t7MsG3gZ6t%Jui)~t3=BhbH z^qy`dn5v~_jy3AH3@o*LgjJ_}e%F<9dBKm$*}0H6Pj^BtY``OW%G>o`tRdI6oy+B# zIyyRk==kCG?br9eefjO(S1cM&f4936`tHS>3*uT6YB;(=r4V*LTZ7m_V@KpozdxN; zpq4Ba!+F#H|BEwI{CT{)y1pX>;r1ssV0AZgW`D8q!}PAeHfpgTFPoDK#MmO zkHZr~PPG(MjI?EpUde}Nfu2jhdNIG;NeUMslRaf+8Z5$&@I+&(Xqm34NQ3SovjONy zAT8sDqGeW-r|f`1XkfC96dM=tCp@j4;UHnf9HZqO-tN6@lV=42=# zFwr)X>+rp@CDfxWBDT(AlZErn?n)=-o4K`QbBm=FU0yP|Xo`z%;7nHDgU^L?u9T-9 zK8#7O!!~tLS+;~AhQq@kSW=nA8Sm49d4>39oNNL23=ju6lv>=nf}txNN1o#t9^isG z2cpFY>lGndV-_%~&PY2dDFh}9w?S_Wnw@McVkZj`LXOHcHj!9(2AugU~hQ(k2SehB?+iEyrv&gq%rN(Y znHdN>+KhyT5a|~nWDrv+j@Ci&Gv}Zg!_eG(6?hI6PsrJULs_P4xJr_d#8i@=C zNylmn<$KAXZk+?F5|M=@b3_#I0|HEg8v&boC?wW5f<`aqvDyFt5IeSB)_#eyg>xQue*zle_`b>rxf*V_B z5{Xldu~P^3od2oK-?v{h&+ly=apAXA@h1~+>61r(YW^Nkjo~f4XVF2yM4@g&2tI=~<>TOX;AEbrn8WXWZqOn`iKE0)lN6_~!Eq&5Z znu~RQKi|=G_69^ zzIZaV-IYTCqMFN+-|74g&dlW0655+r-u={CQQ+*z<^0i}1n*Z@7FXAI|2y?_Z?2qn z9p^V3aZ~w(=r{LYj9}gh^Drs>ia{i?2*C;Bc~^9pq|s~t5<8PZh1f_eG&YqGz<{AF zJx8=)dkJ!8FBsEWx|9J+N{mB7W^9~LEYy;9oUmetSA6zkJ*m?gxc=a2A=?o3>=ceu zVZb;sYbvc<-G)gchL3~bfKpGD;))S6}7BTw2L1qJ^ z;cJv1Vu=H&CPRqpj3TYc1-XZzzkzy8W7XGJ0~1{rsD|@Rx?Lzi%W?ez8CRIA$^_k9 zLJ}J+iW+u{uG$F85(5nlcGqQ`^6gp>1$MhsN|MtJ3S|b}-;7J7+vzgZL1!^Aov{Rw z(%=H714CB;M4Q0Df+E|TdFf^Dg4_l(t18pOWlq>!o709quV}Fix8h4Q*fhLU=~B^1 zqRAN*AY5Fgm{{0FLR9cl*)WcWE#yg;sW=BRI4VWuhmoAb5v<{1kgzl>J+NlP=pG6l z==mCS1~p{G$vu%+&9I_r`T{w*L#`15wjj%*rkcWXU?Uh3O3AfjGTKfarDm7MlrWM3 zQ_zL^x-$o}7?)J&VITtm(X2(=3wlt91N#}MdZ?}k6VLx+>iU10&Op!$D*yl>07*na zRPXRwX|JUVJFGOwmtIQ?rKK>;SrurZqh3;zDQ2V@?ow043v-YIjiH924xDu}139Q% z*ez=%(!vbOU2->ITMigE{Bq=Ca>VQhzbrBPWq-w9&-4D&9U>>CMZnMXc|Wh$^TjNr zR}j}D?W$ZFA(c7htXMp zD#GAEJSQs|gt+IZVG03kVqz%?M}wk$5`< zXjO?E;JFN@R4E;x$;`%za6ODgaYU7G%4R~D<}tbE^lP9iRdbToRdA&MoUFku97j9ZTskX932@uwQcd$lSKOQle%UL^c! z9cifj$S?14QNm#Ex7N#*?dfr`_}5H{L%l)RG0aE(G$onM3_`C*5C?S7Y+le>f4jR$ zh$*{LIUL&X8AyyM%AdW}`BMO}^13pLLkpVf`odOm=IGF;gKqc2um64_bpF&ApB?d5 z4=yZtLtX8Izwc5Q>h^xr6&e%pfz9(=D>F5cHX$z)vPf1{JOyP=?dTj5 zuyw+=q~a^Mp@q`8-H9x6j6o0_=?rNGsXz>Q*CzwGN`=i{y!i6e%U7=!KKak7XW^h>fQ=CISr?_OVus& z+m;`}N4Go%q~rrvp+7b$U#CIfxEMDg>j)H>>{rKKFYls<8cQJev`#QzHE}i>W zkN6F2dIgH-z-*C{1>}X*x0Nk~g2qL_<6d8BD|>)Ri0wXKk*{v9X|A=Y2HGrvU}&G^ z<8b*3azo|}>ygmrM&vw0mgQ3=NiY_H>iU4*jq=et6;gS)aSWnqMsPF zRroA-tw59qa-wSxongVi`7nG(b_@Cm@fbT&tQx_1VMel}0LgBd#o|{LBU#4mm3AYf zT0&(J_-wQby*1(va$lrF3;EqYCZLJ{X`|(rLUbKaTJ2Y0OaYdKc^VeSNQGkz+0Vw2 z`}-{w@>oa3eL>!l{YQX!=Snas0ePV|IF!IbWDk&*N zfu;OI7VGq?1W6AYcrj#IAjHtp@9RSahsxyu;Vp(9T3@WUn)=F^LumyR!v(BECbZlE zAq0lvVx(|DXGKFWhRdu$V$NilSsOSPqlwVqGKZPXhm?8@=LCXT>83bC0&!SSLu28K zbPseccu-7O?-9B?;7XwD$YT&9EXa$PN)MVDTr6Y=3L3+86owEBSsZHvm%>Z(zHPvd zEUaM!KMNE`{BoxtbWlPfmzL-RR!$&nWr4d$!mmKG!y0fMbE__=N9cf?>) zUzG-ZOykG61qFuCVI5;IRzxUn8)w(-8ipMy!bP#X7xqH}7KGLrg~J1|91o)%*tQf@ zhXXa4wnaShfJi1Iu3$3RL}4>Fzj`VfI~NlKj>ckf=l8d+Tvh;l98YpuEfGq5M=`;^rWVTAgnYO6O4Sc))qj%v0<_ur!B2-`-D=!>u z$I?vqdVtGQy>(*kNLzEL&UszaQxX9sj zwb#q|Vhuk88&%#_NVN^RQ8EwJw7ZL=;%cpe?@blb^fOc`I5~`F*N~f#%FV2^p(+F+ z+%k?rIJse1ALALKqr3UwJMWx0(b2$>Hlu>uH zas_7QKb-%IT!BAMr`2jUuT6zV3sIt=t3=3A-f)1o$&I{4FjD|{>&n4qC%&`xkfQSL zuBEgZHw(HZ(@I(|2eI7d=BBzzrmjxODGiRg4DnYu@Bsqwf8>9cfKwBbxp~B(X9|&7 zPVcE(Wu;)VCUmIx>S+Ac86dC{lEdvTF!Z0N5ugEN#jNo(V7SkOl3y|%Jz_I3fMx(k zAA%!UTc`tphDW%SO|b}>)R)XbU8O$_DOS-OtAOP}ra5#3>-0rv*dcF*sJd02x%&iu zTZQ!^dZUD#T0R41R;Xuy=D7%5*jHE5ItLdp_-{#F9k5y0Y%8|Fb!c!9#08^;BFonb zpRdpNRa2{gXYb+O#;?GMOQD0d*VWWD6$#0$Lmd*!34M(MrM^0Bej%ztH-o)*wgxsN zh_CP#4y0LuR>A67`>e4MgJ-*)XbeDZw8LtIlq^PL;X^fzvz8{@1m(2qVi>dEh3UvL zR)djqMU4^d4FGM6U@Qj9SQl4}+#RcAYaz7FLRO7;S(0S2U`8y6>o7X(oJv<3E1-k6 z%e@?0JO`Xej**c{hd}dPc{p4~Sna+oY}ru>T~_5tMJ4JNg!`hrVdQN{q8)fdrTTRg zg-8y^_aIw06=QV5RMLGP1AGn2gQO8%DzKP@g^(Bejc{fw+sAn{Dv-GJH9_NS_!95z zGlAb0n{;#_A#qZuGFlo8P(Q={3#$92wTF}#f-CNV*;unldyLMgHARc>3bT|d|>>_ly- zCuFk%neLDl23;@#t5OE;hq?S6ZX1G|36Ex+#xZi*;bY2HJdBbCY@4ZpZo`lnA8ccB z5{?3qAek@{K!mHefhXfM;P-p{O05+{XA&s!fPZ|NjXEtH!XWRq z05WP0u3f`GFTcwjauncJbx0`mt{`|iKRKc8kZ)YSnWc<6do~L-^!3|kbBM`Wz4<EBz$?Jgn&6!P#y)f;@X(7EQk5&GofN~(k<8i^`hR@zRK5jnp9oMhMehc$w zd5trULvWCd4Wz{D9;?gRZ#J{W3kj1}WvTGo8|0i))zT1GD{y|r z<;@+<0=9?Bw`yxU4lVC2FF%vlmqKh`yqK0FU+Q2$KJDPNvJ!Ruaa)dhA8I0~eEtp6 zYS$De!pQ@K*aL)C^=9-o;P&?aS?sk@4Vw#;RX)ov7Pkd}o0|jj7qy>Py6I5$;6sjY zc$wyNT0!Oih&unDrtdtCr?fPsTsR80A=GtHq*T6i`vC^jQk(G$m)ty(#au57TN&HP z!X+|dfEYFrZzMBUb*_HPZqwb3FUA;iS?1hbZi+j>EoL!}_>*pz82^uZJ)ZB68$v6e z)`C*|{5)T;=a-}BzEESdYl=R1bZKeHPSehN&u7D50QlkZjrOr!n(Mn*5(R8N?N@r| zlQcwEvCl?dMkkP6p}S%h><|E5uD)@$3Y%F5%5Qh*@P#I0G$;$Q^){@R*jB^ z&)Q>PCJMQtU&Gq7XX|`{kXI_~i-Oc0>K+IKYKGCCB&;liOK5fw7jWqspx5VH3r z>N%@Ur15~8K^uA-1p88TRpaDrpoF$tQUPUjC>Poo?iq>~h^Ax`P4csWDLdd!f;lqT z-fXrfHU8gJN>Nx0la)Ei*csO^mL&Tlq;F(W_-jMDCHojCD*NGJ-&4D zq7jv)#d77)wSPle`?|)u`rhp78r#^MpC9MzqZ%EFo?^Wo4 z8$kBaBYXe(=f6Mv;fE*Rf4{xG{o}oR_wL@^v$bWL!OpLIyFIwPv57xv z$hmjz*N0mb_oaaEn})tZ-7oHcasU1=2z=De)s7ngdvFh$Ut7XOTLkF^T_2?D_N^$_GBNm!ET`DlFhNh)9G3)}gd`m+pRClFN`suEj@ z{>l&J+K;?i8)0HM{Hh%c5kQHiDhfnv7Hv00xxyIi*1%DUfx{toz(rCjHG}g5yQ&K| zR!|MvM%k1#BE5>T8Z)Xp*;q0Q*%IS86N{y1h|B6O%*1jo4jNC- za4t7(M3b7`brlB=Xd6tfqwzkdt7GafReN9 zW8L7G$utV*=>v2fF@g3{uEcu5?%4D+WO+Jg-vCFU-T?H>u*^yJosvdLjo}O}B`C+xs3qd15qq+g@h3zPs}sv+I@fD=XIwl7DaLH)pV10f2XcVw&et#;|<% z^Of^2{`#VO>^%v;DrGE}YXIRAau>wN-Dg)D4tEZ^9A%uBnLzbW?%J-9EkXGZ2DXwP0BVfk$U{OJe#+9hPeWvuU;YtxYzU& z3{xeA&wE*w5<+7J{@MVz{>Y!D!IGgzmB0|#lX)E*+U*K)4Tgy7Xx;VNYx$k6tpteK z54-QpG5hPIlOJh!1rSDLpM7a0pC5W!HDqLY*Uq1Qdi3+7hYuhA@5zrp{Ah2V-qWUb zee3$xoipE^dHneC<-c8CxooFqD~e*Vf7<8PD$iZJaCz&&!TD#~yG|;U(l~YgbY|s^F0Ut-gf|O2yAD9hgUEBLajX! z*2eQ=0Pt=V7h`4Kop+4b5ctC*C7effx5KEM>pUV{7Ya)!#eP-^3og=%Bca<6WhZuK z%vh!HW*Qfq0$S5YX2pK8obA>5w#phJESY6oa&u(bmg)k`s~Isf%?=n(wg>WM>jD!j zgxN5TM%(V@ohC>4cD zc_xI?&$Zp&*vN;(Rz`b^)x}U_b*Z`(WkGC2piR}}yhb$^RpeH}$I(GJ^dw@cQjPK6 z8gRIy?L+~6R-travMpUe7+qrH%i1?b<8O`_tXzlPAsxf9)WI4!H{4<5cB&1j)}%JS zG1jMs#f9}4#lNv!Zi?k;PSp#BdozVtcg|q0dkX%^hBhaYZ482H7Xum`Q-?H6ZZk7x zxsLSKO);>Np@p`vVFI7gHV?pwjR(hEC4-Y;VHA#uD=THoC^lb0B@Eq#oQuNjCbMG? zSL$de$PY}GWjE%f?*DUj{Xc2vclZEhfE^JLK#v zFJ^7CbEYZ8iCT0vW7ScmJ?WO(ZmZ~e?0&fP+FRm9atrZHF3pQ^p2>Ho3U^Ll@v z$!G-xs-}|9^Lbvc=Zl5+(e(0wYlA+Ym~RrTc4ijz2qN59%qun*!=3ty9-6QO$6@4e z47U>Z4Ob5j_XXi!YQ!<$ckCy}PVwk^p)k58%G|jf8s2O<{M*gfbWFw}nRw6BXU~vm zupcB24H-3IaQ<;@d;ba1=5&9$sPqyPC@UR)qe<+O>0>&Xg)k^)h_oJ%hv1#2!ox3!u;E5qDB=i<;| zE%NbteR-KE@VZznucar`2f=V%HQ{fVqc|LNLc%tr@K-;p{FncC;dg7_aJZ2A+*j;H z3QL5TuRxOTTTMvcFb#3jpg|9bph2xi{F`ZP1YLyC@sA9#`5h1qySr&f4X>U6U?Fwp zAdZ6E85tb(c_C*bvX9j#u%Tg>RO zQyA_8Z3np?@cDdZv+uDv@5|>q^P5MTN2$Y>&7-3{Pe59rqfWIT1DVj~^o!kxPw4{T z@tu3{(F#da`sW?#wCH-QfSf zUSfiN*6TgJo2>*$Gs^E2@b`-^-f>|1nyZP#?9yUxavF+6@apWBe}DQqb}GNg4k`NC z8#&?nY$Gqo5$tt(e$2q}8))>^g4Pm@YUt28h<;#bm{p(NfclxpsBDl~ubeF?GTs&w zhN`&AL9RjzthPj@ivX{Y;;b4(dr|}g=MrEk!muJ3OX~&^a;1yN2N9%1+*-@kNjjA? z0wxUKFAHmlO6%lK8H`5Sl2I8_C`W*95Uh_4^)3#A3N*nC9k`)l+=JqZk(<}5P+P@|g=5!8%PvX6{ z`W0k96N=iq?2M^Igr^9Eo9S5;0vql1sQ-mA808FIV9bQcD_H!t8*7LpPjvx*rvS`d zQ+6P9{dJD$fZ__1=c#%lQCzz1x{iKe*nX#Kke3Co5s0p`UZ5`K%tVVJd{)-he2$lW z4zCfBV)Qg{FA||Cy$&f^gsrs|We{SO(ev;dDN)N%R@MX8Z*7mVqNjl&xe6c&z=F%ynW1ivP5u&d>PvG5IHkLwy2VH*N^UD704JR)+RT}+U{g{xdw*@(pKmvboT zt4yGguni>*h^6dB@UshvA7I)5VOXBda|3Xj3#CVh+Hkq)HK;xU?6!^jfzRkD#!eY& z90B)bFPm2eM2Rdm!AyrGRhE!u(Zd3js~MdIxCp&3dzTPp$7-q&SyMLV`8>ml@*KOFMLQ<@Us7td@})vc8~FYyhWEcIPGKfo z5NXH9o5Iy62120|1HJ)YKD3$d+{Dnh`}CRD^b30R>h0SfoG!qWj5K)$CCwG6Ez?_^9If;1`g&0!MbL}iCPVLP;ctRhwmXXtme&OM za?f-0+}#HU`B=5tivVaZmfRT4cR!>boz+#zY4CbD6951p07*naR0iNx0PpwTi>o39 zPAn}grY9%UsKLxcD}@UB)MJMyH3wS38zIMd`ACW=>Gb1Yd#kcGa&axeOSn+hzPc0y~Uw3fH5t5HJfYHX6BL z!N_46^*p2|s9u>OUTZ9~cU@Pa4+$3Fnz9uveCb6s9EF9Fq?&dkq9>=yl>8bXbVI$e zi+Hed3OOAW2-YARhC~`Y4FtzEmoT*^=3CB@S4gR(E0h`5))LlM^dMB4ZV`lqSPeEU zH8ikltF{8MSI}5Bpn3uIz+Azg>{0e02I~@r(+!C1D1T4Rr%qa4KhPb;V1!lBTH#Z} z*&I<~oVRJdVbiY=W3k(p+ZYgorQzTW6(X?k0VOn=fax6wb+dsuFVChmYQ0LKhC@j~ zXZacvjy9YOP3Qi41Dh~l|3!8XG%L_P4_QVG9L7OhVMy&~`w@~V(Hvu9R!b~m#7~&) zM|>p#@t7ONB$LJJCN#Dh=qb~L+ikU;w;%y)!+PF--fe2DGC_I;cQ4_t)mr5z;#-A| z2I9c5Dpdvi8+e+iaG=dUJ`NW!E-tAfA;7h}Z4>MT0`7vsj$^otJue~ZRgRs+GXaL- ztL#`}TxJC{dyjz3JiJDLRU7Y-KcPo^Ip{gSWSgL0^aG=l0Wb}|3kf!q&&U8ltuSJw ztJt3eP!14%?}c-?4V?M12O_LavzUzb0f0MMFT=-o@u;MbmX?}*(v1}F#P=|C4Kf;6 z7b3L~FC9d zz%Gxh|B87vgsvUw>^b_A?FT0J6BiQuJ&7L|g*lal!8JydL~?LTugW~fp_jH*fxN?;cX2zJ%}? z;_}Se-KVdJ0Q*|e`I`dD(6z^N^FLWh9|h=T9K*PRagR@wDx*b5Q1)arIX#_3vI~9I zad-FdV(f(ZrN`Tnf<^eO=WO?0md~$Px))t5!0r0~-PvIP-dO_DVv!(-?+yVlu6h>lJ|FHlG|fFf&)4huCBU$_R4U;t3I_aD6!vO@eJe_hp-|wvlb1*1z&?4(mFIueL z_75UGjGj3 zRQkyA`iHbL@Uy88220`Sl)q}K6jdNcP}(aQ%YEVMD$GZv5{@LltVq-$Nr?s7HI!8? z67C}x1|1B#76vjl{BeJE$T+Z6SH^<$xn2z^$QudIw472-&AwVLG9l4dc8?;-7Ox;;>o^h3w?nv$@<{ zwwOy6?qsKP$+Pfa>KB06EF9SWJ<^?=8)4O}%t^yOqsPUhZj5!2J{vP0kQsMogziA7 zG4o?D=4!-?fu2zY2h7(HTRc}(cNQe}=rVe01MC4!lSkAbJOjT5Vi8J98(kRUU0ux* z#lUk);uvy;4xaIM1oX|}mFn&;+({Pg*DK6=QPFlS(S7Cg&-)EU&|D2pIP4spsQY%} zocZo%ICIoxX1O(|P{!>$%g+2-9+eBWT=q(V3{~yNQp|@;ny8`%@N2Z6YTo7(%>A01 zzi1}JXta!x2>=#7K6n1^y@P|@ufM+W`u#6I`|$J6KmKU{@Q{HuA<~i;I`G_AdQ?k!GZ=Ypa zB&RtElw?q(cJDdz3W_P&K( z_s@3;@cSabN;A9cVAsQ6`&zVbEHA(R$}3y&ajx7}*#U1F06+ZrK?B|^qus+w!Mw4* zI={NSxctWLrKJi0fBKgP9N444;=mi%mJEOwFYN7j0Q_iX7vomj7tN$WQ=!=QR3jYN zu1s$HCS)IsCBJc5IY~+-zf8R`@mkRs7G#v zCFvWSHNYhuy1lc-Ie>|UP6M)(FM!3JJ)O*-4W_9jgzB=?rH+BsE_3Bb4?H&lirXt0 zE=SZxScCNWW=%~?AB){|3JTn(YKD|C-=61d7NEW@TJ*Y3T8 zB(zJm;CpIE3acl{AAFF%;fvcJA8mwjk|&J{-|{7l04K=eVAUH|AhbV0Oou`9IB6Uq zVkwbDC*H$x!61(CjZl~^FrBH|m4!fFL*@NMbttFs+?>I!%8`sL$BT*ST+v7}6n9+Z z4E8X-Zx}n7#qir&*q@v(7N+F@HVRAt<)pzeHsG_!ptIBw7P|{`g%^v3Bt^S4_!SDp zWESNUxf)2Km626AJKH@cC9>2}vom;Y2WAFlXGdm|3WUbatNsKkkO<)54&WUCg=Iye z7^&N-uLj)cdWZr-WoMz+5|?%(=aCsjOsX+h99xkav&n*yVpLzod6mSGg|*WhoE)(K zND7dIyaj$`^wNd7ftQaB;~8mae)7rTVP?m8WpU(={sOrX+;pPLz=m=2gcm?m_aO7h z?S@^@6V|0nB?wtrj1z#d2y)rI9+a0}%Mf`~tXIQlJDQjvgL<&s&^1gT)mXH1S{wJTj^Z5%OeSByCaQ&t*d3#etnJpu@yt?}Iyo<*| z>NUT5a{Ei^mAl;A^^ZMv{)vyj+1}VVxeB%zp*Dor*;A>~*2d=F-+$wcix)23UcGP; zME>W6YnyhrIlu8oDX8%{K^B^vc3j0m3CkkN;&8*WHJh+)aA|K zJH?`uSE2Fgcx$ej@MrtGoX8P76Hny!jUF?{QS@qvT83O}0-5wALd2Q3Git&+S}83Co0=lEI!^J#$ow!fk*vB^Q$m=5_u1oWxtRk@2 z=HaQV->>PM-2=d1UcGuRV^>lgjg6<9X*FtFS-G+962zCVeeY~J9Te1`}!jR_TEH<|HSI(V3$W+P<(TE9v-LGJ`y$W_$u=fEG_TB;j_BOw-ExzX6 zbmp?&@U7dc_EXsJZ|-37{pLUSPCZe#ON)cLm>Q*m-g$1rUVib_`3eL6w8DQq4*ag; zz!&zeJ-4yAhzf9iXX8x+;K#?hTo00zY@}SDZhmRFjp~RKH?HJpYAr>XAO=a*_d|N4 zNNA?=d~PzJ&Ii3!Z&lSTp8=(h9>N%rSw00I=>V}*IABlXG$p}O$r>+?k?(8>e2Z6- z6-;`iYJOw4a3f7IWeymrG8!E~T+8>S){Wiz0tm0fa((m?BC|GzYy4Mn&y#T z8y)U+kyjXy3{ThdG%~cW6Np72VUN+@bur!inKSA|GE%DmO8Sy|iGE(ED#=jUI4<0| zC%_|~=Uhm=Y3EZy@=OS2uQXPD&WYq~!hPwUo4|2Ti|j^y3wVDGl(F=tdJJy+6otiO ziW|}kO6Y(EJBV$G)EJ#kKaWNl#;jgoayLY7)tHnLJ{!4R5D!)oWea2LHJrZkCPmip z0fWx)+6rQ}zAWgv>=4p~7sN(oZ6U(!CmJxplHTM82fO*FJmu~*2j z{Bc8P`=EI*Y>(__2P9-wBg3K-i9SNVVQu1ib$pz@)bZ-cunb5_u4g4oay=TA$xyXF zk-N^YE~h;jvMf709S=>CEMzciNIh8$70_Q5vvwDXEBvaMqhSFfQW7Fe2XNM4wpc9Y z&K3)Iy7vuJ2as2xfX-zL^!Bw~^DXa~swIe|vpa(Gq&%(#URBnuq} zh;beok{FAr^UI3f7;*{FLSRL4j0l7oQ-jCKpB$l(u!yfInVcCKxI+%5>JDcWwI!MK zEVW6bV9v}A&FM0Mg)eSj3KIuhLUd8>z|df7n?{QEOU?vM=JGCZNjAUAj{dd*89 z!#YMg4IYEeU4vx-zF>c}zss%$hF`KbZ(ETOs(*L4e2}>}Huk9TS7(K~d;a{Rg9p1` zef7Kh_dirl$p4u-x1ToeJB-IRb`4IgyilXeB(AZ8IRq1?K?n{hUg$+`0!$2vO+te? z6C#ZS$tplCP1Yo$Y7XRpQ<78~Nw>D)B3Em=c88FtO`1qmFP4a_Mx8Y6W`D)LpXc|I z#(<5@TkJ;2&-;A8&%x2;uRi{hk+{#51$}MT;lt&Rzqenf>2W8Fb**<{?%V&|lv~+d zUjI>aJv;k~xU-RGqNG=hry2UYBm>-rGKCX@;L4^7Ri~!->w}?n7?ir*>#d>UyWl;0Cbiz!paL{2EXB~ z$~Y6*sV}?R-IUo6gGLN}uvZDt4GxTZ8+s28xoRYANCvYPF7 zrpotDx>@k4tABaXNW0M{ z1o-5lHo&JG{k7*q!mK4QsE@(yuPa8)Z=AAkZ;Hcz^>k?A;p$mcB9dK&=Xv-441iI? zU$$cxo$~o#8!w#~f0F(0iF=pNU%mzapE3qKd&U^>H`f=|9H= zBCLul6WWVPiWR5FAuc&pyby5VNE9^CChQ^PiI+Sqr9nep17Z@f$Tnnp4H!#VrOrZi zAqC>Oic*PKER;CTV8z38(71*5Wt&mR~ze?a;qkek!2*|0f}8>wJS z7bOd#ZR|r-Z2VYOUBpp+)9OMZ3fhj`qgukgJwlBA3b`+KK!eJfg{`;IWoXU^Py$~WB{6Yr0vb> zL)Spf0J$E%Y*%N0qe?zyQR2)|v7xJ1V*D&BXx|NQkYPbED_>#r)^1oaU}jK^^tRLC za(DLuZna6~;LhKT;(MYRo#$V#U$5V}ZTP@yH#VEi_g{51d2ViQZLNKE{n@i;KYaJy zXXF8Y@y(;hj~{&`<&=?MZq|RYwlMmwlwL-cjW;9q+P_~&ykDE;@{dF8Ss#1s@m)_0 zz=ubF3kJJ^Ij0Nu;_m$Zm3Ny4({;`4|5Q_37}QHSmeWdpC`{U%qxQeDCk0cgVE(E(yKrP z(`a;ACCCpzssPETr=BBE6?7pFIhQ>aRLB+WNYwd839jL7YIEl0l;zh zpyDgx*ldvtTzj%0(Q)`eAzo@>ARQO}qR4VKBvIjDAXhQ&Nq#l%jjIy4!nkltq0MV4 zc)5;TOTM6}Ec$?113SA?8<5*p(VbWD&LG!6hq{H1$F42f& zJQp`_wQ=A~5`If%!`m^s8e~_hHl(dag~eSZJhPqc(xI7{FgXnkrl%njn=zD4*2ycJ zv^(iovJN(!o{6PYmPF+sIaqd(UD0;LK)S9g9otepgY%c^^o&4QorT3R%ID+;LWB0=(MKiMw zBgjIgrP`we(yOW(mq@8aSiPo)J@qP#F*DX5K53w#C7-T0h@ zn!`{|LHnp`A4Yw_G#;R{+qRL^|JrNoMm2WUcOKZex=I37@6hJ8wO%s3Aj_M7+Q6C{ z+~gd=81UMg3s1g%q}*UXQFB+hyi0i@hQ^1>XuX)ox&?E2qweA9=y0dgU-9DH6&U>G z&tHGH*x#*=BfkaM4F$RzG@^eY>(fuk0+8>FC7KLtvk9g)jT0K{po?Z6Jw`BA6SgD5 z&a3Qu%t&E7ogAsGAqj5k?+sfIwm%<1GmYj$=A-r@*UBJa^pJ`Pl|l8{%P$>H|Irw5 zv&+H4>ocIvq2_)4cL^#ZEYu)zmgrBXXmWBU;BxWaYG0xVvx|7`xO*au;9O&1q=!cYGB&O09(13u$KSoep| zVml^aQ;kSRACzZTpy)U3*jYuNOF71x`V2X$I=Rrlf}Mt3v)>8;!+`(0@M?P};|0x* z>i3EMN(4@VBicA3&c)J22*8qq~_xTPi30mXYCc0fyv-dGa;5=M$xnmwq;uK zDFf_Oo`~nn*NmhMb(id@B#YuyECRVrDwonQ*0?b%;H3OWOG*1lj0rN^;z+f$S{g@J z=dlT=T-#tQInR7q2_0@+Tpc4X+Tc5avI@5m$|?IjG$v{K98>RLlF72OFhwN1s-rGg zmZL~DsTy5>77oX#LNbmUt4?oWRz1Uf+CEe1F638TNV2->XeP8fn@S}jTgU=0MYXn| zevq>@W+C?10tXI+ypY-~gM@FubCFn)eHDG+i=L~%-*6(NDKl$dH>0jn9F`&RNKF+! zq!H>G?2JEb?=fK_CtMspk)@ ziO9l8_~lX*8$&S>*a8F*v0qp;q871=`~Y+jFdbQ&&2CH9P_vHJ#57CW_>*=&Ed4+B zdOY8s!yO*neeOK`Lhku_zFyBSHNn1MFi}kUvprZ$c^k3yp%78_giaE_QE7z1-o>H` z)ex#s&~Q1ikw|o$KR;A+UPTO^=cq=`;A_xgIu|-PrWh^T;@MoO09VLH~498DAd$Wb-_4kLh0Gb)CSj#Ba~PjIr?Gaoq@l87%Z zqfzBzwbH(noNc<%bZ;xhNc1ZHh=Us-ngH8Hm@N3tmCIPWsK;#h~95hh&aQXtr46C8Z zBc~0R4Uq?pH=jNYBwqlMz2eq3%5K_mmKq-Kqw%*>60F7+r-sUE0Nn{W25z%n9kB<% zz;%`(FYukUhqL5u!KJfOZ1Fpt2${!o>Z-GyhWvP-+B}kOfLupIog~ZjH9=ZiWKG`w z@y7=*zWx6DKU^gz#EGsE`Xce#+*E$o&k2)$S5W-!2?6j~&JB=ai2!r8PiG&$`HQQg zBRPK&)90-A;BM^f?SHF0cXf$pwJzxxmgE2cAOJ~3K~#CHyl2`o6Da)?HMc_Ka)gRI zDie6-iost{IVvj>ox#y4YC=XrH)uo3abQPrUwMuUbPa%e#ETsf#t~d)0DL0<1C-Aq zzVy{91B)hw2Y+3c*+Ke~16x-r`GeccMa@@u(Aeg+#|A0XUapzL3OmXaI! zgRpqgg)~r<=ZhFQjs#dF!*h){Gh8Ms(ZXm-yqn z?tzH<7wio^VBZ|yQ8m$)0T+)&nzWB_tVo~%b8zICVkm3TMK?f=?MWZk)}P^4b!~uh z2Bgjgz16f3rUJ%*8v@FWuB}!m7CJ0wFSa9lf}v@=`s?~*_39hEQ(sSIVO&i}h_mP- zEQ=dHr)pEFsgx2d!*}8hMsSV7rmBrI$4k|Gqyi*+au{JWwMk(^T^bnTta0l>>ijr? zlX2wF_Sl^=JV&MRFmkN?@Fk+4@6bhPfE>OwM#u)*X@k=-U5q}#`~!Y5xi@mEmZU_sQE=Nw1fc|=j>xiqXi zR=t>igMJa?LfMi0d4|1}R4xP+JPA5W{v7NtEL8dcUPxqFL}LX7zT`mL+ffwTMjuTL zY|Hu$TyNcyaU(Asq`t4;cM4oG!Pl5Od!T;jtOH?LAzY4X7wL6t0efMX2f(O zWm;VbN2{|RsRv2zziuVW?pFe4SS(zbvS8Pql+pA#sR=Y?hplOf3Jqw7GdOzzYjUAu zF5YT1-KcOsO}cdPG1%4Q-E$Z3>!5Dh$Dpuy zgwKP*Z9p4r2Az#H!<7N%LGXA)RM}wpkaV{D)%B|PCg+T72bSMqtK5i1=&a;S*5XS{I$tSpNwYnz6?AKC{`nlu3Z zc6N4ayFz6QlnF}4^vTnAolZ*(_-1Ys`~Ud6vjs+!JianBb7gMvI?0d*VG~atRqWVk z&z)m3zJAjv>rFPY%dfB(%@s6VBVw;iLl=-XH#eSJTbo~TL1v2xu@~1D3_RC7-PGjz z!~g#9Wa9Xv=Lg-+mK-qqmw37`x%uAx%QLI%o{Am{yttsuE;>Xumsi(T*Or&(?X_=0 ztI32$1^sgNjjG=E+uGCYzn#mXJm~b{`ybpW&hs&0cHtUoVSvmSL?W;vR71fEepkEz zRwBz%u%taHs1n$S7jfku7>L}96lgo_8V&6=iQ|ZX+H4E$Rqh#38w4|%j)2h!cMN|6 zisrD#&m1${c6MQ(FEBtVho;UxL)tTbnC<}g1A${78}IcIR0;1@0b#AOupq^RZbS%w zt|e*%0vu2Suo2&{Yg6^dYJtx)=&$a;i>uEl@5;b9m9pPLGFGi2t>JRqSZ{qbq&J0k z*p(kOG^C94PBkEOPL{+=v z>kFpf^1Vmzj*T6KCGUMLg6WJ5jv_SdcK&7mQQfEk`~`03OZ%@s@7@5WU_;!f5-5Xt zk-~y|g?=SJ2ZIs0e}hrG7BFq5aJu#Nvh$T8?0#2)dA)S_~mxe;N#&j{nVwt4ccAE{4 zhnq=WZl#JB{WE!xnT&DQOigUqurn#I5UX2PFX&Y?7$MHMWDbPU8J9}gs;@D{XT{V4 z+&WD5RYq|e>KitEPD<6Ks1Mfxd@*@3=9LkOc-xZk&CA8xE4a-7-Y^kiqil z)93c9l3nji2h~Tnuic5T->Iu>JWJVuNM=?U(^73|W8AAvvTVjoqa9t&mbkUC09*wL zjp}9siXCQaV%_Ti8u+ZM+t=7`r2K9Brge`R>neJCAGK6%R~>n>Wfup@yCx=j9&JB= z`QXK8-zrY?*|TRa`7?1YkR|u4rLk9I=+559Z=SrGK3(EGz$I1LoZr{Eqy@e^aO~w& z+Vyi9tL=w45vsfurNKIchOm#Q8BKxg0LkW1-^w69;F{uKLd#+UXaTUW*J+LN!}q2qp?WK?@b^1!X=`vf zw>f}rhOtL>AgMy1JvTwK3Cy?N7{KHqn7%7XLUUeK!RfVZBsJhvYTZDZSYUNE_E<;%-6Gi&RUIRL)tUEMU=lV#DEK{VFp zrnc8gf|h_S$-uDy48W@%+y4A=m8yQQbT+ya5 z%Ka4wAAC@$T`yLWB7&_7{TPKPFCr?C%^r|EpvLukE?&cbk3DdAp0QdOs+%%0S~eam z&;-0G{O$HhBW-xu9U;|{zCsEg40H+WC@T6VE@5BMK+!Q4z4jLVKd#QMr_K8e<27K< zU=0D5EkuF~Hnj~Hi>T(sj!9f`!byQDL&`~1Q(9SWB9&wni82=`UEgR336Rh(QWL5O z=(?_oqA2OQPTjPn?HAbLb};RG?EYQ<$7wp!xc1}6n9!8#x$gUV0dMWz?t+X)5Mkef z!L|@rHw9mkNArcCI)0l9t;Vm3#3FdIiQ1&X0O^xSLZiv$knY(&R1j>Ow`sumFBu+L z1X;Pi6H}QqKvrIKmZZvDwh$-kDk;#-Ww*0gA}5n%& zDLc>NH@+Q%^2TeSS~if2X~+yEj*-xj3z0908#re0-KEZ7;y1{CR@_DxMGJO(38)5s zV{wMhfsP@;F4evi6$aqb=w*l*%_W91B+C)HD@9O-42JD)Pmeuu zgScoE&z!}m`NkOSgT{k<5Kb$lvZp5$s%bM!2sB|GhRM$`Y?hSW)mJtmpx5@IL91Z9 zsKNkDw5k0vhTEXH$)GQ&uqy*k15yk~h@^eYo^_Pfubu4=?h1j?WcekE4wHcEF8m4H zWAzInhg-smB9KEVoO0G+#GnYH`EixlGz70iDkCLbsj;23M82$Z_{V!ll00;BijQSXgnM?}O zNiY@%X(2+7CD$&GGoY}sSaK@Geo;+jl=AG=FVuIybPgVu!paEoqHdfTOI(=GLKk6l zu{aLNC90B84$?KyMvp5IllLzwcndsMHzL;phQMbRQ%b`ePou+9ct}ahYMw7HeKYzq z1g?Yc^yp7y*!%6BGVSqW-Kjn~;$9}M%1gKSN(SuHcaHhea!Y=C^O zzq@~iAl@0L=Yc~oLVo$>qbCM?j}DFuzM{V1DF>%#w0+ek*sYeuhJnTrhuCPk^4B2C zuBr)-lP1-28=o1;>%Jq!?2-qKj2j^zoajB#`_I9t&yRjI^0~e0@$ku$$DSoEg!YMN zk97+9_3mdhgm#IeX5A}QV85I8x3anA zQG%?=3KyC7H#btkj#RNjWf*We(ijel`||$)Q|ZW+uZO+muUqwcF&uDS2gavd6T>N? zu%7MwGXVVQIfAc7GxDhk_B6~ zQ&22Z``c~@eY@?u&|MNL`KgT(tKF%x7L50DSzyrWliaGcwa{7!x^hB8-B#5A6OlEa zWE4%jvlR9KubkSkD##6Pht$yf8x-kdy1 zL)*zXBIhBx3Ws6^jKOhxUN+#kVmk2m4jEIf#kvfjZ(z7 zghIL&2#qQJs*MzAXfEiy)FZkpTX09{?u{daVA(TmN7QH-a$Goo?H93?GYbdqc3}Gj zuRE5;+B%q1k8%3g7(QS*zI{M&!>s+cYNb*O^hM}yJhwrS&<4o5rwXK21!5@+t7TT% zSkyEu_*;BxMru(B5_Q0IF!79I+0Qu$KfNY z2vdjZWhjxrfex#zDkM^}#t$>m6czSGFNzXzbnyc145|W#9g`}>0(VlCfQD|F@l=!? zj&Toq-Rv0ZdqpuIvT0rt z_Ln1#iNuvZ30E024|^+Kulje`WkA0uXci?NMiYJV#o<5x@)xhSeL5}h^&*NL(se68 z+($?VRAqo9*%|!Jtu7$*qV@Sa3O5t@fxX z==1IF2KgB~8>GI-hflasV`%NBZK(`VJMO4nxRA{asDgp+V0s4Ua|2AG=ZA=S&ccDU z`W;f})jY{rEPw|nW1w>(tD+z z(BeRw@m|8V>?J*8V{J#C(Yk{9M#FAn>#W)(vGq3T3JpP?uff0I$_ecP4s%kA(b}L0 zuwRZ|f3RUUZ1~#J()gE#mb&&C45pzlERj~2$+Z8pAA%bZz&88C2|x8mVXpg|{c8UW zSM+0wYBstV{C>mW3S<|j1__jSHa7j~=G11yNH9{Cl7P55y{X%By3`B>zK{ZnQ|U4y z=x8ZjG$LFoCLR@y-X79DSWF+H!@_YS`Wr1O5=(4TwMdhtjH~38^oq^vBJF|rVjCNU%Cr3%AQo$k!xL;RBT8IzN_{I8HMd@PG_R&+=J2U*M9=v`sf+VbhNix z^~TPcLQlIJZ)L21SDyyxY461jdp!iNx|h1&ZhBoEJ+A|HTXhR$Pl`QVb+~NQ`22Yh zWrxa)t@|at?nkvNiY%hcI{D}cxa-kDgJl|pr`$AJz9y-)fM4xyWrmv5(%9QEPstP| zk(U%-uxLAoe@bp&5nMQQUNAo>GClW7-ox~~(AQq{;HBr^K0Dgkc}AmW=KyAK-kJC6 z3FllQblz(N&daZKubhgMi7ZDvSZO{TE|=5gP55qD68~_RfDV?wc8OYK>Qg4W(m>m2 z@|AB~zwUEh12E~6V!SS!68t^I`d0|7g2GdsfB4{6uXns%)mE}kN-VyKufE!SVx|wI zyS$@0?m8prpRy72Cy%3|L?ja2(r96=x)rFt5=h`XUsmi-tO-GjckFs07I-s8XEkLAox{ z49N`%1*yjmDMA!Gz-c@@M?f=;MobM%FXMwQ|To71(?sLxbgHxru zU*EgF_GJ0dlC`!V0Id3}}|VlH=YQ!70hha7(s6|0N}HGCjek=?uE48e7vymU`b92>=nzdRd6d?&un4BmQ@oL zY_}@UtX7T1b>-tqrMgn9wdk1G`0}f7e*NmxU7^#x44(B_O1?BnpK|n(&5u@vp^Re` z(V9UQTfA}Tu)K)6%P<$+_qr8qRZ`^|cdJktOs26RG*k{VZic?f7YS7^yTc)me3iQ# zdMxC%tt-4r7DrNBktP{U!+J@=B9fBq4Z=9URy10egmE2F z1}xYd&n5FgHowVyUf6983{7YoQZn%YI%oxCIY^wgU(86R0(fz;z;ZW|@ZDnejDsm2 zTvQyU7bzHA{D9_$xQ12vBA+D$DG9xbYbBCg=6&i;()I=)TU>U&=$>&L@z6Zdtiec} z0IcAAXB@U0i5$eBL@4D!U+16`4ow3CKSh`?rr@620@4RiJD1zMG*)U5hdP2W2XngR zb;(nSG;!Sn2Lg;v*5#y5GdBV%eI{^Rdw`itM{)hK{RM#`zS;pi5pbJA23W3F$ITF2 zIqwey0N)98R$l+Az;g*i_DAKFi;}jK*0+^}6qf|1OR0_-3X{^_i4HP2ivB5oDqSpo zjsRBItBNYPxyynzJj}g%AXep(gVYokl@7G;WR-V1C$^s=t72z*V3`# zB^1xaOU3NK@YLL}33z1pI(O|%wm4kWp1;@}Fvlu3#@_d&DP}-Hl|@%|(%JQzJP!3C zVKkaG9$&6wvu9>w;5cjIm=lb3W>zgskZihwFCm+rW4N3(%IVl^knpVhQi{CllTsyE zR`{~e@|ebB$tPzhMbbXPx#X{I-rT&oPk?oV3|?MT7HgEz&Yt%>x~zS)op$imSsYLA zZ;r=a!t~h7nYB5*Gu$4Vb_Urx#AbgCc^2Sx)Ln|mW|6GRY3?}!DboF)}?S1#%qbIs_o2(vXCAYd9Ht4K{PAakym|z0>WJD?jc!WcZvNxm^@YaL(lbk)I{y>>w6B9+ zUbeP{Y&HdnTV!mnHD3JZm+wE_+a)yeh6&^7>mK>{E#a&{rhw}8HT#LBmLW#R>LhMF z*x0~ByKr1x)*!l|7+X{)h~o#l{{nrDC%5nWj~PJ=S6;Cl_pPd-(8M)hwQ|TUd#Bm3 zZF#rks@b~Vu(#p5w5_dXy;^HFYgW^)av~wv+1e%x`Zujl|Nh3Sd%O7P z;M~lN`)+2WVQX=?kugS3#fS>Li zC4@sTSZDjBOH;ATv+~B~Cq=jLlXV(e+2RUj!iS03Fj+-3`?`gsnv6-oS>ZNr0au~6 zSc2Uyw#L|gU1iOW_6U(?L@dCmQNc=RsZe6ZOiU7@=TMu6Atsf;t^gdEvOzLFLLSu4 zVX`{}>^= zLXi*1KW|+Sm|Si-BMW=voXzdRD(+Sj8@mdcDFuny>bi-9Zue4;B&4?;X|r2+FQJr7 zo{8uHT?wU(x;xNE<4OvcP^_qmudo99J9IM~_410-5lu~ay`|`cJkFRoT8jEtJN)Sh z{}dru%b{y;I6F3kuSQx2?tqZ!u2Org`m z>Fgyz zQg^6+B!zJp@HK(tIZdvXYkCwfsc%WJSAXqTY$o%)U;O0lo_t{SRt8x8WGlh%d!zlpL-}Lg@UVcGC1Wo^+<3>7sY+sM1Uvc*Ap+Eod!0Usb zc8_#p+ctYv`Rg3H0oZK{>|7@M+G-rXa%JoP0Qiv-SYf~)va+qVHZD^?pepFYyS*$r zd;7Z8NPGH=7Yhq(wdG2swy{852gzdBnH#GDN;O_a45gP3ue`EVS=L&E%W6Y<5&-*#)wK0!Sy<;5;^VDWOQ2NVw`*3*-jW+zR=qCZ+5%v|Y&M0j+E$%=E#k|X za?ifs5;}Xo#wvH&;jF^F5n;Xf=id9r4)yX}(Fybs`ExJ}c(Alm{dn27SE|*OXDiFr zg9k!+tM$s#)=z)Fv$C=x=)CsMJ5Q>brwIe54;TsA-ma!#k%1+D4)V5D*u}*E?k6er z>$GHT-4h_-xAjDeWdPrlhwE8!!K46aqLd(TP z;By`%MsX#_$xN~g?#F%9uiZ%W{(3SVFx6~_HHae-#ITI2c zPv+x=t)B=Nn@dIeB+&+2h|_k z198Ta1PjKfL@-CEntG3z~%OJ%|8|yp%9uEcFD!m)Wm_$P`wZH9Z zZDRr*P#>_yPinqKdz&C`RNY8{$8ME6dznYOkv|8_oZ73pXu1f664OWsA7&Cw2ZKMV z3o=Yc-W1Jjs>WI^F^EnH&5ioiPwAaXlb)OI5ORyY6j8K5FI9vc!@34eu?E(Vtbu`R zQ&~tcJhzxa-W*E{Vh^th>79uY13g@fLWHxwJ2QjT_rFwK|5MZV9WDgYMDC&ilVjn_ zNr;e;1icfHgn&`!j_cNdWw>0uD!H)b5LBQ$!@S@J<7&4YAJl*{k<+;wOD1pp*Yzp}nQPufJ zBXYNswSdmx`G9==;}nPG(g|ej zBq$p&Y0P>J&AH^>ioFr0l_Fi@zn!CRjMtsp=aF!a8iQoR&1DdATu*lL-N88Nv3ekr z-YBxPj2%2`~3b=PeVvSZ%CzV^nIYD z>mjw6%*ZaatIYmIPL;`upPfH?KhV&(-JQ(x-@V&$*$S73LaJqI+Z8PUjE)6#Xv%Z? zx;%?(tWg2kW?{To2bO2L*P3z+*T@I71UnpY)B(d8ZEc_Hrmpzt!RW z%7=wh-W@cKhn^q#`PsTp8|au~1#lD5!Xrctyf2+wn^9VCdbMPNrh}QnvA~Ybk*%Dv zS%o@D60Th8Imsxdlvo-;h0leJ)70? zi#bM7{!{L-w%)^jLlg}6+`PS*Tb$qe(~NN0JaAQUT73;|k!yK=vYcPfYa46&JfXR; zrq9Bxyu6YB1_N77-_U25zs>8=l=1V;FAD+_fPc3B`X66Ue>e2lqkaY~?KbeOND&Dn zg;T%EXVJ@%EuKDIm`6d!)#B+>h56ZRc1Dgq(m;wg^M#F~0l?EQ11*l^n23#v z;R-nwKIZ{Ia2V+vVd&5;!h|aXY5~D*aA(=WQZewl?@mcNu zwzS_)gdsp9W5Wjfb9*@45lkf762Uf@pgROx6N0b{uwc0pZS4yf3k$Ng@r$r!f$6$i zGUy`Yo)RX-P@RJr=0ay6O1nBTRUp0#8G&Dy0Q-U)eF|&?cB#U`jDRcjWekF0t^%YY zDY^rIT%E}vZql4lrH07ZXmn*>z28Wo4<_nfG7gx5jC~_u!&Wc7Swf13qtQs@I%m97P@-ES zP66pu#2XDnSjf=IAS{GHN3aPzfubZqur9PAVeJUYZueM3^&lO)fW=&t|01m_zzHo= zo56Y!>TG0j0BY4r@En6CxswEHj1wo+k}yCWqu%bWk{^r56BDZShym0f+7URglOm-e7y%G#ywr;`aGF-X@j{#nXltw=Hq)_~*~P1by9@-XoRLOuu}k2CGs z$1$i1Z-T?CslNA2eJ|}+{`x-1){v_a5ONUKE@Lx!sJ50fq2u^m~v4l2<5~QZE@ue8jT)4Oj9w|5Q3aeuYdpFYuCQpdk_{m5NSHG zJa=EGX~N24JC-9_rZz4L-WK77;+Pf_+O>7gX?3|jy->_u+I?s3@BjJrwZX^AASQ4) z($jPIZ;LQtLG~746|@z&&FcVTxnW~jmjhUnHCUrIdF#fDZ?w%#p}Cu|FKaWi;IaDV z{EW8xVupp!%V>FCPhYyU_&e+Y4?gzesnEn01*qQgRzv`JYpWn&D^R<2_3G-W9D=rH zvRj446~uiA80)JAq*=en%jJ&zd}P2cLmwcO4FTpTbVAcIxiF^Wckg-WbRIBS1Tf1i zuPjU0DuKxr1}m6Y?TkDsN4$cGt%Z=P4O)!QXIoi?yaF%TmXbE+R+eEwv>f5iCL7uv z;GbsCk%{ZYb_{b7nMDV+o$U+2+_C|^oQQ8fUbYo-C zj6@Dshq*BrYzv~G0j&y*>j=6tZVJs+sAX^oZ+2x+P>AY6D9(*!vMd{fCHfW&SKzCM z%xcEVxJkj)MnO)7VY$q8jlyJa!6z-4Dc@GN2d-;3aJQ~b;p?8Nix&Z=Rpvd_80~@{ zqZmnW+J$OD6b(a>MhOFxp|PHH3pcY8xcaRmtN}G7V_y@X7dN2V18YVmZXlr;$$}|I(&8{#9e`r!)io9eN5i1Im7u~7jJFtmWyPS^ zA!o*|acIuyBt$T74dOZC*5BLZ?~NqjccY(siB%+w^p zos9b!eM6Itd9rbOCr8LYVj<-CZA_52t=2JRwH_ZG?;oY5ODOUrA0!3qhH)}vBNGZ? zgmlmdN3L(;1?H}UzdYziwnvDbYZY_d2Lh}xH}v_32ky_^s4c}$4l$52M9LfbK_;}( zh!j$NQlY2As-+9rs+jj$5t>SWVRH&k;^yJXIM5ij2mFhm4-whtkb>sEG!$pJt&B`8 z75NOq^Pu_yjnK7RP7(;NeR}*iXU$i9-0$h}p|h3&6#b}C5Z;$VO+i*$O@DM5*%J>B zF!<^6HjM?56#&l8B0^FS7;8w=KN@=6>p6qmv!;=r8$F(;e{ZBOJ=9^sDy;l@Rq(r@ zb3ltBtghwrD{F$51x?$`udnFKYij~*a=e(!2_gOK<7?A{{`%e#W>N{L_hK|H_jXm& zgvaLd+U#sWt~T{$VDGG8E*P;U5U#`5HGfr6mZh@{I9X=5sQ71;+}M`N5PW4) z0yQkp=y?@xia8(5S{5S@+EV_Nja_t1v_xqk#(p+s>EivNC)jTLA64h$6Xku!ap4{a zaO)MgaaqoIK~A_k%3&98jx;ZWw3E~7KY>xq=!O;)k0U% zWuxm7J84a*>teU1OaFt#e`TN7`}-VeiE@w6-I2pw?)|(!pZ5>Hs}Ng~;wgs>V3pz^ za}$EBa*{eiG#Pq|T2h*{XAth8lpZb&mz8xISTlnT0mB8NJ<97^0Nzj`R8ab4p%bSs z=^QO~y4~ZPN9}@F(EgXSjyh5&(~7?`&_#h2YmwMWkywTHPHlw2=Oz+5+KJ%E80&3` zwYRi_#A%lm&1f1jth5c)1~YvZblW^k%>h) zOAfS?Wt}%rHE2~W16T~MO89IXx2bZs!mFlY8CnP7*hrKx;qHA)}L==0SrC%<<6BxgDG9YrKEGUBF~l1mxM!@E?|bzyF3itDD{Tf zKG?g!GXktDwUCmam7S&p%5qG=0imrSv7ZE8!EFF`OGHOS&9-U?DL>+TO}IQIhS7v@3{{Bx*2K|4Gls6Ag(2>eqLon(O|TE7!9j!5_;r?P_Amq4Ff+Y; z^*!Xy$-%@(GCwkuH&UEr7i?r#Az1lj#3(PRlnkSDMvx~Hkw`L^Ys*g>C`XhG9Z`HE z`sjROjCicJtC2(=9rWZxMAg9Jmq~IcBe||fWP)7CE+tT=#H>Fl;bl1ehIOW2Ooe7z2gJT;p9`9-con7Rm-5T9x>dnrXazygE zvg!&Zr;_kzBlN&<8=)b&+5Nv!55M+{ z+FBylnlfoFoF6a8tGBj#yT1MQ%6qpzy?_7nFTZ@avhwlDb9+WpDfP_ulYf=k1K9N| zg@fs^__9z~eANd}R>~y@lkX%h@!{_oj~$0T`U9EQbER3e*s*rVen{6S$NrpJYU?vc zA?RmD6>$wH`$^Yl{GoNqaCuKk*AWZ$+EcQl5*8vn-Yb4g%Jnmf@4^7Z44N>_&(8M! zuDAPmbMubKs<|Y+a^h!q;|EphPHad>2pf_^BjKT>U0NoQTUF}~9XI41vv=}{U0F8Z z6t0#R06hfDVmwRN9;#|kDlDYXOqySCGik+QNsM*uSzi+U>$B&BZYpXL_&Q7ndPvgYB1O855zG!DRP<7qC z^WURyz4H&l!+j@>l(R(bexe`_0C)x^ls$Cr(&ahLljmkGZEQR+5S+d^zjdeObC*C!lyE?sb>csmSc4~g(%@eb8$gc&N#gF8B`se+3e$@O8`)g!V zR2H?Sf7;a~s52ke%FUd_^^773G0}Dv=k`@zwoXB{gd(WVl;};I(Q1Qd<@p9$-{$xJzZQ5m!11%fa0N zA|~lK3@v*?Uuqaw5@Qrzu2Q8TTS9(}L9*6|!^-PW442(gr|~8}rQrc$uR`Qtg-Ct2 zBcsQm))1CpmcgF4T({Ke8S;jpuDF!28QCX6+AFkrElbF*3JSuK3ada9q3``|^*p1& zox)|nIIX3xN1FqTnKmTjyP0;r8_DfVH`T=$LCcBMQc!2GF;>jLO~gW@i)J!yD63Jm zJ#|rp7(EuEXXDCEQ^9sHHwpwtn>2?GPRVJck#r0!4F)r0bwukI7b!|&_#9;68#69U z^i^eWDo9HM5Z)LCFpViU0@g8CREVMq7`;g+5)gWGH#TDY!6>8~)fLShRUgS~-j)iKnNyg?suxLPY=C2%MXnrr_CBLsu$ zW~h>I+PFeeen}>G4DzlglPFpmhDHeY8_ACh5*(dNRBP63caA6=n!W{tU53p0#C7Av zS5amqwj$&~8;>0_lr>~dv|Uvb!#yLqh@o?N384*kCxy3TMv5W9;F+P?SnoY)r40)6 zT?9d^9gsex!~}cXNLM!JhR5Q-F8yj;BWFWj%6+?pzT**actR1;im&X_GpKK1drTN~ z*6o*70c=3e51s5)2ZTW^aa!4|8h^8jpUh6=czj}_tt*%7rAI;tY>)5k^QrICKKSl@ z?Xcj}2StN_0}(!Z_O~w{dgbs_KY!zm+S(4g*2^rW7wsx{scdN}wEcK{yJ34Pk=(kM z9lv(v%6l;6zkP0q{23HEHQImfqzD()cMB#;&U{urUbM~rI>Vk5wvVV{E z$SyazTcL|RdyO6|PE+|EKYM27kFVa&_B0>&`xt*vhIHJ~-Q%vA!N~FP=I2X698xok z48;{HQxP{poCw?dd59_o6#l%k2df7)bH?aCgqz*YUT+AGKXmbvBwro##m~MYm|jAW zV*E!(cF6Ium+v3mb#V9XGd(A}T?Cf>I(xD2a`?n}-`hpTi(y9Y{k#^T?@e%&r**7<*=P%97Ke};a!w}le*tNhq0DSir zKH#sud0wjsquYCFr|4dR0dKC|*+jX$4*v3!SLde9dINa7dxiW%l98BDXw1 z%`da&VeG=1R0GKa1ICo?xyv=>IDL&WEA}~5S3us}$sxn*PBrIvHN-h!ZZf7Du;+#b zFbUJ+KwT1@g9K6|cn;a+H4TN-5|(=g#+?e~Fd$y4ll8YyR|rvjPJ85EqbR9jav?=`PvK3fzYwg?+^mm5ek+4bm6cPhby?$9x{!{k zdWBO4ow}KT=#Hk2`tvb^)Tkewg$t=8Xh3X;e)GJh&b7d=!LU5P^&R#T&IjwMM)HkG zjG)yHjp~kVJ)`ET?eelZ!(uyH*1!af9y`skK9?})qCieXLgI~UW zd%RyYgqVSSCcHCwb~ESWJ}EBo;GY-+rrFvMI2mXd2`A$5k)#qg!qrY#s50Ohx`N}^ z|4-HV|1_Q7as2v)1|$;N4rYorr64UF?M$wMU_nljOQzzHahojJmy((gCZ50+G)mX5 z_$6|HSQN5j%9m;JhCRK+9p@QOy%RNYf53h){^CEf*W>m6fEk*zEo~tO>7&p0>-l;< z`@I#8nouIayHAp%C-2Lb=~9VnMNd+{&}FRvZ&J6%Bp(;RBnBmL*q1%O6NHa#wEoBRzz`bEtkryr&B4Gf^!1k zvlf7#eWfe8wQbe%ob6X%>VbCF_@AB%Nyo87Es7$}j0%1ip+!mJd@+E}Lh2>mc zAX_L1{?i%l?M1g{=yQ_4Q|pS%B^2;4ZoealqvZ?UOKE*Vwfu0Kcn48fEFglH^ZDgG zK$owF{v9`khpCitrKRP4fIQzaGj3f&deYPKM|1Gpwpr2Ge%vaGTDg%x@aoC4yd;{O zX6kB^pxB|#D_tc*$hcMO*d4ZcyUj|D=7qM~#5p@n^cDY>Ih^t+;i(8%yK)i{tvz)c zBwg9(FlIUV!!=zea^v&rW_hV>jy$bC`FgAYC;R%e57kAezqBC!OB5uYLK=orln{&E5`P`WgU_F1{;taH)=qRRWg=%>q+ZX{p9ddOXde&3X_m&r&|BfgW1U5V$Vf^@s|V zn?0j}KzX3NYIL+b5NQ5D-Rk@jICbb?>n41K6>_!D>-)GeLN|;awrjAdTr1P=UmIn= zy8Mg$C4+LC9#Wg`1&8(^aUv~}xXAlMNrjiXh9U!AttRw}0D!MvHKurr`i0I{N-7fa z2-=Y3)xN(b)T>p%VbKrXlHQsty`laqHANzTL);z@SM-N#YHC99k}F=a?%7YGq5*%E z5EuZgwfPNvTidVk>j!w-H zsk{>(YCQJ-{Mm9~{l5g>Lhzqp@W~@bPM-Ya6H5snK79DluYPyzALYNTYA(Iyx#toL z&(6l80%0gDKV)G?e+R>ITw&@j+ka|Oa6BnEK94}YdGqVL5AHtv{^6thD=Sy84i483 zv$9dEo#-^dn)>1TK@{jPo~mIpPd2mNCc|Y0%EMb^9XM*8TwB?fTQ}1lv8jfeHYrT6 zlW}kBQ#D!ActCF+v^266)un@D%W$TVAPkUe<)0Z<#xu3`_qT69Kk}jJTG-uUIBe<% zHG^X-e9~$P)@9)q0kEFlsE0qHwte17mh^^AylNOD1BFOl+BUc0jwXvk?woOoKU~O9O)q4!ix(yqbNT$!^wPv>FqvOkx>ms3bz3y+?M0ET%TIIE6%u-tnHExJ z1eh6-th{*;`tsId@$~8{Ye*NLb?wW~Sq_tIpiZDal?AtVo zLuf0XaqDc?LAS3>UrV)=VWZgIZF6w4T)fRG@SH~#OJbornVg5K z7_vy(aFZvk{%5Dno-B51C$Ri+78keLi)lJ^vjWAVZHQc_Q}eFs%0%+o>okbcX~LnQ zav37H&OK)^Yj%Da{`N8dr6ozgi`JcEg4;?bQfnltj_B4{U$n15N5R;eHL?S}O66cQ z$bmEo9GoyaDQk!X`(m?E{Uj9(W)K{G?q`tekFWuZ%w;M(%aL>`$fdMUL~)FSj;K&I zO5uWGtn%1LXvY{ST4YZOeQ9!qV4 zZZt#J(sDdoY!Z)(c=iNIoouEl$rFIVoJPAC56cx_m71kp9u1phgZP%NCAlaP9@RN< zGkt|bb_A+!nL1!$b2Dp5W%Ii3%Z!3uBMp|M&N2yvnO>lU?Mh$LH@wLo9Nn5W=^)vZ z!ogyS83eV(#%G1;3azZk8%kfglDz7}^6F=cDl`+?QK5;@-jW)xgBU)qsN|wvHj=cH zuwPH;!pwm=j22QSdP~CL@QI3WC@hrK13l5b9pTEbCSHZv_WiCSLG}h&(2ZeDJ{ajg z5vsf_yhw06cIS@oLUFmH@B`mfNVIT>uq-`ghRd1?JyIF(4ADG9Ekosgl<0^tD+_%a zMbUP0V7$-TL!w#%qw;=rK2MrcXfAd(?%!0uL-H^KVw28+;5B7Ql}wFkD8yJ*335BN zj1UlaYUKirM|2R%gH8;^N94QV=(*99A8B2~h@zaPM0rcmdhosXdGq7_<&Ugm=#PvF z-n3+$Jo1}Q1i|>SKK}U7Keul`v|T8C3^9DqbuV~sRxmuvQs9QXVi2YxKNzYY!JAE#cwp1kz>^`%R%&tE!k5&6M45C8rBqc2ykHXW@OBJcV_G;+Jbf-;%o zwa|FbDs?c;OY)zs$PN|AmZxjr=Jbv!s=&ZGyd z^`>F7=`>(uF-O$HCJbayoz;TlM~BAF-`ERVu}Sav{rleE-CM@1J;tGh6?%`+!QX^x zXk+NDq4l>noG9rp(gNT_qT~v>8wqU+)BbCXg2Uxsp+Oz}-tdh_n=8IL>O~0mm=I{T zg1h$YAcvA5EJnl!R0_9z{pZgPy8fnH!1ZWWjY(`Xag z>Gg$ddT~+2qFl;k3Ky>BGwFqNHYG|HN7uS)$cev-Abt7vFHc^yAQ+Fg>27ZORdTh+ z+Q=<0O%w!+qDl*jTe(s&iO_#9Xf$*|Kg}I-@>fLnQxUGynT#5zvclnPniXKm6okNw zn*8zZzh|C2YiX;l=gfGg{Jx2dC(K&DWWgE%i=NKQcbiU6o4UjC@yCzHQ#uCDrhXKK zy`EbJz>8}y-<~<}VlM%o)z$p!>XtQBucjQhedR_)QlU%fpbqHl-5U;@5VS~NLG>0J zCM^eByy}z!$V%m;WuGRhLntbj$_SNa1gyDOWoCqoU1z>bPb}TkCeiy~*Zm{x&`#0M zB72KB?DK9XAU2!9Nn5u=*N<>Wi-v}^8eu8qZIJu43f$}5wEq%3+2*^>+qM{+FWem@w zni4Glme0qYvzJ5yG$+zQ99h~uNU{d;8;plz%29H!#)!oVj`?H$u^{nPQ6EMtK{c){ ze=y*W`N)bsClBOMI;gcr>=VU;S`{qv7hDEK$NEZjorpXvm&jpME#1FWL0HTAv~Sdf zZA*)PeOeRjGN3Lc?@C*ggs#^ELQ^s*J+85PDt(y>S6#=##obs-(pBNAKsnNy@o%6i z&H`T5&e4#x-3O>~+8Fuyc5dI%kkWVem;=k9Gq_F}Cabo`I1>wjwc zzQYAVnuIeGVsc&>3<=~DvV`kZ<{^YMn9b|iDj=uLZra5QXU>IIVtdA6Xj1&PItU7= zRa8JR#B)KttCeeU&91A{)7wwI{^YGc_>b)MJns*%B~_B}Ny=%=^Ld`v^LidjtO5XR zvf(%zYJ@AGJX=6pG)--K`b6}6lp+&h69Ma73fS~fS z7W%>ghcs-`p+rG*2suu~6AZvQrUfPhI|7H`k^>p|jBTeOWMMgk+~PnVgD3G*fgRH&7NB(-DbkLx>!Vf3eN#d1o15NV17Dp5 zQ-@YW__xA>fx$w9Ax7{2Sjo}d@9o;KVef{$2M$~p4Boh~P;0z@|Kv&klppnEWmfcU zR8mWozZi=CA&TH&#HfK15FQ(Qf$NPI0>uF1b82E75a9V$R?b^j_7X?v! zE^NW32qwuetCA%*wdm2&J*+0yv2ra%3z?Tp5z(3RYUbq;WzbrEXmx*C2XW=xQVe)) zXgtUnvEs+LqoS)>i99&i@{RR|@AJ*g>jl8N&5A)-9RDf@bTf+y3C)7UD_AIsqK*)6 zS8`jq&!`RPKALha?RLRn7ncJ(2#p@Qr2;7FzM{{WPG==MHxq+l#cEc{ zG&&k~Z(r(uV@J)+mLSW3y9S#6$n3BS#JZoKrG~f83DeAsXR?nc$FavViR8t}Y;NZ9 zJeG9@Ge-cO7}=(V&o9nCd-dse{Re-oN1ilwwFHB~fuCP54lj;B$wDhWT+HTxfmy-Y zB2?q-Xz9#{XC_NofinT%Kg?ywAn#FvzIyK^X28Eu3N9q_rk^feUK~ypSHTw0i(mXt zzrA)rL&Gc~TJZPrIN&#n=@($uwO8vvNR zIuH0Q36q9&4I4CGNiR5l!agUQkIanci}G4`?!ElaiGBfKfnFqFsbEVqZ>lZhu3P6^ z7AzcH;RYuIj6i3&O;o`oBUIXyljUG5iD4WHRx3=*)hII=SC7 zwHm7b4nQue=q)#)-iRO5CabCdMx1nqDh)<6p%CQ`Yb?elLYS_~4e&-+1CcQV{sC>k z9cmRxz&BP+u)Q2JbYMU%K-`K9Ea9~saAYBcLl9Kp79m+ebTJHO{Il|6A>-<$C>T!CjcFF#mRc+4nlu<#dlW;3g z+?GZaLmNz3MmnN_&hj+alri)bCJQjuiyCVAu*&I33qxiTQcX?6@tRApS3!zadr8OH zd8B%iu%KjQq%?fbs2+4Og0fa_9dCd#EkydhaicI`TJ%uBV1jer#P(>o>JYwyvo*Yh z;Lj_Mm2ub$Umt=gk(Py%HdG{;F!8ln>^Ky;8-QI!ckK|N?UbY~0@Il8h0EYA&N(59HFv6cT;ll~QZ6FTk)fdd@5Y{W`!3ujU{~q%J;d}`; z>Y{`pES#A8!0mw{^dW?J0QZK346_!Y6T@M+soHh0+cn5DfE|*?*xq3j9IU&U2@nfe8ExCzjt|932BG9y_Nlr%wZn zfyYY%$Ux+W4+W7Qz-oPjN)qbYrku@D# zjf0b`d{`Z@XOOn7J=@f?_ayc8X7$XZ{>pn)Mtw& z;fPO4hd-33kT=c(Yvn}+2&c~!1$?uk*=)X897m262}W+n-FzuGUdqDiJd-PxGJ@uE&E!kO;3r>>&P{%ajik)X3?%63 zufPA--Lw7pML21zzSPp+PO|0-eS66V=h(o>##d|H* z-rin}j(b^T2oBB7E#9o8ttkiF51nIWdY!h}thY6B>9MR}|jy0nR- zUV&R0vkc`i17?h6pu^SdUNBViYQ1cYA@3Q&v)hX9L9c-cmsm_PRCjng{ME?c5R_#x zl2^Xr_Ill1M{;{Fg8;Y6)qUA*fG#aqeMm6ZKrz{E=<+_nCztgS#G!+xfe_mRwJ{aTkFw12!@;{4x@!oVA=?;Ree`uBv_!jOBDTIGHc$q!+p- z4Jc(-lCf%`p~fl17U7e4GPy4ZE$SMag3PrGfZK+K+Dk^PIMt#-sbM1?fO+e<5v{;R zD9<&QY8w`q$MFUyzg80`4){wpl~+O;DZgT=USf4(o~N?waeoHnUK#jxSs`ah4~6G*31#KFhuQwxuCmT4UUGiL?R)~EUpEPVe!`& zSY{Ql7WFxBBb0#S%A*w$7-t52AsiC$5s4jPYyk@*2T%$OChT)0upC4Y_?Rz%JtSm5 zwqK`qfG7W_Ul<_lBh{k%dPn|0aX?>eEt-GJ~ufO!aXx2qp$2rDOlj zo%{Rx`abUdYEFVx=058fGY)=j{pzC7UxY0HH| zIII;41)9x}M=~}hUnoxt8sEUc_y$mzb7O+B0%Sn)O=#8v$zMHu_~;QJ`P#+go*rSP z!alIw`cts(LLDzy^&M29A%i`8231lB>1=XP$L1unsE-`cxifJXd7O$vCsjnXZt_|~ zV71VkB=JsedwBC(_k-=**SZF|{HrHnsW19IupSM~Jgm(tnkOMAl-&I_<9&(vE3-%N z6>nRty+>T~hMy2{hA%4~kGSF<>;!vkQP}2 z0RO7_E|5kIk^!3k{$8MMu9O)aElr;{)&}qXblS~Yzb;f zTL>+pNZTs#2{>Td|cO2+!b3!a#NHBsP>^gTLfcDB4 z@Doo(julu-k82p{(^NV{Bs4Z(zZ%zB1T#JM*98=;5%Mj$b~^nv=w2!~9V~!tU$@L6 zcR1?D;mbb}8+H}Kp;7vgxE`*DHV@auoJ2ZSiH=J6%#Jszo}~Kv<$_O*hLr*i;EIOR zX`U}RT3j&Xtq_V;SOS!hN2e80X)tWSOW0LR3N7Z&X=B2%ywWHQe%a?19K;$D!+N*k zL9)B86)B+&S<~rWBB1FuL}6v08j=$KoYvqO3zFeET% zN#gf4(#x2-7QVqGI`7(ok0gU^fen)zWd{yYbwm`j{gl^%)<$qxtd{yy1QY58m0)>L_oAapTFxcG9lwxZyOx z&~|4(huVgnlggn4mN!M~9Oc#Ec{mWIL~B`vm42eZ{q}zHk*!7#a6o|^&|jY`Bc$e% zL3BV-9rF5W_DmaLoJqALSTqoF&;Zv@7_`5^uUbL^2*OSgEgHNJf?#A=ZEchRkEAlj z1u!FNAIwUPbuWYH5n6$>aX9Zt>Qpw~P)ZrrmY6+fvzaj?zXVYl3ZKjr`9}27xlCrv z@YTRJQ!O1VYVm6fc+3#`Bn3(3OtE+{3%nAWr3thlFx9$M;Tr&0mHdgKBv)+Y+K`%M zB$5-D3I+$l4rT3=iShxIRI_~wpgbU?*21(;-3u&(#fO^_K^sJS^$SFCa7aN}ZW!HH zEQ|R{iB)z%Sps0j*i5E#8jg?ecwobW^w5tUc;NpDu*ZSjDtL!{!H;`-tXG^t*om^9 zdIAuB>d>PMq?t%R{j|aGuXpa|Wjw@S4( zoP~!hkWJL)z@|-2hePrgX`?(;W3z70%la2-m&cc#r218lGaGVNdR{v4A!(w8fcX`|3?v`2%rIx}iyKbbk^3C9=O9hbZ$D6X*CZy0tf9*}a zM-k_Nrj$LQ1}SdH+dv&sxPcLL_b)ttYfRVqeY;&Bp?$_ky4%x4Z+8{J&+PhOeABk} z%R`DvRAs5r)GBJHnYp(~Sv>aE3=vRa`t`5U;MdrL1JhD2eCh=a>mYiUD9qr9v?- zt_pz9UixO&JBOe7xd;;x0R4`IL#bQix5x&NCw8xvlsabLO_V8Ey49lFKZcKTRN zHZ_gn%NRbkr_*yQA5DF?dfCh zPaAZvz4-3*$LrJU>+5UJE!qKlHnT=5w)&9XoYM&Uw*B^h>wdw-xadOgWk-Hxs2Uvj z>_R-GEWyw)cBGim+bH=5q0q4Lm#BgB&9Ch>r)2ewM(r!mOmk{gP&BBiSS(-N@@O&v z6crZc-~zgXKRs6WM-G-AkV=xb-4k@y~a ziZGheqb5Vzz&^uU3AOB~|CGTj79%92S%NkiMzZle$eZ_-vYg?_i_WG>sS)-6rb=T- zuw48G2^@???Xj4hFyedC5IJ*@tmjN~)^K*LYW%l2R#HNAv-<Ia?V;?RDyPGRMq@uJ3yuxm`*Ra=7pa|r z&}hYO96g#|?5_ufwj5Rq#d!Qmu;chqoIk z0?qyLeQ~>78y>*Lm;NGKc7Q{@B`; zE4MJ;7zo{3yTv$GDq?oP#vlLj-R}?oq~)iw6L+!ur1$4TW582RBeg0@Dnd%7?k)Dg z^YiD`NT`jhe%_h^`lYi|Q?H%9_|10em0*st@eB-fe)u0F<{s9r)S%Ye^(rJ2v#$FC z=F_`$8vHfLUwiY*Ib>MCu%YlYE+UP-=Lw@+q0so!nSZ@=_>o-?szXZ+f-euY83X=k zWyZjE?l)JAT-zub%#L4sDpXP<9Ns#Z?==G{~A=CCS); z;q-0SX9E-;g_ezwjxsL{4+~t?jr284)=x|{b4GS|UH}rOT0dPlb%IhKNxLnPyo659N6^I6|93kR>e^i)X|Ex&M{ZVz!ciJ?x>-2 zT_v_uCsJ#0%H+AAD#G6SdWXA4g0~X95i96cDJ)fZPBvw_hm2^tfqRVq%728^xniug zXRG0I!9Y0u6(j3>Z=s#4q@JFhd=Kdx6fdwT&XX98;Ho_h{Pu1&UYn#KDVaP&NiYeN z=(FrBW0-3Ana@Y^y%9HxPPXSGlra!SX$VUumQXp-`zc?OAdymLqyh-!5e0D|injYnhSUbR9ro`uQkNvdZ)7q_2?H#*u_G~Q=o)Oq?#slWtAk?z03ZNK zL_t&$5O20DlbT8$tlB?J$wh{+k$&TtNelq!5A6upqQoapukqDj!t+ zLVQn{3`)*LMt%4A#C=J;3QKrJC0nX#PXIrWaoQ~L^(53AGG{XTpu`lrHJoZ7n=(Vp z5Ci8^2C>D1)DvcnAR7kf2z)N3vc=3v+8UfBdTcCJ%qo&HTPjscnQ9TSGdp2=3yPUy z1}jf4s}7`MuDMjMMOv^{rQZ*05W1%cvLFwZG38F=T(wbuUx_g^oksoALHGB2iO}Ai z3#lY>!&NdIa5S(_PA0j4u`B_vOqvazV7>;q2(L)!=xd&^7m25~`#u=@gsOn6#+RFw zTB&pneyLpU#O$FR_ixycbbAO9)(?2_j_*5?gu#Zue1O3Qz^}X_P1X}^gpp+d!x~5L zesuSf_ZbN9eSYs|yQ#PfeM9mLzJhd`D`&lxPzxXfz)QxBAdh18RH~Y)UbTy!zG}Hz z?bqDhK==TmorcBQ5^Gz0!95C#@18h*mm&2DAo%D#pxB<=^M=+NqiadKE`NUGFL#V1 z6QgMe+O|a}-_Aih33qmO;g7|Hioy$R7m90TcsW$w@3OAT%GGr+xHd5 zV;ft(tX_;`FM@!;=3-dvu+&Wg7!Q?oFRDe*p;Sl<8^}@6N*h=lTKAVgsWn zTp|TXbL*r;Nt%w(DXE$zFCul?tNk%MpY#1WX~)gj#^(Ne{G9V#>=*7O?o}5=&ZZH# zx)8-tkX?Oe7i=;stM8_wI>^zvO<%CJr^^$n4QfIvBj;M?Jo1oqCWw@cW?=OP_Xtdf z`fC6D$asy&c-GbKls(Uwd zYil?upm=Q^3Y=9<)P(Y1=OIzJF_k zGKPPCd*;kndw*>874ah}Yta$(`M-^w6R?$Ud6}vEwN?FeYg8Z#1>d}tKd_m9n;PJ} zJ}a2Nyng8i4c+Nk^Z2F;m%GWLtZXThKdnboQMSJsWBBz7{8FsI(bT_~u~`w78q@67 ze-4{c9FC}V+66P3$scfMSo%6L{s2Qs#?Y*YnPmH6Kz_9w1>i+Yo9&AMyJlY6s2S{# z!?!~X!^ks0THrfi({RcTd((p7Ve7RAnrKj>nSrh&A;f;wXZ5N>iCAcmx26b$^*0r1 zRu)EK%8}}uG6KOWxhkUWw?0s`@T7)7EIhx8$aEehnvzJSlcZ6q{#ig*@U>oRfyUEtu@uEr>f*T7ou9u7Cko z&>XyrO@UvR0&enHY!0)KaHy8Rt-oD*kL>D0a%LyhFJ7%J>z9=Z&&%P|h(ia_WjH2L_l3t2}O$A|JZEJr_8wpdb{afMI%fgde zW0wh?WciyqtyK(LtbVBvt_6QlJgK(0Ep?eeaEh*9#=UYXJd}b!9Kyh_Kp}mDZCXAU z*6e2^KPm{Z1X$YI2BviEtXG)vvuRNpFs(?uX01G@8VW`^CS$s27J z+P1ZwPK8g?y^zvGXcdTs_YbDz<`)J|y?M}r+aJD8qC9B5et!?V=X<;0pA{guz=8#Y z6^GwbB7DmDgx`7R-M_pmApFL01HvS_=tD;NKggl7kbgxaTKZ?Ty}jslYzIx2iU$o| z?E`(Y*tSFdNvTQM6RM2O>y1p+hk7Cro&3)GW zO8__z0526Z$s2-+J3BC7OA>V+CdwU77)pJAeT^_jRM3}xauEvjju#$n*GIc6x4YL%zi9_{7GoRiw(x(`y%pH(33SZ=AfC9UBvtz45D))8{`s zKXz{J;-qea$B-^hkFUN-64tYCFFpRc;ji+wQ(jb=K2c}Z&UyH?HV@~ipb&&5xpLUV zaSrd1XFbbX3Y|7L4=mky_VU9sk2~KoBj+k*)OGuSTBd961~Zqq9Sxwg5?weKdDjIQExBtkxli0 zFRS1uy-b?ErI5w zps;3g2oRS*drj#A&ZDI6cH^qKB9=1wCxv44(XCGCU2uH2@$q-2PRHg^jEyD9`w&9E8YFPR%I*Bv3i74v$TOCb7Av8fI&_F*Gd zBa+KRRSuONc2R|NxYRXNA@A<8FR<`ONYlZXgRQUp>Q#ZKxoSa&`i>lnezy&>YYRey zotksy_L@Dg*D7o85-zlB%WVLBc3g za%s42OWTbw3x`oz4+{2cn1|T_3-k{TvN}$+;z8og;9z*_tT5n$`{-2~^ubqW|6hys zI+(-S1+xvd7QzPtaGHbOQ@gwIRff$Mi$1 z_ufr8dxYo8gGDFp)?K7h3dVNDf*K3m6Vmu|{^n=oac7LtbTrgQCbXdRmCvhHX4TnH zZ4#jsY74$W_a@BB`bW9^yBQb zvGGh#kEw!qLY@o*77D!d@yJMiNdb7TJVGg}t5nMkcGu5$3oI%71i8baY8>!(@CdYxwiVHr%{{!?ROGcz^7*CwwHx33yZh4P&hAQ#U6rJQ z>E^e^G<(R&qp6@E>{CX;4vkf?dlwZ6=>#?u#@@l$*{|jSyYYWINEt*4>sPiDuzNc) z>N&||9CBcGx|Pd17QODGj7IirtFWy@cxy(BfHMfL7K=b!?o*)C<_*~WPvw}tz|b1? zl|r|_XwfE=me66gzeP{MU>g-kIGvD8GkOk?&!LOpfS-z_8ajcE-YQV9Yhe`8Gz62- zApl;VScs#z0;JjfMzACGmM640DUwVG`OPJ35LQJJai8FalE~#;30%Hfe*~b?EvU^%Nf%{F+@Lr@1=1+n zUx8hMu1d;_HJ(zgaH;RN+?S&($wwn$iE!xo3S9`}{`KWtLq3q$#SRz?Z-u44vhtoa zxr5xvdH8N=g|Cz$Hid%%+@n6tq8vI*Gq9j8)S2QWF2aC(xPm+nVZx=mbcf*J_fG?Z z!-lXf<4_qq!aJ6~-VV)dQ7M*F9@IHHbSf>_YXY*ojGyTv1c0?9ST7Pb>~ITgx?#ru zW9#~Vn#}LGv_RUDp{4c-L19Rt&lB#cGtmpZw!_ZOWVv_?9`Wop*xHn&$uX}DA!roF z!FiH7yln1X)-o%Egel_|t8-#D8S(*X#2Xx7!}tLR(6rR$kBR z{eFGHeA)$M_QvfjDHPy!VeRYTt`~YNk1L*#=RH2B%UR})#}iPB3T1E!_0@e~x*p_B z8W6GQs5o-^kYz9T*W~w{p$j;t^@Q-=C@8S*iRy73DIGvmU!o@x^$8FQ$#n__M|+kq zfsQ5&Q|HpxWE`{^gC1JX!uuQ3mdt2O*l?IbYD7*2!%W2p1|u<(0_H4yy{3s24S_`k zqG6Rm$t7@%oYxXYhn4P`jfRwCX^Q=#$RVr*S>(k+ry~fv%m~TO>LzeLix-&@7>>0i zc|g}<-Aso@VkT0vvdrR=pA<1i6aZUDyMJ%@`+t>K$`X8VFPY=GC5isArHWQm_<~YK zUpRY~{v@>#1_+-95kCKJN5^?ZgYL9)%}I;npwBh1`YQq^+b-aBLK8g$?h< z#)b!I47r`xSo3M%!%M(nGbVpLA;$d6SPF)h%rO5dgCxX?3XgJ0e3e^bx!kktO*{AY zrq;VOIgJ!`)oN`_!;>0S1CkXk6O!Rb{z^#lpI2|*xp@aM9<_*VIDF&{VactlmC10X z@@D6`>bLfGzNEg&`fKsurs~(2%z{FB;*p^XvGwV3Bw{%Qe$fCN_v&6RWdCxO7}sG? zN~0Ueqn5u;!(b$bGco#UQ?Yxn-ReOS^leui!77d8*gNg&=9n5&g8~1bV(8b6N~qfk z_S@J6zin3|?YqALW1Yj&_QoLDukhc2;jsZrv^<6;T?RQ~VtjdGe)}K2mmVVvT4i$L z$9B~shyz>O*|}nr)ZD`6!i_JXf`+;nKzxd-vAI^TfB3M4~;lQnnGcfDQnZnH6 z4gBQ0w^nB6Fyo$|=Q+Vl(ZZCUC<5@wzx@uo+FGj;_=lg416YONTGvH<;w`7mi;DBg zhtT8v!+AMATVCE8f3o}HaqqQDKRE*QWg|o55jmB>ISC`)YF9J#f7spj6s;pEJI%mu zrD0WCD_a|?5^QZ;<;w5RNgGlK?J0pwd_O2}ig^r7rvzjR3d2e4aHmo*^V;bzhF6K+ zQ94FTnTLf-Wg%B$D-FT@Yi|pcK#T=w<=olz6N+$g|LEr!~pqqir&FCLYCIg6yPM$#2WI!H7PcZb* zcm;Y284fL1d7+%6BdHRt!3~y3x`8??%$bi01r7j2A!!cOjf4B*2^9)0V0^UVXdR8h z*yfT1(+vyMWtO@@)Z5r3J3JEE8~TU?l@^vPy8bu3zr<3tm?os-fVy zs+?60eTU%kt;3wT>I9OmfRn#Mx<4T24+rECelq=~o$gsfel>>cMw<`pf1!`~C z_hCugg2qB_e(?!6hsqDM2!i+Z?UR33$l9?bfUZ4NI_YS`=@k|hm6a~A;7R1TlvJi1 z@`jN&4Gt&;zPw!?1bix@&OGCnd z7`i*r?Tjo%g$X-#Et>wVfNvs=s0cWO<#x@8boT&tbpcbVuC!=Oh;jn8_K3BJXnIdf zGuOa*W3e8@LYjEMjA085EpjG;01c)x$5f?4Fj%x9javLyrE&zVbZGKmZhA3I4suxx z91o-WHw-SV;eJF3r0H%#Bo=d{~4W6b~# zM+A-K;0;&BYr(HMQoxdU6p+hg55O=2w{}L=E%UeTjZ(<9Lz1lQO|Lypfa4KM#>K0} zkc$Uc^3e4C>CYd*ll-UWtMDX`G`mIu)1B64mo8x7Z0DZr3Z22q0DP{=Dhh6@K2}}b z`Gv0Qh}B4=3CRE!C*r8}LhBJ?DV>G~xQy|0+T%4mai<6W3pP-7?Yp-sAbS#OXO7&@Mi~TitO^5W3D67(@a7G{Or{?X zL%JlOIgBd%K}A?m|8pHa;5)sSPM&+I)a7VmKp^y2TbSU^?FCuPVwkkG=)duwHZ z!In2}&CDuhJ}0LTdHI;nPpD&2aQ5PaBCi}7t64Hh?8L+6?Pu47!@r58ZEe@#R;nKA(S>7pVPU{kp)^=oQ^;vI|ZqBZibnA+pq}= zJM4myjy4BPNXVU}CR*@TWoWtSY(nu7RabB>p?|3aaU3ZiIzSlFSPE}dMn@8JX?HW0 z!IdciWp_%6qoKzVSS8-(5UUkxOC?JyOA)@|4?(1rwC=i-0APP}33j}o!c31AM26{C zeuO{CiX>rF?p`@*ZGC#vhL_aKT#Kawk~jj#e|6FxB{6LRMD^iL)VN@%Kkuo zO@D(*?hxSZ2jB{<*4;*`GZww_U=`|uAJlOy-OmC-lq%Ge_dlqpqdf_-=klt0rgLE5 zTTX+KJlH3U_;w8@&JaLX)eCO39k`+f`5X#&F?D7rR+aGT^7@(s^{h{l=l99Gp$*G= zyPPelv}ZSi!CfgiBWptjmJQ7d^cgwuK7zU(qiA$6zjf8Pjx=y}ts#jDU`z5dm==*t~+oY8eg6WlP0u&7i|7 zjxv_9+L5fDLgYbn|7*rDgO&$0Rv`sx55{vse@%?Csh1{Sj(}-Xo|QGTT9(^q_<|8q z9phRUfgQ|*#tFf_>7mT&Ep&kLLWzP%f0qmF66| zoV!pE7|v~22T<5R)EU;phFqU0Rty+k<8V66WHFeDGioo)MR8c*S8!K8GD=dN*?Fzr zvIf&vNA{9GMqYE{Atm49r=hF60N`BXesw%HoO9)pjd{ zqltoNgif*>_!znutW7Wjuoy@QC06J32m4M{eNl@TO0HNN*$fQoT3h?gtBc$Lg8)Oa zOb!eej{xPAa?%RL1OQ`xy8_$p4BL>Z!Sia1EV!}p`PSm~iCdUAZvt)y2k$~^HM=kf zCDhpP*zCkCEXKnF920{HkKG+yMz$px@THS)wH|Kd{1(o!RRlBNT^Hs%HaD}0Uf;Wf z+l9H=c_^Z0W&|8pfUz70U%b3%VeRG12d&vL?(9vHi%b?retv8FU%i*UUwv4y)gvmh z>f3EW+GV*cFaKV^_GxZ=d;7`1$vXR|rVl%gHw1EdsL>>l(`YFq5>g~oDm@XR%^BNM zCpVNbX**B2^u|u+;GCnJ;whvy4`smYpcxLXuIlp{^0pjJNL`} zk9}V6?-#VInh=t}DSngp_x<_2AHKPN=l;lp>wo>vz3;yN^Cv$%_wS7zi@#pEW9I0l znW3Rg_WRjQo0c>-HZJL0$M+cn%MEsyS3jrmHbR0gPR2?~&N6%s2Msx6iqS6-V=*KS zODg5qOVGM{3D)q-cN8fJLTABTF&hsV3wq4q!!3R)mXJLc6=SK4L#;2q%)lu;@TyBV6g|tSED! zieWgR*)&NUJd551>XD4x4l9DA(kVmYWdXXyvdksWPOH zJV()xBB2SNL~xokd__a$L*OhIup%f2qrPi{RS8M3B!{jNAZygjMwl(I-LZ%}t9<$s z9b7u7K48yTiX~MZjUkN|4Zmd2MLTzs7%Sogyx5UN5;Q@R?Wp(Yy2SVk)EWjWh66J& ztKl-QQ-eh826AWvXEh*o1=;<^_#%{AfG`b7c##ZKW&4Hx)>aVHF&dB%E7eOBr4a)I zZNuf!(Ey+u=$@ug1|hV)mu2!=2E&H~nQlrPrfT!~6xB$%d{=E>UygY+R5_*84FleS zAuv+td_J?s@YkMFC>ZYU8OYaDYHv@AHzR_omkpTCp=Ll&%Ugp>fW>-KRcPvY)bO7`zaj5S{chwv(Go#YL-1L=i@<@1F2Cj@wv8%z0w7HieK7;AnI zz1|%~Lxp$KA*_Y)ZwZdpEE;w6&o(dEynTUT@b+K6{yHFRr+!tRVwk&@sNBDwA~Le1 z)8qEK1%xLi!V?poS%CP~<6roe>-p&Ts#_hc7H2qj$k}GlufB?t z&a{8(ZtFQ$!37H2$78ZMIi&dsOa_QY=7iLkoJNiu8#$u=@rXOR9yt~Z$7<7mbEH)@ zYvxAHosJu+re;lz+efH-cc_xk0prD;U!_J<-L<1#DFS4=898_L_V#w8zQP$COJSGJ zI3Kz)9Nz3-?C6hm$1>+WA>>&B&~2{Y*J(rQP$XsBOR(aOm2OF)e83yeZ~gtQ=;uFo zso6U5U);d#KEKom`s0s{u%0&LJPidtD9}8l`X8qQhz{I?r%#=pL$6_8`rGe>1Ic*TX*8oxFPC?_SZ7By@V!e^2`=!?L4-+SLH^@!C9^xs4aH@ zcYct3X?}oA!6LsdT>bX$e~%8$w5?F$_}a1MV}R$wuO2+O|KR#}_rAFImq)*O_wvKb zHJ96t&dkg_dvs=KQ{$$_CAT|}oZIQvj?T`-8#k_~ei04*2|E#4wrpp$;y1MXC5w_# z|2i(!U!F^OgXm<~{~E%|n0Nm8X8NO+8tKPip#QYP0`RUzrL5`yBY z#Cxklp=;=~5|zf2386GTd~MKIwKTLk25=S`#l>M6Nac(Or(^=QC)W1HRDwk4WVi9%OnfRsG-bXolkdy*<(V>P z`V6LX^?UI9ssY%MT;=lhQb-%n<_y#Zguex4Vm0q+RtR*VKBw}8f>JaL0W~*v_r1-! zJoX^DU4#IyHomehwZ<_CD^Pl%nWkU#)o7{+wCZ;(N$9Q$%H5zR$<73T?YK?}$OVy+ zmTW$v`-ptxJ#dYM+>B zY4I2rK06!sg2S`7Zq1h63K$IEs;Hg5HR^O9W~TFC@wELMrgKwhruD-1GT*Y!`r-4DFf48shDdz3IqbR z-Kh+QcsurkT`43Hfzi>fK$%ft1K^cyHRzv_VRf|C%q3o-y|TM%gt-dka7{_ZfVaN7 zKJ@w6Gnzgti37uxOfzpjk`MSI#q*~Qo~HW;)zqm|7Y`nO`_Rn;hi|^~(ZwqYKV}F$ z`G@0g?YiJH;I(7UH&i#{GX}ug+P;7D@LO+u2K*wR`qgowqz)Xoa%l4SM+m2k0-yTu z1gQxy}b}1Xp<~LO1KNEqm(}&Y$LOn@dRBS)rSeP8)Y)Ct zIufZHHzsd<$hOv4?bUz$Yy8`9r|;hR=FaEeeZP3`-lL7nv;d~Pm#bxMGsbF%Zg<>n ze7fVM+jf$}f8UFjI}K`2tf*eGcHIg4XFgKrNO4u7S{wYER1%h`r!^?{s|Uz^_9|%5-dH^vTzgc_;5E)l6Z>qL z;cXGL)~vZbOoEo)j>&2;cm!H0aQC-s6YNK{Ra#`V?2)P1shAD7t0t)=BK32mv`GGk zL|0A}rO|7INU=P`P~stbkVi5SF&OB;;&rXvttqqatbu>iw&8+wca z+lv~!t#i~_2DeF|+0dAT=rpR#I$4jP%h~KdvuK_rz3NddA&?Eq%8@jjO{NWX={ssd z{fzM!8xpkFKE;-l90tcLwd87YTZ9d%hZ8<0slz}vQAr>)iO`9r#D1TFGK=7Zw#K2* zdkmYK0AQ)HP&rr12OL6$MMFcB8zJ7ke1kr>tRducl+sZJV)^E*z0oT8tx5~=`z9z| zKx}2iIOJ-e8B7lvh%Y6YvWi%a_YAWaJr(gw7w->;+uJo9vHyRAS%w{U^pq6a!<@sh z1ujZ&rNqgyvIq$rC5E-JV426@*5h{qpzR=w1xp~r2CO_-fjc+=A+BKXY~URX#B`~E z4IA-A2F=ztMM)C%VB~!dbA(AG)FJMHtqSlakI%BYF;5%Aj1R|H| zLtbUDY?nQm-qh4oZ@fF65iQQ=Fb?PA7?4y#Xt(V~J+WBEgfmnk(Ik*JfK?MiZG2#0 zkD>0L41np~&1>EqFBrq>2GFZX`qCfz~Gm&4S%IIdrRQ`Yk9CT2FN%qtz*_ zxhjd!y69U1wg3wK!{XJdY~T!l3WkB^J~qZMJ`~dOCexS5!^VpH&z~PTw_tf6wpr>!8Rz^7u1cvoUuz7$0- z^Bh?dqKDoQ+jKXQnGDi1LMn{urbdT{Cme{%U`$4xN8A!`vfT+9hKd?P;^I$w{@_1y zujhFe+%Ctrwzi*!0QUJjuh;YChS1^SAexng4-d*Y_wX?5hJ_U`&IuIHEiNudc0lIY=#vAFAPTLoj`z7g7lBW*cp*3HJ& zfdOPe&(d||vtT~sV*)gg+38I9bia>v7Ji&#>dt~X!D^qWHQ`J2Pp&V|v0H#^j3}%+ z7-&gqDX&(sSj{a8i(}1gV8HIrIeD%xIuG7^UX=wDl@(1w`#V98(20qeJKXwS{NzN} z$q9ik=Xxon_TqG0%TLS1%G?TyDrGV6i3Z` zaqd>%<#U(&ZcR|=1+5p8vc@q;9wkSe5&(v*nu*N#9t9CEEm3Mrs9iU`N_=y=sNCRL z!R++t^z_W=_~?{^+AG%=t}fkJ!u&Y<`0=CV<>ODEK7I1=<>aN8e|u5ADY9YDw(jmz z-KS1}8I0eZzb8-iBv1Ai>ncCL|t+i~1ir97al-F%3lDARtvOmIDNmlXfHXDAm8(AbLg?GzuDq zqu|D94OY<{6#~5A!N|U<03;(8x+)p^QNX$4M`U1CA-NL9BtWq+;)>*8v?^3liMch> zqC>%8R6sa6h}_9wWoa~6;jW-G8s^|2JVT+N+gb&=G_YBXoJ(1l!^yL| zG&BhLl^dt}%*P4^3q!@$9;>^@O7AbA*J^b`>8xBuEI}$o2!~q;ue;D%>=DGyKUV7Y z4n2MhgSBy>J%E^}-VCcGcJ5VNiz~(&(cC z#Ddaz;87-epcP3FdHWhQaW=~DJCBiAm|mD{JZppIT?MRYDJq~fW87>)C>l=Z3ZUh~ zS)Il}=s6Q}I6!<^5sV2l32{NIv%sXf2~`)NQx@h8b2X;Z%z!?e79t74E2vhN7D$8HRw!{t0Dbqh0U~37 zl?Z{RT$yh;H--)<7S`XP`he90I^2;<-Uw479Z=ZI{$PRRG^>L;QA;QwPHIdwG-TDC za2O;0Io#O<`7<&$T;Zm}br^ehLc;|$n4BcQpVY)230I(#0DSuQyWafG&%&T{EO^Be z{N@|~V?|o^1g`@FUWw*V8PU5|DhrX3wR1%l4PEqB6_f>s5)@hZWQWp@-8=T~-b;Bj zGP4dIJaF&;B+_q{l(6hN|El~w3JMns8^*hw9Va1`9*$xxZ8i!YHZLyDnHLeKg`u?i zaL&#S2o)AioTYu(KidQoaaMjE+3akSnp6j7n>w|M}DXzy6@~W<7?j4ezSP12o1n0r@!q_$xI1-0nU5{&?@j z-mgDF7}Wb;^RI_eg-n^S(Ln`{=%5-Mv z!sR=Cx6X~vj3P8+YHFM#-_fC=nd#|WL&8^wUfX-rtax45^w!aZ~OL{Al^}pKgBp?f1{0OuqZ# z#eZI0yH|bh?)=(4LTl%{*UoQ<#bVpID<`#$?0Y-Xrm`b}phV5hYIuA|MRsC`t2zbo zD4c8v=Ut)vJg{D&_aUgS8XB+?hxQp;=e|DJI-)h#7v_a7``f8ZKp;5PL zLyog%w!@)R085fxH41W+sF_%h#8+XvafCsVLSF64)dXD*GdM z9;TQAwQ`@C{j$)}4%?%cKO5=z<&@fHL+G>MtWD)_7;@oQC_{oI8noA5i8N@~k66=y z4nla4um_IXllBS>qmz}WN~!`PS8)Pe5o9ePUBCccL_misD-eiP8IlJED~0%0k>!>~ znNe9v-4*gD84ryORb?ejzQrMRI|SsFgGh5jNjL5)=AhaNW3W8J+EeNl^exVJhpgyj z2qEkWQY)dWxZ<{w7^`?nw;NcDmSBaVm`4j??iq9wT1#1slwWKuM3{#)zbD`7>B0U? z`0P=nOBNQZWGt+TZ+I}J_Rx9>Ttz{!hY6R+eHLiN5;(sEIUXJ><l1OAhCd9SO{?%>(@?hhdY~? za@-l_R8&f!grX_@w@%V=@1lVmGFmu!905J?j6M7y)Y>qyz-|%96WFUC|t4~ zsU4oet2Yp|ddzy`m@r{Xr3a(n!pY&}a8&W(MF_Oa5K9XTLoq!^5O&TwgbE|t8+5o% z-gBWIS!kzcm2?`HC}%PwAd_- z(eHCh-!@3FRO>=@%eLyZu|0dbySq1)uVg{5f9*#C87`0f8a~$j~1T0dTv{X1X$GKgz7jWV$}esJU?_lgV_g zDx-D|jZVE(u2ACVIj4TmzS4+ zdisxtPyY4%`6Yqc_4n?TN1E5)?VfL$pWieuP+Q(2Kc4btEa=-J*CI7FTWY)w8|BUW z8S8%q96#F#8jHRJFOx|SYfYR*i7&$`sbj`Z=sYPoPFLgs-m={28RlpC>Mh~}1>w z$}_!(XC$6CtSF(&zB%s0EYQXsFhe6%MxfC=BA1Z3a-?X}3Px;5;fOO7+JLl3118M^ zk)SjwI)vqpI7Zpv(HK^n?WwqiBn>;fy;?j4{7o4_Xl<&H!H~x+4nv-KWY}mxz;H^l z$2oD9gYytmX~z=)^O60m8iYBCj@nWv14daPA((r1RCm{-hIf))d z)!={GI@{l-?mLQe?b!2!a1$F_!KrWkgl}TvJP=bSj+3|q5U^DQ5MUutu^h>&cu1DD z1}%|Rq$w>UGzdeYZLk&^s3R)U7rgKblqy>V6qbFVlkTN3PzKOC(#xWbl72z_2A9689Lk`r>(qL9=4-S9pv_sDCAO` zxQm3zXd8nG9X7-x*^pT0b6K4(r#Raf5|2c#3)EpT$%TR_u)O%3_W2q5%P@vmf#o@$ z5BEQP+K3hA+mWZrl3ff20w3fpUoNxIj4VPdRklNoV|lzA*cZ-Y3ab_fnEV7%Q zGIE!5d9l9vSZov(=&8|sXDzSNfIAt$fMPGe(8wnQenaH;ve@1!a|{}8by5vo4T@YM zf{0z-#? zI)|EzRvE(Q#08%_rpB^Rj6VMs>(K}HZ2o97z3}1V$3=xjgKwQ^&SaXG!kMslX~`}+ ztcwQg(^Wa_R;vh45%nz=J@Qe6*panBi1~)*@TyO|FyiZxKMWnN$L3@6b@{R`&xm`$NH?D0*c9`0k{ z0#}e!|F^Xlh0WR7_xLuu)yzhMAKqq?DaosR)XtT;f*d57Mi|2Z(dI8>D;Vh_Kw!yD zz8D%U<$}uqDog%(6adBg@NSPdI1@98_`&r7tVSe5&&UY0x8aW8-nR47q4&G>FVqBd zC}gJig7X#ch+qio!gbZMy?_4?jP3&`L$NPD`1pg5uU`M_)$8Coe|qN=rs-0E*9Ic* zu=Wh~dLdFo0fw^vsiCmHzp$l&wAiAyfK-pR`^JrK@x_O@OZ(vOKR$i-&$ahvFZOK5 zJQpM|9*VsCFHzd>E`5JVl=g?`&;R}M<(uzrJG9 zIA6YeYGCK~<>h@ZBFn>(*F|w7!`qdfQVju}yf!p^Wmr`JLg0OX7TFM7akxX|SPhS> z621DX4U-E(iB;Mf?~r@Q8Rm8KFArgUr(INglHD#y_6SCu3CAMxK#Ia<6=H!QZsN@M>eKNsP5%tLh7TEQ=nCXVD`z7Re?oL$-_&YE?oy zEM{dLo+q4rcE}5{1D4i;9xxM>Aix-`LRZ(bs98a_a>zI3h9?%r09!!d@GN-XkF#3Q z(Skq*O|%$uR-|GzX{28P4V}$;ik`#*aFtDsGzLsZ^BtItF7|(u*=)3!Bn>OkluBX} zD~Z$vxZ8wS*`hAeT>LsUgB_(J_L3mTaLUmXhO(l>aM14RU_ux5D2SCod?#I`!lpr@ z)b*;!YXYndy%>!K6)G!bmwV3y(_mrExaFSqwA?OuJ|Y990k$-oK{Bn@xN&M+30psn7D zH&|gju^uLj|;UG87E(|z&bRT95BDg zZvYM#SAH9F3H>kupcK&gqUDRNBd2fP1@RRJEU#Q;c?oM5_glu;RV;5{HyEEV4hKXW@6^UgHJj56dd z5;VLY*+%&Fg8}r3N73$N;TvPuj7DN5yb~x6vCaqw4h*tGOb2{>bKi#A^J}kGl6GvI zf`086cY-&tvHBWtto51b-Rmxxi4DIozzd58FJgDtrXsTN zRESZ9WB&GfeYHL>B8+d>Rlk^T0ddJS)U0cH0Jn&~tkot&l>=-GjBaFxemBR5Pc89$7taD9sp@H=kVC8Y|K7J&poIgJN@~El6y{0i%C@eFa5OIVB&^P5|D91(-+gQB} zhN{nyXYD+~37w!+`Z3z?Yxfthg5+ee#}63m?Yph!bn{3f1L+7E9B;D>-NQg&$}seo zmFiP}+xz~m)Z-AuqC+$YvGG7*UlXP4c>beE<2_)au3o)<=l=Bv2q{9|!5wVYqEY)f z=oO#e*mc1iLjLn--~I zFB7dDk8=+gqgdlgWg}4CYePfI5}Q8`D9;G&@HpDL!`OWW{yBba7|~ntj!=A9{uBA_ zIH*>mJ3^s@9S1|deO!idK~30(r4g5CtJR8p1z6OQwrDl!MlixKq8PHmehISYG!AbO zqHbBls8o}PIcwSShsTQ82^CG&fMZ}R!xOFn6Wy?AS=7W7TNs4G>;+(@9UAx?=>Ik? zG-;?TLxeq==qPS(S!gLClcDG-VcAzim3S;o46Y};K<|r&FQ>2)P1ywqa8itLBB>#W zuvlbw7yaJ^+rXesic}ZL-Qc=WQIs{=^|jnfylgrNNseYy+zLjBVG>>6WD)~dh$9r8 zb*JRtKJEa#WKxg1#X+Z&;Ad5V<`9pZO2Wj7J?@Im=*SG#t0|G$v>RqwEUB834p#LU z6qmbnj64TLGIhE83_jY^RZ-KF*UkhbXfi{8RTxr~8^LY{`+DhlIdg@e2Xt-4-=Yr9 z#&BDZa$RYwVE9?S)|a%y{eNeN)i~&Vkt(Q`@w)h>LEB+ISfRjAT3wu2Llc=*^kz6 zp0ijJXaff@moGLf_V<)~R# z9zX=)(Sg=C`^7S74x2Cbu+>!HBk;!S%Sg%#iwJ*VVB8AyX9GD%$h4McyCEjnSw^=- zAvxqUX+yUKEXtUiD)W9~p>KcrKf2EUr|mkA<11|$w6nA2Af|i?{jz=miWo~6rG>hp zVRw3RdYqWt0!=X_Hx+K`ByPVfG1J8*q-H+=001BWNklLpeDw}Ew|jfA2d5- zAd61V%f;*mv!8VPVY&a~UXSPdQ@41z4qEz^ZInLye7&AuFdex%Bo}?=*hrB{-v$y>}xD}o%*>I?inpL__&D!&2+@$1b@MvaTz|%OsM~WUdY#k9@Oa4A&ztXytAI?+rPR7(5$j2heaeN_K3#6)#e> zQ8%^?hYrxHqVOv@kOCziuHS$`Y=(5Zfl^)Q%%EC$ODSQUF9(Q!u7l1ck~RVwLbL15 z7#Npu83DV1HUt@*E+hv?-|&Rcg=F$%p$@k#&{C*0j)IoJ#c)O>xwwH!OLJu6H{wZk z0NeE^i&qQOEXZz@46`5(7y4p-R0sF9x~xjOzO_|l!Q#R(3ABppB#bE)S_KQO;q%F` z2hB0Ag5k!)vGb~7FhU#eXL21T7aBpc(?+YA5Pm$?YBU%$w!3soDUGF=Fv|Xz(@k?* zuJ7*O6Jdm5Z^HcclWr(XoGpF?F+4wLBmfLbf+0x-m^?@DA+gX1hS(9eumCoyyQ2|w z&@T4-JG^?}U>nGb8Y_eWN$JoEdTyryIH=G)%246OY{uqczNy9a`9)_-T1**NMruWD zki9VFM0t4;%ceAFrt~+L?abwrU?7!gb}^ehI&Y_!*a#!Jswy2?JqtM|&RLl8P?z1m ze5slp8tOV`kXs!h0lHkR+3B%khRrpj#qu55m6wQsCWW$AUR@!m5-IbF6D+StQ04Xe zt~O=R-gx=!LC1o1&h-#_+*kVNA$e%%LpnH7_RLHxszsvY2#{7QVOeVDn#+zJ5)rq{ zyQpixs8n0+DxYB#ZG8RgDPzEYoW2(Y{fp)A-e3J6;_Ho~WelEf)-+7t(?lO?I+Lb< zj>z&NIv&y(C@q%lCB{zT(NU6dwKd1J695kLR9y?)mKppWoizHV`%lCQI5N z_+$Icxq9Nn)f2{oi^Yu-8}^h32$JJ~0e2{K>NE3u1^zF4vIKw)+pO}91(C@<8w+6oS zN`93+$z*x-iw{1y^4UK={mZBCcl`Yk;qU3gO)b_#O#qf3=?Y@P6lu>yVRgcL?YXN3 z3V>Tpts4%P?JPr~>^$|>srLCGDbb6$vmZSL<<-g;*qxe^sz}-^A}T%Ql{oT@%fy;H z_0pb)lV37+O~1n|c5)J2=@n}I_?_UkY4CaD=QVB9SNr-KPJ8^WjI{4wxNz~Sn|EG4 zz5CQ=@b2L$qPq@^5al&8?k3uXVwDBM$8(9qxxocctl76ji()?E$&u9oF*)ga z@1>p+=q4(zRanm6-ioU_T1Zd2QL=96w8`luX|B_vx``gmjFO|P2b6gk}I;;@tn}&aORy9hn*oX>(8?+)3 z&S96$`l7zZreUZ7ZApAL+EDg0RY`Wz!l;=ed`ujrHpxj+2HJ>yMKh-3ryk%yhh!e9Ha@ z8Blj0w@c6WcaO#PM5$c>WLc7Yz=i3*T z5r%4mW;DX60_(p{`?F}2BDHRGVY#zfUR+!UcB=-s?Eo&_gjj&fxigr8jq4gXpOO2h zT0PUHk#rXnxY~8BT+1CZT*c^{9WoZYDn)UP+^eI|VWXPHh7Iv1#DOJDmfm@y%e5J; z)D);8K=zU-Cp`RZ3UEbioBhCNoli-m*BemR7)f`bhhCK>`Jhu&3*cAX2wG9p0$)fs znHy+}$_%LOje<1UIHI~>!0(Su@87@o_j~v5-`h;%X!?Km|DqoFe=|AmOU9b^AlR*e zADwP?2D^x?>H9ar2&3ITm{ByMEbK{t_*okL%Hxmy`jy8X|Ba#WL_$u>g`-Bf~xP$$gGn0;PmIgLA?S*AC>bv3F@}ZVCI1Zth-r3o_7w6Go z_-pJE-Ik$o)}^}`yzN|bGI>7Q*J->&z?EfTY)EWB_Dl9NN)5k!=+WsXp9!Vj46ddh za_n~8xsb-k=U(jX9i1CD{(0n7`$wX5M(Rd90rZ^9>o_2())iu4{Pw+;Ra%`(Re4&s zqb%evvq)fh&Y`hgD7|5)Aux`-#g6yigZe6LLwOqqocTyOSR+cHM4vUqW_0Snvr{14 zL#Lj2?N9M5`O2+(>=2TvmFK75z5B`i=@yDZZsr~vFTUVnkKdLM>h4`5wcp|%l6-JefRqA)S7HQ-q9N7+I_qG_C0&u82JcqK<38hj?9gY9+?>( z99-zJw*#Y^^CldKRvfX`@V8ep-=`~ftiP|fhSfK&IL)-2&7?l26KQW@>nWA(YeUe= zI}lyB?iK%aTVKO>*9?`O%yYZ+*We2?qxNTJ^vK}Mdn@Q@>?KcbBzqwZP|8W3QM6MfubN2< zpj$MUZlJbu8^0~PQ_zKVL=<%8i*7~SY#QdeAK2~>V;C2H0XhP29HrDV5rMtcpx(zP%>rR39(?y8Im{DwlFLY z5^W52=rfvJPf|fh1hm0!rjM=fKw)E;K8EDRhT*YYKCsc}K((kuNrufuSTBxXAq zA!+P4TpTvojibQApkxpm?{m?V1@^ps%#@39VxZ$O1#`q5+MZXpLLWg_&|r9PyxVT$ z_$_#g$~o>BvY|1~UqCr_oQei9Ty8`igWW=idp?E%v$gd&ZeaYu{jsnTI_zjH?EJ%H zd$yQL$llGS-yhjR#NOt{%|?i4{UN+bq)htSLJ^7Usa$A;Ld0ajgNdl@=m4R2ocv1S z=Z+92Vfm2kLPDVJy?sclUrLeYjSlCGqpZ`H1R#f?!8tKt0-*)M(QfSntv%i!evy;8Q)#)QXoe;OB|&!Vy4gKRpY+`W&_2c)iP*XMkpmKukx@CdS9Pi z@m#>p7Chl_S%w&I$m!(J2PeE;FqxEE^LmPCX?9n=Ea)1EmzZ7u%htL5HhrIA93KL9 z0tUw=qKO^FIXNb=p=~@8gH6Vva?>(Ws3D+QkUCK$0!>CYghXyCp_U1xB#LHh73HF2 zQY#_o1(VjQGD59OyQ@j7xB|MH{vUfk&)0!Yn=!8AUy>%o@$-A$_c?&UdoS*7Gps&1 zfd7a*E*grBmKzryBg%Tj*ts!acEH;%oI3!PZhdvrCIjMk-Z3x+j$hU7*5{(=|6K#S z5wtA9&q?qLU$Aopultf-)HR%2Pv~gugP%Ku-*zTpSKi=^!Z6`CuN@xWa(m0klgCaT zyU9TMw1M!cJz#L_TI<*yZf9xy3xh)rxa6ev zkoHUr))EB_lRaX?l4ik&8TJ6p_GL}ly$CiWU5@u1*^dU=^${K?4$FmM0lcoKL7?1s zq;TuR9}jfjPbwqPn4cTKvbQz3dh+P6e`#EtzekxB-+pUI`{NIvKYE1f_$PL?|N6(j zfBEdm?|**$_=_(f_zyBJ^GQ*Zc3U`p8S(eShsXE7ynFxmJ9g|Y?kJ6xMvJ4FVkRCh z3>F3rq`=qfxdsCjS&Zvzac&=>p_aG+?&Da@&4fi|mvaq!P~H(#5Z0CX3U=ek80smb zyEG!?lfBD49Cw3ckdn`V(+IvA169G-qd;r!X!3kA8B-;LW3)+;V+DNW*!3#Z8T3DM zoe}k*aofRsG&3_;$Yi4L8OF{OxRmT-r(%551^d?RM8htn!pg_ZG{t$FU7%opayyJm`CVZ{)}vZr`*nfy+DUBLBM)#D^O2X7Nn)-10lyua z3cF5VkH3P|C`7LrZX|=?G||uM3l3MD2rH|MXLT)nr&3^mmxXUSDSvmee9E9CFpF()L}F-z;$Q$U#`qf`eG*9aY3JM2G(h}SGxT6K5>zoc!SqW# zk=evqVkwOz5Cff<^Z~@P_R_@?cosGsp%&Qg&l>AR2|Y{dAG2w_pi)qn08Phe2X5=x z_oudf@*`3DJ3BOBAUrmQgO>7zp+v%pQJ^tGhukSi=0I-D; z8y4GjgYIqGYS&jc{g)p}gXq_u3$d6+J7cgDW32~8H=If54k(-hNi?JeV5#tH0r_vW#iH)(P>bqXrHwry?W+L{4z%RPv2 zyZyOxrCVfJ?Mkaz_QOVq6=;cKy6&k|s`XGE1981xsnjTYn5fpPHE*@n>@`5H`81_A zaMrLIDS|<=ljPTs(kGUr=bEgXdh4~94qbRRJT|}g?)Ldoqkf^}bkKHNh)zdy?-ld$ zOuq2tRVc6l@a9HL2N77sbx%_9K2PAL+3krYNUl1OW`n_{$sT)l&yu}yHWBP00b6n` z1X@d+7DS|)zVS()3XhJs+3gX zMk(MhhQFg&w119L3ANbKTahxA>I?+EKFSq)+F<}A3aK4FkMY`oax zq*$%FH0$B?&J;DlsH3N-WFU1T?LxHFOo-SD2HZZZ zG!DCCkGH51m<+7N6pR_i606@~q+60*b*I`pSNX5KufcCB#g;ck8B!+LK#FrI3*+TQ6apN^|Ixclk3*3tNmzJcCE~g|_O&Ij9wqk8%^{K=lJprAHsrmi=#4~M+vg;1%ncn( zAjXmsYi=Jy;Ds^5AdL^(JE$UI{-Ci=3@szbx5&#dNSt3#&g76&)4JY;=Xo633Xe3L zzzT;TX`?}%Nu)gJ+6adZI_w?V+s3S##qfw4fE5HX)Ck8ilpPv7=%}&bww)%}QFBU8-DQ)z zY~A#$h>iyTJ@nFZJ#=FV?b12^9}N}=U-%UhZp@;=;1lnkaN}sZQs40A;cM573copi zdz_{4Nz_@VZz?%!&o(f)t83d@$Gx>K=F-sND;t?fuclY+mwOfep)Pi2o>i`NwoasmAj6(5~^t$k4_4tG800 zDSKnoH89BG%lfr%_hwYcuk`ia{pt+^;L9If-rZ;@+%f8!7zDs~T;en5hdA1Ki)jsI zUg)EB9*MS}RA_syPV(GOAVOq6%m})X@~l;`xUSk6_Pc5Z=F-w&sgZ$n=)n(-0jG=s zFRSuC>FNhu13@nKlwIx9^Ut0c)IQw&Q1j! zfUVG6boES(p>XW_8TP?>vBta>u=!=Vc4D&H8bmIOHAk@RQH$~=h)36kTP7I23Z>lDK@z1qqN7(HHs*h zO52wbH%6Pk9=DT*XnrsgEeyUl6SdQbjDe?d+L>Z0Gh@_NXj>%IyHG$F#uRZ z5%>jcjqL)@#Y`bSXrC^wD(QUg{QaOjnE}?fG5}B53#JF@OjEfgC@#}r6Y#pEeP0O8 zE3;|3Udzg-3sOoM3V02dj2(;WP+$<{0?+olWI#NX4clQa_?x91SPaQiJ(hIHaZMVa1w}cib(gL>yiZ+&CrPylK)KR30I9+37 zv6^NFM^FrzM81%iK{F(>X{JpG`eEe5PGV#>QRB=QC-Z^*6ZY@f=bZP#Oj~ICwp@PX za?d@_bDnb;2Asg$Z)8-tO(r6v5&Bd{a1FCe4U=fNM^lV-Sb!EPydDu0POYl|hHxb1 z2s_pVU?XmnqQi_x>I%748Uu%b*Hf^Pj)cO(Rm1ya#38nRA-!71{16`c-0SNCx(Y`T z&LG@2D`bj$p1>t`-%Tm0K($FfEXqi=o<#2*TV_e&kWUX2L5ALMu}kvT(}|8cHFb zP}WzNFoc=k%nGbG*!)Ee8kUsu`4M}!2nL2_IP%{bVUun zSnd$hw0&mu5xuphRW2|!(wIo1-7|a7&{>Vp0}C_Abi`C9(UbD)v>Kea(UeUvzqD9~2W?GFD6zBYJZQEGJC;56GkPX=S8M3O z*}tDU@nB6uNXN@}n;YdrYmLJg;Lcf3^5lHbGyiQbB68lmJt+VH4M6h0eDS-BM==d* z0(gPGl<(vmFk_lb9<+no3j9_CY-6!fC0YUi!$~F@eIX~10>vd4{je$l?CF8coq;Ts z&m_5)+cQ+r0>B`_RvIwgkR&h*8lwlCdb>^3>FeMA-(8CgW1)MVfcxFWivZf+gPuQv zfBYA%WF;HxM7wsl@O}3%Vvv!848tddvZ|yFMhS_rkm?>`!lzYo}Fe*fV^xjh_z3%-Jw1w<-< z@d8-|K|c$+3iiTJ-&}(=7$uMjU zFNS~(d7Ku&P796o(k~ifELcwBb*3IIBDf*l7+f@%K?u7XVY_g|!o+VIOrL?ds6r17 z(i?hE%_qr2H~f zly5`mOBKR(hIQ&rmK^0BgNp^ryc~;3sehwfZ9@q|R zEPKFZFM$%nl9Ktr-~#Y_j&c~dA|y9Z3B>&ViX5$C43RM_kUBFMN$#vjhG;GqH4#1- zt1O}I>w@qKSPaf9*bG3;;;Y-S8gr0eZ0p4{FQO3APe6pF|u)o~9sq>a#GBw7IeI%X~2C5h~N0&Gz;N zJ)YjIEF`nZ+2rheXZg-TPyEWic7Fct*Y}^^2p(_cCj;q7*R3yCuYPml>vIe;WUczo z%Q053zp#YVf5}a<{5b@Hl{?m9@K%sg2;!?S}0VvHB|T5);O>oG@6>+YegKYYzKnFa_(6F z^2E7QXTP~-1ai+imS4Vl|2Ez^b&|E`sUs;Cy0NpJS^QOl7kf84%8wsE1_QPLcdHm^a_Wd__~;T0&*kK@B0GN6U&HPn^Xt)C)b0`n%wDg; zU*$td(wkM*8?&^)A`6~X*3j9)QvmR%(-aQFjzU4NGGgpom^uldotpYdFs1J&VS;j< zp;J_!Ww1!!V`A<$fHThfKIRVepgGHFpS~V;m904-`3B!J{cuM0c4w>{M7li_jr;GC zg?IPJ10l+)N6U%YnfRPA+kUjGL2Fr_j>}KobGIjcAN6WVl24Q1@|zO#I020K1A0bw z%TGQA3OX#G`)mia+67Qq@K->p04%^2&xGer;dDus3&7+%!h`Ri zoIHHz&KS-`x`$=c_!F?59fzgKT>Sq1hyRqzl`G>{#-RsLmz|xR+T~IBV8K;GSFJjP z9C5%%v)PNqVj7Q}dJ~S#Yyks*o4Vz{pz4mW?I6t|#npt;g4z~=?7D(kOspW~0a9vj z6T?MX5wlKSuTA+FA_*9+;5MgbRGkoG!P{A@E(#WVL5YpFs-b+K3A;dN#xt<)Y(Q%P z<_lf4F}T=ZCa|pHl?E&*0lu);;8@b4F*=xTGhjhUC(5+2-9_XTG69$nJS49rhKS1P zArNIKvm%ipWk)&6Nnivrj3T%+of?%FQUcJCAvd{jDv=5?6A2U;wi@i~0zxsJ6iP8D z3DxL&I1~ycLhBKq0Ck;Xz32z;!zC->PNDn^uMKVif#tM_b}+3_pjK#Z-Hk@B`-#Jc z$Y7ztaIhBycEBN;`ewkcdmp?v7+ddle39psetB z(XF^?_I$x^=}(D4CB5X=?Iki_g}NL*3TPPo_1iz{x=StiA-#ew+Ql@&QYq^HEQp1i?tKpu{+E2ENRw^#UnJ zpj4jDKmxtYp6oLD@7D74mL-9v3$%JdB^EiZh0M#-E5O@j>ZpYiBc0Ilg+NC*GY!8h z;3|x>_ybVp1(e0)@W>=*kx-sSM;JyRd2VjL zgV|s*=m}=Co@915n}nT%9FM#EuZ-{f_%jIdn~kSilTpox_`bTd`ryXb0*N<6)##VvaBEkZ}XHQ&KCLJh7E4NB;;TsH3qFdGt%c?`o39p_x{{YIYOV3^d zgypg;I4l?}IDAu(SZ?im69T{O$M+mR$nLy{|APIH`w2oF>T-5mum44;g@A{Ifbk$( z#URIv>3TyB2#xe2?X?VKFf|McxePC!9$>o3Ie6>BDbU|Usl$A}y!CYB{j2v@`0v7D z@R1Ot!u;4+=fKHk(rIxZGZBq_V#!8_-D721P z_JfsD$4qcKi!Pj116d0!%>;$*M3R&7X2}vg(F6!_B#ZOKX}c7qMSW@wq*vE0?U;#T$cw)u^b%CIxxO|ZRNp-A74Ir z#tv2r;?ZGmYw83>Gv)E}=%Co?SQ#28nKZg6q9wGi1yo&Rqmvj95AT&-f+NoyE;}96 zC^?t^UQ@)y;3$bwV@|j{>UA8A4VU-4RW8D)879Vh3_`2hhCo$oSw5TGuC;2lDr)O| zK)Q-RMzvRV-vBurScL7eVVtyi+|ezCbpP1NSrq3ZQdxJ{sH(nd;_OE(T9I_8Hnugap&rzGpgH{ES|IiNs_BxStV8oa1 z1)gpg+-_B)wt6xsO_4PD6Rr~)pK@tjPiSpl;y?(!>U@*vqz|8G%z7o3*< zN(yH~;$%UMNQ6a`4LwvKmBXb%6ZK34$IehO0GK9sfJ)&jNzoAna16gxhNJ5E|aeJLg1kOj;36Ghr6Y0Wu4tF zvuHd>l~T#jH?y^_EilvQigDca-n$hw0N-7&%qgy;WH_u^UIxh zXM4$spIy2kfesfoy*ac~XhE2nKFgd$B<1e}S@1hIvDHguu$yS>k9N=YK<}J00k;Ov z&JSf52wUo9xS(!A+^iE5pWlCCfNP+8?dC7P{<^<-=FFsl?n#ZL4Sr{54V&%bB;De6 zXSRQKa`O7*Byg?R+zAS#sy!xfTvq3)b zrw#JUFL~_PNaPhSGFqyvx8x9J8ck}nmzMR8GbsHH7&a>WsSp@-^w(EEy?XW3sjp8h z-FWxir5j62?=QWFO-TWkNAdGe;iLF*{-1E_uS6}_$op>-?sZ4zS$%6-9z4+#~ zCw#ux*D7O3T|C=2o9au=oZd+F_oq%ii{5rS;8sqh-cp`z>6^|v+CeARXRsXOhquX) z$AFf&4T=5H_}5~fur$;5i%^g4);|#gCjQFdtGlO<1R$SnWmJ0n7+@ZJ@Ycs4Og~eV zkHkvlvbO_Wn_(v^OxzPqr7U=lUGebRX$O?*BiI{thFbY=C5#$&OJw4qz~9leo7L7b z*F`iA%kMMhHT;g2Pmf_5HvAm(nClpad+4KB+OAb4hvFSI#cnICB#arVh{~TCryXU= zYdCugl5X5~Wqf$~7Eo(2YuJetil*M>i;K(4sf!}FjEfhwFhG*sx9FW@kUWoeYW|{O z?TUScd1JOKtbwr-*#(AjsR<4P`>Pw(JGbGt=iWAYE4clG;Tq)b{~zK$66oso;)VV9 z;>CBDU-tV%SbWOLZ>Jf7@|qxKPKs*|nH+|3odCIPMg)@~eyx z!iCr>_^{iLyqQj5xUjL^Zgdscf2VWEota_NRv6CP6Z74yet}>=_MvbZe-c3){u~a4 z9C6V0EP^;F8bqYkFtnw*fuZw5_P>pS+(!9it_VKoS^pNX`mzWvl1Iy_fxN1NjUzKl zrYz~eh^s1;ig_hWQpzw?Ocuz6J{TYyS`A2uvWzYdz=xBxuiay%3&CZBi|c4e@XHEV zHNZnO2!9cg*y@XbqOb;bs8w*)ghWjaFmPthd~DCa6KvocH?$s-2n!UBkd77aVIeHb zl8Oi;iGl5Hg<&OdDkTy<=M(A!j&LHb^NADQR3k_jxUUV@n87iF=yvxb((a--09a*j zbQt8?1OMs{2BRS*QQ9S+&&aQ$DB-`-JktfN)`gBB_^LJrR99~P91A%(?u_o%YRsEM zF|v$m$}`Fk1Y|E!BfBGdg`$W7^JFd4%wR=|HDk?@jDVM{`#KJfCgZ(ICN`3#crcUU z^(@O~H>=P|DkX z_x&$3=q-%DnoIYphH%bxBYEY&5MEc3#3%4=*hRpF%0%xLnUt5dln6cX_^X*W`p=wv zqkrv}|NQpf-+lpi`;Gigo;27!(|=}CH$z=x!jmBK$yx688#}&+{AO~NHks?Q*X<-3 zMXB-8+Z+3jo;?5lpU=L!|9EpQ6>4-YK3on`L6WQU-rDGa^a(%^Y0(^9L0}x z33(K-Bg5c`{aPIl*>99I)5po7YIAXvLqYJX0n|`lQ(10W^AOHtv9o^PRShjktg7dpYS@9XhPt!Q8vQ$$B(Xg zj^DG60;gOVVai26D~v-^>FcxCB$GaSZC(uc>FKhw0MB?cTQ@D^n08 zK|4M@R(6it8AvJfW-kC^SmSJ-GULX;%EnN{^l4W(Y#*u|j%h@z`=fiZ`=E=011l_9 z+gw1_C14DX+c$A@aQNo%XH$bh+FMhaAH!>nmadG$P}#pa@ss`4E^COqsBY$zrpRn= z`}&pv<34-3otj#fPHKM9O`_+=4RE2iH_PRlE*DF#q^gndvFe6#+uL{S?c6yBxPQXi z{YSq;?i0N|@|dopyMJJ>-JZMKj|+c!Gh`s!p^RQkBl4_(la z97l$@tG>{x?`Ql-ENSgz_|Vhhcxz-lMTm6#%%+Va`3?yR_O*6~BGf^q%7;D%JFuxX zxs*tNCe&XcnLqnQiF0n~Y*(N@rBnJH2ewBFVZY0QrUCe2Bi(HuR(Xh;27g+nqcG7} z;j}+&XzHhifg}zxq0_2C;+^4Y?jb^GKi9le1n1QgjP|)vgbEi5)45_Hoot8(7t%vW zo{a(*e=6VzF8q|w=hV^Ako1ZILi<24Wq~`8;Jg9!z>Z<6Ho^$7k~=80>{Nb;XpR8B zqX86IMu6?WUJa7lb`UY_HCB8)uoJK|0U$X5{Z;*MSJw`@=B|Nlw!>Z9J8_~Y4N;2< zu8iY3a_ijq5HPCn4wAB9w-JS2#kKIoW5jwmkcbS#T{Z{v=mb-1)K>u)Qi%}VkF%jVp-7^3U(85MWP1eHzfHpu3tKj7&+rIimG!kSYz(oEHx$gUVsbCnL3Jcer&&jcr5MnrjhXs&#aw#NlMCTnt zj-}LBQ6_Wjr0DR8CR5~~4lR}=$p#{DRi-sZ%ZRf=jjy1fiohDu2GGc%RK8#4ZlKtA zFEwj>)N&NxE20~qQa`l@Z4#Z8NMJ7z9ckw>gm+f(_>Rp%`_?@LweiWFHG3W z{ji%thV8w^y}d@4ps}E^Mfr$*7C~XymmVfOdz*4SEWG%kE0NgrJ&bJ%SC-4>xUgez zWA~*|OrKAC3?+fztu=w)m6d~idVuLJ!Zeelb}|4ZR9o`c{f3PP4=y7P|vhcXTC3;YVQmT*zo8VZ@HA+*2thv@u;tkB<3nGS{J#V?nW;Yz454M&s;Lf?9V z4kS|EQ)5{+{z3pv3ou)d0$L{4nDQaX$8@a;1NOaA3gZ)LRfPm1tE5qY(i2_PuhUu! zQ2HkhpONf{S^=$|h~^%7SnQw>s)Ih_qL5c5azbuYk%>{`=~`|@MCqi`YM~3Hg=VX$ zMJ!`a+n&a& zNRt(-UY!weDzqx!f-&_V?MBS@kf(VhZYUazVQ~vVcTSHYBs3KY_6F%r0`U#Du=y9e z-=GyE=vm}LBMd8O{fLoRLHGebiq|VAuu$V~(1aA!I+0>=5Mp!#Gch`jqQcmqD}hE} z!Q*=2$-WrN8RAH;L=x5@m%=d=`3ffvLhy|Ja2#Uj7-r5W|Aj-z0voW;Vu2KT*~0!o zG!dc<*ax#OeM|3rfK{Qlwpe1*W3wQKQXq7BdD&uPQYD%dT#Z`#GXUI@u-u0{OG8wO zv6SE$kZi&F7YL1@EP3cA9kyAhhHkV$T&q!-RMNbkH(TV^^ncTrJtQuehM?=Qdoet3BJYqm+?)#>ca zzFpaUl5HPrngrs40yoK>kYk`SAlEs;2Y}n23GIGtOncnJr#;zI3W>9fX9~!zEtB5p z6Fi2*dUdN@G1j}Aubw-%urPY&`w zT3QE694=jags_fdFCdX78|G4YO3AalNU-ep0)o9>?>5T6wh_vTt4l74EdXKMZOc8> z6!PZU^Ccd7Hhn&ZZ0*VYrcmd`W9QEv|M<+cX1%;tlIx_uE2}GSo^3Gtxu$IX;O;#& zF)$ySHT5+K0`GGN3G)=37+TUSX@qj)JeJ2+?w;O6gQJ6QS#uTiA%O;qeZIxLSnW87^SHm>$nmHK|uu<|anc87i32Qv@y3$gPo?-T``ifR@xmjlfY$gDtnS1N3{% zDAzSMw<_pjppBbbx^E#~7RbwbeEG9~!%U^~QG#$B+N@^S^)k z>Ae;?X+DN~Q%;|G_5kac&C#HDI8X2bs!3Bj%3yfSA>19HO0~;8aP^nkrOhIhKN(%^E(Ky(Wp9Re7(Z2xwmsKgP zF|VG3I~bZRlrg{#3}j|yFk1;*Z;)8dOmdxhV#iRm;5D|?SzHjgji5{m4DLK>Y&FdG4TktT_7 zjYi?UHUV(>kr0`M#v`9AA*d_(Y_WOBh`IPhITCiqjmyZkvf;yQ_m^!Rx7(u@!#3U! z9o_#gTR+mYTnRXWZ8mqaSD@MJM)o9-9q-(56H^CW2Q?h?M9p~&Kjiz4Fb;%^;@kV! zIA^w+fyMB(=^9kAmLAdq9nv=dxMs9V3l3uj4NBZl2}0;;D5DX56-Jz{$sgJoE+LjO zRPh6UO^D-A+0VlQvZg{RB%Bw*t8l6yxEl@aIKpAUQ(?eM$exTYg#>EnDSZwtg>sHm zaz{w-u#jNX5k?)XMOuVdOL=h_(~*o0Q4Z}GVoQQU8!Ok;&#F_0Bj_A0!dfMg5@C@8 zL%3Cj1qlF)g)z7_Ivjw@Wqi^yoxcp)$Sn>nE+sYnmmDi&28}`VBI|`2Mk(}K@Obqg z>+J08X(|c;AO8IF;rl=*N6pSaz1MT`2i-w9*4j-;y*!CmrO z42Ux)s?|&tOId-gbb35eMF?_76|3ALb1gbJT8?z6w!dmxr9cASg~)b&ee5L z?KADY2xsiYs`b_k11u(io-1>ZPpcl#f*noI_U0$c^8NiP9 zEk?8mqwg0fgV+lr8cT?+b?$$Zo!w89c^1cQX=?@S^u;z%#!^~sd1))`RKd2qSvBac z0^32#1a_%aSr?VU&NgnQHzXuv5|WV+C7GZXh6^uc^GtB%JM|rD3YIY4tyDLLVFu5c2n3jf z=yWXIoyIDh6!=8|9os^L6>9>fkz7&!s|sqtUJSrnjwJ5hv<6iYk5x+>_is?xEGlVs zzCm39JMaq&s3MFOF1$s%uTGF5#xPeoBEL^Kb4}0~%#E~FLtdH;1#{D0FWDVUH4}Qp zFxjgmO8OW^frTp=D25t0d8>p$t5z%IZBunu8}&(Yc2&EOK#7=(N)2L3x)D z0FJV*!R8`yWQ!t!g-xOr;}7GvNac^aS`2JI zM&O38u7O4;&2-JLSnC6jb?_`?S4)tnhY?m#EE39L_sIq8JB_Z#1MH)eP*Zb>)ulvL zsP256U!C&{xwvm(L@NjxKMVFoe~9K5{lsvPxWNWE5Rb12)m=a=9q1$-OMZTl$8N+p zS{}azj210iH~;`307*naRJDFVZdn9ckWnGS6(ErKs|0*>DNzx^i~)GSh>`PJN0>_- z65l%I9jL%(jmAoeFN@%frMg#m!04}dxuWhOEs$5Wmi&1Y;yEDKY<5B6rF=eDQ5Uh! zs0rn&1hk_tp_;5b;UEEF!~;)X7utpIHsAW`AO8{n{_*FVN{HKAd!293dY)Pj_8z=? zUV80b_qfLqW9jUfC#`+$!+rI2FzBliEdk+H){K1x9atAyhx_WlTewySWxDa|0L_RL zEte7N_V%`%p1R%B_2}H@{{EW-A;|05xHS`O`|Tyc@9ug9n!^q` z;N5jNcKLP)4r3+=0?50gEPwwv>aZ`41eTtztt$R*Br=(o$L_W$|2lnWD>4C-lmRXU zOTKdtuROeR;J%`nnY^$EAvr5 zvFC!mps@TGST|9WCTX(QWL+us?bT(lT9Q}mn3N9eBx!BM&I zGE!t{>!U%C^&XiO;~HGiHF#=VgQJE9Z)up6ilmKvmP$17?xmY7^<*c@}eyQ)Y>{|#?KShCz>Tq`vL(U6dMZ8 z;udyUw&h&Udny=cRodQGo@*_~GM;j|TzVpKOC$bhic#vGtniRui#F=tX^EfgoqM*YC6PbV_e+p;T>vfE zTWhKb@>b!vL`??U5J9Wz${P;VSn5^*U~i3@LHVX1IHV7bZyfv#7XWw(f7Ti#xw(;F zA%t%8Qb))?KKUvt$+M`Q-KlSnMy+XZTAdyfwZSe}HGYkD3-SOCT7~Xf8H|v^A&0h| zWKROQ&LRt8ojEJ|`g9CUN3x#5^*r#>tetVHk7-~?wzka!f$+fFE z-)UkwnBNIHFUSi;u4@ZSqNBnk78bzTdDULA2bSB56_&vx1aeT;us9OWlTA54qH}0L z<=n_hT(GP&H-I}>uq-#C-lK05+7ZkySQD=Tu-u%9;#d*R3F)LhP(V}FSDNok{n23+ zL%o!NA+s?kEoF_nw;qV4je~W-MM+)B=U2$mGOh8#XA?_oeQ6zDqH{Q}GifS+2bA@$ zusj~2x-hRT4cSGsVfppfea-F7eXX~DQU?6v&$rP;_g!f%lwNn0*Ou1SeH&~31Iy{n z+0EhR`c{}3Gh`U}?K9h8;lKi{V6i~!usKCwSD10Zz_ET6>hn{7%E*+m0INq6cyM+9E>~z4-Nn8@qR} z-e)g;W2XGwNFe)^>9hP=&syD+j@6B^j|E3{9kd+iEwuK{Ek!av+--l@{BX}Q{`J=n zO%m4W`mh@E+oD+gawHlRavMJuEzZj)#!i3S&j1>UVJCRo+37dg=h0*K=se|w^o|_U z(%{bZP2)162#LF?-d=s=UK@bH;@)dUkENBt*T&Xv961x)GZ7WgRw27xg0QEIPpIqU zplQ{6G&uf9UcE((qspSS(O^h>{}>_<4(TS9NRHb*##nn(fVRijeSpp};Pbp;uv(L> zcsr$bpSe2b>hwSt=j?LF&X1{B3aB-+WH!Jz$HqE79|LkbdU|w_Jfww2%)n2Q-+XEu zcaj=`#+UDns{t3#y$;9yI9mQNVgBSv9f5)PG?q093(Q38JmItp3~NB8 z_N`l8wgz&p{swy6V8ZX64KCLNXSyf~hVQzRC868F)eFX2tlCa!r9Rd=ftK23oWMkM zcwCk;U4>K%0=k0OjYMJDEZr)7&e&Y8j6y9Hz^(>%yEdyeV=0;J4WYyDXmcPB3)fM% ztvjZeibT4k>gO1qf>=tY)SA>$(j$Vm0VVTGgai7EwWt=9r`}+isdOmfpt7MUxD^Ujn;1Sjwh&4Ot28%w9da&`tC}_& zIjVXHcdtOL(L6JEZo=gx$AV3AVpTgD2#NN3ABRKXwyK6<2^NPP45azpZEkN>4m*w< zjxDGGZqQ+e&|w>%Uz}v}&pg5ELCZa8)9EMCAgt zpye@o)e>yQ_1j6=f~G#p-J<4h%$vvgXjE`FAl!IyfwgZg(HT#~b2%2ifjAN@;llFt zMMYlI>VMqu1&#xn1g&wDi9nW(u)wfFCn=J0pn^oIvSiwhFaqZ{K;Df& zrQS?vGAT7rL;b?)Q37;@;0mi{9h@L5Izh09im=Qe+N4p+UtP&(i37>2>N-I3Mi%~? zH5t`foTPzS!j;$G6#7VsnEGcOfLn(D-r6iMI~JO}bm`5rxP8^0UEQnht&MI9^DQ(F zx3WE| z5@Tk7=*9s=N@3v(z%5K)SAN^;qrmc$Loo6pZxYK}ilRZyb6hdg4AhZZ_+2iCe5ta^ zyeO9!1b78>?@bVOKWI2sLeI0VaqExwOD_6;-+P$H0zo{)&>p!m34kq4YN-50 z)D4I#U+*gQviFnGkE#M%&IVIoIg7=@XD-et~|+h$^JKKAv? zMEizN-30o7Z_g(Z=1W0qU@Y1h+8bXo6`Bj-5s09{bU}hGeenp;H`~?Nju~_|i_EFJ z@F4ZGBB6_hAuM?zg$DgyX9IAphEP=!)^azn?NxbLRBHjxapkTGhX#Ny!2zr$&V*kO z-G0VhcF}S?h@S`(XPA(o4pXfR7>^^yi(~S}!PUJWk~f+Me*EF5j~_n#^@pC`=HOUx zxUQ+VviD^8`A+H}Q+)kqaq8Ccr8=N*Z*wp8&zH!41!0By(ihxo*^xkgg9Ksjda)Je z0ys!qhD3{+pk9Rw!)+D}v!O>G3<}-zI6D?=XYin{|U&ok@df;)`;Pux21b+wyaSpIVQyqkz0UzGnVy8hORpDff;u!u01g7U+U zq>G8Zhht+8tG3g%ENIZZ0;%8gLu+wdO_=1mfjMMt%+Kdpwi%l@6Y`#OL+G#(xGm3M zq@Wuc1{D2f%n-6X2PxLdW4e%fh8aJp{7BXXHooJ-ZFDE$Aozmuu4cOW-H9oGm2xDE zY*CNPkm8}Wp>yZXw63)xY~sur3{`&R7;k!3` zN3V{m%gfIY#=5#Rm<Hf*(`#-<=>;HD#{GU%xSte(t z^g1YK))< z7=-28@gsdhM?jJd@@GIU7Red}S-j~JCOe6%!c(VjGlPsQ44UJaR3wu`EIW!8kPC~@t3Q(Jb{0Fq zm7{9%oPpj-?if#ZvYL357;m5v+Fwb;Dr973Wr(jSMVA+L8n0 zLa47Z#K_w3gqB*<`A;vs=TSCqX7%n}-VJNkP42Qzr`Y;|A zQmZYvg6k2=(SZC7^Z?7J@TWq9k5Lte#wyeeq8SM*eg}b9V>z(SXckw=X3)^)LAVRc zjv#>sIP?9TK&*|=HhPaheHr>JPa!yhUAPr6xC3^$1&SFrAS5^M5&We?IA$0LT9pj9 z1Aa*(!6HJ|G2kOlX*9}Xu-Y}DDY&AR0q2{UUZZYRv!=wpy`cHbmJ zcFSRn>|ij_${;j2CNI2=42#a1zkQiaG=9wzh7piq5MUv^cjYUBx`KdRFxmEJ&5?eU znISj()rlOKl}1F|5i}t!DZab3Wc3m%}_ra10K-! z1cpyV@*UgWz9ZM;$TGNYF9NazhndU4(KFzwTRx_^Rn+POGnPAJUBF;@cmc12<-yXrdv(uyZa(D@S zcO(RPcPX)xjMmQ{pISs{rj-hEg2eck%FC?TkWVO07k0>tUrv1ixABEvTsVI5>J=tz z2?Sp`-!1q5Y-U#90R6SJSF8QL`l(y6Q)O2625O^Jt7d^5SD1g@z~Hvu-Pinwy0NN< zHY8+01Fc>ifhaD!CMd}osLs3h-P{AuVXo88c$vT)N6aQ7DFbeEA6pjrf+IkY!yIan z+EF#K`ox+Q@U2TvFJ*23cSFeCj#6nG5DVt4J-sZr+{Zmt96|h-Qe}riWr#OICnHZ?$D~uLEY~_5T zmBQqc7$*M;(q#CITUEdovnJVapF_|jl*&0KO>wZC6Ht|lQ$W=muvkD8fQ&tFPEMzC zxJ?bV+;^yh8O(UZoIL2nxzhsMLVz)3e)8n?Apm#p;LV%2N3W{Y>a$nRR#sMaS9jOf z*Zc39`}+YS;BjQOGuy@Jqn2y+7q5JG=bM?uZfX)P-v|2sKiI2IY1fXxuZHLih?Vg= zY2%8|WgsuZ<+G~SY3CH0Jjvo4OdK_q2s5U`kLp400DV4>z$-cnZNidK|H}>rHWJ!O zCBGlbLnyawemnCvAhY6HxddWNkuBs_e)xiIlO-F2D0SphmJsWViM4<*1k)KGN6S7a zo)ILS@e2#qk$r`7V9cPCum!`Z6vwbS2{_*FMCKKc812ErY>RpdTVafylX@zNy)bM_ zSP>)qDp?Fs6pfgyR220_g2$k|LYt9xg_a~i;8Z9X385}2ovy?q7%0Ph1P8FdYy~_Q zgXao&zo5F<2m`GnkX|7bIvS~Xols?^(_0mqg_(1e4y7MOLzPJAdw7SP-c4`#QG}W- zSdCykYN7ZF!)h;gzFsVN;d7Kntk8`_^KXd0U*K-o3z&9N*45yAAbj)mV=Hlq?_4inpQ&o3KtS8_{^hW+3R3p3&JQ})()8R0-La0 z0b`G+1UNPftA_Bsz%$mo_JEs8EEG1deZkIr%73tSeLqblXmo%U+fqBW40qa6`BmCm zX@wFI3zW9nQP8o%EQ7;NB(}>=x*1mJVl=xMUPwq90trLRG6`Ad!S%rhgOb2TR^mMQ z;v_!uG?V#1oR|I1`EJc7`#4*r6mHuDXnOAXzVkzkz%2hI=f(Zt{zU-;R=h1O_U3R5 z1xdn`ky}sk3PSs4%rK2fMUvexj)gbPSaS?47t3F{Y$9*NbkgvP49XZ1pp7NLRufZY ztb>iE+&t;mR1wWEXqNxV_d%j5iH7c~vZ%#Nm6XMS z6A6L-G>)clB47n(VI2(l^E^U2*qUev19tbfyW8DU?|{I+1_WOF-EMb#GXGM*cJ|Aq zg5!e!z&^EqYt%jE&gur3{v(K>15?ywW&4#DlLZr(Id9Hdu3()vLx|N+Io6c55wCjgb6A;N9 z2$@;k$hX+K?w>k&c|lXG&wXU=kUu|Bt9sJOHDjz#AT<*~nb+^!yn+QEw9nVt!fB&s zJz7~^Y-n8Q6JS5_@drIs<*`H4$k>>*j52o)Fv-1T=1y{JC){{8MDQ7ni|Z}yt;#v5c!vl zWSRY()ZZx@kg}LgCsm-OyLLJKkrST7lb6(+ zP%XfE=>4W!fEG+1g+LTA4{7ccbyD)A;Lf4(I2!4NONZ7oa$~(y*fmnIx@$!YRs|Cx zDA7B}f}%6uGG-DcA@&54`r@h^Ig}bqi7B}}NDBzNt->VvfCg-RG;^Gp$lUnL;9xhU z%{yB=aOJ*ye)t@&puN4lqo=qC>h22D#Tk_#Z?(GdP)>xOuY=5 z(IMD-abaPh?_bw3UitjvF@W!HM_;*&30={Eeb|w{~N z5Q1nIii7K*lJ?HAIBAmDE$^!Jv=ZY9P`W^!G@Ekj1ehnaKgR>Ai{3)dQfYXu9-bs2x;9&M z&Rg0p!53VLdJz!~1vFwfY|(8m^v^x4M=C{o0Mgq?trWy9^@1Ox8%eNMaQOi|zg;DS zY4o7|m;a%O?rA$)iUxtq2!8H5i!t;-FTF{hg8L zP|PC3)?n~Ku<1TQc3H5r6@?3cU*>VJFG&swkYgN8Q8Y@9Iy&zATH8Qx8yioxb_id- z;JYu_-O+@nXp(QVp6VbDUl3?+`~b5G$E3pxIlK$4&;qq}%z&m@oc$iy^kVU=F9@8t z+2uHcu<8)N;c~R#3nX%2&`jKQA)^C1S@sz?kQh?=iYn+ZGqS8s26+flpaqp-4z@SQ zanq%HU%9WdY;T@n;$#a1(lJ1A42Gk0S=jDo*er%ObEb0*M#~snM=>CAnA>0z2%KA! z_rG#37mKCmD1sCSfY6{Lj z5$F{pU#bw{HQR$oEH@VO45A#t7&<+Ia|9~|8ex>^3kCxosZ{p_QQgp8MQ*(N^_~AJ za-jp*0#7Fcf%g90!}g<<9g|m#3&@E;}BNYo)*s+x@fr~$B4X24j ztisjXk%C%~hsHyp%oa4(2l9qneVBH7hJC+3xd2U<)=CH<1Cl?iRUy|>x<35qlZ889 z-}O06Be7@=pI0}`;Ke?KdwpEM01hyUw=eSQQXt1VAMH?AdcPU5c`1t z$^q?;V*>Z@_8#g$`f02TxCH`lvgrun8@X^y&ODLn7LIK?XRz>fns$45vrNf!OVL?u zme+Y1QIy>HvV0KCx1eq>hEO5|OS^(0dt)qgvfzK-d+D-y5C_^?)rjv~oZcg?KQgU9 zm7mdGDw5()ItzkZYndPCC>fnWh*=&-STggZ&S%!+w?nrxu=sL~OIwoG53?qrHd{VT z6I3^w0%06RqDSVB-J@sDe9H(ev(=hK7niNV3a zpSQMt-g<-rkw=<+arpLd?_f_L_s!AX(UEXnpf17pdw}oC_r%`n%4+q;ABFekM{=?7 z3+F3&&)N1q=o}cdqyKT{?FTfAT*8eg7};E0;^`Zbg_;z2N8^ zU{&Dtl}n&i3l~U!(Haa6Z0B_y%8!IOdtpK1BfxV!laOqY6uEdkS#QI0VS$UJ4Gb_j z*hbp3P-Haacs#FBZ0H54LMI{eq&cF-INJlTB_`Jo&tdwEHU^t#*!vo396dJN6i!we zW-lu##L7{=QO~E$6 zYcPncN_>k_W~Nap69y^^{B{Vyb`XaJe0^5hm7pya#y&;nMsVcTMxnz#l~D^h76uHE zmA|4FiDq8Mq^5l%361h9c~!XhGQmt5F8~MY1+6A&79=@Z9L>$}Cdr|C7x=H>v0Njd z1J{V&Xr|B^;%Fzv&#)oE0qjEfB=%w~NCydamR-)~O?w$Bea<2^S~Lcm$gM|CUkhS5 z!r`KGGlu$KxQ>K12{d6D+>K1e)?Jg+k&Gr`n;EZU}M`n}# zpv0IeN7O3A?J)PFgn|)tjx>Q4C1!1ATr))9fzqHS3+sT{gX8fDL z@7O&@^|@cYs~pi{3rrH6{K1_a-x$~~-+%~f-_cDKH0lVa{X3;Wfc4h$7DdoQySZYq zI1_Wuz1q0YijEqMKoK9R}drY-O-2kUBH9wgkF^5n_o-1J*PkkV+1OZg<8*@>I7&nNDHN ztSpM3U!R?g$7j!nM$cyicaJlp$7d!6k0-WnZ2bZY?k_vSZhw0D)7!U)Z{_ml&C$V| zg9CxvH~UBXdq?~GM@MpFfB&h)ddYhQdskQFFIugxK73f+;2Vr*>eH*S6Z=h6t)3Tcd^e$Le}sViW4D}Ak!ELe?%_S!Y4 zWAZ<&o!?8Fc^bu=U#>}PXp~5e5@XW*XiPE+cE+mPxMOEmcc(KJ*V%L!*`y-bZo8xF z&@!;z3{yFA#a+4=DecVufXyQ+l{I|4iD3C@#y;f%%wPgu&j>yrgbF=A;0b z(93?dwjfop_szc7PYD+I*KsjHa4F*h?}ceqVsqKpMH(tz+d=C1|nn z-h8H-e_Y8|BtX0Bql!kr6(w}A=R7t>Qz1^JN-DFVfiTO@;Hs9d)YCu^Wy;twexy|D zF=a=5f2;!{4Fg7^PNh_rWX!ngk~fkrCmMv7?3`pBOOepJD>SP=nW9%An(Y3Maq4um zBh3JLqu-!3spzckPdbw6jR(@1E{pEXFy&< zWKuS0W*`pQuy(b~j@Fu1oW_ZT*2I;?WjHT1xC}R)RDHr~dG(hPLgBC%i#2)X2A*_| zBvPPP9U-1kU?sj^Y)7h05|tij#LSBHI^7SlIQ8QFwZ9N-xuA5cH7K##8tnbSno_jN zTl;-;gQEcODDXOHs5=Ohb`2UL8_L$Y?34?^A|9G{BzuCSXjpJp%?qS74tzrcV#*r& zlv*jDQjOqB&xBNSn_CMiR&uP@3D8ob#dBp6z5zcTl`y^FhL+Id5wG9JVT=d7fJ)9` zv6HA>A0J|C&iP^i;oOa!C%}G)!Jb;pX*BEEtBZ>Rm+ozE|M&2455;;l;tysne2wYp zqmQnC`dMt!;CIu}->ucyt(&ms-<-3n@gMG=3p_o{vHgq?oAdgB`M}R}aq?ZW_scoE zz06*AGhoTPAD4FjJ-awG>AUOxD!j zYy3CSW?MR&=xOuXN1)!^&S`7S3m!vY@P1)uwuEd=?3J-;dyBNR^y1o;fiJJ!`|af~{`rN0?f-Dz zo<4hacxq_-_U*~(+vB$fMsW|0k5BgZ_V$mD4RViGPfb_dBtjcbV5ezW(vnEd$?gzx|3e0J2b;!tS<9lN(Ei|rvFPO>%5+@z zU(zc@cNy*mms!LDYrR^AW~@p~_n7QQ8~`po}IlDzS{^DuNjV1I5g8Q>1cqFxyQf zqpU)U1Z$NlO3Vfgh4#OE&_Tgb^mVl30V~uUv<_+%%qDb7#-wCFOVQ~EYDenOdAmOl z6YfrT^l#9q)Zd>@pYut?2*@-Rb4g~18l6uJiM2uRwGjGzyn$29xYrLHnP;pU2+S+$ z8Gtpu3lm0*25RyCl6MtBlE(VmBUdnu3!%F5phF5Ckoz}W45{`Ak-8nR%M#hp*+wG- zFf%W1wZbjCd^POyR4){!vxRm~wy5PRm-Y8B6qY3^Jgp??sVs}mBw`h(io`*;(WJ|G zj~ES?!Q}#AJTqM=ua^r`D9-FQ;YT9q0xX_cH_W{&5t=ke7LCg;xY;-jjgrGWHT0`YY*Fwn3Gm(_iqnSg? zzf>j?b6h12_LD%AjjNA8FK-_8!GMhb&p~WQ2N%HIQNpnp@w%i9Bx*9DjpmY6X%Eh- zn}HmTQ4GQWZ_Vvujk-uIr9+?1hK0t;##)dpE#&pqsfD^DvL(?$yr2c5n)gA#EXJm> za7_Yq%{ghLsXCX^h^zVW)M(eqC-+j$eTkZ#a|*Wjus!vn@!(o6_koBlXhyDflJ(N; zz|hCrG%vo{44nT<@21!^tuPXAaHE!km!vMlv}rx)iu}GweTo2(Y`Y` zhYjhT^8rJ7b4x#b{q)st@SB&~9=7^U zrw4~`4-Y(kyKg{yvUhTPc)V|1*KUTqCwm7+C&vfIc=z|-80|ee+Iu6?`|{`^1@ifnWq|S0^D?ZBi(;)1%pM+(*{Naxm@>Vp=jj6<;O< z8jv-vyMvcFuBWP^FsK{n4OH2{Qu-u$9C&;wNirxcG5H0dC*p)(8K0Hks97;0T%r{z zXs|jF-?1;*g>D+)mP*Ey^JHgLh^8bEny}}5HB*w>{Mfj0GXpO!DUULf*NQX8`HXr8 zE2*k>o>7!(Ng87Syn)46)r3H6bfZ zBf1!1#;DT(fa{$-E_*}ClXjkCC~&w(sg&7pJt0tz7$YW%pwJTtvpH&@ zjO6U%akEs(WLxbvPT*p(E={^f2NFdyVam=8cMFAvJ&>OZDALodyV(W~q~7q|-lE~E zY`^S3PwBXKeSP{ly!UQ-s{E6Eo>ASxI@JrkWg<9w0lnvPCH0QC41?EdWir1L@C49qWPOhCXUbhX+?$xSzu!!-D7l&0IcXM8byi=+i6fc%yz2;V}Rf9xS z<*G6)8T%5wF#}OXI2RNXomF1j+BdK@=4(uMw2y?J)(gCet0jxOa${r< zsafc{v|sQ6zOdh|a`pW0sgke@vSBZe`;pDJS5@$gx{!HSAStFJW4|>MR%X+HTqFyk+kP!#%}NPs3ipyx0py zgtNw$6Ct9r!r>_c;F{!t5%;D-KM`D5`C~WEesLo;XI9etnTz|)3zI(_3|!UVc6ioF z%1c1*%Is~L_()I|Llw^*eqjf<2MkUJc-R@Xt5#M-hDnoLM3A2Kwy!AL#jQLoSTdB30lBBIXw<6RlOOdC6>0Bn)W2R7F z2E0Ka2_`X^B^RL=DVPw04L+3iCcV*xFLRZUe`Vj#^Ly29_p1}zdgV9D`F-B!`+W{x zQ!>kMed*0h2HN%#&t8Ay(wA?%E1T|DL|<$V%5x2O33WU{@PohoUHX9c-ewi?|K9ul@7sie6BMWKo1aJK9E;3T zjwB_GE12_n)xpMvyAgWTBU`F2q$tT4Dm6&4fYD?k3KdGp6wnK<+q82Hbo}_wQJx5{o#92&5;cs$lO0r6?WwU}* zA~SM~r8Al^BfALpg`!DTyDt{zN5E@#OkOjc$Bn_ zPTpQ8+Br~%IYd`0V08pXQH(NrE`_28(BP=@uZ$=!p@oJWACSpWDy35YA{bhESgZMF zYI(V2?~P?irBjtvgWBa~JA-OJ~A9J-y;4;waR>69%t+0+6*Pt{r)Rrk}NL5Mp^6f!+60Ep2IT%tq zmr~0MlP*Z3rPM4~atrMitKqiO6tz6kTkt$KZB_0WaL#BU>RE_q+75OLo=CdT)=1h* zZ4`XFrl3~K17TjWaN23O9I{VNZg2FQ_2_2uGdF$y$AJD`zWl21#<3?=VhyaMNsbFG zLP{#NVDl@DpclS$BCNrx_59J%7w>qH&{rNWcbW^)=+fu`wbdk05+0Lpj^w3>wtvuM zyN!;heWYwOc_~CFbTc{{>$pB(@Ryx0w>7%w;PzqWml;6I17MenRVZvv7pFIN=H9%n zhM;rm8#4H{2Zp#%ReOBp9P{QYui*kVl;*T^S^!_CC*k^ajf++Mr%L-l74kdE+GL)6 z`ue%ozB~8q*>~^Wp1VCa_u|X*cjgF|B0c%e!|f+@2vH-n{lsezQiG6M3=WTuPLBE~ zhP?g3HwMiPZ4Y-(K;^^z{_Y;5=l=fg_x;`7{oP%+?cLeieY~?bkU2kQ>J0ckaLgC@ zy?K)=?$ye4xiOj#Yz6J=zF9T0@yAd8{mF0NXZP^YTYr6z4$V`qYVZ4Np|8CS2M|%A zvtlSr2z0<(3;Pppu!xt0mO}P;@|PH?4f?m{=etUww99hHP7MU-B- zn5khPGCD&W(mE;7@l1F<9KNfW^xcUt&pQsx`H*SA*)4Wi^Gc(|1bV{G%oqp$HcNWe zg$a_SGZQLrn22X4PQ?<0qp+t}5~ckeMwFJu5~1t0W^rdG^u;=kx-aAt*z)G4&nhDf zkpiuXU@_#7gI&)74D}6+I1IKs{unI`3jlB@B*j&LvbND^C?9odEIY{#Z{G!n##>TFt>dEr! zUtj(D>&Kx>o)4IYTA}WPqj$VYq-#6nQl}hU>f~>+*QH@$lu)eETT96LmrA4LU`0tj zw|mjftrCIf;Br2?5Q=Wxk@cw1a-JhE1;v#kaSOs9fK*uprHwJ)pPc;5gV4pBH;%P_ zy=Dyf&({aZ7{EamogZ0j}$7%`#jP5jt}EbipB2f%Ly0CZyYrcR7!_*%|ZK=NGg|u>}Xw> z6A{DeNYWRP=@)Knv?-Z%VIDkdPjC6Vcz+Y~KHoj;!v0`l>L*{Yn@sxI=`OPL?W!dh zgzi#_w73}bBZQ{eXsVb9D*K9Avk}@Pd{@Uzqp=~Wl#rZC+63*CBp;`eWMchNPwoGu!>}>Xy8f)M=n>?${18$=af3!w_dAJ%7CmH?Q=RuY&1*XT-s>x zH#zdHYKF%3nvvvqJr{-$8y{BlLOmNsjK!m{_Ppd#D&pDbYYtm4MZlXZal`A`P4>vh zq~joRIDR)xo3Nde9cCImJgj;pY{GF8Iv7;bExc}z@2+vEDK!dc0GHNb#Z<;8F0e{A zKAfHiPhe`Ym*V9v#8stw%8z;5=ltH0ge1_KK!dwV!{XnH-N5~5r>^~W$M>@#6Jj#+W;qpQAR(Ywc_~(*5MXTl2RoWKH z4eA)m%c*61*jQ~!i)HVnRB5(k5Dcz14d}E1Zj!i6_b*A0hPx{bS$x?3Hng496qqQ; z*#mI6GV6jPkzHNVfxJkuFeDkA67|e37+!3j*bz&f1yUOp zD}8cI$wMxF5}vh z3ZN_$SYO8^JWxh^?E><>y4(pxcWC=rD74y>1M{%5kK4bvlbn_scy_93k==rHSwdy6 zSQjit&(-3^3db91-)Qy2kKTLRU6lXp?LV}gU2mK98OBNCWPT|Tc4jYikW=i%HYPTy zl!n%EiIJIBI$2E#Wd&5QWr>GkSc0WSlZYlwij+;Q6sD?)RH->A9JCUmiPTE96R{I^ z!lWGbC}oF;WA*`d|E~X&GClw%aqP!2LdNm+T=#vwTnVq;o^ahgeo}=4V58qtGE;L6z@AHFV}`7(}Ajv|pfirBL3~4v zoaf~RbB$0aH`1uC-K-zBAk`IN;!Z(8+J(6ZrzJDgyrxb)oBk4~Sa%WuZu7D4jun})Fm2B!!7 z+&%b@AugzEfZN@+1G;SQIso3qn@eZkcFzv>D9-KiwY}f#0lX}D9qbzFcD3?-U_|%Z zoi5%YduWGlU8$X&&dR>OvM(of-qOz3E?cX<;MqBS?eFPMHDB@a@nF!fB|DvpJoCj{ zZ@>QZ*}uI)U-gF{e)y`$@0G*N@4LU`B|SUnqiZnesu@@bE8vJ2eLFU<_I1_0sxUYh zZMC9|mZ7Et$g}!gJcF8mqegNERItPp5~IohOtue()Y?>C19_6sO|aUalvv7WFbcO) z&O_Ah1YO_;!)JuiE&;l%6|k}2VdKexzH)hkR4gDi3;(4N3ABY9X9K0-ta7kG-atWf zX{s4CdZu=eMx<}D8|iYXP@*ZRS;%fMl5S!#Di!Rf0c!yE+bmEzm@Nu&iNeat<(pM0 zQi1ZLRKZAaDN9b)G|5=ki__V(!7(1;l~NH|mIPVgagvzmWN{^#k`RkMaZxjBMPexg zI)ddlf<~ISXuuPvk-8X?L(Bec*^W}O_WEKh0c(oKWl(}7Q*eY#nmuqN;?g=|%S1s( zB*t3Cjznd{F(__~T*{bA8^(@dLo(z}#ctR$mS0*P69B7LQkmba;r;-dicO-^?4*n! zakVfY6+p=sC-iE-?JIba8X91|@L@yPpldw>cJU#p@`w$u@#CPpM@pXzVfkIRTSj#U z1jeBZR9T77Y<)AjUXM%u>=_Y8t&)l7rGus~DPv$g&fe*?Q9@THqiZ2Mld>&Z9*TR&iKP60PVBeL%SFZ%wmm?Sk!ALPD)2 z%tX`;w^fCtf?#=!l)WLAtcGA#&Wnb%l0PdL6U<&Z*)d99v(tmwwVm0DXoL_jU&ewWLDDV*C5uBWw#IZ+k*X>^qjAN zrb*b9BOP~pUq2Tb)9~SP7@3gdSqd};jFl1%xQN_M36A~Iv_PSPx*-4nAOJ~3K~&R8 ztm?k>XhBgO^##B9cERyL(PW<;Py95Ib}5&TV#)(2rk=>CC#Ih4jP;DmTah=0r33Vu9VFaKKLFcMAeVikG$t)v(@+Pb^h~L`S%W!u>2+Q=s_otBD=c>`@MtxgPu{_UJn6tuO}oXiAqOY zUA=vG?Phns*VUYv>iP%Y;wRc+z>J%BXO9#Oti7`J?(I4Hd;h)gqLS&$s>!^IcqO&)Q$UNBBTs!)TX%I==PH+pnMf{Oq63e|-Mqj}o}q&lAj6Ekc(L2 z*v(<;e1n*J;YagI!U{?{O)C-+SpcZ|V^yU@t|b{9nq-r48Bk6%mBi7e(XBv0;gr!b zdtR(aEQia(twLFWR{(E7@T!{Nf}yst-hxA73W4b+EH|_8=cZ}}%dU;kXssPC%9GSA zAfRrR3u&ZSG!g={^Z^&j#gcv(@fKx;g={me+Cl^2bRk{xb2zT2iwbK&CE3p;(a%Y>4>F@RD7`l{cEeyghOrkCjlU>K>uD@D7P%LR zEU%2kTyxTptimsi-QeExJxR8X-55eA{mj@?(B7zuIHY-3?j(g97}Izogr$JSD?X@* za3{plMUQcq@v}tq$f2ROp>XS>{V9YDfiuuw)XyW>e+lLo49OWh;+(-okF^6HiLd8n zMUp0zCGom_SkYR3(QA+mlpkrZPxJ6kVw?=}iRnLfSCEuB>8Vuv?rBt_?qxClr`ArbG!4MioY~*+`AvO&B zPLkAd(zO8BgpMMqD4f|qE&2u{Xa8MvqGoM`Px|qcq)0De5w_>lI*gsA(3)M6B#U29 z%qoDRRypbKd?kfe+Os0E5{m9v(s==GO$?zWgsz=jdtf+wQ9Q2+znr}HCK1p9CEqN9nPm+OcwAwcWAG1S&U91?IW;e$bQArf|1!d z7ZBwzw!Sdx6XLp$*3RGLg0__Jaj4509eq%Em5*gO(f@<*@2_0>P5;{M3oZ=V@n2#a z4OJoUM<+Vdf&A(5BgTN^SA76JjJvqB+B@ZEU!3`>k+Jt{E{_kG{;rY1OampBy=_P0 zM62qN5GR=Ni|Qz(k_r&yB99K@Y$oQk3Re4yP0z{AI&_ze0k>a<9|Fxk?dM;f7XS2Tk~T& zf|w!i3Uar1p}xA>H{`W{425^WT(0)_celIUo-ladf$o0SFt@wgWXw%AN2H3kw0S;Rv(h= z!PF9_p}u0u5u?2JGik`Z5^iPE99iQ!;K0xm_7jNzxE?h13M6J{2^t@GFS2 z2;+#QQbYGrU?uBd17-Uiaj?w!Y zF@S{ zhVu^gtDA7ZuU$|>vrp|*YJZD?hI$DLF;85g__wAo zttBmewH2OSOn|nkUI1<3!oWRI9Y%riM3Gjl9Oy~iW->mx_TV_-&qv0;`~JT_{P4r~ z%%WNGvf2F~Z|C#c=6%QU$odgU_SDF#gd+{bSdFBrvL;ilbsd3Jymd)et!_nEue3$3 z*tE@CZ8U1K)t5lP6asEAjv=f*q&wsg5(g?sl(5rw$w7aCM_`xILr&cvu+QuLeN@V} z>uT55Bl%H_vHHCA{(Rm)&UhneeJyy#;4|X8ID)k#c9gg=<$$yS&hJ=JKt z0X2~x0COc?uc~nrL zP%Wo{ZnZpflDF4&!f5ZiBwe0AxcaSiaeI8G*mC12YV7x^{}?{I9k74r0c+it9PfS0 zWm^~)SF5K_SL>B{>e-7IE==7jJmUed%j=k#dG7V|j(E|c+3RZzB5dA%|JIKnc~RZ)d3i+ zB6@us4?$dR1;VU*g|Z`~z@V=X*l>AdAUwLyme)Q}THPPsH$1l6!K3@^eI>18z$}07 z!@B_S0QL*|8tf8m<@UX>UT5~bjm^kDE*;)Jlxh3&&SmE}`pobbul+`NK_g?zzGmM7u;HaVd^WIFb4^IZ zaLmn@=1^c6u$CA^=b0Lp;`6c_Rr08#$%LM-rcTXF#L~a*pl{`v{f3_=C zA=1eOB~yvy3Q01BataedYSpV3i$Q$8g%aNV2v6$*hGj(pW z&ScmzTqnS~vN2Ac)W})JBQO5SPP?+`IvGTg7d4T#_=p$SuoUmc3%XBRy&m zJQ|D)W=9T&2NE^k9}Eq6$@>?nFPM-YeBd_J?JHg-gf70C9xrst17NxwEX2FTXfqHBFx|VjSp);;~pxT8f znkt`c!J0D0qg|{>@Sg*}@)>*zfi?j5O^^~Drg#u;aS(%*m$=GcH?KSSB{~U9#8Dc??p5rbihvDqYbszU5p-3`Gix zfwB5RZ|7wFt?6byyOyui=F$~*#B(vM9#a zo0jJY?z@!OaDM6qPqC&9WWd%AC-e zKfGcuVEe0K5AX7BE9UpDOt_L@dmrXMu+Lb~UM5l3vBe$aiE2W?ZrQ+Xlc6)6fT);Ln<+IVY@)6LH&b38 z;gxX%@HbW@FNyM;#>?z?HzjpmmVL>IrN`aB5MwBEnfMNh3sGUQ=S8Wdc0#Zo`nya7 z^`;(6p@v>&PmPypXV4%4YwE3k{>$+9$&;_)vPNweUg)2@HDe(8%WCz5YD;@y*_9x} z1YTiRg4VWqcEdi~b_j1)Qxd>zxJ#(k6j+Uk3AQ`cSQuwwd7$eZwkS$s-s~c>ltbCl z^0M6?Kjh+#-N_9PfgR`dq|jBT{B`c(mJ5+?xw$kweICsfb4J^Bb{r?&RxF27w9Yyc z@K~*PB12>m0)NH3Y#wcFhe zC150XBs-U{GH3RBl%0sY(RMhj-=5jN8`?KoUU-S#Yy4(#xDl-%B7HhO)&zNEaCtm} zx{kD;H6)f^`S@taTGz1FnS>BnIl1Z;i_7z3poN54 zyJO?YDyw6uOVkyRPQs+@z~Pms;VTV<6f>|0wo{|s3A8-%u-cQt`6VCzQoG9A^*we# z;h@28*g)8h0xk*5P&OZ9{Ja(*g;ETd=x3M85tH5-t<^Q0!iKGCXkg}y4cLvL#dibw zHM)RV|7r!C4;YWFlyD#A^-pC9A8@Hch;)f6B;Z$&ZGgNtpVxkul3;0}=UMVnynqav zweb90jY%}pD|W%#`Mo{JGoq^Wo@UbAq-%C>Qc=%DP7;_U8k`N;52-(zoKLGk!9JN= zXKU%u9r}eaE2Vj2C=@a@CiDuW)yJf77`tX?Y>b$L%zkKkc590Pw1m!+)7gx|wCF4J zVxMO-q0H8P$o^AXvsox_NL>t|G6@{`f@ec7?q^PfyWthOBNYoC=N%Y)*sm&J{>Y?I z8o2tR3WHV}$6tdo0lUqwN|2<0_Pex6ve%-1*S?SdcM}vf7(9o?j1zJlB~*&!UixuJ+ zpII`lq}a?PifphJr!84)qE1PwmMusVL+QLmp2v*Gd=oHa0fPx4F_gs@V;3ESC5B`q zcF0xfMGCnY?5gy>kX~(nz~0aEJ<0~_bsSm0EUS*<>N(H*K0j9IAFR#Mgj8H1{EGBR zL*W%dDCg!X#(XJUplyf*NCQ7t5D532b*UNJ;r9Mp|En;L&Dq(05mG>o6~57PvC*?G z3wpWI%Ywl!&T>|XRz-zkRr(Pfvx>sfVE_@)*pQ0K#3cWjABEDytjmI~kOd99{rX=3 z@XK%i{RI8!`OzK$Ib_A)&+J1?YQ%3gvSHH^iV|e z@fdEoTC3S)#3P9nVXE;sRbG@2`Z(vB_ABjU7PiC9Oe?-|Q&Kc%&(bJbf0JNMu4{(S zl4QB=Wxa5Q`+vT7EgR`Q)RNZNDm0Z(ro{Fs+0<9!#e4e*nlTLl)&Q)LT*;ROwlLg1 z0GN*#`%i#edz5|G-rkERXsVv?340A{u?`vN?i$*{eC-p`YiG}$(TMf#(?DTmu)8a+ zYqVDmBfEOfPWPUIz7ORz3X+|7l(Mno+(y@~BfPqM_ipdYO*_u5EOaY#eqpQWg+jz6 z=9%st{qXRIAN=Iqx2|4&`|VFooH-+V_rZg|e@E~O`o1Roy?l0If0g1SM84xL1XG=u8e)u zh!D{YbR?nV(TI|QLYahzhPDTl@vIJDSnzh|4zg#v3c?z}?Vxh5BgV3u)v5{^42tjE ziB?0Z9;66(DBr%*Rt%+Vz(bP+Ku;2ng(Ny()!l?p+KtaCE6h79QV9&sWBHw|mT)7n z2cD#FP<0EFZG+)X%Z)OrHl|C=20>Z&#dQPE+YGF=|4pSJzDLzcm`bh69&ArJiuie8l^|%MH&A35 zEW2dN#K0;*Ji2=LKqnMUQfY-oPT}7XA~=SW2M!Q>$oT4Y39v{8*AW`99IMmLV8?DA zT?(u_B1oSh!4Tf2>mI~@1hDGVlna=X@1@fbfH?{ zdC-QoMZ%u5MOlGsOXNcvuf-2sa~H%+*_DFCO$&CD8r}sGu~g0AP*5_c3cY~~>K6=x zD2uKEX*OtO5VwW<_KT1hLCZhP;C9Rs6qe2@qYrqFJHd==C3jyotuAn_{eU0arnr|MlZX2?l&tAf3WLA68-{a1$%oi2<;myVrVJHB@Bv17o; zr;t65A9=8KvbTHEe<0J+>76)q7w?=O&%{`xpmJ_@TLnMUV$VwgN5OB_(gi#C^!+XS zUGKJ}LQMM`H~SlL3B3cqG%wV+R^*Ns>lLPMDmb&h@G*wavAd5Pi!}g6t85q7;>bSuII0VEC`oK9?9j+XHUp zWietuY_ymbh8Y=>#!y+2UpYfmCDN*#%i^Ff80A&!s6FlvcK^BzOEU_DRsyB;TgH5E z6NSZunKiK?=ZyWK3JFz~eZR5V+bF3=FLg0YiQW{_m3#_%*ClO8o|Mq@f0tv%xC;; zuv$Fk9=OY_Ibx_9X<|TP$gKPgFXrP#YH7Ued2wZ5WnvNKZN$+}@IYg|X}=ZoB?~pq z>t*cCDV-_k!ElFovyhp{_+6t6t(d*78RoXS1@>zbH<&(SqcrqYHdeN9qo!r>1UGB7 zx#b!$SW5`9CbDdKvjw)p=8DD7>@G5}1jf=vQ-5TG$Uz4+;f6inUtm#pv7v~8IoKmWgx*KGi&P5v=mn^ zO4@~0&hsSXL5m_wtQD|ccZZ>BFuIIo#?Qeb1iZ>N+^(FlgKuhOAi9_8XM?c#j)jVu2*eAekg?fO2Yey1NkD-55Ntf%VUK{DS?GKE^v|?3VqA-7(>}{4QdD zqTP@>$dP1+q}Y%O2>)Xl9&+td7j%VJdQq>M*4K?799zd4ykuI9&%4AGLS9{N&>?ya3 z@C-g&bfn!7_BvCqK`m}0H*wx&!fbr^A4=2^;v%)u#JMkc?#D|S@b=lSOWM%l_shGR z*Efy(y3!GQx$Fr3nUUXWbtIoKzVWAz&^`b7k5}LSMB8{rOYnZ%7SDyu<>oQLc^wXikXUv@qS6Lelk~!H)y1XQiKD-Tw7LTq&b(7H!(Hcnu_3BXFs4#iZb`%h;8`g%B z)u6BNPN*|jt#-(xWCM&X$>?!36m1g(U5+wio}@Ows^(Jw03ZNKL_t)^?n+kMMrTV= z1!O^R%f^Ezx!#r&$#}BiDcj*Z^}yh-Ve(9Vk{n9l_m*O=+9hp&iO(9tFWd%cCk5CsiqwfiBv<Q<)mV-+Ed*3KW52|781O3lIfX~~{y@$Z{;uY%-}8S7M$lh>3DO$1?Z4B$dbhFm$$YbSwN<}OK_R|iK3!H$v_h}Q zngp&dDUU;m915-^esU66#H-|`4eD(etbl=KVmP48FzALHNlc}ifl~T^pWPQ6kl>)h zL7M2MGNQj>dZNo7cRcTT(wvEKQySG|$Ys~D&wwCj`S4)4^;KVDh+VCA6hKHy2O-z|>a zoVsxBTHjB;evt6Jh>6jIy=SNWf7tgv6K6wS+`av?qf^0A2PP$jS( zF}_RtLe)@t=23MHS+s$1e$EaUH0O!FLWV`_LMgAnX9m>OIckEd&V_SIg3j5ml2hUD zcwUXa#6&B3qhyCM9g*#vS8cFoMAI@jjvmXP_;cc+xt+FSOsvO+vMM7S$;a-*c1CvW z#GRdVTBcu$e@W3ws}eZR&evcYnoC3nNP7qE)<{sckdN))?j6~on&Hp5j|jd}HE_&; zcZzZKM2s*>WYbrs?5CV#>l=>P#n~5(JP12W4X?6f(4rzdOh<>zzxyPIhb6>{dmPqK zT#Z}Cb|VJYMs!E_hwR~qLavC1#(0#Wbs-}~mK?zbzJnd`I(3Bd02c}wq*oauzw{s> zy8?9AH(&^(nbA&x{aImmqq9L`{l+@-EQ96^Qm|kbg~H~N@#S)v1JGXWitFXhrUY5j zsB$RrC59 z)>!l6#EPcQ#Sordv5@G%8YjrRfWS)$?`nT7=fBoIb#&YDw zjdv*_q%`=l_Q2=m7ZwdB3hO-K9G8(oE0wZ&S$G^EuQOYXqcIkV2P+Ah-a=8^%S~ah z^IWwJ3cx)q+I2$;r(AQ3a9{-vGNT2~gW>@te9U_eh0Xz;8xjQ%$_s_lMb~5v%tvbh z;SID}MO7`Wd4u0t(_<^`Xz|(2bN_D#9KNeLa&a(&c9HYgnEj1RUf=> z+dn;p2y5Wn*XFk$l=o6&bo5QWRbSA1eBgrT<6}vlkDdAgye@e*^j-WrInP~t@gE*; ztS5#fP$}UmHQMvkXV@I`+W0-M9pcxc}!Ddh^GHiKpwVs(DF zjWwx_SSJ-$r5)i&$!I8L#M%%!C2ciNx39$Eq@7G6w4rX;ZrF3xDEDm}($Wg%GS&tUSITCsZul=Dz)rTZRU~M2*KQ1OC<{iz17kz zJh?D1XJ(`$l*K_il4O`1AL8FFk_xY4H&Pb|&4UpH&b)L`Ju8qBWizvA zXzjzHjBBy58x1Rll6s`ft_IZt-QkQ@!b8lV*$OA@tmz>N85BqfERU9n1X|x!Ebh93 z3J|Fjh^tqikdfhC!rUIJ!_wgUhTZKC1=Ez%r{?=H7DP9}2Y34z~KD z<*x5?HInXX)9X{|N?jc z(5rO2b~3RXl}h>UJ;h6|1S+h5|A+B1;m}8Kd~)*3r{DV1WaHzT44R$oUP7`p={{e% ze;boXqAzJJ?1teBC zw2<9tWzoL9T>r(}-&R2L_fxOu+VyOZkuVA25iM(_H2?-2@3 z?4{0l;n~|i3{1l>98lAh7$vGLky$rpyIVFi9>U8$JzY2UYY%r2Wf?zSHyCEWf@`T` zuv|E}Eq3c^R}J}&8o^H6ZCUdo!%Z=Mtifvi$p?Sxrch&IXt%HhDCzuf_wPQBw84TK$G<5f1=H@(RYbBcibCUX1z&Sk0>s$-c7_4%(4&)tJGv_cPc%g0f;0 z0CA4!jo4=s>0H&Im_`PyN1somcVga!6x$|-!`L!mmLkj}X#%m*DoZk44{#U(7LQGl zegzs&#kRMRb=jlm+)|cmYv-RN?@ZTL2m>OB=EJy(3~PA_p>|d(M|?H%5H_q2k~kug zS$X_;=HXCccxWF#FcFjy&%k0Cj2g=x69FD2BwDo#5=1958=cYhQMSoPVOGB79;jRHk}QP}nD*Z~_*+@5SGq7>&`<%*o|mz>{9oeE z@3pP_4CAqWRX=P|*+@&|VHs)C(KJhysk^wARykF-)!Do{Q3GyZK|-u9^ICh^W&-n# zAz%gp6HIIfi!aJ9a#7qGY>3ma-L$(%AUC<*U(x;ndq2(TSR z&ktX_+V88SL# z_ay<-r{fLXvRi|4N~f{vx_&Etw!XpTK9q|5enUy%Z$5c6W1?m&Z= z$99OH#0|g0V5hJ%@9o_FX|d(#y|h>@WsYd%T=&Zz{Xz@_Wtcf+#=ck-M0ffO|X48E0|jeUk!2K}}i+hXQ_I zJFQ7ytHs?2Q#55P7^qGy(T|i2ERiW~AWptB2H9O%}_BArlMi4stvFP z&2x&tQb&@3sNp9-T$?b!o~ia2JA<P$BT{ZnZ=Su*A>g zQnE1yt`mmDwNdWSG|0Z!j;gv!-M&yg(mG?yl*!`LxB zNO*)1Ku>7LYjii^IIvOJ1Y_lU6Ip>Uvt|~=b~>9KADoRQQmc#GH@Dl=9Fje0hiXV_uS+Mr z*5)rU#g#X4C4tt4=MRnyI2VY0F8=46Z@>Asq9&)W*{R>$zyEIiJ;UO|O62+$T4%%4 z1-!r)m^^Dzttc!bzKboV$fAB8XOiM8b1DheJ%CylxD1a$LiDsR&T?f*>Lr{$TmG`^ zT~vqgq7t)|jkUPg8T1x9B3y5&;-TddqaDBqT2)^t`H|BdIT4aFpq%!(B@A}9CAaSN z*TZ0KizP6z$S~nSidOv(-YXx0z#si@5T)Iod$fJuPn2|hz-)NmbR+2L#kJ~O^C!1j z!?}ZI@w*_7;`!nmnZK`3U61`t%?-ah@L;$sLt?Sz^iDw`8|iSlu+t@WQud><@^ZIJ z<~jA6Mva5^j1F^j`>wX&b(h=e_Yb61%Wt{D8j_S)}XfBkj3et+P^ zbn+g(1pK}6!5#Za41ftUg4KrOz$ZgPvaSN*)KECEZ!jE>?*~)+ya*4Gib8r(n+GVM0G>`RA`Aj zN-Bd>r6Gc_>=B*nDjBL71!mmbXH$$lsbplkR|@qFS@)PumxQ{dN{VJ+Ql5cW8I+9e zDr#d6u3IUE41Sf+LFW;>-gPkQPiy3nzOIIQ4XU5RkgiJ{^B(WW4;GCd6*wA-3U)yxmgoIDhhollh zwGGZ7(n{no@u z?;y$|BaO<1=n(p6mcK!@4H|_to*Wos4UF~3rEtWVK;t$7fa46F<7px(gVA){U^nJZ zp`pNrw*~Esk%7{7)GaR?HwZ5i$CtL(B^ZMpP{ObS5_<)5rU);!z;=qMvj^L??|UqJ)q9j_+l3F?&1S*Cw`r%Fvs0Ql zJI61`M=9^khP1~{2HlolR~&ea8S&b8r3+`Jggz+ia8~r!A41bfX!obugEnD~3`Wk>OF?yAvnjSMadYnEh6SHgfj%GYC2hxBkZli5CMF@Vl3EC7COj04Z!ka}=r@Ah2{1@yPpn-02<6ofU{bGO|7yrnl7 zeq30+^QQD^e>~b+TMh(+g|*veO z9f{}KS)w=$oJ%0L48Rqjc`jS2)k;-3@XS|p&TVAOw^z;6 zQMfzf@;CA_1m_9mC>he)x!r1ICR-y}(nvG2=UrC9HHn+;Tt1@kXZu<+7{!@Xok3SM zp{?*lqH44^n>8w|nuW-Opm}q{;5ad}nV(5)QoFFpqkyaSpcf;=XBqe!fz6L<`W$h{ zj1)R=%yvW0VQq`;^CI!j;~S#N5gCNR?!GMo-9g~v$6`lmEk zGy&TeT)xVuOplR8nU)%w3PLIg!@(F~(8~qN+3dXM#bZS0LW);nF#}=>f%#;gTj;`e zy+XL#B_At|w_~T=U3Ilc^W|=Le#Kig7+%4LwCZ&|yWcdZ&S(*wxw%^Q{??=S4?`6XuI}EKVxGOKVA??wm)mfnXT#$dp>H$2h|4r3Bp`as-=--ICGvhB>qM_ z_S81Gyqj-#&Yt!07STgUA)$JYiW*AK7K=sIF3hM@LH1weQW^~|QcNfVl6!(#`Ua#} zt|Cv}kT=QMFPmU*MAC28XHqRa*0R)AkYHaF_jLrk&h}rJkI+cF`4=<}@}SpT=G&hf z2urp6T~!5;1X;oESOVan3u$6XGCaB>DexpMO1v?sHSGHc*Ud>m!t~n4``wpr{=We< zK^$kF1<@Nc`(Alr2<9f`%HCqS`j^`?xBG`VcEHAfRRDZx^`EKtFJ1aL{kbl_e#qMu z$yJ;>5qp1jbKP25M)sjBz)uH5R=&ewHmk9;lF#ieZ_m{ZU)R9g#cA%gl0|w$DI{xt zR-eq$nx|iTey7XURzH7uXF;Nk+R@)|@C#Ry|EHR=w3~aK?D8QYtHr zR+yAYqs^53BF=&w*TXUcGnzgzINqu&2ii#O7OlXoN~!)Y%tc2Sci<$76`pk z|3X8`D#pzuKsU4k##wZtvjxNH5|S(8H|)xjc_?n_q)|F)CJTn!2PMo)rHoM4aJEo- zRN7|}-IVpn*zQ5$M4Bv0feVC3N28A@M2dR+_-z)LmIEookXh^DxC(Yhc zd#|HJXye5zz4JXIm)(VP7Q{G!@(adF!Q&1q*npL)l0j5;#ctMjj@m~-=+(kbFpC!T zZM*GAzgp=jw4w$Y>;46-`3uIlw!+ZJ33$%@1P*kPlSiGRu z?cIG$7sIT+E9rS1=DIw)KC>=&(Xx-3i-y2Z(_&E;;PthlRL>Lz&j^%B=ujgAKO~rT z-;q0ziqb&?^D1GOU7iF(t5}$gLm3AE03ZNKL_t(R^oF!r6Xv_5>9vPnXkBVQrgQUutVkCUcRzLgl`=J)-*UXMHoJalP^skKU%$ORd%w2|02>4Tjh_8D|JmwK z|55$y_t%X!U%y{gI84p(c2LFz9M6ucIm}4q#CT|+Ya3v2yLZkQKA&OvJ=^7fr*i}tPbszdDiX`4E3MO3V=>uCemM8`+wZ>h z&a1Dz_On~JuDyBfn&Ge5@Ap*r`@t*U;rdq}=_C7ucH*H3Sw^U5$W%y(zs9~o6^-|E zYLl<4KrQpfuVM=RRSOQ8k|AL++u?hZ86l4yY2@rBhA6J4N8yksJx`|-b|y?^Aq*;& z3Z=rT*g2#fHhDOURNEOA$cwb7SdLRQ1KUZO2^X6uTi(0S zXi5lekcwT25RHli&5J%{K53|{Q1Q?QNdsp>B<(6LZ8i;i3o-`VrBUhynHu9YqN?E} z*(}h*P+-q%=b|W~RnbsLiu{(MkD>r@GHTd;uxMuvC|+Pp4MvmwoGBDMhcdcP(~&{v zT=c4pM6?kWK9Tn~2|+$kHBvHKiYougDDTV0j17_t_I)lnH@ANo!mR5v(N8WLL|=#n zdw(L#?%kscnhdjuGNdAWxMv&({Z)-v|FyJ6u6^lG@7fY=e2IWGuEEB+TF7s<4(7>M+Fjj zR|In8x0yxLJxH|>yIrHXdvr6nJ!yehW_T#oM1*k|5F>;JTz7YOCn$Tg^1^?lb?{2y z0dA9c#Vk#nSQyOUd7-UvE5$gs#cs6|?m4gR=~w~KjHvT%!mo@E?CBM3eF5#f2SYQC zhAZrzJtit*w!glPfO*Dom1qtECyT0I@bbVSZ3~w`YSz9*l@iL81lXd0c9M%NiEZ(W zT)}QXvfra0bRo%})L#xp(2mbD5_U;qtyaTHTnB$DuR{6N5ArzH`V&&T@w|Bs0 zW5Dp(8#i1AeZ%3H_{-vr+G05W+u7Uex9<#p7}${1#;|J7WLp<+UCexn3i>dMUZFgw zjpN7Vfg65vxp6#Ec55&X_>zv}Mv%t@q8k!-Yjztt900&U{HBKO@-h49dAU!pi6Sc1 zTj2_}rKKzW&!x|8ZT0iRvz2Z=z^S?V%n4)($xrh&>z z$AV&*FBd+3fxa3)3w>3e@W3mKocTU@k*)FM!M`QAlE;Xtv#)+V;n_#eq&y3NWjg|W zkv{JnA)sh?+uhpJ<65Ma-ORSWZdID$#Zsk^najNU?mKV2_3Ep@@2{@C`Afs!Km7d1 zq&~m##t;51_*M4R@80{4@b|qm!}PO(G6ShxFc6H55{efLZKjmkOVYE%Hq#+&zY#@C zj+ibR`58r05&L31N{>QW$KcH=wbqTu3QjAz(BRmvPj3+xeUDZol+LNJgw9{5QVHY3 z1Zv=0GVE=68^b6Z+Z>%vg%$Qp%H*j6uncC6CWmoBadHa`4u?+x-I0=@Sr7|^rM7A< zrdvjbD=C5{nLyX;_4%!qfvb_8{|+n8}meD)uF_tMl(rWgJP~0k!Upv459HKmF$?tBSUBd?}B<7 zl!P^(Og86@&URYj~ZBCJzd8(USOc zp+NJXJrdUuE$o-@9bq9h;CGYKe!=N5qUWnTJC`iT`+IfnDwvxg5epqw^73WX8D5yy z-B*nNoT-@W-92Z?(TI*yRLe-j4GWTYA3PNBde9GXCAyh+p_<;c0B@HeI)j(9{( zg|U$Pf!PjcbD@Dfl6xifGtI!coF>#c3JJ@EL+6O19Og*kD3`PGVR?Ma+^$?6VwzN% zZf$4;*9gP#qZ;*uXs%@KsMf06Fb?F;5mou5odL2=9Wdf6 zwey#j;HFay3>6k=^a5FKKQYIKg#~($=K9RH+@#7G_iqx3HxbFvL<_@alN#&>?oI89`pIRp3PBPzWNZF&_bP& zrUgSWBC#Bp7VKS{fU1hQ(A@n(X0^scnofv3^X*DT1 zH4Tiz5>zRbx$UewS(W5_^ait~{`E>&>ysS07B{0#j@y^+3-stZheaI|m^Z{ew zY%&rWez;cKM6`?%?DY(zO|KnxD)K4M|F|Vk9Y;N3+%$LoRCku*rMfDuApfTG`PA;L zdhs=#0pPou9*fylRxX_EE%a+a14F7-V{hl=#j|HGoZ+$3Si-H2r2)a;!B7N@g<}bu zUJcjymN!9DF9SBv+N)A4r_zYni;tfOyCl9Z#?e-fwNCJ7=$>`%4AT4aj^j5v8dofU z`2v6UcK7%V(r@$TYB*FJiG zeSMwQUjg7>V*87KznlNZ=`-tq1M*Gn^o><_*U;1iyq>a!FrWd0t87T}d0cK3$}x%( zKzzV~wVYYSt1A^;E^43Ad=wI(r8_tPZ!oT6IJh@v7=BhHYbk^H7d4mxG#TJ3P!jtq4_4W|Pe9 zNFr7Xlo;6?+k(3gLgOo(MuN0iOqbLCbSAwoxGcmr4SBRfgj30(fNpw#k|Y?2zu6Z? zJD?~!?GHZ%Lr#Z>{)_#w4x&g$R zb-kW05-A~)M=Ta?XfNHYz;e0S-{FaPM z4D_WfxHmIu&sZ}USM%j<3o*N_WUvxjJZ-ei27JJGEMdEX%nf!RSxtJ73R`zDmPRsk zBk{0MOKjFOe8Z|0?lhYZNrqtxMimiAF&JrrIE+a!Jh$YnXh7@AHeC{X5Z3~57>U;`emV^@MY56X04#u((h zJW0FnBq4p$u_aLwT_@*d6GK^%ca82Q25=~LPS#ILgPAm0u8%E8W0f?ax2#zl5G{&w=Vtr{F!xx zyWeXFCEdS}Uuh&|xx7;Uv|v{^FD}auZO6QN+6N4DzWU`CpI`o!b~wzxb%f|tNT5d$ zU|Ee|1F@+=*pW<>Zo;I5#mdY~8_)b6iVN}1Gl=0q@as_(7Q@*PUV$frp1J4CmKO+P? zSDdg=!6Ci4EJ*8A_u}hMOtgA@;(R_CJB{??2=IHvoiBa?eDQJQc6kOG_VYY;0Tu{J!(s+vndq|EA*a zJ%|2Me)T^9;7{aFk|)gXe{uVr^^J|iH?FK-`s}k?9qxdA2e5Z`JqG~Ykjov?BqJtf zAn@1i@*&mN1+K%SEEns5Y3&8=#o3p*k&6hfR zH;)MD2v)vP7XC)6v?1Bm;v;V{nwN(xdf9mt&F8auBtUnByCSJdP&segSP`S-7xB+o zj;3<}-+YC2z>nk%BC#s+5KQ5yJhJlwu^l;6gfAG_TB!hyEcI*l}ETkv?8ET)l* zB?ucH+8jm$WFf)|hwVplY+G>IpY?C67g&x1O@)98aTV0IQ9%fqGjd9 z0DKN(K|DyEK^!=8NIel`KZn?tx5%@$bOADM$jfE(?P=&7;Xvlwt7ep(yDSw zMui(#R@{^qu{O+-qegHPY{ad2tvzDoRom({o}(#AfORxu^=gn`jexkdtu{1RR;}G` zY*|~4hgM<++uw$T434cv;bEhZC^YWK1xuR;3(W#L3mb9?Ghfsc0%=i%1RoO2Kmvkv z0yC}ZSogSd+J)5rCm*mj4GK$knt?fVrWzXhXJNyAEjxmMt4Y@{O+|AxLNn*n2@ab# z0r3z=_X`khZO(0BEsQE)^g+Oqw2AnvO`+^iK@0RPPyKOeeKB_7aA&go<+D=h;?%_Q z3S?4~gkwQS5M+KT4hubIAA|7aaV`f|#xw^nEBQqsQrWQ|p>zV?v^9m}m-}R;jM~EX=6a96OS3gG)+|0iETw)AR5uDN@(D8!kC>Xq8FpN|;+v zI+y4XM))+3tc+d2E4nIXVAP6Z=#i7RduMK5y7iw_(3h{O@)^iFeU;wcd3cvsK3}jq z3vVsozrXyX1^{0E%l#6L&CmaO_rYJ^)$-u!>35%)!5RbIdOfo>YRPlB7iaX9K<{XT z&Ov!XkL0ar8*?5!(Sxu6z>O4a?R@BvS8Q{J3C*leK~c0qDfaAJMRej-Q9f!%kQ4>-$UlN_G|s)hrQ$D zUYixCSYsBkEzBlo{okZMp1pBn>FcEr?rvxctc+_-z~+F}U(5qlm~CXmy*JRzq_{Q!>O z)m4-xAkvw&3m#@Uzof?52e#XdbfJWmFRKxxjs#YjCrO1YUXkUNuCIXL2yyVjn4)07TZM^VXlhMtjNo5^eX{c1W$Jbiz7L75_XtJ z*}*_M8trHlhv0e61&dL!+Uex-@(6YZexwNGRh_&yU-T9`*-q}qVlItJhE6e`$G@8v z3<@4c1($P=s$jV`Qq1J~e5FXaRV9a@NsOV96J4~2HV4g&+K`hl1kply1!;lNX&V7o z#q60tRVSWNU*S6EnYyu;1FJ4p}pa3(r+`3G6`?+FwH(+psny=SdI{Vt%1(~A(w=cjxXt;wtUFxe`jDF^%B*Y#8X>&qNfZi7aTN4e?d5 zWg@TOAEce#Pg4mR#-&iCA2g-4C(>q0rw2IQZd+ld1GVjVPCcSqpfg}stcuwhvNFm@ zI}nK*xgjCjorHunMo1valky#)nLF!PC^Tj{D96egg3?T4~0!H z{4k)EO|w`~=oF|hNwLyQHRx6|)oSZ#_>Mhj?QeY9dwpnNK>#>- z+}X=FM!j-N=ZZAjW1hFdauRu53}rDk3r%4RaY0+FJO*t^u6`aJVaZL>x!BB^g~H3? zxL~htfhvX6QT>2~uAamuS-eW!^13>Aa=9ODSzwzW&A9~J2!*>I;rg|;By7o0)gnk) z`9ZQ7DyTT~k=#FMY&X{N-P?Ds=!|(h70+FKu^lZ*QxS zGF+h`T|kG-y^R+DWx&+7+l;FcXqMd`&yJ18@)numX0qk`GRgma@$7n z*{VPv{c2GqdDuz_8%Q|@p3Rdk{rh1)^I#KjC~_aHfOo*n+9Sd zoquryWX7*M|mt7k-%6y>Sowgb{%$?K5=pYWo&S* z;&Bq^?(8~Ffd-TI20US87FwS%=5efrqns^BQu{cb4Meegv`(tJj<^LnGa4mvmVEVp*zgwg^a0*<}nVDU#ZFGVf?&y@jNr0Z+ z{3@9VGD^IM=^SppjO)S5Z;)rAfz|+eqmvVmNQoT`fTk0$02~r9hm)1q?L_9U8;QUw z_#7b&LZeKLRv0}*9(kK|m#lBiN{IoZelb|XUPdC6AZff2cN)m$3K0jrAu zV9^sK)T&V@ja^L8;lNN9i-~VZlT&1k-Q0?oB(+(Y;;?-j8f_5uvuPcBWCnEE9r3G|Ioi^@^8oUrvp_JMUlMhi|0 z2xxicB*&2Dnk7fKARSy`mL1Dr#V$e1#_-wOV?Wl`@`o4Tfp2ew4DA1g zmNfbjT6Aq|0L<{_T-{Y8JDdoiMGP9WOAXfFAR(BpCNT+}&^Eu2VQ?Xf3{@C=rSmmK zwQ5l*Ppa_9M&^H?5us-R|9SS+QaS}+Sui!2;2yWD(b^{yY`NUmBEs#qHCn}E&8)Hb z!w6^SueIuX)Nadm5xd{^3wyoy*B38NO3#P3^0N7rd1sq2X-6Aj=y}tIO&)W~(N=4( zLC41N)|Rq`>)ZoVJ?K=oL+?p<`W!t;-_xh*^g4SDzyJH*>ys0u3DUjGbC(}Xll{F2 z`6d7RH*5OYhEM)a`K1%?-i4{X^5-k3FI_rw@!a(6^4#py{EZto{CdBMu?mc;aRJ)$u zYi%}yGS22K78lf%GZA&vnnNO$g} z8JvaiBhCm;qr-~{sx)aWP6nAWlg;cvOfz|S-YAaIOcI$3$)^BQ($@?rbCjKNe0W$! zt02d`*GrEkS$V;z40F;#){}-RKaMhk1FK3{SR$4EfQtrfgJ+wcf;s64#3R`7MLijr zN2J?<=*ze#PAbZk=4d?f(i6=x)H%RxNDp;m5{~%L z;Sje=ua6EV-F9#$AwZNJ9h`;~#2A*71vtn+Xn0`sGkQ9i_3Xqf78Dm%YI-h2B5mO) z5#mXPmuH+iovJ(JWZWchS#Ekua=H>um$MeE2RW9(l?Y<%h|bq)i8mn)%N#E9#i%wL z>bD?MYCvHXRj@dWMYYJANK2Y_kWe(nany?{Mxs{?%ws8-#L^51FM!Y~W5p;gp*w79 zCOB6b4q!hQjAjlaS!^&50S6}eQdN25tx#w@hm6^8fK zN6S3-%&2G(Da-wwNXS)a9moz?T^_IM7YvqeZwRAT%p+L3JPr?CwUdO=6CSm)88Blt z!m$lH3vR{U4CXSc&?e}6MmSnYW}5|VDFI3&6+4I6Dn46WM(zn$My!qD5kXt(Vv%;f4%zd`IE7G zUw-}3;NXS9&o6vFfnp=D001BWNkly@SQJ@|O z3siSarGSD<-K}k{s9U9`lfrUA8q;cNVw#j25)*eaCbltZ(yVjQnTuXD(`nM#?9Mhb zH}$Hw`v>j!dETRQu}dQy@JAXY=Q+>&exJ`XEl1O@wmtH@-w3+cDaVnTriifvy6Z<{ z0*s9dE$g};d0>aDsbjPiIbaxKcp*9OI`G|OQyO4Wq60|;Q=V4E%*u%y*gH#NPg=}n_y>1YAgu_~=MF=)jYk|7>h z=W$9?B@B5xo|I2_F&9JT9aiRfH3)69jrPGr`KENB{-F zX!4D*>lb^y&{n3B0xvS$7smE4_kzXlM$kyu!7!HG515@7o)_2~HUnGO6-KdwX$}x9 z8N;?OUqeM<2f<*EIAUtDNj?X{M?)k19ze0UIXtk1awN=2qkd2%x!?3090Vpkljat- zmq+BN$BS7yw}Y)#_)DP@*lTksU3mX6b>?S9G!~sjke#SOa*=-pGaN+ag5N13?11cs zV1+{%m1a#6WY{J88%O1W+h3;&yL~l(%_YJsCfHv?1}RAlN6W`3lIU@(2Gfhy@`PLN zlD;zLR^rJ}xfYKXTVj0^^%m+FQ~^=~Ii+$LTr5sMqZ|pX3rWasQe5x4=xib`^1Ge{ z8H-&E;dUb3ZnwkWafHdlLas;d0i_JLF$G-#?lDZ0*IEXmBA5is`(o zT7XZBkZ_dSRg_8`a+Ml0(1i+ngf}+MYLV=$kuAe%b%6S%0?tX~WNn67!^DS*nBQEH z-WO9~^8YK6mYLoJ3;MhW?Uk#6(8uVcd*`Rl($k%xd&AxQJnb(G@G!zfqNBreL~f9v z!Qur`-O?Oarqy^A2Bf*sOLzw*d2n1YwnQ+Y)XP-y68Rjeo?)C4JFWu3gEsnVn9NF~ zi@6*-pu=3F(rW>*8qDJk@!=^c%o~)xj!d{F^W@pKTXYmhARE z?)#3NWtb>hSkrx4{~r>TA{hR;CoT^7tO$vBV_#kWYV92@bl;0^}i|* z2OYB9UHMq;{P5_5c8%-NVq_D0bxaca>a}tmfuokZr|YeHXs=e2ckEsw6fe6`8ypYS zSP_gq>{>0+ig#a~j)Jp;VtG`Je28;1yEx--8W+SeFi)3 zuRU0M&^tSOduHZ|sP8}S+_`$^kGS2q(0Aka7y8ciojcdpbM7yFIPAOdhZ~}_@-@#E zAJ44LuJ$f1t=;!@ERy(RSp%eCaVL{&s}Jxaq3O?_h`asn*3wdc@0Q17>E1+6yt#N= zxnlYG$2YHEy?Xj+;qsM*g{f)CY;-yry%e3Eie8$U!Ygt#&Bv%5-rda{Zx`H727h5< zxQAC|+b>|v4ydPB?5pz#g+<&A)*VNP7AgL-PB5^O(^^e2K7MW=b08XwB+OHRO4&4k z)iO@BBSYjBNhO0nL!6WR2;&e0Ed}Aw^ZBNJ)P&;dPEB{@9Zdd;*A<1fv=q`thZYjT zy4YleV6~d& z7mO?@?mh;ZBasYxkO-S(`4KQ30rS0l0q|L917;y1Qb`@4Br&`k0a(NIjDS=%5HaD3 zI|m~$xsd}Tm^vsrl7F!+E=xmfnH@sNNOajWNxK>{w>%?ACvAx|gH3rLvKxp10c}pw z=zc!{^2WiW_+@$QAM%(iDMT@054*2KTATO_J6W~h*Su91vELZLaskjG?-mByfZy;c z9;Msm^kXQROUpr^D50j_ka`y6nlnk!Ua`C(a46+#fV?6A3ph#DPOhXLontQHk|=R*n1t4CMO$?ehax2@j%8uOYEWq`R-VtG(DQ?$sN>_x+$}2}r45wkB(&mb zDEeYa(Ja;WFf8$yT7gzUCDq`^U1GIjJw{1ZFJN@};=l8^oMb!h>~7@3Vy+P!j8}HPeTR9fkEfdZ>C9!t&k1IZeS za|NC=8CM?_V}rw1AMHUa$S-Ld)L?PGkX|l6Z>z0e^$+sPqNC%T-Q6$8#~TDr77LZ~ zM!Hgtr{xzGl8f|{Bg1=`I@I>Fo%iBB`rj|z@BRDgs<_d=K`Nj8Y31?CR*SY&8l+*Ha$KR_mC$vJwc|NdI<((T)`Gf$pi^LFOh z?Cfmst@|T^iM;M~7vF9ice@BR|Lf;BKfZo_ZQ<_1%juVw7a*-uFGXdqOh+$Yc{u%0 z9Pg!R-l9>F+}}-2J&Zn_`bM5#nzCP?deaJSZ^$_lG)ekkw-{5`5vU7TF|J}Ri@x|s z3=NV)RYZw?aW%c@DKY?>bfDoEW*C!JM_#Yta*FI$nOQoKZ_!y8j0NeYxLp@AOQP*g zXC9|*N8V}RXNbD`MRi>w?s=`+MAQh1Y9I-mKg5KUdJRIH*G_b2Lr)n-!)T~i42Pvd zm31R;S-QrYk%l2?&63AFY8b%eNLlJ8LM%qt0gS`QJn>oP1G~&DmU~3FvO?nIczb2tr9!^~isFq;NahZfdzYn0d`T*0><_HQI zFh+ea*#kDH*HM)lblB^1G@Ybv=)6|5QCM6=VNR{;ma92GOfdX0G}Yw-1`BaRKc3O{ zIxzn15|MQ)vGp_Y3rUv87Sc!lpz1^lVX4_2tbvd#CmuOJiTy3Nf^j4@_G&@!IFba~ z^Hh~!8PZ--l-id7(yyF^@YeUx3EaZIZ!wvuy)9#>w;skoR04m&QiV;# zIq<0!j+&~S#w-?6RF#4Vu*l)?qm>V0nkK*f9PIYKI(~5T{JUmpjz~%@HG}e8V)*F4 zY+c`PQVALz=%s;DNr6BtP;8-aTf!wJVQq*0x(#t-YnXOrc5RJD5H}sS#xhQ(nT@=V zG{bIeqNcGXX6b|32Ok21i%Mv5CNYMClW5)`OJgzm7PS>v!m_w37X0OTCU{&>IaWIUU6_40gh>RG%f0(6zH6tXhU8I!iX4f=WeAxhmGQH%U-j!zU>l*34)H zCzTJ^bR?bmHuC?opuhkA3$yn^N6P0jH-W?%Z5Yh30*}3b)VlO*h=30N}T{}zo(i-Ke)0?c0XD5h*eT+|cR^9=N>q)q}TAZXw;s2^%G^|VV~RU3498=8(jSjCS$Yl(DjkQ>(|x@ zpKDvd*tNCz)wS7kTcMHhz42toYFq6>&T!?7@)6!;3x2B|8X2Kkcx~m%{S^^Q0lKeT zy|y(Q0{sp6!aKX&Zs+*q^zHli@4;;^es%BO`XrDQ^mP&ddS`KZYzdG{a*Mw};K@h4 z;>~2exF?6s6N`%u{aqsc1stz0DLy1V%Zpiqhv7(Gc^3M%6oXu7@PHsY*Vif%S& z;Pf^>HAQ~oHJX6|iNRvS0${m0L~L$u;H)tKZanbZ{k+U&GOfUjzX}-54Kip-vm|IT zAP^p42O-7N!7N2sE><9I(5=L~;Oe=sW2RhzJvSM&VE}qvylxoTU_bR)ijOpkl1i#Z z5VsM2jU%DMjVyyHsl93xL}-;`EEX#m3?ajSXcjJH4~fCR-dy3ZQQ{sq3+SaW*vhfh zx5V}Fp>>!|mjQMtt6dB?UcWqj4^#O#)xQ8+f+M+2jO;qD%Nh7 z4p~`9dv7V0D#@ytu*zsGkwycLLnO%lSSmEm9)%civ5kwxSm;52D3oOVui$lznUjpy zV1omTfCou*@sKzPv|skWc&LAmyI~HU+y4wD!GF2=Wi-~Fe_Y6Q9A9ZLG|ogzRwc0+ ziTDcuo*m>47{3@zyu#x6S$Z^FOh|KYh%j25NsM!$KX^zwC>csg3}!k9K$fyACQoWN zAtlfel40gYgYU8?n6_Wap1sVY1QQ;JfbdeE<)Ph|4q%YqF!=B$>j+tSH04P%&x#)4 z`t~+ERpl=;{puzN1a-|m-(wJ7ew5~J7u>>5KQLth`~Z+^+Y1j&JI%o}BeBf7SqJ9@ zO4+6q0M|_dE|Z^u#dd`==P1)RK$2~i1V?QqUMz4B9hEU}UZhabsH&l((up9Dq>Z7b)kszCF4VQJV^GpJ z=cuMtNh-Zk)Fp2QhKyFJlpgJ4vPz20_aSyCVRcac0oxwe4u;d@VCGoM>f@`K1e>z}?Di1z-un z8tZ;_`Mic!^8M{jgd>}DJ+g^cj%jmBL|0~nMqtNhN3x5Tj-EO#Nc0R(h0}mvqH|~6 znX@a)<&WTmZY+zn89(_PATb=anMo!3Nr~hZa)9p9>g8u%8 zmS2GH!9j0#t|$L@7FyAICC`Oa1W*G!u>2p}v5`D7rK;J+UOKTU;imxyA*`0%k#KfxC|uiOOWQ`1lqM5|0Ft0lO1KYJ%>f zpf64)CK8FIi6=a{_$J)Thb7dCMqju07p6E5Ntl&evnSnnLgfHC;57T<%4G~`kcP;a zgKibadfm;ox>CL|BxAsc-9_Tssk;aCCf4rW7x;c{$`YgWR`ld?dCu zSbGF;{mAeu9F?<_MzfV6YXM5xnpCz}NXY3jSu(9fKv;G)NCqVXCyCTd;owvmpj%2F z;xJ}02&k8|@2SOrFh0N9|wsXZ{>wm&)EPKA>3xXi7&369g7 z^e;UK#bcp8j;Gm%6!+6_#H=f3VeQ4AiE~Lh3jKp|-g}lVV%+pakdk=r9aQ)3a(}|V zDCf+o#**I!u8%mTChHxbB+JWXuc)xt5lrk2 z3pjo(tKg{Zvt=P{+dJu3<_<%j&24kX-q|tne(LX0Nq&BnH|>1>m1!@$0_2*SzY)d5 zTSQvwpj+IjE|?NZNyF_zCBK`O$|O-I(+xDQMj|l>6HO~E5jSffr5Jz(hGqTB!Xq{M z&dsY@T4E>Xc3Ul(NUP|XP|RKi_7u($e`#}41{@W?FhG}^Ulugr8=Bi`(E_Zm1m!#P-WxIbuCKfW8jip1&Az<$;@zdi3v;_g#&KvS2m690dXk+DMHxgFS0%WT{Fi84 zbP}^JDBh~pYFKQ*qbx8ilE>mJ)C8ADH496mTFcHhSn{uib?{6#lC%d8bK5(r0hA=m zGRm$wL*~8{No>GQ^c4?^1Yt$wvo)_Xo~}B4*~#qCtSrYR+$Ya7vO{KRl5#|bbY!$} zcslaeZ+;7*{4W6B*?*~^+b;t?e^WjzW~$Z8m24wA_5-6R?aMNP{`U;;__Xx17?vFB zoaju2>wsS~vYnnXcYXr--At1Nhq+)e>tXJO0ml5bXPOLt$Lqduy3Y8w^g?H{D)aT* zQb$--KUK|nn~`e{0cMsp4VsaZ%;pfoFxSL*=pSF-_{$}0r>jBBy@TDkg?hxp)EwV@ z_xR+^nX1`=Sw-Cw2X7sv6|bmx{%~^QoN|mtulq3@$4uwV`5Vx7?cCP2cq~>p@}}+i1N_MNPT#%*xqS(C`*eD2`p)9I za#>(2nC+uUIV6=$Bqnu(%M-UIo{ZfR9hK~O7oP~cCMFjX1l@@x<-3VTi*g4(YC;IH zd}bhWVuDj?eukHGyOprlt!Y+N+7Nt$VUaIWJq7%9ZHVlZK@93ta`u7Bd%<_T;{25$ ztc{`a0BEgNUwi^LUi zxoMOImJQKAgVZwmDu+9;jF2v*hCx2tC^fP{iNeBlpg?C4-ARFh$e{}bI)A}!rIi6J zH=Dx0Q;x=@Mx$UH}W9XFheqeI$QiHj0K0*g^Wqujz-vLv!4+g!@d50=KwiLa8p#~Y z;6O`ZNsgOW0qHfzQBTUTQUDTXksoE$F>6 zIu#0pY=yc^q{Ofrgd5&uOrVj+Rm_l@v!VfQ5#2%+FkZWOdl!S^KYe^I7Ixn{R0L zOZjiE!L+T0rixma#f|Va-=!^9CuMQ`hdUuEeTq4;TzS%^V>?Kw?JwosNpN9?dgXH0HH2;t4>-5jp|YV5+mj}YS^rQs|p21N%C^7a#ocJWWK+deD$*T z)i7z}m2Ow)^)D|ewgUO3)kqK*i)eXDSBvrrb5;lbtCnGVCvP^kddv3Sf960jkJScx+!k|X0IN{ivO?PO5-F}mRl=`;ZMaM_3`)GT z36NEf0oavC3YQfiC-7CkdSU_tYAlME$cWG7|BJaGx&dueLYv^_G!31ei8!?S#>LqiT)#uo$)YoCr1mX zQEj*gZI^&?9ZO%Y=ea;J=FJS4#IV_n0wgShw^S9w$B4Xw#R#a2DfDyed#jfg-x*A! zu?EJG+*^3>)}l9y{qG`6l90c_nqL4g@~~!RXJRvg#aV2AVg1c!QHwM)1NIAPG}O_| zoQ!4XuCX^8nLRkk@=7dr5W^H2=!*sL!O3h4Z49U;6izIZH{upR9*>}x0r8Wu6V^4j z8G40!U<6sowG+1xYSLvnj?j1nq=qm{bsGsQ-G436D?Ay=(J=bLigXYe4x@b$)p+EK zoSq7>Bd`+wB5JJcEMpjVF9@>xqER^o2u3m`g+ycE|xOHp~iwkN!u?3iv9AQdlyVixlL+xMjC338Uf4H; z2t)Xs7LFWfQxJWXYE}m+;l)7UW;*bVAa6?WwOSH5uF7S%n$DD(DPg#6c_;V=d*DF2 zRNDSNlc|1>59HhevlTcXC@q%~O8<~S1@>EDG9<5(*LE>Bu3ckparpO<_9QV+QctE; zY&18q~2}Wbyi~=QA5$nhfWMqNWF7(hHwik9U z{)ryKk=2`mudC;|U@&?4S@Lq_4-XT0%AA$LnX_cI0tOC)x@zi6oizKCNSIYOQm`^Y zNTs%lw_{dEPywjiTI;J6uyQAisj}kD$^*<(sv20(adKGCP#KP!1-I`qu#)6Bry@G? zL`qQLiWX`$azkNOzM?(A03H~bC=piBO^=bPD9~eQ-OZo|y4pcpX*{!is)IQG*9-jV z*S{|vzPLFYCnt3xC5{BWgMSHZd5Z}oVfBiiF$rsxYOVQEcL?bWjwyJDZ%~juX2vk!xd}{U=KlDIu^~hQ2o8Jz( zFS)J`w|Y60JS)l7wZ|7YtbD$5rbp<#>}!?t#Ub3ioui|GJoBrCKy85jl(f7nIOJ`@ zET1#bOe!A)TrP*n(QeR+B1yU|BuA-8>N*1P3u zooKbC001BWNklI`o=iOfs$)nk z-zZ!TZvvm?zQ_Ge2GELfbuZi^V7?$WmiI2?YFNmOTP`#PL*8uh%HIyl8QyWti(U}t zGelFuBy2G=TM{`*g00U%n#>LXQhD$8T3hm9btFW~O}(Z%Fc&3*Ci$)o?|Wg$La05~ zGcaAV&{|yKkXb<4``l_0*6RWLeUG3?YO<^3uX(~nV8EyuFr3ZKVg4*AD{MFxal;4<=Mi$S1b8FJdzRac<50Ph(1;Y_;hbC* zY8!LQ!Q6=*fVnS-jg%|*!T1~{QXEOcG{pP3Ple`Ej^%z$t+O5GqYy^bIJC2V0X|~v zgx#S9jGd!)0a=K#_EisqP+h@S-|4<@0ghrcGq}-B2yQ&K9~IcA(Rd%)tQ%JB?j2r} zOJ%6Y2dX-zCiv*)vAD1ub}&NR<#KrtNNKCrZD!bju@rWo(Zj;LEA$Rp7>9-7v??x? z*VsFlj9lhSNCUu?g-LsEQWq zo9VJ22}&(FdHA-%f(4zZ0f1ed%+H@ECsmumB$UmH#Ht)hp2W>Kg@*DuA0+YyS*Mie zTz{6hl;}@@G6DX-HJ-fQn}K)yRe}O4uOlq{sw|> zP|u_Dx`lzW=ln2)W2nbM_~Nxtnw<{J$D$UipRU00|QEgHaeUaK&mvhmFS^_TxA z2pSAH&_7lZEMjmn$52X~sWe8Gs@cUtq9Q-n{t( zmDS5(hXUlynhwAG?^=bI%4np=&YU=_9WTbqANofhE{=+Fk*93CEwA9F{I9oDR|CT$ z|7}}(1DZ_vOm6YEpwS7r7xo`NeDGj&efc}+q*m6}*VgVoelQjtv(GJhjOJBA(6)E^ z=ItAJZjXGzBe&_FTrs!#=@G|hOx6<(%V}==@gFt0bo^loB)Pm)C@Hh@m6j! z!Ey4Gx=bnXEl;S~^F;aIOG}$&SbV>o7?NVJUx8Rq-o%pnUgfD0IvW6Ig-;P8biAY%8 zEbg=_My}*kbTUOMsx)qpCZVZFq>9o?m6D697rCfb?XFU)_NKYoKeh9D&P#f;CKBM+ zKk|$C`99}7KM2#nOoIJLg$inC$RrfQkp9sKZz?UEO|ThefeSW|U<7`VF_6t9z8qmd z$vit@v^KG;k>#*KxZ$w9a*x?D1L_`b(lqVAyBQ2caAV9zc263_g$t7hjS{Qj8I=th zkJ$XOf`{}%eaXWzzKa@*@?hd9GvMmT9{+yjJ!!J`P&*qG8|G#>M*XaLbG=^oDqw|V z)%U)@1>7jpxlk>`Wo0xX{;FOzfG$?+)gpEyq|c9x87n8taF;8z0I$v>)G`D%7+zgf zNnz10kIgc+o<#|57YW45+mGU?2GB(|zj6tq!cqn$;gfZ?!^V~;XOEBb&|0NN8z){> zOM~%Ux{i*iQ&hDPzS`DkY55u054Z7%4WA8;>(!MjeVe zOT7#PO~%is2n9+K)7Qx=Ew|sVbb0?W+@<*lDORO>UI~r$26iRTMZ1X{OLORwecJDL z!<^lD*k{Dt%=L2yu(_>VX#5z&BHB;u$qT8GAIpe51RuGp>wK8I-r?XimRMq zB`Pep?`laKbuXMnJ%mvqgT$RUEVTO_xB}|{-nfv_x1hN`N0aA&XtS{gBf zx4CtnJ5&Dv3nnPK#wnn7(9BT{Ol8D@ofMw@z%Y56rhvJ*pXR9SQ8OWH-)-R51z49| zc(ttr4kx)Q@+5gbl4Q{a(CzWI0yq>?$u!wJ9fZ|TVoD9k<8TF*>_?u9O*q3uhz%XZ#n;K`=nWls+Nn9T1(peMg_V% z(HMKj=hHjUH8j?Os*h8jJb3W`ZAjtiSDt=#ZTi|>M_=G~X=Q1teLuN6vbJD#XTGP+HtdwI?EucKNWOo z2kRtZ!QH@6nf**~@}cv6uVaj&uXkGBw!m+GDT=jbP!I)@?09&|PSl>X^LhOGrFVbx z>h<6Md17dA>g4pv+2A1P!#q>j=Gi}=etW@lee>(xy+(yEX3o*n*_XU7t$ON+i;d`P z{lBOM2Vt;f|MyBkr(dB`r4lFH-A)sB_D=U2d(~pz-kRQAG+`4t+ z)+_h!-J6&w=JQ6uQsH25Iym|Fw*+B6|JvB?hacU(vjC@c(z+l71WPwJUSlY{`I+%h zE`6XFjDj$AVKds~N}s$Sz`f5(RvP6+=eovPVXGp^3xZb>+xvQPdoni)K36u{YnWRw z0J@9t%7+0pxY=iPGI|G7GBrz*&b@odh_XE4a-ohhkA9`_{@*-p1+~S zhG<$(`#8GiY5VdN8Qe06wyOr6C}P>_CWc?U*fp}-h*3fKB|y8IMrozwhMwnG4i9|+ zf#&KE+BxvoYJC zcmY1ViaHuS7LZ*oE|-hNM|HBI3B6i1c$V(UfRl;yF{@mr)ztRl3g(_M6j;aPawwZ} z%xE!ayBq~SgWY4==IVh+pCP@GbZeA`1;btz!#uV4_()-rV@87?D|ACOgJ3Qx&Pshg zGW;!$P0oV3NUK0r#>%5JlXPVQ&jz*M%s`TlCRN3dw;S^_Gh>sF=^>oIdi5&v=gIk_ zOTDxjff2CBVm>LcZ-m{{aH^+ega@TTcH;>@ei28BEK9atDW$O(VPSHgFO>~bsf0Ge zO5HFd&JJf)aTLb}98VFoVKCc8_gFEgH3aS?<5|T%r=-QQSF|JaxiN?Hb1r0+Vc*Y| zWG(8lR141grAjgky62^=x__I2@nU1UY=T2^-mq3mHj_b^4HQ%v9_|Ote>L|FnR)b9 zrB>VbEXv#=ytkGkY^qs%M!clqS+j=0b{%et>e!Gkgn1g`8DCw`MNJCIlU!dvJG;oD zjM|XaFN%SETCF*=)8QxpdY}XjZk*``kXr+)*NENPItV3=#(7jT;66YPUDICJE*{WM zc&JC>h@!Xw;*opupZ2zNRZNJt)u-^&_~mUw3#>(21J6;)K;6-tsuVo`nNQx;z;h92 z0ms_@Vo7SLAJ`j?cp`IW`|9%2^p(p-Zi&{o94&-F*>NRtD4kO9x-#dkBlxaDK34E0 zwJxMp9?Ef9ol4$%6iKJsk%GD%X`4aZ3k%ar{_7qk?p~5jSVR~e?K#RQmh{9Ofw?I5 zjxT|K&4%>$+wUGA!kU)(SAO7YK87X^qrEu1+^B7SYNwo&=9LQ{uwnGq_0J{TGQRx2 zQRhFM1f5D&UiFH%cm>}7Td8Eb*)FZu$!n%P}B438-M)!t+CR;H^D}N2ethU|8*1D z+S$p|Us{a5bx*Gt@Y4u!J-b;H_X*NvzRPQa!B%st(hRqPXDBMDKVi|7H6W;F>Z^9< zpPBgUd#~KPdDHOrts6It-2Uz6I};Q4#^xKKYPL`SuUWjpCgod^W!^rHa32@ z={_LMc?%m4jcG0}77T1rBpcSDTZZT^7VIG(Y(89kZKEK`GSI2}9&S2}3NIHQ3T6vX zV*6;X^b0^2X;UXKPdrQf=c+fHLqZ%_>FRLINdLOrjfUp`-9;T^b@&Bc?2V)%>Q19ZkuG z&cqTU%A2HUDc#_6n(*h|t^;m@1WOojqskXUF=NL-tbsEb8wvO>qG*Z<#e9wQ4#{tn z5fv_z5lsQGF<*mS!`rg)UO<_paheb;@#7H~F02>|yaxql?#y;~uf8{8AAiP%RHe6J zuc`tWE!0d^LYe z|Iw(uG8!$0#fF-y{~evNCr>^WCx+pEmp4G2)i8PnldtcBRXs?MCBx_m!{Vb+L*c91 z0?*G}RWH)ycQf-d_=V?3FDXLQPHMY^llC|_rN5*RE0tmIn~3cWrFuhrktTOCmEKJm znU!t;v{nZL-(q&;jis{jU6MDH(UD@9981P!2SyXk=hRd(MJ1AfDTC)E8CuDBDvtFY z8CH@p9aR}>L#@|c zd&T&=rf!F|b*Y^V_`N2nrpylIV){aQt!dW|?Kk@5hZdV&BfjI?v>X}#jp}^ixrT$= znoC1pjSLKl1(q&#RpvJ7}K?LVO9jV8)U;!TVLEr2(wCb z0e6UjPWF>_Q0*icLwDkplRGW7Jw6+6a9$Tx25{_TkYGmS0B9n z2@rh!`d{vq_nAYVoN5job}0<~A6sYl+thuBar~0VcF0j|FK%({U>p;>#_@>e7L)i5 zMO6n3u!v9tEsLX|h05LHqBZJ7ZjdUWDv<(;0BsUnOugW$FH(_MhnOmDnY2Hk7rSe3 zdbR&y-_P?qZf^?0aqNQ=6my>Qe8102Bv~TrNj!H5w=(OJlL5nZdlh?|4O}R?UAFf7 z9jJK>}!_{M=v#xY5Q6z2pTmK27xsVHmZ3{W95Qlny}aG39WVQ$sLxp z&7FJBcH0sQZHmDbnm1Z*(JS8Dg7P{6m1u8vN6O{bGQ;qyOx9ttzJWr)Ie`tH`7Si9 z23J>EE+2ypw^|14knelIaK?V0;F6$V7X&-PU~QtCAKcwtv=b{UJOYg%GxRJ39oLO8 zca$SoJV$D(NH-W)5~UZ4Xkd*C#bYNcHtQ>-rP)~kz!@q7-kzr*=@9)3Qbf}%%fQ)F z|3W;zP6VYL9%B0Z(4O@eI~$BLjwTQb#9fd93DPTsjn6)MxDc+!Wkxa*91fRfgW4T6j%7*A6tmC4JH*b6`BOHwooQ<+-xqaT$jaQY?Q2y${|R+f7%c zfUa@BTAh|x$?!P6T~h)_8c8&flPI7yj?VA1+S8WY$Vl+YG))nK^YFO80Ol^4Arxp z(TbD3(q5kgXc}cYof3seGsVX9QZLFWf?kFWi5s0;siNU(=Xt;1XG`4Z8`bTkN~x6H zDK+~2idMgk&Y)7MD2}qy=vOq{O+Bq(69#k#sd|SrN=ccC%1Fs{v@}R5u&Q411y}Av zMa0)|b$8K+S09y^7I!yYZ{a|j-ntuGQ~B$ffMq)(TY3}guiV98e7(Y|SsBucLS~Xd z2Fict=t@ewSq|mYQvLCZBWDSHX1{w_gXFVEbwd!e@~!;pgu`u(sn1f)KrMqHS}|8g zM1sNL_EBD^?Wzmsm6Iju^Sm;$jKf~~B~iP-dnI^ZJ6wj>M+MQK!{am8?tb&@C!bw8 zIQZt^-~dQG><(LA9x9_9n+1$73_o|%Y~hM4Y;bHA8mw|cX^xI8|Fr70$4*{Y9!jI< zhxe4%sG6i@zc9)D^$W{Gb=JvCu|M6s`PR=g0)KdD2>?Fr$gfPkG9g_#PVK>o;VD7Ye;! z@$dWa73R>t`NKqH(@&uyAKLy$;nq(!b`5YJYohE3uC^$t&BcDBUhh(wUmLI`Q`TbLY;S8AmKNe*W^gYo{hYo!(z7hm$MCMdQlQ>K8Ab{T*(5|Nf=y zCFD;9;Tv8Z(a@G*C$?LRJP3>#BeTuDVbpgu(_Gb_^#ljrX!^!mr$5dB+JLDZk>JX( zRHj^a6xonB^wlKBD!2{qYO{4uxX$z$G|jk|-GRzxC3{wIqoq+NLT;Al2(vx)uejP7 z7)R4(=&c*{D%mRVkVgY@8+qFOGJ=NeDwJbk9k#n>&};BJ`;ako*qAOe=mi2gNak3Z ztx~=)2l$q;_Zqe?tQor6lhQyNy|qslXku^`z?wCw?C7w60}7?Qia z#fW+e{AKQJkSb^IG*MU-ASFhn$bvB=&q{oX2{^Ykkw_T#oya8~BoYs%CUUt$c74<( z-P_}b+(lO9`J)itG*nP_HJ6TICs*86B;?k;G)aTMA&@s2h>Q@*G0E09BF;PFrqoHb zB_$1OW0UqQYO6^@U!`&+C4M%}yGPVy)WvcnwLUT?Kv>X9bZ=vFqvs5hbeG$KDNbOV zs5S_mEbf*1Gc%o;#w7gLm~dxb{MV2H6D)992+jUqlIq*|#)kMT4Y^L^vKom*P< zl1%yZ7JUmwb_X5#kTB*hRZpvbO*37A{qTzGBKHU2*4Rf&U54l*b`az0oQm|Yb6Bgh~y#WCpEL9ry!2l^V869_D z91-=e*LSCi{3@GZa> zdEpvyZ1rSD?>QFt`ADSXlIkvh068z(T|SY*-#tOACLH@g|D8z z?#rdG9DnuoJA_?r@YdcV#e9Z~$!N64{$&rdZ;>=sgWjh=a+IMoAGyl*W{j z1PKG)Jp30Z+C@Pq8u7w`wFSyir>!VR(FrZ&GUnYnJrWD0y)dntR_9cMza=X{8^FL?s!ZZ`eN`Ms71 zb1U=S$Ga(nRiQ}GU*&}&vgohJbTY;uT8uXyLl*6IJx^{GHOU%}4#Rc5_3krtabFT8tL%sK8a5?7@Hf*8RAYo5Dq8Y)LP!7+*U64AU&#) z^c1S;9E0ew(VT&?0W!j^L%|4?H%#+U>}BwgHW7A37Lrk|ive6Ilr$3(wBaml=%P_O z2aOa*XdxUSdc#219!(Zc^^x=$@RBB?`=EHhR6uVy`pF_Sep7#f{Q)2GGw{hlB}frWEZxMJs))$mrQ9 z?*=tT4d&0Cjg)GV8n?uFQ;kpL`Awxdjg2Lcw`j2YiIO<#DfH2)I|}=31!~S_7adtb!;S=~lpDN~zVE#8Sd8PPi$Cmgj!3UjewfdJ!eT zUEKBli75F`gr}PU%&IOm#$8!l-ZUAX=L?(q(N!GBDlxhace!^2@yf^+KZ7xzvFR zO9bk^khQAjR^&?x*u0%dYbm&HLuQp%O*Qf}jTh2hSv0O&C@TxRHI+1QX2dzms) zRts>&lpN9RBJ^kd<>JCO|18x!fxTPWVUd-wjsZ=sXAGBGhRl7HTxFN^>+NiH$8wG^fL zTjX(@17^t~;o}LK*N=&|djW4m@qcJ%?s)fEtgY zhXF;vS^+FXIPMs&>yWxmjWfbIup_PuD5p4Zeu6#lbbP!%8j(AUjfT!DKAI9lji7L0 z^eQ&NndwL!iO(5<;1r5}*s~+qWRaq4*BzXNM6Xl4z!gsfUyv64W9S!;Gy+F zhCpL*J?IRD?hHEHd^WeefiNuolDMdkU$D7u*bzWugNq!iU@U!Y@=J09eqcLNuUsrB z#L*5{5X0#JhtC`|3q|g5*>QaxU=k(5)jKOkhM8L*vm>4HbpS+AJn}$*nWA1f!Ax@+%Yu&*sjotbqB# znUoNoD?p18^z7`J*`DMXfN(CIOZFttz`&*NcgW)q?91hlK&caHfn&D)qViARPpBq* zK_%iX!!gd52$JY4nlZ}fH!>_!cGOa4nM{sWU!m@VCuu*LQROqUI6!vO&_+*cA#kY& zV{bt1S?+;R3NZ<1R1bE*&^=={oE9`b2W*B48b;tblpbZd3C_ZZgz0jxnM}`_NGz5P zk^&E4rmQ>{DOkN(=%tI=(lEyrFdL7U4^5kqRt9GW^82gR17GYpb)x#^Vi%hT0lvG6 zwZ91VzP?sHaqacn0Q{E|)ql(9-50mtKk^7vSd%M@#mAes?iRJU0l^&QH+@M){7j2c z1%qz^S}h$=QFJed&P>B9w)Vl~ioIpEEvfWb-M>IB=&3=5ixYN~F|7V?AJSKCwF@^F zO$Wo?DIvm(hT;kd-us8xsJE2w8u)W%V{J-BSeQI7?lp8-o+SS+ey|a%&BA~bLzE1t zZ?YyRE0>+Im7rkrl3Z4HLWaer5ma8+FpJ*moE2XDU}L1L-#d5TV#q9 z>-v~W--18Lh^~@z z?5eW@wz?2UXp?97Y+jz_^19_TU&Hkisu_GJ_(g09(w>oPrP*2-E4O2WjkL)d$bj}X z96mw!#sce*Ts|Le$dm29hQKenkZj&*_>=@r8Os4e+;GHga(lXt0wt)cM(c=zj@Pft z11SeOf~Q%16z55C97LT$JU)b;B(LDCW?iM&j3jW4jW6uJg0}S`IrRxU8020g4*M?> zI#O~DIt9nC4%IU$VY^ph0rs%pS6hMQMErq47)?j822<;dn~-KjnkZ~w9tWxkBV6-( z0MH(=Sg5GAxe)8zK6Wfb?l}9>qd{0q{Y+mHHobE{Q|6rQh5cxbag=x*Pv|PrfCSE5 z1eIkpG;4#qOd|tdtc#f(4C%l^_~icTso-bdzE`dO=B6Bb_NoQG27s>#4LF582+o`Dh-MT zKgK?HuW2JJqc)f@PFZkEcx7hNS=|h04S-G9zxqEa=(ckgZfXeh@YEPUn61Ez!&7_9 z!(*R6NO{+yP()pv93unn9iDm<*fC||D2Kxvf~c|1S^RzqtxY5YD+y#yqJcsFUyxtc z02>Imu=PdT2&%4QY+?x365kwWv~{_XEo-i3v9fyIsC=^c;XhbnZbf57d}4v(NM#2ZVffJNQi!X|HnsClw9VWeWjRn4@OmW`DmWuR`l=UXKe@VF>(O z@DN9J{tVR>sA+*KVNQ#eqt>zsu>$RF*@dFfeadC?$D{BZF%x51UXm*3%O^RT-sTHY z6eZszr`Eh~;57pW+fl@8926|h(+jNm9n9mPg&4xFLIHtVmi7!r4I37wi#;%ZoT#wj zFsQw8H5K^1z!P=l!e*{xp}_zwn=lrXFtoQX+z1Pj#KHj!}0of2DJ==u1}ChIh{#8L7^a?n2AJ?*#Qr*Kr9m`>&T%* z#xvkJ12i>yXl#auXh_P8a;nT>bd!2477bz@Jd|EFS&_)utFcrpw~eidVd+9;5NQyUe~Xr^Qjw4

dvmMF5?zN>TvLaD0 zjjyFE6^$h(Q|#0Y^|-AqBhOArTFEZWlV1WJCRmV|uowc#L&!r)VT{p0w~j#|4c*J0 z#vby}ZG9P|8+q9uu^5sRrF3#(xogX3NzB{sqACqzQD z;BM&mNgRXbIRIov^&r@Al$k(~JfoxmB51+qCsJ`e-XdI>R*OpRglHe0M21w%f&A%5wNT6QZ_}PP4zlh`$AVW@A`u0bqh=^_RzWe z>QJYHQ8GJ{IK}RG4EQW#Ip!H2U6>ap&f4MmhT8^={3|$;;Xf9RT%YeY9@B=@O~Da- z|97>8g#~PN7a){E=P%7i+IFNyq%zxohsWGLLbd#kmEA@pz%begl{RCPEsPgDn2TR( zorNKf(NdKDiQ|OIV?D~=FekDl!YasDUFk!*qrcmCYcb(M_hssoEaSBae@o-J|!6dt`Jlcg{4{$lVUUtpG zOzeQ2sjOL*<(lgkUj9zcl7=r&ul%nzU=8AMb12mVjJiRA;kmie)Rg)8sK2+3 zc#gfEs-PF9hE%EL@nqaNe`CeSQLd0`Kr&D8#oV53cY5!$2-;l&ly;SU&!( zX!gcp36pp?j&q9eO8U;RwA&`()=@Ow4k)aKHMv6rw5|;vXFdHDvS6%&zkmGo)0f_A z7hEw`$9ngtvArkv4lg3UaXWL(rlp2foddzDbOsaSjF3ElBuqgEgjjOe348GX8l)=C zLANuMJL$9-Ar~9ur9{4o+tmY{wQ$4&BQuXAu z-J8OI`3iU=8+8`h;YY;Q44)_+RXq=b zgjOW1`C@@1+=F^K#OejChW((q?4paYXb=#qangRT8W`~!i6hJ`@y(5UWWw|)$?q6E zC%$CupdXcl5i5b+ZW~<;jD1Fz19&r|p^>{m3$P_@HjdeI!kUgF-zu263r~`usn239 zk|1p`*cM2}fEsAhcAfkZXagLySfR64y#YV7$6D` zjNr;JvZ7)61IcGL&cFpR;V!2;P(J=1c8O)_*^VL9_Ukh$;r8#p06 zdg8>u`1mpT0AO0d{e1+ViU>XifyfcA#3IbQiXm-9F3Pau4RACqP#anb1T=e+>gbT4 zg6B{mN`@?`s;QK44C4$i+oWJMkTsT+lUD|#gkA$Q01*WN;l)M^5|msHzN8jPfm>O8 zS7oDhIoR6zJeoxFuVGY>OG$QI7rub`vzyK##5WtQBn5CGy)p^{!^nuP=TfPg*%bO& zvz5vUyo-gaa*!J7ogG2$`c5M!RJem4JMYS{8qDQDN~Jq^)<`T3<)A|e36~AE2ICo(+v*33msMh zLktZ?HoB0y9e^?~8E`f_g9U(LK2rHJx&;>)_srEVSZi&8`&?}T?x*|;<7)Yh18Q*M zVU45IawIk&^=p$by+@3W1_%R@-}}JXTpF(RHdoL6^>3eEaUAF8F9E*){_4Ybde

yzwp91H#f%*OH?#&@hLH>z^#_Y3jkV@9U1)yI6>9rOb?Lf(4@$z+?2q!~x~a=EMQO7xU)ZCIwU=u&?&Q8227fWL#ykhD`%)hH)1* zZfuyYn@Ao(-LAe5c~7UR96*~~{Ms62r7tO4a{4<0`N61*Z{M znXuXkEPt7Kl}{9f{8D=*+*u%5?g$pc0^DXQNAPZt(UX?tD`E?b+tbAa60zi2GsWOc z-a_->jB2jr7pe$H(YdgWqz!nKW`!d^vyiTlpMD0~duuGKbeAee$%CJA%EKKC^w0J-?HTx|$TI#j!h+F#d+g zmrh5eqrzu@f$cAb(<3||F&seV(UE~i;gLszsUy4N zy4np7?2cO0MTXdF4<{DDDbkIH0veFjjI<*S^WY z0HUA=W63RsbHosb1sewX+2kk`&q?&BqNaRBlc5a+>dMzuHp+o>9e8UX3rlFOwlHK3 zEPb16!-aZk=c>RL?(P)o5IZ*tl}5Ip z3*Z8a2vam6F>MM>MBNVbP=csA2%OLA0vFMdWWb$X&r?FHs!DUAbx;kYMnWYZxH0dI zp|RP8yji=Hx*cFUHPFyx!Tto;mA3&^*jdyOBL9j3Aq}QuLA}~VZBw_=ZQTE?MyK!a znCk)tbkf&bQvq|oJD-L$dW?!@A}%`@NRk)&YeJj*$8;r(v2$$!G19~G3T3Tdpwt-{ zJ#^Y}qP4{f0=(aTySci$>NuPK`sVLnT-tP;E9V^Nf<5~B2LS=Qhrhgf_OosIn}7QQ zXEVU;tS5c`zj*uN7vDT@3Io3I9`ZY|ZN^%7*y|h?Q0`|)hnpRZWJ{e)mvx-%_8Mw6 zu%~}6ExXz-H@Xu0V>e5>tZ|gf7ybWt1l`@ghe0xSxpSVtihneRhJH9_Pt{6urCRfT zVVQM=WBTajAy2A>pUXFxx&dKA4mE_?)|OmqW<%K!n+FYUg_F^(>>ze6Mk~6-b|eFr zl*!!QwPmjf*sXACy0BYnmbF=8nKoh9Smnlh)x45m2+q!gz6bc-1Pk^^@G*$7etcop z=bu3c>nO;!$azR-PA=?;Hnq)q*`d*DQ-2h#yBe5EyA^RXlx5pCTebY zk|3yPYq%Q(%TXVO(@!|VgvfpPGZP~DSsCYdHS*QiRW zsy_)oX;Zl_6Dhg%UBd*M@SRqIZIZ92PaW=eQp~)H2!RPOu?XL>N3lda6lp`{EZ@0; zo$+|gtDQ?w&+H2<`B2~B3&~TK;t)~;NCkTl<$;K2;5kCFZ3>kYHE}OClYN-V4IXTz9hUjeguaS)XtVX-o~Ig4r`L!u>6*`{#s1pK;LhW zZ4B#o^VWJk!D+L_P|70no`dVp5=H2(Fp{1|BnRWO@{`to=sLTfHV-R|2aHMhC<~#s zX6!iFe3*buZOvl=8{-A34V9A6(R8TZiV+O@m64Gqi>BU0Vu~gr0gAdx(UeVG?ILTF zDw~pa>Tc3%e?c#HF{!77TplOJWG8qQZW9VGN!Z0BA9lTxsdWkmz$EvU-+RYl?& zD4)a8dsX!JareSizqKBaU{9We6la4{B$<>N)kykxjuE$N8?vzMb>!DG$I6b?vLcnD z=Q0MgEQn=1DtTiPzZM}K(U~j1Ct>o4a2MILJV{#iVocK7SF`6%8G}L5PMu!h7_MCK z(|p!^MBCrlKQNh|RlyOjIXmlGtXSuXv$fh&=_g*Uz4T)PVCkW2XHTE_o(>F+&o4e* ztG$@d-#H5moWD0+xb=K(wM2>G^z~b>Bnlt@IS_6A>C<1-YR^qjb2uGyN3i_?^TE`a zYNq*MIUI9i(c^`%OQm^Q5aOW(tf1u~h~Frj^g1Oku@CwT=jUJfKRe(H&s->NUVl7J z_Ra2u=LtHtk>_sCN=)P4OQ4<0;t_`xpPWT9GR1dH<^9S<5;D-es}bOLpBD#+lfRIYDc zondy^PS%y8ILH*FtM`C1uR_c1isxwWq9qB<4IWSw&|QLKkT%pp1Co6fFL$~7Xs)SC z08Czz+@gB0Nr{xYXZb*Pi)TgS5|({QMZnNrW5z?1Elo=(sh5e}P%$u>Sy+nfftC@_ z*_bai3%=r2?4$u{_t+Rm#&buIU6DZ9&9^aT(qlu0v|#MylD89%jA`0DLhaE|F1Iu` z@^h#$@f>Lik&4%F9MO$rAWJ<_PDD7T=t;^6jSI_JBv~|hl?#TPr-MScO z5zPJ=l(zr#zUJjQwNN6yLuu880ARTtvv1cNt6$z0f%`Y~cDM_<9&IWx-sW&mlilu- zMvLXIh%Xyq#?n1RVX2F-oqaC~=y1p=Zsfy=R}-SYiY%}Mjx5xH=>^iU>TL_4@HWm3 z=FE{b&6*del3ARvl|=H3^QKpk2ZvB(ekgsVUjO!2xS#s6(xg% zc*g>41<4FtNrjq-jP+}=p#U@ z=q*Am`H*7s`GU7J#7;JFxRI;n!e0;L(2Cb@IY~y)rMWD%N!~JS51eXhjG+H}6}-RX zBCInLK^^df510pyiN^9VU65S5H2uzg-OW*JlQU{bfKa(Tn%-AqW}OP07*naRPSzD_C>J- z&t1(e^bSf6O~C_&!G^=jYGPQP>|Ww$3$;ry+sUS`p=Aug94m*C%A-jVDu*UTnF-Ef z#jDwK3v=j^k)``AhV4AkHVkO(zHSns4UnO=DrG26V)`vkj^ymlrJO1WCjr_tt|RpV zr%^W(`%Ectv7<=$FP2^~bgbr4Be%pqeYz@xZi@J;4b8UZwES;Y>dSgeNMOv@Aj_hZ=*Ylt|>?a%I zLy%;D zwg}VcaJY@CBhSIICvq5S?=du8=+{^}yigCfh54WwZe!?N4^+YxOk-(ZjFxmla5vX{+NiGU^e{7_esg%f^W9kn#nP7Szpd zPyozbc8LB8B-_~VMkL9K%Lt#2Rhd8w7LA!2^%OX=0cQ2;+_rSAVLB=`_P{~%Gv7*q z4~bCc=vP{353EFbwXT#(7QLlX*83LpfOf!agK0!O7PS{3_X_eWy_mT4hMiF5TELL{ z%I(6elB|wkMiOszCM?ep+!sbX4KFTeDI9ZsmIl*0QaEL&1keOt=}dc8Oxxfij~fkT z8b0%Cz;%D~`Fnr)$>i>j?mSa_`Etm(@C)JR?168eexX+T?#hsp7{gA16D%4rut&r2#@@CqfKj^|gI zm-9h_r56|mEZK$91&83r0hjqkbVpzXo<4Qpe;9C(gtfnXWp_f3BL8n9*ziuA`R3>u zGB&k*PF?=s4Mxy!#PW*YXdtk2;O}qtXCSngeTOLC+>H<^t5Zs8>d|;rm_VELI+tQ^FCkZPZ%tCy`pG+UUDoAs`JXlI(hO``;-3( zzpJZX&7og?ap>UsE>d8lwGSVC@%JyjeDvVq-f78|E3e!bYg)Q{ksAX7VywJOptrPh{iL#$+R=+)#g#*7%BSGmUNkcA7_VOt z)|*%XTNyJ4Cn2K}^rlilrGt@hX42km;u^@PrxBQn#*Skf8yo`6R)|9`*r1XvvZ^#rtTa}yYQvmDTBn0~4S9%P zB6+i-L~@X2Te7M=WRqr1ZIV^1(d$JfXjG(X_hhKx7ft>zbZDEJ^NZwYFNohC*Oo6r-OFMTB zZ$OY+1y^9wE|(Bu0|mg)ZY?wAN`pFFjyd^_%Luj%Aff|{U<6fa@P~`>S4`gEw*%1X zf)R<5EElVQali~}D3%GiG`a>ce>Pz|!dN-u+7Vn%29qXKS4hPYy6Z{`5+_lAWM)QO z*|fP#CSg*cE3nZq8)3pnFDx;RrIY;%NG1?e7R08L|j+PQ&?| z1*&GETTvWEPZFagu@6QFw44zo9(QFah-Ugm*5k>l>qze6Y|mp_kh*TIdC*4)Abs4m zhE8B~F#vT(JUFtA_Jtl!oKHhhwH*cX#i)9aVUtQ}hp2}ZR=nLW_c5#P;h|Q4>v2zX zyCqL-BbB3{i5!?qceREPQ27{6V8m(xgAXAM%{%AVHR$+8Fu0+N7>@;tkuPcJ&;%Ha zRA?tRzf8J9pOIU@6Y(3!bY}hreZOo-^7)|L!YN^2$Q$$8nS6#qpLkjuaVIRpa zycq}!+GI6hs2-vzIK*rM#8ie6ZNFJ6`08jUly3pr`uG8Gxx`IdBC#1xB;W&dk zAar3|Sa9SZh0?)7VZV?X7r0&7hf2DTxU;&7)oLkKi0l`d+C5lSM^7O~d9)l(-HD{g zNZCb5MRd*v!A9N=h`a~Ro6p(4U#(oogY!1Z4ST!G8=`U^^JDEL6kgk~39-gMLzdM9 z(wEsoNI4ehGg3J6sY0GzOvnc*BdA*byZbl?n_!d|N9;b}?qfv&EpQj>VEBPyH(~(; z;wXW`-Mv&utD`5*T>kX-=L*2H zu>MYr+4Y4$;xm`W-de9<0W7axd>l*wY-8}&B`We-AD0i1^$Njx6Sli>DB+9Q-CxLq zt30?cp@m12TER#;)_F?GCR9ykcP7SFy-F`a;E}8faU@rD@N)A!axSh0O$V#yVrZ z3<31OUBWBeQ^OptL!PxXa37q0_!Q4O4#_vPW;$gCR-dpX(Zg&4rgC~|SSJ8WGwqFg z5yWkKy~_@75TYxC(UZFR1?Smy23&qli5-r)x#c-6WI(b8kykG9e}?=cybmK1%O3A-g5brTLClo5S)ByIRabut zN@(btTSL%13luXK8c7~7{`L$-sntSm*0vm`9&6|jDi{QI4L=Gs9Bjx6GI<5EDrg4+ z+9e&}k^(DWq;mM(tkv>j5-l)lVDD?dS%lrN+{#CJH;_4GEG#V0aOC4KI_&o@083+j z?0@0A2w@B@??@H5zm9%jUrhh8mJnQcTppC*@r@dRQQl(I+`;bIAUMQ`|wH2&^qm9rm2F^2r87a-EF3P7GxeofG7RgSdgv*z=c^iOp`A#oGxvXGJ zf{O(&uWvTx_cbFxVaS`os+mQ}!UyhnF?%i{^$Nrr;h3pLLXPeu3%ZH4%-lVQu)3A! z3jLie&c4WuSSVZ%C&G|A*DLb6uU81eKKPO9 zK1`nzg3Yl?Z2$IAo71Y$3jh615G6l$6elOxkYq2l$NH!%!`B#r8M>{u_mvLlQjBHa z>L&Q)rPI|#+yx$>8nPmEW1hqlTy1 z*0LXh;{Z3bkU-m_X%ZdeqDGUbq?VNL02r=f%!A?x2Gw8=k*c9BA%Uq0VnA7|$ z@Fv4RRfA?_37QLcg}s;q&4644ij15Orzw|nBJG0kN*HVqGi#^mTK1a4ke3Blg~A4R zun&%7-W>c4i(aN-Vf2j5XfpsK5(BYN3d}8WoYf6UGrk3960Eks5#heT#i&Q= zanzG-^$7NQ;9nYIDhKdZ_00mILr`RSgxt1xE2p+vJAR`)Qf zvL7O8#8i4(r-u$X7#NCV(x7e}&_;=ug+u4ka%b01i%|gTXR=-`DD*q2%0eu(pMjI4 z#SE+r0gFMA-DnjI0h3YoE1=6@N~Cl6vG4VTFolK~Yavue7ZUX;o8t(?a-+!HJubYL zEpCuN!)yepGv?6+bP>i%70j9on+M|+xQ(;`33mj3V=ItgttKM!W3{jvDc{+TR0M@1 z33!DgWpp8xS5l?=Y9s;+4^lYL`694Z5`2rW{U}8@5`ehCc7_zNnB!hnAT+hwDAzF| zHS)R%ZoZgC=U>jG6^R>I-~z47bS339h%)yg8>?)`dmsZkA4!!+iJJ`D%H<1Ggf)fl z<_pSu8HtGnF*MNS=EiU4nYzK+U*WE^$5h#jJ?}9)KZC<(_AC%*XHm$|$DuW#mjt?x z5-qeVFp&f1BkX|{!dX!$P+jc%K_qgKkVl8xb(elst^|mbQCsRMN ztncJ&i|2k_?EB$+i&piCpl}|eO?1;#UL~Y5Q zEh&;J|Cvm+#FJ!6LmegSQoOlcH3YGQg4NCIoVrUkm@k2_P!#ZtNdtlA5OV0DlonR# zwlWxFJ8btJa@#IBZ0AzOD0@H8_ow>O5ZltvKPj>!^yqot=Z|YcDhsxEZlSDVOM+(K z@HN~!VhTM}!*v1N#s6;aH4AmaV&YVJ!)a7FoanV~JtqTmQ{d|foW0yluZTf8ST6TU z?Srhi%gV2G$=BQEH~p`i&Y!(M-YojX7tg=+THukJ2*3OV1o-pMnL+;qJI^S6aU=i! zt+l}WgWi59^j_!gr{})&y&qIQkO*mB2$W-C>%bAh%S2ci%xq`TAgeKO$;k1NWYmbK zJ-SL8;H#e7eyhsfG;gKs=@Pu8AsU0`Eo(N;y^ZGWtOs}Y3oLhGE2F|(9TpH5}4Y31u z#1m2f7C~3BEqR4wVz>yPLqMzXU|zc6!$_p7P~f0HxD{32RWKG{(aR+lzY!&xl6!&i z`l?md$EpL4$&6%hYY(QH52~&(n2)jyrsv2gYmnS$W50%}YiOdY43k}HaNhWD&={_9 z;?+vNnlV7mR~So|g4*&Thc;HcR#N5fs!?SwuVwNJ#+Wm%kRfl^OO6g_R!^uusz?Pb zv2#8%XICn#m6OWCBESJVPr zImC*jkEywe;-ArA5q1S=vMzQ39h`$TcyekoGbt1BT*?kEvfWJ?ZAPDUZc60~lZz?P zcJWZd>r`rS4unq4%o#IIO=f}5F`lc_K$z7AxJdaz zv2bK$xX`O-3xz!yk_tyfgV|&&xtBa*(rn!LAX#kf73v2@btz*gBsbo!x8AE88?MvX zP*@S|Z71JeY42@N$B=BHf0p4#lIiw!oI*)gShN98m4#O$W?=NL)K~i}Ue$u*zx!WB zPmWs(wfL=FABROlYLhjUD6MRG`(U|{+Aft+ken1*RvuT)Aem9LD{DZOZ7@z)h$5@) zA-?62d~zxvN^_w`#pqZsMNncePg_<3Wx)9cR;cDpaV`9`<7O1OVSd5r@$O%qJo(q(oD|w^e4A{1Rk1Xy zVX~K%C8O{aov`j1g||JaQgb|U9!GZ&jl8b0v)7cgyr;NYjP-6M|dC=^tcC! z9k8Rq7i5pRFkOE2(VgDMzi|M3`80*Y8$iRBU%gG;AWGm*L(^$gI*>mRuo38i7}1)5~`jr6Gegst}%bm$9k7yV57qWsBI9S4ru3VFl~TJ0<~0G#8r~XQSJMDtauqT2knqu z_Ej~XX8jAVjTzuZS^Y-WB))nFf00@U^VJdw(a_s|zghyM^L@o+88(;5;lPEIN1R2- zMoE^V6PHU_>1Rr61}-6c?yph7u&RQ=6T?^vk)*R)Q}za0EfOgaXEB7X>ku9=yeMwVx$gw;r{ zj2zqH3IkjuKclI*C@ez$+TBT!rCKE$4+{rxxI`+J7O@3|z7HVSCNyIQ-B zaH>{6Fb2$~*4cnv4#!<#Z*83K>=ak~&WCgz;g-H9HcW+sM9)Am1rOtWuDe}L8Cl8# zacPu7=?(X3U$i_)Jp&nCOvc$oe|lwh+M()YwG+v5q%MWa(-J*Xc%;}#h^d1cXy8rRVNHIjRAjG zBCOc%)#s0AXRkaqoc#y@h57UoP9r`w% z+-ki!J1+QDJHz@|;EW<#0E}U|S+*al=~XAWRLiFG$;v&v?I3)6EY9*6@Yjr>UrF9N z_R1Gt6`o#j#SGtm_QSv5t>*7NuAKe;{g0Zz(4SvztBueNsZU)?OSg*zZiIXGS&YvNxpRMDgLZD=zLzOIDpYKL%mv)0@jm?%=-COKt|OT7?}?TMgumgqzy` zUZe2H1IfmwGYhL@L4GOEuq^7!19H}+T*FmE%sU}8bL&Q9T-%Uy3TVPch~h{S+2I6P z(rkTebH}Z=?H9PTtRKN~YW%?I9RuKh97RwdLwTbZIDL$op}t##7)#vy172PO8YvHO z8Ud-i22%uVTxhVRsWr|d;`#&5Cp-`ro?y@%^sCmvXfK307~6{Z4RW^_H%Fseq(u8- zgV_D3U(@H9j7d?6x2kb(cy-KkHh6dZ$)J>egi+q|&DV>r&LPKA;@TJ9>$9REL&qV2WW(XaK3Tn3k>LRqK z49^6Xzh0ZP!k+__AR)qv1mcmXgjW&mef32HXZWsB;0{ygP&^(AsDdFu8B!!MLFr%u zO*Gpu!`(nwL6mXLqmPhTWeXkSzMVt?4c4#+88+PQX?B;j*Qi9XRqPaofG=s#tqv3x zI@~L?>ezpapllsw^j>{$udZqau$j&yS{fKL*AJ5Qc6|jKFcHu=fm`k5bpzKV<-m2q zE(*qb_ur<30ReOyz&og62wu7F`h10xqPs5fN-(QP%F}49yPgi(Iepu;yBp+D?$-q6 z*R}5DL#t&xNko5~HZ%}9Y3zE%3AyklNd|@#+qiJeh#<8)9vB?QG z!43EW{1NOBuxyo4YA|-$LZI-eXj0TSCb3u_2DI{G9jW`8`XFlEYS(Jm=!> zpVJW7my7`BoR?i@PHsEYPDD{2)2!eYa-$*88Osuk9Hf^z0mk%~@GB^|RK8?uAv3s( zUgP7F!^1zAwSOEQ{>3yudvMdN?WPaznl=CXrs+wyzyf?N{-J4}Z>*UYcRDiZ);o8u zA2pb@1r*+c@0sT7oeT2t@$y3L&c*$1u5+E+6P*+ZJ~_@asUeR5rVa)S<4B#p=qPt6 zFM7Og2DU(zb&7Pp9>$QbGqK7r5S?WRv$uQ0jX1*p+WD2C{T9ma!-rj{j&Ie6#b>o}Znc7IM|g|mg^L$4NY98Cabl)YA!P;#4iVis zCztszdw8bzF9r*cyUx+`~5-x zpLQ%sv-X`rL3EE5<_zZ4EIZJg#Y%k(IM%c#BXLQJ7TlZ#yb3Y=Ag%`A$YZQU=aj!3 zS0k+`+EtA&Qo5wb=>&(aIptx62<56ziq#m!WMD$0Q3bE-ZWMN#gNmpOo>j*oc8?*P z6PS4eilsCS(PUsVLlNy-PxGrp_SbdWii6+?VU;lc@-_$SOTCFLL~d9q}8aP+q=lDRGK$W?heuHwUHe=Rq> z2#+nXauNwIIpAF~Fb=ktY%m*p4Z4wRL}PLaDW?DcAOJ~3K~%X|F56xss==FOV3OBc z)z}3a*Rha@1O&7k!S-wPa2pz`4D%5dp)mx;%vXwBxl`)gUd)405yLSIqmkSJMMf&{ zOsdy`G=^SqDtkm-L81hZa;BH|5U-_4c^10Y2 zRq+tj){ky;Vg!R%>{|hTQB(skf&ww&75y8wlFYRXwicmT=@wO@wLFHH0?lC&q_yhR zl;9$Kz}UhnBAnIF`-|9>Ui7nCF3P{WB+@Gn81|3A59NpcqZIe!iU8zjd8)h5^VSa4 z%Px%&q`wzLju!AV)E}J5>w*kF#sOZ;9r!^@ENg8rV+S>KBN{PIK~ta-2weQ zB+&Wf*-g{@2ushyzpdS=E!?h|@9n1#?!kt1%`|`hpl05Cmgz{#@#N7x5#YS&{ovcC z*?vO=cq5b95QToxS_4O`@sd1)m*2iQIr-ao-AkkyO!e(&;;{(7Vzz=NFO*xTsx9>l zLbRu`x0Ei|Lk-Jk%hOh_f!wZ>u1nj}Rh>VJZsMb<3HnJI%8& z2Gg7yrxTbT#8?70Is2G+EsGTuQgDan1?I@L;1o8e9LLeP)oZrCeVkL^Nbc&dgAwjU zu~ycV<6JPP4_qf^ay0ii$fQE(<8+*qNU2D5my2qOau-oYqVR}Kh%kn5oh!{~t_Km$ z5ae@;bNm}8@CsQ^c#_kkV@1fZwAhspc?_><$O^I>9UR?X+eo^MMi7m3r3M?(jaA0> zx)6Q?udm&^?XEU%yIBgO-zX|u#b%bZfrHkuTdG>%CSBa0mUn2I!=*tEc5FI>(9y{7 zL5E?uf#9$iC7Z2^;#kgz=-Ry7v<=(H!1CH0HlzAVMBMQ9V)~n9@-KPN$Vi%*vD(m} zV1cb+^km82$jTW=ZZCrfaU0C%egLt+tIR@z5g2iV zXkc^tn;Hn?c8Yf3RCwlzHkeb~x*7noBZ?FTIr}Oq;u}W#5vt$&XiGnV^;h?>I`3=J zFRS4wX22_&&#=-@ACib~z=J#n7=9te8h|w5JCu0@Dh%E}R`wYEa z#-=k=+XFXIK)0T$&AukRi-@dlIYuiw0F&@LK3J9l>@_dLwA32t1|ADLTdhwuA~>+z z+E60i+a*7D2&)n`FxzJ;gA>j)qFm%c%f%={pf_AViZ^opE9z>;A~ZVEPT-=E&Vc5# zn=}r0^OQU?1~qPUx3|07_zT#1`3nYMk?1LB8^{}o2yUKoxADEGtvR_#xs4&l5O+4q z8yPlNVskMdIogqil)#_l2!L2gKS-1XL=+~ZM3%#O^r8X6LVn@M=ZU$`{RRKm6@TBO z#L}a$`}&rWg}&tcNCA3WO!$jS2nb&C`{k6sFw!UDH&+A-dZaLn<*dcwrNt$*p|OnI zrw(0_J&-WiYgP(0IaXE*5>72rilMnhDyX$2M8o$>(uS%#h|mmt&~>jx zjGcj>REw}&4e&8T3z$|fF8WF1KtRLB^D+jwFdi{p0gS6WO-1ZHqatQIc?|nmRwiK{ z_9UXS#_AD;Y8Y0#5%fDlXA&iQOgS9iLVy4MN2!4SdVJ}Zrg>pf>R0%EYYS4)njfaF z%kl3p1HO&6^H4hf&D&^Fzh%}|^Idt`kQ}Ih7rG$87oL5D0{E@3%Cs4mkKdfUIc~|< z;|McEaZ@oQ%iiIzvXw;d8FYaGk*aSjiraeK}dPddFDr`yO-6yMe(wNp3;i=(rxJc zS>7W4-|6&L_TpLd`Rv1z;JXczA1@5*fOPhUe|>*?divwPzx!cpBF=T=!7m;RqLuq> z^i?1fGyx1BIZS7nMowajwTu;I@6${L$gdfx86JmwThIBBJ!`d@Vz@kubD_z%e z9I3j^YJJNFt`y8#?6UeC4aO~Ti<1@^;leeh(4)Gn%yIH;M447t3BzLYG%IU}_G1Px zz+5DPiDve+vLbcmnZ09eJ97hinpN_sRI<~-$W?8XTU~D{Z{^d^a_bRZFTgg1p7=Ck znSw-Z>NI#dj%$J-HnimbzO}Ydpk)M|Wm2k~5aTM%on#FFX9gn2K^WDn6-9!`hD zPdjz_nHVh3G6Wf`&nR@85D5&}1~3{@2TP&6vV6aZ_>FLPlSRJ*eZxm9k%wNTFowEP z=R%B|5DE-?a99);sY-!m+y{TK&&T#Pm>jJE<~Vp7N)EWV@nZ$;8%b8~Dh>^J)|_p; zc0>Fx&>M|X^NRLDS`E8)qH(_23Is-r8A2C7+bM%4E{)L z9NUUFHv~JjBV`jrU1+w@;L2n;aui3Sstprt(tLx2s8Ax2C<3HN^rG5DE~<9Bn1obR zZVK1CnED5Blgr&w%BDT%JinJBHYI>R-Zu$~<@28BIUklB2;o)G6>72*301)_YL$r~5CgM~XZgN($=A_KZ>Wisu@bRlI>Z!S-F z=d4*ob+iSVuR@!Zq7M3THWL5M!}u zXLHy&(Eu?yayK9h_}vgJ(qRL@<7aIYwzD`OgckU{bLY;V7D|g#qvsRnKN@}GL1J$q zyhu1Sb{mpHX!mg`dC(2wC4J9Ib?;eo6l7rsBQN2m(B6!^@{vi2j1G%6BcHD`_ewLc z*mOkrEn&kuW$+hsY1Sh(bQHa4dMl>bkTkWt@4mRP@%HBTCl$2d|ES=PuHe*$KX(^U;9vyRe31cYfV!p)#+E z17XKZOK;j%N8w9uX<(NArQHyKP5vOzjcsjVr%nG;-JAmVZ_V!aWyJz$^khO~rzdN= z%*LpmWxzt25lB)`OroMfjZ2C8{%6}=Kp>Jem>TH=RYB<>mVS)(_2FHXnk#lNcwMT1 zhAS9;Bl(991pFO0g86aN5s>FxbRN0TUI)yTujcOfE6`sF3On40r^No(|1cnrbG7WK zIN2SH^4|y8{yG@7ffccE-~g4;LWTVhaA6*edP4Yv18WZS5khB$j$m{k<%AsrmWw%9 zgz-^<@5qfLN}<372%X&wqcnk(gs>@%70|4Jcn+?J zvFhDRPJl9(IZG}SqQZFx(Q-M;6b^Y1$yaFZEfxk~z{x+$5d(;$kM1F!1F=_#h>j-* z0|Z9L2Ojy@OL9}397%d;79Jpd1CwUtad?o3b;84$G|&~R-x0chkDh{$DT-WY_8n24 z<%ynx1WRt*M9R;r(?wA0mjdt-R0&Imj1cIUcxaa%}m_+Snj-;Chx)j46o zCs4+=TrTGZAunnH?u?UIvhnQWHT0?mSS=PJ?vGP=3=b?U< zD}%n=?bC|X4>KpTiXE`-dEw?|p)YF{sHM^suw6|^VHF^{bnK~?6S4@2TV4S>(@lsx zECO&zbE27)brQ`8hlhtRUi>q=_mAhtBK2RL+gw@OB%aRr`L>kWzUmOy5aVG-ICGX_} zF!-{Kp`*#(Lj%n z+biDp)7LIc@9tihzIHmjs^jU8>@;YTh9y{>zAaaYS*x20b=kvUwK2GXtuE6<;9C}| zD+;qdAgKGPMvh~4q>;_lL0 z0Q{B=ntzV`=2CTfi?lOQfA#Y9>;Jq&5@p@+S^`x1%`iA^Ym*q+7#*T z&?cO=%|BxawJFtOV6*6Spn2HDEi+jIwqdxBG)R(Ay~DGqG>)l-x6Y(z`i^6EQnSvR z3CiE=)LXNs({_qv-INb=_N<;|ghfIw1$^D&tawMWI4rd_jRNMnJP>L0EAUrEFF+D+nwY-EML$mqOuh zwmq9o(H4BK3tBOUvS8+3&9&#U?XV^9YzLXp5FANi0c2!C&t_(`;pyhSXlnsLe_eiqAm#cZU1kdP1dWI30y*}ADNOYfx znBn<3vUBE8_QLs@&z_i(v*EpHE`t1-GieQmjvRYx2SP^{)OQ5>3-d7Qj(~M~4%|q9 z!vs%9w23)}ix*BQpHd@DbFSlC1IM-^e>@o>jAhWc5c=()nOTr6Tvx=gL zwGH}{OxRUKJCaNcCEZ61;jkkr8x&;O;T=MrX`*dF1-wYzPfyt3s&HS>9$ZeL>srub@6O-JPKQ;qS)lwrONH6c-)g(sG6m+*Aw zJ+lCQ8-fi0A7A-+`-1Q}LR5PH)sH{E+Fh?}E>%pow>HqENe^qbidaB$UA4&c0l_OP zxK&%1Gqk)wT}E{??^VIEf-AmaOsOUJsqC&#*BLumJFVbNhb<=1HPsaFB$Q&W$7*k) zu&ASg|47wZ$dSH6a}c2K3e3kb=1F3AOs|tlrxPkVGnW7fg?9N?-*d-{A2tTsk%nvBDxOx^gE(|#1B8S17rWX@vOq?Hb-3#){ zN(F~JiDXKjlZ6U?u*5tHdkRPG}ghwiXq7o zM82f@G|{2beGyC%!9Iifi9N2`%)L zSsY-w&_q`NtK`1e_CofYTq`q}vY11QaD0u{wgcS|>=frgFbW)LtVhBSo45J)acFH#s=FUm+M zbo65T6ZZG){GRhFO~+;@w)N_@6ch74dd_)1jM|oF+zXtJmr8d_pfhla7K^*I>qX#P zpgze}TL_>}ox43lnQwem%4g8}oUz^X=~YdbAD^2!xrzY^JMg*N@xNg$CeK5iz(#y= zEs?4PLq5TaDN7sbhHc zrt~X-^rnW-QbUi`$DoFE_9n;{7fA9 zhhH{7`(sew@Y^?bcO!Ho^#@%3ly6Tko8#l1t@`nfY@(xYFfNdM6)k=P^RjmuuV@cEDFF^rpb5W{tW0cpOFQ5d<#4P#oIbJt|K6}69i5l-slq<< z`cK}!u7&EPg~%yw;H$-+qdq_&>%I`Svawk7tVr#4&j{{{6I9lg_btKpHBvdK5UPkP zRy@rj@A+7sf5ozuP^vtrR&hQn!>*SmYy{pU7jWgNMesDrMN!W{n0=j-+&SdYT0!^* zXsBT4iwv7D%G|4gdc_#FdxiBGkYzS~-4OVULM~ON=q@v_bX)w_Xew9O=~+YG*=cnOLS=<6GzEj;@MscBne-k)LGUp&n7MOx zs@*;g?@2rOBxtNDv(iib|9;k9q8Zxm5f~kz zSvq5^7h5puW@gWk$Tah1LMNfgY=b$<-5{{tzauP;BE8B)VyLoWk)6n}md$3EFe6Th z4YNqFm_nD013X~7%$2E}J%}CD9`s_p8$@xi4=$5PNlWm-je}b3Mr>HG*IpujHbz{Z zGpxPUD;qH;j058lo}?uJnThi)9kkn2FBoPS7{4&^?f2+kSi_Y>{8j&EhaD@*Vz6%M zrWY{GjlDX-ok0X+s7vA1`giSB8*tD}=s6rgJO{UK+ItXCsmfpA^aZ2oF)1JY@i@?T zfx3O>((4_u<35$YeYzU7h+gW*FpMHw|KL9F>;1#e2TjeF#a7jK)ZJ`CZ#T8URgJHz z2XlcliBYu+vYPY~8u|@#j<|}?63ntsc6%{1Y0d+dH@i(Oh&MUNw7QuXcm`KDXIR{9 zzWHYJgO9(2(msv-{q65XpXRzBU%Cwc+TDHI7;xt4cX#*4TZ6Uz-AkYSVt@BXUw(gg z_sVnPpPK|_8nk}RP#G7J>zwUSLb~XnrNQtfF$e-Tn%}H>gH>;k9lbJXX!ypdZ7q zt--4l$^r4wiptUw`041%w*s)f1;B5-^X}1aBpjAP$*}Dsst8qe%j(wa{Jd(Y7$B<8 ze2c#FWPs}kEJINd2wY@jT=6*MqI2Fe3aP@a8w{`^*Twvqz&zwNN^bwXxTs_+gG`ty zxmwqX6_-P46kHJk+N%W~IwyWw(KbS5jk6WG)S>Z zhEasUn-_(-DuK{XUQ|mHLTXRkWMFO2b#YORgwmQ7y_Kox6%U@<@!26ZB*VpNbX8)n zQ6)Qv_NKN|+jfmj&W2KOTQ$%nqsLQz-fYxaFd30v4Vy~Bgvqp;-ixTZA(~8)X*Jc} zHt4k{*`5w_iak_{cn+qR45yPws!`d7lY0iSc8PBr*5W=gSj8MXB?WZSo=ey}EjRFJ zG33-bPSc2_?j!Of)2A^e#Z|+wdOGg9X%JdM>9m&u8`o7zbes*a zU^#tq^|ni(XHMF^>H|(rDTf7FJlgjshOG=RBIw?yMSqV&(LIA&17N1o2EUBfxG|!AOJ~3K~(csbTmXk;8`vLPF|;s5 zwEgAuNX$OgGud7?wv!=|K0_%(t)8vvx>W;gjVahwYS=43xKZxaWU8#!UvNUbW8?w- zbL~a;!0@$}si_0FhvKSUo9j@-&^O2>4GSyM3lcYKR3gy@Y($tG=(#1D8Tur0^yj23 zM(O0iSW93a%oNP+dr)M*g9muc6DG$;K?wAC{b+)~fd<+|SNbvlUqemt<8iP-Ce@?w zoO;P{dTxvXxF4vX-7u_1L?vXZED-|CViny)W7lU^R3N|@b#e-+v6s&M(_;Ri*;}RH}=qe{`Q(4i9&>~Gb0C9%YInA#Hz7#qLvKdS#lrJsS zw4N@(q&U&tI`jUg^LA|hi@*Hos24uAlPMnrENkTl)F#?(eVNdvACD zorl1zFLrY|&$|*O7QE&LiD2R!n3S56KEg>5rDn_q%q*(?5GT5XIw)w^@=AvD?aTkO z4;Th~@8P_=iUg(?E;#I7ohYnc38XJL6uUg@)x;VMzJFMc4V8M8HJ%&E4$=D8={tH! zC`WncAe%YJ8a&%Cayb;Mmm?W_p-FL){n`)zTG5LM3942G!S*+hUu}5?2WDTTL+hNb z9KcO)FC6Hb9#*gX*Zlc471ovCy?gk9CaVxe&xpLnfcQQQz1LN$>j}>K;*3>_x5_eB>w=n zHRbccnA!6+4Er2veI%Y2Vi(0gwUe%B&5QZi;P)+$rwoMEp5t6(TD*}D#?XP{S%rp+ z`XQCAb$wCsAF4?zvMA3N1N=8E&My{&$dLR7<%AkeJBcpp**A;h3Lt4PZbzFtD4;lt{4FkGB9n8mV0 z0}|@#Xo$4R=_o?0J@i$Ey6q_@(GccQDh%qj(Os!$kPR{O>vpnAoEE9iVNkgJM2lVD z{^B|sJqZ(lH5x5E0eBb0YGJ~SU&a zt?>o@q?24Lq`#-35D31BKSqd^R^gF~8lb#sC3loSUAybCiWz|L`|l%wy=%xmJp zF{jzvZamn|*Y?#9oPqYr%O+c}52Ry;!Xm!psObFHy=?V=xc{g7 z?`MDc>rXab{_4};eY)1~D+sf%r=SSQtw*|a5P*0tKgov{0d5f+-SS=rPmNadLhGP) zM~6cKN8UNG@#2lm)Xzm&pJ@{P@!8c!A$@Yo@idH|pRT$ecq^nttFU3~ozb&*2Sb^A z-z0{&wOS^j6Gvmb>itbz+oyRrG*~tiJ|UbVbG1G_UuVPj{_x3*KYDGT&v|=3eD=Ar zcLE|?s))~hxuc9`&5gZK5Y)jH3)U5b&=_#;O*X}2ue|Stu#Fw?*Jvyg>IW1SxyZ@* zEVmUs!+FP}o$bL#p%1v{_(#D)Z<4tI2&+EHXVBw{i=F+k^8Y%X%U9$z#2TO%d;czq z+RIxsX;s3y%h(vMTahVPJ7d)khDEd&F(`QBNd1L!6BiX;>6+vQ1J_3A5Mt16kG1%UEdbI?yp!DqQ6k(LirEwx< zVv(2~J#92MqlD;bO`T^j8BxO!(-QblWk{Jr2G!Gc={A!&v0Ff4R={tOfl`WexJD!p z&frXz1dhbXwLvjO=902djbz_xs#q$mXTL7h}eaw$V1R=wuZD=>GEJGV>Bc|qYpTZM#Jk9<(9Hoy*D zf&xp2S}$UF(YZ7Fo^{$2P;Rq0?gR`5ll;Ow5bsrMnxNoO_L4ZFpN)*(ek=M{sM_t46v z;1!-zf;6*f!71h>6$g7UaOe`A6dAVotFOL8Y{mweOG3=Oz5b+-SO-FlNw#8f%hZ~w z^2Szgr@#64AO6NbPL8SY4d96WuRwJwS-&FcO7yktw|eUAno+{;h#^s zYu9uP*0O7{#I=2D6T_21BEv}~(O8^#qUSFsVn%(}aO+{F%MQw!a`(-b9zNN3#8m^s zhNjSlur03!rX|=F&`&)4%9{(7)?qw&_3Ootf2MxEgW!9=y??c-P$$`KckZk;4<la_Db~Ci(rU&GW}@XPdj7KxBxkwutgSW_&cR>`bDx97eJKjI3%S=GcgGa>&y|FWPz<5O> zX-~?s7xwMdH*0*A?z7>I#HN@s)Ap;H-|1OnH`EIXhall=su+i^C}^nmoX^{{e3lm zJdYdL;CJe7H|&mK1J~#)abJQb4RE(La3&}VTs5eDwca%Hd#onHrl1(`-QHH&VD-2` z7>D-04N8%WE>n7RjNjKizl}y!j$kscO0xbE$-xL);%9Wy)kj2KH9htD(IR+_Gl?be zCH=sRnjyQ3ZuD(XFIe*3uZoZsQA0PAiH9~l2`1_k4dtJ3~M^fqn-K^0d1cO)hkuWxJR+O=UVNNez`OpYNv448wp@ik;M?mOsy*Od~QV&Fk{ zaBA?X5~Q5_j_TdET{>lwEAcaKquuB2zrci*hye?&ce;3hI`#7$WxQ=juqqk6aiJZy zyg`K3_6c<0xITeKXQg?x!!cUt5Eb2#s#-8C!B*Qx&Gp^0&^|1&7TaGJI?EB2JI4yu z(cGDr-quf@sd?_jU;A^Oc16x4<7A;JQ)0CqEveEszx1Q$V1bovgY$cRSTM3@0zATa zde2o_a{qF%52YoRk}>nrM8?(kOlkXP`kq|b^7ca=4EGgnUJ~%aq$T>AW09+3rF`JG zLRZ7dji>K9c>2CMWL`~F&IhgVFNzT7h17OX{vfY<1@|ZQLmbC{m%(#=O`+W+;_!n1SY(9076*FhnyP=a|YwJUR`Mtn{!$f-3wOLy(l@=hc?p)PwJ>7I+1-MzE&OayhMQVDZu zLOyt=_mvF!pcnSCnky^j8LH`kC#;)ndfChx3Li;=jTCvs4amL9L&_MAG#VB{j*skg zBIvZk4%_WVa9c95Jd5KY{oUNshQcxXnH1!lXqL(hh(gMR(|R}O39I;UiKL#&9k$wU(f$UF)aL<#jyI? zM+WJJuOw7PkYwTX4Y`w`FnQDa)EpU`M&P3cLXlre2WbNae96HY85g$uwn1L@x2f&* zYRW*ESPra81ar{O5Jm00E$&OqBr0dzzw7i4mX4z?wK}fi@HK3O)HWL1)yDcG<#Lo7 zGW%9FpKdn(bqppOv#qM?*R|4(V=1tz3V}{GRK0*LSb-Zn-2QGh;w6GP1g9WzvLWqr zfvI)D=&_-4y0l1%q2|ek%gmDv%`ptqXlPhVQ$m5pq(wtx5Z%b`V%(0#YXlqWa;;_1m=!S1 zh3R{<^HZEJjp)h(WFtmzNB+i7$M&aR8z_es2I4tpp~5o#PLs}o`k5An$ZItqfxQ2r z>-=8Zyw4~e*^j=O&#g53CuUm zWg(OVloDD)p*Ld}yBK8`y$B4NoAh7U-?Qg)p0C`lY{79}N$;x&qWI{X=Q-zOvKgga zWjF?N?bBXP6%53190V!!#iYnmr0jvN`fN zgJ64+3H02)s3Qy%7m@jGStM41borpOsI9C6w;#RL5SQ8Tfz)YNsog^ymah&D99l(` z4?13`q_MBopbuu-&|%4 zY1hJ1A-9OG%g{#k%49_kU34bq89lmusP^A-s079^>xL!c(TC;Gkt8dv$n~%Lzx?CJ zKkq^c4EVDT9&Cmhqz6uRZ*=A#73Yw7b^E8^UAH#sJoro=-zgY78Kc^?;?kIGXnWhj zepzl9=SH~(fgI!9Lu-`(E z-u=4&(a+3BKZ%CE^^4zq^CxlDJ1Q464!9wG)xEusy_(lmTFJnJunHxi+7MRO9)p_q zLz&=*=*Ge^=afA4sY|pzVRoZ%RnqROu)0k6)d1mFOxIVB!|oIG+m&JEc7$aqY1gNJ zP+6dV9B{`jm(n8aHA}AqnE>f&@I!Ik`l+VNWMzoRf9Nvwsdphld|kDEMUofZU{AWD zgJHcI_MbK6t-8>z?96)@l04y39}+h1fx_$6e?9*urerP~%^e*@ne2S_THMAE(0K1x ztU4Pu=G6d8@ev7G>_Q_)Qf*WeGfFZ2CH)zB5|(@(sry$P*ekb&T3D)!(^gQYm5+tr=-Gl|CRHD(q>h5hjw)XU zvl62A>J@bMJ~c@7RlA@Dxn1MY`*ttsmJZenTESWcdzY5}W`Jy@cnuP~w05gV_(m#~ zrCjowK|+3(LOQ2f;G;YNltofp=9B@=9+u}`G1tgngS=U#QYsvpS+G{4Gsw;=L;4;- zwgZO2IoNNB04#DS?ar1#^%TZ?l4Jj~p?NTLxUqba8|N|v6HEs9_ZNY2y+v(teEp_X*VT zNwPgM0=&PU;QSd~?#tIhE;PMEc9t(mB~${Fk|FaETUEWiSp=4sFo43oe$|^ff_oQX zKg-TfNS*9CKX&oiZA{cFcn}A8dtrZjPxfF?wI_PKqP8RzAzl(wN&g^hm}xW&d3*o! z?d|8^sp06r!STTBfE9eT=o`zOnSAWISiWQ>@MUMJeBd1o%8FKuM_|a|ydg#l}-B*_=t@$Khhq-t1hdAO@0U{xk{f_=&8Vmahb%G4y6Qs?-Kv;Qwa8vx&a z@cUUK;iCsLybVCS>5 z3{{>4WPj1T_1`UoAq!f6{^d9Cz5GOiv3C?OMapu+ri5N5W6JHCrVzu!i+ zs!^#MiafkI*o6k`feNEri#mHy#rnS=gM=IIz(rYpQFZr^^j`SnJvH5X)zLj+Gk|%A z4+tJ+Rh8#fKF(wXyY zeT?wj%0RK-SCfO6BJz5~g;kX_&@3EI?KMt%20Q+%0WfPb{BT7`F4~XBl-iNzQ^k4E z*T^i6;1qF^*&|3$impPIvs8@a1;D7#E>jynDiW47$960!&_!i;6u+mDkZ5Pg%#mu6 zqI7h0{zFvke}yg$s!|$!mWs5|1?cws(NV-!^LfOsv*y2%ap07JEkV%qGi=!j>1fM< zmvBnOZuFf4_X8Za`?!Jo&32?rtTUsq2-9r^QP%CK+cb1F`U`13Go)?4d&jCYi_hIH zz_;60+3!xjyR)Uu=bbjnGPrBx8N*R~NAqHMuHE;#V&9nugT(M!)aiDuQt0A7vOk#p zLTlm3^@5?W!8S(WrJ9S=g=aejT93X2d<&I&8$%MVU;2e>N|US$cvTO4r83}}w-YXr z$pKA9l%{2H;c9hZO{IlPS654`#(-7jFzZEHyU((;kzvka3CpPPeZyq!Vy&(%tX*B* zN=4WFGe+4|_8Q$op=jsDe3aLoRg{(cH!}ym($2uRHw0f%voJqb%2JKA{Cx&{FKN)2 zknGKpL4O`oz_4ui%%1ad7WB<1A1hay*mqVwa~TC-=_VWs_K3(!C`Cgmh_|vD^SuQ*u6l)P(w>c;QhVe zI1054FJ~P|KL&AV4_d%0by=6V!D%0Nlc!`|sB_rv18BD|_Af68ou+!&gR+RDPJm)O z%6??8MDbWJzdH_t-f{p{ANu;_)(~>|RxQEWe@3Jx=2=MDc`Hv+Sy5Rc%U;i5nE6&N zrP)|GD9~jUBQ1JkaCuf)2*q85tLnxO4cgf5T`ggib-}Sq$3t~J9Lv#b_YV(w8Rfgj zWl?2`#^p|+#g5jjQwf1Rf`S-_zk8l0?x1T+fX;-cFcV2z+!3PfoA+ScT=ko}T^$%a%+t_e* zHMH2P#Qt%}it?skO=hcd3vFz;Mk^bxPjxp0si)q?8y1r9aMFfjwYH^Ru!*cQ@HbVp z!==TqfVA4O(n}kNT!+vr=btVZtNiGN01ZI$zZR(0g|EI4%}iO@8ZIXDxB{YC{C=^) z5doLg+25i92cA`Ww~kNc)e1)7LCDF{iT2#5)l=D7zd5;IE<|umPw0c!JX@cAsSnrW3fYP3S%z-ZR*5imoF%fcw$b zS!C?CXh>_n?TTjFU^jhc=Rt$dFbA_69id7iK=Z3f=tkR6x!!!&XZ;yRaI@Ln>bAEK zthe5g!O><0T(7C0VQU92t1u2@!QFO+1+4ncYbt`(o1_Xtn6H6vty?=&VDz(KOY*g6 z>W^ymT8P4`Jo7-TTBZAGjh?}p(j~h@Lo@EJv6{7Dhzq5~l4NilS_fB^7+r9Ixj^{U z5;qI@kSZ)tGd!*oIBk_FuXegt3s+oA@CMTJ)xz4+eZ$+@>QW8sk#XTKjVc#bD_5*Z zGaX)fZ*A2MZ)w?%Phj>>Jb!dPe?1>%^5VdG*0PMrG7&B+tYsM*yqrOtz9t<@fs{v5 zmI6Bk`~iDj@8?50P3s64`|Gbw5;=MM{XFjV4OPra<<)l07 zI}m1j7l1oycUk>~44@(B@+=_%TTo4~6x+LpAIr2mCybSS2!RxoI9Psh3wanc2s`(T zj4VvP$e`7L#9sKSWYjVs^?M{`zq^%~V+(5)3au25evOQMdn^*I$_E_87?QQ79UgW$ zwX37S=&J&K(AR!}%vY5X;w8n@7{gqJvcvvO@skGFBE!RO1Qy(0<$FKiY|v^?1i-GW zT@fg)&CS{~u7x=@O!2#KzyI4`=RAv&KH#4#WBA?S{z;{B#~TP$2W&ulV-{$=5p-5} zE>^$@q3_(e7*SV3d&3O_VD)7l)ksdQu0wTGOGiW1BbF(pqf%}2Xpj`R6gsTU;CQ$9 zr9-7eDqZ`_bO2KgmoE}2*PQ#h4qC}q0dC2jT#-bpGOJ5FTshym^j{&A|AED*px-Ua z3=4jJ|MJz#zn@=|CrIH>(hVCaez*L_pH4nJKNlG`*ed_Z6SC;+D;|sRs&C;KpAzoc zvdpngCyA_Pr>&L%03ZNKL_t&}@Ty$2N2wh_B=l{JK4oo|RbNljkeir-yJx!SCLh00 z6H-XE6y6?`wTYFdN!><{&?@MKlb6RO&lbGPXQf9U^9=8FTrTaEMTB!4i{fvn2HCrl zoFo4q0k3lG#Fprm?nTjxZZIaQoHlv{hbtiCY?Pae8M_a~_HJ66^ zGJlS14V-Hjy2iJ1hNt%6srVM!W*opqf*pY8XN)1c3c6(scx!?lq)Gh0#>QICJQk zt>+A+CqdCI$*yLM@y<*(W~K~bCqvb*A~+h_-okYW%$ij9!YP@QyMO|aD+ z=?&}+DEhgeVRS}K!8m-;HfM|@%c8{R<$=A7gwbOKqrJv@_by*2gM(140phbrxg5cb zG-e-6qAy`bOS3ybRCSijY21-cMxQc1(bQQv;fcYRN(!?{FHO=Un%HO60E-!O&G0sg z^OyZE$yl-U;3}w_NTP&Bf;FUkjv>mBh^0)>35*G8oyOpV1Xx5sKUrr}HiTO;LHl3| z!n>)0q*{u~g~zqKrEP=Q)WRmCX$haVrGjS9i~09%bvti&JgL_1;RCKJn{w%%K`#|Z z%S#esEm!FuM1zGmnyz0~y~~(=>UE@8H<4!LIk>P}$NkfM?33cUS{Z=i;5Q0Jq^4gF zZAdPLZtf`j>ZTuRI)C=k1)c80XsN8wcf4vEUcCC}n#z^zQ74l>;{$&4 z7mx1WzH(*O(e%!RzesgRO5C^;oWIK4xX9>mF?0}NUAaD6t zV$hBZB5<%*H_6Z2#)sE=$7!#3`?rB^tF-XR!Q9HQ%dOUgyGrA5?3Lu%?Z7Ky$#%5j z0%*J9!B~dFi|3>NFA3|9V~?)Ap$v?6=i8SrUi|pt)ys2%uaVPhpMC!Mm&QIf-a7fi z7d!T5djFi(-cI>IW8gLmQsa0N1p>KOyG+NybZErmcfbWnzu5e8!s~%!yWct7m5^$83%Y8?k zVsTo0yckkLNcRY?q>W609Z1l`d zh_lz_UP)xXW@W68)vVObcI#{A&8oOFs7t+pu6<7N z70Q5TrcRCbZqa|#knGA38f2Ym5&oQM5WQj8+aQ-ipiBY7gpw+mM6)0^fNc*?(inRWebiA>?HeW9=_9aO^38lq`JN@UrBk zT{@v?N>tDkFrbG9atDA660wak!oOW{oVpO(0AWos4p!o)5?$+$nLTPM*U2{V_x#&ywa!Cc);QM zF1Eh>G!8(k;h_B&AwIPX3!=(G&B5Yra8bKQfKeH#S$Y5k-nAi^*1&3X} z#rcvnv;LK?icG71NvXm>c`@W!YSC*atoS}ylV$WJAKVs<9glzW^2HB7*x$^nf7~_@Jnn3i_Z!dqa$gzNoSa{~Ul@y3@1Jz! zwf!cnUdtgT*^u#|cRLv+HO^|rusu=HKeH9gG?x$NWa z@q_8kbo*G@*u?|=v;$1W{`-^Wxl{DmFLzx5#l`6$I~(8d<+c4WH-62`eEhQqhpDj7 zi$$nfC&D=yNuNdN0;Yrz0dy>fB#SMt4rC)fVW#lN4#m1rg+_O|ktQv=YljS)lY}?q zlC&X3Wk|xt6g4b8%jS}VZ;<>!q;xcU7S~`pr;scek=$Pt&viq^!UwS6RyI4il|@xW zyDuqNA$KF*inKnMoD6}`x##hD#XwJqgeH+MosabV9~odoJ#7unATzgBk{DS(q`LJtg#+v2|~LYX(l+0HH@4 zghQ(-X+q22`H5bmNBAT;Sy}~S?{yg*r!xzE(&Az1P?RDe)}$uj6I~M zVa#)(QD2RWj9sRi(C+kXtV{O(Y<0CO{EeO&4^G5Xm6cQa##6k$XGw=y9ObcOH<5^8 zI${Bw289i8huHYShZBQZ_Qs^MB8U=g3Drmm1Jm`P!Oe6G5p;S`*&8Jl7TO(9Qhk%e2d;eZoEd{f;R452vSn6O*~l8aomP}=M+YfF05_D|T=*v76~deQs=dw(jwU9Sx$EAzU;M2{vFtCN=elzc=5`P$_l0bUU_xr zarM%V44;G3rCb*l!Obw7V<9!{%6DR z-bkL+3>L|k5n4N!H?n`GBWwTuyaxuNlaJqD@z@w}2&Q6(%m_JG zsxu>JxLjD2PR8qv23K%o8{y zr=38j;{;DCpd)QBk&g2X#FzBS(7y3&$_LXS7Q@ldL^LetZx!F~1k8CN)SqC+9G!4y z@Wgx=*)!Eh2CZ})83OlFUEvD`kNbTDSV*zvtAtUKg0+Dun1OS@c0UR~-cT}Db-5ok z(5|S6S2o)JBDis{I`w(mKc#neFgc#{I!| z&$J=*@%S`0q+y2hFoP0nyf`*vRQToL@i@em8ir$4Hh9^Bk~*Zx%4CX0bd5;ct#6F| zdCYKlTAHls9A8R*8BT`dUR$}XgzzwH-=zIgBiV3dJ0kgWG8Bu;^oz{d z@HZR)FskSX1q^Y<&UQggCGxCfq$~yu*h+PkQ}U!eCt*xjQMg!>NTSR=H4?nHhc#oD zfZTy`fZc)7;Kbm(+#Xa=VI>e-RT4&dsg^MiK2Pk@;s)%VbG@=vSwQBD>=d)o(gASX z-Ws$!?Mi#nSTkSR2Y_<>hV-+>!ghUAp^t73 zA{ArFBQrcpQi3b!D$JL??dIn9lc6_*DYLWRrNh7!%=seUeno{_NS_(C~b~Q7DX-$w@O6I70uR^!3J@AyzjU};4 z1-M#Qz@Z3#r5n*LgLYSQi2XW88uAN+ec>hWKlX zos-kOm#!_JkR|m21o&(F_>R}!*^vnAk3ZH%_^V3~PcL3_`>*retCD2BjwnmwXCznn ze%IGuv;YU}_;nRC7(zEsD_PWpZG1DhBPjy(($c61?KtX_#_r;K2Ec!RP3-nh?aZT3V!6kq>yNLM9u+&EJ^HlaG}C(t3$)x9eEch668RPe zqQ)HGXLMM$5+j}SZ3=gnz+_2Wd1X9MNz+&y2W8zFXgWZseM6e0xj2D*~PREj22GO~M zVKy$LY(g2)IniW1kAz?)61%%)cE1C=JHdKvVCcFK+-rzij+OTYPZx|!wC!9`J_oui znt=^h6LSBu1tx$aSJ|s<4GtE_elAZQVMDTSDM2zYo_v4upnb43S*a`?5p;zf8W|R9 zEF-+`2JT?)L3*_&V=!!(m<#)I1E^b@6d~;#Vntf=#qOrEHx4%sUxY#bSCMt+&Kg0_ zhM5m>7WSMFS}Z zB6l8sxKmGkj=+j7ZZ{}gFx>4bVzMhHECfz@R)-*Xsv9VryUMZhy)YB#I-A~<53k*h z1YQT#!QE7=?oSepMoJBOY69;4!KqRBhN3r!vQ#REop(T6HpMLsx?7&|A&A~dc?3sG zW?|#Hidj@ku)?vNChvH7$CRYaf@UeRK8*7h}pPY>U<+JHWEK~pS z-Scn0f#^M7aRJvw^anfOTfzJ}uptR$J#XXcdcbuxk$ypXMWCNzxzW1owNrvp z7jg^d_BY|~xf+nN3zUuQouB90jDYO>cG&H2f~U-?!H_+J-7rkhWH zlZ)l|UYolxN__I>@5Z7h*St3=@b!)`j@m$Bpt!8=P{D&CWUnCUvlg|D-rOje%H6vS zx8)YJHZ2MD3XLGe66MsKQPOt^;Aounlr;(U?lprrX2|nmY3^?gPp^VIFM3V!XpM_+ zse~HZZA-|t8YO40i+ZrMSp-)X=6V`T7kX#@n9|*naQ+PElWU^oXfm>^{-i~1whKO5 zC+rJ(wPQ6UNqDmmR6n_WShk~~AU2d_ek_>{`sQ>zf~G3T5!aCOSvY3Y#~?DEcEb_< zgrY*BkOv|mZ$<(QBI6^9(_EOM_n%Lg=y>KY(Dl9C)R1`+(O0uUL z=-PQ>n^m#l?S6VAB$d^~ee_pR!EY5*O)rDSBDj6FzUZ_1^Aos!qw4%cd}W`tYP6=U zZ@+46nVm57wpKO3oTmi%UKOQP)yQ$JY5;3jxPitap{`*vGOX(A7qjBPO2Q)hnf%F` zBv_JNJz**ugKv);{Ih@Xm{N~kv z#H9In{8+gi^ft`Q7$DD}!J>!|J1|il(=(ZuGnedF!5AdHKQjIz$RqDL;!9s|1m+Gh zHgF+9h?!D*I!88UUy)&D0b_-6#3Q+QGLeYvDib0^1q5^4 zDgTGBvwLmpFvECd*{VK_s3asBNp)f!xsty`1Wx0~k}NPQGo!7+>(ItP^1Px2wX-Kk zE=F$*hG1eyO-KTU_M+^fg^;zdL0Ch3wSQq(8@t*?p<@@@AF%iLyvHdkqawDCr6Z*U zMbCNO_xV5|osZT$hJ*g{Tmq=I$L~F@<%c!;ViMjA9E^HFzLu}mM!8Pm zwt9>ZIE&@FL70axg+eW7zV1`RR&zs%z>kDAV+=Uz8hH!-2;ctKG+_{%4P`-f5nS@m?FKZNwAYrhJ zNOCHJe4T6#I~e8jBfAh~W<3mYg~wfzHB_wNIah|NgpA0Q6sB&FedVbf;4tM-SG{r3 zRay&Yt3Uq#<7Xvdz4x=@H>HT`{Qc{1{uMIdf4{~od2loLli2kiCC@wO=dW~+f0{l$ z{#+8Hf!lAYtVX+DW7K)YyM2Yi<+3*)RJC?>KaT1gKw*&DdzLz3!=MV1lmjh?@kLpJ z54#mb?PKowyX=VPRa>amgiw;)oe$%ntNyI{MF{=CfUr|tROz86=JVuX%4~(C+V1;6 z>)9bx0xmcNM!vR0IAb8U^&}I7@o#z9|U)(tu zk%_Rcu2=gsjZorh?3PXi*1J&>IHF3vV(o{kmm&sc$ckc!PLaOgwZWN8+><#X1bJlk zwJwgJn#Q4$jzo7L)?{cgM2;ArdIT9xPq+5dkESxz0#Bt|)C$smWaM@_jyl>%Fbzlh zuw_iXnN~V#=d>~pk!S5mYz6R6d-5{|Bx10LnpEQ;9fSlvYgJ4gu)%TIy+8&u8CgDU zX1$Aw3OzJDc*(v4yK9V@(PN>5Mk|f_iruhrT;s)+HFz)`O1j29i$p| ztV-aD>!#WJ8VpzLzT(_!jK{PHE<$nbt}Ce+MGckI8m6WD)Em)2nED+XV1~~)c2n$& zRW3-PGeOTh0P~GKK$exgl9fj(>^{;#3V$yVSJ&+&F#iI{3cE^q0HpzLEOk43+fX<4 z07RBF>xCV%$};v2VV$2$Dk}}2@6^;z61y6c=SPw}N0~8CF?N;&%N{{@a{@DPo?4_NEI3LDgMqQSfWck_p+iav;l(v9N~3`u?R4y8>|+{;ok&$ zAvSk?KuxA|QwbcG9d9*u_S`KkmBDIQFOFY*6SKXx_XMBsoyN02wI+)n?R~L#`Z7-7 zzi9+*x36CgZAh4?M%o-sMJs>%*YmHv}FH4VwEw-rm~wo*xF|C%TObjbk!HbO55%h0g|M{IoINYG~R{^jX@ITJ9+w8Tx)4a*efC%WPgdo-RG8;_@j=WYwAfr3#TC!GF=nSKUlyhu02Wfz|Fi3aFMX zsqBl~Zugaeq*!tgDV@@lV|NGT<+6xw`EKZCLK?lSUIy*OLx7i`*bsHOQ&x$Rva#$n z-th)uEr0DMpr=Im0}a&eq|Z)IgQ#~0LSZ1n55J73C8UAAg0PBob}w*rYCowU$%sp_ zcJ?#c4BKN&BO|D?B4G2>&eWIM50i_Jc-ft*uLt&Ia zFAL(e)l{QWL@W&+d-LFGC8gv^Sn%4a9jr+gjp_Q;iJO>lR)c4w!6hlMN~M^1 zFDV?zq_31-x}LfoE4>g&M_Sj{98NxB&V zG|>4Os!)yeV)-2^4(pzMX7!B}lcvIgE-5A|0U`5WOV+U-Zm!&2)mR2s*SM5u4?)mh0=!>G9Uq zmLT?ELtJ=cqp)(Yeke+OxJ5Ogfv@7U)(@yf?IdOi&S_@Do|s*sN6StVq?-{HTvZoPPL zbQZP%hlmJ{Mpq4vQ`CMLd?*0&glTns_Y5W%&`^ z4d>bK0pJ&3&mRBAhsVZ%zqtV5x1^|gZ9V(>d60T`cK&X)dX!o}I(~MuJRb_Gs#OHP z{HaP2tWZb|mOa0s>PuZ#tjhqk_xU=r?1n|dqSDI(Fnd1;(J z zEH69ia!qo#%cEfuhvv_A%~0llM^zNgo(+=+fVjQPHBs$>&$;jV`umIHQ)4ml89czk z(I}#*s7P-7k$>jK_p$Gyg#PoC+6RsE7`Q428mAIa96=Ae5BB0A&P=sPmL^FfqSdit zqgBK}j3I+eDuUC5O{)Jlq6P1CdIwh$!5f5RrRh7A9ceF(5h=q?*m!TI^>A7ktHR&u zSC@?GKAe`xeppg0$5^1&j{FmJm~+VDp)!24R5iGeg3~~9nJvnuaUL$}IFqR2eVrUP*I0(R!k+7lf>O!EWIv%O6 zR^P$zs;6V!3RGE|OyAPf*xMSqUT>(}Xt8PC5&)v|2Ssh+L=rbXSiq}Jj} z!0%$I@JJ%8pMHAt=IuW&u5VndmOjk(-9@JSxTJr`rUT+yB*269i3SQxa;h5qDBgHq4NY3O8LHCBAYY1+? zie^F3+;cbfbaP}FuSIvWa6?WcRZ0{zVBZ+M`$F(*StO&$ZgQR;`R4dIJ*xj5io=A% z27eQwoiM{>JCp)CW2qrkIOJf(B)THAgG%5KU%`Mk4x-r5pn4~jlK+>~D<;un6QLx{ zNCw9dY8+Cb9Rt!~^1ERumK;XHn2mlm`uNFROoHkWz#OvS}v(RxajA)_ZkRl@$CxG`+QBI6-ZJamwn~2KS~x_UHC29GF8c!bZZUc}7cEn5IGI<% zRoPKh3tlOk4Z)uj?eJlq>?=Sw8ucWsCx@yEJ}fe*o|-Bmi2jN`VA7=jbf~CFP}*?$ zu6h?{=|q~G)f)J2bop+6dD-CmtJ!lyF1E(#TR_1c3O!RS3y8eqd&!(s8$&FE1$bNyN%3&pZtPNDrAWKu9)m!ou2?f+&shF1+Y=vqm|)1X5Y2xNh_-(S5j8#9IIL5 z#W;g0JPLeC%Db}nc96XV2CIQ^oxMqy(8g<5DoHiU*!fC`V#cTIgV&@OC9nj;6a% zgw_f6CjAZyxpJng6v~zdMqeO=15uYmS3btpI@l%B3X1kwv=q~ZzIv*7vS(M)mb*Q@ z`SEWzd#_&!aNP&|^P4|kAeORq?NRMFzbJw>27G+~(Uo_eU(b1dcSrPh6vd(G^Yo}5 z>HP`QbEW4e6fV$l)X1Dv2$*cd)BBl5J-v^XP}K|cUibTzz9u{sLuvbmarniT>&%+n zaMV)*hhZ?1EM-w%Q!WQR4B8X>8dzCbsHT_f4>Rb$yko$h{=XaP-0x-|eC9Iahi^3) zU79;FE=lF?D}33d~D zdn9yL-sGPBY%1nibho)KQ*X(wML~db(>+Eva2!E_VY^3!Om2+qNyc=mA8<=T#}V(N zda-%Q3xSb#k<76z&31F6^!mYZ!|-w(P#r3OBPcS8QCbABKEtKN3fS=U?~xEHoD?Hy zU;8GV-_k!gHVhkhlHp8X1CWefXDq_0L&ISsu*u<0^4TzCL^uS-j->`M5nt(>I|N^i z*-O}~hv2#POt98Cw*f8D90tCrA+S76dI!W3W7V!qFnSm{E zr!(K7pRhI`S!^SLeu~nHlq>83&T;_4Zn0P$aTavShl38!*-E{Fp*eMd5R2A%NUAOPzb!1 zqpXUfsuG6gmhuiM1 zz6i#ZG{(|<35F&P>-?-S;&U`wjU~gwXY^DiLt%y<%D+N5 zKzBztoSKmKS=)@THX7`JRZ1u&G|3w>C#7RyHlwD>SvT>v-}CgF;uudKp^K5O|q zArwx>_tO=rqM^f?-CbfTjrH1BRi&P>ucec<`hH`#vEQ%M(_4YE)Cj|tg6)x)ack${fA=2v+Ry2Y(s1CGO$E%|(td(~%=+#j~)+)1TC(Z|kuq!Uqa^dsp zsyxL9#*F1UUQr5%La*$tKyX(GgYGV@NC^!+mRrdqqwymlwY~*GfBv#}btcGk2Ek+l zW+v?+&tCPLP(6}xlKHf}y+PI_TCB~4=S{MtWf|;=le85kf)#OM)Hd8A!vmnb(CYcX zS+nj<=yW2;dFFL63eTXhqE<=qlWHZ@?_+}PsLIPIgK{(2`X*Ff*wQjOFdFrOA_wJD z^0Z#hGb+W2dk)N+UH81RK`hw|gy()#;M3cl>!(|%0^mEp5XJGU2M<2fJXuPtKOskvDS2GY})p2v6lXZv+xWXPmUr|mM)K9(o(lX@Q?UO&!dq&?cF zn9#09chlqcX$Q13jhEX&&PL0A&LO|*wbXHBq&VRl;UFwprXyz20Cdl#)7ON|U*zxn zg8cbC13tcP;LG0fNBN_F{`cE|{-E}RQuXxfSFcX5U;6wyfmfe%n#k?m-g=NTS;CN` zfvyX=j);a*aI_Y~asBYxnRcZ&^hBd>6i!8B1E zhj|Kq^UL{J$LYKzTlwg6ZpzodcZta&z9X*=;boS-QWEHpvNN;sr&XwX(ANE0!Y1q*M-LmEK~dc*Q3#TYn~$zf;ij;CcA z4jbvk8$3ZkRyt#6W@NKaNJm;>(Bxa~68&ReId-Q46=oHjNsrfMl$13Rw=W?a{WxYL z{-PwcueP&z{mj7iKZKpnYuoo3$D-~J>!DzSi z5a;V3q^;50@8@|xuXnCwUbkGX{IT3Am7Bdzvvyhm0}T?(-e3hhqKgp89f6DH5&cIa z*WFGHG9}7e!B=+AA!FIE4zR~jx8@sJ_N)+?IYv73dfrB0IGyG)($(``7HDR z@A+--S;NQ4x;?5j0=LrB(af~vsKtp!cGWuU@vJlDrOlQ@#}q|N3=k84Vq>}qmUO@P zb6c@0M!}jW|81F)g@XWi4n$~otPv2if;L6dD#?Go_E;xI5?H># zf{4%dCyBn=j*fQxtT#-gUHEq4XnO+~QnFoIT@3poUBpp5|{5%W#tFI@`gPK3D zh0~+$iRMa`-+%wVvd_9(+V)}fzB%CJ)BqM%wp8gQ%N*5Rm(AoRd*xCV51f-fPEOhP zbB7%bbqzFP4|3(-Ka%g&;&+F*^R_OGb|#$*eryB-y6rWE?1D9c*3p&*)PG3)+z$A& zPd|I>H;Z514@a=A*KdCK;fFVGzW+6XxPhzOr_xs$qa{FB8tne3`)^fkenpba;#zDJ zz31LL`T{lCoa=@d87-A4EQwfA472B@NqZt4k}60N3PfY#7QwA05Sp4BL-;7FeqrNMUu_?nBvN{R zDV#3zUxJ;kuY*Zj6@6o@xD`Ke_#ZbE3fs`&8j&t;m{_;|^5Sg3t0$%<#z=XH$7R~A zg7sKNSDz60nLTEr&#}AeS0IE#J~}fUAL?~^`Z=a|_)xq_lhR<4CDitzL#lvrw$orG zhirJGOr4|AI%UAqQBz!d*R;-jKoR)JknPo^K1eQ1ezYg#S2)_bNB9; zs>X*A-IJyHU!RV}A%#bWB%+5Vv=LxeF&!esrno?gagHPsG-2oIC_7&aZ%zzou{yFb zcEVY~IuO%bED4e$X_mOeNm5C>V1DY)IsYn|JTc*&Nt*sbGE@vR=-_e|01Z}J!n~2(DOa7CA_U-xVk!< zfGGDS*TBj_Tptb?0=UJT!|G^W}~~{p{s@2z^3$WU)(L*-pM(VqE-jYhGnAZXjoYG zi(-kmR=#?x?IUV3)CZF#^MW@cEwlsH1Fi;NLD{N_@ElcJNUF2&~1{MPBqno=)anhoVh zc!_IbdI=@;MZXog>jQ0#kM&alr%&G3+j8)RX{I7u2=BXMceJ?Z_2ulUHq}d>$L?!{ ztvX+_UYD9J^W|~DefQ)1t1mfPv*oZ4;Fk+18&?pw2fo4T3q50jZhcl+SdLzI8Wd@ z4+X%Af}8|;Rkx3z!tmiRqCy6w8M~WNxr0gVa}A-*2g?noBf3`7Kj}c*h(8l&gM1aI zMw#?F*Gg!#J+4-XN7GFR9m}4q5W=b|5)A5XT1(xvW^cv zws&vU`5^h-YGGaRXXM$G*B;!!;HZ*g<~(>8I#yvTkHhtXVBPp`=2uq6gsJm*;Z%Ni z(+zN57r|U1-K6A_QQS78Y#|otSTmwgn(<})mc0h{EJE2AXLt8#@F;Q3C;RQGY^wE6h)sM%%4Y_f~x?KVMlaF#T0 zvfD8a`IvLy(|H7~F@nm$JlZP=yA8I!_9=d@3pIm)Rj1(#-P_Bf2@3kk9{C}Xsv6F2 zD;oA1x6asvm3$T-(bOp0OC5CTtDYm-Yw8Lcd#5J9^NoPv0#41OT7&1tIiF00vCe?) zZ~Wrr(Q>F%(1npsjNIzZdefl9c-Bp@c$FT9^2GGVuYUL7!TzHUc6JVD6|hol%Y?eE zhF?XbF|{~hcDugcWv9I0Nvnec9TFXID;(fevl?A%G(79$>euFqZHHb(=#2{P*&|;HOKSDOj`si`-S&hvC4~Nlpq1>0b-VQS_@^8& zDXg~|zkLw;7k;H|)h&tRoe6^DmPzRq4QnBW_3^|FzjOH&$$WiZ=Xx;AD}!XN>|FCo z`I_QQL9c|KYH zt?jXCDL2#TSBX3SCk4IlZMG(K|NO^;51)j)nwC#e`yxH>>*V*YSdW*=Fq`r{G0Xby z>ZCyzulXd{V~0})gdTdj9J zRK=Ru`CLn@`>KWjV%ZA(kBv*YU31Y|gResA_@Ic3X65VU5B32?jivW5zq@*on@JN| zO;5+v!eFng&$vsXYLKuiH%R1Y(rLZ=P6v7h6zAyBwDaL~RJFjR5olvYeE`{4H0ine&a(KW7p@UC*vDDl>$bm0b@Y!ms!o73_V5xeLLcfji&3u=iti3rKP*alzc#H2S^8#6A43N{^U2U(5-)0WR8n zZ^8^PxhxtBzey$TnAcU&LdL!?(AO!Y1>yv;Vh~GBd!J9~I#}5(Ibf4du8`ROnj3~M zshi+zjuci_7TCP*bXLbnQ!>Xn7|}_SX0(`X@YGC&R-}q4w1AY^EU!K}ZjiG4*2(p9 zQwTH;7zEZyGIvsjIytB$OY$_Cy7T<%m(?e*-sJQ!)uTQZHURFWMq(SWd;rp=>H z#mw+&^L)P4BrZK~PM2M9SNtmluvq_gPeDy`jAUMz_3C_=i8OaUM6bF5fDr;%ri&A? zo&37Gb;5h0jv-8>;dX@I+5A%A(CA*Bd5Bttg$OX645DpxmC~v;iCUkN$hK$a0)TK8 zMGy=QRzr`vBNAHnxtt+wV{6;)HfP<@dNuHY1E4ix{*kY9du{VD!+31To@IGjB_Uy3 zC)<)G#g;vbIhA8ew!md2bnZOTfEi0I<8)f_M!mp%Gu;#dA=qFS;|2oRMXp*1Z3?~U zQb=$19}Ik1=x+KC^bgqkd)`mU*eQYd@aYss`JV52-{-*6SN!*eX3!HpXC5nL?|ss2 zudJM$oZSD*XHUQQ`s+vUU%fUvE4*`8ueQGvbtk$C#~O2-uHV#DTHD-0a0idn@C$-q z@XQl$fX<54P(82*ZH&1KNm#1wb$u-8O43yNrakw~LQoRSE_5TPM^ewP@!tYHNm4`K zbQ;Xww4iWGJ*JFDbw=4dqmnp2>b*>&{L`x>tiT8SNAEf6Cu}VBdG7dlfU&bno&Y_2 z+exseUrbDM_pLetwW@cXteRlZt*WHMw*a001BWNklrlHE9r~(56K6G*>OQ?CLMsejQs?njz3v=%D_Hlc1lSKPX+^9_HFbp^PPz3g z^X9*)pa12vcYe_@04_O^oNnRsRVN=BBVak}MSklWzMw4fW4N0*VE$7@)JMB(q-!oh#T~Z~2 z%6)|6=GZ;U{50P>hTN6{4OL0ftTXuNF^v254_}ni&!*?e#nejJ7%P9yb6A6Lsl`PU;%U{=gc6Zm_gu54oY>yzd#dw{iqbbD8n{ z{s$dSt6>(rgLWcS(oz333ZHp6sP0}W2`OHPk+eS;Q;gN%{=l|Z1+TIhmh*^7^?>Hq z^v8xrMhD2HWZMf!lP|eVu5&yTUya+N#AED;_YJ}cu?%B&Vb>epX9B%XBuC8GysN7N zbGU=ud$bz=*dUmtG3`fmFzkgF=q-%xEru06Nn;Xi3q(BcVHBotaL;gcRS{U_xws-J z_i!3%DU1QQJX6ja=put&#d!qxwclYw)H20^iyX|BTKN2eF9_7H%N&HF~_P)JkrA{(ePMi-L zc#_J&xSBpffLN32;Y`n1ZvJQr@IA^aU6R`}Q06FdtSRC*5>Y-h&`nPbi~O<}PUz3! z-UY6t%;y;tSde1R?MNgp8k3o$*U({I!7PUTh(z%HQLf1hbrpZcX7{1Jg+d{hNlSZ$ zns1bp%8+3wyWtVTVm!a25^T}Q*S~9qT(6jLFn8{kAk}dF%Ih24+8YN~4wY;vRhJh8 z)3U^n89lYyA4J1fXhlkE{Om})i6@xp^qP_=SM24d*X~P%b;I+UZ)g-P1lAr{+g=Z; z6hRKq)I*}{YEgRffnC$o+D%Mf$&tb2NPK88lwLDD{_=~jpS}L}`mLLIjD*47mEa?3 zwH@M2qLOIL*{b8I#?TTp7y1A^rsS&|4zcnRODiTOD|W0~)_st?5%`9^1xc7Z<{n_T z{mK)(5s0V*+6+$);yLtEgi;$@o*_M^J94K-z2E(hI>L8O?!7-AL`vRr#np9>pu9f& zGV)mw(c{_%u3 zNhwpNV?T8R>~6LF^tLi4H9Xhq*K?j7bC;A6?eeQF`0$3ZuLz0W(iinD%t+5(`#%i$ z%C8z9=31@G-7^W2T|O)Vy6gP|$d#Etx4f6Hg)L{@CBd$$(%5y{32sT`RRi7Kb(IP2 zdXW&39H@hpQsF>0uV(<(j_qL;kY(S!b4Pg?YG07F`b@l&#sv1o2$`inp3kkXUtXSF zetP-n(UV7)mpPvQ+0*CLCwQUJ{m_oH+2i?X&A>?rIi6SJlELv`@1N|zTc}ze zwUcICK~|hOX*R-qG9VLgEJPdZ_JC2ELC?c7{xdK#8dt;y==xA*l#%UNP+F%Ea}2sm z`+}XoxAzTtL$SDb7w(4)exbxZ>FKbs!xRv(9Gd%@woU;KoMw?iO!h?s6 z%Kq8=l2BT~bQwo`z$AL;nT#Y_lfx{Fp}~Ya3x6phG_akNCJRN?@C8HXC`T|B$qQ@% zouQ2ZQFAnL!K~W8R1bsii=$KafRhTGR4i6P66q;#Mmie)oE{}U$xlvZ8X38f=tna2 zK1wu>GE+xa=&Bk~{OHI)d^F_hyzQY7!K5JxutIwOC_6l^@*~<8wk5eT*c~DFN|75O z!_H93z&DvvSyBoUQi>d`WQ373VU$R)m@_MUGBSi6I7uo24vb=OtiounlR^&NiFoug z6X=6VmqMhgB|Rq>U)C>NX?6-p#q0bT=DE= zcdc*v4Y1aE@Mga%c&#ta@`FCbK0NeCS_?#49(kqt^JefpW87%JYVJ%rBrEgqkO}nK zCOhC}&G<2G43EFOd7}_i6S<^nLh(~$UPw4GvE-G$-+WV0hi|>$mf*sM#?ytR5BV82 z+qz1rwGSv(F4{j{EVj2`@Av$`!+83!q4ARq09^xY&8q7jx24oA(Q1#*3Q{gb$654Z zGb$9u0$~;$ST}T=FXrM2Hy!DKm@gdqMjw60d<~4@sIcLgmVwX;SPm+Y>Pq;46sxt+ z9?m1ACi?c_4Fy@$H?}@n_-_DA8uU*d-}~j#>`Ncgb&0Fg0u0{Xx*lX+jb9I^%(a#(AuC_|Kk{1~` ziDgQgbyIIivL{caT6g!55mG>oM2l7stC973`~ECi5Wb!b8WH9L%TlS8^Uee*l;--0O z_4i-@>^D!pJ#(jWi5KvuX#*iJ8eyEqg{b%tILK^ajwupPiQ%pPn=h^%G?+>wmui0DXFDt7)lrAZa7 ziWb0CHJo?4c#KdvS33_>eN<_8EA496cyY68thm-j2wiMr6b{Ts52_Rv8u#t85l$<9 zqggc;+-x4yC|)?Ai*U2nW(?hw0g0XiH`+=vg&10vAc3jezz(}7kJyyX26jYt%?-k#_23(=NT_kVB>R zuqukSXzf3+_w&48(r&Bf1jqK*b|4Txet$flM@m2CtV+8!zv*d6+K#red}?cJ9{d%s zOg<%F$Ud`0cGLI_E7R9L8DVj1Ay{x0xXM?f7MP&Qwad&_ZQ<;sb2m7+Fe}$?5Y50{F)le)b8f!lg!SYrAcggDsaZ{>av#_;A3{YWOjmrPeH>L^!&M8ZQBCGBV$(ZT-J z^fMZ?Y)c~}!5uHWuY#BEvi;~r8Tq!_O+asjbPEX9Z3%Cp*iIMcGQ16K4iC4QiA>YZ zX6}~kGhI@u;H+Sj^q)^UY4V(k;0od!jD=Mi1EQ2CSmm%?J~(#v;>916V7DO+TsIUVeK+uhcnk1u2tZVrq za+Z0l2C5CW)-qtt2ZguPcvZSMNuik+{mPzq?}MwGcTeqIjhy+;RQD05dvJ-dANFJFEA^*3KWd`QQ5Xz2b+D=R;{W5udCTUd)ll&)igf`Vm#;UwMY zRq&H6L^mdP#E_(EUVno`!>lf|&IN-~Z#gD+7)^_LC1D;Kn$#knjR=ZN1TaF)>^IV7H&O6HqO3*WVR6<|GwIbH7EBIB1xMgu zjrL3czlyA_IT@>)>F?TDgvIBHF~-9aHF2Sp3cQBgmPczsLsv)F-m58n&`Q|a1W`xj za&1h8qtBsil&xeIZlhezSvj1$i4Az7hU>_eoXb_n8_b8R<*}S}nBXJ8lfL#0fn%_L zThrX~&3=@2P|1Uktdvq1xR3xrLxn!#$%DBZ6*Kl=;h+aiOH+e_cN~!(3oMypbF2S! zN{9_R>%@eqjHzdBzqVtZZR8bie@>vv{?tbu6}z2OKMPoP!wI>Lw19=04}4^5eEI|l zN}Yk!F&41sKp%N7v=3=?k#r8;I;~?WBRVS-1%m||oTd3L(^T!#QxWs?q-$2y0>26? z5h+QJ*|azr)>JpD=mi`{$)s1d(cN@&H)9f;C}KsTIHtyx0jXv0{^t_xLfgv}J!oEy zVCdS5S25Ej{fMeJk!Xp7wL4sB*>BV1wyE%g0(kpYu~1+Et2lSL-JWS}6iqrdX6A}C zq4~h;D=SiAW6Mh8UU`r%_sR-91psS?9ERTUt#M^B%>N!Sw0oJ{Zfz01YZ5(0*=Z`- z>-3EIDaTj^?8)ojM=?lhuls)1bt|ad_3QHM#jo#W1%-3KzdA$wk>q#YgB<3CnjY86 zHK~JBy<5EysaewkovAd2c`ZjjkWz2T2dw$-LZ3^j!z0yZHhpx;2KQJ{s*!9)eV%8; zjn7{dHVlU}-F)&IH^v#F7jCx;t&R4KeY55YiCQ&Zp|n2Q_lMzRkNx+m+8fV~6*@2r z%$CY#y0j-1jOcqQq-SEgfHaaqo+1b*#nI+B@=JOIXiv&_BI)Vn%biJwMkL{)0~pqb&xp@oqe+ua>=rYWxrJ7{7_}e$D5MROWqzPr ziK6}FLyNY;xXnsdCT;&kFu8y7x&T*{>M|D1&IYSiOQ@~}+)F+IUg92}O6bGjieEps zba3pqKkflm3;NfwE0;`6c5vh5voADmu)WmSv69&2=S2i3>!E@{4sSgGWN(* z`UgLM_0>Oq_xHEX{_g3Mdp|rqerILH1lUebK3rZ|wxg!aUw!2&{OMcERskz1Y4z|q zSF@!Clu6dNwScwb18`IPtahsiU(&k@;vB31-pOVswYi;NePgHOC9#B9_M{8;7UT_- zyIvBWLtSd7`qJ}uXOIM>jwCrq zBuqI9OEfGwlkCE~oq-NMB&(JOI;R;ETM7J}_TvKhDEO76Kv$t|_V$8EB>E-cE~i6V z!P*r?bnT)muXxXj0}jX2>PV-PPK0K^N@L-$6~Ck(C6di#0{8~oC}LmPae<*Tt#mQd z8n)6`UJZ;&WXC9+94=O&3HK^d+{iFCEBa{;%TeNiuvi5Z!wKC~fC+7dTY?ne7VHf+ zv3lp{#>XAGQMjzVD-+!f7NCpsGviymrmy2On1Ai2IV&`86GFu5)%=uzk(9#fK+mv- zYy!vzmiDO*>CgNzb+~{!(FbTFZ>`17w-FS^W;N#NSzJNX%_GfLm^kBW> zXy?A;=kI)c|KQduznXq|1dUYvN>f?uRlDQFm_PHsEI(hc_FaGuIx8MF#ZD{J`TPYXdH~%*e z_{!B+Mr8R7G8d*re6Dcq_1C67sjxEgeOmCeB9j8~bzn#SIvZ9+8qly+=h*NsM1gM* z_0?|e7EEz>3&ZrM2}6PuJ)GFhC?jd+ZuXovo6pUv#%Hx^R*a340#Po3eIAkM!sD1d z>`+6Zq;YLmM-EP({eL#3fh*@tN6x=+>eOC6|EJ%WtbTS-KXvD`Mt1M+{Y&x&WrJ{C zD|xdwoH0o=xm0pS1{2erRYy@Mso;V)rnQ&6^FlDwEqNzczq0ki^4E$}nQ80!7jN8X zsBCrGiErNEGh7PW6Cf397B18LK%3h$S7!GOByXet_aSvOKR}5}~7~JH9V4wAHjd zSeDS+9+;HfTEPN=wcbNk1FCD9%kowCT2KX>7%Q5vr#n<5oWZoWCt?+CWNb8qLXVA( zMNs8K8CX!!xa2ncYJX_r0;D!>0Ixmee*+IIFh2tkeJZ>9#0s? z{>u$4KJU|gPIjf^pg5$=Nt03tl<7aSg(d7WKBP3eTAVVOgmMX)`!?ZBHWTS6*bP(Q z;dGM@waKqNpoQw%nUx4l@EmPzt+XDr3MR&dCNjV-%kIDVy0)LT4>KBr?U+khY{yni z48-{IbHGqgxj4o)j@)gb6@@KIZPXfGH9x1597sBCe(rCptV6lg9j98ndXs9 zN~A(i_tL1EG-(f&GO5xsB`;YuEz45=fPLqDKa-cJmIcN)nc(>R&i9>5DI*ju8U)gU z`pQR}H`9a#rocw@(;y_!UL#YACNpJ}GnA8Mf!A_ISfqD8lg!30XUYtN{wQX|Vg>*@ zi$F)z3xO4vQF4Hgi)3<+Dr5?tydbQY7@JYeX0GH|9f9c!e$k3FwjWbzhH|ia5ZAN0V$v{Od?AV4;Mwx&s znh!H2+Sj@nuSTOKxkFRX9c*t)g-`p4qOBtts}-dreb&b4+}1nVY}iFt@c4w!%(gU@ z&x7Q%gIX7ihG3s|6f%Ef(hRWlAwrrl9^<+cK8-OnzPFlfgqSnqQLTeJop*iXYuV2> zhDU1Kx8EWz4+#GL>)EsCPuZgcAMhu@-j`)@eCKLq>V%ToFlWk)gFbR(zwT(iAxR1G ziLhxC4pSFR?)=l`jDdx(9KuB11p_j|rb5XRbR&F{y$iu=7164}0uM;t9%vm(O(jF# z-IupcO{)1y%}3*EEIO?`7$fNm1KI@~#)_C(Sd(F>rtwvyIR-YrZ3KPrdo7jsL+O>p z`KWttyE0u1rPppcckc8VBcbiKvG+o0Q-Ve352LHn{s*AAd2|2Ew!f6w(3@XUh-J3L zH9!}xUP@^$G%Jf3`OGEkQeLZc<#hYb?#9O4^7@^X4mJxzL<~|c&v5PG<42E(vw!?r zAod&p_$#tp;kl0=|Mh@i?3Y{#e{p#B)xUqWKc1Gm?fpV-+)af>RyOagX`@15I8UE1 zeN`bssPcANit~YCzrsJNj{?}@Y6FDOWSEyiAjQOAwlSprS|vfQzJ$1s-a!61Ou+TI z{N3fboZzXYt(mzmtn$^ddp!tUm~1W8mB=%(br{jf6sj!H$8s{kRET44}@P z&^Qk*^x+dmKotY!1yWoVAa$zO2(`cqm{)T`E%&r{bN1Ygo?x^xAZF5a3uDoVxFfV37B5RTcZ&cHt4UW@z#KX zPYAFeH8su-^dD&h18hZ1pG5vfv)f^F2)JTdj5Z{yq1`#2p?bE#h$O7nmO~DQn>%2P zpKYF?4XPF7^PvI>7n@3+9F!~3sv$t!gdk{e+!8XcO3`Y@C}j|0FEA_TAlWV!#aIu= z3Pu#$%a7!mq%gW<%rKId0km?8QI7=x#vYjaV3Zq_v-mmgy$MBh7FEDmXpT{iq~MvI zug6S+1Czp%^v3t&IOLjTGl()?Zy=0=8Dr54q@80Rmg=y~d+27EiIa0!G&7bG4T$qz z?Fz>HIg3OrJP>3UR9J(#1ewRk=e=WctgwD3tjgyu&3o>ez@}9lNUdFGCbR>IBIyZc zV`!x>VH$}SBXdb_G?^@yIl{+4A<6z)^eG#KBv$jnfjvK3ydXe}#)dBcIw~%LNx>Au zHfl?UsdpBpdU`u1kdkw|8ybeXd+ts8nErvu@LRRr?VZh)htyK!grh*T9i3s z%#2aBvOg?rQAmu~EEt+_`~WDP9Mr5y-z0U=+%Gc@dVJ%?)qx|$MBG)o+kN&>xfkZ8 zBTt_{ezM)5bi~DQJr0@y zTF2K7DD|VPI6{7^r{M8a<-HEiyP$3rhnP8t{R_cT5^wvU0Ccmb$p{JquDyd+Bh_4u zlL6C%G){Z7;B1&TkoIaR;eZlk`i}<2!wAm$b_RT@r81RH@4oWt$&=PC_r>3=rFMVt z!PeCeR@Xu`SMWXVgj4=&9TYxOKb6v`3$_Dk;{cdsM@loHX}E>;w%6<{VpLX#ZkS=} z$)h>g@Ar3@r3--d$F8V%{T4cGC}@Jbpwt{m-w!egFIJx!J$$ zVa@yG;e)AbQ$jem4xc~&+LpYe2Z7D?+}6m0hyVEJ<8Su9-rJLh{aaxBcV9l)?SAFt zn~vM?2k|xc2KEQvOI!pi)BSy5Nyo`7I%2dHR{HS&001BWNklHd6*b6kFIpVvLiRIKB&ESw+v{^~8-w+o*yTDb_&_bn2Pw{gp@Rm>BBNs_k`OQkF!x0IKab2ZNZ)Rv_2n<+&v}XoXH^MWz7chbr zzB?3QViveBQ?u9>%mU!{1>|Vi7dT=D_6mZwVEo(;2XH3>p23Iv>=a~mE>N9?3!NAw z3;!KL-!Hq6nEVX$u$>W<3-J4Px7-p;cD2Ye3p_GrLrCw@Zh)vjudCe!q(xi@+I)|> z?CnC67f75L>cOxM;4;-#M^TC-L|JaX(c;278L7|5g!0;t9TM(43bT?B;n6FjR}M5- zR=M>>M4J2&8yi1EA9N8*{$@b$w8a8k1to5ThMxOgXskeTZMG&<4+dD&E9y-4OTV>lQA zU7uH*#SQbqgt6$w#+N{z9n)GQs-g+a6kk#3HO7f^oQ7l}&yZb#BWL1hBaEp%7#6AJ z+9YGHnB3etp&p-Bwj*?@Tc~T&42xz`7V&pN1FAqqSF+H8XKu;)xKb(@8BeYnw7DadGmNif zz{X}220!^PV`*@E7dLh|f2KBTTq7^pKd4F4+6O#gCUvxG)dEFX@E7@@xx#&!y`gJl z%$LKt1x9(LI7k5?`6ZV<=XJ0@3^Dn-6Bn&ppB%YvE!)hqP{^wLJ^TjgqmnbaFOp zL_eo6f@UE@jUcQiu|k0pXw0H>_5`niVBTsH3rn7777}CVR5QHRs@G4EGs1YO0>7-3t$T=EOLxYG*mXi z@w50_`HKQzbVSfe=<|KSZKOW#35)WIV56@vqTZyhuO$wfqv{K%z(wovV(-`OaLuc> zN}TYjk|dx>U39)EB*d(l9IPP0SR%`SQNs2@a2-LnS3^l5>K4TEI#@c0M3$J~85gI| zpkHD73@S8o&ti=c!*b!OX9inG!3BBvQd@V$;U18?GBJ(T%mr*A!AyuLLkc>s$xp5s z6Jx%(Wm-G(>bM>^7R|-9-fTjE7tMHDU$lU##9ESWVCy$sO79rfP7|Kj+SwuTN~G1| z5wGZ5LsjmIu8AYg>$ICXIm}!}0*nKd3=MYrHj4GP85~72INGbf>OmuK52N!ZglILN z&e!X9HVc3bs<~Zph_?XavXL&SOUPx(`vDrWjyr%n+X$QZ`)P#hAXwuAZKPL8!kU;+ zlVw)(PN+?zZpC(1D?j|hM41>3pqNR1#y-#<+_Y&m<)LnU%mOGyXoJ@E-wcBO2XC(f# zcX>v>lbXZZa zsxDYeGER_3R3jnwX64%B>_KdAzm+(X{8{-??S%?s{iQ9y|Nb*hnMcasJA(cM9{7i= z%eU>lB9(GhHNbD}0iQ&l->d?k{8GA|*m~*l7+Mu3*wo^PUB%_A8kD;lxuL9L#3Prh zI0QBpEV;*tYcmK$csw4q1wOLz$Z~WACdldYw zD9!K5SuY&$-EVI1JwKd;1>HQ@T3tSv9P3Z4ysM6R6JwLX_fP$}et1`0@~zn$v%mRh z<{a zNA$Uai%5RwJm$|+JPqzF6gn|~?qKIa!SAHn$}>+ff#&|NTzOK%(XcaB7#w6eiy$lj zp8ZTagT&#)Ca~&98qC(X_lu=pamw(#gV1W?HnMD75J#L6Va|d}DFR$e#WJZ_Dh6d8 ztciH$eA$>PMnVk|^f&fZM#PjctQay{;A-H7klzeKSHN?GTN@#H)u-WDt_x?u;m=@k z!+1Ufq7_(_BJVf?2B@RuV;vz(a9C7yDT3ABR$o^R;VT>lhkZ+U5aXs=V($ zf-1W}ueLIfKI~ll01nEm^On9jW`MdS_nIPKq8nCLyI^x+t@^k&2@3dal`T$M%B~|90+?1 zv${ZjZq-^B(KX<0(V1l6^cS`l)Mu;22BaMfqT>c0#&P%y_9U~=+-}t^y(v0ufJLc; zKUpd@(l`N5H``lCB}lEVgFq>2i7F(u3p8$bA#p1=Z#N0HI~ekBqRqAnk5fpC_GOkK zwO^M%sSoB%6Gf)45E4_NF!_j#BF=!jd8j+U z?OzrKPPC&|Bb+${f}yk-o|B?XL?sr1ju26^EXx#!_RiLr$V>Fjy~js~`!9CuY?{&y zbFr!2-R~9W$-dxwMT{QMkRdlxKR>uw=~kFZ5%-~0blc9zx7p<#+^?{20Z#XPy$T^> zTHcW@B?h{?)nd_})-#yfkh{>#JF&vNLvJo`?;nDWIeM{IRJsE9+pcVYF~+YE#jB(X zX6GSDSkLc2y}x{17=nWLr(OZ5T&}zk;0oot@^%XPlmGhf=~aL@E)FZghK<~q=I@I( zfYM$AR#a$4uZEKfNXgh1+mK$Go&`^JL8R3SAl5pVsX+}0Re;;TVGWY=7U%ArDgOdY z`G;W1!^Pd3?ZRXDUqz%WS8M#Gai^+?&62y?7YBbp3eyiu?BHakzAc%tl6-m`EbIf=>96k}yu0hvrcDyJjyg zv5ldhNU1Rnn1_@wWBn(=Bomn%QLY{n*cg2r5dof^r3zm;z`OnH8}s}7Z@>NSyFZ?~ zG5hh+aYOU(j;`G~ZvEoj)2FWnkD_N+!~ws5EV8(E{=)2yTRq1gx21gc^Syl$;Gg{I zck=kR|N8qs{>HW<`F&2AS2Po%9I1beMt+Xd=piJp=Z4NH8AYMt90FKFSo)REdx%5# zes$vkqpKicq+G)&^Yex%<0M($3L|L3dr>+F6?RZx38r*7{a?H19b5xs1pcPJRKKEc75PEsE?c zpa&T0j2>Wr&B-360-KSX9pFIVKDg5K6DTw{Y+TLk|_2mAfI^yHP7k=CmVp> zD03zQ8h360O|pt%zAeS>px?zS4ss}6LAU08sv#IXgFRud8{iF)CSBxXY4EtP!Kw?` zL-)%)Bh3|Gs46?W?&A0vlDt4#0Z)K&JRIaW8kObi!IHR$2OK{ydUnu_WR}czR3XVv zHIa={9EZSYLBjT`=&>Pk8;_&#NCfvm6#*?wp0QYyZs;YjCe!03qtpa|vS}fMrRxn6 zDDx$bdG$OdzUguDo0am_^E9t&Nmt43LlwcY)6hk=9c&xjdb=3uq%w&kX%)OGs+Hh8 zC(LTISRpya?W1D3TB?`o`5m?PgbzU%Po6F|@_G|*1%@W3M_gHJ6VR{%T~x&O_mBnB2+%)D__kkICOK#q3rWK3ut3QI*0N9#5}WBFzuv3%y`@ z-#diR;=r|gbKFqbb8Fq>zJD}bp%8X6F?9?sHyW>k!CL(snvyVK?%g#BI|C*>*x7Rg z#&mfA^W#IqHG|;1*NfR%EFAdo+6ULKUB9s83wO>mR=1uX96URJIhq_fqiPqJq-JSD zcbi&SK^Cjm3cjdz?rm(2?ClRf${v)tYWzlklSFouHv_kB{SOk>*777X%?d6#J#DWU z+159iB=$;WuPe`USdOt?btpfwy`x6i0vc>(=uQgp(tR=nmF@_QmAx?$XIZAMKu8P@X)F-;H#(3p1Up(yno~1%K5*) z_~O;8ZxsA~^XZXO@86i2n0Rx?+%a>y@ZRC47fuslI}(o$F72O~II@F$%z=-mC#Gw= zNB9)5{3lPJofLHbg?#Gizy2Gt=&vGbDcuY0vKpOZd<^%|B=@$H2k1gRz-~bmXc;jo zg7J5soSciWWmpal^|Rz@r61QB+**@ZtBS%E`6T(02O`fO7OM{Jft**pEH2VCs-D%Y z8#>oI(>5$7ufzMmWaebrgqRL^j2vdun#Jp8?j#ehg!Vq*S=t1xvlU8c=$_qmD|FLx zY|Lb~;yH@6yaLq%uE@X?BsFml45<|d+#Eb34cZHt6_&wxmV#$wLR&M4#-dEi+LtKw z0eBOIw16?9v9JNA%8DgOUJzuih5H17t$9J`%o^A*97iC$lwhIvs4pEwD{zKVXhd&J zr8D;+f6ipkvyhJVr9&CvzUkKARQXXldJmx->8K04-Dn8IXOuEf?<|M&t`^46X*;s9 za1;tGNTa(E(h)*M1Cli`Yo-7zDu_z&uglkM4~Oi+gYyEXkY9L$Lm`@hDaR6AhCIuDEDQw}#@L8`J{AJ$6)cC_$Zp5J*Vp60GhqgJ*x7^R zS`53wJs*dCo=}gkgLCGwI;YJvjgO6)nTm$TP(N#09hDt|!G3UG3%IXl77|>Qm#}~0 z&V@2au-`c=JmHQ%R@1?EV|ua{s6jLu5NrsbB}s@{6@sgzjkGt}(7}1jv6LJuK^de2 zm`gfakO0Q$VL&W2TuID&63UwjRu)PXq;O#RoSMalC?3KS+_a`(`mLzWd%|xqMHN(~ z?dmPIVfXdnb338(wvjto+(YJ|Qc>@{=6G{nxsT)?xGc=O$%SvFsRB7F)I10A`&UrL z)J!#TQv~v2I*oFsN@;$c!PU2(Tx6`|8Nw|a7E}|VBE@IUD87p#q(cm@!aW%AA(c=0 zBv^VJoJ}soblrA#qcgtGkZ~P46ko=_YWXn+s^$~xo$MYGoc+AAzz~$#WW(uxdwmdJ zb7Y??5ngSUVH<16w^o35ga+l2k#D&PJ_PdOAL;N{vPh zvoEtZ+PTl9xU?gUUd$l?<)Q*z_BX(xgh$!`3*z|x2->yLJ9K{IK* zxOSJ{@~#eVxGDp~laoWgYBw3&1!X&;8;@);2gE5aDHVOjUO}j(GD#(ID zY7`ovi-_Gqg3YUEuTD&7HV1T}vo}-c|MB9FfB0bfgWtRo)cp3v^%(8tzPv*<*T260C%cr4 zF|pD0B!5VvsPT8{$92XvW_Ycrwk3e`wf;Fdc9ae({0qQ6JP8WSz^+LYHVyTEwW1QC z1*AWbkK|h9`K>0@t8)6(7`tHt0TzDiz);cQMduBJB`t9DQiG#uh>i9#+8ICBP(8_VA@lky$aZ=eo|!)PQwWBTmSxD&Ri zP9)|}%8igJ>j+w9j!*pLs6zQMiqaD_~`(rjmRR8sAnN^olB2j)1NYN{q;Iatkr zsq=gg7AUzeK=p!v@xnagI*Q1i-JZ%ipg48)&+g^K+WmbG;4F1Sj`CN>{A;q-{8n$ zsHww`)@eE2teFr{+b5UM7$RM{u-Ta%VL(=nQ6GqmX7ClISpv!N&GFpNm*<{m-Z}Ot z*J*p6gHF0D{$IF|Ai^>X#gD?@XTYkFVgId-fzEakC7JGcyX46DAU-%~lr>NT{nNOS zgtfOI&i3AhECFQ;F}_g)aQxPA17UO{S!*=>upPxv!5L#TdLSm3o@FQ>f?MN81ZCC; zpzKm}XeEZu8rYmQ+6QqkE|`m7BdQZvj&6E>ppLNPl5gp7Omb$p1u+!#7st_fj|51AD-SV7gO605pRp%CumXsS zV6iMON3?YRqc;RQ-G?L31U+ZAzy0F(Y9;)q|GfNq>12C7eD%U+SY8(0yaWC_J&mdL ziO)AWFoK3Sd-a{^i5WjI_v)qH01!a$zs+;_id*va@afl=BZi&n<;%NmA+ws14A;-9C`%OL+d``}L!v;|>?4++j+6auFU z>BPM$tak;O5rdV_^DSe}jGq`A3;NoH=cYq~s8Q;#gcm~!9l8%} z_SygJ3sJBIdoM&-4A7z^no(Gx`*izu-)Gk#fEobZQoV&V0Q>0wWf#&SY)Hqj0uC+G z80-<$B^|ym^!S(nF^YjZ9GH339d)+~+;HGdkeDTe@@|2UUJapHLkLAQ@}B|08lAvu zK>a{7$z!a8ZLDSh_w@sXZ5F46k}Mk*ehA1yCYBSEMpVFPa^k@Wh`E!o0AwgaYW>2Q zVl^fPDa)iBM;#LS7|koP~nuH~n#JB`Nng<_j{Fpe!S#ytGGu`eE5alkRQ z@zfpBq(h)WL1ah)*G)`CG^U9XX(Tq0keG}uQ51zrNMXUM3x)(K86_c7HtlLw-E^6* zs;H_aQab$u<~!$i$z-IcRcgbvO)xk<_k7=ZAZALKZi&GchG8Iuc~n&qVF%2ls`3i- zQzrZ>=Gz=K)z8hk399v@3PSW7nPRJ~>ToCv>oo__O6&||HW;%4c0$>JY zP3-uDN#Bn7YM~a-^+#Q1doWOZc+>|8)-rw{u8!ddf-N!beTbpHUP4cm$L;J*DJu}$ zkGj)OI&VfRAYI5%#Ku?*)~6_2woLYQ?V0329Bp@8X7>mw5FJuW#=|_9{dGs%CWc1P-VIq-iyA=A;>5 zOUz9%m{NU)CGo`J#qlfemO;y*6EmHAlf~Yhndtd&;d8HZr}KJq*7szb7Y78 zM{4b9HX0O^`M01Zw*zKK)&N7BS(Dk^aR2}y07*naRM`;506J0R5|yKBVTmUZrvYy- z4=xnLCYpsQJuVh^g}g3RCX2UD2mt>ZkyZ+F&mBG(fj)Xp0q_(5mH8_}2QwH{Ukd&~ zZaH!5)?er6KX_DV6vEs1BKCv#ae4BpCU>>%zt698!*iZ8<}Y8uJNyEhUNCt?NmAXN z0GUrT8e9oCm=MxPnA$RwKr{j$s&aID*}=%L)+{ zgjTLLv;iYv3o>a?TpL7KZUK3$ZQ7{45_$_vMir78Ia@7L-)eFB3$4O|x8j<+qPgQ0 zw{YPclPI-Hw5_7WT~Up8U}3p#;kNOd1q)*gpDS^&layh9A2%wV~T zzF%y7Gn8C0J!>!tto7ePxdMVFp>xJ+SI`w-1bo=P>UXj=${PuC!d(5T3W;VVv@IaCl8?U&DvVGp zghtCn|6Qzm1)F<1<+j$I`!_pAIy>M&0+KuXdycUQT3!-z;sqyKm0JpnDnWu2x&``q zSdXk`Ed#g0SZE-MlD;Gul$ef%JS^~CRupmz%qu&Z3fU7Z=<7fyq1Um2212_~W7sYr z&B7nM?r70l?DD20SiGTo9}8IPrO;!!T$HygL0%*=!44Cv#dM#JG|E^A?Sv(Kro-mD zyd0~+b0na<5d-fn<@Hz@*8;l&y!jH6j!V}BRP$6{2|#D_21BrXkYf4rhS^8x^AYgi z{=rq*;BuCdC-q@Hn|*t}Z0>@aZw;l*n`sXQu$mPNS(7@G;*#;IFlhDJD1ewP#0s0K z&+;+31Kos7$TGN}9%UV&kD_R@V&mRk1Sym-AyExYDfE~cL1V}a>Wfjd8c*ZD=Y3f7 z_OTzSJ+dZ0hh;fi$uD|rA0K{#$_05qS{|@j$0^OCoCC!|(a!LhF@@aI`$*2J=~!}l z{912BnTsj*N_RKbLtlp$h4;ye!*w`uRzPyIsmnQ&ow@*9@?olv6-g9pcdeljizQng zR%f9c6SF#tyf(Eh`L`_qJe2G>x7pR6Rxy>ZPr;uv)@~Lbjgc!NjjP=Zg(e!KcX+Jp z6%hEBSJP?5CwE(y-lD)a-f|+HSYP|XT<-p_;1_@#Iiq5*lnzU-Qe8(&;4_>-AJrj6 zB9l#wacU3{3i*{+DY_W!p^XsgM(jEZ8RW-S^LS=wVNa3^k2kak8HBv9AAUNm(w?~h zM&2{&Zt4hr%?c#5qd}!ZlNhI%9}S&W>gk_<(+AwYBgnb-v12%#xN7e>a9!HhZyxMc z{(oUDam33ieWYeLYW1OPGD-Q zI+57_1s7&{}LU*J`M+REq+f~^3w>nkg0vR17|<%(&Oa`zlkqcyZQAgF_x9E^jm zMB#7}qPzv*1qaqFnpLoNt6~vE2JA9_17qo^7PV|?2(^j}&mBT0rLbIxpySCn-A9$7 zjIiM-nXlk#1#V!}0p|p2D;cocq}=mPGKkqTF|wgMxD1M}vL3g!T&-bXcIFhe{=Qb!QT+nRA^Aa)j*9&BZCQV@}pK}JCXwlS7= zu68n%V~_)C=UxBmDkWCJa?$bYmkazAKxiy`TUmJ23Oq)1v@-~$l@nQ&{eq?=5ODcB zM|iBq&uMdK&xjnqInwGx6bC}0M_O49j79KB|1s$6$-wVHjAJx zR=`$=13slThZPLi0i%*t7;l?dJ;?V=R3Nd0VRn}61rXfA0$@R22L{ic7E~a$;2j4Y zc9#ck__OqL6CQ7Nc9!E_s*z0-FdakGWR0CgA8=OAQy`s+*=--~o?&j)bK>>`1NLh9k%bmx{=wb| zAJg59D9U_^PGE1S({p)ZjCH_$v>d0WpT!_F!f)AOS^GqwwrdY5q!_$zw0Ps$06K;F zzrf_D>zt3sE6$EB2GsRnz&4v(t0F!R`>13x*pa!~#d1R>iblCGB-ClvC{0f@?1Qxq ztV?1;;k2p^?)vWa>({SRyjc!x_m3})FTG2MB>+5$fXNF-(Ha-bIzpv=j+hAi|NbM> zuM|<&T_^87j$xe}6W%M&3x$L5)5%M@R*QMD_N5yhE<2TiH4A)>L4N498+&IsaGpq^ zk%3Yy7935a#>@@|90DzdHcMbPLTeI(IFL}u>Ggx-zX8C%n`zxYIUoQW4;Ko<%d1cJ z)*k4UM^|rke003OK0LrhZMe6foUsdq!a~CYAxv_6=}!_Y{S3*`R3I_-nTT9Kf$(Xi z*jk__ii+oaPe1+opUuM60SL1K;e%$=gB%Xq6myKgaRh;<5N|Y9odWA|)9DMPE6V6Fhg69S zNCIXRVb$fZ2$*VwVlINQ55_+Qxv5&65-O}!(Golbt}EEv=C0b>;PG|4EZ;(VMd_8$ zSh<6IY;mCpN!YQq%6%}0&N-W#+ADWO)dNGJh3w~VD!FL90+X+%ZT*+8v-xfMzTR@;M5C&$ zgcLNP9yl3C9*v9YQ`}27}tgDs5 z_-w^48Q~?BvVt(n@YjfLUK`)O3=UtipBYM*@-!bAB~3wti>g7Y*u~F^?`hJUFR7xi z2ZVTf;I-u7N`(LjcMjPWLXakK5El9qQijoY20j8ZU&-Y|4-BCyIe z^@}ar+B^7R5<$DnMmS5thB0I0Sd=g@dR{P$#sFMn3_aUqsi|m=Yg<`6!GLs)h-eJB zhQ?bYMsL;@s&-SNdJPZmY_&^VRp9&Id){6e^dm*qqiSF$#Zuu>F9b_7Y6V2kN^_-d zB&U4V09raLDX`Ujw7H;SCRH&d2;^dT4(t{d6kKV*xo!8@Cy0Y$U;CIIbP>>ozKh*e z@W`h`bSyrMzFHiScZYQ4dD1fu?>7rVQ+uR6$M;sI7e93+gNw^|iPz4_6_$;L8V0n6 z$_Bu@c4vE#akH+yvOhC5sOAN&XAS)Js`gCCd}ePQdj^Jgx3l)-+ELc(svY26l_Pmz z+J!-nZ6cWV#q7PtUOPm;c$G-rqQ8_)73z+3>c#cOlna#}Ty|YbK<-F4q(iO3uJTB^ z(9%T@y29Y;<;l-KS6<}^_vmFo|L+#~2j{MwS(%)h>*24HRrS&+d$CxLOuv(pkC}s= za_gD;MSJ~rVjW(%c1*}N*dEn*Y%LcYmkEGIhB%#?F_-Yh)lgx3DB}wszwW%gDppYU zkrP8pceOOlpxI6bd;Np+Q+EAiw<5`1XLHMs9DE_Ro$rj-1=Sdg#c( zJG++~d)KSit{kEMXy&BKeH9tWM0V`pu$wiDG#;+I_34C&u!1U7aO7%&>JwdS(uE0F z=1Fx9qjYLu6s9g%>*8Us^Nr`;V%q%MuRrA3#xgMUAGAa#|iL+lRL4=bVLf-53Eo;oJw=q7Cz3cKrhFv`&+O1!>E=K$5 zjPd^S%Wv%C+rRJex3LnwcYf0w4lC1{*D;es^7X^5mR&?lMR-OFtrUhNZFW6MaVDLa zjs~G}K&`)+dinD9{Yap4AWRHL05Z&4xD^RRx&vtY>+E++OWle`W9vTXE+NqeumYp6 z3PW`(+#X>|9Imv%VPc=j*|0MP)piYhIHP&AhafCvJeMMQ1kV|)!hNMYWLRz^8G!Kt z8~aU{D-51XDe8eM>!tE~rVk*dp5ZgQju?(qQ6ZI?wD!Mcp=~)+5&>pCjOCa0ul-+N z#}tf%C`m~}F=?C_8?bV(O6m8CNnjdDbP>;y(@d8!7ZHJF_kq3cB%?`AQ&GG~^ezyT z)lVk_{5VM*)(%+wnmO#lauBy7IWl#t>my$Gy=a{l_d{@*xv)!Ns`R52#ckvyQG5WR!3 zj*)>78t5DjVBU$=;tZ(Q41jU|#^d(3g=R-eXbEl&af9RA%^b5#Sp7EFavN~B zjcj(iQ0vs7w;PaK0}VPEYRzrK=UOmv8ygZ!U}RPbgJzyv1J)ANL}43*Gj@5cmUu_w zU2d%=lnA+L6jX-Xi*oP^`Zgby0J|LM$D*HIICKw^dmOhrhwhD=mA~P-8e}b2d&6vX zO9@=vdZbP0c4BL*syYZEGY(*NMQ9~0e-d)&{ToX_D%IiyzYQ;|vVlSH8ZQ{}%kA=K}%=O8E`gx|z9m=15zRJxh`JhJR-yIx$ zVV0NZjf(zLj*Yd6%?dB6oq zD+qdd-hC**qc|M z*)+(FWof?-cCt#E3?ks zCSEw<=xyEA^s`Ab9L@v~z`jOf1l?5$^w;|T?h4D0Y=c*afCX)v4_JE?ns$0q^og9k~_I(V3=^n-7|wvTVV{PtfbPD%)V z=+^$lU`X<*FmBFJ%a~1Dlf_o3O%Ak29-~m8jU6d`9}9{xpn#_m@z7ut3E@2=i4gGZ z`|v=Z<*C?L^m(O)Zo2?Oq+AgX0%%N2o(~Ox|JsM=H=x?W55g1_wj)GmX&R0H7r7M$ z3pj%ND)Iwopu!m-HMP64jyEbYAo~FGo_w?our0^MrGJR@5N6C|i<H4BKzFelXx8 zDO${z9ITL2VKFKUA-Up{Oe{73hFl^gGOU;u!jK>z`(I|wF{CDOC~j<(aI3YT&j>Nx z*FZRHSFZ)_KI0uIaMlIs2D7&T;vnMZ+s(M7S2-5Jxf-yXu-j_eolX`~o6V7awZYW6 z*-X?nxWod}C~%@l1yZh%omDN8LG2d6wPEB})}sRHj%h26 z#xWSm0z2d$ zx^?;L-CH+r?C$SxR)eunEZkcEAd^X_`(Hl)`tpcMeFwTKtik2^0hd!rE~Q;EI7S}L zS=A-Yb4FQ}aw|<6eA(4|qu=2Je#-!OLZOq7Cd`CT&OIiy>SbiDtaRabZsjqlmfd#d zVivJ~Fdn?LYT#-IlWWa*EK9sw?zW~qOnt`fCOPfwNAJW8eMxp3k7cj_e7;+6G`}=C z?+TEl!cxd2qUo4)TbK0Da8V;aRyZKY0d5Yw zEiJ0ZhDMxvC2T1QP1Wo$Uyvdp8cS(}2vQ|DL>!nD(IA1ukBVKoe_@A7JM3P>f&Kw| zzn+hi?obs-f@AxOZ3REy=lyT;Y3QAc7r(e}_gFb|@xuA1tcsI-ivOurJ-KKM z_`!wVPB)OX)CynQ@;BybrK7NRcJ$8SEOj!BV|im>`SfI7UviGrTz z!iGIO!ZjC^c5M&p6Ia_bsk#Owb__eE)%cN5$E(NQ8?J6`O>XV%+`V?^+797ajMrbk zd<6i%Gyq1{H95%+*ci%fgWI#%kj@6!2a`uh!)w4Z5b)7`6To>CV6p2B(4ExhH56{i zpM*1oG>sMuK`@u-Nv{_)C2NvpE`>;5&8GW=&n?%3L<>Whku-50n1D%nUi6+l1nC8F z4X-DR)+&mll~yMMP^`o&X3OL{A1eJ5u@%u+=|kKmObsxsc9ASfcEX0OBy<$gD)`Np za3H0TI_C@NX=t$K&h~#6@CCB-N$QmHBw>{lO35&qB0`sbl|YuI2+FhyfQiF`2H%`k z{7T z17&8?@x+>+;y}aPHe8s9EPq#N#XLGPlptI~8{$ZR#MK|!J%ugYYnjszC{A`jA3+tKV`s?$l44xq`>W#0>bTNs^xV{3W|VxyOA6eF7)`k z_>Ksm^!n^1&S|Xh3zNoS+}P`jqJajBeS%ypNtl0$iDuKqTZ@t4=zQ;h zsk$0i@79$8og*e17x3zh206#E*o_PdEW=m>X#-^Axs)RnW%Z?k!7$jkF1-xMkkL1} zB<9tX{Va~6_^h13@*H)3bozENxYNbiGGz@el(MYK;H&%oUza28QYXoybU5sag9Y+k zu+NDccR+kr#4B)KY8qnPf?2c?V>^pzD3uZb?sg2y{X5&8LXUJ)I7So!Z6Gy^QrY!2 zxLzb01OKsSuZ6u(nM{3oDegaZ6!n!svmK04GnG?yqj1q*?T(#0E$Q;qu}-Fv-6Rqv znDV{({M0!$8xkHV%hSkL*O%){QNl-ixBH&&tYkK`^`#V>2v2s4N8q9*RfV)uNl7T* z>+K6qf4DPf|AYa`;EC#|TU&e2o_@P~?RuwNiB3G614|F9qQPZGyAnc`5%NsV$q_8m zj?`9fyK(f~l*Z4Xu|WFkdzXL82W)?P>(2UTM^EkRpiiCpk=J&I&&q}#Jo?e8{VSCc zt!1%%Nk_F3#gzsbnG#~o2aM2Z5%GT zcm9I2`d;|*<-h;?{QN;OwBG>ujcZ4S1;8IXHHf{mZJ#a|J{zmOCrQ?-QR6GmNRr(8 z{E{(XoJa3GtQ~t{09-;<{g)5yXlJ&!HvVM~%vJr4Ig5}>xOV3n(m``2wTZ5$u;v!S zYCp2$FJSpKHvh1bS$X*E+Sfa=JIAiAuebB*-{<~Ztu1^!w($Pz?_b%k?_d7#`aOG5 zKG~>NA9l*VFsO?cDZtoR=3cgaxQmFvYPn1fLuI0`&U(VQdTBjE?5wdQ79w&rq>ola zblC2C8$1rb5R|sIF#t1T_J+d&`_RD1kd*yz3t4o@>wHESf*CifnW0ot7IfGZ6PD;Y zI#dczAc8gqF6otFY+pE?4jTzh6N9C=jZ)!I;ZS2QHM;L?O-&*-oU zils!BRWLAJoW?So5W0RxG17El8dN5sva7supslU1i@2Ir=tf+bl!dPLYPy|t30MZH zd=Ee^7})0H#)}Ow4Tba07TgZ0%gE@iow2+2-*(bCY8wGpC{7?pA`-eq(*oVU#%$wl z97zCg(jWgureGvf2C40ce~oC$i2vRYBzQ7RX`#v&eyf<_n)wJmcv!7Ci6MFq)7`-vE&tAhJS}J4jzadnIpt8=9}Gyc|1MV)Z9xu40|ziPICh^b4!eo7 z3grx$SDXi_SnhP2jrNNe4tBrggAH)E9JqWicy?D8JH_IDP*#T#vr|b6#+9K39lokD z^VO9c6dXww3h0JQ&bq1=q_UkPNYK?#t%IF06dN6UzzUk2ot;&}GnvrRLc?<5tP*97 z?3WOt)0%RrSO%xhbD7o3Y7BkblUoDh6!}hRY&|k~J(i7aGEEK!qaQpRJcp&oj&^dT za-+^NKAWlsez!9RSWh`wml8aT^U`~}lrlO{SYJ0x3O4b0&-e5_7Qdd7NLv*~PtgL~ zkA(ejEsp--BrFx9?_o6n8gDeS$CO}a82qF%QDe;Y`Kazd7W97N)l|0!NzdT) z+-cYOdmKL8jevHk&@LtG_*_@DHFx^i&x)|FBpw`dgjZ=*nmKD!JSLvo?Kcvj)=(@j zC=H7g4pc^y)lFQlEdT%@07*naR1;$cu0UEuq~B&mP)a*$9JN-fD=kJ zzA{odhZI8ZN!O{cp%!3mscSG}v|~Zg_ueQNwjT@tY_7eXa4r4qD7*xC5 ztd`N)@NHR&ob0O4)BEBqYhGtbLU`3z!W-bVn-dRBOovOjBBX=J4!a6MjLis2z37?n zctKrAF79ATf7$FT62`HZcBO>VLSiLxXek_4E_B~SskEJ5G=AGx!eW$`Hy8~x`(W~) zOGbZjCE+lo$3+D~ZECrQIcxp4s^p z@}Y^FcB@3&wIeBrGAU(MUQ%d-SJ-V^w?|_YpN{+6?IhnJlOv%FEauFK>A1l!{vtB1 z68?5P`3;d-A%8L%fxbd`Lv0z3?5pA?ctMM0d!ArU|_yi zehU&8l#7KWILif6D|=HiPG(a+5eS5#sqFn`Ff~u40ZmAmfl4M?4{o|CbSjlm9}l_D zmCSP1$Z#fBU(OnjTfU!JU5+Uqx{`w%S4gC^3$aQpL+Njh8l;SU%`7)oiJ+uhce!Gy zTWQ4VN}I}&3Rx*Ox*5$B^18^#^2$NqU}wMksN7ux7rXfDzJ1k6t{k~73%-lp7Q)8L zK^~=(M63KrHNa&N?S`ztWxzMbQn-<`N2ybRhK_mRW5yuZ(BD^;!3V1NEhz;gV4 z=bZOE?|HthDctrv?9W^kUo#wzvTz?0=gO=Y_kPydyIs%DMD5{N)E`M$u?J6uhDhe- zDZ1OJzgyw$Ek9nd%d=qG-d@YaH`=cCloe4(ZBAr_6Ioi@<=)Q(&k}Y6R0#Ur35r8l zECHfTYR{=U?(IZ)DcD(1#C-PgbL1+5+_881($cFBD#w;hfFmR|TtA$)Q41n(u zOBivruN}qA98vHQ4lI^}kz*@$!!(;kh-LwwTDL_rV$yzP#HwZTHMW24@W=?NOH-NR zw>DzhN-G*~^GH!q3^k;+2J1P+tw|P?Fk)p|Qd`(AD|8u!-GfsS`X*?jJ^mkES0zIG&O>hz3qTD1b&7? z$)j2beiGD%)ZjfZ1dzfm+gqMobgF|b2CdloX$Zr*zBlQS6Aj{axn;3n0(NHZ1#QV&oczd zW5!}T*hJ&qxta7T-rhM=VWx+Ny+j9w7!mIZw3Tyd5Y2=~zR6NnJql z&|Ume@+!}J)Mg>C8b91YDtzaN)_B;7uIyNiy0-$%WcNElwCvDpTI#iLFX9G&p&*np zSvi}P2G4GPI6jRM#|!T9I3sIuLJ(kAv8ubQRHR<%E6%9TT+Mq<3=VJkcA(R1SCj2K z@W6imIPLrRT=i(YQXY_QyGoaKJ<%7jnD6CBrzYH3xpN=4o5s8y(R}iqMdO~TsCe1Qo4PQHXvZq(<4$j}6`auQ! zJs9P)H%UVpZiWwP+Ivde4RJV{!{Dbn{1nx3++%mx|G#h8tFl6?X2oS#r*m^8c;$q` z%JB~btrh!?Fb4Y3>5H+LGQZ*nJzDNPe_R-jCKuX^{iVcp;lDCwmCFu+wWyM~EC>gi zz(47Ne&#o!k4xG$Dk)?@t2m?LWw?!^if-N3$}A8KJ!lF%>e2;|DM`2V6j9-EI_NhO z=_}us(iuvsE=ffq-5!F+kZb>%0^k1MpG;Z5ROaC2#Nine(#-bWtERm{t7@12{OHaO z3rby|0?f+a1aI}y&(4^vUVeGIezpnfcn<`}ChU!?heOwrY!>g@slWd8(cqP(rL*~M z+T^2n*rak3lV#bN(VdB(ZGT}KLg8(BXsa*D}8A%s{tL5jY^$p z=fW}d41}N9$8E&#l$%5(({2;l1$xtXnim3A+xn1g8jpU;WHqX3S>L0V?bklB6n$Cq z;3Ch*eFglg$W5gm*-={1En%P11&g9%WpF@einTB_tcbSd4BrHl^`!BNW4~ml(2>38waV+32 z+Jg52?a_djg`|eFuT=pJ+z!O-OMCkhD&$}=>W3K(2aBEH&5J>qpM$NN>O#9>n60E( zt~CmGZ}Z|s`v8h|RC9zgR7K<4G->XLW^t{^MG6wjKAX}PTg8CxSgB^K9ANC5hPVM< zaweCZS%pfB7!VMj{YV6?_urqJc{iS$dzXfDHvUm=Y-W|E;4u;zpl{5PRY(9sLHEEr z#tS&G>SJs3@wy51+S;^YfN2BI7rYGL!nE>y>(gj&p;7-%gr^%%$sCQQ{khqJZq(Je zZcH}^#LbWf&MCN9hJs6D5N48%-};*B<+%79vPwh6qVOG41d_=ybKq(H+>L`_Z>Z~F zlmo(SbmB;+E6vU=hs2)bh&a!vAf<9|d2ePWZZBkZZgnnqv@vvipjVs1cFLWCU9aTq zg{x+x%fH+nR+()=`;fI^jS12nN&kywnX8>nLW;Ip^x;Q1*BLqFa&w<3(b+D$S`HU+ zhz&UBvaSXechk!6s0Q18k)!_6VR(_64?~$mgDI5D%0bc|QEzzw9%b($)vzN|dr5^o z(_Q(U6BE4yCtiQ^{MCQI`PVmJc_U)0-rIg`4GAHB_69C!mvS`hR(pTm z^X94VldyU`K(up44|@lkGn%Iizf;fURyM1foAjSM?DfgUOo3ObRTplZmOm?I7n^i= z7^K)6o)L__rPI~1gHx{FWeAM)BDjlAjL$nMX3>ZS^e`%YygaOshB9eLcESWaj>Drr zVZu6cJ+TXT;)M@N;y9OPUr>rKW8WdI!n%2FzsQpnSM74wtsEh){ZI3NshO3UGC*Fq-S8-vE*vrgj_fBdH{%wbYg}ubZTh#4oVMrH5A4sY4`#1L-n;z#>cN>K&xP)k z4%Uxe7_4s(xipB`6T)CBwD+x{p%We{)BVJdH7fmoCG|*YNXIHH^!7Vgmi@$)``um9 z@z(o|?A(pQbl}mg3&E+aebed^dj0Kxnl9**Jl+0^2aS415VDct2Iag82N=p~@mC=Y z?E3~utGgScHg?+_#iVvn`*vCeZm9r6cLm3j2on)Wh@?q&w|A#&r z*%7s;!=iYI_uLX5v9natf~$;x-k=T+ON?tD7V%gZvyz0}d8+&FI&^4?VyUY=Eg`S7Ni;sJP}|=iU=2>09xHpvz8qOz@CBCr zK)hWBgWm;k_=4cE{P&0hh6YF&FjX$G3~c|>d$yW}RmOTYi;>-u8ay3c40*VHzS z1$J#=Fc`Qt*Tg2V6(9!N*bP&YG$pXHWMqul8Bt71H<+vNgf=lDMUgF0Gz}zc_<`*q zlTb>cAdv=bd)V8a_L7H4t<);g*h3?A+1~e^^SjQ{sa+Jo#l8^RL_YU?-}&Qd#P-f^ zov}8e{8zV9ZN)^RMyj$Jxe}H$brpT(v7-GH2M((aUu4m$7vx6VjRakxzXbzBXDU{7 zdoB`L6zc0m7h$e|L_c{iKP*Cnwdj+#w8hBcVMO>Z2r)#@!ig7+bSYQLMM_5OF7Wy8 z-Pm#t%ikDUk%SH>lK^3q0}G^qMy8>-x`*sX;gx12)v}L3I`O)-B8Q)M%T($rg- z2%K8_Z!%WO^#7`wLgoHVnrmURrEp1g44OM)LT${nBykj-G%FC17%gZk|F$5p&u4mv zlhAGZP!J4h*0@|NRQ4cGP7r7@+r1bx%Lo%D6J{kZw!@6zxTvZboD^(1gYjBAhwGHI zyr9OrYjc28miq>s`|>K4jAGI5o$;PJajPw>`j!$$>0B}5i^wm=?rG7Y6Y|3^659Rb z&caVGtowAd6+%0Q$VEh|c(!WOxEvtzDn9FX&aKOx5a~G@ETeCydL{tmyq0h>;hFj> z%$=P~*GMpJgG%S=M1q^$tn*J<*pHmy>yb)#%^3_2Upe}nyD2@%mWIE5b$tB%`1plT zW7IDtcE3dhef##CYwMT)x8Ya8?iDqRR?4gJh=OB<$0KSQEw>@DBYbN~{-+k{IfC6+ zF9;Ks!(3W8E&zB&t}G2+TY4ii#-SIp9b?AhiFmz+H+FPony#a4)+`=0@s-^SYT?V9 z;%Ht_3^^VTPfRH3G=|Uuz?T-jZ32xXtbtlTi+qtx70Po=jNB_kI%n9JkgwMeg47LR ziHkijI)(D=794v@_B+Y+C(L=#oP^ZqF{W4o^;mBZ!U8#9HukB6k9;WbwCCv;&yam3 z4EW)fzmU(}KNWa=?3s8UXh#9??Cj0&Ts?pO z%=&{LoH@6;o5?@YH1C7z{k64ECi6X;yVdHZJT#bh^F3-{9?0hrp&^g8%-RI<;4$WB zM56(D0itCth(Y`F0h|+%3yboTju!o|2br2jKd5M_>W;Qw8(7bjqttA@Gy(YKr~Qob z2#kRNqtB)h$r~2iHg>#Ih?;cR5X~XCwobX`TNU-4hYZ>Q!IYxP^EhPvFJ#gd>ZAp< zCNqONcGz(TKr1DZE%? z*I-}YUj|_VM)6TEe8G@JGks$KH}tmmF$N0}&`?GX_Mw;%k}H*tCG@x*aUQ5!z;>96 zVDu1j20gfn;En-CaiEM4wqLn@m02CV*w!-l3Je%57Y5%ZbQQLt5|}uYBCBY{1RU9UYK!b)$=+3o>Xo%ah24JDOHH zn$E%}ywb$m{LBg180J;WUg$rt%rpwn*iO z`HUjE84UCy-HoK7_4UQlF#l45g&{QmK>D0qj=|TH!nSu@h-Zp@NGWy*suEy9V~UwE zN3K-N8bULLQUzbVHj?Iqx$;V#Wd>m-Qx&tCPzkY8^$;u*omK4gGQCC14Bf)One%YY zp?%O}FD;{q5GTo3OE4@~_TmIyf6!E3QF`Sk1NJL9Gz$sYq!1)5Uo<7s@+Z6|uSsrE zu3qlx_I7J+@9}^W z=!Skc1MIbX4Ww=$Q3g3#8yNh^RfzyHAli$+zN0pC09~Im3lokfh`pRP$H{i5RsI!5 z?Q!IBfc=KSj9~?iAH2Qr|3=VF_cK7to}Q0DU_-zgwh9U$2Rg^-!|BOHGh;VYwzI%& zl+2b{$>!V|Ns|F3DF(NscUHl%8Sf~t7wu8(7$@h;Or}(4eDUm|3Bb=@ekjm-4x%Xq zu?v4Zcz5~WE31>f!kKKgt01#- ziI0NB+Z5fn=FzL*YMpWjs7_gUF7#L$5-LfA1&EQ`fn6__#qbns0C2Ya0)#Q2W}Bf) z!&(_bXT_JHlGd0@DTnh2?qC~(S^nFKaE^J%q(OfLVNWvm3JYJY4}0G}+L44J%Z=C! zYXZzj;m{DdF^X8qQ@~V&YoLR0R3n}3>+9=9M-tLDP731%M)&p!#f9Bh&Kx+&1P%F? zE+#>PFw42CWXPjrxpXBVaI$xGaA38I%IIbUO~Mwent|IM0x>w$? zG_u@EF4S<5WZNe6A{iQrcgU?Un8y6sLAMd|DW_0Oi2O-#Vu!_QvD$&ga-*G5lvbS~ zSc29b6-fyfC-=Tq8j=u8SzrMJ7r`(97chGh5{1+xc@Nr9y}))a#8_54Dvk`5We~}E zF!Dqkbfi$o6&4Mq3>he5C>9O$9odC4v!Evjk#i13M54R5L|}DdO4{&52^A}bQrr~PNC7t1idrTCzq5WI+-l7C2>5Nh7BpUw3j8u z22~CgB00>s$)GADbP}Fb3^cPOao{%*c<7EVSHem+2W77OH`tc920fkHS-Za;^W|cC zu4pgJ%rsm2!`QaMJY37=?iqr?*c4ow2)(O=9W}WILV5lE!ULFE?VJ)Hn zE7s0}V(WN0!COTO^OvDdA~ZcuKeZs7>pB*k$v1PfGo;u`>X;cG!0 zAqtieDH&i>eSL4sRYET8ILpNp6Xuh=)uAM{%&=1^5;}|F*-8CfNG#^nPD1bs+j|2Oxfj; z{UkpY$Vba){|%L4l#=IN&M1x67^-{)w1K{Itx?XDl{Yv)1f$Zv?GCOqb}h!{-pShJ zqe?Y%zfx6Y$ASE(|N4jE@5^ENnM1q~0RxsdOx1zJA+!)2m!q{|9tW@zVHMo?AGWS8 zwyFD$lK7*(G4=c*Td^ICt#Rlm(cI1TA9H#Gdxl2Y9H)!=_4`v^|0LzTY|jn?NThxVEpc-Ny2{ z=l44wXraS*uAr)LV0;@x2P?D}d*E9F(N*6qCQ!1>&}J7bmj_nSAc$4(vK=}rb}-;; z+&2tT4gW7{6qbkV%XWY+oJ=VGg%8+=kgFjWjJXq5jf5>guN9HSKTKz`7UO$x4>@Gw(k~?~6 z_?DV_2+-muiV-xX7aT^@1uVxPCV<8nzahqw&kxvd00L+SbXW|i#ERF(07_fHh5m&R zTM+IegmnaM8Ypoxz#Cc~WmSLuJe_ z+h7a;UjtU(OgZ=I z*Fwf@2%4?IrL|l+#5gQ8>v9ZSfzK96Q)~i8-5++sT*2k6I6b7%t&bqu^5__Za27LJbbI8ac2CVCI!#qccdpnqe6O2rz31!zzS|B@9f=k_UgfGk{<`)Ha&(|NOd~w_uDQ zKZ8utXy>j&X|Btu)49MWi$ZYm*VF4PDa@3cTHW#Xqoo-tyYLbKO67D)e>pIWO{9qm z2(3Vj=h>S^7Ko{oT%f--d7n3O3^8$p$^@IH&{+wnn198_1%fX^ zIZhqMD!GR41#@PpTlmYlJ#+eW(fsnFD|BxZO!71U`014^zkh*e6~esj|A7eWwO)oF zUAvmHC~wiCw8f8$oHQ?~#EoLQcwj=>muaP8S4vy`!K0`9$;@UF4c06rOrlyODIZON zV9qQCtUdq$AOJ~3K~$hO1DT*!)*yV4lTOW8K@OZ=4+PP}i4pXo~TE(e#=kUFC9ggCkm%Dhajlf(n!b2+c1{ zf*Gr{4f=d18{^N$8yh?Zj)@TH4W>DMj!wP?7s2z4O&(W8_HsmpWC04to(ul|@!!A2 z4*0u&&Of>+aQn;8Fn*S|yn3>~aC+xwzgT_i9q-S7a_-vktHYkZ-j}y^;r9LAdw0)_ zF$*(=fJ;n{>5bYDl$_-G0ZM+yl-!HST`5!%W6n&a6+%K%^Nr6@%ETr@20AbN4w;hk z%M+eaql^)^r#_59__mw$VHq=8}g zxSY4_?#wwre?6{%hrzx>k8QSFE=CI~E3XZAxrT?TwjpY&$c=@yqNWg>6sU{1E7kxj zWtB}p)u-IVU`*)FS(aly&u|s~B#+O|B0~F?eVB9_s%aqYu-zpfEzfD~e5<$|F8O@b z7Us>R(w2Rzg|-FShx0&WG!X)zNqb3|RUC9HD|bPs1wAxkuY~4ik-z~w&LR^lI|UCh z1F}jCDhp8QQzC1L11k$@3NcrZm-4CcU&nB(aw2(U1&&KDxF zsR+slF{F-UV>jJUG&_-XrP80BkWdSi?M2uQ%s>qolAy%8gHY&LOi&lul+lP_GY&hc z$3iz!4>#CA7>&5Q-KZ)^im-Vw7RUCu#|~hucf05Yjtb?)`k3t3AM5!eQExQrkHq8M z6Y+T5@1!T#je+wC^ftuNO?bk4!jGY}SD^UNGEc3BS*d}~3qBT9=TU}b!-*T#z&4fv zGY%ROY1KvO!X(;dL(viUz;YSHY#OOp0>8F88wi6z_<)52BNZCq(2mC=!9X1x7uBzF zThlDQJCcMISliU<$mknnMxrTnDcF>Mj-w{~k=TP| z0+t1fPaW$EpBVO? z-osIo$}TK`RU8LiVdm=!^19_GWia@7#IuvC9kq1LZ~_xokA}A^7|sS=Hf=NDah~mF zTUw>FzI*Tf?d>!3i^W=+g}C%og~QWuB_Y=;%qcYY$O7f3U>r8XqmkX(j_=d??k|5X0@^NSkEv@qaT0KEEt40!#_l2rz5Wo;b9Kr5qBy7;;=__aN; zRS;ZEAMfk*u?x=)g50thxtYm0l1Qdp38G^pSWh;S%?w~zM=L`epL1=cDGWGmQtE6X zXyahmOjVYtoJYXenwmOK)1hRoiY?Eu+Qb z3VX-t{9T|uR&WNP8HkoSIjiyEN@E39Iq! z@81D{|M205zxmHUQVW-jlOG(qXhh#R`F`9{9qxRSYFv1D&FDPZ7K(d$eBu1DV@&o? zJ%W>RvVbfQx{y_1NTb2R;zol>AL9*n9$HBoW9k%wsa%tdF(JDfNRx!zS^kSjdIdtq z-&GIBAKWizC93{tf#Fu;@-|S;a0ZNDJqk;0T9(G%mD7M{pQI+)lZ0nJ@>Rd%@Nk7E zYzE#UwEv>^m*E>O#5{YTyzS(k zOrT4i7J@hkvI5b0*n$z&fw?p^SAy7(V+qhcA=G9kKz>`OBNR4Vf(sZtI4gjf$O@6p zTcI6=d+Aw55JQbL14CO`< z20k;g((m@)!R(sRS3Sl`#>jZT@ZSLd%l&tv@EFCqIA_M9+a zvRW|QQ0a?}0^>^RI;B$Gs$n_>EFkA`o|=>tQ#x;D#6=7bp;v`Xa=HwkGL zvz&gqUaX<0P)O+HHJu9dU@{PNy?r}v0tGQzK5SW#<(16wo%Wz@XxPGQN%?Gy+@<@8 zvSn(exiU7tUJGcMO*wUQq195p2nvztS?{^CUa!|Zm0u2Z*1vr8@b2~vlPYUf0322U zlqNUAP-*eHxs+eO(b*b3J{At|RvWe2%%YI&Z-oIreR}2B-@jO_F^_UP`oWu{D4~K* zjUG_o;=bB>Uu|XmSz1aL_sa+gyHG=0uHfnP<^CpW7z{Gp|M7KxuWjB}7_WZ0vSdtT zArVWeV@bB8S+=mjN*r5~1-@9bqSjl;PzOVH-Jn7W_6#$F8oI(@1RI(XT0>ZSQF@V% zu%zIYvYN4E*+NpU73+$!%e5amH|{ePqB!mKEq)l$}Tg3mPW3eHRQcbpT`;WSQ?m z7||9RR^9LjOLY{sU&TgzMKl}bK{_tnJ`rhvT&pxq@5dr01*p+S>&`A9Omez=jb;)9%ZFnM#SeN)`&u0v;v|RXCcO6h!ge z7O$cV?_faEXMgqd{oNRr%@EO3iId-rM@XUMt{O?fgGt9wI!9tt*lU=(Nf;J(qj)rq zuqu2qPLtt@5!v`o1guVly^9d5Q7E;u3GT+jo8t_lL%4hSIM0&!8QqnU-qe?_h_*jw z)r&wnCCRh0J1_yW@lDME!PtbOO5a%Jp&@Z2ItTV{rz&bCM2Q9N8k9EXqK3;f4>nTB zo7DzPX9J1PtJ?;#bJ5E3whT%J%Z*hWzm?LL4TV296v0uclx}(mG-@q=k&}fCx@7PT z3C6kv;x0FG*oBFKZj_dTAgr6q5a4Brs*Kf+nvrJTY>U%`n4iNbbZzGG{mqvQB})_KFjEqBy8Xnwo~m=0%24 zZ{_pT2k_i?X=A_!JmLY+Sd@@TU$9pto`cBf1AFD^iD%>p-`vqzOl{HQiSXu*vt2bG z*~yJF96~F?H+Et%3`pc(fyi+}vJw%wj$#@)!-r{~gZd(q29bljjlMD8jMAYc#4=7? zi>2}Z;yyC2n<0-64N7e^Mt}jv$f17qM+uJ}+6`JP*RC+s?b{74P5Un&grtGT-R$sM zx0>yi%jmESh|5fy(e@evW~SQeA|2j`@7~_e?%&RKQDWUTM3Vs+G$s&>1WGUZYmq+b z%?qCFycVdJ{ee4>R*v_M*8(%rv2TH$3qQRh*8bO<3fF=L;N88z7`$eufPL@$)!2Dg zbqh+W+|w>P>t0|t1@9Sj?*?Dlp5ig*X)Qj!b5`bFF;9fe2FJhE?pJzfHo@nfWN>I& z3dg7Gl0k`UgZGo(^Kkh=wuUxti;+e(vH7c>zDCSYiz-Z?OW)=6fH!@=kAZ z{e#>Ww+20Xu>Sk6|NZdcn{Ph+<-gW7%3iN@CR|&p? zw<_hzkgl%mDghKRlB|9U)ZMxXsjX${48p4BfVSKj39kyCU0GB%2UsKr@k}S^*KIqh z9d(?%l68sC=`VlPe}DSo*SB8OdiGnMJMBcZ=t$j>DqA64^*X|ADWlp2Z&oTOT++@8 zPK*g~W_)bmI2ce_Y~Nk8ATEvy`>5kr*tG_|&+~P<`uT`v!Ol^=j@;SR+jVa=ws)WB z8ZJUSt#7kAXcmu}>JR1>4Y>#P!9ed8B`_=0+gF>fpZXrR-7oMCHM1 z1Ww^vN->E}g;(V^8b?pP&FEQ03}HM+sc2Z;gWCqPsU7k*_!z@zY{BnE!A!w%!yuNL zhB<1Gwvl9Q3x~JoF#ReOizH}}cTNawh+OeFNG+dazFf#It{evbrbx9bHB0xiv za5`eYN09DCPCUIOpUmlT4Xb1w*>u&&2xdd{IPajPIrmZzG1jeY=-F;esTUmg2r3K1tD4ud2)ZGhe zg;q3xruvV?Eb8OOx~o9t9N2qzkKcbB0sV*!dj!@KB=&!&#dx1i0&jEdJ z#kaifQQDKyh~&$Sd9hyJxE^aoz9gk}Y_wLS*|zt0?O<_i4EPeM_+V(^U~6}^J|=Y zn4V_RmE_E94}|y9;W1SPGG!jSw_mH>XMNu?x)<3U7#&|{_p5F3Ix}c{^5suBSY_;> zcEV_dYaZdoGxx&1*~1p9E>LC9QQt2{`BzeEkSacLS%&hu`N4Y4(%tpKMb^4s^heu@x2EZ=~y60 z#9_F%`xdDD)%Ui_z@y7kC+s59SA3-@*?jF&rtzcnIIJ& zFPD@uubKlGuL^(zAFzF__;HazvfM~IRVam{t-8g-J#qNXnj&|ZZ@{;@}3?W8mV~5HJU>j%OXE$I*$TBAxJkvGE`WGyQ zJx7^DBfX*$C#4`tyulG8NfDX`88(lTgOv(}Q=57S&O(npB@4ZlA#9k$4IIG~d&bAb zdI^5UXB1-TyBe*iu8{1>ZRXL0O>T=0H|StM3!R#alDZLX0LQD9hJi55HM(jLJhhD| zi>dNli3=7MR!O^Rs0WGIXF3>`4X3B<4;G}UIs}<<2eTb6EpN++1lUpxTrs-aNKP$~ ze5Ls^sw>9MxPehxk-{P4Zb>etL##!)982RVWk4ge$}K0~CG=|Kkd!M3GA<+hMmg0F zlE+cP>YK}Xpyc7fp}K1X%>NWnA0a4_^XXq+ z=u7kpd^i$Hhmm0kY~whNVwp%p&R`?OY8s4Few09fl`ezCbTrfqmHVn@80EQXOrM#p zjNN<)=!n6a`?XAWOI>YtYqAGb<>xAma;rK@lMHfb064?mcZmB4p_Sq8{c1UTeb}O# zr&^X7sa3tExDA7oR;zq{e!g`Z&(Vg_UIfu>eU%5@-Pofmc%CqhjoWx_75(h-7g@YW z^O$etJX-SwuDv-{$W@@d65n;~4G; z4srlfLcHrmh%G~0`XQ(%#27_Q#IAj5^DTSQJQao;$9HDMaWA>bnH*@XfX61?@;fP8 z(h`|iBx6l#5PWIUMbKlPSNFTwYU?(JqpoK*Y3Q#*4F2HSR&6w$K3#V@ZCAgurWlT{ z{iA1+>2?n|q-5A-*1WQT@!30FqsgN(+tkXcOyX?d8ZbxcbL4Q?p$#q_OYGRIaa`-$ z4~7;Qi0Z?dxrG12*V(-`m7rnVG;Qfg++uo6*S4{yO`F7|DGk)MHAxc)ES5#LY?-Aj zGc=`BGK&|LF5}JgMi4|=a70uXa4)=a2k`?OaAsuo#{C2KX8(q{64t+9-{13|R2_!( zvpqRUTO0G7=Y5}#3x9a@$vOk*^)r_gyg~mFj-)YJkeXF5BQ&5IQ|$BlUoSuZfnJB| zf_%W=e*5#k=|(d627o`@|GtOflh<#a^+EFTkr8d6btEs&~`x2=`IIy#jv1#%WYCRLuI|?I=OTk0JaMWgH`6wmz1rcgh_7& zCWFIsDh0-}|Bk6RX{+<>f*%eAyRU4dDCUvY^gVO6M`{V?dE~dRUdPTY!SJngzAW)H;rCr z4t92?R*Wwj0mdlIwZ~58AmYuNd_|0xGY$K#>O#BWT*iBW8A%)9mfe(9mV=9j*0saS zhqYi$nS#TycxpR7v`wxrv*zug)KA+qBw;m)#S#M1wLTRD!+;?`3g$2}t zLZ-w?6$YZqL`WK+llhWmc9_YgJP6;?vpdG(?XfW4$&5jUCeM2@&l zOUN2bH-oQ$DP2e;fZqY_e__Ho#93+9#9^E@SC}&jj2b7z^$X_>Fa|?{H*)E2SPTY~ z&DRYSOKHR?eWlQ%&8=ljq17pNx;TCfb`7QtnTrD4QGmAfSWP~4f{X1?uF%%<*H|3x zqAPfkC;+AnxQ_U$H8)qQ8}?!b#%#nC+L)+}w|0P5B-Bm2^=OmZ_VkRy58^gH5eT#po983_)GS8kzm z%XN#bS9QbV`Y5Smxni*K@G=kePYI}hoTGtR{kGwWjq;@?2b;>bf_qoBY<^xd=;0ej zn0GMo^pqNd)laN3bybNR3)i`B^rj&+3k_Sftix zum?+aO>i}X?WS9W$J80jxEaNjo$%S)cR$;Yw_{@-P5J0A!rTw>*D3IqCvRLYN0C?V zI}*MMk3E1xo8hP)_|#DxrHn}SmhSnx!<dW?6_D@{yg@ zm}&R|*5$;?z$jIQjujYva%@ju~@%0vamnFC|9pYLdX%#0dxTh>>^2hEVYk(iHc^_EDF5HX87*(bUtzbqko<>hRirRNm2*#8m`GwR|9G;*2MQ% z1y36i?VU!qMQvFJx+RGiIe+-Ne!SmiFvYS&Y&#Q=#le?sf_)? zbRowYEpvlmIUR(u1P>y9&Q37D&Sr`6z>s9ePfU0k$FZRYhPw9w-$Wvopp%lYaP|G# zMcdH8gEi_p41Cqhpu)j$$QQtd%gWr42iRU8*#oB`zyp110yf%0A%n}b!kirm43C2W zd%+=WfmG-)NW*_21W2-qEyzKUE?`z?X;lKJi=8m&1okS1{Hjo>8(T15_PARx?u9R@ zRWBM}Ly1dOAvM4T!^P1nt-V5fw6%w`mB}-E;dZMv`k1Bg=;P7W)jCcaW5ld}uhM;F z5Lai@YFu*H-d$4hLT_hF>c&zpJ+gM>`i%@n9`$_KONOrfvY)UvSNkZ6BdQDDZEHB~ z?ZKl_GogPJX|+_1e}XsAs>hQM{@M!~L~WW}*>QrI7saRD9YlakHXI5R%o z9?P9w zURaK-!bdW#hzc)X-nHwOZYO7~mkOwKp}4`0J7lo%%KjG^9^X#e^P8*9T&~j%HafR) z-E}vDFsvB>S4rGpu3TM+La;8$z`XA6BRs-N$?A157+f1flR>#oCf35j%fEf`D-NVc z1^wGUZ@oUNAgqk~aWgUid(ohaoxx=98W7%o-tY~ne6>?h(K3AsPL^F`43NQ*DHfuC za7LlaE8Z0DH51>1s0hM+ zM&j&IxU{Yh;MT0G)dP_^m?Er77Y$kwXAn}Aqtf3^M%XJ+DCLgk?;^L{bdd4&b%y;l zhOJCyrcBP{j#9Bz>#%d~TxRNG*&cCa>YKNZ?yx!+{r}_3hwVgywqKW-zt;c&AOJ~3 zK~%=ZvX{uy$);B_XNWH%s_m_KA_e_1P<=4uXELx(L6-kzu&sKelyaoSg$d?J#fM`3 zu?H-9#d%|11l$i|Ux*DE#y%kHDz%;BSL#Ba!LP!gV@REc4SanxP5g%aalbz{oC1J{ z@%bA2O(BRbsdum+!BquDO#Ft&Y><1^-_QJ+mZOsTkM0}2eKQX{S4tH!B`fnpLC+I_ z^@d~)gX8H^5+o4 zrs*G4Cxa3>h?e^+?<=9>831gAm(eq%*u_*n$W|2A_&u~$ zhQTy4Bnj_GJ_DskM)r-sDkK`_J2EkS&mcNE!h)CS^NB1|=!x-(^B9Bq1xnK!oTa7k zS~fcBTzi@Pl?VOY901n3$G4wbfHPb)3v z;y8lCL_E#pIb_%@2^ItBM1l}#d*w{v@Wpu~cAQ3o6~r-nCJa?MV}tx3Y6;V=Vkh0v zY%U&la-;(>eJ&O^fx6-dWY zgRMrV7=rB$gWFs7-souk7OtbKMuXe+Iw4rK_TJo5`)Z94EbU;aJQ6zAcIT9mLHt!O zRipO4Q^7+ddz}o?wE6I`_E9EuZ|b~zRK9Qo&o%E#a&-2wwD%_MqOzJ}I30aVkEHYi zOHxGR2i{#$Y9=*FVD!VMvs4Q*Xx64zxy)+)li_Gg4TWQ_eWt46cyo0ustZ1IX8mcs zwPgQ-E#tn!rLzmw)z#+0XXhGs?mYVbyVnNBH*eNPuYa?uL=PgbR;w=zn7f4_=%xn- ze)A-=uC^sLCH#-B^LuUUKErtR6G=8EvL+GBieyW+rC64*!Cqv^vJAdxvSH%Q(`E|6 z@{G}jN96@(a^agmSST{M!Ni8ZdXcLRLYF`WVT9&t*QGc6GeR54{oc>>J#q?L+_;I( zIaX3v(Q}^neSR?8zDM}<#+kHKryb?iiXUC8{^XxXRT-9^bWy;99gtIw#_a-u5(+}!Y%o@|T8qntu3?Ktu*3X%x35EI^N z4S)Cjcl@RcI`;fChrECIA0yJw9^TJ5-%;DaYJ2&Pn=QAemz@o1-r?@_;3AhBeYpmn zHU=D3@O83;);U=$Y;!AFvX^@36fqluG(%&F4!ii^lZ<pv(rk7Z*NUy#Z9t^*9&p85q|oP*Ohpm(7*$VI0&*O%;WMR#m@7C!7 z-X-%H^_4MVPUJO>28<1)vz*UY@-hn(#!<~0^wxpg<3(@ts{u6TBYSj40Ye(pRUvSG zF>H@`n3hus^|SqSR>|kj7KhT=vn?qbeFiYBj2KX9MK)(b1@KISg0BM-xNT z5wdAE#yjy?l?&*eiGV&DngE|CjQ)mY3Z{%99t3i+95H`J>mGputCWx=EI%`6Plc7R zM~c~CC#(^4@&W-?Oli+B-6T#W1KS9QOUW-5;UpbMU~K^WH5yZ}_t{W~%!Q~CVsy3i zEF`0+g>BTJ2Dqom4nh?Kp`}8x5K7wnchoDA=@i$f04|6Tv*9gt*QC5EmDavkSxK$U z71hyDkeVo^Y~y08gbsQ|rli!`7xq)?Aa%HYXwY?6j$lLF6(}ad-b1G@J`~!iA3^dd zT)FEWc+zWh*ti7PT4MmIZXE3Z_~bGxx^|gLdAUcvGbumIwA;NC!4y zC(=?lHEOZ-nwo$cDabST54DFdVA7ybUTNHn!}r$k8?XC_$@8Ei3FIAHK$<1X?!v;> zS1HB^2X>ni9oZ~zEr=FV91P$N8?U-~{n0Y@MPmwywu8^)0xLw5+X4SCUbhK@ba<}q ztifPw;Yov}GQyBMOg93t?BDLR#++4IIg@HBUdUbV*=qp6ih;nr+RE3b2^JVhx4&Td z%q#1&*wQ?cWo2IhxOYW;3X;Os-lWs$sk>_b(ELI++apfjY=?2|y7~X955jTOIO_WoU zOX@pla?B~J$kAeJJE@s?U-RL~vPS4|Pa?0Th;x?3nH4emFVMG-7YPWn)DO z_(lxOgBm#dSpG(Qn?D_t!=t)09XM0RgC35FI`_gk6j${Hh z3^n45F&Ku7L1`v#KhAe$P&&tgG;0^*IhqZg&q8)F^v+a*m1>am4KTT?G4vTOCHs0} zvZ}MQ43!Ot&(sH;2ZR@C304L)Jq=Za(frE5cSa6iqse)4IP&WLT~sa7BKTS*dIO^{ zCBbN~7+o8-&Qx4MFmvO@Gfkl@L~RVAzRDYmb%~XTqmPXVgR%^!$)A)W%V=?0dCy)N z7J-xOb`5+<-N2wU?zGWi=FZ1qyusNal03$lNaIh+GH5=w>&K1%UU>`wCIagQ`O(;Y zDNC{^vY!!V8T8&5&mK*vO8Dp~{0V(nc#m9RR!kwJfr!slWo?E+uwdYKFCq(Y#QA?? zA!8>>wF-FYSD~oVIP72~CSS00 zLIT!nXxk~ReNB^j6sgKux0uAvL9#v3_S66y6+WN?xOh+ijJs>}zNHLA3aPtFfi|9N zfU;7WBZ1@K;GkGsX}Hvllo|+G`?BOEiP@_f1nJ}eB4WA6C9eN>z2?;yF-@*DP7D=s z37vQe8?_Hp>00kYJcq}Ye?o*^HG?3Us$b`48hq7&1iS4p)?;wjp|VaMdP`#ul+_oU za_0bWiLi!qZ^U=Sd4UF$;}l9>_~v>~^}ZwkZHg>{Xs@ zK*(K&hAUfIXyqQw;mKhgk@&WH<)62I{^Ysw?w8*@c-TXk7weR^x9!#U%enS^O97Q* zE*83_fGmJjYhP|9bOS>Df>+?c?_&U*gA8jn?P9c^{_Z0=9DgweJasu`HoU#+Qn02a zy=to)$?@FftDZaQauY94?My!v$Y0U%mI&d-rbLW63|J#^C7%7QtH^UOxk2(DTw~ z&ASLCOe(<>7U;xX6B+0%-|@SFcGsB|ndV6mxBV$~7O! zfa{_r4LJ7^F-^I(sEQ4^c3-nxEVOKX4F`7=k>M7(kZAn@^zR)_qK&Ec;oX{x%kf*@ zQI$h^ifyoRJskc*ogu3kr_fp|vzj&jN+cHKm=rDw2+L|2+#&aCweM!sO6`)gi;;7g zrUoyKLx2y-FJt;85}IptU&3VD8)%nhdH(+04+7vHpYBKmzIyGOlUhu%8v))tBgS1u zF6?bJqyP>hFg_n~Mo6?E!Az+)gON?6!0KC|oSjCbJv^a|CHMA%sHX!LFy9Muuj~yw zNDL*RS3DcmB){qze1vrPf(F#SNWHF9Xs9!XR1F-*v1G^N@L?4I6T5*Nn*5DAba zG<8Wcgg+Dg3=qeSEmt|POC>{H(rBZ$_?Lp!nQGkFZbgTv4W5MoLwx1!-JPY0AwR25 z!ZUh-7q$7F-K}T`%;wmIZ&WE@SUj`SX@zqDv1(z+&Ky@riq2N(MmjrA8*Q%0=bO&v zkMr1!(#N22#jrIm^;LFAz9c(!#{O5%Bh=93ZiE$yH4g3?>y;PSpnFuMfy7!eqs}v+ zX6YLq9hwNc6)@bFDhBXXQ)#;#m(dL>3Goq+Po%Rhd6InSA!4$O86S;4zA`>!oEPpJ zJ{p}k!VNtBiT!`GJF);F>t~a z11IeV!{?Y#H%2W|K&K6XlN}_jrvhp8HK1{VD4@hCbLh^gy*U@VUFmQNO71V(dlA7v zMs`bt{TJ6tYYMX`0gK+$(u!g30Rc+|&UH(qNTd{IY$&X1q`SHxwK7*EgyZg97gD@7 zXUun9AWZb*3W*mDMJ%V*RR^fH-kNZ@Apum6zzc@aQY@>KFeM}%aNowD=tzXO<^ry~ z4CtD-EN*zy>VcQ3<`%)d-dxSmXhAH`zuuVh8j@r$67eR8tHwC|u<@bNq2|>Ery4!F z60spU0L)2?#c0<)Fd4nk(P1Z#&bhAOH#rB?P-DB~&cg%lRv7Si^1Yk$z%Ef$ZlgTB zAkmhJlX709*8F`f;)~HvH1J=xuC=wT!wg3ktGc0C(j;t4lPw+HYF&`Pj&0qC8I2k0 zym@Z*p&*@To?Yx=$84rhe+ihtkijXTG8mc<`IJJ~Qb-_8O+IaZVLzj^`2~BQ=RI27 zZN>=eoFhkZ96fs8_qn*IuPR&6X0=(h#7nF5nd@V;5nd2}@CHlXrnw$(L4&nHSgg)( zfS>xSPcX-b^yC-FVNZR0m8r^c|JH1!a`%hX0V^Ejl-K^Nv(eT(mcDp)ZTf-Rs)U}j z2e;Lo)Mj@BSaDmi8RlOBVTN|_QCA;-@W=lHzf?ir|CfefSty%PnX_(pXSAf@j*go% zRy5YT+>avWXRzVq3i`SIYvgN-frFSOYV40=qsrYo3Z=@&Of(0l(iir)ME zN5gCGRf%A6#kRhVm#OGYw=i)=YO;XSa;v%ARFaBQO>HYoT6!!+<9Iqgf>Ig%3`ptd z7nTuT8P|>m`OYK8WsP)jEZ7bfZM7s#EV^lduVqvzG)cvm<6p-Mz> z(+B`f4KfzIJAF=sk&__=_v?vyN?;Y6>4G)ircw*hSx|W~vyz_TLYm5FY?SX3eYvxa zTUi~X_i=8x<=(@4@xsF|uCAVc+Ha=&^22HU_=A4@_}wpB?2c+ZJ70Am1Itb&t6Ny9 z19j_{^c2B@BzRLr+64%-;0Bgg_n;-4#*(<^432}rF-FwRAvy1uWkz(}XfQYmVVF62t|^HI?bI_$Y;?aT%Bk zE^OA=k%WXxB5pa$&V|wyIocG}X#>^;dfbA&7ek8$dL_!N;mNS4`UkJNl0p*1R zZhWvD3H~CqG7(x3GJwFwxMmoV7-F53)6Hf!7hv=(>{)#Ln|0Q zuV88&y0vMu>yAQ`NH;m_a3J>^|DbYrbBc;9gmP?h>lgb-0cJZ&58ot4FHATCE>WRLb>9?*j1h z9B0lachD64ZfRVvPdb1xI#%Vgwja^hq$Nm)RxyLZJ(`GDQNd7GS(eb@VjX3PhqN!j zBaElXrecOte)YG?#)ftas=0`WS*2;n-_|TjI+C=Xq0Lli@L4&yF*nBToKS@!!OdEH>_pw^LhjO0?4Zd0_?(Y zr@a5P9bkZr88YD)t7*UgwfsxM4<7D?-HA`GGF=L-fT#y`Bu5P*7xHW5{^jFs7BI94 zz6gQlAYIrv^DL?H#yLOZqQR5rtIC6Cce?UJm_cpQJQ6Lt76ab<9{~Q#&(F>dfWDat z0Bat!7BX1XgI3^1CR4G}C#}<6K=O8G=C%Ux1?KNq?GAPg^ep5&hSyMcU4CFh1`tLY z2#7`$bU2K! zGT^a6%k0Gr)G z41Q)WFwHvv+9oapO0ql{L6QBm+KrN0F~oqWIAv6QW=TW;45peytR>c{tsUrz$*Z+r zA+D{$EgciLH0esN=qGphCIAVT8iUznSarO$j3_%HSj;HUs83fOW8G5_sjK?9}Nq__6@B2~akf7tI`KQ$Ed75Oqk* zelFD(OEo#>%%Wn@T%!EBlwDjx=myM5KxEkTGJ@)Os9kZnkp^CV)Zz8Rw9hSGdQo@L>%Gpt{mdj4VhPi2qLo3#(>u!Or$+M zD6yt4unXHY^1WQ-m66}a3bAMO(BbCEYYsF7(G3t@L5x8s*Vs4Y&MSzn@_FHKonoW$ zG#V8i9PKoYqe6H)umCsMc2tZWH`Xa*l3PuCWV;_`&_xyzt}}M>FdAin5#lf?h{oo1 zQWsc{9x}0c-SQG0S_|9t^T|5ca{3-we3#{dtN)3J1`O*gd7WCTqB3SR1t$Fn<2e|DC6{c^T7^k| zRuaxvKdeU)BG%}5JdxP5ZEkvJXRi|3?y_Q_Gl zK#w2%;`U#^T&qA@C4WG*jbMLAb%Tas z|C8VS#D;VOfPZ%X{%@#mUfZ@@zM9Bkr9)4;2rcC^_0el<8o_aA(pGqIn9p~JulbIL zDPV%WhWsU9bT@h)$kOtZ`Fjw<+CvyL<~+QMEND%B?pCbejV`s@+jk$l17I$N0nHUl zr&Z}%f@%5e&fHW%@7)Aqx%uF|KP_HE`_z2cveKOyAdwzH7u`yylS#A%rTZ;Ne@B{0 zf#4?ry=5i6tjuLnWxsC;mbIu5$gTFIi2@2^-ZZ*~z)_RQgMxNGG^urxM=ZCj6lTbt zkm#I-k(YleOv%{rswE1R?kQTynx9vgi)$*F0|Nr z6xW;%OWJLH!+wDRt-G}L(nBmaX%%z{suo`F9=_jv9WhJgZ(ig-89%n-* z-+uoo-i;J6f<8ij+$N+`4$xNUT!j%|((r5ZBFQS~@D3RP?HIE5*MW!)^b}#K8?+&x zkSb^!`ium2*|cB_3{iU&tjU#*0QFlo(q^Vl%BwbzUFa>!j{;C-aa0|2&;rbwLL2g+ z17?k}lTblB1LG__!h*m7Mqt&(NPn)?On`6=3DG7*(q^_cHU(jY(Uxn>(aKWkTxJv& z=&e)TzXHjEtPo$N%D5OD7`25$k5huo^7Bg}ej}C8N%Z2WK2 zuv`}MovJ8H9^nE2ql*v#5J2z0`(MFo7mPy!xD2hFbDaWIV{@D>CtM+I{#8X5Q2Oum z0|S(S%!r?i#e54P1V6h@T&sYdWo6oRYv>-br4oiSyH-_VZo;uN zvJdPOVBy9Q0QiQ5;i6>P%d)`;Avin*y%w#&ZpQ?64ZyB}W*gKjP>v-?EP#u_a~OR` zP(O$BaUj%T3krC8`FLn3AW4vPcQjUHZ^fK%V(Jkh4 zEb9^U?ff;57!HBqB3}H3p+MOeSM4P?Z}=g|Ul9)qfdQl`7kwuJ^`G3HqA zr;}xX*Sbbm2@#E*Rpgh~m*1%%>hxctg*ntT1Qnu{MmNZSRcD2Kt=d4|{|Lr}w z_fZNV9PkvOzX&d{qM6YIF5jfv{MDPa22v;KWQxVwcuI`nfE5WD&oP!1GBA2B=E$WH%MtwQ zH|NpH*ZGO57r_pMTCp<);QtZC@$rL)HJ1CXtzDUmoO!e}nNF>xqF2=n8ceyVHAt%0 zT1(xiSd-n1{7fUN2h#?+fsG`BR5R9Af7G|qupNcdeWNRHEi>%8Mi9EZLg0PvRzx*v|9KmK+8$A$VhjFI&UNWNOE zYx>6a!pph_N!r|%vcM0w*mZkV^QnM+j|Guywd;-%E@wWCxfbWvO z<9ozy1XLkEgad7q{=S6f84m*gMmaE|L9kF3B5h+e9cQ!_sJ{G^@m;8_PzKCUO8kuH zU$~##dLFv``{4WA7o$g*QOmQj*>r>tXW-24BY|WLm@#c$QZ00O zsciDH!mt;a&dc%uf-oL}c`~{cyoi>>@EK#}r#T?<4u;Q=M3)hRm7}%_uv}bbNg)Q* z>?B0ruiOJJj1;V$#55q7tQUD#LTYzFhp`7PA`=VdqFIczv_O~u03ZNKL_t)eXNzni zg!M>~b~Z632g~7TG)l06Z~~rS2%U=oHW~#qeiDsG)6*vb^%T+OivkBYmV^yYAD&Fp zo-{?hm0X`WK{+8M(2SG>`Vz0_S*$R@PNWl715Z)(EFc>Q0D@-_dG&*kVqp2q%>Z(t z4`vQfMF?y@xb{&G;VivgPepj1Q$(V9XhQOM$c4#(J-me8LGWJruzaj$fFznNNLT@5 zyo`0Pj;DPVv#mgmnS{jwbP}-&h5&Uk>9a;KUkDf*-F^~habskplVLW?VrQl?lsIz% z5iB9Z2;=BCk&u;aru%!0IOrz#QM&ND2>=#SA?LS#Gb7A*KRet*zD7hKwOQH6f|n~^ z)Yey;RW=aAKdcSHT<5R&m@s7|XMqVRcIf)O0%yNp!OuM1w~UHG`V7YtZp=Q*fzO zmCySnu84)c501~<1qMNKT>Q2`#}FV?m%S>B4w3;=nT5x#uQ!OMv5OYQ2N6Sl&s%{P zh?|;Q*HVS`x0)jz)3PHvo$&9*0J$edTHcBIuT@eVO1wZk*9&C0XM=t^B7YJzK~G|P zFdA9mu)mjovl3%mW{}MgP(!!Rn?|3}D@n`$g|!>yJeh;+H`VG0cUi`yzx?TwRE(*U zZ^3l24GuEdnb{w-6|+W|?S&oKgawuxaw*n$^7+Gyub)RR{#aTeNp4(?p#O^n{|P}H z_oACojpB%It~oniVY$v0nDb{e6y9~Zkr-R)#8Apjo2e9jH+@E>%4@i9ybfaqok@lb zT<>;;`=+4_ZvuU(%Swi=eg*-p8Ov(D+FWTD8XX9o?{_**FL0qg1gW&Ap) z%)(?bE*1jlWUOZY*8!(E1Yc_Yu5Ldos|HRC_J1#+`5wv`f@E zIoCG>_I=^mpyn@a>YEY1aeq7R#EL-U44j8-%f_Y|PUo8a&GF9cIbNP7?- z4Iwn>H8`)iW3q?P3_TOpY6{Tq1MMxV?CP0`sWc)eQSnP? zeg;mQNA8u}ZZ4r5X&KR1`JZwSW&v}deqKiBQ8BknWCqqQJQ zAfP-CA`IUV0y<^`2Z4E11kYa!APDQ=U>+LkgDJo*f;#4@)S6*u!_A32sxEmJM(`}}Gypr5Y zR{I3yt~{=p?DsQ$?1Zr`78H+#4Cf<)ayqk!owmy{o21mKexPG;WPM87i%@!MAb@LhDSQ z9UGBGHMuy0A&?#nRc!?l{%s33D1BOV|01wUI5BqB zSz40hy+-Ny`zRN;08Q**$#3Zho?|35Gbp(bR*6u-_1yqT#+(w5~u6r5WJ zi^YM!?6-58C>_%gbZoA%UMQTEl3mK;EWdyLe76&$_8DIeX_Z0yA^s%kWPeLuF~08x zd+Fp>QeG*Zljo^IgBoiBrQmfe`am9s$S9%6?$4VkEN~l4^k`gG_c$AogMEoV-%9CL z7vkpvQCF@uI!@{pku`_`w31-~uR@#R=)&z!A3pfqS-Ug1dBn8J#>F30g!LfF;;D+D88mJMm zXh#~MlQV3L0Lp#L-XZWen%!i$@+uYU5KA4;uOe)_{n=;l0Wc+3jdtoPiUSmwwZLr# zaoqXx{ju}=V`%JvpS@BR%9;JB1z#cL3J0g$)3-v*<{0U*Q+ zDv@@AspWl$VDJmyarybh(?|Efh%b5%YWD@l@fE&-3F!_9umCW2)b>{bz!ukeSnl;) zo=L=Dxh7rolfY4=+T{?OLjsC!T032wR)>224a7W~{!@1kEEpytKgli&eLmv!q4jdK~> z;APYyfiA0hd|oIPgoHr5RfIGmZpn2BwNv6bVx%Iq9xJF zkfZcj@HH18PYz5c4k2v*4_)W`(sp9U@iS>$5?yGLCitsr)tFopi-Kv@Gl?L#)eUbR zp+k<2q!ZEN(F7TCFrO6Uj*@~Wr4F9OZ--uDh~5+4DWy->^r8yT4$c*ZcF; zyWUu#HO6mZG-=-7_viEeF*|@BYky!*;Trp6Y-@YE_fvLEN}YvcgX$N=ZnQs^>e*Kx z;aY_Q z+WQFAXgmxBo|mb?N^7 z_s@Ebf@murJm(aIHSdVrw>n+#t*xE~QG&jIwTM} zy~O1-Nm%v~XtrM!66vN+QkGBqa`7CrJVMb!c}EK+dp65 zdq;Tn4jJCQ^s5W6n6x5S{t~m%W~EWN?D{C*<-V`=tG1!%`IB0gPN@5!^QDAP@))_c z*i$i3J74Lz01Fyj^y)xJs$5F$TB;~91M#t!RzNCEKnP(SVnkJR4Cj zV}n*$b&>i(gV`b{32$yhM!Wu&cv!7|_q_5na-X>9P56E>P(lCj{q^b}Z{kh5^7XT9 z2KNZj&T%-7G2KWao>(xD1&cLYHvY@JnPqLrnK5%nRL~o7&7q~+N^B$&Yl&!3K4@>s z$FvnfmO~7d6M(J3tw&ELE<`VE7=$Z=!*E+I!4O*1SWKLa06X5IpYlWw?;yOIq=S%; z3yFl}RhW{JWMdf{eq#3k05fN{Yp^FtZFSYB(Z*rP=a{^6^$y`!bTknE%oQAUXX?r9 zEa_N=tMK75gwIql&=yP?gE3s~gNMb5`7-+FM+UK~A{-l-b?FsQJd73^X|!Q+&;IZ* z;U0u;P%lVaG%lol+Jof)=3o@ebOIaR?jw&LPT>bOQcF0rU6SvJFs$Kj55!`H+&xH9 zgHk6U!l`{wctB;q-utVzK|4-Fc~Et~qdg>1YI{sF2RG}X#tqiI_ZSKE-ec;Jj2vJ5 zi(zr8O9AWM0KlhE#_H{(`)|1CC_k zf#Nw1-KC3=F5onEN$}%BI&9!;?3oI7@qk#w-g#mOZP@hC?4Mm|mBY$2Z^ z&>ot!L;ys79KwcibrJW>(vIOS$s5LRjRLo`C1pI@=X0!rsar74Yhb)oT3#}6%P%jt zce7%TsIeA}3={5Hf?u{(eN<95hkXgX79(kc*DO=wc3T2vf*_Y$p5W{~Ms6!|Y@TyR z(_AaiO8W*_P+bz8w$Dmp)G8kgT8@Im$(A%?Z69?rk*2zd434&pM_N|HGYp2^72 zsIEi~=FEU}T`AGEnd=`uiwqj9z5e($htAZW-Ugtyf265% zx!iQF-q-utXPmGI z5@C>)vS(&Ur|d<+>}|=$s3^d(TCPq=SKJW|ZIF_oXsQm5p@}Q1E|giRaR%7MYEdCw zY<(NmV#Sf0du^!8uu&xIvSSF^0KALkGGgpvr6bTM4W#3}!LG!{-8B=o=vFZ)&pLpWJF%xQZ(QAYtNS3x>V~ zMH5>2h?-!PEnK~3B>EZ?=Sluvo23=$(d@AAhACtiBbQ@p|9tv9i=G)X@YL{CtVjm5 z_VpJcIbU;l~nZ?e8O^a-EiD z&|-QACk(sl|8|iR4elzOgBAvou8i$c zOc;%)*TZ4lz9e8}j?+rcQUV8I8*#ul64{EV2bl6B0HK)U@2HhuZx)R3 zHw%a9g0W#cxoNK3>4?_CO&Um4{6z*Z_dThM(rf){zJ7butLP7-5 ztM%Hgp8_y>8`E{!f8|1&CbUE2=NvxZHy{6cd;9++QEva@_mi&_)+j*LwAO{rDjgsZ zxoDKw#lwh}CVco?fov9org}wRK?AFv<|q}`kT6=|7akyqEEqVhFxaJbP;Co3FQvS#gs5N<(LP&%k6wHemXYHYJ8;Li{^>=p7k`hBocC6Ag#+VzpCN7$uPDq0vR4 z8&x&?-wr1htcvZ>BK?DM`a+XC<#NzM+$f{=hUb@&V3&)H&0@JzJ!)p3zZ^Tbf31{x z^5)7>{$(c!(K5#U{eO)A{_yrAf+#6jy8GhcvXR)XxCYMA=-)%}kknG)uCuK%>ItJ-1%DS-n~H2GKmW$SEO+q%;z9$B`k7e~ZaC2U!dEyDBf`C&Qm+&- zi4xjTVB@cAhO9%yrC~!}yD8}$Y;{5B;!9L%Q~I*UCUB&UVSX$3^5sR!mCI80GtKO0)g5;M8v z_P!{vFd=1?F`4a;vk!(4_Z4py0-fmqP8%|(v!q*%vodC)+gtp3<@BRbAIrgQ5elY$ZCO&)$k@P+x(Njcv-~vV&eZrnZ1bR*wFyvkb;UCq6 zMDVw0Z}1|$3)fVK6lCli9B~b;elZe&j71o{P2xUc3tTW3tWLS#bD#@Gh3#)kB1{}E zY}mEklu4dUD28AM73eEC0W)b@W8gldOtuRw8$JBL1q0nzhPjQ-Hw}-1-!>@QV0dhw zH|j=kg}}yw+lIv)p!wHsu~$!d^^OO3+%wcIHyRBCSNlS#^}1&SbFYCI+AcPPev3jo zyHr<9Gz^&PArVe?$n})-<~k!T>L?fBp(!%NR}SO7j)YkdW5PU~xEXww8QAOWA+t9A z>M}5qM!Vq4MHjKL2p*^G48R@$@@OPvorW)uCQsxR4>JX2*TDSwa(CLV0LFwQM^aZG z-n1N{l|L8glU&O83^P35IBM^<+o<0XBlCBzZiq6EIgi;9+fM0##rP`53WG9I^{K@%lckZY_>pZ7q@$uIiU93Z>s+obeo_09j z+AiT8AG-9zWzkpY?PTUFGyp~!H%CT-C+}Rj&;oq*4he=RJ0aGjM&ruca1TU-=22JJ zP@Oz;?%?2)Gu6p&&mG#&Ll*SOn}7bpd($XCJUEzjd*0Q{6Iblx`Bh~-FB=$t{!8`e z*5BU-U}r?~$?wE5AvOSxY?JW3!;9HYZ0sarhv`na@T#ywFYw)DggJBx(LWi`gkeR5 z&*l2dIR!zxnes+!x#iqObML62wH030o|r6Xt$>$xrTT!sJ&vM$-wgW0OKUI4Y*Iw? zvjK$#L^8WJ1hLN9>ly{;+!mIc41>MF0!$KP(w1Apo@cSE7%hB5WNTbEs2w=m1Y!qj z@Fhk$qipBdOwL~*KU4XV*1~qYx$sP}Qw+s%7Ui@So^_Hg_RnY4RwTm|{-D7UaJ?8fx}E#%0DxFdLI=+UF#MXHg)*g>%(4XgAh9@gJw2HS$& zu{h&PHioqP63j8g#G1t~cHwJdV?pN9y?|T)UQ^s;fS4=dE631itqng6&^GvxjLKeI zc~}O$Jy+FW(91$NUg;SHHZ1Nf&CkzcL8AG{fSSedPex;jy;?)`jPR;Q=mu?rm3iuZ zd-pk5n=jUS#ad;)XGa)9SJF;{Rm|rN($#-dtIY$cmC6@@?-D#1;njThKCYzveFa^` zK-UUWXjZ`$j7c@)yXn3{u?&-A{cLR<4DYiE&e9Z|$9dGxr&$jRs3Er5SU)DulK3oz zgrdh;5L$}oeJU8Tas(5?ffQ>Bbrx60_Qz>0w7cz--VqATIA!xVHH2w-l#KS`J_^y= zp#CEx#WNqX|DBpT#e#Td>IA;BK+qsIJoK-)o@{$r3`NHbfJc5*n0OQ!9`0Xu!)U7v zk%`79fHKLoq(E~qL0mNLzzm#|2|uXgE~!`aGDMRE4Q#@2C<5NZi$u*)GO@WSElNSj zlw~H*5&DkM!&1PLjI?(erB}vujii0nZmQ&^UU`ch zyWJvP3vk>{oA@gx(%is~?IFkVXb=LN(MJn!nO&2M1;DcvrYgxuEE8&vrK^1rkWPVF z%CEG~_q3@^-EyH=opn#0MSwDITK7t}wRgPXb$QU3kIC8~?keRmhu+(D{5iFL>{aS8 zfv(s6xJ-M5d*bBUN!vGEgpO+&Y>$veCz7xXdf&LzNEwZ~N`fYxik)utI8L&QOL*Gv zC#1Y#boI+pX}7#h<6tm-u&Qyg-xfTrUSB`m5(lpEceM4qT-x2)E*PW+xVWjqq}zc6-+NqxWYhJT{K$#E>%vJ%3qhZw-b@#xu+`^ zlxIy;)<<`EHIz5)J20Nz)n0e9>Tii9%5s^{c9uX4v;rrEz^x4sSce|}?aQZ^ zUW~T9Q&(CWEQ(>k?>dlf{?338X3;nMqi0Q(+4Ejroml?a;I8^M1HSxL3f2VWNknrP z0I#!5X(x6f1q{FTne+|LNP(tD869sU!U0QsAXbzfHflAUC_9 z91WR$X;#>Btw>EHm$1Cq*&7+~yPI`sPU=d}vShmNy0&8EvGOX!4Ki6P@u$nGm=X27lv(V3$B<+d*Vyk47wx{(4jScEDl}H4VOfwM!&DL?d!~rcF6E_tM&N7^ zUHJ(jYyfKz$Bru+W=Nd7NF>bbt{~UKP4kFKl$iW)lKgH6QLg0^Q{-Nk+R>Nr_ z^Gs;!z{`VGus!1jpALM(ssg59Fq)v2Ff4QM2ocdEs@RIUs+#D? zW&(f?N0X94M~K~si2Sk>c57g~B*bnBO5%wC03ZNKL_t(U=pal6?SG15*nIJqnL>JtjOV(Q$EsP?^FcHKs8nA+Fvb}ChFgR6~Qqq&|(ZM=c+V!M%2(NQYpdAqE3 z8(zl_u>xi>+{T);%bwU6T3xY}249PN-x!?)pZ7?~(s;UoNLn*r!JDD0hxU2hd4CyU z%Z_vlf?W64xR`qtQRPD@daRV6VFhLF5HYRL4V=3j=S6laXYTLXhzXxmKuD)fMItL+ zL9Bi6lvdQKx+;qapKNf6z>p577f+sFa5HADSN-DON!O=P9epDLEbH&I{K4I>a{{X{ z`0A5V+Zfp9wmqNe?;%QYY zbf;IJmyk5ulg_l{=mPh?{v?r9%Vcz9E%bB_@fYn4RVoZ$rpmk9T89=Qy_09=HZUNPp)ABn?8-pa!ejS5G(bdrn18*w*=pn|o;^^rP$UD$?7 ze=o28|66yDWm#6rUXY53dtFxsB_WO(+yW2w{~17Sxi3pG-&Aa z^L)LYU-C?Gky~r+Y~M9OLL-)k_KL%%^Y#k(vrbio9!vA_N`-y$Sp}ZXOP7^BsYDIE zaU4|@vDxg~o(PS`35?#$yB`8w#92Z&WLe5G7(ms$S;!CN+WdIz#7fyZJZxfKqLEOW zYni6);cWi1tK$@o&ihQB{r>01W11X&<1@G0M|7Tu4%lTSo0YU zEBhH8w4a{Bpu|-!28$*JRW%Tkg-Q5ZCeUj%BC+x9vfK@lfTfD0E()xmL2ykxcwx=Z znVB;ZXo#?jnbq#O3$hZ`{p`1#vS1RcF8A7w*#EPF>P$bsOg28UFrl`qNBfK?2 zIFyW4Qx|Y;w3airyhJ}ChGJlv=E2-W22B>x&!bBU+b}k4Pl-|`Bd5DiTd zwBfeWD6eTVY!?C7wH3yO!*lWiNZ}Ba0v(d*%ydoB?FsfrW8tykz=$;yV zPm5ZiuMt(vs+~w$1iImfG72r$%SK!6FHxU^_RA>=p&R`T$aED{T@h=pGL$B)3x4a$ z202%oWwc&Iak0H^PRSD~N}Y~3`sYtp9ppOglp>$q?pFy`aN(GA%<5riDY3)tdZ)H- zT%8|Rz4q+xZZwp8j-=Tsw6H8~y#ge++`>4G1sCpo^P66~R5Au^*Ii5H<&KN!5XiTl zrO04p&5-m*k3SKQ?mV&IElXkh_)Onfj7c5_UT)P}FWV$WskJ^df9>lD_Sk9lE`8_C z{$v+sq0qm^qrShrxLG%Bj=gH7w>mNL-ZWv-8jE+P^vG0Zq;u-evrNw z`QxY2kKxAl=etj(fBtAq)p-|y=bS@n^{pRRWO;7& zUZc0)L(ag3C8B=xSR-7plzYe<_RFDA&v3V-l96(0WLIS)hQ+hV(#j93dW*(`7Z;T< zNhXIO?2U=YMUYo{lpRT-L14LpfBe(CD(Lrjz<>Vm@4;uo0LlFFnKCh`7^u)F z)C6iNL1-3442OYNfHE`Proy2y41rf-rA;7=)9sP=*c9Lqv$aRqMZVzFSrsjt^J-k6 z|A67PouJ^le)H;E;^F4r$8HKeXl@^ab-EXrvb9T^_iB)1?J>R zZ_ZNkn_bqTn!+VJbd%((ys{-hP?{R@ZX8ZNbslaEi8s2dfi#TyKiRy?ytLC9$u(@x z+to)?*8}{F_7F`gsZyO#6;(cED|^fNuYY`)B6Y(@XrYq9eY*eIM;c z#%q01e?qn-e>@aO7??&}07pE6Lv$!;=IlqA3k^#)Zn1T8Ds1nJb*l4ZM-=DPv4h2x$%Xwt%>F4M;%U@Q% zU@z#)7+MAEy;*}>`!-4vB~9x|a)MNlWUN5zFG8T(MtQsvCep#aL9C&wS1Jz-XK6Yr z56a$A6=Y789`(phM1obKZO}_Wi65l~-k^FkFvza9+XKLPP-+k7)a-=474X^+yjp78 zcalq|4BPPv8@3IgzRaH486(*ee-h=vv%CqcwM@nt` z(I^6Xzr5SqA2F!5XL|5|qsYlp$&NA}%ok=Z8U-+6*i0LqXPAS6d{HarVsJGm2|} z!)E@_&bOJ(f3&{-$vtYXpFFcGhBN7(mlaYevy@sOD%g$G($G|qgxzd{^?Q|d=FaQO z8d?+K!3_MbSLXxAWXV~G#G?`4j(;bFZb}9u{)Ij8$3=mCLS!lnA-X|7jSWs=71^N( z*vK%>B=Ot8fsQdGUJH`3rC#6&X_N^9p}9FY2;xzq1SzO4VPn63DX!w!gnjX1f{}Mn zM;Xht?-SBw1=rT7BZU2SgY!(HyG16{#&nejjrq6h?yV(?BwuwGUZaApeOsJ27QD9f zS}S0N(zWjVJbbvehU<5JX-2ojE|^Rg(T36C+|q((&8V0!?U+$JJ7Af+oPp(%k_G5OekV_j zsv72oPYK${iTS!JLg}DKGh<_v1W%8So+wLlEUZAR(eHENu~W>!@LR<@E0A(}>_kPt zE{ZbjR=xJZ$;&YF=;;%3rwxUt!`H-q(PmA45MbqN=z8F)j{+ow2M&l24+Vf@KaId( zGjWq4uIk0*yEeo2JqyLmE6A7Dq7uGJ6h<5W+#vU~(57*6cWS3?oXU z+)a**?+1ts@{AR<+n_HMGH}~j!`@wEyGNxXL)O{BkukJh&p_ClE#2jDCd#w`GkqR7 zIy^W+4NVmiqG+SN{S^Jbo~nSWW z25@7KK`>CQ-XwOv8+}y;vH-3szlzkVl?|75h4y)4#U)oMTLYO?-^EH|Ji@{%v2XAvrmg%Z;w9Cs<6Gk|IN^)hX9hC^pSeZd5EWw1PXd>dhY~ljV_pH*r8>qJVsI)+YN zt73awErViQwRP13I~DX-|ECb?4^RHf*17$(eV<`G*g$+p8DOx2aR@dCyZBI83>fn> zcH?MWw?#ri$-HTmO+5;owS@TsRVp`?qD6>E3`Jp5q;ip~M5;6*byCt+>CJAV-u3U< z`+2_3X&N?Qu(5-1{QRExeGaGZJJ$OqV*@Z=nZLO4_l?TScNp+%^PT8&Jp^&N$OQT zX0VItSIgbJ@~#vFZ4kU)h~=mQ4kz&gJN&h443PT^xtM|Qmj$#`6UqDGf<#uiFlsF- z1tGpJm6EkCu$+tyb1I;324xMLll}XQq{9!wv3(^_!dm$_86F3P4J+0EOO4>(a(GzD z9C&<*pB$vYA+|>qA-PxM)GUlE2YMKvlHJkduyA^Ec`rs9*7%^E$CnL+=}0>F&k*|f zmZ7Qdh5hL@eQpI@EwE4CBjrO&`5eJ{1fd~~GN6vaJ`y(~k=NY}ef7}*%id636Xy^M zU<|*b^@zW2KujU*RA1z1v@cb!r|p(#oKsE81gmXhzS$~z8&<#7)X}q45FqBfP5iTG zH1}Dm)1hL}Uf+T0s0xp^+ulJHDBfrfOc+PN^#TXaL!Z z8q^j&qm>5R*=)ADYv|iHz|M9a8!t8RMNMTa+B2Nntvv?u44#cZYk$k!x~7QB+U{=F zwIw(o5zE`#pr%M}6rU0N*KWp5nK0KJfKm;C-#B_($(Y&VW5F!68le~4=$Z?kw3`yA z35Di?Js5AT_?S*(`|X^ms+RR&zzTvEbp|DhX&jB#nP(OyzKma!%tVPk146c?sx3FY?U@idnVXx#O-6| z*n~;Xe-mW#5scWgF1#JD$X84q(uI{f(Ns!-&-N^t3_kok(O8+;psA_y)DEW5Ge!DB zp+aftVr8t``zzqJN8E7D!lY)ot2R{c03y>gENoujHvqKlG7e;x!)Nb(^m+un^ZKIm z0pD5cwjD8rUb*2Y?uxPE`7i9=-xgubcdfrSX1e_h0`8TW<6_gEwKNX~5n`qBcTJ75 z_l-2C2s}4vj-)v}wf_gIYP16ogW_k;(nq7KPc=uT*2pD7Z#Wrr5 zOUIAS&Yu7K+dFsfM*NY9!9TtC`&%E}`rVb0ktl7k8Bpg))rhE}i70J+s_z0l-3pb0dT*oR7*VYC{6 z6~EClRPxb9=t4N`5=DeVtrK-4k-T9aKvVHw@+DanqlzZ4vXnQ}b#Wa=b&0~7(>9n; zN}7^p3F;_O5u9f&Y?z$GrKH9MBfbThkMd+-m8b?z=9RZGF+nv_GPh}8eM$Y%ET$vi zH#Ub5x=@JSSM*ih8I-gph5{RXX3PvAlYTX^j}TgAg7$nQe_b^A=hmHK}D5#KuL zEr2WNlEdr`t!ykDH#CrE}0u2HFQ+HQKJ$ zvguT|+GZBba2d69v>o-*S_d2Wrq}{|9XvvSIJ+zL7UY5KCgD&4gx%0T;Wq4KxMfQ&Jcu6t||JEKI#M zmHk3qfp`Yaavh@vgYvH4Ho6YNuR64r*C@+4yjH6gSy2~vsctGB0M@Ymn)-mp)E~GY z0}?R1Ks1)1^<#OE423UWsQl>WxMOah%Y=C0@~fIc5oaxYU8t4oG`!$igvE$8wEq0I zXMZ6>Ogk)_d`{7yJu;7We9wc-)!mchX=OpmY5Vy{(MTkyI%xmE`1gjK#$hj0`@49z z!_GK8rFqEUdh_il%AGg0NI>$)U;WP$@LzTQHC$dKMxKN# z239w2xBO3$RfkH8%Eh>OGG;-!ms%zCM9dcfDcHoB8(m?(v ziAO(Zt+E;nmj3g{!Qb4xb@S?9u3oz~GV;rjk&*Lu8o6@q$~Akt`a$S8vuO9QWh8ye z9*YPL4lUSh%PiG!1;W}y#~XIck;wd-ypGItdFl9JdCQI_%612drPF&^=FenXt=p&d zb;wO9w2m2xU7tf;Xl*NiDEb9+=zy!mfgT$Z_WN8x4s>V;U?r3T&DDVFf&COC`B?T2 z3=EV8T41h$anHbz=E(rLgwHK0pL<$8;=&4qW*A*EDBkSt&7+St_?=Tibnk30-yH&5 zdwWVlCnXXl$=HAcZ*rO&C}|XpDyvrs(X%<)eK+%T1LsQElxEcjOvt1$=vnnIP}49s zm*mV(xfp$%m3T_B_mm^&r*%vUN5gZRdFy zZxT&obkfE&VH(qDV>D@uQK!*bO>7vY)TPck>uhmhi%M4F+B&)^D?NA-3d@p$E2S+I z>S5W#4h(%c6lU5&FT3YG&EEFbLr(*-IsP6D+H3VZ>2c810A_!637136}1vV^+2HhpmOP7c{a~ zES8bsS^Ic3tA(+vZg3U9ZoRA{&Fw#U{_N$W-G`f7y@3Y`f|kel*9W{=qEsVluQj*I zHxCPxPBtDI0i+u#YLI>FQz59*p!YX%cpC}qUBovW@!8A4U@G2uH<|m+fGNADK$l=L zb_ww`(OEpAk#41IXxgl9Cxl{D9d$clG{KqhV40F&%j!x}XosC%d}6Q!`+XO~(S+l( zsGyq(l+7ZBt9`D8VZi|SZXdLOK z8+frT8^niX_zN7j**$7Tgr}cT!{C^&!X+2PfrsZl4B~JJ&}3jid*_gAvHn#e)?DAC ziyyTiz1sw@t$lTI|&m!Xl578 zn)G+H_FiHs>)H>}^7E9_6e$o;MS_(MPr(qURcWq_NFH_^4Gc8O5@a<*#}iAd8c>fe zr4y1q8!Rt?Q6(}H^GPphkiYL^UP%eLwK4nPw;Msn9Rm8RfjIo1_rHob1M@CcR_!ln6sN`-@8&^I$a$62gqD3rutb2%ao)wuR~+?1S5}56_{EN z78E)eCx=5^chDtJs)G>ym70K&P$PV9H+D<{bV_NIEQQ-uN0>~hdyudVcE1L<3Y*-K z|F<1Wuo5Hvad6luFq>b0SA3__>9qWaqwgAA_izX`C>eW&5BqnTMT6}cS;zfy{Q|~h zQ~DKP*?E^@V80>n_BKrnf4i&LN*2I9=eoL%1X=4F)>b7BAYKJ;k+7J+@Zf#g2}!yl zYeVG>t*RXiplS}{4sIo-gDGTG-r$J7Z(X$4*hMs1QTBi=fV0^s3C_!8OO`Tim0p9_ zWttU~y<||lN8AQq zDC0C9cljA)QR6kzC|W}3iiXk^Bi4wo^ZGStrb|qs>*J-vaWo(+wRT?KqnK`-&zJHJ zmFt_2&V!(@G;(&>+JrvD&(4t4?XXxm917`>t=6rK4+qyBE^32oCBk~u{kGx|Hr*ki zafger#Ce)H^F=d#3ugReGKS*UP`1_QtvtAiCVK?Aa>vNG8oFXq3ls`t!|-Yp%iRW7 z_MQq?Y=pW7S=rj`9b7Ol-|8xo5EBHCZ;pN{|B*tnP*Z`gaw9oK7TH>&y(1kLC?}K~ ziRi3mD=>GRTTqPyA}r)c|0jy$#KA4s>x%?S4y3pKqT!qWGARGhhScl`K6E0vC@g|F zi0~pjHPV}L0&k)?+5OrZji^2Od$Wt#Wx`49&mwAn7?Hh*;czrln*@LXRp#d!C|?+1 z54>>ogAugwnSW6qb-~V)q|nN~3k!Y22OIAd5x&dh5Dc#!yHfpr>MxMS)6933l-$%Q zi}=a~Br=(B-dh(p$wE{ptyC-{rfI~+jkG!l4X2IXHb%>88!RUzrWQ+0h)*{d;&R;d z6uw@`rR6x*4P0)9rr8kh)6S`ch}xAGf^-cTkfwxt1B$O?xNQgBfAHeT^QVsvZf%uX z{l|~rD7++YE3wo_tS;?dG|2tTKH$1K0mL(o^v)RcuCE*R4h?Nw-1vI)%z*1QmX%r2 zBC-iDO|4#9#R#SUlLn7ZAzY}sFeUx?=Jo5>Z+?1`o^t8YW4jMaypXm80~7SShDcaI z%uE6nP9wZURaZyoQ4X}e^LSf4_F`NO1=J55^cf;o36k~(p}6Wky8nu?D z(n^I6`NCe3pGh{fYeL~_OSlTUdgpW0GI+x+)lhRW9J*)V8(x_pK)R)0mLsHB%$M&e zg@a2FTwz0M`hxpOt%Ui~TZj;gWGqAD{;*pI8{|&p3M=vn6Yq@Ns?gG}=&Rfy`(nh= z_N6#@hq7Qot@?AuW$g+K!R&xR-6Uw58!Yyd@~rS@*s`ogJIte#szE9g5IU1LS=fOD z+okBP*!{)}@jEHwyUF5C940JTbV@nV@f{#ENg$V!9do~|B+b9CC7kz5?X{&QU_GVJU@ zmL+`_1MAN1&T~CIM|fs<6`4i}5+i4H^G?1eRTgI&E4!U9ElDI|*}Wn@X41%^!R(-N zpQ#&kWk}H|3Bl1?tFnLg-&`Q;z0k5Jc zCB=$uj@L=rKuoY! zh{goJw~%Yw9ZOq0BnYouNHR=;#mui`w;v6wf&t(if#7y)ZY9uABa_E@l^F_9N!L=wkjWmZ=@TK<4vuF07KYe+yd+Xt5tknB- zm=F-MsOax~QbDvu8mTY*+i%Y=NR4gB`u*)pTc$=~bX2lDd-4RMZHqv7gn%`BAJ-c3 zd5kratig)+q+_$%2t#V^ac~CS>HoYz(jeXN_w+L}_A@L}YXSgL|9r<8)VH1%&FzO3mn>(zu5#>{$g z{|p$-J#*#{*T=4_;i#;f%*56G-Fvy?zxm|GjVqt8pJkq$e5Tmw#M08}_05f=e>{5j z$jsUIad&2B-LMz%y?pud(E7%ei&yOP7k^4i_+<}%Rodqz1#+!o7UtbY!~V$wiY?)B zr3v6r(DZ-ay#C<_5cs;@A0!fE2e(U90Efs-@C8G}PllApK^#ZWi_FUB_4p*LB1gj$ z^w{ez23{X=R{>+dUY|zL_G2h)m)hl_dG^A_mL`nx63F4jFC5nWJ?<->;4q73Pk>5b zW4nZJgaQ*)bv%SuT99wyFk^Gb0gcQ5DQ7eJjbHjD{r1&^?rfhh>?SM37Tf^2{b$rX2AD5eSm z+TtCEuv!?HP#58~_H8cZSS}#zkBj}L?)X!KLrUV<1eXgMmc@>WJ38P3e`L0?NMfsq-l6qXY>O#PSRNqG2-ouuO)K zNxMp+!-QizhD=+ zs?>|!@BKXAUzAYIi7`HM5b*q-_k9iq!#mMrdm-@@&I=bdM%%w;f1y&YgD_dP=NcQ1 z(ub5x6wAp<#Yk{eJQ>(#@LWh4C8i4ruFPOMfj&BQkct-QWH3scDprNcY+Er98wTPx z#%*g5d_d}CmQit33=>kEjS9Z2TP%qScCKb=1hl6ZFcXczuy_k`l|xJdq|sl=1H7d) zYBHzU;o?1(y4qN?!M^hn*)>X;w%9XsND!S!IiHjgyUr=k%dV5;#Zf`g4kV%pgXMEu z_Ep_E>~L1x&Q2+-)S!SAt0YNtr;|B1dOEF=&X|*gztB-V*6E+88r`W!K^@XjOXBQR zD*?;wgk85Gi&lAtu?|n+ENYw?>$v=f-91rq1YqQ6m15hBnOi~D@Xh9dv?4L>zSwrM z9Lg42L#X5#)Ao~H8j`l4H5_U!a5xtTe(J??dqUc)u zcDnB0PB2V*>(2E2cPbK|Vh8+6h4orB@ShBT^OIifpi^MQ#cQv`VZesKM*w)zb0EQ( zC*zY|Z_@4rgB|{bR4=l#gC4pu{!XQpPucOs#`;n6yM9y!{d`#B=bY;x@+Qp+&p_-P zTV92d-bQ`w(w(J)KAFidA(rw;qgZ*DmR&}L(l*Fij%j1NYT$eKM}Rdik+bnp0lW)+ zj^#6VC7Cj4zn#M$gj`x4A$y(GfjoJVS_B*HW(Mp>>C0!&9zWXt=T_?Jc&E+3{f7^%9pvcayhP^9X(6d z#{I$Z+Osc(SU7(XUGY%yUiBA_jPyB@YmY#FWlUI^SA8RfzvDyLlKO^*41)*l2G4;s zE*DZCTVffK44_W{!_{zv|WV{}6)?k;6zb8oRU{`$8_%5=nzVUhmZO}jn z9MfHh^omum6JU{i6~TX`Mu+;o?k-KNBR7@F!JfF6U2pe|K8Du7?!9`(&Jns7@cVY# zL-8O{!eBRa_15?H-aCGeVul-VVsb5SkWcw*C0;UVP`R`C{B3)B=MGfwFoB{6cs9#wRSS$K@H^5IUTCJr{a0UNQz(Kv%)z{Y2{L{uep zE~2I)m>To1)XRiLD_+_FI;tgfYAafB8PN7Bn^6yLCq#5FT&nuHsW4h!$xzy;K!ZHOzWu3LD z)ab2*OC?WM{hh0N=y7d_UM@$c!l+79B~;2^AAYud#|}3_p>XiMXJg!@zK6#NJKRDM zOfT+EdtHBj-4c7>P~95M9(73r;NZ&p-^8aJnNE{o>BLv=GZ)*13D4VY#9P`YLQSwB zSX{YhO6^H$NwbVlK7Y&G{;vPh4BYnU(_x`5d6biJ$8aY_gvUPl*Y`)GDC2Rjx8YSM zFgxMBa~xH+QyLOlODy%%qG`VXJA`tSIkrG{rLr#~!&>d9k6-|(?GS%!o*UJQH|unI64kD)?ewaUJJp}B_rrzSMC=hQIT*9 z*EN)PwF~T2>9|+;GC5CfC=DydWjpL^iloqfbq14VNo9kv-j$VF z-~C#7kLU}gcvy}kWLU6U>XKv!UNP?L8}#3&n1MNS^C+Wd=Fi5B2g!zp6We)+i{{a* z_YJ2<&ngZYZ;?DnD4?%i9T~ZLcI59v%AQ1OHK?e`L2|H0-E|DXqoaWExJ*cWgH9L? zEgl7T-BK5hOxFUe7{%3~Q$N%7J2I{fusRz?PTV{Zu?I%j>q3?5yVU3_R}$EHGlIm* zkTWvg7wL<%&}G;~+=gZv0-=IaNb`;&=eiX7L0)?LPS>my{`Iuh_rxUgwQOA zsb;AEYp)UFmKFrjH$desjhVX*qFcHm-HL~%37Dj4;ySvRPPer59!J2{a=g3dTNg0u zS;n!gvEcQ|ARY+1Flbkdq+l!u#jxIX-GKYI&aa@WfVNodvH;)qoi#h2x2vHtk@R#3 zCKWaS0d6OPk}FJ_Wke#TZ>?XXKmpJRL*b`u=yLG?3Uv)-aU&(frisT&(jA{Xpkp>! zt{4M8u)k!tl7_sMTZIZk+Jt%>;Lb*JQAcA;N+eKm;Tk?jRTQvQNa7@}GPX_{Keb0f zg)7li#VuD;)npOoOK4@ZN^nN@0A#Lu$f(&f#CG#s7R?se2^YrLi&{FhNrp3=R*75D zYQ+%T@KgKbt)hZBcuFLTP$RYip-R03Ya&#n@TxY7D2az40O}R zfIG!lm3&chGi6VARcd^RzHX{48FY`UEA$4@jh$`_thKS~2-8aBfJu)*eoKN?Y8tfD zb!x11ql0coxqGPNMGf8KnwX&A@*1PFHi|lSId;m}%#+85o8OF~q>@1F<84)NghO>? zwNO&8B$uTnFc=z4&UjPr^NzF@)WmDR*gI8F?5Yh(+Hf66Y=-C4E-qT=D={>#rzvfJ z8BnLwV!-Qf|DP>z+oMPM$@t}X$7Q$KjXNc@#?haAKQ;gTktD46q}PVzYLUFt-lj9q zQTA&;w>ybKYcjD`PPQkgCnTfNPDEi<3jDqpRx_z4DLu4f0NerVoxwyU9^9!$r1_bn zWej68W1_}!Ou(YOGjSP$$;gTyZmj6)6iYibtk-nO>$k;iI7jAe|>zOy&-hJ$5ez}~X=^v1>08`IMl zLEpvczbzW~H2}VL?ONY6*K91Ib_TVVRMwdo1;?4a(ch1}pLjQ)+u!?DqWRgEyO#iG zJ8t>u#Sc0e0DrVRjBxzTPwy1SQNU&tHu(HDNYF-@0d$}#U?@yjGpSa=;7Yj3SLY8? z$c~0N5ODJ7U=uwHh^@jatbz@Jo9Q0(`HUFP`ax#9YH*9`2o{X|3Yg|8q*NLz&tg7m z{vTQA^V8;i$MG1OfH5%vj0bkg4;y07U>6TJ5c+_h)M?UmL!k=E*rCEM&0N(=U{pn& zmJ8CfC?XR>XpMxF95`|4+D1wwnp8b?yJffTFW6zH-ge*T_5M0ZqlHK|_G2SU*7JVe zpU?Y8$PNSF)xQu8gzSAt=r9_)s%k>y%?zYNHENLxVD#+wvrL+$dS>|S5IA~TAsmXK zRMI4OLbCnx%WN%2EwBVwxm>j^$S(f9 zK0Cqmu>fNlM*+Fr-!Uq{idZ@vFU)$k?gQ6#3S`h;*W#SZ-!PF_ z0@v)F%pqD@D6iL;FbeDwqUHN{yhbAqHXE>Jv?oSY%{V#3fBQ##mYz3!yrXn1#ZF;D zf}4_*RXHNEqdAP$PPn4BhMA3Zg)>i7>RR=()UB+~cs?R#97Y5-SKzNa%^zD|Ti2UU zC@1TMYzyP@I#mlw3YqcNeIMIuR zHJ7a&tbcoh!Ei@#b#Q;u)f8STHYqC}?7@(NSW&`C7}?%$!Z@;A!O z3d7D9BWMT1FEgP(jeW6o-33s(xw6Zo6bUv4{8{;@JK)KeNtJF}{J!JL`)g@-Eq;Ug zF0Ekng;t$cxL!rWpRW2<-5dBJrOUU}!$9k6!3 z!0;6%W~l~As_Dsvh5iROKKkve{P!gVzS#9%_Y-kX*zf4PZc#JMJEii-UqWUY}-{1XmB2xoDI;97;}-}v$0Km71FG2nk*HrzIHe`f1`ro~R4Edgao2EkRGYT?0HKIt=p=xFHJ zA=57>;KjfqXc~|#E6@T0FSd059f54SItp3s2DJSRw%@atEvogGO5t|LZ37|jwfpnc zs7u3|jRqvRind7a9F2a?44V3dXtzAT2CS>Kkc`4LVklYhx-JGI#Cb;0g^=NJjY5Xg z%${>O#bVV$IT?U+EPF$zb0v~Gm`Fo|iGv1Lb4q+BY{O7jL01OHHD=DFQkF>VC>2f* zx~*_NRgyAV%(zrY?G>;ZC5-DjjWqtEJo9T}u-NtP*^x$h6KV`LnwxUk{sgm^HEyDtT4M_4|SH*)5eP%jG66)b~lYg8o||uAuqb>Oas4gV+dx^xYYn>D4_7Aqb?2TEh|BD3f7vH+M7@g|r+fBc z41kM8S76kswm-P%fD5%!^c5Rmxs$|)JBycIJgP&)o6F96)ajx(hBSj7XogV^>D`M$ zTIXeIE`pUltt~Q8$3*~}T9+Mt$?#GYy+xOmp+ZDuWIlIAaXrw#{o(HZ!8Z@Tc(C=y z+jkLChkGUaGxCc9!LIm1`Q83|#?4%q?#(w{bM#3@X=7^shA;D_S zb@I;B-G?6*d(k#YjPs{PUL-`HQf`M@bzMo)_{#RScF9PTVUhD67#e?g`SRuc{oSu0 zfBWsDt+mRV-gmRZrTe=hE7aPLU)|5#{P_G-*ZJ7_SgebmuD2g;yF3iL5E#FD_3=r} zyHitLzlgOhwY6RQa!w)6$CkQc44_;0h58tiw@1bwo`@MUUYeQ$ ze$T)DD`UFn-hKPTiId4xDbVgW?%&_q`ts4^Z=UWS?4B7x$E}!a#ZyaVZP0t2IF3_K zH?v#$@cyaY{n5F_Ul#IfyYtj6ZD0TKKYw;R;Q#*kn#<7BExNKO;Edl-p>Z_~KRZ0kF z!RPMiqOze8Vm0$9Yf+UYbw|~qgp`?5U;1t=$_eb%OTGbuWp9G=F0l6!G>3PL``Vr5ET^h!Sc)xsL;omql&O35 zqa81u^?1}Mad<=NS4^5ckz&7b=*QD)XJ{N{jOErd@hS<@4XE@1h7u>dPydL4x`T@J1>0qlkE`W5YPjqG|Am+FBfDz1RZ4HQ`w5DjS4v&}lqD-IIHfy=!JdIU;<5yI=H6sSG9-g>A+GK|hJI#DP1t?HwvMy9Jff z>?#)^qwv%L2d%p62HHaDA=M8xjm2&pEu)k0UJ7fyjeCikU<=XtVG^xU!vV>-hK8DA zt^rMqC8l-*al`8J!eswD#vu-#8W?XqxP5mmj#-x2y+X^%B>rS9MOQjSr=PEZHDPYT zZ&^{#vI>{Qf0c*D-yLv?l||JzC=0qdfObsyMH|xA)*H`Btz5nR&W>a}ca#NDMsyJU;Qc)MGt63C%yJq z$Vw5R8j+N3W$-%o&MP7;_%TCgbuzfLjs;DlRTOLh{Lx3R)Dgbi313`#ulpNUhNK1W zsDc~Sn&1Rkr(92OQ?fk&KdP?oC#^gUD<~gAv7oS`6y-w>ik}gY!6Pzi8)y14bk(l2 z*#?j`Zgm_To08eYi!o`|C3a(tX`7JLi)Jo5N#nLjn`kvVH#7f2|Ax8Rq?_#hzR&Z6 zw%b?==N!={#^*fm`+T5HFow+MpD1h2q2W(uMCJBkXgNr$wjg3w3~?2K^fx_$ufDl) zaBy~ZdVc)k#qREgws`3J`oi6BZ>?V$Top#z+#0EHG7U%a>mOG~0I-6;W;2-V*Jt<| zoO=rzewG-&wTdg$`S}^^L5%XO+ijyqSLg4U@6BV z2CrS4`qH`iVE6vf@%gLM)0dUXjl_-cL%G@5^DXV=Ai~b2W1|56=fdQiWm_(ME`=HL3{_E@@FgSO~RpP?KeGI0dRnq#>y?uo4L;972Mr zf40!7WKn=?C_0{?{ivSd9GE;e7_bPg?{x}#@@OjMa6s)Wq_!TM*coxs4~!jfeX20P z^kz4nQ~`hvI663AT+Ll0hsJJ9^BqmQ)rsgj933FXCNg5Y9n3@}^*O4kv8RXa5IzFE$m z8}SpNlCY3?1-xbJI-;G0#x{}qa^Q?qqn5@dh*qtD){ua5$SMzz(d>spEpo2q zj*faVTN$N%#*scYCy^WLAw)uNp`@Xlfg?yyf`KMcm7ohcCOs;I8eBQEIX$faSw0gT z4J<#zyH0OxZk`ctEeu?46Sn#|YDQS5p3Jc7 zxDVd~(nk6a>a}q^gmo*TIA}cr!}KbJ6z0<4yOUK#v|V*10W_6P+0J?-uUh1)r08nK zqYCw)I(oQvLIqZG{9Nl>`kokGMgL(HTgeHvN&{=D_|E(PK^*WWEi5SFn?8EA zz$b|fa9xg_RlwWH3S95HPD)Javlh~^3C_@E2WwJ>*qmR{Hck=50eBr^(;yv2bJx2^ zZ!dX2RY4CanmjoK=1Vuy_3ojng}7~J@Du6PNBI>{86#-psdC&-_`)iVYJwhHv;m_L z(3gWTH^%yfKrS|_3_pl>WNkwX<7xyyQWGsW%(Sda;fcg|iOMs<+}Cf8cOE=l^H_?( zj*c%cU%h#AaBya7WTq7eJEH8kty4`0=r)8ascmB8+Zi4=x6aE$^N9Zp@DGm@2iR@L ze^{M@#YpHeKK}S-BCt0a2()#drDpzGH$VS7A;yBTcb|U8Qb6QZftMex3;xz|1iiX` z<)-s2(bMzihbTIPzlhDmKHqH22e6OjaycRXa)TlNU*FymCj;m_VjA?@t|!OF;Hx{8 zOM#wfUm_fcEe8areX;OwKl}qOr2oE82w`8E_4x#VHPvKfG&=reVbd$-&rU}z?W(C> zQC?`Fjaew6jc6`(AbJD6Nf<#Fu|-CRv?FUMqEOIakzd$ZY<(R?1ar^>40}=$CgNIg zA<7AhLU3t7BK0+}{uh0O_2@rJ6{*Flr@lD_NwkwrV0n%xEN80TiG~JFm>+{NQxlzH zJY@mV8_;JBG(>tibjI#CA`pzShF+jCbXSoA=FS*9_eSCc&YcBZ<@GP|xID(?AS7A9 zR)%ocFpc&H2jUnjt08oM+^<+KQYe)odH|bSe><9x;;!I!946tQDR?M|3oCH@cH9<( zLd!;|MeSg`{g4}A#8Ubpp29<1NUa=p;R3%Ptdbd zSKfT7#8L#F87#&u2hdD?7UVU;)!VcPFQ&F1YGL-TwIzfSx~R1g8G3RR@U_v+z+U09 zO)Ys`1Aq>p6IB2lehdwtB*!4NTGXO~%jm1i(~Xp86d#tr$hgwnA?|9SDc zEe(1t9UEayPwEhBdAK{)`pRVixoHTlGG*wG!D}^5Ku{BsOf1yPtP0*jQii5;FRX#| zB0y42u*dcB&CTQ{y}X;xp=q85Qqzcp&(i5|N~+N`!a`^|LIGk1O%q9--;0NL0xXo^ zsv2?Ex`qX_Cki!~2O%O_W_sgjsFM}Hlw4IkzQgvP?bKC$!CA6m!5sX0z11teP_+!T zkPgAgHW{8U4hg+z3KvasdQ z_?vF;+*}N0NEk1(3JG9*dtvsY1?q3!4@p@7XCz1Cy6fHDjHLW*=Nf}XJ`^&145XB! z=39=_GzZBOK80{Ol3{cUsp4CVZ+&W%tcrt?#^DP?g0;tJ%J4D^8~85Es4MbS1amh+ zjg~_2$3I=T{P&x;*4Njk5c){i`DmhAh^}BtE*sQNA7MrN%Y|4LV6mxhG_X)6JhIQrGC9$*zm74sSO}`ww|J6?E zb)^#a-N_fvU%f~OYR3XgzS#TUen1e%fByY0KDr`s=6agFLwbPIlyv~C3It+-U z#J>X07DLK{=3&mFnN->ED|Wv{)ki2FkBbdXN0G=(I^4h_LV@Cf!yylkX+UzY5h>LR z?G;Q&&IY7I7gD`)n9WELR1^xot@2>xaUh{XP#4Op2pF&*n&)0bWFZDCl8Q&@`|a=L z=vmIFu{1gv{J{caDSN?*BSBu)U+DJ>X-4+dAwU>$8gVs+hW6Qy)Mo)~|DnI2!k^>q z{_R89gl+BpC`N(;E8Y*Hi<&_bs(pikvq1sYU|gUTplfQk1ziHq9qmGn; zmw?!I+Zc>SLWP5JJ;1euA_f84b`%ZTT>mU}*-Ew!7s`QM@cMQzL0Uco^XD-ay}uYq zo0yk{j)qc6B}aF;#^l3QXE5@{jNy}L{Y50D#R%D{+r5agUnFa&awAsw3UNg!0y+ha zE7nCf`iw%0XhL!$@yZH0mcTRBBy?I>k;H)-a$&u0H@R`X#l4bmAvA05Mhz`=g1q}H zZvMK$s(3M)$H^#Cfgn?{?#sn2YZD^eB7_+@tM+MIYxDuHJ=X<*qva3=%-HzituzRg z{>RnX^|X1IVYqx{*ici0ZSmpa8UuD>FmZzu@Qm>w(qKzcqBb3xgfO9u4v!|I3hGo& zkfKJBBV{N`BSlLO&<;{5idt!v(qw9WLDgTd^BqlEe!-sWeoWGgkN|$)*ESL2_WeBf zhheteR@!;O@|a5u(m>}-`erP4a}0G>dftnL8E6xU1wMm&X-F`e)_Kkx1DfXzpyw5E zsf=l&G>qELV^pHVaGrAwbf-#`0ejhkTX{=-WLCWM%c(H}K&~2hWt(icUGiBoa_gfC zCu6`jVcbTODSt2kw&(MZ_4B5YK-d835)G*!o9qJSKd8G=%N$@ zy(ke@!zSG4RwSP%=N(q_?jqJfk>ftsb-CVZQH6toS}%R@g|EXn4qQig?TLMZ?9klz zTt^oBW{)DKxg5T#Ewk=Bp>l;jnS=XKO`|1qTI_D9&PLGHEMlupd`G&ge4k`kv+^Y+ z0A%OC0{KQ6VM5#AM4#)T`S7ff1?}|r=aqz!ugHR)cFwB-^re+X7S_lYKe7b=`3Txi znqEjx{w;R;R_Vqgu=&f5>5VvUA%WlbMN%X)9%Q%Yj1F!J>1+|-~N@Z!8!uwLUMKC zkEOF5F?7a-wEe3G?-9{;`7-T@8yg;VnJvu3>*Bz!EF-Ym;CLbabwN>H;BmaL@wB_? z!R`--_fN;m?*)I?F%*4P-iR+yLh<&Cf7{!O{~XL@3+2o9g24fJsaaY3Ej~zYSE^w1 zdIM|i^YwPQc%_GCj?6LI>6j|x3vMDri(k(eg_YN_WcV7ox1^wFZIeT^{)U_Hp}9h( zWnkM}MA8)|-EuwDN>xKBOzNcc&+DTh)i5-LbCe&2Ja5vj;VZ3q6?8Sa#%y{m6sGk^ zCSZhCkX>W80$!CesCI+U7d&b77K>7cDil;!h}yaTST`QvJ$f0A4GhXG+;4bEQYFQNKyH6W_W&|2VmAi+ zccp3W7`S_ExBGLYJB#{ubnht@%P@GL`>tK~miH6h6&sd8NhEj|FOn?8_Lp;T9DuECoGTQubc7sBLYu2MT>DYau8w6%7WLd#GA(GeBi(+_Rh_Vt+XxSZ#wL zQ+w2-dYh<0xN;SO2EcYtDe8Z#Q4OM;m=85h|2sPn?cb4W$XuBE*AytWA)(Vvt@-KdJEhth59Ft&x|7FJv>OP%T$- zRZ9qBsDH43Qih2@qwcs;!TUG$Rjz%u9ALL8QY2N7!@9qFRBuAK^3cH9+~AX&*7%zU-OzPkHsGHTsVX5E@S0s zP93vvs`9XwiP1X21En5Tt~~BN+S|&^tKK7D<+{135&L`;2u&0vQs_mcI7>~HI2u|r z2|_*Ds^I+W~EyKeeb6s2hJ$A5SkOlcn@7u&y&C+izxpA-#U zh83<38Awqx45Ymrpe! zsJ7LQww{AepK?fl z_mju=R0=0gkDdF=HG|kLaokU@U+`v!_^OhtRt|n>bx- zuGY|(Mb$2}`dg@Jt=Lp-CG$$~32DpFn^GO8G8bsqu>famO+tW?p_p!ZxH3BPC>)76& z2TUIGHsAr}Mf0g$-!1c!nt@5Z>bR?JK@Yz|O5M@F_l_i7YDC(F_YNrL8FP{GWia=Q z!l1j)Fp6eA{ddFQUG!RSb=&*ynRj*v-dJyICgeF7Y!9?}fuILlMGZuQ0i`)ZcZrtl z31Z1yjv6FKmkm^-!5;h2Cf*xmv>a_y7~3182MCZUa`;IEZeRYyLr#%Xjp}Pz1vvva=YhS88AK}KH#G<^s7d~ z$o_s@qUUKZW0-Dq{qp|VPe1tKAr`{DX zf3lyXyC69nFRWZhHJEaj1MI~c<(c{nI%72vm9v-1H$G`lU_)uc)6hX-Wn|^iZ$7wY zygAYZx!!L1W`-2WvVgEqE)*`TMLy7Y+K$gnY`^(9uGMz7&a#_LFW+ZeX<(}`-MTxO z3!>#jan*;(3R}p|WRHLI^zdM{e4IfwIVDsiF4$dd7zWQ=_}A%=hO>1wKPBV$_ixqO zm)3*cvhMntW?F8-au|`ZVRV-U26fLhEg{ot*DTUVF{Q!5(7LhSFl5%Cc&TOGxN>uo zmmh^;wz38p7Wf8ISchUyZj&y12*Q% z_7Q8pv%s*i-Ptkbxt{f$y$zT$z$Jb|0avN`0~}QG+gP%C$Fem15=hB>IBp27^&*aC zv)qwRF$hkldmpltgypI|rU7r8#11LWvSp*raC_C^e+e4Y|45%oU%=#}ed}RSDTGYU87b z`Yu6IVmSF z$hPP~Rbj1yGB*UBp(R?p*WuYa97JCQ$zbXa0$ja=OU4uiD{N~~4TeB`zjq=z*2?Vc ziPXuXcEd0{QuZnPMDkK|W>8gvM=~5a_g5F`QIM6(AIf;QDp}b+0PlNzCwg+Se?#7C z*fE!I*T}Ir875ID!`cRSXuW#pxC{8mj1?-M}Zn)%K{(^9bWjcY7F?VKdB=; z&7gR)T=@3qA3q&=dgtJMj9bQlIm0a0>y?}b$k>G}=zF<(Z6q+bwLdHjH0)`i;2C1=kkPyOcG(&>fAkqe)E@-qk6OM7qp(;#~d3@qs*m)2gTPMz57I3W_g zH-B^Ddz{OoM+JkptMot&(`7GVSWyPa8Va_ykhW3iIYC)5NMECqX?0hMy<`07H;N%C zDK*=^BUyVJ28{Q)FSg!ijJ6vXzP=8=Mjl0Co@3S76H$7GS_ucFPJ5Xu^X1jBz6La%U7d;Gy&QpUsJLfbIo?`MlO(F+%M@Dp~cc=j#oI1CofM~B8 zG&H7>5I83PSpm@hF>*XdO(FG1x|$;j+HO6VRTm*XEW5yd85pBJLxDlvtX7XaCu?dh zJH3q3Oj)58e`mAIg$dw5be?7PH%n@k{Wp~LMg~@Tf#Ouk*e^clvE{f1!)VubG`^e~ z@@gX^$SN`#Q${5em|W=8a;o=l@ZDaIe-_TRwcyL3*Pi#V-A;+=rig`(_rAfh(nMNR z7?ztB{q^xL*Cay^v5_>?Zd26o#>9{@<_=8G#%$GXB&##sfn@&;)21FX8ce-WgjS;% zJeY&bhY_GrsA~$$=Lkiw_9xeq6FwU>+wEFUt`_w>YxW(=Gm#y}k&VPM1UC2{HlkcK zU}l%e7(w)2JxXeBR1{fhTE$|lAoEqOE_u2h1)hyZlgyz_OT=b%Jrpo>@#{|hQWPZG zbpQY$07*naREJ$ez)Gdjz|Yn2e#1h}A)582pjB*WT{tizNtiVAWpbqzW(i~q>Jr8@ zD@081s~)ftw3-Hql~(JbM#1U>lrsuS9MCsB{LrYGu^8h(bL>H54t33Es^sG?v7R*OY2g&&+xQ7Hi zu5qsfVZfBQWY?Da-R|rzXP@qld+HU^@|7z}-B6{GCbAwfnN-Zxq6bB5E*u7MaP$ZH zsDJ2pcD(3gS?>=H`<2EOhv^X?dVW$_TB-;n7o*=HQ*yLs&*Iemu1{}}5TbakYLa^2 zDk}07F4gK4C2$DVm5b$i_{N4*?P|X|7Zyd4dA(}&suqy73Ow#k>1y)u-5WQKxbM*% z*xk@ePw$pbhdV|1o5RLIRsFIB{NqpdfEAKuT>0Q!wl{w6tKLIB_3@b(_5)go26aWw zMDMxFIVaCUZaA=?T*wN&5V&g^kJk&pxW2UKO4~g%`^C{A&Ko z{PwX1{h2gqJXla_2 z@?jZL?XK>Qs+D&IQp^KZ^U8weV7^2Rp;mx38os|QV7;`2RBWgV@XmYu<9wJxb#w2+ zl8=UsBLC{;in6SD?XP=*WRUcv-}ijfgDy${A9>7YSH8HW`LP)C$x}D~@#o2vyMNm3 z*hI8mvbX%pt&b3^OPMXGshujUZ9V_}(&mZHwjl*#q zv9DA<$WoFK-T`Fl?y0aO$wRQFW~ULA=`5Vy(GHSAp&9!Ue|2uo;CU7@+&w)j_xthXizBZEl0m_6EJOY7IS{7y_5mj=Wf^ zCwkLuEf1&LZyWNa)d);3R!5Wy1q04L?9Qq-io}ND!+lENrQ2vEXV-?4QR-=6!jUi? zFv3#saD-_tI&=>zfEm7oz7LyXeenE3!yW>oy3BN7KBi*w5_XAX9 z3H&?KGCH4))f#QUHHhaKKa4|4gZSDsiV%_xJ z;6ko}A1eqF&9GsjDg8MSFbHNjxs_`r_O;~9-jsp$%&n(quPAw0ag@m;kJZss*poDp zil>wtO6$A*K7>`9VAw!7e#JSovM0SR0g9XS@v)D2`$Olmx*Wz?&lMl-_iPN;xS^*i z?*(v`92wfCkJ^Rx0GM=g+~>eP<#iV|*^;_i^hj!Wc6D5PM>0z%-87bT1zKxHdh-o| zt!^uG(z7~bjvnX5#yt`1**oD5@KGY=3tM+@eZ6)kxck1=kTy0>m)^|3x$cRlG z;gpAMS&_whFMzjv*@OGOXBX0!4U07%KDnfo-IsW|^0eEp9e!}~NP%WzeCfB(je%x% z88ENdse#eZvuoddFn{UDhh;>0?Ag_qV{%}5*7GmB4>OtV4>4-n^X!Bo^WoO>cTaV6 zY;M~7om{#we{=3xX}j#_3wFX_{5r1@xBV^rVfQ1lsdr2E*HOa%UCPUgwWiJJU3>5v z*t@GpFApLaW!WrzOk-I=l{4mzn`Y^G>nh5McOh9rM9ua z7HqNS$gi~#BGghkKwOy}MPzl+tf34cRY6fMCbJoCCLwExCXFFF2^U_w$wb{m6PTUs zT+P+S?7y_{=lLGcU4N9eoE}O7efqrb^TP#eplv4I$`Etqs)o!ibt7b~Ra$5k#2g%g z>~j0JV}YP~rKQDjURJ#fsuL~p65FLqmu!+3n9C-aevR$YL}<5QyI^YzVk=|134_;! zD*(nP9Cl%q$ev%ogj!-P-{?Yf1papB=%g=FQvC*>-RTM4fc^}pH9?3-OWk#GhZv~FeTSx_5NJd4Px zxf#*3k|&$D7$4hx9l4Iq?6-!vxsEpoq~Wq#L~x*+;%YqZx)hK+H*bj^$9vC<2@g^>NjeUuF9 zeM6CaD6+U1iP}NYWB|TS8XZfat!gA|%I(#{crnJ1ItiUlrZk>L6CLqV5$UJ%Njp;t z6O%!#k=c->TXhE0iuA}w>&Zn!Zzyry&SZG$b2Ozg#&a7U{1>qoCBj%MW#eG028fH` z*7xmv_SsqegC0PqEVG&Y%#sTAfCM%pTaQsyRV4qg_xw#%SRN|qR)sCBjC{t49l4KY{uDu z7ZzM{rL!y%#&P!K_V4cm0_Zy*h0up8=;Jpc2M$UrfN&pUCgfaAHVqZ6;^Nys{`)%4WV#n>JSGDFSP)l+9GXC~Gk?LB+@%e$Xm|FC`G z!cUb;6OvF*ZxHVCB+V2$Xso|&Ei2-w(or>u3%50)#3CvSXHgrQ z;HGfk9ZldIPOQ*bm(s(G2B;vUju0+acJi3q*=Yq&ozzi?TvFpSF@`S?t0$U z+pBtpu8z;x`~tkONK4ExI0O_o8LooKF)A3uf};^v@(c1V#!^(YGLHtJ8C*x)w3-36 z-B~x7jj9+p70X9aQ|Dz#Vi28d7#bsr24T@|C6R3zJ4Q9FJn3k35&j&lr6PV3DOX*( ztbDEN8wIAykQXzKuvaZ34Ebu(V3jSf5n~R7K?;=vfV?1C;EWOr;YA!*W3X>Z`BrOAv|X-~ z7{Xsu{AG z8PbhAU$En}tO7lqT}T3NRU)B|7PQYoL7lQ|R>i_d zn2-2yk8HiIL0)yM%f%`N_9O6BVbw)}s$2AC(1T63I{T3%K!ZBlO^!w@!LTY z!~4hS)N*3)tYll`dk>>|+2-pFqqb`eeiTJ?_vz=%r}$)@8U}#4<|h#z+S^PoT21-+ zjh|01JgYxFxzRox-X32djpOv_`ud~wxxTyWqen~N58r*4xvVnavj)6pl>|Mh#B0;4KlmaTDqB0@AJF&D1I|U_A^gW?QU!c*N zN<4dliI@ra>OcN?;@lxH1Hg$ro)%wKdDDoMZ{L3X`90iB5?P;^xfgrcZUorPtf!_P zY&>ICYv04)yDLus&D*0-wr?E&lM!G&$^R z*xvS2FQO$a9us!KEvmY4WVlI%znV?Ag$yoRR@9V)B}u#87%7u&Ev4{}ZFc2fSFfs0 zut_YLfil`=_P$|Zbchazwpg$mZXxFiJZA@dRc2py!Hk%HO90CyDY#Y;Ws!RoUctVE zMyo{sZ;6F&8$;zbIIy^JsbmjOA#gbSf>3BYz$G}ZjKGp&Ak71e&I(yEmBx;dH8Voac6P<>Bw47g z0k7Oi&Cemo?qNh><%|<|f!c&*(e3LJDb<4HQn7@~%AagL&)~TW@6or0!TdK09Pfy` zKn{Yk+IxFl97oq@hNA>MQ?NksAVK(Q`Bl9yT-cyFg)%zCK-%syL^XN~x;8@WfrY%x zv7^*Aa2w)lkjjoYspYUy-e|HG(UKQYR+8Ats8Qx*vYr<~PJ+G+xa|=@C_1eaJ|>?{ zaIJ<&%VSpU`D9%hQt#KrD~ux7a0mOs=)5}L2)&H>)l|OWHXi2>J75Sjv;7 z1tl&sx<-Iy*jICFVYbO@>L`w?lL;Wr*K7EO?F@c-2aHUY;kyQfc#@_e$gf^)VmBt7 zd3wj6W(Yl)ez-YiFkYRuyZv-|+ORUs|FmJ|{@_C&uw66y?CnsKh=r*vb+iWta|sl~ zt8qXXK5yEEonb$3PjJwvl=mv_Z~Eyqd)OM`U+A(ofrD;2g5*WTLgl_#B|Ov7r)q4|OVwH2l2vHU|%t+g_x z!3(M(L<)`IOH$~c=l=(QKf&P>FMp_9M|Z^tI_Nk$ebVWnC;!ie1lx6?Sx>L^ZnYQI zT_NH1y}?vUwmIG|MjKu-DwA&{TJxw4^JDz@HtdHLM<4GR^R-5U4|V&ExNvZK^6l8a zClXBu8ynvkrk=fg^3;{PkJhg|`Y&1M_S5ElhjEM#*oM)7c_}z9U`%Y+<~Z!6b+B;^ zBhWQz+R)08T0zDT0hgepN>pjwM2gx)Mnb4+B1Ib)y(&^wwNfYLFl{&6Wz~Oa-_P?i z&8CG2?ANbf4kCH{e810O`@ONjR}A=z!7KAKSI$j~{My?&#aH5CG63FvC47F>gyewu za>woHOBFAGE-L#4i<4mRnpUKWqlC?Yuj)~dA7~AYF#MRlzGTzTC=VA-Q2Co!`|i?j z`<&mXwpg30?fl+b`0JMsj=%rz#~07P`R3`-j~_5OmOu-X-TC&2K3!?Rl0PlA0NC)g zHd~uY9kFMXpNS%bFkRK zj(Bx;XVwsV_e{{A`^$|R?|ihh^e%Ghj=m25w#|0T_D#**p`kIE&leL#L)Z%TB(7Lt z6uzk+Ofs=tDW9O@T9ft4&N$w?di2)Ezq=iJiJH99JozM9JbHLgHQe>f`s??paL@+~ zllJRxS00vn2<_$u;rrcqdhMiZJx-M6{J$H1a5jw7*UsM9=vHb+x5UoUZ*Aa2dhA!@ zuv#3tOTIuDE{mFrY%JthT(L)7*znkAzzh5a0!E+%q+t>IT+&n;k#q@yd=p_bQ)_I! z0j+w4#CCjAUZk7368Tp&{z?JuVz7)D=Srh#d+@QHlBRu7>MPyK$q`%thjTgA45kb2 z!3mNyMss9x~;;hiiDQ9o#y9ETbYVG9O+hZt)QX&*ew8FnCE*k?Ko36ATQ zoWP+`RVok?O*|!AV0^yBQ5q4Be@z%xFLBYMgh6XQJ=A&Du=h{BFj{SSJL7Towkm8e z91Wel-+4B4cAvm30yk7=sPqjlg%5ZCot0`{F{L?kuf>e#5wS-kF zhvvA0E~s+FX|B3ltfhJu+!RX`%`otEfwaj;mi=zb3r4bsnC#Z=^<>c7vVRL+-EP;nB8T?M@eqMw&>pAh zBo$0$51voYpMPuoZzIpP7Y^Q(x_SB2?ekaf7zl5FI{&K*S~9G2dVE^=EBO@~=;`Tm zE{gKj|H+^^c)9PR*b7*zIu$lqi9#|dMJhLCHY%cS25raa^s6-GLXuor;3E%DrM&6( z!G^wQvC0qLX9wJ;=H02C-S@*UufFkSc@6IT##%l(_V@Q!X93tnr_@?{wv7zCDc*QI z)hC*|=m31_;(MBSSL6Xssz10mka+m#8cXEUY>(P%TU#3dT&qoeaQueBAtT^17YtH7 z$uD1xE%q4#ueRJ!wVl4#SMPPa_WC`0-s)?stEU@huz&Z!h<`#25{afWJ}V_NQQ2h9 zP9vct*@j(GL*{ifc|Aw*Db|qH< zygjUYT^Oa$?~7s^x@P=THHA7#HWEwXc1}Xh1wHopWho9*lH}`7Q?>-A_NZjZc&z{$ zyzUM^X@9Kd!EOO-K$~IukPJwTFcU!8noVzXKbAWw5Fo5F4d`-y$&p?RN2EUE^DRk@ zW!#pILSwm)Cj%veVCK&%0Jis~fMPaoVnj-RW#o4vH)-rQhZhO3En(zEa+P*nNRz4_ z%(2l;Pqt>y+7=h6NNOppj0%U0*7%0>R!12=(^8X-8Ee+M*mG@hIs^T)#MDkpZ9r>WI2fr%*I~b@7@OjC zd(6&`xD+jR$kBQbmh9Do2FdG@EbO8C zP>>prjnp%#YETQds&Q7Fm*3(8sZvT)WuE=5eK1IGMCgN12h*c116yOul*L6@uG$l_ z#+WHc%A}Y*S2gy{_NOucY9`a);GSR@UTauc?a$7s6@f`}qu-rAP9n7-t%3UZ_#?71 z1?U;OX-86z8Vh%~=41hOIg@VXY}d0t&&I2f2H09%?_bDP8z46|PjGJ}S6k0AjVkVC zyWF#?KzZ)s_vc*9^NgdbgQsl@tWF1=H>_-`F4ZETabA)BYDIN^uISHcr)O4N z@Z_M|t+vv#1gTxpS-Z(K7(U|;5(C*Kr_#)I)Lb*JvqAmDgG$MCQ*llnoL>>9YR}6P zTjj(qajUf}h9u9=(9@s}1!=z=TVB!kNx~Iad|jjH8P}Es?^Rrf!nOFGhn3P{UzF&v zef}4hS{u?=9Jr;#>U;2@?1=2!tuScHjy|z>1Jla`KVLs8zoNj?tu{ghbqo}}V~woe ze*5V{J(Xe7>`{TeWxs0PGlUF5#QqF^vf0R?x25~lL#zWS{k~^eC_8o`x?QBOZ9TbL)Q>z_)&t zL*Kf*`cd?G<;3lHD-!z>`<#@{s?2hiwCAxzQz1}>uPAKG1k`J9I zj=`eW*2-T_bvWm5jScYb?Tbg+B@-rjg3al8=@jkcOo_( z`IjF4aWh$NHp$H(En~BY4C=#|>30p?PmM^m***hOhrhQkK9v&6UOMCvPubUJka-lI zU0o$NtFKmrC)e8A?imEPNf_P1>i`n6+!c3^%lUkMQ{JS_iW(Q0G1H5@OcV#RY5NKM zp;&HKP6W02&2r+7_wn0cI_x*5>U*$qa01V^K$zIF|* z6+>x3e!CA?HY{%s`22w|#$lf;UAWmpBG!i7zU>=u-0l)hz+_UER8JT%_UkKk-=vYj zaM*=R1`Ku8n1mBJU}V<_vk}_TL;%-OdeZJZo=8tpwosxGsWh3JD3l1MoJg1crF6=4 zfgG%f$&wLYvY`vP0>N21=FZY#L5X$Cef-K*5V~=+GO!dvIYC|U=unyxB>1#)u%N94 z`hZ6}WilG-WD_jS)xMo<9Cwu94O)L0OZRpX482e9!VqCtA$1|`$7x3jsTUX^?(Gbz z{iri^A0?L2+mU$Z2oH|f^W$uJbxvGVSvV|tGsfQ$I|;)uMkQp{_<{|5?~DG9U;#Ep zY;R}U{83d?MuY9qYb0RF3mglpc!4uAFxfh%a-MPOlmlSHTRIRkGAYICDdWvC&)9J=O90k?s5<|jrtdtC3oY1! z>#o)|GJ4du2tE1*Iw%XQv{+r%dh^SUdFv&&0OPP3Y;NNcVo(8fg#Z8`07*naR5E@s zF*6M&J!9q)68D2YX|lL2(Zo|DG1=|E*!?Z{dOY8sDreM|_R~+%kUl@p*X#L3+!*F- zNZe*=ykfW-+cM0JjxV;viw*6OVBuO~maVCDMoq4E-*~a1VJl}R+eGcm;x@B*8USu% zA2tAO8(Gd}V&j{qA<|G>*zs1G-UOqsWsRKCF~?+XD&JQK7YJ=9ro^~Sh}U9{>9(Qu z{Vh8wEPNBno?G0cg#!Om#;z$Ab1Nj4u)!XG;);?b!fIS?G`b9QD6yX?dPN9Yy>?3p zm4cW zSQ5!@Ea^yzuH_?EXJECcw8^4pJ`yhLB0$4r*I{f#x8X=MZ_4Vpp$;Uukla?6qZ3%0 zSOgROjFPNKoTVtS6GJZ@>B94o;?lD#uLaNtZr|4qxZ-soxh3%2l!2-S%~MOiKe+n) zz1IMIata%;ih%!g;odJN9?v<^)?SV>Z2NIX@fVcYy@PY!E+eI2upj=F^a^%hVX>|% z4StDt4X(Uv40!4J@Rh=|z3V@oG*B%bzc6dR&fBlq+4=zh{&uK{=vjm3s;7sZk`DTk z0r2Gm0no2k!Ive%YCThFFA6KAM(nFdx8vE-Pj?ZQaqU6Z!mfRL;6D?A?WM-oaPxZ_7J7Pm zUtlom?e!TE#f?PD72YMHuzaD5IE4p7zK|j~!htnc2W*JWc~lG>3i$a;0&64Lsz?&} zqS?aq8wv%eAtV|)6gJ#eN;K$tC+r^sb65T0JBG&uWraKyG+9`NwPWEB`BvmiQiP-w z4tr+80Cwz-(cUnPM`UA-!JESq`ilDBf*+m>UoJ4FF3k8b8qMS<{HqhUjo)HU(o-WN z2F9y6lHj+Xta=Oc2&-r)OyTp@9NGYPMvT_rwlE?GlA^E3iRNHBkX$q+rGqyK5oJ1m?UAF~oCEsXzm4#jA++maAOQNrHep$8i|vl#@b;k|!&;wj4fZ?W z>mBF|MEU~8Y?({La}8~w#twDa6Z3FHG}-NieRfPxtQqu1krh;J5{*d#PoCAM<*-ko zT9Frsv6{`ay+hNRU-KaqjW+Fr37iE^?IWq9#Y+#>PW*txOvSgWl<3Fh3yPiEREp;wgUZ`^82 zU3Zk&Wn3mFLNaAR%X%aN2ynWguGcV_aBAWqDUFYK^@Ols$+Da>N?i;~LoTw)d4;4Z z#$KCnWki}-E0YQUFDj;apYgVv8l#b}YHlq0UF@otfzE_ii0GusMK_0jW#|>uV%4oG z6w4`~i(cTC5f1^Xoiks*kT6 zm^^pmD7`wu>!X)MdoOtlV579EJDRKh_SHRmaM1PJi zEGO;HDAm8t{fi1q4&MbQyi%VK3{WHL%5L&s!1KcHGVn|pk_(N>CY@&bv->qKc@j!G zIr-j=3r0lIc*X4{mHO;gip!8jYr3|v@#lx5MkSX4z549Hw0i;%Q?0h~#v`IFN}w6G zqU`eS@@~9dKmL4p(lY`BzlNL$pf_rhA78t$t8zuKQPEvkhd+IK^zflWv^yLl19Ms) zsJHEfd>6HvvnkgU-F58D*~j`1*i|QRHojc);;u1Z8JL$oEmbIAR9Z)+PL7zd?D%Je zvp>G^u7UBFA3m&5nv`7LE&Y7`W-9<*_9&$)Kyk0(uYI=q)HoLiT@3grB=iYt!-PGD zLcr}B+?W1_wHLj;p#kZm={}P6ml!R7NbQB8Fo=qT%dj{c81M%IjIdEngVA9~aEOiX z8eZWw(PKq%U=5xR8OiNg)jfOEsBV}b4y9nthYM;+VoNMh7UHV0u{>@hEJ=6JIji$% z!XO&I(rSL*j|!ScQxr4U0fk?gLNhaFU5wBwPcSq{ODME)SnNtOW4FnuBwJE|eVY`@ z8CbDGDN}{i1jU3TcTC*Q?*OnnSb}HrJK7N&5ZkG69`)yEG>DcB2{fkUcclLt2Fg2z z!y`Y@k5otzMCk&djr#7S27ek%^@GY7g$WKL-@ZNg-Jr)`2c3y`P^lavXt3U~ z8yS7yG3fni2L;z~ziT`?>XM+1@4lt}Uk2DGhKEPC(OnG=Z&ON0Rq)8*(G!OV3GW+F z_mTZ*M5saP zuf&#^Dq#lGK`FGFuGo;w4r8_$fw`r{Fq&47v=Lhl)J)sX#Rn5%Tw0qkm`(%E!4>;( zTZsglR4z4D`4B}09eL7hQnu8}bjbd|0TRTJ$&lJkOWzEsf1U9dZejV5%D`Dvt%qeL z!~%beaU-^Y#H23%vg-2Ip`qZe~eGG(K% zo2O%$E#f&A8B4c_+Cl@?9v|N#?P`;RF3uTiv)bib%H<5pw^WHNX&6&-#?Qf4S<7nU z?Jd4BAQ)|T5M_63>;5Ydmbal*FCSB8z-ixwQ%HVw#AR+YoJNX`uCo*gf{W5;iPOGH z-Ej52G8Xars)8=P5X*)mw64T($jgLGxOFk?lpsuviW|-a)lhqqmd!;8r4kS{90K?OoM%1%1KXQC$*UO5m?DqSc#}a4P7_ zubA)q2V_{D2+Nf(9Ph4yPwK0w{g*HIU+y0eVI7xLdTy@%Xz}LtN4L6`rF*%)PQ*23 zr`2AProU6ZJQbR(r2Co*W{pOD{PYL=GU_zxbnFWB%coQ4EGxU%p7xX;Gb4e?+d_DvSdiC3yW;_^NWA^;h%RuuPogB>yNPG>~g&n z-@EZ;TFlo6lU1Q_DB#?^;T~hZsv`VPAfTv9Ce!3ZD}}>nSiEN7Y)Bkn0~|o(Y*5~N z(YP%ZB&wA{WOE?fQmaECbf-6jm^o~R(42%CYrY4yRR|rHk1C{|wY7O9R^TeY9HM<8 z>{m0=Jd7Ci)mVs*2EPvSYXj`RqrtO`!4wr1aQ*UEcx--xGT_y`_QJ9T7YO5+SjD15 zKGwW_k)Kxxbe_fq7yg_tj7&_B0IjydnUn!6Yu|$Ek6^M!cz5!7C0@yqG_smUh&7}8 z0%65cqP)Ua^gpW3@29Ce4dc>MpoKx9wgJoXtH5C?Kde$6nNk|Wk!E2;JL7bWgd)q< zrK3hNAzpB4G=@nCF*7D4;{}-uCNZNXYl5Dr^1(GCKt-m6NKIP0vF3dGb+?{BaV!uCM1tD$qJ=g(YcLGyjfDP?8an!i;cqY)N`_=fVqzT)x-~Hy;;0l{ z@&jvT4M3A)S(2Iyz$H#P=s-DyEDIws>6U|o6di`Qp$XJJgiB706^S}C6AR#w?@a=H zQ8q`zLh3=+JPg))=&r+HFwP_rvIxjxzN~s;Lvw<(4oawD;K<}-#mJ>5eLAd?L!-C* zMme*C0$&0?vPm??VV1ZW?5;yN88N#s{R#j~@`qxy)bLQrs&)wsjZ4OyT;KL!wZnAY ztPg{c>qxJ>VdYQS0dJkT^%F0S;<=g+qxtdS?uohW6s!_1#5&0CkfabvFrO3sO0^Pn~u;Xcq^f-eA#jH+)Vzml9n`_IPYa zmp@qoe?a2PXP-asQ4L`~N~|{3EeM7$v=txy@4=%VJ}qN7?L+Q`w#C^FJiuB8_wRik zEye8JR_4uXC|i=!-+mHGUi5%V#t1>`#M}^1!<&~JSJuYiWGw!szxb}(FyZ>uy2t%g z9Q8T$-8r|jvvZ~JVFYb21<}lsoi|SK= z&Z-MIr<6tY|8C{DCuiu34r&SDT~%i=xHM^OQ0v{?KQn|y=2E-MYC94HlRbI!cZbe7 z7buI`_Jrfp~iQEQi(x4k;=w1a zGgK`dIgZJAo*Q|qOb{mNE)jz~tJJMqFYeZVeZ2mR1Y2X%GAEM-Vt>r7&5e!SF#z_n zKW3&Uc5_O0PGyYcZjrl9REJbo?8sBP6ksbYDOL{yXhZ9BL!bTU+C_Wh#n0aQzF`3P zM=zjVuH-dFT5BSzUSDv{N0M0upvMbDUD=(+V72PSr4*2AxnYGhG3H*QyI^CR-mS3xmn@R4YdK)A+<>SykdX3Q94;ehys*%B8Fuy}onrXBspu=BoE!Zctqh%CYU5jHwAQeD1O6)p+)d=Orp`L1435^;pVY*# zQFlH;mX;zs62}Y$jpfz^8`w_-4TLcxg&fI+)iQpjpD@C#SrDwmEO53#CSg%y!7m=A zkVtOOz%!yM;Re*y8bNEjEE+BIuVO5tA(U78RfZ_rCzatdYg~=#a0`d*Q!I>l3xlv{ z{D9y}`^-wJ;7}f>3f87rB^L9dhOH%L(3p^**U98|vRt*#JViY!iW(VeK$5org46l5!@|+>p;cDOckayJy|YVg}A8 z!Qg5(zn)FzjUXdY&R1Z!9t9HHKy5e<)_TK9X4sV~30Fp{lT5lR2Bfqi#?>m}+S)yd z!d&hqFQn|14erayk|y6rmF{uxi{CFCrA)bMBjsz*h~N}b4nzxS$3PiJr=6A8p9HHg zP|IRx6qel%nU=nP(NqgE& zyrU>np7Iqxj(cqeq|M?+>R>_xm!fZ{FPt z-P`3Gx`X%P;h6q!(8&^oVMzZC`6T?YJoF*8+eRP zx4A|%|^tpCdjR{Q2l?B-& zLTayUCvbgw+I2iQ2*z)G?fHETi!np#OYY{$Oy=SB`ueYFH#~XP7_VXb+}zlmwXw0e zvAH|;TjS^YdIB`hPXD|E+NM@lb6bj>NEuyJAZZW6sNqsf` z?SF4H{H^DH%Z**TFj@L->sBiD>ftZRU}QlN9QKh3yA6blrrKwyeZWGCYgYong_aso zTw$JmOa*u^8TL6e^FC za7E~b(c#TH!7@(ax>GLo`G^`bWUkZh*R?hDB3BlNty6Lq>6FHU?L>*6kyR=EN(s@8 zBx1FS=(Y-1f08AsTZZ67_XhlTBT<()0VoTd6L4dL=R|kwiN<66r&GrO&4vE*{s@F3 zDhH0pmlS}y!e4b#k@C1F$gw zxrhm7!*2u~27|N_r*fUO2E|nPEs&_THO~5qjtTKz$L3PyR%bu3T@L_t=NtWh; z)jYkf*oh&ZV$6B(V9;?=8XTVNdvVYI+6P|q-jl)gYtG_EFAet9j$U`+4@g z<^6aZp_hT~x>v~$Qyh`6mJQS^O7t4c#*J?iBzMMcNsZtcgI|GGet!%D|*TWS-QgD zf|E)KBMaiBT?M&y{eq*k^Enm#Mu$S$T??p2Dc$aOJaqXwt#%jpp>_smGB(64IxA6E zQ!!om6C~A4onj+4!+sVeLN1jGrUkF+TtEe_8{oT(PS? z`Coo3;cWxpj<&X=2&}e6KW&mhbMZmbUjcX?1y=u}Ve{*2H#a{U`HGn|KHzw%9MgrQ zb}qbW=@ARL+U$xe&W=^=s*&It20)>5ObP4uQ}D&R{^DWe;m+>ii-GO$=i7^IS0KMo zVEg*_{1F3w|6WEUWk9njo>wJs@${6j;l+nDN3eVQ_NPW*{hPWl1(#4bbr6R< z*=K;fr6M78Myb9Gb7uLEa#)Gv34$v3L6MCer@*--_Q6Y&km#j%H;>EYJL7c8W8JU& zR^1+zb#hO~n@jaN4EP$&y)&^#3^dxNT*vE67?YIW!D{x7x090sOCU$WV;@4~p3H^R z!+*>;8JE6@+#0(Z-@*Tz+M4aLtAWYf5|3N$Seo5>JSNH2nfjAp@7j!UUUIqaeEH?o zyH~HzP5b%N?32fm_o;8d$&}$=W=ly|nJp@gVEwbs_`8}i%I?nK#dVxJ_1&w`jlLz3fYR7e&eoe<$o7}h52$h;)c z3E7iSH{(?*fy7T}ULYzOv2)USfAf?V<_&i@OQlVuScF37OZJ%$(+ivjfEhVgO3a+Y z*}Q$O#WUO6X+=P9t9}7n zQiiT1!*mz_{AD~&r30OWCpj&nn2q%CWICHx$pVOOpqjO>T6$Q&(K`4g8ZEM-CkG}c zGemD_B7M?uHcoMpVQ}0ovI8!KL%CST3{3+@eg~ntQ5;Fp;9yEp0p`&fC`Wn6hA=vX z3=23mU`DiM@9E&iLERXWpJ|X?uQXVmr(8?c!;(9rpC&;IO|%i+7&MMeb;M9vSkhp>5dm8>i{coJGPT!o6Bol zmC$KJcv6W-01`m$ztbvQMMX`h;F4N| zyGz)T?4)kDu%otyoUvS`PIG_#mb6nEZa=^z#7A-D>M115c01L+IF4CG7m8k=p24DX zC!w7#w77) z&o1RriYy3`lWFI@1^chp&cXWXQDp7e_& z40y(`Eo{VcyVGwnZ~Wu;mfA7t9Z+0(JIrv{wB$n4_j`J3B3B4`9FtPhNvdlg&7At? z+h%h&^5~mp^W#V7i~+A*{`0O7cvmod>2L&X4`#xto{jphZOpqq;0>a&7VfPa#ofdC zvw}E2Y<=t0M6lU%xvW~=&N#!~ajCEnAvYS!56dbaoSIrz#)Y~Hr<@76qaP7VFFPsp z{%?PVjYyMZy8p8O0;4-JH!%_3|6HS9u=C2w-1+Ot-6>IM${hAD{$j-+PS34enY(!N z8X#(S3QOMt*XsC`$Lphev-Bxp9TL=^K0SB6vX3unt5Ju%J}h@WGl+!B*KeJpWcWRV zSHy74UAgh$@lQWJaiX-DNEJrXbFS9mylDINo43l+V?&^YwLt%LSt_z}N9t$gj*OSp zI9%`4>x~OjAE*ED?B2!4Uky+0mmBqZofwZP09b(=_FB3wKX4Gh)B+ccRVcbXh!@G3 zdL@HaR}y)YJq2F%dVydv%97W<_W~iwn!|y_I$mIEeUpihoJ+~|UNi|x6C%y-cM!X; zpFU})7@pdxPm_k(vj39OLH92g$%Kr)hQ4{}u) z7QncGg~Vi)B8fIc4H%ytL?Ug!@Ir3)`){(cqR`xk#L-$EJ53g~4xtn!)Y=J0rJG90 zIUMrvBt=*WQ^er4rQR|mZxcSvD4C;JC%3!cdCChECC5^vrQAw%$fW%7oqClbsG((6 zDgw{oZ#NPvMvN_bksT2WifCenq&qMR8Jqh377>B`#Uc|yVXz1$RS?}SCF-#vp@GC= zbUdmZ_&I|5OEgkMewyG)fJImxx&)xzT8lBAQy6j>G=QvAOJ~3K~!QRhVt|ucMDf@ zdNaY0y!g6B;D{a7FMRNPM)_A7%}%(G$yHVEIiT89YGc@`xzT<>OG_- ztyaIyF&B0<1HR<8!Q?_O%#(w41b|0fTf^v?@OKNN-xOY` zxM9Hn7&5CZ2~8!jE?MgK6nAe0G4FW@A0l3qV+OIv7h`JojHPln-!#{5brXBd>a$bt zZ#CCuwnTk*-5C0Jm;Qb*g8uQ&U+o8+0gSdM$GS@Kg8YtMPd14=->SO zV&RqaMilE|6dIpqgX-d+8(XfNp{)E1IPSEpJxpa;%1%wQHb&{xX>4^w6dBeoe|JM8 z=+l1x;Pvn;A{&jAqS)$;FF(Kjp13jdX+vORx%i4ZQx6*##_#_Av{tm7XaM~AyeZ+nSi2-0LSYK*S@;Aa>cEZ6~!?96V^S&x0%{_A_oJX(2w%go?WKa>1i7MM4twze8mdN*JXq|U|G zmQnLtJIUSMza0N)_};Y(ori3Sry7^{?mvnI75W^tS5a~(*L%iv+ya>SF$D|s8)5x@ z8W2>_S91{qyllq(tBf<`^WqbC zW-$CDknAOl4hO>upX?dXlK-pVa_Y#YQaFCGYs*&VAg7z+M z&gRK`-pncyYcsJ~A__XM>2yB4smXJ=qH%Ods9RzSj4Qa5uhfh|S6KQIjwPG#_bh^I z@M2An1+SHCNl>dTt{`_?)ks8DW-4TBh|wAX$FU|6t&!FodRuB}C(t6%Dz1`3XfUH_ zyC4E9W2l>npUhHy%80_;ds zg-L*}z0^bvkOxy5H={?1<)RP(EsPa44KZkYgjh;Gt;lKZc0I1eL?8O8R;qy1OZgpY zX0iizung~zgV~mj%h1*jknVae8^4t@#7h~!1(mz~KJ#eRAogQ@uTA1~p>M|vo%NGu z(q79Wqq3jtw+kTP60>Vfp}R#D4lluLTjWxWNI$)#^=|Rh$kq0PkrpH4Rv(+O!LCv3 zZoegAm&>{2n(=$WfT=$QqRA2=3RCcqyK<&Vz4Qda_+D~FbL6%bdxm9%1Geh3yIUv))E4t4eCT-8JMFcXUf?vRVl z(%4(w3e2N79PLH)EGDd0LbWSxY&2y#b{UmI@t;Id9&rH^Mfu|SFI~I_O$(}J@U2J- z^LKvu@rNTL=uwx`F*^Rio6(tTBj4)4g@wHWPxF}4H5A?I>6x#okYZLnx;wGw2e))bX~uD*bqiSbvtE6MA;$# zCF|^dn>?&A-q^7lf7Fn?xJn$?#xb>Byd+I)!*Gd{QZ!;jMY;&&X{+Lpf+;CwWm{Bf zxj{ljQzm5y0a7%$K)YBaRD!fgflY9;+iBW=wDWt;8`f?qO&q_kKUyq5e$IJ5mKhI& zsZCV}bAVQ(8$Wr^T}EmnoW9!HR>)Re@g7DdZ=Kn9Km%w4S^N6rgCnITF<6FkXK$W= z&xg+(ot}Q<;aRVRs7p>o@&}PrrP=1W(Z7#e5sQ{>$*Ajeu#H}fa^sR0G|`l}On&5} z%=?&-Uf+i^>dcwbw?02q`m9}YXx(mvr4G_SpZw%I`=mh!F~QF?4CXgCFEWZobHx}s ze{ohAyxA-@wf%Oz*R$uP{8!H(?|d=4;Hz%Co9&y|5{#N7t5KzIFm%SvJCuB3Z>Yv_ z17pF9(px17-=LMj05nSU)i9BhL|d&gQeO0mLP~*+9xu}RI}lkEkb}!f9US7g%t?{^ zisXm_)vMfv0WOPT7Q14_G%m0V&a^awUiHwc%p&nunMzAXXe-o)co5FpI&4H4lTpT? zwo%c7*Z_9$9w;m>Y$y!gqQ;sWR6QXot0__|D;0Vf=pw|GG&xn7SSf`43yR%<30J~- z^yHl>KsYz?52>Zqd1QdRk(!dK8E|I(TevfkTPegPgD!X&Wv)>%!aF5VmXTqSuo{h# z!iKMX@faCfPECTDjHXo-TmX!7Ir)`X=8mWgSfLvDfyuurj3aL5irm41#L;luC#j8; z)K=@cl#iz=Bs{o2@~5~L0k5yih(w|#c+G@5H;xNfeZYHp(fij^>*KFQ*!J={ZOAyP zy*$uBOO3@c*u_^7{gj-F*@-aNAQI}Vq9kU^5lNtvo?^)zDndG@Zeeu{$Fi{HsC>jp zy%CYeA=q{ElHEZx5D`|gbc}SYnCg@4tg;zLQEV+Ni| zGC*;iOaR_ zZdQ!fc`<3x->uCjC}h0;XQX9iIg;&Re)-+#n8K~b zI-OSqMNU*bS);f&H!jZ1y;MrG^I_rMn6G?09!2Re90qNOyoS{Y9qoRd({jTxPr2-f zdC%-cZ#f7XPXFc98*j^gj(={ucdd!F0X)jMi=jBNn>MI0O z!vbLtUE5w5?i_`NMb|ic0|PE3*I}W{QaHz$uZ#u1WI><$ehlT_B>EI8=o_=g&iywD zi&lnX9l7GO~6(579em+&ODMJq|C5CG?w z@d^`DAvth<^NX8Tlrt$2meJU&8 zf9IpnnglhrKl>jOu_dbyeF)3#P{~!_Y@WLvoA&+h$rFl~y!zuqd2%A_hoqU}si|ym zIsfUSkpl#8>^rbeNzg|hE+c97@p69qk6z29`iB!IPd}{_gw1^j`z5F@m72@T_CzGZ zBK?bJ!x05^X$xGRy}(ZVTUwDWmNq|aUsx#p?bh!TFOv6h3Go(c3}rE#723O|lr|v& zCY5rCazX>g=%5R$0B9KTi;VnBsx4wz9T_6rYKRea#3j>_sJAl=4`md9wK|jux$zJN zBvld)47f2^0UUPKs``->J~^O7tU=!cBYz%T89WT_HL&$`=#~PYGc9!%O7^@mI85?Y z>t1E0GF-V=X{mIfH8EubxIrAW1kNoxhlDJCLtVx6xrN}0Q0Pf?T9Ye{6(r7NZ&WIG zWDiDJh4yNyfqHsEkbAj^IlId*esB{^0n!%)$oB`;Ac_1*Kmj9h{7o zBx(VJSJh3Turgq#{FxU>l=*Wc>7L*uf9oo@6rh65nn`n3;4iQk#{&A501ElCww~D%r&K*_^(*@fo~RsAB;tu+J4-&Kj)f)iJj zs%3=s1<9C3nAbuIoq${$qO<7j)7YLc+P$VQuwFGQ@t5isnPJ=WH9ovs)@WXd9JQ_8 z^0n_4#AfNe?YxwDNpVr3uU6t>^$1EbHKVE`&4Y{SJtABTWl|l{(~feUiQ6bjy`>X7 zGvVY|AschdqdQVm1DGIXM|>8dJTunZf9cYfZxz*zr1(g0Cl+3c`WDl^@zqS3D>`ml zmfOg!!CpEzBiVCWSsZiX@vM5&*ppnIm6kVnCcOmC&v+&!+<0ydLhYd)X%@hoHn;Tb z{2nKKWdaVj!22FPY-^MI_Nxr&V{{XastxIfJ7D9x7?J)ue)?DEfBHtDe|FTD!jIkz zqFuU4%E@jJ$d|_qN6B%XA(u$Tx~`Z==)-C(*-glU7jyyOxsSK69etzx7*ad>PN={- zA}0J5u3BP;p=E?ujU|oKthrV>`^-pR$)C{%T&M!-N ze`oXU*^5ne6xJC*Yx_&IF@h^*)85WtOi)cgYG-g{q)sXS`HxN8q!2FrC&0I{(f!nTtT*EB5V7;h7fA1Y}D4R1ZrQHZSCl{o#XY zw;zQh_)2iwnCnIG5#mZ(hLS<@%}<~GVjlpE3L2z7__XA$60Erux=z+nH!}heE-5`y*|5O5Nr?jEv934CmAJI^Wa+5 zeVtO#@cv5TLR3yqrqB28+Z*iaBGlDr>iq$TPNcO6EQ|UY?;RMhTMi?fR;n~AX@lqc znN{hqNSH*RHSG0B8AjBrk%7g5MI*TkrXzTeSo0dtW(FgiGpy>tRW!{5!x~51x0a%x z^+gip;EG)}Xt+9j5B6KJlkd^Z&_a`S7;$uK>ae!J#(QZ%BGQWRNiwpG0{ftO3Mj6S z+c71ZZ-Xu*?7=LB4PEVPf^oDWuqus)2T_8YiosGGH2)BcB^)-YJ5|U{ZUD9l+MtNA zQE;r~BC%Py4WCZ$#dBm!(g?;cbgA+e-G1NQg-A|fwRCQ2C=!xI)40BaCkWyFE{8E&lC5JT!98Hp+y8pW1g zSi)yApaZ7aF>g>Z(Co@*?1m+Rr-9o6#byNxzeE7$H`6JSOe1S%O{UdyRz<@xg-Hhr zxa_Kt3AP)A{~=4sS1NO;#t#j7|9nZDI=f;^YaSWl7&f|+WxMg;aZOx1t@Q=yc<;QK6+A2 zv;IY##p!En$9aVQ76WKxV8)@V*?D8w=(EIT`-#Mw(lQNldj{WISe*&bw7aV*oU>NV z*6jbTZ>#MB=eESWzBe<1CQdBzp8d1(OHA!&YbEMbVw?2&vp4P4ps2Srm;(k;+B1i*bXf)Jha8dNck2{-eF0=X(s4A0hTRc8mh& z@$pI(_wW`io$xcT#DdT4ovaO# zu-?AC_pr0H;$tpNgcJgwLWH&W!@~RYjX@Z+kHR;<9R0TR+;Ek)UzWaNjK&~ImMolP ztgLJ-(LT9_4Ql6`_>UB;K_&;HEg0hb2HseEmK$e^5@3y<)_{27*2UX*<~gT1Zvb9+ zdgCxi{4ybx2D39)X8!gJm?TxYFuxbR;IDwe;IFM?ovp@Y|^wQ|1A&r=g0Y`t_nAOxAgue0PMc>S% zSG*8CQi<>eqxigp-Wmj~sf<{?3{1BxvjlO2TIjA6&LMx1G+YOE`Wxd)VO2F4 z1iwixt4e9vfY$)opnUxx`9?Wd2()^SN5qW*<7I5a$ru?Nlnm25XlyqS4ij97t*Eiy zu$w*O$&K}q9x>3#sY$gJve)%RSW^bnjmM42hF}@xl=_d1Ggp;|WrVg@Rbad9v{Ns>v)oS9x^O%+_e$% zYkZKxVL+Xu2sl@lzzWp8?*Xo!N`P7J+D(i|c4unai{1xP?MOr6$BIT z0U(px@kwgiaQSR1bvC7x4glD27dLk-k$fGDMaV`2e0jeXOQ@MLp|LZxR(s#jvOK}; zFk}rD3szW%G}3nGazu$75s9doOeRtMU%ZluPG?%)W@~Q$Z?fFXnfnuK~#0+G3m;G$1Xh;b;ZND%;Z11*9 zANO~Q|0wn6GNpb7ix3&r-Cc>Pjr@{i9Y-r2pOYAi@*8XWKHb9A(tRU2F8^%}qaR7qIJI=-seZByk+ns8yw*>{aaEtT?$>#87F zb7wcOmWo*_=#Jydj?w-mM^ML2hqDt-VC~y{+{9R*>_RXm$k(vPv?80E*EauiN^0t? z$gToES}H7*OGzxYb8N-EEs#E%P3Gu~?(eo-7XHHC!R#z!7}zGb)H4{;rNt8PV6z zow$DV;AQ@>;+HcV_A?0$mqmCJX=DoQWB3n2TB{6tEM(#=au_aUT$ZcdRiuo8ZeKny zT)uqAr@xK^|2;bxLBDAG-L(Vd3Or zfyiTGj+?3=K<%p@`ljj#nmcmB`ZnJACV033NUa&H&NGKzJE?-gyq;mNF*-<^B6e!# z;y?emvsTzxRD^OqfB9(4jeFs^w`OLxuKs#*hl#EM+U!wyRCDPCEV{R5ww4doR4lo1 zW!_&Ds0;kSg9LrOa{f%y1vDFZB}dXtp%?QzPrki0^!d=xsC>W|wx*u5 zNhVXPkiUNY*_F@5e_cHFt@;skzoN!t$G2$!=3T&A5AB0g;sJ zBkRbooG~eB@QWatUWS9ldRYBO#(IHT1KlvGS9Al13A=LQ=w9zJMkX9dsss*CI~Q=T zN;SijS{EpBpbPkaR0Siwno{)DlzhK_Nw6{D>bUDgnlwNj$Mrj1^+4S!+Nym*u*iQ# zq*Yf`w4LBpJ(r6`3dgV^ajGsJTt$aPq9ix&=cJ2vF&$BA8pfF{kBbrG`yC#K3`fVw zZua~Hj+ETM!%h^Pi*859pv%g+GN2t-P&7xB2R-&3e&A0C=}?>&O@rI?Eu>QST^`5S z_L%w?sA5PR2Y>AYtKjXi?SB&${mIxz!S$HJ(2zabJFU<`l3O7NvHFn?Vq(KUEyHJf z50~bjldslt<-xIt;?|5IXA%L3?y_A`lK6)cvJz|e8{!HSat%vqyVG|CYpP9aL&9H= zL2MJsxP(8ai+1H&MO*Fm#-hyXbdVxCo-jg-^ok&lgmWUHQEa+4>C4X6Y| zj(^3nB|M zb1zEv4j_);3d<5|s|?nqa$lI9DaZT$vOP-%LQRf{-B>Mu@$9mwEH>O@uuR{cJK@J+ zbYw7c(`46iRO<}bt706Tu&UFkbq4k$2Y{Lm*F=yzik{5+xf}}DxaZ8q%8*1oCI2si zs!r|I!nJFgn-`v|Imx(jZNfJqIRw{i*}03!Y<6iO&gLue6gZxB?M@w8lU)yzW6g3M zPq-y-7MU{&XvAABXF(E)c7f8Ek7~*aX*qISYqfs)%X@py=7$XU=INg(V{qKokKu5% zcJbWOz2A$V@2(6ID^L8qfA!JVKO8xD7BF-u=Zk zKM-RHg})rS^662Y5%LDBR<@pEqjChX>SfXSw35G}#^4>6rhsl!t|j#o#S$q01rvzODSFAXVdYtY^>lloa`Nu*X&ksWB6*9wdOdayP6 zu6V(oI(R5c(T>~QKG4c~R4?hm!dCdqjw+#)9kQ4&JjGDtRMGAcS`jaj%wfR1GpmKO z+LSAmHB~b#76{?sRX+dzQ9G@m$&jM3B#kkYWu$1|?4T~HMr9&Y2FC&s3@A!sz$P3R z!5PeBjVv>zUOxy2wHvk%%R%jVjVY_KK_QnccVo#B?7qmkqW``_S5BWVzA zBw1tTK%fyE2{d}^Z*V0^`b-`rOJPM)_T&Lh+8>WG02|6qan7U`#u$%`50jFmAS`3W zR1fwhRZ7^KZcs;PXzcau#&n}GKwG2AQ*r^5i&eMZUfu5W?8K^~D(z2CeGHQ{|5hm+ z^z*Rzv5yOQ-`lUt{#$ixVDc+-!_%}ZeCJU|D5~svxqVj2-f-Qs<8{Y%#|faso)m@m z(u3sDY&4uw5Oj{Rh2i0P3Ut0tkrD>qVW)hCJ2P13OeJBZTx$~B+$i!aRSvo$!knlr zZ4KC&Xe5*%%gM8%#|?DPj*-lPXe*UF{*hX)w95~~UIz!sq$6Qj)eKUDK?PC*waHLY z;w(efpvx}}X>+WQN?~$D!Y!Abg|O>@xA-B0+k`Ak>J^rkn6nj{MS}ElLSyEbYcG@} zE9MNsVg{j1QJqS5*&<3q(!w*o>rFb8dspuFC3)?QcqGtBMA^)Z=7I2({9E zCg=T9dDq~#%cGRYL1dTu-3b}d!n@3iUoGB#a$+Luyxed z4ZRa?zN}VW1y(AULuninF6qj-l>B%~a2kb{3zE*hYgX#`!O%(qY3aG_E1bV+1o+y` z^Ghv%Y0T`p_J6j{?x(H84CBQIQ-3fgjMofS9OSxVBR4G9rRXK9PD z!zc<}Lf39lF1SIe)(b~MQ`8_;3m4o~s#q#5Qd*?srgzh}e`)XUc~3y=CINxtV?%^F zkDvE_K5`yEtvt(|i@Su1d38iIr5T&iyt!W)mduz%q4PepZhBFJ%8y|3U@I%;e$T!F z)V-om)knhfnfy{NRA@C9bp8xtq1FHZAOJ~3K~%y0pWyBx86Nm{w}G(v_2gOWU!n2r z(*Nv$rInt&H9q`kYiqas&UYupnP>OTXB2QF`9o2w6toX^jcth(%OVg2S-_b;13i0r zsfl4=;|F4`mW;|a4N@1HLd^r}mU)B`2_&%so0S|F6QS*Vpe&-5svYjom5F(EwrSzZ!;(*nhwFjr|yN zUDnK0G~AhE&P+RF?J)I{Bh>GSIvC{aOFdk9pK(1CK(o2%1p>HbnBo(9) zT^ZrE6F}Y`lCbPpFSxt{`ZA9u4;oc8YAm9iVaCRMd!M8`9UQ~;Fc}&iT&Ewnm-?fQ ztVyavqL!hzRH_^Coxtd8M@tI7vU4k)O0Sl^(`hm) zK$$=+II!Iv9du!{N(N;C(48LH#CinDl~w6+K@#Yy0cKUUBl54Ro<6ClNrPXKH`E=x zx#<9{-oX)RsF+6&ZVuX8ABN$P6MgKC`vymnU-cz7NuIQGkydd?x~rr&DI`Z&@(v=s zQeWYT(IM3ysfj@v>EwwAqrbGTMu(JpWoM0!4ju1H9w!)j^aQsZe=v#&E1)u(7#4C_ z?3EQ&z?5JaEnZx)gNycQhQWq1#iIgPO;rN*BqcoURKOZdh%MX2q$lxG5go*3!FI)w zeIV@<=tNclTM4%ZFB*m$7{;Wjj%Hq0KcEbaM*Tc72_<1g9ZcD!ozF0fA#)8*Q zZ`s%JR=dr-JKLTT#Vt+|BQlj~lgW7=E{@&`#AessHV!^X#)FKd?KNJfwBFf2>21CJ z-Y7_<I3X`Z1GC%Bp4Vt+y7q+ zBG4>Z1LOyRgjO&?!gnm6e$P~S@7vG5_zS643tmR(MkM?A`)~*R@Shq%qj?@z8E0f?7wiaYU;9AA(i175l>$v5mLc(zdOg*7Qcw5l zV7jN1?$py&G|-%e$taaFp4;Jgi4q2xkLnXXhQ=8@-RV?I6O<#BCQ2pM63UR&s}riF zQmLY$wCa8<)F_a=K{T}9N>w?6D}}1Y)di!lm5Qdx+5m5|2(FHJBca_^VmGY9BhYn( zVe{WSjiV2bFvY(~ZXSGGF!*NS`#5QjNdfSn>XV4aO3H&IH*fNR)L5vlC{BXA5}Ae6 ziXNn|47KqZB?skL>ht+CeGH<(^e_OheGgQjH2Rf+^QL{R42}m5(@9zx!0e%+H+p#W zl#1A|EYd>{2d}hN)JsW_+9J5zL*7+HeTASj`Dcq%2s5a**L3!dZW^(lstb{B;U!)a zFcVG5vniog;V2AR5RPUVC9_?SVp3}nZ5eO{5?7|qu;mUWo{F+=1aWPEsS-}Ki1TpS zH2lHt2}{l($kOUK&bjP<6J$vjrHziaGVN9-D;n)R!bMQjQ>QaU6+(bw#f;0HqElg3 zFTsIXm~cG%g5Z4eLD&j|m4eSnmb5CnnUrpNvh_*a{mPT=^V{b$YniF|`8MT=ZS9}4 z88DY{Ou7`~#TV`Dq%+wfs;{_Y%~@DEXE zs(-qFIhR)oC16N;qlUwvXx>|Y^I=+snt#1WK@uni%gW{uq17bXs~nbC+2&kAbwx_9 zT$osycW;xH!pgZ)+%wc$y$n$6<`;hw{(k)at_ZP@ottVV1P5Q`6?dhdBER$s302NB zukt9J;n-e=C~($$erCx7v$X2%_h5~tgx7R3%y@tY4=YL5f;_*_;4p$i)ryd8Z$tV& zGiYPL`&(mh-rFvPK6&fp8CPT7nr%LO_{aYmL7$mbNc72*ze_yd{o)|?EL<5sGin=T z-BuSI?pze)DqVvM7}a57Pra6hyTXE5;=FTU$|J*&?s9jzCJir<%aA_K1Tqqv9inw{zG;cxHHyF1tb_|m< z>z{8mG!GvhTfVI5YvL!DS%&Lp7_J#}E;HHIyx!+7hq?xaK{}dZ`lqsmh#G=}h>RzZG-O$gbS`%e0z9DvD`?E@8$K?vL_;f` z&@Qv2bi~q8gJN7q3!%V!B>J1FdXIT9KyhV2Pn~sncQUYv5}P*8qDO zZ!gbX3yL+$z&NutHH8DDB-xoZK!Ql{k z9(N2A-N7c z(}7AwSedj48<$y2OVeoubt*TNqV|GHSrny_B87|GO^TXUYHkuKyIC&#KkfZJ@8_hA zhT0VS`)mlfe!k~@pF^uMD z5=|>R+Qn5g`Dy{{CZ%5apcpl@w&7>~=j^zTgU7uWm@)I@9~nR!0RMGh>r|K_DS|CM zmYRieAT`v2uv~k?d(m>oi(}^g%$$4 z8VjouaxFvU$NO&43GK1Ug7%M2QRw;&g0L7rFO$|hbNZ*9bH{Sx*6KBnzpT~v3eDM1 z?thTDGBOl;oltbi)U@AuU<7o}h&jPkR5##VYTmoex;QcN8}C=LBbp_EZN2|Iz4WbOSTVN5^k zV0+BOo_gJ7D}3fxDNC!$yM?)}?4xaak^m7TXnLR?~2ndJSkfVrhWMt98~5aUh3MXr7lBaJ4$ZH#ZvCl z&6Ia6{kAMu69Z$mxaAg*ZU+oHKPFjHvh9*WxY+N)YI)|1<(9a*os73x5hHN%n*cR^ ziV9WIg9!lR&(}|`_G%K;WF+wFgOTJ)pOu_XgB{#(lzev zRV510(m4cGUg_)4qZzSO)%M`kP0yBIZJhf40Qw6AC!U#!yN(=QCZAS{nn$rW6PpRGpB~jY9zCK6bm7QxWS!-+0&7`8C0k8{u=X_7x zXczz+IK7g@aoGX*q|)p4-8$p_g6bn&SZI9x#s4W|5C?v%^xk{#+&U8y;vX)ui%ENX zm@?y3St2EbeVXju=l?Irg2%D6U9ZN{*Pou*{M&Zy*24SWE$kM!1vvoXI*oh6V09i*%P_fAZ`OAT zb*Zm*Xu~C*62fatlj0wRJd-PB2wtz%Z@eo5lDdvS;FXcSz61NXd~o^lfj$zhMmC`RJQ9QlN?FnAu-j+s`~Ms0tCqlbp)Jx7zuIpH9Cyk{A;AT~>Cb zY8|f4e0XBtW=-ZJ@zY6plb;@rB(7YM3Yu~Cdk?k8UfQ)owc5P_rC_;g?Ar2c4{L?p zrDjbXz+^f%(ONNh-lNT!0LtUZdQDY~!seakagB&-qyM|QgH7;Nsv0J1KYVk&?Ad_s z;YBsYkkOba``WaGG^AE_I*P#>3^wqaB%!Y_0e2%B+0dJ_0c|>Z*Y12K{Fb_lw?{j5 zBbgqg$vukPIc?9P;^6=(*RY$Jf{l%+-qN2D#}PGJt7s3hH4KawzYC&-P_`8cjUvl{ z6;tqC5V(J_b3xh9c#qnQo!JPZkX|&vHC{Z`-v)x)lr@kH4To)e{KoX+^gM_Q{2Chn zSF>qFL~9=mD7WcfD7GDc5oOIwdu7B|4qtUQa7Go!FN0^qSc2Q5e0v(fGh^ui(kjR1 zkBHP5h}-e%*dq^#X25Ldt1PUz%u2k z44v5vBh@-Q>~qrl4E0=enD*$X7i2}q#dQ_04VOzRoF%Q7NDz%hW1T>9EPF}h ze0ahn+CY~#9=oV}o)iHVSgW5fP;jM0TU;X2edx5-BP_Kh3+(-f_o+bfm(Gl-Q;LN+ zO`1oJd(#?1qu;V4Ug_3K%1cQNaW+icl7ve*4d$Wax`~O0+t`_4+AX4ZbKPwus@t)a zvODl7QGA#sC7N`t5|4lcmyDp6?8&+efR(nNGO(pMF(;dGs+;RFvZmYNl2O@GISu4y zvnA2jk|8kL-cotn$aA(#Y!`wog=gBcbhjyx5Qi>HfJ~Bg5y#^jmt0O^}?sdH%EN~%tv;e)`s=H#?=(YWQ7E?Q@z5d^MGTV6C`pPaB9;8mr%+A(+?E`-QB>;c2`uP_PEqxm= z$`~Al3-?!kk-YJO`-Tj7=!4Jh3E1kSR*=YXT-n(%x~U=pgT);>ad!*n5HeSmj@4IK zSM|cu@i~(2I(RcZcg9E$Kml*Py@!J0W z{-00ksuPlt=l7mYxyAzc+Ww!0pGh23IG<(z%M!UBltsf;e*+pQXZxtNe|geEV(bZn(^ocsbY@l*pM| z>4@QF%wwSgWgSI3!{WYapFv~XHIAdnqH==mP5F5cbnML*{}B)yM2s3ek2+9m)Xk$P zP8v2i-{6Tmk>uboNz$qVPAa~`z9r(ZBE$9t2c!K=pOgI?q)$el_tRL||K0Fl2c`71 zEJqMtbkN?;(1ssR=`*^K)XC7+t`{qkfh}NNy)cF9x!o`5oyLPSUu7c<0#|R_N!97a zsp{0!G=eKpVkx0RDlAR2;J2voNqUfquwJ9Z)6@8mq_d(O$vX*Y0WNY_h?~KgG=LHs zbUw=Di$|0;kWtAR`B6MG#vq!I$|9vn?0Mt)_yA2uMWsy|ARpbad!fKcpa(`#Kxa^6 z311%(-{D4}MfzK;E_ z_Vq5w9!zO z3rmZbUC5CKo$f^LrajU_`(UL|M+Ltz79CmxD*NJQjJU7aZr$P$2G7I5Wt4;Ja&5g15Pb=y>0#@g|e$cCi zmX_*WMkp7N3J&VMUA!Iit*@t7`9^qDd{@N{gUVxG@}x>P{xE}{b0F6ecu9rA%7B(F zsqX9Hx##aX05gWZedvo@uM}q1jOpps%vq7sqaOC`)rbCl8|Dwx)2iCgayXL?; zF);f!1NP)+NO0---(S3QMFVTQ=jE6NImT$Cs({t7C+@t(T>)Xq6YZ@Yqu-B|JVI5}*ya3(~kJq-c zOk}g30L>PZUG4Cv`!n;N4!I~{)XX)}&tIH7w|d4t{%lP2+$xh`c<#>4+o@+rmMg;x z*-Gh8$0(q8oB{6u6hQ00?A%U0*&DC9ylY{2v$Ch5ab;rRtNR)o)9pKRk6H)gzt{At z-#_&xU?{mU;0Ea3`1bzA)$?ekg|v$oUO2WQ`ECq<_uGpe0!{YE;?44l?4Cr;m72kR z7E_Tr7fM@u_OINO#aQ2gDnhhj^b>A+9(30Jk4h9Fq5Rq^)wZ7RKNy3ds7z2cUsVm- zr%kXl5Gw{_ai9d6Fd9yVHF^%k^-RTQa27>~(?M>fx(4DkbZfY*{=vXWaS~-#lLY9V z@V|n90e756VJ~zbZ#twdty?r$bQbd1R2iM~Mi~s=n3j)dYU=Tn-B--e zheQ#f;;*K)2S$vga4QL}5>vb0vM`k?E0%*1^vEvBl$q(WFnL!ENV|r!8409G=P-;# z)J#2a0&q6GE$5J4fw*O|IugWi?Dm(92P=Q0pD8ph-~_VhL`E^t2AxQrhZ2`EG9+O~ z8bRm$h?zD0d7>) z4`Xr}LnAesj(P7Yd*nh?jFK=Am8QdZqXv_)wA~oK;>ib?ATy`!(_HOlEh&W>Zx_HvRdyues*Yl@a6ej zDjXaft@|FiuCz>YCndaMSFCmUoq(E9WC4%o{W z*a5%ne0clA=z9a*@T?~vgwj&}N7EW1p;1hW^@fo}M1{_A4T?mP!|t0`GDGU>i{<*Q z&%PR8S-I7IV03m^4EVJU>zAWl2K?{;ek1@U2#Yy1pWt0$BYfq-{LdN~-iV{bhIGdO zSZxe@q%~8x3+vl59tWqZ;7;13#8>?cHI)N_U0ISUJeotJYY$JZQQz?Jz|A%`nZe`M z7GWZ_M(Nx8tMl)^?uM929%c<&yz8FlYr?8dMt%qL&Hm3*##!j6|PvarOjG} zix%ptl8UxzN~-K*QA|d3K5~TkinhYy zM!s0B0>#z7{D$-4yhK{lN9BBRLtZ0h(8Z!XZ%Q_!d{MJyL|DZUa71JbG*=vmOU*FrRU#Vj7SML-E-6kSxKU}cQm^vxRh4KcClfIZhK8qP_+k=H88AXa4U^OHG&ZJK zYa3#U1R29|)UY#+H_GU%5n6D!U}!oipdO3j)h&#*#+Y7@DS6+xZrp%6s!@1b6LR*$ ztpcw}i|fLFTd{CEwQYdg)^&m0Nruh`G)=WrGDzFu4(yR%;RE(8th&OSyPHx(Q7)@; z;T38rtzZ={xr9^6A6)9~#%pkdK@ZN7e5-3r(xJ7%wI|ib>p`hO*kVz&{38R$QmuP1|6ItP~Lh&mJ1>!5SKgt7M_q zn;^Uc+3r~J*lSe)``;_0O5*7CD9aT%Fw=m!l@~j2HU!;$y#&5?`sIRFzgqwDvG!^X zy=)Bl4H@+8ny-ovBWJ&Q{>6oFHqmNLtPMQd4pLE%ic|U(6xUPYphGGV6YEWZxom6# zu0F#l)Uwg5&t{h=PM;pG%s$&cogj$gy~CeYz=sc4UY9Wdz`c|Z(!zifczJfh`;fA~ z{+SKwjjYWZ8bMz@A(IiW4Jey6I#;9e0CqQ?E!7$lT`hRIP>H5OgBW|pIM0#jiXn8P zHoUhmPDV#|>q%8DNQ!l2LVWL*NV(m6g49vaD*Scie^K>g$_@_b^(KN|N2GRn`~C=EM=bRq5`0 zyP9WiHkI|EUI&6N73h}98U)7mOIe z1c$_rlRZ&Q8I6q!D+9Op3ONI1QyRS$-7)&pbZQ$o!EN@4Za4ch{N|KyI2#F(blAZG zZ0BzxGb3Y>eKb1QJhtAasYNbXtW&gjhoWvaw$hA~U-%X<;u>(HWG=stq1NeMLH!0W<7Z#Fuv9kqo>wBM-2l zEq)|yN2+BQg4|;GRb?T}w?C1%a2Z!HpP&7jIzk51hRK&0Pa8U4KEp3Kh^R{ASnmUX zxEbn07#~QP7jRv59O*e`gOL0mS?BiC=3$2M`jmbK>SBzi#BmAWKv`T49ySe*3{9G` zus}*elUbc2W4@8JkqGM6M!nz$sVWylVi9VQDuoMnTct!=q$Zixo9_SG`+MGxwapZc zpN~nv&-c9VbBJ+*#*l>R36)uiFi0$A;wet*WLFCmnT3J?@2~OSa7p90gd}>Rzv==} z`e{n+I3W#}T_;qxgJ#j1(t)*ckK1C7r=c@GCW*5EVA12ipf%VRwdThhgOaCeA)#jL zhMpQYQ^;1%6Q;SelK62>Q(YFY#P;HIqW=)@Fo<2kC6qHFoHpbf zq1QNFGJwAO!!Agg-yNarCZ*Oyqp-Ws))F?NoD5KEZ!(6B6Dp?ssegVIKzVqQz#ZGt0 z$D|u|RVtn=?Mzx+mAx_pZRwYt>}vE4MuXPsG_1&Gq{?7uc}3+$c2~=8VXCM+7(ujR zuMlQ?@JNNi!ueAkj5Ygw{m!dF91$VD{Lig{|CKQ~_)ZIFr^^~a{{n$s1#NFnGT$2R z9%QGcU9NRh>X4BnO5u;G8aC7kBj=DoA|KaiI#9kVzZt~Oa5id}U3f9Ey!gqtL(8*M z&kq-uho-MhMd&LOj*_rG^C-%%>||oXNw5sS%R~Bh=KSQ(?&dqcisFz8`kliaWlOUE zHI(z@4Mjg1)7xR?YEauEcd_Aq*PQ|HV<<{}WmHg+l*OpDs8~Ggb`!8qg)faevAlH2 zI|f}EjYa7mQCBxE9JvU)RXc09KD>bh8XR4)KkHYwnIab@z?v!6)_4ZBp@D-NZz_QU z4cFZL+_U)l_yTB7gTuo8^HWCN?OBz5vD|2^o!z+n`s;80?n7@p>b;kmTEk{V`ew1V zv%UTrA<>hU$D!VH=dayvQKdu|Fk~NNul=)>SIhX1YO)yvzP0ii4}kWpCTW;FN@Csy z!V1JHUU~6wBL^n3+#?vn;4}+ZGCsz65{op?3E^*Cxf;igU|=*1vhj?@$;!0K#Fp6Z zW@Q=`b4I!&xW%v(V~p%Az$yk_3Noq!=2%u>%Ii9xLjWDdm8B+FrAP+JZIU_+lL_RY z7C1KC&c@pMib&`Xzmi&nv$3Rsb24NrtjuUu#L1+SVZLnRS8`%Z6lMJ!o};m3)p&B> z@F>G(=F!7dQZ`1%>X?j@ePfb8kI_hoG;6qu+lYcf=G1Z`X%ua&c@G~jDIL{4vME*e zi&(45klGH4A{Pqioi~lXZn7}$^oAt8Z4M67KgeX-K)7mrSnz8Hz9*Oxdl3#}>6r_C z+Vu*HDN#~*N6(;9-LDO23-UHGN@lNn8a(dNVi>mDZwSkp_<=zzh|9XTyI=VnJtvfK zi45y>_q*7Tydwi3wiBw1Rto+j5%_L6upfmW`yV^HFZ#P529isoC|K%XB@y~6I8cXH z5GFiJT0t&Avcg>g1!$>1$uKp6`byM22D&WLQs$ga`dCY$HG`H`jqw2)`L-OS~GQ1Emf05!Ub=UC3A5e=>L>E_CA zuDOE6c_pWzaSBaWA{{Z>W+{QFYGs#Hk+g1Wl${{qT{K`p&YvIY*=g)q_BeN&dL~LI zK?QwEmLkK!S!cYWn;t1CYRm+>>r7Ncq*=27O01K)EqE-16;kV}UIb|P%aGY=?0i=Q zjILPbecn^1sonL5{Ui$ExT8VzosV}H4S3ZcJR8MH&v&_(msn>nN)$Y6i!8jF ztW2DJ*n2F2zVrWH=U!vL<(VB-^%BTIJ`{WpO1D-<99@I4JnWt}P zFm3F24sgA(HM2v$v7ucLyV9DnBnQP#gVJ{|bp++Mb_+?+@xe&+8u7m-Qo9* zMZJYfS(e2d3Ya#B-Oe&n;9lGI;m6+ zAeYQaX3?28*_Fw9J4r2}n}gfQbM!Qj^I`0Gtd4(}n5?XFpGRHnY)ISwX_%_Pu{!+r zoIJnPYF$~+!+Vr9^oT95Hp{KA(Wy7G7qRG30{t`n;78nO8uxItLXJE%K?h-!m?M0@5mx^H($GiWFI3qqNhgv$z)oQli51-pim_ z_m2j{2cLTe$7cL<39;^7L&DV+DXx5(tHK1gFzHK!=wp=^&;Liln;9GXwipo=^mz7+ zXI|-fbw%aET%eSXE_DHm|8lQzWeK#UqZV|}qN6_bZ2Xm=#$!1Cc=E~Cj-&2z2ZQ~& zP3h6ei7#FmK~qzB<@UtPd*2yW-#qL&jBfTKpAzW}qC5tEYRTPS@^U%_^2az=Rg=j+ zv9FP_#Nhb+%ZZ7zZ+DLzzC6-sdHREh0sDuy&Kv{qO#v|bU$j??>P4F6^Wt*x{mEA) z&_93whu*(!JgSN0&a6Rwi`4M725|pU(QClSgjtr~vR&MeV0pk}uuw`D%V!1N1bMW| zBxe<${X=a=?0~WKvgcj6b?esk>lZKn@#-7zp04&~R`T!t=HZuH2Tz_qT5AnR^wd!F z^uO*;Isx_-@JHY643t}|wbp9OMNZ|`^w6V?>*_6nCeN*3JwJ8w+1KlizhrBTUwwS7 zOd3Xwm}&)QOw})cs15L&n2;{dU3l^A>33V(+Z%8H5Rd)zr+bsGf+m}5;o{a?GZ>9( zT5w+hXf=EjA5ME+wyAF0?<^XFN)7$C7Z9AhW>d{|5+-MqESu)rY;$|g) zvX|H}_6=wo5LYGAnpLrG@Ah@*H9(9}+-r1IF%3YivEWdn<(-i~2hYS&p2vmM4Lj41jWH5!f?1*SQecN&$(>}cD*7*39z zOHz_lHJV%>vjc5fkcO*!kYKX0M$dt>Rp1!{ylEKRsU!}eG+Y)urg#BM(ipxX!XrCJ z2Rr-rDF1bZ7997Uo(Wc_DHtmWJdQKy0KK(VpS>OMct@Hb7>#*Xue_d(}b!)(COq`?!>{2{P zXmM6tftPe8c!R`U0;N+cN?d1cRG?EA)M|N&gy@4KZPgTzkm`qMFO{M+l^SUzQTEb4 zO?~Lg{+^xB_gvPrYKVyOy}l3``RjAe_k6xq@@^^N$SU3Eg~U4A_3N#peYbiXgJt!u zo&LNX+&a3Y(%H)3h=MY#w6*7_VQ-8Gs5G&&CnZh`B-w1riIv%7o15PU%yr3V0~1~& z?mDcucFNRBC!4-*4m3K}gq-C;AHids(xiPL&kfwsw6`e-=vp`9UMj?RT|$xVMJTGh zr6819p)8eB9B6$qP`Geh)iKM%%2EQP6<1neT3~?104(dy+HfXh&RHENe#CPe z9_dxBeVBC=eg=v$|F-Gx`&S~zFMK#IBE-4vnjq09yr?!Ete^d zsF+ebR|{=nlRoUNO=^Q!2oUPz#hkogRso~BiX)UgOKHHkqy_iT&zSRAVa!+ubKZh> zE7p_U=z%+(axoO&;*lj8vWi{_*M1(xa7tOhM~)>v`=;~7Z^qBu^9aMGd!ttK?)hXS z3^nmJ6i+URdM3Nxbo#LXj8VLy_o$l>ix>C*^siSs+npssk(NF@+ymA>FNQ7Xosb26 z(J>rKEb5DKz>V8G(gB5~&{!Yd(PODWYS2&A&%G+*LtQ>^* zOisg00phY%fNe1==kYLG@qC%=;PS}VAES=yHJcJIES%{Zs#cS!*FO4Ud%JV@&ZGMe zZ|__6e(b``?2E{53(yuGr$V{%X!*Ab>sJ@lfnHyq>$=Zoa)DNOn+m+VTAr@leGB;2 z)w2uhcFsoiet!D%%?%BWg^*sD+dGggOq*2DGo~L74h)zA3xs8r?#b7GzrK8ReVs7j zXI^^d(j~YcLSx!b`}7^4m+U;PwvpJ1)}Ur(M+1P>c8_(X+?GGfj$dxgR@!v4=fQKd zWUww*Dwjb?Ke+j;6?vI63ix%}Z^DExme9rt-Qf&<=>#$gZ~;qH#;V~&bdUNq)Y`OH z#|@7|GVP2?%F$T@6fzvn@bGHWzWB~wwi)8Wy=p3hAt~k+7tEwx$>}~PF;_(sP&cY{ zl?CXCsn8{S(5}JOQHG;-C6nD<%HitRnnacC!Zdy7s=&}0aiVvzLUTun{iM>E)xV`o zLYqp}2@;g-Dr*xNI9VcEmP~%xP+C)P!&tR6F>#z>F^fqgF;Mox))>5Q)iA+Ff?bU< z=e65YCX=iL|3l5?>q;v`d8b5gs|_`4#Tx z9v(M1c&pDI&?OROk16z5FtbjVRaSM7D-Di|K77eGsuDYsqt$vO+#Dy`Lwu%?eg2{G(Egu1G$d%Rf zF>%Ucl}KRdx66ea!oXH>OUGr-dN&?;pE~7R#NOPF1{x^$3xXenR<5K^ia9as7A!O@ z$0L+rqq)TFgftx{N#jKtdYzt)+q zhk*wkNhs`w_!o689ff;Gbg1hmyv^KObM$lFC%EC9*mr}qUL^KaPCzY|j5R7&eVub5 zl}*~YT9dklvos!ELfWnc@Ac+Bc#}wmD`!^4*iwJ`gwh15OzZV9H&EM9IbRM|GrKNx z^`uAs);)b8HyI+L1*5Kc`~q$*rT;qE!!w0zxy4>lsxNAFIH$p}I^Kw~mC6Sve_{-N zLZ@E7b7S5oz)E5WVUrpPFXq1gr8vUr{P^75#>VSiu@7lmPt$@qbKw0SL0?zi{|Sro+)Eob_pN9XPLbeyjL$+u`S#Ch-lGU-^a)*B zRj-<+ESt0@RTz?3g>8!sJu^FUcR6x6@TK2;Ci~67y?eKBpFjV>pGQXWGbY`n>S7^A z(JJt^E4XCaAovjzS>$U-b-rBiDGwQdG3$fAIul0@4UUf zzOZ1Tt=jny+k_Fe31}k1u#$i9*1%Jd2+0k&z|IatK8;+9M6Nw2I0#&jOE0@J+cn>O zl%H>vAw5@SXD{s)&SaBy>Tl%T&V zvf4C(Q%!2GYN}C_h@`#PGQ49-o8}Cemm5|L?KY59nUtx7_jFW)LYbMHc2B06NCB*Z zn_=1-b$V5Tf;hoSOB&KMrD-*t5OdOA=B*q)bUY^@K_kgvpA$5Y9mHW`nRXFIaGP9S z@X4xXz7)iq0=9#@U}BZHS~a~}rJAjV3rZ?>i4GRNGJ`J*gEQO0rSVc?%udj_7$jC{ zZERv}>RXOi;dqRVlc0nS4|yd_Z+S|%Xy(33LSiC3IK?d3wRXxhlP}3>=$RT4c5-kC zD74U5gHwuJpcKXcO#wW3{IBRHe?fAX{topWJ>EA&0Fn}bVPSRkTz48Y=|}dLRpCBS zvS>Z`psHQhyLxW1e004}Uqb2_#Nyo7w*@L|t4I4ugTSH5Yv3R3S3o%a`Mmv!;09o* z&Kx4T>+iGtPb@AgmObaBXC!E7#F}ykBsJ|#qrKeg(|^VmuB2(b!&k&ojO|~mbu;p7 zrNooAH-XAhN_$nyR9G3rDuGifsj+S);|;xjq0tglw3qV06CLn!DQ?(tGg>tcvN83v z2~kR|q_VMWT%^mu0}M?gwQ1b1=`e{&bp2>PCuvZ7_ORx}0c%NEt4$kM^cWn=h;{am z>@iH=x_f0s8%zP)zX2gP41T+_fr?~TOuEEWyjnq~k*t*_+RmKc?fvRN)UEE6pqo_V z@l^lc(CI*nRq}j$5Ji9B!HwPB>H`F+VTDj=>)CYql}@=g?7Y@<|8|TpfJ0bxEp#}$k?BOZkmL)){s4DYu`g72f`?t`;t+%1YpD^m zbAJOdj(pRrrQ%wc#-PODnjFs_?ogi$XUggvD-cOjU#TipvVs&e37%vOT~qFn=LTvD;a;Q#MoT6VzKyl$;T<}0XH;li8np%Z?Dxi^Zap_f)aA zC_mQB=F8`<{LEqYgbR9Ob6?F;5`;u&q^@I{*%pF%M&yllxouhlsv{4Eqs3XXVL)$Q z0@)V1v0Yxx7jB%yo*bHrub%u}M-WM^G?o85-vVnz;?gSLZnkCRHkT;03ajtrM?S*? zy?*lQ`WzkTH)8uUp)_MOE)?3+M^1ln#*tN&$jcj}x67B`S$x=7Ua*3g#2udEMIx7;GI1UlI2!`Eo;}EyTl0z+%vVkv1)^-{7GQc&_HZfJ3m?VjER|J9BFrBOH5i zV!%`F**Fk~#wd2jOY5i=4R}PECX|{iw2EdB(u8`*Wm1(L!eJct=P2795oIOMC6hDJ z=nfD703ZNKL_t)b@;#%xGs!6pn|EePkM-utB`qD*&Bs|q4PrmJMJ0w z79QR!WX94A{*CYIJ0Icv2qiibi9l5sA~uvS*<0X3;w&ryP#Yevu&jvhBi$mq65Tx< znOSw16qY!eyHI4`kyk2fMU_TCb5c5DPLKgYBf=6- z@+yUqS80dLEm}5v(;*vr0na8n)j%cVfZJQ^6g zvuI9nl*?W~I63KQlVYSY@5<;af%D{{7Z*;tgBYmG>)xJZ<%ldY$`{K)CNt`(<&yUW zmYy61e=ja-oh-%iAHRrp=e+$PKk7nMPf=;olbR)^a@x*RTmy6OG?rOOC_N{j*4|f! z-@FGs1FcHj$SbzX`Se_O^h{l{GT9F6+CJPl-+lhc+igLkT*|Xg4?Iod_{h~8a9~5= z{#!=i=Ib@_XlQ*LQhfYnY$NVPVKUR(k8KRNO?WtxK2$`fv_dtj)3B~Z&Pw9^znc9A zvCAKSJd^nJ6d@abzq0VgM{DQx2>QkjeZa`BkUsOrDJIg!hBuEL{o;S(uaBUAckFR( zliu4U)%q^MOG(_I%3ujwZ%2;WlZ>BLF(i;?Sxj4QZApO>#!iW+oL%pMOh{XbptBE4^I!e`~$9*`XPU-lbm0 zix?rjvzGH<55e@4^FxFGBzREh2z35hBJBSczNSQ@BMv<)yb z9_D@s6Yh*qjm?+xaLs6p(YF>jDsrNMzL4+CeiJQ|hiUWJV5>Y$2+2{Un< znj|z^Y>3MhFt%YBj7}Q+@03D2w#(%`#>R%Kbre~sv~d60%_5&DwTl+dBwg|P$%Jcnen8{uoR1>_9R1WF3%vL25n~y zcnjxd3dXGqh2*(F4qcd;xd%U1OW_ze8O2v-NE%H!&rPqmINc@lSk`{DZ)-fg!D1M) zYbW(~(iV}`Om#|Wi978LWW_LWBZN)ZMfb*&?NORpt83csmi8&L>`jRu<4WrwV#UCT*s9opE^MZRs@zB(TF(Vh#C8A0=7z* z6FO&}<8y;{XmDa;!o^-$BCn8)Y&n(CyGwMdBPU2{9Lo-_o++ zRx|2+KiCfUsj#2>ekka@b?c4FdcSb?+rREEE?)Nr!c(k(y_t|G%Kk6=fOndw76X2K z9jNBwjqBG>-FP_>4kh@-AlU%FK!`%uh_Vwl$dTJO9FE4*``G#rPlV!;eNJo>E2;4N zFZ=!X&R<)-x_tot&NYj#0r<+5g)6{gBKI$nJ1;_1f2uIpmGSXN3=kL}v|$qQJ+V5XvQ`_D#dlA1+@y z>TO3`q=K9|10EldDe34L1YIf=mSSv}dcuDLrvogujqejI>Fr3m8cEhSM%Z`B!?J%3 zyK%*Rv~Ve_tFdO(xJWTnr}M%Xa2o6kDfSVTYjoF`sZ_|Jc3LbLxC|pZPWfsV$}BcJ z2x+XWF?EW21E?DVE;3=J$Cm{$g}>Nw1+$Q4RVk=TfhweQ`;kV}kD@8#q3n3um5?k& z90(E|8nIiI9I@?%`Wg&-{A8MOvbMQ~slLxmgR@a(T#3@ci^YHWJ}FX9Z@>56XIQquQ1%i@FB8XPsmY^jeL9G+K4FHh|oX z>U?F|ZZob-KT@L(5w7oH4xX=1ZyO#@S4iDpS4=y@RECT2+zcVoBtn-TP8r0`7}&yt zrGieD5jmrTrUf{eF>;ImYrK%zR!mk>`Oc(pOry~n&rCT4&uI8;N6QrM`4ZTO@C;d4 zID`RQnUJQ`8*?1GZGEBsMIoQcRT)+5#Jw zCh`(}ml7|*wOBlxTT|vV5tgxuwTPC;>XwV;JZGAja@Iv)0Yqn!Wasp32Bxuypfom` zOA|aDa{``STf_4dk-bQz5=g)pGqdUyR_j&7;uH2P5pRyN!^CrOuTzdoCMNAS*6H6K z)V$F*KY6%Z8qJ^Q1Y_FNDoeQw-<1W)lQsy=S`NIp0H}1x%U&Mn(5k7gpqKQHuHBoR zEDKwgXt^Efb&7PUbogNF)~&Ixn}Db{Fno2y@a=xrrBr$G=Q&6BQr@M?vLlyVU+v9J zb4vUO>JEWeUX*CBj8U8~sN+cTXsB>s=-Z$4uq*Fg!pp>nT4jVhqgNtz0pMGKN9rx9 z@X@CS#YKVX4X3~oVcB2T7n^VIfSV(!wD31z%y!}Vgm!*$#n0H!dgkfmj` z^YQ#yr?w#JaP`_(CsoyTxv_adb|2!y+_;8;)B>#C%;OU9=`kR zKf4{yDtOY~ub+N=R>izQog8m%M`b^w!lAcXg6b^mt7))O0J@nMH@0 z^UWR{x7hjymoTRv#iARcQUho(zQQA|V+k`rk1MOvm z0O%m99wf=Jz}Py#JP+@U(#cSvfzT+hebyV*h5>iIYJl9PchKmpUC{>G2h60obpsJHBpti*k7$uq7yr;K zOSQFCuACT4X`@!s(xsUUPLONt6jozSg|fQT32D|aSZ)F%416(yi35iCqPy8e2n{qB zNy~bZU6%Yydq2xpCoacR?ABM?>@r%{+Ol<}g7dq-%bxQ9BYhyJ4 z*V~XrrbhIp>fM8Ej8#lHg^<>j7f;Hh>bpB&pj7s5m#I|w=+o9nUZPWkA>WR zFk)1EvIyJHMp{c>J2;)dl$MZW&wXhLWs*{4n9ZoOf!!7_=^Rx;jWv@NYPwqj5kC=O;~QQv`Mw=wHPafqol zNDIaFB03r)a{p2;=D^UaTxzdp2RG@J;QXITktx8NWR$(+Qssi2z}LUH`o_Zv1vgJBSYzUYZ?0awc_Vm=3ZZ*Rcu$yz z9+keDS0pV>hMEUVN6Nhl$uz?q%$96b9US_Wjd)?@X+(lQOyS)!CiP zJI4S#e+iM?=`4K0D-Xqf4MpEEvztKhwSzjyv1-&%3{v2 zErea51aU84JeDK_=pwowjEaAA|+&FlX?Fazk1)Dj_j{*h2u=3g?YDP}TI|HC`m{;h8- zOe3!(Fx}8{roP8Mnp~`AQ?_7opZki*GN>+Yp-eOKJ=dxCI}3RO;2bfI$Lu$Y1X&cP z2M9_i6-SyhMl#>((_m;rLt-Po4JWd=cr#gd`*>0Y8(ur%f#b6Lx=}e>$*_;jMh|p! zGR|u0%V0aomNhyyz$Guz5HFK;xiczg6&p2NidBKl8t?(p(E%~e6$a0X!bk0D4K3}K zxC)eJ!Q_fozft3$yl-crCMnj)I9iNq433Tb8v4ex5!yK-T)>e~nb*pqdV)!*6hPOM zh&7{|tMnrQwJ&Nok}9}><9!8XRc2~%tO5zx~?bSz6UG0LY1|IabLUdY#8az+m z@-{-ddE~wU@wEPo89_D_9%J}y*n8`iRM6A2r-0)3=nNh^p(h!WQ94TWaEJMmmPHVd z=p`d%tRxSRuM^A?Gl9-_CFsL-lt|jud$OA(M>u7JJ26VkfBo**_ z*ee}0ng*g$f@mt5QaL8e1F2jupen{CHL!|gLn6nMU^!|lz&M>69~zdXYe4dA?{&xp z)bqxs)Ud~3i~yTKnU+kH9sOZo4XM(sBPMOun%3P{+U!T2UR0qgev`RJwiK zAuL+mc7-$#z3r(U%(4|v@^tkWd-eVoeYpm}8|Uaanir=%7c|ferO*8Q+75W#+ZX0N zu0ujC-RF5One4Ll?RL|ttTw#qWbXk+gM=5pdNyx{*!^BIWi%$0lf1dp8)O&-eM{_d%7Mn(`VZhA}DP8$JyMXWx2G@zVq({S~q^Ywav-16g z`dqOyM_5OGui4)#HlIAao|YuJM`%Ts6)QVlK(=AOHH|Fx)*Cp_kr3KQ`+I+{PlT*O)YrT9!3QQY*d|jvt^k0~&J{qrn+jcbN{e%7wSW zQ)x4b;{!>U6{%4M%)!ydK^$roVvrZiZPd!~i?VTO(j^-Pqzz4&asDE(s*!dTlV}xd zFHH7EsTvuoz5rOu2A-9&(kf9rD-zoHv%w|fWZHvyJk^;pk}D(A#+Y9$D#hak@z6}H z5l@#E$>}f%CcTn84?ZS6O9N_>w2)BS8#cu_mMWF1YLiH^oT*kvFbtC~jdnU9^3?rO zX`iU*5-A%Mob7d&#^WQ89jx36iE~vCMV@yg^`H#0VwX0QfVC! z;%#>_jLS$+-+RDTIFsmt>Gq2zVg;5^a9YYBmr0zIpURCk3a!j6~SXQ zLhW&|^HbE=f1x`u%$tX0A{v)$%pmo@Ov?qiLqn>P?YfwZNRe?Kuaw|^^+3m+>g@(X z!Q;C}TLJJU)i>zQ-IY+xFv^m4MQyrjE>f^n+aYy@K0-i{5ixpXZ%Zfyx$~r_UloMe zVXaKuq(;hxf*0Qtvn55Mt@1qJcAwv|R;9N#)>VN!@?Ix~SGX}$RMo4;ZLCh_`>^Y0&`F%B?75JwS& zsTVN=!}zGzD+-rUBCBbhrlGq0!S($1cB^R&__s=_M1=IiXUl>)WnP`$z4rcDJA4i@ zZ8)vaXDOEK3pM*}n&~^pxBC6Qo%ZS4a=^sZ-Ob&#+fQV??Q9!L+gCr=yz_}js~vLj z;^tcENps(KM zV~bHb_x{6&cOE_Z@!9jkuQU=jh7ZX#`rE?gyVU||n+&vzA^TZb(7g2Ry5sY0{ZsAn zq4@Gbr&vdS{o}(wrW!KY0>hEF9kAVvT!M_`Sv(dvZ4kMfiBUBJuMK5SaVzs?(wH+Y zOwNREB6^D44g@eqWK`Lw6A`i}J7=6l;!Jjx8n+_F*A*eeHl&jh;6K`>zM7uVuS6(DECjE1>fF(PW8snldRswjuD;!0;N za54GD)fZ*0at&M;YlgSwnlM+K*A6UEX9#*KmJ)<6DYr6?X9&NdI9S0PB}UccW0h$l zL=9c4dbTtWY$#u=DKDBstN-Wg?0%a%%rK7a*z%mn!U;@H;@XLqxNS~-h&3CEkz=8< z)ajZoEJ{cvBFnhhN)^J=PKXO`kWhPJE*4cZ5)xdnU2IZCiBv91CVEqLSM_dx&)(nj zp0HM{hML45$HxIRdCv2`&xf0e*$dmN73@(ACyEq3lu4Q{%gj_&xODNB@oW1iGG*2n zdUT>Z?1c-4%##SECvQpQJgSK`2c(o(IW=myDm!p$_(m~xJe5*bbn0G8+N;sY$$P^$ zm`59IPfd+Z87d!RJ(1JGU)D2iBl;-aW3prKE2>4wW`3XwF+4RZ?zI}y4k*Y>4IBo) z1dC=N!`bw6V*xo5wOIc4?f*9lJlKDU62xPP{e&`GcqofDi-3=nG_{rS+Y#LN&V?fagtxb%c8BU8lCzO)KGFj30NsX`*=&Yipv68BV zzxx>}v!Rn-NIbTo#dAhM(}LBL8Lv}MN^m{qCB~8@XExMCEF{%r`&St@)TpP)sZv;m z`1DE5r;~dB*F29)v772ShAXGXya#GbAg&fDiLsUWr5!X1HO|IzTk~@;{I!Q`k_*?O zSgH|ui)tnBXYh%#q9&DAIqqSV9!sgifJL<!WDQj}X)m0;2Bg`sTNs($h01!a$zl@?p$gLFH zUh+obai1sK<-@A#Ab{2pt&dfIz#!Z@VHn#U7dc=P{?u+HDzD@=C?!C=Tt%`M9H+IgD?7eE061$6p^jJ$!Qi{`T&|D>E|- z2D9+taq>BH-aY7=<=3v5I1T+fJ%`iuZm@mdX_D}*%<%`tq|e%DI{wewX_RkK+|{){^p zc``=b@5+^->RhF257wDYOHUPk*QAOdi!rh zbK{U)=+K`6p6f-ZDn=vTMP^`CBguhOh85S#5bBCb2qPe7#$56EXi_Ufh%ILVd?^Zc zNmgB|=(cJXspy3gjfc?lTtgwlc!+86D)*pP>?j~vC#A}jGmz=*uEZn;m&Ny=Uy~P z`({Dmo^K#Hn`195;Q-yu5a1U8Zxggl_hX76O~+kppB8|#`i<+Q2DwP@cLlUafOk^`rhJlA% zO193N(85w^qhJ?R^<*Y4Xh`}S9O^^GBtai=qz)GalES-+v+VY4P@R1Db!~d>uzbd+YMxu9T-WRZW$U4{z0?w!Nn6%J0P3dYnL9jq}FQKkzLt>0vV6QmZ5s_tRd~yAJ|Ct__?`JLlB)+r0=n%Ya z0KD_ru8dOXr#hSYM-M7tF8T5G2X}5iJb3!-@X6lZ>8mXgt_LzlsR9{Ka^RsF({@SF z?FOA-%jvqIGL(O-fql6^{jV-nx?2jo3^qaFLZGZlrJ4i{yu`uu!S%OZC`qbmq=b>K zthh#BV=~?LG%aRAt7)TjQv3>zRTMd;p|eEC%`D_qu3P|8dtxNY#8mAgm&%FRh9K=6 z#5l}BSM4SJN*1pVc3(wRQAlK85IupFoZVhuQ8Z*zF&J=IyglG)!Y;zG{ z8S||(c2?_=M9p*ZBLTV9Ug#5O(ls{GsH&fN*2FE6EU65p&ye)1lxIVa z4yPv1Oy0ORI$9h}P2DgSJw*h^R|vJvFnwl!>J`dx&tdxJ+sq zbD+1AkYK2S*lH-3j`dx~PBdkVa2Ho;rGabdOBhur)RRT+CFAEDq}CxCdcA^@I@?F| z9E%WJ7U8I2SdQL4z-`naX|y@}JlB_^#W-|Kp_QtCAd177bGmOZlvALp_Q#N4JO6V< zM|N-?dzNXHqgv&^o#dtcAj63f&z}5RW2c{Q7J6U8=V$unxuaZOQ zO%fZKNECI_C)pV{6T#AXDOO%>pnc~Iv@4QpOcxH^VR1cnT3rs zD}KWxwMtPwrGT1^aa%*@5%Khze{zL(NhqukN)ON)QOWU0?O$!rg>J95#fK%;8m}Fk z`jPnR$8j9&fP=GZYZ#DR*xV8N=6P)Oe^k(hxN9;jMa2zX5c~~`U*-QQK)oLyBD)4d zDEV^xInU4UyJI9WZmxjMT;`s8w7R;Se|G!XKfnG9Tix37=I^fVZX5h=zqh@8_6UG) z{_y>uKV6!iRRlETmm0$5*|vmOAN=CP&kvwIh~pEfpz#?Yc(zXiS3n0UC2X(&$Y;5-U?N^Ms(|Z65 z&;R?u?-$qYW!KghFYf&2oy+GQVIjgE)abT?;PofZ?(d!6ef@)$q-Bl9fG-^bPUEx# z&65jkxjO}9%v>OJ8{O^zP%Uh2Ep+$>8x7;s9NN&M#CSTJesR0_kw}4sI6h~oP0yP4?!8nntZU~$+OUkGS^L-CoOZla9eIM4 z{fF{O+uN#m>qLb>4NOJlxsaK07^>c=7^;0CEJAt#RZhszIE2*Jdu2{3s%j8f^x?5G zvdZQE@O6HzZ5?J9ucRZPNv^hIHzhi8l<5$QMXDTomD*aJB-(~fE_I_IoZd7DSyN~_ zr-r43L46Y_xp6KQOcE$07r72;1MNlDU??p62)o>8+53CmqpTg<>Jl8Cqhp!add~B{ z&mTj508?{iCey9R&oHX%s0{Blo|}_738>yLs_C$)PQ!=;IWQa1bhK#j3iGAtFvd_! z-=R8}AjJ5MBO}r|Bi1Bh#Rjv)YEh%4#-r%YqSRIur@kk|gma6(vQJqbzofjBkbg7o z)I$ASi15lB&cGy4j(162ks&1*K2zaXn9A#ogBFLW-Lg#;P#LD|=Y+fd;c!|SJ|7-2 zg9|b#Ldi9I%cSKePA7FBDTP9pROvu)YRU!FOzTqKVO{X5YCxz|O8E@C;2fDsh)jAq zRbU6nT6q_ArBf1DXFT%H;}E=k#y7@O1rw=w*i*F9UfG&=xmU)g)1u0GL9cz1!U3h8 zM8nFZj7rp%qLr1lOSa;?;;S(YFUibQa8{gE105q|DY<-nE!p;x=Vq#iU7Xw%+}WfT zYROZ-vQmbrCMv6$Ix%4CZe%5$4Cw7yuRgfsiH>yi^*#4dor4lVJ7bj^3zv~}$I?e7 zErgx|S)Nm0&#hDfhet#sXHKA7Xw1BKKC^b=w5G=dUU>Ya0-^=oXt;pVXBQuMvx4^v zmy-#zb8as`>U;1rSCnOV~edHas_a zd*f-=elzZsyqbor1?+xy|EV(8f(H~1>7!8@DEYl9!(Iwo!*uGkA4dJ{8=stg`K#`z z&jfn3eR|gcc=!C7<2U~;!n%2L6Wj0BXyo}(n9lErRy_x@+^UOjs?LD&n|Ztdb#+S%#ay})4Y+w|3U-CB%n z>Yew#UOqjjLeCLY54NAC?A@#qJU{l<+k0Q#c>MiIQS5ei-0;%gHZRb4ES-V`Rf4T; z*s38kI_6o=r|AIj4hAWP0^U3blU}Y4#y$J4$8u#=cXkHLUJb18yebH<>H$Mw*2jZJ zd$9cd-XHUtCOh=9zn#eBBdd{M(k(-hPyv8}?^tCMGH49+rd$)%)kwO8SC&yUytjj~ zsHRNEiHx|bnj-6SBvIakU_|roL{ccJow4!;ipvPNSUtdOtI4xHp;qE>&3Cv4!hkI` zzIH-|oMx~YiIj&}8MMYsgy|7%X^b2*R9?j!6w9V-f5n|7iIt%ped9>YM|RXMWzSgE#5hid%CUC^%i9ZSjg8M5m)eg%N%lKXO=^567s4>_wk6K+<*za3d?w5fDbTzZDjEwWO!~Ne)x6q@mEA$z+mI#kk?J4P zDpFkH?Qu;?BotT=0g3?xJ&}0D1~?7UPN|W%oJf^79b(I}0wL<^Z+bI>WY(TynP`|7%E=L?zmM;e zY^gMA$)~~P5m0_=y)2K_*~xXY7GXt0|VIA`P&WMGow!5r^(N__rwS4~8*}1Pr zNE#?v%3!Ol=;s;g;i~$SP;ph0{jM>`@p$mjpI$#Zmr`B0c;SQlSE}uU16ht68@spO zQ2^zK?_a(6`GsqpCrpgh#oK824h9=no<4f^*4zqXgmzA)droJP+{5B?}YHt9UMrz$? zjJK5%J>xr~)bXG(s6N|!Ef3U%%$pVHs7R>^^j1@5aaP`S4S8z}Mr5>Au`VO%+Tkjg z$W!YbIdOxqRxbss9->S*6+Cr92?AY#HHYO%hwP};P!?czbfsdxulf{;csWm@Z>cHaRDe;s9 zi6fFuxm{QXjQ|G<{7|^%JtG7e88q+@=Y`avv|J&H1qG@a42=td>_Vm_LsNd3453TY zVFB|}W|$^vsF24DRXUQ>I3srx=N-{Kqph)&)MCZil3H51rULWRxQz2jjj@bN+6)T- z?`b?OomR4SP0UUOgT8{W)5AUNLaxCoc=-cy{8DGRz*@a?X-USss!5t^!(t<|3E{?< z?9^I@WSz65#kCL1m9<&${v1fS+9(9aL~$-(!7y9bv%+DdVh2CUmjH^cVv{y%^G znGH!ot(By!VV+z`Hgq9)o>xSmT27{6rKg_w4&uFH9ef4XYaxQTKE{DUQ&^<;IRgUGmtXF&@7$Ip+ZUp{zk4KmH3P ze+JdF!N&5VoZ<54*FJdp*TrU#e)aL~15CQJg9fpWOp<$Dd%3W8#aq&2tk_7-IxtQv zW;!tLYh0Jd8f~ZI)mc}sVkX&D8x^=hM(og_UG|ANJ08x75LA8`hGcw1I5kp-~EaL?TtIOHVb? zM=hvN!c|F~?QGeF!dmTapyK;gEq6P2YazK9O2rVJM)lk@Vyg#h^_E+6>yk``HF49r zYK!U^dEvaxj$Bog55S zxv?mz+I;Q$K<}Xh$}UXSvK9fd0ckUeL|MUHwGHwtrq30Ha&VcJNNy$e|JeqEx(>Lhnt3rO?3B1t6kRo%n!qSYGLDHMC+x}WqUXyv6~Sz4-Ar(V-|XBsNzih<}C@+W-HY1^iaya6pH%Fac-BGd6bKS)a)73 zIf5+1YGhl~TIxMWa7!U|IK!uu4>Y9Yw#yl zj;>+QOyyotW;{-hilN6&djolegTuViFd>`cAP|5)H9o$QCiDu1mBA&%i=I-4=;>Oj zaLVQnBYA&RrtW4XQR_T8Rr$!<*EKp;;57c-AV_MgNnL1GQ@Q5 zD94WilcgRe5kq6=k%vtwoywQR+SB?DxhP~m8dW^pqmniliuOv9rGYcMR?o#!Yr~cd zPg@ly)xyr>L3ElB;%!Fo?tw3xy}ZbCrq$sq50UafKwJJ1#lfWF3DG2Rcn|PVir!w~ zAbYSn8V0W08ccMy9sJFYe)rn1k6%c!PJMN&naZk8tJ~;U;B4%6@ZEQRd@YKSFB~^8 zoOPPa)cTvegop{QJVrV)ov_8xGRIdp>ZeJP18gX4S3(_VfBp2yWbowoUrnled!Gy@ zFx<)MZ3AEXz45E+=oJ9I{U-?ifE{qU3m#C+U`X8m;i><(0cHpM{@#ASFB33P81DaN zm|R7WWW08%Xy{#nkr_NQe(ukKWgopRcS&0|4!ql!FR8ho_XI3FwuZl-zO%3L;JMybBQ06;?JDt>uEB0r@78{H!_B->Eax7n)4+hbS{;6N|LyO6|IWQX-+%Pz>&M?d z*zYg9u2JqA?X(xXJ8br4*;PA2nmoN+w+jrFo5|!HE(?J684_QY7;M;e$MgC&kDJ$* z)$26+V&$#=t&82r$SkmK{~NwmZ+iNf$?Ra0^{(A4d zY?!WC4L1)$jdNMO)*Fyh(i<5~yB(K7a4em3T=$$ud;Y*4bzC^rW`r!SPtS8KDEvd6 z%<5J+3?3$MP^`b5p43#+X}b}(882&6?U9d-hC68@S@l-S5tT44|o<^6WIJYwTESj5WhSj5xgYvvWfRxgcot+7SW|8 zHGut@;Rt7o@qE^+$K-{g+LL69FjGy9L&nMsoHNpuq>-etdM{Nt$zu?5hTJ+(v0)|~ zdl#1>CFANuiCRV)41mX(pcjZL6T2l?&WsJw4LC{vSjl9(RtaZiHp*nBn9eJeI#4r2 z;L&~(WYM)6jDwYA?4ccU6|)eI)Jr2DF{@U4JOko`r?T8Kj9y`lOkZ~Pq_;O^d1RM0 z7z{KHjx@;j!8C1)C)wb7%%%3WS{-YT?3`61XF4S!^&;}(@*0fi)kqf^5%vlS>9bL9 zGsf17%fxPh%5u|@J*n(4Ezcz%|Hv5dzquyeHLQOjE%1T8VvKx!z7 zo3>nHHL9eNt>RV+ylXyPHkQhiTjhp&{-~H1C#|KGN}gF+sT`qDmaMAc6~b#Cuu*h* zm&?8Q##$R!H1l2?9MRrO?&R7Cltq}0PTD8ZavYI^rL=2YNrQoFsg=(Gqr)ef;(3`q8w$^2wt!*W;HOCnSz2-qlEcV;Xb!`7AMWg2xVN{zf9KwY z(c8&juywxsmviR~e>XO-zHmVy2OE*RF&XU8N2v9$LZR)P>N~G8;Ge%y#&GKWfA2F# zuA(5S;_(%C8*ZYHGQ{f7HOz(AQ6PvSi58^hQVm5_2)j=5WAzWB!ZHLih*f5l5z%J%;hD>J%BO$$;IALP^;W5~_k>r1 zGORyuZa%ns_rfQe=hl~-K;EXxmzF~siJFG8bEEIeE*4|>`cVF;d9^!VD#5DBn7Lo| z4kwXt*gp8L;-e)xGu;9-cbDkIV6)ZgHLOxyrCpKC!PeM#GR=tV+uA0>bW%3l`kTKR4T$YFp;22m99bN4z?a=6^!j~!aGh}a}NN!CJda?)^ayFjzNLTI% zckN??Pzx^4-n9hFr7EEg*Tury(telu@zf|Rbk>L~(`C{h;jL4xawSzZuwB#@)Qptb z4k_8WwP(OCdsahhEJ1CCwsHu;YfB4UL~Q~w43Z0Fp(&iT)eFJj$VerJjaX~DHQux@EE$fDDeFZIk^h#7pYZ^FWjU$xZ~&y)YcYuZh<8( z0Gkts_48IcUI8qe7L#2pa=9}Gy{ok^A-$>>wr{mike2-+l*1mZD$Wv}blJY=&751B za=F|Ikd`-wg9Dsq4VPg-dF}mS%8IHN7$cs>nog4uE&~|^I7klSfP1#sV@E@o+*FvQ z-LU;#AM=J1&kh24&!5XFESXklSeQ6$C&0G4sb}J=VVG4YU&O>%&D0b+WW;|#Un9d= znwGMOLhUp8jIm&YurapcC|xZpZC7!YS@Qq92t9IU>t%^C@+~_VskR|}-iw!HU1Eit zPYcx33S*<`QJTjEPnhD0(?!<}<(<6}8K* z!DInB@tc$A@^F=QOK_lvoWmSxvEIK6XD|CgK?mU9*N2v&_=>8oM(~$sV8`avd1*S4PWQfU5mJJs@~uYR2b?OYWcBqzB4PJP=P`cPqpR16dEhiqZ_YiuwGMQUH<#6;mc&_GzaUdJi+Jxb9DRms}%U` z>9Z+HzZ^vK*SCRk7^aH+)xBsS-=?w?3~)7_tSjNjem3mT-g9<)Nk~FJJK+7yFMiwk zNpk-&L+G8s&c*)b#zuc*bNlq|R{?kn6EHj9^Qro3AV5Al=>Ox?o4ofm0KW4}fO8We zGwIBRu28ypvxyTJ6ke*DufL1zcMj$lAntB@NabAo7iP)imU!fcfhmw*lc4ZXR9^NuE}!g_g_4QSFlb;kEtuO1&t1>CT;7_i^Yx*j(3wc&LFgBVjLZ z=&CxR>waZBk*zdU4^5m?9?m?kdalTl%&zt8K3q2BoI{a^>XB#ywTiFO2ktxU3FE?D zT)!G!8x(6wt+;DhqWjxSpzVc_G;Ltq?J}fa_XV;3Z-%-xF&N%O_WjSjOM$diQ?N1- zh_c?3HJ71rUG2E=8++8~30Lba3_bNws5+HpD8UAc^tnD|AY4y5wH=%on)aNtYJ)4) z69E}8TJ%yf^{N4|BlynhV3rVJCUbr$7L!9JE9oJ*?zp;rd9<=QGZOPyhkA#uUix^{?xClyIXZ&$%@{rbYbylNxOo>7z!aGQjJ|R7TQc_d^Y3~AQ1WOV&?5?~`-1jW> z{1&^1uiK}Q$D%Qd?!{Aufa~~~Zt-XK2BK+o-JYpq3pYL+&$5S+rf^KEDT_8#*JPTg z0zvUCI5bd3sGbVO=?ASr4^Gj*42}{rU<+g#ukKpT-lGT z9jt^x^(HX-MtQLy62oAA(RYTz8fXSxO8h4M7y9??`Fx*qQ`T-tNFw>}e1X{C`##V2 zhai##veaOj2D^W_^aK_iY-EdEM#h1BLzfh(Npe;GN!~ek)^LpGs-&BcZz`k5psNZ>hS+G+W4%-yX@Z8bU?YLQf)_Gs! z?7n-V)NR;MogwHdcIuGnxf!0`p*p07!|IL#D5aF{qx>QWdUD=(9rVtT(lYy5*OJ`G z7=|ZmMLNO{yp_deO~i-$M_CZZmo}tlAbjogPVB(j&XP4ekqr{Dhg z-o&06t{+_)@7a&hUTx>yuK@6SOq?eZ1xBO8G9+%J!a6z{fA?G80KFH4_*bv~;~v4s zaWo&Z%5BE+N~L?FGo!75anoyp0WFdnI`b6J5?&-)(t z+jsUTd7y3BYX{ZEuu`jGI@cuu{ZyY~{P#~k{_w*W@4azrkTWr*<^ff?y^j3Sz4a3qNt z;2qtJ_KXoL(rO$_4PJ|mSu0QN^QST;*~5f=s;PF+OsS9O-uR@sbUIDvpWXdlSfKY- z;ZX(GTl^z z4rSc!DHUU14x;_uVxVN@PN$m%N*TNk^fBhn!s3PgF3GWcLtSK4ScZC@)2?>1sI16e9<(->#(aD1 zP+_(8e_{%%YRufKt_{l&Rf(KRjI0H3RZWBU#d0b9RfnLGF+ff*8Gu}FN`u^D7_4{8 zfGV?NF1Re;7l*co0K%WivMK|UOS+MOT_dxDZ7>}Ei`5rc1%{33wiJ3*UNT;W@mA>x zUT!YAi{-XLqV4BZ^%R!LjpjO}MssJh1sekIg2CInyT*W}w_-TrVJ!&~EFRMo|IG*V zypCJgU^Ov(?F`lS9H`~l062gY=aK^7L5BA5?mf}OW+h>c*W+rZ;3<;ai- zh3KqAv0I5EJh+1(DdZ&UDxMhGg-Mh1VKi16E#NxH2Wl8em{l7O4UGWLNHH)3HwHY* z%TAdKXY7X6eV8ZoFK-{6iRa3+tn^HR{|sMXqEl3*#4>ylSCX*R6|Zb>I#>2-N^kavlc_ao*-eFOIyM`E7iPiDhB(dydMK6bqIX(EZV_X5kIw3XEZ zYX!{WnB^~5wLgpj|K`~U`l1yH3jFiaJ2it+xqI6eN-SPazh(pez~|0Jjh!zO;BkXR z@S}hkA$mkCniaRB^yKeEH&N**T0t0`@a3j*ny~O-NNDgYj}38eJ%04bomV#gIwIw2 za&#p!JR3E~(`OTCL*Vzc{ng}IV`%yq*Z|L8xOM6BFaD1T`qjJl#v+w2bZ&w+&DDyg z+d1XH(p{}YD`9yfNtZ_ofUMz}MF1U(pK1hMd-U41Km6=hwOLNbsl0LGi77Dje%v5*b<|7pYX)w)ZSZm$=rvg+2 z%LG6IoSm+3c9{_mm4*QxyQP;IG{awXSD>&qw1%Ob!C>hAUB=LcwPod9xFtwJV^q&; zd46P_T}uung%;d-jnIjF3j;ADwre%>vJ0+nv$ll^x5R)Hmta6 zo-y;{fl?^#WruiCC%)==#`rr_eM4ozy30GW5;>W$7Y!ds$CZRqR##xYuDbpleRQb2 zEd@#!?2vteJ%D;`l7nzoAWBR9OZX@A1(&oK2#FNa5P{Xw@YFE6Nd0P{ybs3G!HFc( zQ0FiodW2S@#V`O1frS|Zb)PfSHNtEkR#P$IStSU$sB)l8>tZfJOtn!$Ew&MAHk^dY zxg?ScW0MrrzOa>CIj7bLev0!d9|U*}pXAlPsEQ^Unok>GC4K2-N+k*WaM{v2FCT=s5$XY3rDllZ*Jz>MFWi$V}zH&MQ!!k1U)qVss zo}k8>NOEm_+1`8j{5Maa-}>FZPnKR_}%O6_J#hr?Z@l&jZd?9 z1y(Yl2oPUX545V0K}Aodnj-}~{PKmTCtl(a{`~J3vTk2Pe`B`(_r@`d>cax1@r;`=UV>nxY82X)1bgMU}m=-I1|Paws*1rA1iI4K@65ssx1b0sty zu4ul3C`V~D1=wRv&8I|h*rlR)HHET9&GcAP?YMT9#@++f^vQB9`T|m|dBCxe=VN7v za1Nw6HH3$!Gl`CG)}X-AnLc|n`rE^I{#aS4eXoTUdZ>_Pz}PUitI%cRllv8zDgaEd zvU=(-HnoHO0cjT<^$ZM%sWK95=My5;BFlpLb5Ho)L3-7zGL}|pkz7J{V#mXhd%dUh z)-zM?(An2%DR^o@Fa~(tLTk)ob^(5pR#oq=G528ats`#6haqgVy^7!C)~= zc+I?6gt(<0Zw{A_gUGlC7oIhG&mmU96~eT$?!s{qN{M*x~9i=p-l&0L(@*Z zwUmAe=xkNHWv95es}fCZGixquL|nKff|lBwd56+ zR$EJKz7z`*>kOw|qj%n=;}@8$g08zpWtl=VRlZFxFsE#9U)|L^R5CcMZ^MqSRtct* zYWn^r-AVU>T~#>9i&R#(Ftcbw^5-fA4-5rrI~djMIcpKBX+!EPfvzXG6lk(S4pWjH%Q zAv)tUHp9h$I$}y5f@&+({N$pLVBbQt&U7{)( zY8%K3%t|?@-%9>=kvq%Jj2dq^LMK{RQ`N4|X$PEWjct7QiPpeLHiQ?h+w%aFyy$W= zEL(`yesG#9{mQq$+Rh$ka$~VrWlt#=+SO04v2t&c$2#{jVtSa3roFO(3`j3RQmZfw z8zGjL2m7#^t#3b5K?BYr&F5Tn!aP{`=!@e%*xL62HMeo-8{3AALRs*%5;C{^p#W|@ z5#+*njYJwjl&G%(MJ_^C8mrTjP+5;61z$xRjLG% z+se_1Knt@5gJ9W14@PJQmD-g0(6Sh+OD@epC$p><0@*`vhLHG>g+fAnagY6<`u?7G zwq7S~){Z4hvm@;i?=#Q)J|D1Sg>*LMf2RG>V-&=q#VbKp<2EC92Nk*jo-2bg3G-mvhk3RX- zOBW)w9!-_<3`9n1CE#PVX}gk%2n+nJePJiC+4pfROt!tkceDS+{a^n1qu<^C{hj(Y z|LxE3U49CSeX&}_$fYAX4cl$^HKFCQGp#&QI*Qe7gig!jC5d%ZO|YCnD7ScVRL=HN zQ@yv!>3R&ex~FU+naV!IwOxc~g#t^8n+M-??2 zC}9~+%Q{%TpYHngI@GvWj@#k7v!1M#9|fx7w4J2dUboXz7IT*ktpYD5L@`UTO!S4%jm2`+WsjDa>GE*U-0JK` zSZiDK%gr-|N;NyLL2i&8#}MF1J_ZmcuB!E|)KrGI10icoTUef!Wwt4W^FX)@V$-Hz zfY?#RZpl5mkm#m1vLr>SfLF?5)g&;7u>Qw2P025q=+Z`$wJ zJ$toEz2qb70+|~$In+-}g>!m=$%&@EP}cILdk`}(I~OlaHu?wgr2NG@wZu! zn%oXZ@sjN@)=6T540!W_Y)x4WwW%1+W-e53ZHI>8a+#sj4eJr1SQ%Eqne0*{Z9AG` z2l2*0YO74(UgHc$7u9c^)4&>AkK?fKj74v0c~Vh&SoHDmg`7wLZAQ%yRJ<0`@vzp# zuJ%&o26m`mxtB}q*`V5!;mkPTgus zmT@mFq~bc#n);~fHe@(os-UTb(rWB=>u2Ab+Fb3PhmsKAw+1g zR=5$@yUdw}vH-FU40Ul!biVy@>+8j6!9e*aE%^nFN4H~RU&l9_AfC2(LNcr)qv8(? zfH4G*4(#YZ{q)@*EMxfWE)HFTsTHk%Ubhfap5VHo$R68BAM8RUmrbDqHiXn_6*OZ1 zYGk<|$1k6}|3qe?tE+#!eD>_oYU<~Vlv^3K=Zt~vy7eDMg zu%oe3+*G7b+-UMFe~`hlg#D4&C;ctj3E-*69;`$b4@oOrC%9 z-*M^Dq zmkv>kX=@N*4XI^{EN?E2LPK>EK%k+%0}p9*xw0|fPS05BP|bZ^-{wkR)j8{U;n2Vx zxqgEznQj7g3o#$AUFRp)1{xa=l>;f-YmZ451ppiQtqqKVYNtD7Uc0?s>`s{73Wp6( zVY`JITUo}+o%5}mY?&b&(Ih7lxGq&BwK90E7bc~G2SMsEJC)|Vh@}c5qIU}5IwGe! zM{aAC4s2K&WOyk^x)p>ocE+b$sllGnFoVC80hc;NNP?drbFFYnmNUnbOj)87sRSAR z(jH=(T@k?*oU0>P9l~@pXb)Vcp0HjQ1+JV^NC+dY+uM0ZqP)b=b*L)HZr)3(z)vAA z>1i_sKPw##vaBr@KSf~8_IQ@8@bGzNyBlM7&%rLke^g|f8*>9feC&H~p#Cc$95 zyr5Ar&}3R|#A-Z8z!e%}G-S+pRXWP1gkkeukh`!e0oKe*d6Jhda}M?r&9JF$DyHh> zoSjP(VWDY&FN!s?LE~~y3h7)Rj5R=oxRQpw6#M0c7*QJ_2YO3^azi?XVheM*niO9 z13qqFWys8Dc0>}PoPMM&1nbv%UFL>Em9nnAa`TUE!^)+CsenBU=+&{V< z(~WxrfS(?YM;bwE0X$M72fs(7#lh%V@IyY}_x|$9-S%!5MN=3oQYo;dt!U%bZnaY~ zqw!+{muR(#+P>^n#&TQR(*2W2{+_lGMm=@+?xRN^?Eg%zV*EoyMn!!GTmYUx%RU|? zVmPAxwi*zpl3DfVcHn+rl|$M(!--d$7ipb?;I?gmNdIu#owkg=8<>GkcDs3F=VCD4 zmzVTnFkYo^Sba?3^}gLa?5{SPc0AoEXwrY_XvlvIob$>$Nz5^G1%@b`gs_gtsI=ll z`gnn{53k}4rzh7kil>dui|KT?nSXWf!@RV@ot`n_uHh$h;xsq8HyQMNI=ohzlxpdr z!S>h;_KGEULNFD<7(Fdr`2|5XM12jto!Mt}{xdG|)KI=AzO@blQZi5MV6^&_}LC7VycG4 z1UBOI!F9`Cc6*M)s31vkZGyzuuuy~M4sxdw^I;&gK})3 z!VWwCvf%pTif|UZYhvyxY@5bnS>JNPdhL!JLCl6}4TQ29zyp{y?PzPHF>irp13@FJ zzY@izM4_NU1x`??*QLg)oPw2gLN(4yinF4Fu;kO^(?aDA$V)x2a-K`Z#uYnhFYb72 z*9F|SPthB$=y`+QIzVi=0)MsaBmj)oo= zlM4xq>8VLDDHUacVm7^G*qea4nI(3hfT?wn?K0^ei7Tu#%Kq@Kbs3BIq`^*D1!q(> zkxe7I$PWpMiD7Y)%U}ZzzvV?Qw9#FvqaE4{>gTXa<(Q|VvP#072I~ye;o_kfKRtHD zeTLcPk3Vimb}Yp7wxX7578HY}hFy)C$7zsN`MNIy4y5*kG^aTI#C5I*mkJ35?2A6hqn%1+wGTLZU2* zu;d^{%ZviM>~3L6m`}!O$FE{3kzKJE29-U^Lt$I?xkuQ8Q{Ajj zsqk+vFV(G}=&NHFIs5HzM&D<^X#vBv75G?xkFV?^6B~#UdR2h4rZy&+X$pi%XNT#IZ)wXm-JV=6T=eBOgjrvw$|b z)%966USHJCYGm}g0RSdI*}v{Xx=WN{{%{UA)+QM;ZEtw}>3bt&#Z>jVK%JL`7f&d~Jr3A%AW! zW^)_~84W~LngIIR@lqo;2#yVDVZ$e37-xpp4ZA8kE>dhHn6qR+Hb`u+OCyqGJc_hQ*E0R#f}3qY$Xbnra`;p$z$(xT>T;*Pj4x9DQP z8b{+~3<})9Geq-pXnWBtUH5YPxEztrL2ZX8b^yb{1pQTjw2C=3 zs7fH#ot=x?m>HX1Hlefix_~Je@34Jgm@PYUjaYj&%6NxmT*5=llX)Cw4VO}FQd0#S zjfhCG4WoCqCzAqfn9yr`_hgIokD^b3InS0jDL!Nt(V-Q?4bYh&8(=XA@gG{ zlR5T|`W1_l9VFbdEtJlAjZ@KitbzJBJDwc^0^4=W5H)j0fj6sWf4MD{T+rTFtbW7z zo$PEQ)@1n`)-#!}ZQDQ2Y(0DYJQXTRhkT)gXH^n;rsDx!e)Wp?>>g-XtUjU*lGQi0 zMyH>RuMgZD>@ian?_N+Sh95j|)O6jnmcbsPb$qN=BR|hYzUQrokRJFAKwYY^dS0fK z@1Nxh*3#L#1aSeM5hf{@vfM{7U)H;-1Xj)_!|E&WUcnn)&!Dhp#ZhWlu686mNPO;< zrqC4)sSVw}{%;2S0Ej<$`Fx(+dEvl^hu0fd@ag5h(H=jvAwAi9>r&cyfY0swzfX|d z^hs90!#UN@S3n_+{rJ4GTU}y(JL;T+`^t;br>+Lu$#1^666d9cLHK)CzcP{w+patS z|N5o!Hz)*tLIUL_Ig|u)0LZ_8{L^oR-^~d6FHf~39ZKSyDCsKI3Urugev3>QiPW;| zR$I~8gqg86qBIJQwO>uaw{)B+|50Up!lI#4nPn&Hf=}vCkTq$UkhoGrUH1TEz2b?XnvIx1*pw{J8+ zc74>~s7G~yh_0yYkx^?|ZVj9bVauv4P&ic29;hjI<;fY|=vP)}ffpS#d){(@2x_1S zGI>yC8Ej=9YWCf%843$$k zY)ghEU2#aNh73eak;xVMr^sQ@u#>YcKd+Ysz@1T}Br3wE->8!bf7h z1dej6j_SE{M{u|_@qy;i=(6~oF;aV0QE8*Wo!GEFQsXo3q7Ho4`z_TktrYSRnk)Jq z0=&WcGormv9WW%p1TIo3lJH?4UVzH75{CF14wFS)#aXN33CX-2E%oJA3o^@^i zo6KfA47pKCgZJpKN!FZHl}7C_U6>e6MP^ng%w#GqY%!3o$_QNb(#5T{DjFYe6>Brv z*I7x|Y6hs=|6(Lgn__LJVCS!MtJZgu4@NDzp+`D`s1s=)1!A zpSR$N7b-bAtN2!y&8xA`e_m|V%XO)cA-`w7D6Zr#VL5#at6u-%<6r&ouh8M~*Zj7eU`plHcYu1~Mu`hkJiCl6P!Z*55KQ@U0$;k8rXFN=6Um2RX~bAFhrYM#sY zIHUzu`9VXD1rW2~8v)p(>HA-RrpJh@0OBXoI@3_NcldAuU18en#P`s@(-`_tW~2|R zKlpz;;NSl3=~yInu6!yr0n4tNcrmcBPgV0{*>{I|pRZR3-6SpTLdQc9)%|1%AT1@2 zGNc+WwMt%+AJtkeyYDjR7WRRm23TWykc>@^)jcEwPs@3%9ZiN~K%FshOEclQM#v1s zhsdO9N=yWJh{w7vw6ar;@8|oj^76_fxTt|DZ?JbJG#7JnpD2sxFT1G|VnHyUlzxIg zSivFU_U8tz=li+gcbKH2!^ydQ-u$MOjEzW>5}h)^KbKTY4ym8K{P{0C{gqg4Pf5um zKoSFOAKjGE(~jzfR!o_xk6-nCQQMog@fWRDJ(b<6J!r5ZfP(V~DIu%v72+wwXu+q^ z;qMW1c*N}zKAFMXxix)n3rk7j30dJ!7Y$n`#qxa$xd+R zax9-$Psz?gvL(dzo)0pyq%cvd*7OKsI)xt>yywzYpCn$YPIyM`68qfuwB;( z|CkA0r>a}J^Fei>#1BI239k(9wgp2)MeG8Xfe*6{%Z)Z8;W9`I7(xfL>O@{ARl$)? zjTAd@6BC%qtFoVn%`Wm!iv^1Wo|Au&tC$#?Cb_RIW-? zR;bOk7EXe6Xy+FAc!nKcr0Oy7&23>aX4jcK`U% zSC#t9kAC*S=;^_SudgqT_fISJjTY;|rPO+)e5$(JdX-Z}(3Mc#KT{P8K4g}7*$~iU zI*y%P<3{qjCdF1(JaIz-(8sDjl7&|hAV|qneyDaq?VRE52VQ=p!UY9_TxsA8k5&)E znaoHs0=otpVHg1X>|6LRU)~V|zRpL_n8-Vg5jcQT4nEYs<8r~9L?C^+&NG|5&{R}l!kclCgM zUz}YXUS9f`T0tE8bD4krQ{j8xMSs-?{O8ZG=5)!3@;JufG9{BDA%p{M6seBD6BWTK zOTq)(!p4(yNw7$n1*gnw#|D@8t&}V%0-GW+-^#iuRi^8zm0rYz49z^r%=unIgN&#eM38f9aU%BRM;XVL5ejVkWMn&4__6+&dw~HZ&SE+u0%04A1w`I(g@Hj%R94QjnSh0r8D;F!5 zl~~c<_-u{N_B>0<;F;YoBjKn`M^M>Y`69r-bI-avf?cZlr#(IN;iYBTqv-a5E%mVMet2vq#a}zO+s^%{9k*2&wIQt z+L@AAALks|kUr;m-{%7XSUDLM?b~88Yo|$_hISDyZge;m+H0rwEEJfN<<4O&QtnEi z@(dZm{>2%klxMd>Sln^4^#vp9u+3 zC>_pt`Gc`$nVe!W4hOO)WxDKjC*!dpY!@;tpHtvs=$ObavGu?)yWnNKlg@?-n@&h) z9Se@#jJy-KQz&Q)r?9$<ZN4cNk$jW$nq$nvrS0`*U50KOz! zm1ku`lvx5ZBqzWm{#tO%fIdc!2`QUQ!})#1mZcmIj%B7s^!@tnlhT?}pwcdP7PECZ zmOygLDe0QqdF3{0dE~RtnA6_>`}E55l}ER0gQG95-nsW-bMKpvpQTHUdzJjrAGeRb zd3b4FfnRUum5mjpa%`#EFiQPUlve)bAPTkA8-UxFk~zz?l#aR{(puKG*D&KR30}b=ohLx_PoF-5w~)alpvao@s! zLF7@r$Ii7gVnR%rV7+H7c2xJ8K1qRxb>E5tnH|liy+W51OFPk_6w8t|jg*nxcWDzX zLVa}-_Bt@&^>wk-(YpLc>&8k^Ut>+~8KZnm4yCKEJ)aT@GUdg{lk1O%+SYQV(t#7{ zL%Wd}YBp^50*5jlDKiqmx9$gw;2r?=ENk`Ay*3HH&Ck?lu1)rHecywv`~>!ynLKk( za0njH7059h_U!8Yb+POIdgqaue3Pk#QBaYK2>geSh*n7Jp2F|?ZA3u^2$Qi^r9 zT5yzBApw|;tjarps?4b2zgU65)wVIzCKBO>BvJ~s*kDGzu@Rx@tU!$r<6i&J2q>vkvBDIRnI0uH#Kv2qaQ!v^GQXZ!wT`^K6x5`SuWH5*9sq7}*6s*z#mp3F0 z#KBMCoH4WykPFjPVM^*0i(CUaNsl#LE)-q;WSD96b*i0mGW7sJcObSqgW{~1wWEt% z!H_q!KZ*dc5!)h!7~ZP6bdF7M(P*uKbUEjr!_Zi)I^=W)@)Z6W$nqDj*jwy;2I13k zQHX6P%7*20;~E)flwKsN2%+tZ7;i15l*pnWG=t_>W38$n#7!pCHISHWamzXb5U2bTVtBa{b{2$<|L(S;M^KH5m# zK;D#5zcHy@YHij08mb#lcsQoy*4U?Hf66GbgBVPMYb4b2DrIC8I=`cR^CT|M)A2Ek z8>LsqW#7jWjlv1gA{!3sNA{nEIl~6@#5>BeY5t- zS9vzhgJA8_7Ry-@&2I=Z^#S=0x* zno7!PZ-Vf<2ghex7}V#h)MxKS)IK|}L`#9Lr&i{b5A9hTdAA?A=$To&PTlfihgQq@ zF{#k4mivIOf5#FS81R{h}7MdBxo^#Z;Z zX&eM+hjheOHp=xKc2M@T&^Nx|h3DCXA+?WjB8 zuJ`NnA%ktE+oMsPD~?|=3=yO;N7bmUzJpg>9``ShS5~opjH;E3(kB|JkRw@QV)_m z%jl%%aP9;9h!~{p=pGrB;P0@scj3vG?^fH5`wh`l#=>AIC3;wU+TJWLR}UcS4S862 z{#D1ATL0o?`#@4-#VRjc@> zwu<>?t5Qx$W4uuyg>i#HttUpUZpe&-p4mX0qe*i#9EG=H;W2hg)gI*nU@%n#cx=6d zUg~8P;sUgG#iC&@%u)zVD)P+0&%iln-?rJaVwYu23v|j$E8b}sH}yP6v{R|Fd_L%k zjWuhj%YxOen*s(McI}yhJt%7m4a?1;gZ78~7qb49XgQahrlv-bi(v>*LZ1zvL!fvn zs6}aIe}`H7E(D~DxvU+)Y3vG9Ahm2S0I0~b^p=#6*v<*fWeg1|&xS&3a5`5G?I^os zGK+*-A}nQwbGtrP-6Y#781N#a^_4=Rn_5j7_2mv8TLtne4CN~CfCy(IkMJ1OM1A54 z>aLYuRSD$nzSGf?MqBvXA}^U8H4W(ttXynPs~==`-y=n zwIqVvs(Luv4l`e#$eXO(KS{jQT-;R>KIZ{N6|aTM7%m!9cU(ech+3=$nQxbwg$Kf5 zX}e-ez->(G=nN4c6YZMe$Ktu&^MEe;shG@8ey;PexCCR%32|oBT3S1E6(x0PHqKHy zzyb{-cjJk;JX^};^zE;DD<-jJ)jisGh_eFSQ^dSVHuHm%br)2@2AMGDy~k*fjxZ}i z+%1pQ(8xLMs%Nje*8%w_SDxqdzx(hn)9L%6*M9xi!Qa2Q`f2*lzZ#W)c{519 zJ2?65o%cUpsvzb%y7$3zyuH48mi*Zhs6G2xPFzorrZvzz3B|Nqk*CN$EBY!{!-JM* zaI_*VvzwGu{hQag+0U!Dz2$*9v_BW!Gvi}C6%fIirMarrwH zSOD+|WegGNUD>a!?C-JvMFUmQinmf3c<@GK0A5+S^`h{3v;3RXGso)6{)=F>8Z??} zd#e!$-0o@@-0*(4YMU~gW+O3PG#sXh_Kkvqn>Qcr?p9jLfTj*uVH_-ZSJwY6g8tK* z=@{LWi_s+(@7A3^hy4x! zh#;!37KXm!8daWD_s#;vUX+MY#@VYl4ZwS@4Chf##fI9$&i(9K`*xJW)e$zkH(AJ7 zKLgDJx)M~2U{K!oTElr=oYj~+q0+EwC3%!ahKU`;SJn^eC8xfIibIyT+W!LUD(+>z z-tlG!nVk;mhkbNiLfMW%_TgyHz?4d)(tLOze^g(bc|@Yf-a5nY_4@o%WlNVd9VjX3 zs|N#qyXtlFD(_Q=UR$hIBvjP{pyzCr+Mv|NeRy#}lo(W<35MyEC(7bJq!deRN{1DI zX@erB!eXqXV9b~vug*Z{W=f^CDz=5+^1gPmfKO+Y9H}3`_)vt%1 zDm9a#7vl0(AOpT(5uCHj zha78%X3M#+fW4fLm7%4I!Z45xPl3v;tEHx=z+(|Qo#ZJay@g~sTh8WkSwLIk>M19g zhC)@=yi-Hc&y5Xd?TmKtDU_Hyf}BIJ;j188y6AG&_;Z*#4a0I4DsQiZ{9NahH);r} z;*1*oSv9IP8epwGnW!xgYBs8Y-ZrigDL;1g6xJkfkJdC=R9F%%mb$Rxrs3>@7!Ib? zs7w}G{mRSKb>9-08>P_mz~x)Pgu+7^kb}S{)?@9Nu>uRVfm26b^*bykn&6UdDTGe^ zldZFRZR;?@c%%r`t(?5{sL47_2C>7yNz zfX_(UDY5003xjaX!{ul4oR6Fs=Zp$j`{<0tKH<0*b-8_5xA?5U{@DH}+*Mg=N4ohZ0E3oh1FSHnP%3 zp^~aRz4qIaC^rQ_* zDru>+G_v;4>3PxGSsmC(8=eq#A+)NDD(W4C?P``il06B1wJIOJFT(oWYt@7wo}BEg zp7$?!2*>SoBAt4T41m#P?d&++ott}j=f21=?Vf@8w)xh8vUT-&PwYH~a+u3=<4U~kHJ8(eG2)3nD@`9NjA z6EW<8{JmsM*)76B3emd^spG+#ZW*{UaAIoQd}DW@hNK$#nW?UN62}K}J;gEQ5v@g^ zUJocFRA16WCTJ3(FKgZm6Xv#Iu;G=2X)>3AHKS_XsdY7nD6!Q01-{8Wi%zYl{kaEW(WmYRs42 zH-sao3r#H^p;OKqNY{mu3r7mGP%{vT%k~(FGBaO0048i`(?#q1RjCIf#durR3N0Dex^ZX&|HMeK5#wIz0?B16 z&0=oMJ$PGg#fH3zZNpC`jIy~JM@=KJhPTVju}e#uiVNp0_V34WQw1JqvzmQ5hZ_nO zpoYt^9Un&Sr4(8QY=i(sAndWo=~#?e0YTax+exIl67eMwqwg`)&_d{L-`C8J+6uZ1 z9GdNW%t>kIQX`^HaZIw7P&*jUJjyhT;Ra)*T{#q20p)LutFy3gWp!{erq44fYLe9$ zld_?7*2m76o^Uw@`%Jryh-S9}=dzL`XGM33%FL-$BDb&N31YtRHG8ngOy-ecF!^7E zfU(vM^m5Ke(is&nQy+_ln;QZWO4xDF=mz2uYAlJt>6OaC<~cU|&dFtxtE6Pwbl2~u zWK)}I>c+fGy9(Gy`EI(eou@%4l{U|x{@}sgKV19Kt!pHx0tDNN zvfNZ(QrdikR(j|e9Gh-7+T8S@EY&J0#!4Aq9)npK&Uz8>2wZlSuiFeRJ?wZLgjCZN z?rt=zx2R~4`^w|Y){mkbNje5^F6aOZh4(hjR8P}yb{mbW&u(_$zUl%VDeg*N zON;*l;J?h?bdVk?tV10Pkl`V}+kYPfZ@n5gzX8P8FMMnOjFDDT;#~vEH3L^NGWJ@Y zA+`9V_C&r~6h{+4Y(m6_Fql9_tV^wlXLQJ^Gtj8naB(8*Pb>p39w+5Ydw+dP@~K7g zFBfG`vhx~%rwmfSxr@Jdu(zlig9*#vn6MBO#uH7KW9gg`e{qjcdjdhHDv3tH4SF9m zCU+fIe4g8ZoDA0MAz2%W+_0MurBWj3=7%Iq+6g}&{s6Qe=tBu^!u&-&}rtM9ejGU8$&lC{>**eI#iu@uuz^L(c;$3oeA=hY2QbzfRm z;1N($_0KO91i2uvfOO%IAgY2R?Q}r~pgMg&5?rZf&--)XrmSPtJWn@InHm7~>oHgM z=AH$CrGNDl*XQ>bt5e(xN^32A9`*_3`^LihnUye`0f-%#t3^|h!9-9=a zM{HV?f>ftxflwIL*TpwZ-)Bz?C0tALW5|CI%fzk zEQ6|ekN{ontPo$(4$Zubpl~`on(ee4OA0LZ#tok{qb4C$&$x3=D`Q1+EE7-(%8n%i z6??{)BoGW5V-LXf=cU!^kF${n=7Oob+K@S!X*4wu!E)c}F5ugD5N0Sm26gG3175aZce}*{pGQHmc&!PLzQ=C0lzu7h6TYHCT+GSI)K12EFMT znD@`ETzUD{>)?C+doX$2;S8K649`+WM=iHK! zSnN0!@T<3%{vuw}Ek~?CjlF@Gv;8;>xMTVi>`#FE0T6YfjkTMZ*hbrD-T;qdt{(5$ zmGg7$`NFAc51+Sn6~;LX*zVtv3hG^pIz3Q z_346EwsjTsDa|6Ud`KqPMfKoPvsW)7j#3xUVObS4HIS)Bc@kj&tg9ZnBDk?lzkMYt$YqD4sC!rVNZ4KaU~0W0InqPFls74NjX7 z;`UhJE%@#Ow~+#*SpfHylI1njGAaS%xmQzZ1lh+_x6uX>8O)Cjrn7w|UWy>+occC` zz+u?Fj>oEK;*>$A5gp6zv=1wkqATi?lnHJl`^wqt0S(1X(2{AlZWt5~!Xh=3@g1@n zBS1B|i46zG+7z=Q&MLM`jZB(udyqAA>l~eo+D#LfDIgUw&IFIPaz0DXxPDm>Ooj;2 zB091BQru%8zhWxhkA&`95cEI`ayMZedl|FW#(E`l6#bX4vwLmpFvEE4DNdLbA*tzz zEMZ9|5=4qs3tLrvS{)HD42jfPJCT9X86yjgQIeJwqMQ20V93CQVS*h9R2Rk<3xp(v zx32vNaPD5;-}&a~#*2rE=O4W+^}qh?{>iQU z?((Bd{`}pM%eE$K&mFq+9x81gVckth-V8x5WZdme-P7Jc53!UsJDM#^F6G%-dDlNH zv$E@{m2s~`5(RbGt{Kn zSl^}=w|gT6YK^=o3CuR&yIhomsaot@&Ot=M^1ZEU%g%*A=Zap5s5jWGhL<%E4_nnv zt0)QeUMTh(wmQ7Ky>-KbHgcm5vuo{dPxZ=Sw66~LjF#@nAe<|1z|*;;(5Bih8p4iJ zw5qwi%bFQCMoh;!b!2}rstt>c%?1l?(RC!=Q2Grqa`4wm7n zVRG@xmpgV6`I zSu!jbDKjmGn9gF^Wudy@6qZ`r`R}&{qzIJ3MnqTh^NLGUid7VkXm5+Dr=Xx>7_Jt( zD6q!xS%WZat7#ep7&c3(JmW%Tk|}V{Vq=vZ$RLyk1$?nHtV`vm)pub$HmDo(N@Buk zG)m3pxPa)%F!y*obD+D-eR0Tw+DWwxjd2TcOw!It8aswZ&In_T!p@KW2?br9;~#@(4D{8fcf-lMg;aRH`E zh6Sy}TR~!bsyfs%7(%biEN?5+yjfw-5=1L~GA^5vGNAS1pjta$f8sWzuR!7VM$tr3 zjubulwv({qf-E=rc1o*DZG~i=22`>n-nsw!lj_c-!^GMSI|-DIuOz{rHHai|fofKz z94#uJ0i&o4Dz#u?aY3ExWFb|q9?65GkgHxDT8k-Zed$uM{mu?}-P;GD$)|}Ny~qb_ z59}w-{l)?O>({vpKVGRKy=piN6T{4~STdwNFXttA8Q~T7q!zi*loF0c46W58NL&={ z^z3Fg6~}DoD4`W+LISe3T3|nkk|MET3m0-r_MxistwBPg*+44CYal+tz3Zds(WY;H!Rrm7 zc=#C2b3;pFU0#efJ@3nCE$^&PvB5u4=q1TWx^hHMDwc!sL2)CeWXs%@$<+^Q$cE=u z3_uT}aO3$EBfqo0arM$5QBe>Q&C{Z~ebU50*&|ToES4YI4bqEq^I6?M3kA?poX2dL z>OHm7D*V{n0Mcr`#f!_JSWDaV0qIc`$-|usuvSGB&lScbWf)$ni-3fwdC*ddqqG+a z0Go5O|%?ZyK2WOvYm~6Ds{yf01!@SrS zuW&OB`awX`Gd`ka25t8VtpK&`dkpV1D4qckvtqJ3RZ?UFN=cdR?wGswYYg@^o41n^ zAcL9Nq|W3rp^zNw5b@xo3$%C_fq6t?!Ef+VaLOZ4Wq(nBqTfskZnI7CSuh(oE*u-b z*6pNVHmUWq&gmC)gkBWRd?qkFrEP;<6haWJi#4N+6@%J=tc&V=E-OZ0z(@^Pu907B zq&Nm920*w`Un~^{!m$DK=s;i_+QW&-Ne^GUFQjB(KwP-_ogcVxrhU`7Zd9ty)_l+8XK#&!JeJ= zbZZa~Ew&&Jv{h$ZY{*<2?=q&{>2eI?5ofVSR@(%OHW9dpJEjCpPwT>goNzOi8Y(nh z1~J8;2`xEH2&!W-6+hVrJ!Hl$vlT}wGh18U!*aq4Acu+A`9Q>50<+j47NvEwFb+O2 z2Ao$j!J9Y8f7^njy!wkWkr7B7SQSZLK!_W+?r80y*t*8a8K z3;#U1asOIteg0pMUj0dr z3`cDh6*7z_mr_~QsG#d7*T4Gh5?J?_CzEhBDqtwBzODN`P2;e~NU0*7#ix3+i7vI?dx7($XPo3M544MpR>Ih5grKP3)!TSLGJ`kU~asOsjX4s|>Yp@HN zfkLl8z)S=gm3#>+k4(BnB}<3Y8+o23`4)(_G<()a*$%wiQ2Z9l=Ul_<5vxe9J6s=V zfz0ICko~cm927FbU&|1cvLlSohN2D4p&`SPTyq^_;Ow=&+E@E>IE2_Tv_@R*;gwrn z@ZhD5Tbm7Vx}!|aB9%&HgIt+>dUi#P^4~A0duIWy6(zI}R3spp>y7d=>grPz_ST{4%EYNU9kR zO`gSI%R9}CW$KYx#-k`y0W_zoJQWeZAP;=`IxBUr#?CBfnfj&?B}4HJBrZn!EWuKN zsHo&I%4kp-sLx8Y#HN(6DDbl&%dEbPQl`m^GE_`!czj@QpyBQe;-#$Yv>^3ZQO&5S zv|I%;(@8^Jb#?-w@p>^0COPK|c`PPddCJi;`P6-Oo1r zh2*h40TBjRoBh7yuyoTBVI2ds&SLuosjHge#P&#^BLus4;m}XsE@<-X)Rz&pIJ;pt zfPAK0snHI-Xs~KO3}C5rca+73i3*6(NU3o$qUeFPzBQb}1Dc~NxP&XQ!-`$SlX#1p zLZKV74_Ayu*YGga6g9v}K&&RvOo|8PLpd|#WU_Np8gGk(OB$--b_HBHj1ia{i#YE< ztxOb0aLgb$d^?Y3kPQ?brW9damhFj9Oz?J~G)-VsYvzG>7N^LR4xID48ha`x%4}RU zkg`h=oLWo+l19&ESPs5`7f(f1QN)47hD^6*4NegynHma?ktqZ7hNwaC%MiW_qaBJ@ z^Y({2ZF&$%sscH-fPd|#r`6i7Av6LqdX!@>7iX=`9|Rt9xndU(!P%Xnr&Iy6b&rl7yh=RnR1l%oRPRnvuVW5UEEgDp>3~b@){(p&|G*>Nhoh{G>wjX za|0vm_`5+IfB%&P|3g{OJE8A&wdlR2C}=k#twuBHo_7TQkFT@)ZR#+?ctc&QYFyX$ zSQmfHu~F=8wqjxtV`3UxP_`wMfLfDP$0N#)kuS=MRPDo8xrr2wi*OU6_#zivATEZ4 z_>jUhAQCtHVS9hids4wVjZ)$G_?%-Sp~uhrJ|C3@&%IjOn0fs3!*h4TJ&|I2-BE15 zu~-9Tt2IR>C@;U^1+1h3&jYo1Hmmg0G^!HbRBOsg`r@_Z%&4n;xeF8S8Qj+29YHgi zUNfw%X!VN{YrzFrY=#&1rmp`Kc#kz%zrX(J&egJJxk`H^kr`%ZEVwXdv{8xA9syZy z(FG_`6Pe8Qx@OADDp^qCbGJob!$=~lvK&DLyd%w3eNop2w9# z^WM{aHPsS_ff9LotaA`j8K9Pwo{T)%?qwLa1=a!BD2tVroKZ90mfC(w6cyx!tow0k zk4v8VG>v8nYpn6)X`V%{q(~@`d0g5;2(_Ox#8L$E7DA@@w9BLHA?E>IW9GgABV34R zDP@3eFq&^`5NnT1V?%RUXB{U?;*D_%z~&(0vCO9d z;fE02Hfvq5Tku^f1;A;$6hV1gU@K7nHkIcB`P2Z=9t6kN5??kpJotd>NCQcfn6*W< zc6g;E``}oEF3TFwX?)g*a9V=t#su$Ct;Wmjf$`pO5=!ulNE*(}%W66|DUr2cqN7^O z22p&J9M-Cy;o&j4JX>vu%;HH7J&UUf8cmeE6*IQ&^jSV+Wret5S%4h#DRh-!%Wx_L z7X?vnT4I<@R}(5}!PivB$JHDSqdaOn$sPHQ)1Ims6TMW6lcdW?!*Jb74~0v2N~d(x z?_@um;1aHpig~hEOi|XdElo|GAW-wB7eDzL7yY%p@2N26C)g7=dCPQ9qqM-YoT?d@4yPt!!^WCJ@2HCDFO`q@(RM4Ldfzt*FSVB-3jVq3NUZI!VwG2A0Tw@X zqmPTU7$j$32M0>as(g5Q=kTlBuM#tZKm4gzxEy@atF&*-kn?f>(%!-8Z50V-v*)io za51%JyqY?5<(_gT#cQcC@*rweB6;g@vw8mHopYCOJ!w{cedgrJ-@TkY`|pFkN<`{?$((GuWl6n=hR1fxHwN)<`Z}I)cW0m?R%I!lH^; z8~08%)B{J2o2Jt0W`+8ad34X4Yfcr7DBF{9^f`?$4^Uq5fESb)O(R2Z;p*g_9k6n)-^+sjYUh{bZkMU-uA6!3vz2U0*&AZ5-60r+6KHd& zXv(_E6I3!-SDKUo)3W5s-enIhZ0&kLv*b?z)37jC7n%v~Q7H*E%Poi8x;QaK37))F zepG)Xzb-3gbpY1uyJ~IXP0>rF?gq$feOOrLZllp?IE?y-H=_-9cVlQ^xx3kFd7DDZ z7;?A8+8M*~NG{|k-g?(4{ZNt8pfv$s^%X-{khn#U@QA;qR^&_`7FN_`>_4{XDsB~q z%cPMIhrP~fy1sn>{KqJsjQ?&aWRYQRE?&$O<9RA@pMsNW7hoHUxEV_73)h_Mls$}i zE0>qaC!>U@_`a%qrsJoS?HGCa2P&UlA*BGI6TFO2b7Hg*jfw4Kh|`I=OpD7Xwxlk-M^8bwE zgv%iWBO{k!Acb4vJr=@9ZXHfyp%)PI6Yy9|d(v)f;?+!E$#m>Pwlj=_PEbd@sV2Ydb-8JpeQ-x4TPxRC=cdcBI#Ogqt(D}3h{|}i zdXB}hZ+1FL`ASCYT=FXR)5(Z#ljxyO#M{tJfV*!WtK)Ds@#U4h=CunCD~~U3y?%1xx7S|X-cBqeFMOY!`^$^MG}p-}N8UHuQ&_NtIqUg24sxAM$)&*mzTC~M}({+$%b2&4s_*3@|q z*7tbeMot}YIe4-1jP7ApF?imp&My|{zj)?Nz-XLl`i=0nw@`jhghlV~np0khpDSx# zh=d=he^9&r|3p}qcdm8m+AAz?3a|`kmxt^(yX9S|Dr~nqqIOXGS!xS5-O|G-SAwj< zNR>h@FG!M534&X9k&_ZONO0CDdu~JBhojL(mkOfpkPd|9I>TEfMz2ujyF5Z-Z6}Y^ zgtUqAXQ;{u;v=D!I;gx%d*>VU7!{z=jE?K>s#2{(dBdvF?7_hEi(>M`2i2xzQff)NGZ$JKv@+*``9T9 zYL43veQc{OYbv9ys#L=`fSjs=)IR^s2gm4HiuSVsl-X$MSeTb;KfIywZ$5%;gLEa`OE+qj<7kE`ZgE@g4fiI=pud@dnPCi+TyxKb-7h( z5S=qf3CQ_BK#lD`-rzv$gNA-B){tHrg4PUu?=gR#NSQT%s=BC*p0GxNCH2tQdwn`h zwWY!3+gepv3o_TpmakF0CK8O~O24bsNmYG@c4`=_QFW-LGW=KD;f`Fynrnv>d`-~h zq!+kVy|J9YE(6%4U3K20w(u$$3|1*&iq)jC5p|tJtFg)X5E4sA zJeBk%YD3#p<%&p%oJ=c0lSeVn5V@I-KsX&n#^b6YygHHfxD!DurB6Cft6aQ7X&RO% z2JKv0&sHF+7c9_wttHgoiRuSY#Y z@F3AY|Jmd0Lgv=TcXwW`ZQpv3*gpM&3Gm)G7tTUf@iGxgx$42so&}QiYz@h>6Fye< z)DOv*?_N6F>;3cVtGRz2^s>)y-MM=Ehqd9SC!b~a{<{5}D}Vp&%&p|i>)7XaUX~NR zS-1VFr%)bX1y9auzOD*}Sz&Hpm4kidVKoKNyxJvM+1}bJD`9U)I=b}V1L$KR^rgr5 zTkA3%`51b=;*zX&e8G}AFZCle)IZiEhtksK)tMLJpO>R#j`imu@%i_vi;Ko_->T6S zRTeP|IbeBFd4q~0T5Kp8so3y9ef#h82Uv-`R-rGKuQ~?b^8x?uKYU&9ZyNUE}Y7lnC+lRy!M=$L>qD?2oXD0w9Sgwb<=n=zp-Q~FX)R|R{SDT z{9@W0OP0r^L|T_>d6Rejr}}xG&lks=)2+>`P5m|0O1&xni8vX=XyE(ui)Hrz)| zI+J{aLrx~XJz-;RbFiXyxPn1}FvW=(>I$TD+nmwuDGD5HL`lP6i)6|STZ1+5S)OBT zB|3Z2!6dk^1-w|q%I}5)hHGR(Rvp4G#6I5g&>!)*32~I6UMMcK16Z8Z4h)9M24T5} z5HOdUg`wH@`rLazD*Hhw??yh5A0h(`7~5Qd65GxUMj;K)qlsJ#LMy>q;BzRa0XrVx zmIXH;P5EFq&Td@=@tps=I$w2~i}=RW98J3OoGc?KF|9dMNb#RrM&VtWxr|u^I*mC- zhNm_~3Tug*N3K53>uq0g4Fh;?ndh3$sv7n)vNr>SQS zvZuK`Iqw()Y|vVT%@ka-b-}`URV51!Vup*yn8Gs6f{Na>CP#7KI<}~H626$Wh`Sc4 zuqul!l3Z$p^F}93ZLo@=_>4s$m)isoM)~UHFYrq)WECjot4DH7qb~TRZgc^fy&1J7 znw}4c^?9YB@}NJ%U|j=Sx|y|to7H z0J|>ZY@@o5uq-E$VS|RYl#^lRB-VMCZdZGoX~Q~ z-z5&In~bLx;uk{1G`hK>4UdTHR19 zaxCF;QB4;$ao(Y~O5P?ql^Juw4~&_!8l~|sDkgU~5ytoO-{qaXAg+toIG3&%DQ}oS zs<^2hq@#z$ynsiTcj8FI$}PPn7H_oTuf6!pmqfjiklW6dK;7!un%DXEcbgwB{Lw$% zo^IUud7@|+aHs$PAOJ~3K~%F5Uwn7x8v-GV5pp`@_JF$`;Q0pWuig&CP0BOD6O&;9 z;HB0VA5TBNUR}!Fu)4v|{#<=_`{r@()%MH#ck<7Fnmn%Vf3k3GJ-%19-N%*e_e znH#znu6hQ5i*2oISUWv_{O?~T|Dlqtt;H9@YSvp~X22X4 z(!^pE@r)WO%#P=k z*n*8dg$|0dW8i7lnoDI7DU5yaSnzht!hz-Sn2y$Te#~&kzoj_$eTu9^=2fs|U`)+2 z;4^Ikic|AKRW&XV{MF)e7Y3d=YYaH;>e4i&3t2(iG55Jt0;ebvhJ)6^8W%cUd4Lsc z%3{r)MKv*4uso4A$Z1()3WT}7da z23BMA?XZE70&5J(vAG3TPf*51=@noSRP{)BbOR3MSc4{C;~e(g z_OiOyGsdTlSu!OD-no_rZzwy46f55P!{)R2O8)k%n@^Aw`QFZb$69-JyZ?J{@8(-@M-fi}zSGs2gE!g1LTX#Acl6ipVVrv9S4t3Cq)g zwAYazJ8ePfs<9#ck1_Q2*_p;b&w@5octumN{QYQ4Anx^S1g%L}TU&d_)9cUn&x&$P zxVRX;sMRR365@-_)+~!y5%DWXTcOjWP&h>4xkexzR*+Cw&|g$oM+hQo>Ie}`i6L{b zd2s|y(3Jy<#kOWp%3(zu#bxk=#Qz&XU-@+JOYIF5+!gA_{E4z1Xo(-3I&{$rs1E!U z+t!?8wH*16Sb6}}Rlop`ObEhAE3Q8Y>=Wvy1#-h6$OOWb2W(Qp8Jb|JVF*+mBC`W) z*A?UD1)-e`N9-GfggSFFAi8Q>uOQ*-v%oYW1p;%v?Vn&y?fZif9L#=3n}cy}wgwBy z%l|=rw7IeCC3is!tg3-zB4)@=&G{A3DwWIqrk@-WGL<$syr+_Vf`;oFNo}u zQBN2iz2Z0h5o?kds`cCByO)>Yr%jFL=F!>?QdvkNA(&k|$Vx`k1u9~RxA?Zqhzn|) zvs~jUQPtp!F+z{)h&yJv4&+mC*jkK<;&hmu18@VS42-5ZycV1me)tqQ5HRpS$AtC) zQsoq2l99;y9_=}B6XmsGfa<2P(fm?nJV&JxHBk^J2|pd{AejEv^jmz@QEr!OR23(K zGd>kkm{Wl%z(SIaW%!s{83)ruY(BV2mal~EAUzavVB8bd!W_b8KdouE#oP|^LR@=z6#LV zv-AuK!@c_X1iCvrO~2RG-}WxS3E>n_1s>IEt{@L10-{Q`;=&=p$}GVEtbPHza&!qK zRY0|-;0hv)E^**2QMZK9ERLuvP;`MC18N(rIYc~P#CdiDZeu19l%kSm@F}ox((KSz zEWq~$KcIj~JIfo`IWzu4>28#C5nBz94p^rkIv8%Flq_-R%=vYLK_Q^A7+O07&IBD% zn0G?~%mn z25*MV+&lxYIqQzdnFZ{%Kbf>1J8S)>EF7OYNy&IA(mM$ntI!)s3JmXc#P$ohUW_9G z!R#L#mk~3`Y%85G=O~WS28Io`4UyCWm4%%mL)rLlmrN(a5>BwB1Q^ilam~v>4J=<< zjJaBB#XEA);z2bY|N8LL&o;N;>mY5Kqvg2jt=O@orH7u<;+(c2@;urYaqCLsi^{_D zSL?_4aesaK&(GdJzSl@rzuI~5VCOog*!v6rinl)6Igld`qU{e?=|@u6u&#i?cH=}_ z&m?t#1?LzFP0f|3;%I!w);P{C;a2;_`osS)0YAL313nJvFd_%unuS1boqL1Vs@~fj zaFJ2b!{__^KmPoymx~6bPcd%R)Zc93aF>;E%TITO?h3=5ub_;khN{-uZfzd(>1^## zSn_U-Vf-Kb738-_NTt09agzvm9$l~@dDU4JLlI6S@?WH3acteH9=Lz{o<3mwS@^}1 z$21LTzplM9Xf^|=p3Be(`wWt5Y8Mf@kl1Bl{5f0`Q>isVD*?D;z?%AC5@eux&Y;z3 zAawGPoMQm}FgCDdq(lqGQV`9}GX1unm+j#YlW|)nV9SbNn2&7q0LsCCIs5gr z+!P)f4oGMxK4n`Wlv}>(lt4cMWL>%q_D5xZ)U?B)S?Nxwc!qJeNeR|>be+#{Q~4Fe z8OEYg<5G_`n#Qq9>?pRVjZGqKc`!q)qDXZ*4VA`#=e<7HvRl&*VnDQ#SJ^~DV&Pd7 zpZ~G7+A2O|5xwl+^<7AY6&FH%k#6t=Dc(7`B9jt4!AI%PNzNGSkqSP zvZm&W$np-tS`S@yO9@*wuOLG zgFRMVc;q*+(}kp>4))Gkl*)=5CdwG*N{f!1JZhL##>K3tPCky|u4$iIY7?uBE_bHz zMUO_Lf0ln4G1bf|4@F$cDi4Bmr^xdt+TbYr(-~mQs#fM5j7c+htOBhtX+SOSiBK*h za?1~{p8%d&rB7&}8 z8hD$kow@+9s`6pNKI&CZq=pAJf$OR}lil#fG?|a8JFju^x9c zqSvp_xSnAD5BJxJ;Ml<_tGTac&YK=gNqKMDSHMi3;fSkm?Yp--J8zLeE3q-u1tXmD za$ft?b#aw=wA9qH6^A;*T&`dK>gvN^hVns4l{fX;J4)jUVOXm!!0tL7r*;99y!4Ch z?ek~<@%_gy0m=Ofub-Yjxb*M4(ZxUgdikqcXRq(>baM}`JX`JVZ@=#L)0?#~w-3DI z(33V4*CEhV>(gpi9-~#XR%u`LDsroU%UrfKFRd3wQ*xv)*9HF`z)q?qVG$&I-7dKF(xX^HHs1f#-ubwC1BZgnCez`P+*Qh2o z;H_HkRkD5eSE#}462p?GP4ad|BT_<2t%*VVbgr1{Ldh*dpufU3=Y`SjnxkmQ&1$)7 zjPQ?;7G0x+7#ESdBFACE_z<)2Gz z+d3gKhXpHxiRjVkX-DtJ#ro_N)x}amK$j}<8BEI* zH3*KAcrpEjZ5H9T@e`SgGO%FCDYB*{PC!8eS6FG18N@sjFqat0<;bzmlr>jQV!viI z2-um3pz>UMy;!T<0qENnz;X!OjyWgdwPGQ0;#w=F%(1g#!Efxd>sU0ISB;?7ahOuu zp%Zn3I!qB@Y+a?LYfxFH#|FTS`q%?(I}IUeRV3MUTTSf4V|rc;!^yj?iapmKHN5`R zV3etK-M{JJW(uiW)O`Uh_dK+ixcR+4kHzwR{2q!z^Ce;syo{=2+8i4bAn|s^QsyyxJ|eW2k6S z&R)G5^kCsVfYzs#&P^(r57+BlNlq<(Ac1-6r~B)lITDOc_a@{V6e-Oa9FU)E$d zB)K3fo$jB#^5)gUa_->#zVXu4``fQy|L(iyr-wJ5wNEbJyYltvZw|{jJDTf$bL*A* z7e2dkpbRV(J#4BNILNF7=#po3ed68?8t8QJ6RQQuqbTJh&K+L3x!}J?60ARjD9V>T zxsWcF%jM-^&)bj!`r6-(i{;&Pz`@<+q1QFc4-eN{2iMC%F?~pLE4^_P+Av=Rc?G>| zs=`?@1g`I?-IY4lr89=sO-fu1oA*9@ru@nNZcsnNh54?0JcuJLZ5FFvao*jsr$TRR zl(iCmh6w97NAUY23ViLi`?pJS@EExC3Ufo#NliV2hIv%(s$Z9iAlix`qH~oGUPd`x z`n}j+iJ&Pqr={AuegtD4DWVa;8n)&R>|2EwtbdIp8tw{mQB4&TGFh8mR``Z&PA&xN zwWLdC6|7+B7hvV6_H_HNpTDu20swnja%+-dWs4MMT8+qIE`@4At(xasp%XY5tGF9b z??cG1EKQ~1(k@$a=7P$STHzci!R%IIs_n99yL+86M9nAD=|m6>Y||XkQuSeBYl@NS z>i#DuPt8C&FgFZ^1+X}9Bo@|#S)SMiEU=7ri%@2!)iSwycV0H@UoiN1t&XQQWuLo# z*pA{4QkRcC(Nm3~s2;K?I}k}sq$fIkRGUxU6~OI$gd|D_^A52*h%n0@lPzV1l6e<2 zNqiI{p4y%*5rxIA;54(a_ADmK@j^Zo`3lz6N_oRNM=Hm}#Q9~SO>Gjkvv!JGZKEgR zym2%@_++S8JOc7KD2>B-IP%8{NH@?D)&R4;5Fy9l-hiXvslD{T(A(fQ8AQ5#cr&q- zUYy0hB=$uxBWhSRSZ`l_@e5wZ@aZHP#5@-2YMLGM$LH3uQ)RuIftWBSM#%|8mt@6* zl87|x?;6bx`8@`hbxK=|5sx*Vwok6tLV9ICANT`eCB>$dNx2`SVd5sPcRFj{%EWU8N{!A!yG73%CgidA zKLAiwCfq=psBnr>VNGteX+@~b3fZ@`6$5GBBVerP%(39m$>`Xn)nsKO(o*sV%h<87 zPup$PGHOc9nzq91ni2WwDoK{`)0494N-$;IxzkXXHp^$p$(#~bw9l=inBW85j~ihX zOg$B{ab=k37dFb=7|V*Cq8-EjyHa)b<@WJ`L|C~HDXE#VGByCvw>wk~DlQV=uh{Xb z2RGB7kb9q#)s-zc{WiDYtPG|-?IP_YSI?EmE3LrEbcm1K$qB}tYwqlLcTqZYKX|<_ zA6=h?ul7IPen^bf`i&3!hRyfSAH4ed!RJq3-}wH{rQDyd{N&>ccdl+e`1#W}Km7g9 zWi|WWy>&ovm#o05KI%$my@L!(aUIJ3(x3jOM&i7eeqZl=b(a-zH|IvA?)x1uGOXj9 z;9D>ETMO6G(5nd5!?4K2!iKaEVeM{cOKha~&6oEt|F9lv43`g^$=sz(_SYvhUXVg-0iOP9BlbHzuGv9OUvnvx9prbFYBbMUrh+}7ZJWT@NnI$ajF zs#W45^SKO1rLED!+08#**x$nBL}deOVPUZL!|T1C!zSg1_6~a!Cf=g8Y=qsW%&}6d z)q62iJwdC${Rvr`R8`bG0L%WTJQKPwoEZAQP)gQ> z`oE`ZQ}Vi!J`8Ei5~j#aVD>^ugCirQ6(1@%$OzqFzZ>w&x0GbtzoifGLgX;`9#=`KR@P} z;h1K^uJ~OzXxqUw>#X?rRuzOz;HqeZef*jUqgX9f`FRuztJ_+O>L+c1lYJ-dy71{F zKCTAVB$e{fuja!syt5dE;c)C)COvX`nds#P3%Rio*GxNzjR$-K==qNZBBchb@xZY< z&OCwACiZXuiB3SyFYL>}P@LNUyZpdj>Pey~wkq`U$_#_v7&hx&{hn+mh5(nJGPC5Ww!DG$| zeFy2mckx~^=uFpeh@b#Md4SC*iWQSbCM{exQf8igF&Z21N50an8S`BuXFgWM-q?vS zLau2PxRD9@bGW4QDy;+9#<~;(&`x4w*fDA=P?UN$9va(Y9Ao$r7sQ&qwoL>P#aCOB zv7qL~ZbqXiFQ&ve7K%^9SduQ)uEu13K$Q`V0bijYPJ?mZ@*1GU({||o-cUVIZGS75 zW|MTyUN~N0Z9SGDh+7Akt2!jGR~5K3uroykU*Cq1Turitlx^SeLSv`KpV?k3!?P_5 zwZo}sIG$dGXpc1r=V^rGaBq+pt9C(wpvc#BNuExo$+MjTk1m!Qm*T(lDleO0|D)4yo!yfSsqyDqkF=eZm|5rw%+oO_IQGtAl?iJHJ^MX)ve!^G zu+-DonKli8bNTa?+<-Lu>D=BPva3tp2<&!X!`Q6@bMX4=X7%L`*bjJiIQ-Se?|#3& z;thrdz_)A0aPO|wR6|D*`r;9L;7C-%$*IVNISN>72GI|e6o^E=AdPcBeYn|R@Z3XV z#U_}P4Wq*Aoz4FRU^NiVDv^x&@+!@$S5_ao4e530d;P}w-z7W0SRO5Rw&~ZK)F-3L zqep@XU0X-fW+$2xIJ=Ylw4Pp0_**=Mhk0vpN9 zXR|}sGy8nm|G8R8;Hr(O@KD2AjcfIkJ&>idYZ6_~VcD)D$#TI{D@%Yu13+=mfur~Q z0I?Kk$QkoP4P=LzIB1p_zS>zb2jroHGD(FqqLCUq*+3j`NJVNMXXz#?I5n-5q#VoN)JVZ7?97c8n9%;jiB@ybXxcHFF zym%=j9xtlx$B|^51ohmaK8GJ-Zen39A_BD> zOD;Bc+>@v)EO=%}9C^0`M6&=*4N!QGh0QTurm2gm0aqP2j%8tn7ssxD7LyLN(Oz($ z)dEz0VOkK+WvLDEmzLUINF+&tTL;LjuZ{!V4&e3*7G~b*!c?&*K=(eV%isWknO5ga zxz(8y!R~vzYnNV0HM1B*^U9=USp%W zdwTa$`Pt2*z4a5H&);7?a`^JI>N~f-+=ONS?ahDx^R3FCYb#Dr8D2E=7=rug}fAab*1rtNmz|M`D#@MUFfYKy~3G<5PJ2c2G1VX$&N%y-7X;2aZ4^7Z=#;QJci2gtuvAm7(Wkq1!>hOBz>+l=|U1|Zg%t5 zg63$H*BUC_ax`-NRd@OAk@B#X9g0ClxN28#=Fw9mTTSRrxcHMBSFc_@z3at>T`hC_ z%l)oK#xg6DNZqFx(Y?TGX@ET&CEaFJ4j*oM?6Z1=xBcokq0!rBcWcD%x7qL7y@lmba%>Iv5`3X4zx8 z%{3P*Nx|I8$G54hw@NZ@4PSzsFJ_hGluvnmuIj)l&MGh}`6M?jxr&(quM^T%>Zun8 zN~kPzymbc1ZdW4XmXlea)0d_$&0=cH$qc|s3~h7l(n&$G3|`6?Ls}$KDY&Z-SZ6x) zC2dK7oas22?I6_&QrL3IAeE~VLuDLpPtO~4aw@@W!eg0;Y?A3bdSifDXG{`1TH|Pr zOC6py#O5re0q0EN&j!nh{b(l^hU54gwj8*{c0>}HW{R9luQa5k2-i`Of6L}?;z=gte5o`R{oU2a*j zC#Q_J#i1ehY}Q#|+x2N4fL@zFn-t_T(fD{OJC;wm?RUiQF=j$(Chv7>AJ zd+F?_JMZ6oUS56UROwRV@JAm$D*yJw-$P@2yXT&Nd->-*H6Rtw+`M1(wQf<_lf8|G z_c8Q50a~`@hBn^XHT!R-kD?UQRnPAL%=b=T&j-(rzAs16XZQB{avpi?RqjX9NE$5` ztKr^8{%2bC7>?updrzO;yZDdquq3UluWx;0KzkQ3orC5QhO}5y5jtC6;(Ql<_*^@- zrX#3MUsMgcVeos8So%VNwdd_A3Cpl`rT&T!xV%d0q~y^Geu$4v-XTcyWCr9qG! zHOx~dO0(AuORq?tT0UMzk2^E`$f6@5FriIfxsgYTrdFQa)OtA?KEUNnn46w-=@P{F zD~)&$VxI)Z`G9zs3z}L$l$66M80K@>Vdj7ZT}?Hmg#r%%ULY+=#4W)(;T=obOyKGy zS8^%m#~fmG5*Qp9TOAArTD3Avwu3V5gTZ88r}qIt2MGW^;Hy26B!j^`fDCkIx+Hse z9<($dP3Dc@a;5ezx@;Kj5P=s2mrq%0EZGiXs0~^hz$S?Za4Pa_m~5Zzy#^ecr1RWa z*qa_2gQjHT5t2tei&0yJ#m8Re!djTz+FIO3A#Gm+JGxzyMjBL&@hOpOD>+sSk8Vej zV}-(EI@cIWtA}lgJS|0Tjl-H@YAE%V;VK*&sBvF#TXb1d=`kB476u1-qGq6VDH~GxnPUyWeP7CQSiUQ1iNS6bvD^lPByMWh&Ehu% z8jar;rXt>B?U4h;hk(ayq}^VOcrA3D_K&^BLZQ}U2HB$13(DGrJL~=cbyz^CSHY!T zIx8=T#oE!5k11;=>JwLVpd?Q>gvGJ$Ik->Jolc<9LO4FUv%H~9Ndwy#Zj-G#+@d=E zFJ0&N+U9*mac>xBU5ajd4AP4wVWE&-n%wR0+4DKiSB^TU>$cVpzwayGocEmPJm-|w z(xLpcdim}z*4y^# z^Q9NLcVGXiWXFvq|M=)wbqcCiYOEn9lR`=Sm>L_3Y&2W-+%L{zj7?)v+;odh5-t)6wNk53iiO zEN3CKsnlVLIAFTbReCeEhx9zPw81aN^luN18Rb}d9seha~`(0Po2D?a}#*uqA z+=hhQOa!#&Rg#9K#4LDmu9!QX8X1P)-~HGHedErPdj^s~SdAh=?FWUOBXPibO{GJ) zeCG&U&NR2QHpG+@gjRvC$e|&j+|xu#&dGD-67Hg^3u<)_jaCzH6O_koWk<1-*7~8x zw<33zfu4#GD~y=kJjDfWv5oZW$6xUE^<~YtE}@dfe+gn1JKgfurgOCj)r{T&4J%JP%nR6V{?G&SM>7bN!F-ZUGCryhNfb3JHycDCngZ8Q`)F`ZZ$ zj9*tmM)69pAI-{}>zNd;?>btp4Cb&2k|m;R%aRTqGAL%Xj~ZOUQ7 zBb9Sl6wvu=FA_EFXdOo~uGHxh9nf&?qy=32Ftr0J1#gl)h8-r{x9radtP)*~QsI>j zo|1XN^%j~jGg`rRM-nyA=A0F5iy)dEU9J5Jim$!g5#DvWtrlnMwD`pq=xAR&9r^Ee zdqUs1&>tWd)`HZAy#~O*uwkr#wAb~+ipSayofF7#&tAs#6$$vcArR%(k-2jKZ-w@Z zjO}Uw=%_nVHU^x}69jMIN_4H^sY=o21MuR{VtGQqDKf0Iyu7-``K|myR^6t|i)j^y z2CH%nZx<6}FjsUf$lak|2~bv?M^;Xwywheqrvr*|FX%=9#L;ZI9Dbel#ByHgAoGUg zvR#uWt+$pnTdl&Uc>(xlXGs*BNRd$yWLb`lO_#&^6Ru_%!9c$S&0Vo>6|{$i@LRnp zZolo5U)ZaCBH6eWw!OYd`J0l)wZhCBlzp|};aqsi>@$qsT<}?PneA!m0-EiH0B(Iw zu6g^YdQ&$HxV;gc3+UH;=7NA-+P1c@tNc~CB`M7RY=4fKtq)~OvMz&>B{l1+7C{9J zKDMOR)o&4^jR55*g_wIlGdHG%L>C##95H_>$t52tC)EVpVD(AUUU+dyIIL@Fc>R)NFZT|?8x1zg1^r;i34M*hw=Yh2 z3~AW}&bb52FgUlNegMPjs2xeffwv~AX8J+R=z;k6}X~w!q6c;+O;H}yH$*zjcCXiG#Tx?#i=%e0 zcUV2w!qb%uh`z8od5b@tkiA&El_{)&rm)L? zkAJ#wNYJq5;7bPB^y2D%1=P|+yf;;0}mB-L&LfM}z#T`s&O{nuXT^n~l3c%0ja z6ZB=#)KIO z0PmTaLVv$x0qJ(tJ_L^Cf=k>-njhl~*A}wawYH>``n4@ZT6S**k%04%T)Xn4Q8$FK ztSkSSEZlkBe_*3_qCW5QTvyf$Qm41yRYltm=N*-GVfN~%7PDnIlT5%2U_0Ep7ytuj zyYg6Jch=&M1Zl-_lssx9HmFTli-kU;bYo4Ryg4&0K@V`42a=?(b`5^7uC9y^!-?O% z{oc+%ff5CS-ngJhW?%hn2x{d{*2Gs>&k}Lk+XX$3tE6bFWKyg+Rw_;=W4X)M$>bkW zpDx|FKfCqxw`a-CJJXY~MzX#5+3jT~)+KNCwI9}%fvMXI{8gT|sbO%t5o^mC-3Zyy z5~q0x3ziA%;e+7>4i};yJiPt#v|_NjDRVP>y&D7SyXt`)tGRY;um_Ae3mf$6+2!er zzf3j-(yNt=GBLp8>P;v4cS03%`&*S&vtQH8dO ziSlZKW^M7ACcDqnAjJ5#zLn|MD}DBQ4V(MKSY|5qzQpFb99TG{Bm?)G^~@aB;2H}$ zh}CmUcU1z+wk(o{tEBzj$!>Uv&`MZX22&Y1ITI z4fKG-MYSdXto9Mk4Hq$#^(A`?LM!SGR_df(?ws7rTb`RGdfT`6aQ3Eza_^Raus3J? zuE1_Al>1zv7rAdJZnq%);Ik&+OL1OM>*Xh(R6|ta%F4Am`z;XZDU1n^JWdR&#viKR zHG++txJH9$h+fx6p$S^^x}hqs>x0uycThAi+m%tM8+fnqspol49JS+_5l&`(sw*h& z2xO$;!lvzbF7|SRfUkJP)my2y1|c|%L{xhxGWTi%8)>|004HEd2x1LLLBNivD_D$D z9Pc<|g>!<6Jpn8eRX`Q=^k+nM{ojs(XjiPW6QpL|V&?&gdvOP8jenz#e+gWrNjq|L z0C=pyXsdV9byjPD3H>#ogb?=(ha+7X4_ff$4s11?%pf>AiFgz@fDX454%d7hJs-h_ zIhlRpcn^H;+FRpXP|ILim!;V;e*(L-5%9KbxCw}sv#LrXCw@vTYJ$zYYFvQVve%2F z2A2yGptFYs8K?8*DO_6$^^kaqD=TaNG0=WTS+E@_3k<7*tqe3mn&Hgl!n;Bi4;Ki? zxA9m7Y$;6(yjoarJC|%>RkUyAT`njhq*~CfvhO?PF=-WK-YRGt%JVXf#8&;V$m1|c zR?aCf6BDyat*_LOsGi#LhuUgU|e+nu1m8 zQM=L5@d7I*8+&w{S-CF{>!NT->pJZO+}#x1zg?{!0jY4?s`!3^a%GA9EQomyN;%6P z0C}HwJG+8E?f+6+xdStDsI(X9Rf1J1>HA3`SfdnTvOKfW;BRAV7=W)FfCs*;D~I8~ z*$<%b`>QMa>FWJ^`_>My0<^GyCDY+F__dg~z8zE;l{9L0QUv{;-j zCBOXU?BAC!+pm7O7mGdp{Ix;se&Vk;K7OMWBjejLSCPBbfc7>B+)~*QOTrD6Cm9BZ ziE~N)g~^bD*-&QY>C(f&5ct}G750EH_BU2NUSl=buKa6bW231p-&`?yJp*Q6cq7+5 zJF7I8_m9K+(&ojK`r;-grqmRN)oNlaCGWGs_m##^!Rq+Lo-%^RymD@Oe0nPT$*c7+ z_4P8s#ya|Pu{b%?I2g);ZY!d4T|L0WKZh#nypA1p< z)c^Q8pBK08D~cx&+=b`0s>#AL8D>VpGqh4AEF#tQz-TBz0W*mQ3#S_5TqcDX>iR`33Gjml4}bM3cB(<(-R8>HRaX*5f3|xU zlT~XuoTDKRe7eon*V)?JZ{4UbY3q##91a4)`%FjVB5Ki=sfRpzYvt>vEG$zNc^3?w z0M{2ozB)oUHiHEdg$ZfLoQ9dZ6%6=?t8SeDH(XGwl%!e}g_ICkt{hXhs%F(yKGUp% z;VQo&ZAvZgA6$~mF26>*)8 zYh$A#&{rqGVH%v0_NHrCxG7g{H<*$1Dvig&3+PoU;?~M!wX-CF@LkA;YpTLlf_cQ+2=D|h!BGH} z|3<7K#-o7UF&I4a1Vs_2<~T0IRed5(#Vyr}(o1uPL99jm;K&8I%IQ5(k2sW!WRx)(~RY(b!xRmJQ|7vF9M-@9NcmEu&?clHioO-o_)vdv%nx7*-cGZ z`|Zw!G1X^wDGB)6zAPOp!nSi(Q^!#0jQa@W1KV&YCFRaR#~s_B+P3(BkYL?@=8tql za?H~(e&h9SzMyZalZ9#J-u7E|Wz9oYas561I)AT5~{e_o#ap2AsctdiMBPRRE3+#b+QG%>C}M8vt

tdWvfGF2M=mIiIU(_sUBP($FblxMRH95DZ7W8156|De zWWe|Sod^vEzjuD#hyUIl-cB#{bvW={0^k4NwsDnVHXHI^;s&OrBSMs>4EWPXNojW-_i3!1X(4%kO{G##jf5PuapS&^o>O-daGJqHV z5_5j#hp}%ytP?^-BM%kT{*s2+`9Yu_P#eF)45=UyBl}|KSh#``&j=Qc zjE5#&3>lzcUvV{0So|j6qMigi6<}+&Ogj+7QJm}N?^XEw;NJLeH#Vyl+Hz7 z1oYw^vUyd)3B$`S*3wKU5Eoj?`GeD9Zc6zW_#DqTZ<>P9W_ibYEO$}$?bP6WH6XI2 z?WPFc8MuYnxTu^;<;tA|>Ut!&43v#kktfz%Cl-W@$*LYJOiNHj{ITM%KsOQp@EFIg znjCpt)prwnT_~_r0BuJiW+DFi!Kt{LGI8vj1uSzw5l6FBh)>OCBOp4q%W-uhg=Ab3 z9tXxH;}+q)aY!NX$Iel~!?Q++C$E9Xu{j;T(P=b-#%?ip(CIAkPx%H&49jicnrZ-@ zO(H1iK@w(rTTLd2J3CF`xdGYbjrP9kG~#g_4GV6&p|3RMla=WEmEBf5wS7q zMLZ7tnn%puXEU+w$#P|Ya*e}EueS+dEDkysXy|)cNRLNgS)wbt9ZQjR!%nPD!oU(<@i^U#;l!{qwCW zOe6<=uU!2ssP7d9wQgLyDlKMkYj9m?FT|Jeai7Q5BgV)*dgtoLuh5ZkK_9N8MDzcO z%n;n&-J7wzI9fZ-IY_nuA0`UNTTX3Y->WMR{|^KHQSs!D7^WB$h@;o4tYODY#3e4M#;I1OAGcJITm8jBop5P6<-u@H!*EM^Iq<4wm$B0m47gw# zaJ_GDQi~Bsv4iP`EyoJk0VNQh+LrYE#V0EOe(;+we+r8R51F+T_ts|-0qiYvdSYGt zR7D>Q2XJEII}nX&xiUkG+V3)_1rG=JTMji`P*z^l6VI#6O7_NjW6)A%re~`^+@xkr zWf~6Nk`d2+e1fR^{RJBK2T%WSLK0+I)mh7z;9(W1WP9tSwHOrCkc1ArGpi=%Och&a znOZ!nelQzX((yDYQ#P(X{FP88L zLSQdSY#~#`vEyb&oP;{E*j-4Ex#~2)n{B^L z3&O#G8N>p-_BvbfySG;{VyQ2KTN-<3!HnC&tybx+%S_ugL0O&VSIK^Jz8iIY16dSNad?sZJpyoa}kjzW?E!MDoFtBM5wM^TtCNYOouPUP* zC2Gbds>!x9BD15m+^Gy+y@rr@BI3eq?Md$B)WtpR#)e?q02V;$zl{uY-#fEk3b^fM z0h-39SYI?H*3G>$Z{DUU*9#}Hr4CfBseDb0FL`M!@*sijtsy^NB>lB99jj6I@ z=%`YP4N~qBiSZu*30)GePT{o0+70r=VTBUGXmyWkzuba}L z7=Ebr+R|^b^DgZ980=O!-p;_wLx(!7WqRbc5gTjU$D~kJAKSic3RaJnRm;EElL8+e zI((r^18`2b@%r5`{r^4>0KpZ(T2nk z=fAlB!7ulpSHqKH&sWT0-wA4q)V#5gI&;7=5KDINhKc;wu06W?IRkB&PP0QqFth5e z{N$A}l$l3~0oo*J$#9yic8|Nqwg96!)A@VoyoT6+b2pQ*j$iFO{IA?Me|}JWb)!BH zc+#`nM@F7659X&srvu6k2c|`#8=o3Hxnz3LqJF@1Trwta1m9iSf`m;NFK{6F9G%wu z$t6REN!qZ8ydeFVjOSLi9iP_iJ0j2{(0kx)LK3J1=ToI?yinA4Tbtj!e~G^j?v=0R zIFW;h&yA(lB-YA~V>Vh0F&vyaN5V!UXCM)772rw1_;iU{42`Am>r&&Cx_9*yLltNf zx8iBOUdrBWN**p3eRHql{jXaZs$tf{_~f#lnU|92MgQkdKW^7D^GK#iN!4Cb_m#6M zzNt(uDo#p!X9h&50o!q!T5&p!%jviloXOT239)6`afVn-vlpgnbD=(IydpeRaXAjd z`!t2Y3Cd$TbBgo`LuzelReMF#hQ1bnjK@eRDbj*%l1qp*_FibmC60l-s>Q#pkZK}}P1Lugs3ED^Y%FL`p|SW?Vma}#_ZFuWLf zi<5t`bw00c@ky?Z{OnP*$a- zFfoQ^V+hGYUDTNAA{Z}bx(N)Xg>Kp`vhg$TvutQ(v&P8^9x3u`J;U~9}tUzmRq zFOLE6>#7@t#1Ujv_&S9Ii(*RErG_XHvTA**|DeIuI9W1T#$4bgRx^ zmGz`IszcqZlY}hTw0GVTWmbE6>K!MFYRisPPKrcazM*N}aJ}9KJ zblu4^v|XN@@w8mI<#yQ=4z!P$+V3YuRbDSw@3E=yPdJr%WncRs{eQ5HQRP-tj;Hq` z?U9=Cw@?30iMhWb>tjv+GJC`vtdAdgBiI|Tp4hO3@fF7#>!bFSlb-(o03ZNKL_t(d z3Hn_*G?*Ls?+yN{0Zb`cZQyS3;*j?Rc3Z>{cNsqxE4LN(UxmJN08E!mxpP+73LvZs zmePo|R{FuvirFJ|jHz8Wh#)58m;8lBaPNXOH^g-@gSO}2cSuH=)gZ0Gy*l8fl@mx%PGwW3(= z^4jwDhU&~73Z7v-qWPnLiB+)c3d1hL)V`Aq1-eVB1qMk0Iob98+U zxQiJy&R8KA_~qK8uf;Ijfbi|?@{gN6L)}?tj^AW}kP?++vUm+_OXTv(vQcPPn&3BC zLQJguTU;>aiVt#|jgmUJD#X5!UQ1rhlY}sY8i|H>nYN+1Ypn?!A{~J#qMBe#ZP^_I zaf~1*cJoEDX=wbHKm6(jfPa7cS&(ffl%g4Vatldg?n2I)D&6kyj5mie611C`C|OYB zNGc@H*M0TVyZGkg~2M|%0|Ipc`qzok-i-$@im8}keXNO>)Ol6>z(rgBR4K+4IyH`9S#ctaD`x?sb9;0 zS8xT08jPly;p5nusi4wcYN3Tf;F*r0tiJH2F9BRl{g5--g0B(=Z7&96RyWA0aF&x` zdcbK$DS7DE9XMp$*EEo1PO$shuR>rPFg@UU%7YudFF>aQa%WIx5Z(@@AJNw>7e#9$ zE!JC%RD>?d z@I!cPupF1glBxQFw(1dU?8%NqV$Y!jjr|AN503BTMpWwV+a*m_#R)c@V^vSC5LA>l1$qTA1nXW~xX^zL$<(5HJ%`v(KgO5UeNbX*3nA>qt4+w)O! z_BwGKTEdzvl8Biya>YB($26^`y-Y7^`tTEH`4B;{*TkU?y5oi7ol;3fI;k<#dG^x_*3k!yHk~mruudY;YaJe z+0zfzAw_u(O0XgAyH;(mJ+y{jB_y^?K;<^kp5k0() zXO=Mf)jld|y1YKfjHQ*t%PV=kyaCAbKy-S8-A3PFX&ZVW5r8YBk9DAr6pzFEN`#<;<-;C*}r>a zG8p}p(~cag>P0%Ij*8F!ZWi`*z7oyCvG7r5*KW+v=MdDz}BsowmfmJBbR^GO9{yiZPN{ zc|z&gz_sH+O0zRu}>Udy^WvCNXDMM@w1!-(Nm>2Y?@}olRyrah~xqGE{0ku(Sfz#GxapYZH zRmtZw{k%sk0||&q4#xdT&oG})lG(%{nPFlh;AhW%5aY+7?kElpf;n(lh^39e?T>u5^6g1VzdaUP%2d+T3u81E#ZscZIF{T-%Ea$3;rYy1ch~A;-GWVIjYjj-=G5v(&*g2U>q4{asyLJAh&4 zj980L{rS^08|S<{UzR^nY5=VC(QK9jVxQwHzZUyCyL41s- z>rDgJG8i05U@dHQJ=QfZWziuySkuRl>1U&=)&j7;tU}Cn_BnnaDqPpA*I=fwy8`!h zQCA)1H!3KJrj$1kU)RG3m8PYHqfIrA#gohMX?w6LZec|QH9DCMt>Zd%fU4uW9-=D2 zn0mkE>k1>(URYKo8cuG{!}zl9OtU@KzM~R*`9RB3tK2nj>{09&DCwNH;=g;kASlQM zPncA=)~bv6m`e0YA7d-g9=ZjX4(Mz!E{fb`re5juPul z9s%s(e~6763^;i(6P6%dH>T{u#$9j?p+4yw62IbXf#iDl*up!*`-gZC^c?c+yZUDfW4F_(x^X$UQCA7`*^_9!MQC(%-h!StF zeXi)arDJ8g+RKeKW5wde$7|aji@x#0FLrI^-u+cc*-bX|(Ur-DfpBA8OBU4|TFP=*;3h4Rbq7Zdd@6P}?Ggsuy^gfPK5$e@CUa!Q zCGY++6x8XdYrBaS>ux@S6h1z_bf=F+&9jr{Mn~=9y;|>uhNi@VVep%^qeNBj&55CN z(rzoXnEYa8T+|c2opiV3rTxhRrnlNmD zaUOUJR`uipWLS0Ptl$HwoFd4!zw5dPcspjM=8zdxu#*}yZC7zmKobHu4lwH_T!hC3 z$e(B&V&K(bjv-?((lNxIZ2;pmA~`JN@Cv!5{F;KIqN(Do6rAmtbIhUiP|jHkp+;NC z-Y!9J4EQxbUIhjMc!p=Ga9<|~!Um4F@3B+JD$Uve!QljlbKeYnISBBYrU6P*O33eE z>oCnr)oEDhAO*q?e19NFW_P013_`itHz<6hzK}weQ|5FS)|ZBh6+SYIqn}HOxvnhm zb0fTE1*xeuOg^}P(#{Z6D$PZeX@-@`48ri@u^~v&m^9D;Yc(992z?%NaTTcz(iN{j zfjXjMEhLW}T!mV8cgCIS_<^YZDdO6!xUdT^5Kt%f8n;_z>U)j$#Ok(cTBjP70Xvyj ziys=R#yEtou5dM?;cOI=xu1NF8N%J1ig3D^i@9X=e^DlDiYlga3z|*?9d616tV)}< zd0k=o7&nZ=K#8@b#(LeDm1KuDFd?VK}^jING0%xs$!(AsOy#jt4e6!_4z|uq0G*%-Rf!6+dF3@5M z*qyMXg3e8_f(q+x5BT&d8SQ$kQLDAbKvK(telh2`b9Ddh9PoY%vyPWfuKx3{v)}9l zW6IW@%g;$^HJn}5XQA(gn!X##Ro|BI>XYLQ1=cNXYzTHY{?FF=ytb8JQM`*b(AuJ| z$-zV41#gYWrhiZG`P}c59VVV+q95P)eNPJHymRik=RR0@AWYVx(r?eh5JItF@}2QO z@Am4vX0L7zAj9>ZqqD(sU36Jdl#;9Kqx#$RXP>VBlErauSR9 ztV_&A*GPA)j$+$orpQW-M7UC4kMwRWo^;2Wdr&UFEj;-MfdBmCbEYF`6e8WX!trX1 z{)|6*Oh@xnO-QOw@96ie6*4tryi|(3QfPB**Jh|{A2U8~b*Hh~hQ(qPjAeHQVz^ym zNc`4g2Voj*TjIPX9+!pOWvbjett+hE-SV%$`Dt@4gfJcE>B2Ozr~{PbV-#08qcWO) zP?FV4yp)l8o z9naGw2);RFQI7>VZI4R_P6x~+$&pt3@gPkc+>#vMl4ObKUeX0R4fxZ9tpuOG#ZbWQ zZzh?8y?gOYz|o zUna?q3<8TU4IlNdIDuCyMVX;1l!a?6(w`f1TQjfJilV_ahM9^Ti_vOPMb7DlfVt@s zbPfBKo22!sC@_l~fV`|$dSswvj9WZUERJNYZNax~F6p+h?c#5fzNYArT@~IW)NQz~ zT4n*unrq%h8jBIEnu~zi%De3{w5(Hr<4FKkBcP3W)2U^ndEE>xJ)-XO$YVvC!D(Fc znyiSl_AuBi2Eg9lZp>|$oY51a-SpH9Bi}WQXph)ftFNUEknY*MzHY$jsZuxXtJlqf zMkyP?E!NNhw&%JQCPCWK6_@2}4FPV$o5t);rGnZpw{Q2fX@74gXI}-uS2iqHd>vZ% ze1rm?VpJtQU!h0d#S)#W1 zzQ=KJa{+Uv9k}N`Pd(&pDbdC+zrUZCeM1!Gk`90Q{l(+9+pZ)y%lm9BS6-}outXm$ zhcWmpq;}kX{CMK|(Ri>X7Y3xy*WZ*@){O{1-+!*W-sccvpN3Pqr-$pBqgr}b(j$h} z$(L1H|IK+A1iafD8Rk;qmHkRyXWEW-cUL_CTKz{DvqlUfR0#BFRNvh=sGpaf0l80Z z;rGcc4jTYJRPdv0Q4?V5%Etj4mP{CVzW$SUXx z(|o?)&a_*e#Zy&>!zd+{eHjVdolQyFQW_S~90u8~W5rD|a93~~x0ooTvMj~mhiCWy z`0>w||55JbxOMC`S$d%iu(?6dM-a)K(9G0TukqCG2{g2Kq9iMW%c@egC_$^Z8&AF0 zim;AW2WfoVnm#uAO#}3-E2CL=D*aj6BcjW3bu91JRATx=BkMwHS;puD*2jGP_n*|1 zMxm@>F;XQ5i)wzWWTlY8BxD>OqWmJC4&79|W`~h=NI4c?t-Fkcnul2+m}E6&xytILC3rHY3u045U_YXX}$3l#`FCt*<=daX%FfLuA!Kl;o?W z`huWok}MHZ4-D`5NeggR9nnt%6}8oAB8b(tg&c(Q!fAG@68i zi14AYO4bH<+ygd;WrFUKcq3A|Jgu6%OgN~zcZ9-j5^H*IG6y}9^ewA*6r4^?xOf!c z)Q@o6w&JF?X^EaUa6sXomMYL7SY#WC9RXPvqT=vew-wj0_6EH}iWAdmh3MOOzHw?J z8btXzzmD(0d*lZI9dC7lGn_0($>;^D6v7M{rP~)rO=e?z-Cav%t0k;G!6F zdK}O_A6UHEx=p>j*%gQ0yctjayZB&$-W%KV!Pa8Yd%yMK{a_?QJ%HzmSbN47(N;Y# zb+3{?sp@af{aJfBvFNu_BhRW2FWdrwB}dbfq(0y~2IwXH{^7~fi?iuQd-pL7yKbvQG3ks@f1o&ijiQ4g@4wqO zpx!SrXMKG?OmzLr`3SX{X-M@0yIVLI?a69|!Ys74&$_#}>w^eK%p~l&60HypnV?7K zKa`;Fwjm8KemR{ScRg&9YN*s-^%e<;TU~YM3eS#ZD#FV&>k>FAnRYDvJjS*K0vpX0 z?siChREnkeqPmM@VxmmUGHR;gzvYgxRBT!zz*oxbpcY&ncUu~$O8^!vwdL~b6(_*< zH%9axN+0$pWbiP-<%&lN?q9ARZ6>ibc zP{^O9mr3DPe@&dP3b%q_90Y4eLkGCNUN9i*8z3j3s+enjv5u3O;o8tKZV2EeewZHG zgXEtM-Cj@@iM`b2z?D;bpNq2Bc%iR@Qb)`_`lN4Lvc~TZxWqKL zwRDDn#>+d2%dmaQI{PsOtRdkQpAKGG2~H{?S)|Lb)==~w+_+Liuf~6MdJ0w5uOb4r z@vm)QHma>OBw+)SVR#{h+qq()qsHlp=yek$F9N@EPTAX)=Bc>xDfl->j@AzIns-GR z(wu`O?V;1ar zLlX`sb^S&TtqgyPaCSG*fTbT-95My{QL_kc3al#uOs{JO@(o>WQMV3r;I`@BGe~>w zMEkH_*sX7Pn+eUtl97nQF|hv{Hn^zr27{c}=%eUmMbuYvg?;P4IP0jHXfvOZfa2`) z7u1nU66GqLJw!r>vaLr}kSAy(zS*?1d@xdcvv;%c*?8Pq z9E=vD-irY@6mGqOO84A@wdGlp9y7f+vj4U~WLd&wh-PphX_O-wxP;NpfN$mJJ9Xfv z-<`#6ZvYNmMQuk`YQTcqgM-c7gw<}3HzQ*Mk^?g^;I=yWm{LQ&ot$4PCM$o)l5E> zei;ya>qVCMDwK=6cBGn>$Yzv=twvjcac73_nWSZUjE+4`vg}jt$#1Tb^0C95U1R98 z@16$p)nEI$8TxnsmbH4!P~ma4r4hfXIV(oeP03{xa(zBV4^EjTSZ*uzCU;8|to z7Ne2ux#6v`Z<4E~zW|Gqe#RLL zwo@G^q%;B=;1Oi(+mkc}x>MM(&XW3jDa1QT!xxtRpRDtFapOM2xDV<2APF2dl+~;} zvZm1%TN%ZoBX8}pqv|kNnn4a|*=}$x#4b_Nr0F4q8bNh2n8ctS8bmL_*@NASp_mqW zX7b;Lm(mwjuf*!v#8wEkNdg_d(&?Prd-*s+}qea$)*K zF0`uN%=8-<%YDX*`>m=*B(Pq$Z`u-+x>K3b@BDuNrdNvotLgG=I_)pZ{pG4Zr2&gw zDQ(rV;Lb>NRc)*o8deCL!n^2(^p^YO3q3zf0Z)y-%T=efT2)u&)ynX@T=vfS`~3bn zKJK5lx2Mba*0kF19MILw79S>X?UV6Ol*Igry!_ju`f!5dHR_=lx7Bj}F+bSU+2F!~Yu8zpO+u626?FYqgGSB@P3=6yFGOEg4jlr4zzZzsR#8-yXuJ&y^|A@`(vnV zHk z1J%s9?ho|WGRa#~co}UMU2HaIXNu@Dg0i$Y4~IWUfw}^j3m->mdLgbmRAyD6e6fk} z9+lDyInGVgSh7{wR%J&s7Qaf&4c*#eTFM-%AeU>w4BWP#$&r(#-AvrdphhzZ%TmtY zlq(6ArDVteG5?+t)8K3>y`50IVyRRbIMWO5lDsB)yI_8aGFnSM)x86P*j;g-_{82> zuFeV0MAx1Sv9>+U_}Vh;p1K@yraO&POvg24CFyk%+y0Q~`cu7JTv3{*m@fr^5!l4< z4FBLg-zylK(61H^vPfG`>X`I|T%KWT6C{SLrGU02NNy2^f?LgPA6o)PqR4XG)k}x?Ylnx;PArPb`OIwSm}kBf?Z7^LZdPd zlGjr|6xIgi& zpnIp&Y0oEz-txT`~CGq9a;^y^Zbp<6Ql2 z8gab3hE9#+6Lx*V)LTRA{9Ph+AN8;rSY(u%Fjd@WbE>Wp646}fS6H%4A?|a?eFK)I zw#M;7;>Ku=(MHdT2IXgru2wogt(Nn7g|HCE4L33v^hH08T5rNJfQHO}{9gQh|Lgnl z-`~2dCtv=n!3wDpe4}KDzNoQ+=yo#7*dBVYv+02V03ZNKL_t(>v?r!eCogMEMz?jF z(dN}4**oTZhLhfe<;=Cw+&CI@&{2(}9xy*~Ug?dE*gZQ3Tw#^o$(VlWcw`H)kqO5+ zApkw5m%D*7q#t|g27v~LY^<0UzNSZOd{Q6{hihX_o*1?7XLLaw4L9Z>HkClgR~}^6 zyX0~lo z9Wt3n6=(!QU@FP;sRXlQVM0hF1Di9Jrx4u|{t3Hsvw_r(OPH_))`;P*l(Z2uA?C1(2@^`HwB#MB#E1+xA%!%B8D`QYDS; zal$PwxSmK?V`;sJQZAkC=L>SXTS_ir{I?g*FrNj&*P|3gdeQUXkh0(KVFkurN?>5c zo-Qa@G11fujHw71d%oORGGO^w%Wn!B2wX>jtV0B_JXo+i8}b&E#Sx|SU*Px(A%qED z?xYr65etABmQ}WsZMm2fwIwkZQ7-OCo?+y5@ygz4qEi@pO|2OTsx(8fkXBN-xk~}* z!|F|McSN}yKwY8$3xg+`J|os1E0i~>Tia>DY&g$RY|3Z=&!3Wx&Umh(aPDUe%CHrw_KqlfzkrmGKD(}UHjb1+?X zOi>r1fL9$my$Rv-^N;NNiyQ6b@;(53dt1Gxnd2_A2S?QvHnUk)tEHBk2sLXKaG6nO zqPf#zTdne~(|6XAcWr`}BL3|36uqDC)JNN+dfgQkNeep$*VhVI!;kJ<`})D%pZqNS z>Hap&(sxF$cA#sGzZ~?+1n*xrb74*RKEkM+>w7y8#5)|%4pehS?B09N5jU6b$~fC0 zb*Xk4lLniM%=xP66$_BiuhKrY>vbiAzd!oJ4=q?Zj+Fy`c#2u|bCYd~u_ByINz8V~ zoKNH$Ues73jG~=(MRN-01ZF&*tIUU^>Gvlwkyl}VM`nOo(=%aMc`{)u$T8_>g439Z znD&XCZ30dC5^O|Q%o>B#FWVFJp@O6OSBg9T{Fk3rdW~;?BtzDv?`~k)QiDcodxdj# z(cEvGoFJXe;51645EgFq;*&!*4|ow|u0ukA-eadx9kg~r6WcU?%7EO=OQm@FyJnP*mC3>{IGug%kyB^Mqh z7f2{lr0evoi?uSM3&dmsbk-F+Gs#23GNG)+R{|nt#BL%2=3M4V-AqWrZVCNSi4vrl z1ZG!!1Jx)}LAT^Z#)A=e&elYvz)YkqheetDv+;s`lsuc4CKmgh20&1 zlO%hZC0!og#nCQW{i2(s!YJRSOu)~0Q-HI7DIu(z3tfgw6+>1#2=mN1N$T|eCBNV? zsEnV+iNe*$7m%BDZr1xz@|)<$75KXVJxyPvB1@L&qz=^$M1W@< zmaDCT>&gptJ3w`f66%0&>MjOW_@q8?%!>)3{uj8%;N>CbE{R>>>bRx_!vsLIg8K|v zN3hA^#>C!459wZZ?B+x4w_6Ac_QZed$u*Qz$BBEY`TYi#1Wlo*@ckUAq#|#ONRm z)9tX51~m{NOwtNbEh=;=duWzour7hn8nlNbq8EqwVCPV6mbACfZeej;VtcW7V!Ct- zjYD9`rGG`A@AvtQlcj!(^)jyke}3QR<@-zu0mIWfQ|+L!BN}q2SZW75Q>C4$WTzw$ zPFhIZ7TXv-h_ve*2QDC?Jf|sOQvh8uc9J=rR1D9L>gl+{Tp&VMwE9so7bL5d;3$W< z_UiF*j#HP8@hKla6!<~~AKmU4Z%W#0sMJQ8wE9Lr<+%QVEOg_{PMdSLBQrCxkCfP zrEL`fZ204L(bt2~2#C?LqL~Jic||g$q}$KeU=p=}WUCGZM7OXST*zD8Dn%>vx){jo zLJ14TTl*%qOk>Tb$V7HGF zZ+|lIyLq$YuB;peeVB>ps6$+dTvVslS?Jb#Tle0wuB^Q34rSA7R=pa2@v2qS)GC=G zo%mbj#H?w$(tK3_Ot{7?sT9>xV-0|&ur-n5rbck%w5(Xmiegh|tb9#nZmilbg{%>Z z@^ghR#R^?Mlj_STYNo+r;4Y$2j0}?%VX?j&Pz`wm9E8XbhRPQRM7Aj?ohH_N$XJH%4ufQv&M3*`C-xaTb)jLjhOP&UqtDFKI2dyWon zVicJnUfnf?G-SDISH`y&VeK^rvCF3+@eIdDP>rio7pQFmn!u-{xmU*0sj-LWsXoi* z2y8oMyxZe-mDjLe@EPH98}Wig7K&rnas^{OQy7Wai%NW~3C1>xxF~!bZQznqHLYMQ zCAS%l;E4=P<2C5YjDX$>NA9?+k;bedn!eIj2@2I_n6>qOTP@lVMWLJTY31(-1TQ+($=k`9$Qo z)o29FEZ2{xju4v$d@tjNyneYQFZ?#I2QNk;;+LzwMObm9o;y`eox zY-)mBZ#{hTv3HMb_P=dw_2wF);RUYZ;#|H=f3mM zM5((sp=O!a<@DE?X)_%bx!~WK8Fcc7>HE`X?@#N5ItXOw<7@N3-6*z978vPW)LsQN zrED3#7DUSzk@}@WR-sU6x6(lk>5PWYuD?{z{Ug+28?Fc)N1v*COt2ZfmFTQ)bijE?`cIoX8K;Vn_dbHC3 zc$vsXP}O$<+IWQ5U*jEd+w;?A(z@-d#Fj#sxnek+qg6WH5MMXZKhm4n}6 ztC7n5Qx3VD_RxUdv8noLu25Pktz%QmWEyU$!&HUFTJ>Y{t0oegMwMfn3^J}NeeEB@eI@-GrnauIC;+4a@K6+tiy&RC}fMOm=L83_SD;w^;t}CQi1ZoicSQ>Z8pq0 zYoM&-83Hfy-DTaLRZ8maRkk%;j*V?oH!KoTRuSB<>Si`vtwHz>SXSM0UYLMiB6 zSvk;E1Vb3d9t+WA%XfH&Hj1>knFhukW5Ze2+%97F9xl*ZV{sLVx)&GETaK;}hT7J} zP_>N^fMd)^Jala#m;j6uzm_*%Lev3QYGGZo#$V)r$gMzMgAm9)- zlqDKoq4kLRl;P$n7=xGRx~Xl%hOj8SiVXUa{%l-r?FEV-(NOk*ioxB zujA{Mzkge2E5PF!70$#itT=)|NGz0Xl>!E&i?pLOLxAO>LK$O`T3gfaz2<+FvNuf# zzj1Z*LY_kaUDh+#`|hZVwj*G&CYljR*@4zn`EHL^RrzxW(#muFx{e&o>&&9Ody50@ zX|Bwc9=L0bCJSu;@!_d~c}Ok>1#-S1L}tx+d!VjsVNmO#|F_>~$eU)%D6pz7Y|Wqt z>5ca{I2)-ixck}79}9thwXy+zvH}ZLQ6ryZuhN~_ryzFSD$Zpz;2>X2S9B4ab}^I? z#Dp7`4=GG%Yq#E2Q|CN^M6wv_Xb#RGvD@(ghj2G=+l94KTw znkNsGBIS)HUoJyTS?cOQ``m zN3*hJ#jGH9$Y&kZ%_QX*k8IAJ;PeSS2gbjhB}FtU(;Vj=udKip=?dN>Z@uVcwEo*M zDQeVZmm${)W%`rwFqEd~F0#Gzo*5yYEYA8!>{)~5%xabe|-1x!NH?DcXoHb*?sij&VvUJc6T4`9vmF( z?TIS>=ZnAHzC5{b+?kAyC&x+WxXrTU2Jx?zSn7(!UlB2er49K|%FUk{ zlrJ8%2UV08S1T$QW_vBuyR~kO9jsav)H&5mucI)TcB}#8%>{M2Omj*@jbn$qAb7T0 zp@R$~k8w%R;79?Z-v`6dXsO9IA$GrDkEY%2wt<6~)TIP4NATMAaQD;i_|%?L57W%d zB$VsAO(0=epJoZs0Agn7yh#)D(6H`YM+()ttp$M@NG&*lop_^ajU8GV&JaYACG7oj zNJY%-Czgl9h}*^zoRX_dlhWS=r74J!Swo}J&|yO&S0Yd(R1{i)Ss9jW!y(hWk#G$~ z=zb^dbTH7WPUe!-;CDpOM-9;!XUK(!Y8S8Ja)d-uH{y;6<489K@ni|R)iTn}QN0&Y zs75>z@d!CA_8LM(&?p|_dQDhIVlVYNcZLO>Q_t~NO6%qLcPvbW4Y+~L#5azsG z-k2~mZY%fr-bV2`@)lFVO#~zDn|J`Nm)xP6HH8(-C5ioc_m+_IB`b@@Y*O1c!I%XG zkA2TDz*^!Yr^4b4#bOX7@=^!;pe|M~=ak4qewn5s*0AOh_5eW`*w|xgIhO>0^Adg9 zB%6ml`6Q`YU^0RWbQyb4kBo3Qc!wJR);(p)uFnWW>VCPH;dV=<!r*{ZK*EUa*fG%=;8h+WEyq5_+4#Xa8qr@u*tPV@;IolXFK?u*=`{Td1dsWSy zod+wWsX{50A}w%1jg%QHUSGJd+1z;Azy9#q^YQp(^!%^K_W#)UYmZ|?@V%F#(UF07 zbae7ybOHq1_vp_rM+W8b__?WK#HYV`XYcK=^RBZrS;(7!Cw8=T^r{LGdS-c4DW(2Y zuwhp&OiP{m7&3p_49_+;QnyYQPE#S4`=|pp0H0krd(mPX+Tiwb zGh<;GL&^ED=>95&i*RI>G!8fWOaEE{BMXhyo4cP-(85$Dz|Lwk>09G>&lfo$~U6Z;H#(C&pjtl13JcbfJo@EHyF6_hq0uu9@~7n2bdMQMJ-qt6{D^%vdb}tcoFp*$SsL zAfq}cRMpc1&61HYO>4+71JZbzEjvtta@^p+u-mCJ6N{#oFju2LB$_b~IvtEJd`fS>2Aet5wdR|{NnNlmw&LQMv;)B-2&znb=A=d^}sNL0rJLI(vfN1LKnOR zH`Co}hxu$y8Km*MQ0rjyQ=#(+g-sQfD?{YNP|f5qi-b{|+(v-BGH9dESD{nkNJG>@ zSKVAjDC)b{-k6)2RO=vyshny3HeI{OPJ+n45?kxSDMPopj(|Uni}SLMFP6*e`m57_Z)x8RYzA{g1yGGvaPYeI}IL%`C|s3 zdENwR&vBXLj_i0lb)Nb#*8U>hDrlj{y}46}0dZWn8x~4PJ#@JN*IeNzUqZs%!XEQIGfmsXJUY6IZh#LrK*Zn&Xvx(E| zUoE-hEv#%sUR@?A&cVDE+_1YEyqBQ4j~Xqs{q(i2?`pDH@#XVgCGe1g_j5Ot1kNO7 z9|PW{h;brz&2#viUb}gf1xNHjDI?3q%5LCLievk@f@xqB?p~NTD)p~_WBeVDMq|^x z&z@8MJ|7>C@7)`peD)c@`{2Ro=>7;Y_=FHXB8=_9P&|HVD1P?Of3YPq%bC;#L@l@2 zs%l-+7+4zxEs7C?sY?2mYq@o+zi7N&Y^ItEO)B8^r~T7g{nJ$n;{I~W6!446ix*ue z;1bG^&cs&ww--uuei?(C9E6l=a!_GO-J%%)*W^RMn(1PLbTeF7CV*WE*r{I^hyKyw zp_97ofJN+Xq6hS9E6=eEuehM|YJIi$t?2tJ+dtV;zmC;>YZvb4^Rp^4qTy;=^yMJf zOHKsOlE4T*Z;8*B7=-=+5J2z0BYQzJ0No5jwBpbd25R0W`eKEPl)ufqrZaFZu!7dh z8}s(e>hc%c9~*lwU;h8iu--g>xR!$af~F<9OtZVMh?7^TpTvG#~$EGUKBrY=N{ zlKjHi^ja%T;f%q)m?XsELAnCO%GPO0# zl3=bFV!Vw+G;SJDrtu=R0!y4L6&JTgd>#Xm z5WTj06BIPJi2J>3Z`_$y#IiI+6)$qZ&N%EL8Xd`91VB2C97{1Zobi{su`#RzbuQ*v zr#hv4osnxwNm|656*z^&11)DH7y)JSj9UqD06GyI)g7PkoM7hGvBe&Cf@g=ZQ^kfb z>Q0bO5?PR&>>=6#Jtw;v;LN71v||{;@cIr974u>u9TIHs z^>9x>jN?6M2^@Um);ZSv`U(l7tZ2^uu6tepT9U3g z$X!4Hkj1Ze0(6Vcz{pHA_zYg>G9H4eIZ&ePGbl|w9F`Vu3gjkLYhz2gxY@G8Lgw1$_Ipq10bSP2DMo?J1lcQXwFs6MNNo|lEsbUCu zA6aRr>4YLVK%^VHK+3g@YYP}c&$xUr5uDS23T$F~Nf3xv&+B55k>;g+?78egxHIa` zej@>+;_URSAhuUV%aI^J6Ks5WJh;^JzV9dY3DD!_`DI4-%XV{9_NlOg8}^xeV((tU z2!4PW?*?Dnz#emRP{{V2SG;)zRYvOzEbrA!T?$}MDJZEK$09w@rV&k-R_DW~PoG@> zw*mO&$zQAMTyFN4e> z=Muu=%yw85-kPP9Vjehz89QVf4#1b=fl-ANaz0^LI(+?=`17?H`0K(7J``uu{2ta&}7* z=}WVi_DULW!v~F-bw7RBMCh4TXpKT5VmC_QD{;KA2wA+r8sR2g&@?k!onZ=# z_oHgC7ZIdtyRfh!v}Hn=I0!Ts4VWU>78)(Sv8cgzd!ahW4m2320U?LlzNk?`ORs`^ z5&D1hJkL3^Qm8JxpEL9B8us@-uaY?i001BWNkl%fGzTBSIvv8QJPOaG*W3 zWV3)VgX77XECSOQg5e}&PYwv{@dP1cjzJQ#3Mq%I8x9y&7T%8m(-3t<%vTXNiC>DD{nIj1>RizhQy%)6GYRQxizsTD1jQ>4GB zWp<>N!n3CiTS!;|*^b(Ty1gCn?}gj=>EBVuQ7gA4Q)M!&%b+oT_60b%HKrPyy+{MY zjHNQh+fvQiqK@qKls^pY#u~M?$Zn2GrKVyq#oJo|Z)=9QR70&jizowdg4P~k);py> zWj$${FdB`EDCP9bx}r-sc^4;7WL*h}*h+Aow3VJLC{`vX2FsK?fy9`c>Kl60$@yQ` zR-k}xB^1m0I#!T^yvpGi`q>nBPd{2Kk4ne-nKWpwN|{ICBt~la3KBUn2_NecQw>4O z?>vTud;B4XjCBRT-eS?ai&&@!nJZ)fx`-^_RkC{YOe=k<+VEC^8-(39s0gPPV%zj~ zF~m$s?IM-zgWcLcg5(G3T{hD~-g!!%dRa!|Q8q$G(+x%nYJ?dy7LGv^gUh_0_S2MQ z!f(Y~G$P(2emza3vY9oMv1ViIEU(4+(A@$!2F+bC)~gHfroPr@E$ZpzBvW2$3T)CO zUC&r6glQES5nY6gzQ$F!PUhpYxa#@xVQ*ub5tL9Zy4ln}>tO*-{Q|sgvKOI|++|uD z0f>w-0RLL%_(fd+yM_vNiypTzJ~Q>$HDwOJ9moCt)g_%q$XcTX&RQrddew%c9%<{& zEO;7LqrxfyeD`wz7~1zC==)@E@8RCw-u;_*ZYqKqf+lhW%DeaZ=)OLp8vdfs>AjqI z&_N+^hutr26mP^#bb%E@Xu&1RTl)j2DuKXHJ6l_Y^3l=!V68eC?DzK@hw^kM>SH=m zzfS}oBM@+{6$ZDC2cJb?(*cY&^-{ldxfFs&{2Msz%zNV>v3Xaz-%QKWh@0 zQRr3SbQP|w>b=Vs|3CZ7dL*dg=UzMbbrYhpwl4@8VwzycR#-t0R)(z4f%8{Q#=&63 zUX2yD+z?D5c&rU5(U}8Pwj8XWrYf|AY*)s^3FE$q(?Sb}XxUg9wNcL`50}tbi(RP3 z<2INjc%#bYY`<{Q1l1lSKY#mApN8;+u|HL$bLnYpOVZTXqU7quv-ogK*ibPG-x8IE`SZOrNsXJ7mFWy!3E-Xr zfqX+k4yUF*d9XZ4O`C$uX{?%)yMWond7_?io(dUI#u`&2Ca=)bBjZbn@!FQb&!N_8 z{bG55o+!mWAkD#_s`%FRsQ8tyCpi`17V0KMHG>79Jx+TjbG)K}vY2fb@v|82FoUt|!b~$3Du7LrE;QFVh5q4h1;AemfcGeX zp@T&N3xA*d{&Vp6CWFtnd7lyJT}uW7y!S00{g1DnJ$tqsMawJ7_Oha$B2?u!CogG* z6oTPFvtwhGwhp7}{QmxBXwj*b?}Pmk9kf$u;Nj80i!M(lj4 z_G&u3$bIceSs?r2f$p4g(puxg^Uwe2qgy{K(Iidl^atk%;B`^K5VnFL&!*av;@HI zrSsptIQJPkR91KpE)}AibEO@8`u?Stm)Nc{)OifpC!pEJC>Y3vLe6sFZU7%-G?I_k z#?6owy|vn4B5D_%urMzX>*Dmqp_V40vzENr#weu{rzf$+R-no9!4N)eRy!kKJV1W9 z)*c2GupNClYNcC0etu3}INjXnWX2_`Gd#INH!oC>d8hKMp;Ei6F5fuT%9l9aA#Ph1 zB+flTv!8zo+m@wcHIiy6SiNSiW#`v`vL;bgOB+Op6D2CeZH^ZbOBtC{Esamn26_&( zOcN7<@(FyDkXYeW}7PHaJXTuywPUrvzl zg?RQveqrW=v8Yy@^PfRx+XvXC5}rN3XgX8qaz9P%mbi||-ZbgT8U)BYsR{hlz7bi6 zo)({9mHJ6KI@O(r5bn(oujNQyO`*w0!Q_$Dpg?xWX ze&2N#FYwFod9Vv_7(xX8H5ZWw(6tCxc+tKShgNi1gOFIhUwIFANuFQ4CeIenB9ig? z)pyx%gLbI0jvZp?7wKTuCYcB>b6{b)+^j~AqQm#T`nv%5&Yywbhy44C@K^5t=HbKp zh&J!u*}ZAeXojG7HTYb5zxdZb|NEbJ|NW>M5rzeH1wkG<;!uVTJ7sY| zai<+_y=Q$d1-p+>MRO#quCCC=d{`*2t{wN$wdIj7FLPpJ}QwS^y1J)SylF=6hK$C4*0E8J+R(7 z6@-3q?x2b3e~73GW^3c2plpaP95tGaP(wS>BAu`~q!XCdCeezMFdQSt%kjYIS;-<; zunQw{g}i7s1*@|TA_^do1$s@ei={lMoV5xj(U(h1K!+-f+21mdeE}+%?p?mp{c8w_ zql*UnJht@&lc4nATjxIXIBifl$V_K$~g-?!&*m^U}H! zt83C|2G5wy4SPnk9y5q^&Wgm1lWtyRs*;e5o>`8_gPqv?z!Ybu&RS_V7p{DFs^vVb znVth(@ax|-#@cPFlFm-u%S}b9K>KF!?swmkTW7`2_mTtQo$^i(1WNPV~nDjU}GUL z$n7q4XqXTT9%F9_-7RiP6XTa{aUt!C+>+ggE$KD|qxhjQw5v5Kc?x8~?EW3S=bZ1z z+1mLbjYczHNubZ1d(XYsc8gNLMX~n50r2EFsylo~lGX|b*V98rEj;XS9r32LtV4Z_ z9UVX;u3k^%k+49=SV`eJcW&_&L8Z1D!taQ=TyqTN%!NgK&ti8b>gu}wcaZ06CEFuy zLqsCxLKf2Zq0Z|K+xLKH?5-$oSUBGx7mg3L9>AGV31@ z5zBf@2(FPl_}x~RQQPioGdnxM_fR*APswgQHZ@@A9+xZc*Y760;)i( z7y5);+c$Z9fN~&gFGJ6=H#KUBuuNOfHHNEgz56gKNkEpVsFn2w)$(foRX}&GeA(~@ zU$$Ph;_eRpW%UIE4ABrQFUJ_RB#g&jS706&E#-YxMkjfm5#Dg-uoD0jDdfDDu+-XT ze1OP?)(w2*fqgov@CN7k&e{b9J|Cutbxnkb|D+fAc1@I>G%6oJ9v}GL_YJ_9+&4!1 z@9~uD0Lig^PIPa3p6|nx_2qwGN}JA1X}*4`Tq2gR9T8|3W|QSF4zAMN(=tc^4?Gr5LS*7=%{pGS*K zj&;g#?gP~}EMas#b5@~C8M8iW@$mo3kVf+eH-30{*g>v0?L9eLR9|SOdzUfnsJM7x z!s66I+tz&V^T)sb`-j}MxctEiX{sPJrSIz6tySDyU0WMhVwhW@e;J4#zqz(%ShoFE ze)@5dV~*Gfnj#k+uNYu%QxLb?W6TnBTp^S&qtJ`4F(s!1fByE5(~$EUO`v7V+SvHc z<;NjZZ;rB;-X>^JG=@a=QBQU!4zsVon8l$-m2ka^?#az2t9VQ7#i0=l*kH&l(PZUn zaxeg)Z(?+v7GgGp?#irXfbGF)-DR4!6Y>Y0ui*dcg_N+R@WY?i|4J{GJWriwZm+2> z(RTj12TvdLP;iXoZ%(5Vd!d`n#Go_7&z*{Dk4h{UvQyg;fcTJ?0qQu7kTR0RRmRFg z?ur#xLN)5({NN@M%Dh@p`EjMkhL)95hvR@lyD;d=Gu`auK7IGQ<0PjLNhM1$+qf|@ z4=qq3xoX!xEsQ*~jWpJo#!*KRRk3)K^^8V}RJhe4=t+v|BcbTjSA&8tH6sy%v3t1T z;>u3$Mb1FvK${9)!p<>G+08h`T7w!<^rfVAf88=&h&rM)tVd2yw!pIOqakG)rRS*&x43IREv~E;rE1q*SAdcBSS0Z+j7JPmQ_*Xk zdZpgM|lL zAPMYCl6oXCCW>PN!_BZPGZIRLmS^zPAOm2)JmganBY{au+M!V#<5BZwfk1*XOQ(^1 zLwRb(E!T?LGz+2$?Aaz2Wt7CX7^DFW~vj%gZAc~uTD>% zJb!X>gr9Bb-Xmbw*t@%Xw2Rxn-L-qW&kV%(e}DhUiBz!&j7+fM_+e_uvd7NPPoMw$ zH7^91p+#A8Ept4@KGm8BJfEplH;*~oVe|MugRxAz-KjzBjAV7oSJuYu*R(IB@3;|pWqfUI^`_x>b=)Yu^1TO0{nq&FihWW0i*{IO&VkC{DHFs+ z2V9i`Qw4J>A=*I~|MB*>6tMKKO9*fL?48NSSD_oLbSfi+3INZsx`>vm?i|G4vWj+X z$30Bq3yCp~AVR9wXxy)8h9Rd6v4;nqfU;rRvW`Dhw3e!3mO&-#aB>4|UrlK3D%x6v zv`Kh_=-a>W{<)N^_SQ{_EH=E&JuZs0T)rXxD!_6T>(d%g3!8)ZLI#i<1C9PIX zH1o@r4VcQbS+JjZry{JiMtf_o8rB?p(>zhGM)l zCDl`3(gG8su4Bao6XJ%{u2Z#jrZq`P07mZNxUnEH#}H}!QL1DSC6(TkzQYa;2b_9} z4>60O;Z) zWyyj3Wo((e9DJg$eqzt|BN2=O2UNrX(y3sKrzEk@kSvt6hxjw3^*++bc{0;Bqrl89uNrJQ2=qoG~eb+5uzh9#+FVDgGv! zy9i;s#j6D$6<26Bf|dBv&vbx$Sr*rl&5IXbyn6lm>dSt=zuY&Ro%K5t)BRy( zw$nd5dwFIWc(!7yxM+fyla2{k8m=LSXPEr1!TXFR)FLtIYhu4$6NWiRn6RF43V7q& zDPZP+-$xk|Xxmw4S1bFU-JoYD(uS1N)48ilOYhzOT?o50*n1^+`@yGw`|QfB>zZ{> z-shED2HMqI$N;YzVZmbD#jkC-wF>{$trgx{xe0Ylo&1AGurt>d*@=Tf7^S~#dsSRy z|0_;Is<~N7MH-%I?mk?w)eGprE3^NV%fp6w8fz%`Q#SFdn1DWfM7N zR0D&!oM4bs6Ad(+YN~rjNnI+@-TC9g&kU%0nhCK7G1|q{Cb+@Yo6xKr{+H|Ramrw` zgUmG2uqI2Jy**q(}K+)eW__He){fPD+)BHJsi?xZG9wPQ*Um>fHKN< zZp5H(G^&bm0b6BA#nv0L>&Ds?M;|Fes;~A7{HEv>NnA=*VNlS4NQfN;(qyNitwJBw zDu_xZJB=vpL?AF9bVTJ^TA~{v&FE^&9fypH<*ACuB;uKimS~OK3nZGwQU_PuZ4p>R zDxn?g0rHemR!pnwOxmLrxx>`smc*`j4N|uR`IO0yk5Niq#RsU&`I2<@y1OpW*`rj^ zI^8V%^E0@(z=#zP;HTKaX>lBT{(>$x+*L$;iGgR-0+YZ6XyC+snL}b_Cw+Xse{y%y z_!3;E?1E`JFf?T0W(IMnT#d&bGsk{V03&>X!GLkVcrzVD*bS`lq}r&DJ!Det;W8Xw z36PH)TTrvul^I*YQkW*#66$jUzwr!%oDik9V-=V=MKBkhB_dscZco19eLAi|VaVZY zY>1gKwjMBZD^k*B?b$^|IiEc!r_QJUQFVQ= zVpu{Cp>kTUyVhjk%$h)(%>vuqiiRje!J0A7gK$|2dWnW%VK25rlEQ{5eK3}xu1sib z8r(g!>%ipy*yo(j_p4}jEZLIo4_!gd_ngo9oR3GY30my1J32)<_)hdK2Zxhqqil$B z0QR(G6T3-oNwn_}k9#gF$}B1OSY(&=PTS)uLoQa^B>-cjGFLfq>I&SOTyqq8fl+z1s;LJ;)>uMn7i~%6EnJ9ZnDwGt9#RLKo(8haW7!gmru{ z6y_`3w=>x5C=z!%gAegohdA63{M`@$7W~~l=&v6L5ck1{`wGR7ur;$|{}K?qe|ehG z!Y^YoB9Y4UAwn;=c5}O!@KBie?4q*!pKo9O_sbV&&rVKIZ0-;Hm(0BU>g>ho7vDbk z=Kc3Ba#?}n^W84T5uVp}YtOsSYv)rL_8?{Gz0$Br+Mc1c7g+l)XE^=00Mt$B3}W;r z^C47*Gm%+lLH~acmTJ(ydiU|8ikhtyTyr%YLP#CDhKCnsDy3Q_r#-@urvLSeYd3}E z_}42_wHXwR!GKpLt5pNDa9T|Y^Q}UIo}64+6gYleuo#u!$rU2<3Yf3}vOM?W2L+wL zz!)r$U^QBy>6d@aMiOWWE|h2FyP%VjX3Dd)KriTDpS<(7V(z#V%l`cCdy_j|0SsWL zAX=SeUtzX+q);F+DldpR7wabTutn3%#9_cxondj()a6)yt{&5<csP}b`Y-p7F(6r`y!L+*ys z4WAf?03+EFa(1?sPj;adr_<92Xmev4i)Ni{nFz);+1oskW z70SCV36PiSc__)Nben-1Yr;nfc^inDVd&xM+A53INYGlPVl6jMfBKu{aU7-Z zrg_71R!Y7Kn6?tD<P z>J*K7tTb#yDT{`u5+;d@MT1NR&s4HC^jDc@v#8*RlQ2LA^*9JDj|FB0VR39X(1eTR zfqX%;7>;mP0W#DZ-7*N2)^f8zIWI+J<=5eod|NWi9RPrf7CXUj4gMC*`%^$CV-2}? zz715Ml}vNnz^*a4aiH{HF*)G+V#KPsNC*toH{3eVw-qS->RS!%O30oL&iIPUFLW8< zKXqWHLv>U5F4(D(R7atrC2-&Y2q;UtaUb{!oNLiM6{ocd$Qu=81k8b5L!AbCz#7#i zZ>A9`$`&RFti(LX$#nTfiKb+)fM|^ZY16Y6)ta+|qN?kss4at@wjs^JCyWi*!Q-m? z%K?dod0Gy_(N5gJb+uzDO4}7{;5;sTOenfKnudWUTX1upEUn?J!}d~o#yG!}=?r2^ z5Z@)Zw3F)LDu9yfyJ(x0g^M0)lxpRod4Oy=WQ!hju69`Uy^7C3t`zQiDhW80;Gs=B zar4peWAf!gkWZooEXLAE9%;L8ZN6v1FwkiPrFlMLvL_>q$BNJf9f?dOI4CI+s~jF3 zP5k-gaDV%*rN97T`Pq|yP@Pqfh6KIQ>1@l_`oVS|40yfY`EVV-uH*MXzc0Yt2LZ;v zf>#!W^@982eo-)5e!o>kKX7$rIsh*h5;I!9q*fT?o!u z_A-^U7nz;N2=~IE{>_9s(3{ePa>>9a2&uY4_(C{pt)C-l7Sq0 zP>TV!fGfa;K!D?ew6#%wbWQgW`DNQ_c}@#dQMhPZsH37qH0}{(J#|mh8SMijQ*HFo zKeTv0VtVL2D zLor+=hIzovI2SBb^vnR@}nLuxGZSm zSR+B6c0kMJ8LuU42f4m2@7m^dmUhX0p+3*EARJ*=Qi95~&hSfQIG11|pZnnG=y2=n z&yRVO9B4itdzD*3&u_Zu4wVC))EQ#~lubnm0ZA`n%o;A`g$@>e_tq`1Ij}>$iX2 zy*NM5W^|-Nfwf>Axj^%@(0_t1&0pn0qM!*_UU&}waUslg^K^X6?%gb z*d2@tD!zqWCc8K99!WFYN zuh=dY2DMT>`{~cVQ#JNkwul;;QrN4KTXhS)qxz?Mb3?sX%Wcy-nwmwc6ssvnRZm-3 zBpbscftqjai)<;>l1}2JcDas2o02-KIukPjt-^+u7dC@2DhUo5+)zfR67V=41-dUw z_?q@Gf{a1aLap5yQA_TZ1Tja@{tDR)Ne%TyV>>g43JmsQFHLj0;gZ5(U|+}efZ{QZ zW3*&N^FUV%78>P2-5S3%jZ_^JUtP!0RHzlhalv{0ien3gU{rA)v1%i4Q;%1`56$-W zonG-;jwe)0=#~S*>pB1M!MNmq_f$(j!lSt-N{FE-3WALP_5lD;k6mu$(y2_KV6pO= zPsoWvL-yFf3gl2&iaI`kQwUoMf5uZDI-sDcD*qNF_5u1%n-Q5LvsQC;X_S@+p9qa? zQ!*CV?g>s3par`HRnZ*9B9@8~B0GVQcvH$E!)@;2Yxyv>R9^AS$sou>qhNxc|O z#PloHh50yy;fdH3s<2yM5BK|f%72CJ$_>8;DE$sl{T;xO)w#PNgjcW^h2Rdg=l(Xe zXsFQx26qeqz_{B#ehJH$nE)Y2&2?ON*5?-t z0I!WT02>(o!_Lms|G2uI*S4}Vnr_}KWKF|k7S?-0mdu!Gc~dHvQHvLns>P(wrCB_w zz9JqA!2^Y^1Vw`g)FBBCorRjxDTqRo22$#U;*e}QlujAaIFOFpE@si?Knp|vkACNT z_uePR`C{roYM>DQ?9Nq}uGK)6Uo z47C#9?vYex>sfj?|w^%gjwdX4u1{b zHfHLMV=voenY$oINkOCaAf`Zc_cO4crM+)Ubu%Y>>q5cIrrA2l_jLH;g2Jse%q8KO z;WNN;vi{3==y8(Q>SV;F<2gN70i%~AqO}}u z4r5tFHC_E`OSS|ti)1OE&ay@v<(lG{ay@pGx3owe5~I~j&OfrkiGj{bZZ01`1?ITK zg~>AD!Q~hsO7bD7E^ekIE2KX{Sg7Niv}VoUyZhZPP;ZM(IMAU1wj2Xw=P$4Wh|?Gl z#j(*ixUt*Z|L}j-gr&Iqm=A8!iA4~8Oc;hI3kZBqE5A^mVa8Gs`plMtAxxjkx6_yZ zpbS3HnME7jz449a;MI-i|HRaX)6>t-E%_A)zJD&e3j;1t_vF!o6PJ8>;p>4S@xPnu zFeBY(f6&}?QOMCie-3Is=?3jBQrFr)1tu$(;1S*s;d1wlwR8yy1Q5) zX9Hsv8UoFe)tH`RXtp}CegZvNIO7O~<_SjwRu|ZmA&(%mDV)ymo? z;e%#Aq?{$MwwYpuOH(_uz#Y_OLFHUCngPk^1cLh8;>?7cxs&J&YOr6Z3ilQaTC#cC zIlyJ69mHND@(Nv6jHTB0BnDL@bh6r7(b{ZB3CmTk8ti9cb~X*uNYJDz-pNy>jV#(| zfU0)>^3HFEbi&Shg&sSlT_nHFY$1}A zOaanMuLbY)z9I#K-qfk3*g>i2)MV={S;gGUi@BLYRZDoW7tqD%V!?Qd$$vAyx5rXm z8lcT6GP?sB2V9v0Mw1mtr9?6VK4xp;w8de4(b&7@@r-WI<4rT;*{d9ZtQhxh3KhIq z72q89(=Zleja!^#4zFkS3O(PJZD!L8KNi33v{=*_`vlUpE{-k*6pI19C4fj!7fMW$ z#quM`Eq?n8O9tT8!HI)V)0qewG-O5Fg2lDER(J(%g+A9*K3xi8;xKh>VhUNdWI3}G zJrkg1NfV+q-wEdEiVBY-?Mr6SRZe(pv6d7YD2&D_%TKA8!-^Dx!Ee(ejKmCAxE7)u z#TeVia1Cufj*pqCfh^^a?MJv`IdK5$9B#`(0fsNRBDU!|J2GK3#x-n*T!Yl0J0BCK zsjRDdj!TL3Q;QVe9rVH*^>|MnR@ShPdmC;dGm0Hd6H8vy(z zyODP(Ld)6q-rjgo+5g3hf1SVlN&uGp_e@i#Kfe#i)|n6FzmJpwKPsX>ep8?^x}LsZ z_%mip!2C=DmfYo*(p>gH!;VF??RG1JiiPPeXEE$D7OT>{^Y!&Xzy%Tu06+N?O1zue z1FXoZoxq!%bhNoA3|L9=o{kLGdZFne%I)vzaO$FxR5r?jq3Cx1OeIdI; z1!p`c_fZfYmXG?EzyC2uAT>FC0ho&(BrsmI10(UdIoKc2Z3WzI(yz61byJn-s|@G3 zN)wh2W3csKn?p$o{MO+U6g-ht!5Ks-=yn8D8Neu9uF--_ruZ%2sc~I=mPq zbObX@IpI)Ubo#&pOt%&YC=)n1b1>(8KK2SD4SLb;ux*%AlRBDJh1Ml1z)8}UeNqhD zWgc@Ym)-MDgQyLAS1UOH_NARPp9s3j@m3muHR0wXjg`zhlQC}PnvFDvuUpn22kM4Sm}M=mA+{q=p>WH+Lz9Mh zJx)@r9t42DHhf=mfhvvB55>H*wtLJ)MIY%Cbr>Z*rP2eL+=6E<~cV;oXvGY`21_tgDNf#(it{Zr+` z07}I|&r^-vT(^*mGCe)D@sLkU^>9)~3F~-=%1|iw= z=-C<`bJMA=4otz&ujmrU=%?fPxc?~R=_Tb^G3$x)+dQlhZi9IoQwkN@D!=TPYRqDl zF#s8!1G41rvw)~eVk>-XiFz{RY&P0Nv~K}p&^~({g|!&%tvG&Z$wDYx#cV^O*bUUI zkww=^!e~oT9YYUc`sH${MVOpn`&}Uw2=< z+8_W!f<8a9vD0T{!1pOZKeF`q^yKv9(>_tG&ff&`(1{O?9vLo!N@C) zKtzkuU<;NjytWG#S=ky?G#MIO3z@w0;}1S~ErrsKB>eW%hv{Al+tucX(~xW{Fed^N zj|J@%aYvejwWqqX@ZVe$J2vkgm4662D@Z#W>fa&hE*=7V!G8P0a=(96F5`cBU7q6M z@bKM_X~E+7K`78Wn#j?;I@p9e3mr%m1ai=A#lGMs{~>~d`t#0U=hNN~t~&I77W+Ec4Bu_ql_s#ND zW#Y^`doAB}I`JCx7S13~P>X(?EL$rynnG&LGEba6;q{_#<`K!tshOjinf-FI?FDSo zO&y3?=$I;?8G9MV!3i&>*xmA4!jRp|oy?xr=&Sm^e%V9FTUT@+ z?3oCSnLn8mnXzJUbXU*l)&y3B&O96wS+lj5h|5>90wbsP0*$>+qwo0L^aOTEg~Lz( z&(#&ZwsoJ;Fvi`3Y!>cQtgFgbC4zxAX2BHKutT8i6=yvC#usWEY=TV*F_f=;`C1=oNf&4lhj}Ag>_GJd z49Hheqom9lfRhGZ?jZDu6V??&>lVmitZ1wMd_{BeZP{;;0}AM#XEkex0Q`h}C5A|BA5rVNkk93$EsjEVTIcxJF;6QPaBxj1 zHBTy1HduqF{7v^;jPn%ea)KuvcOmF7POxCF?=RvVxgZRJMfntAa5nJX`}jhGfXe`6 zRz}hJTh$4H48f`*B??m#P$q7agaJ>MZ@xec7?&r8zPvv=I>PNpAb9I&i;-B@cZLAm z>%%)cLsOigKa&mB-5nuU~!p$#;9l)#YW*Hkz4P#oVRpGIB-;#|=h7SGDaI zrv)CgRi2HxWljRR;wx*dQd%AyoO9BZA8d4+Ma981P2M{j7SlFyP?+`AQ4il9PcL{-mW{BsXGG zA*L5?3+=26Q|$Kyq6NlEb%CVrMdT;3^HJtBRr^5C7H%{q;CaOqN%n1ZcD7!6DUe#14C0B%xfOnpBC zvn;if!l-jSInwsQ8*trDFxUMUq%he|#bi5{L5ih=sGU+fE6XMa5gF`c4#aklz->Zp z?RNrnkqWztn{7}-W2j1V^;g(}f}*`KGNg4p)QYyY&4g1YA5!0GxIRdp8>ZW0qN$4u zz5Y!AJ#xpD;HTnxdh~7mmtDFk7j+YaFqs-bT*_>O^r0bxz%H@|JLFfFDPvJ8F zCi071>#p)J2EqskklO{m>CdEaEJ6wx5R8E~p*KQ55R1K`uUfEhQs9kj4@l*)jTi-4 zR&&824-hXcbQ^?}mS76tfKE>%p46VSnJdPKr$*=m*fa15%}#NS%~N^s@;nU7o_7t& zj6`ucdMeaxq~h*q%qnUdvmA|e-_1Yt^`K|PnB!fnt3p>C!Z}B z(&7xMB2cq4-VEJYxNi(74mJZa=|%tTTkj)!f~n8PKmK@pY;lasoXNoOC>BpOvqGNN z%ae!4)erym^wHsX`q**b@%R+byCru-V0rY>(RlpPcxz`kyff6d46m#48SHgP1ZDAe zI(^F9@YM`Q63z?SLl0jnO&*pTH?N+c1pN2?sa+iH-kNR=W$V`ucaZL}OX90&`_D`% z_@2FN6PO-7dGh$#v#C9}%-6uuqA@pPSsU=2=>#O`0K%2gI83ID(sUy+VQr*A zlzRK^{V$dbN(rg0CC(z$SGoeoe& zf*$}}1zow40po@j`|`dBJxC?(p2dmOWiYHNYKw2N85!ci-Gb#)A{*DltW72Sj58Q|4N!sNOd zt^t#Km{!!lKagqSdO@@AMI<$r^K^+pQt85`bS@FSXPrCWnvJfEm)Z zkt;&p-hx4z%}TuofB5;V%X>=wIEfQC)kYl&R{r{v4xA`)BPDb-@f#V@;y1pUlN7SD z6#aD+oT3wCzxJpUn&q zCs3Q&US>_>77Dr_8qjnL`1@3Z=aa~UizrIgQ4v277_i`!eD9+l6$Qr-X%6`A$2Wcm zag|IgMDZ7}y9jnnsET1N_JY_qqn12GhwF&rg!yLA)NP-s9cmNe024s$zr-NAdpCu7 z#z9yNgW_oOz%PO{3&?C@VgtH}QCb%G83B;ufOL{X5Y<+gk@ET9ky4Wd2O%1!XzWrS zGXM@%ROXE2^YDA|agj+$!&RgUVs4_BHG z%tWml_31e9MMfEDfj2tK<|3?cVv6Pg2Pp)Qm)T@3OqZvbuZI*N zVp*lc*wWb$4}-I;{>DIG`IsQTa+bpIH@7ZSsWJ=Yd->%za(Vgk`|kyaA6iQ;`;iF2 zuqDk`>q`%3I1gADaDu+$Q?g$H-&46iJxVU8U&-zC_3PKCav8Gih<(DsfCY77gq|YK znhbtjr_s62Of6cydMz8Rz&FBcRau9a zUeLle>{hi!KF5<5Yf%Vvk zpvrIgJ`LA zp+vaJT_-1QU@HiPW_Kb?562#wQKklM3Omk;?mTjPDfp#oo zu>b^?jj_2l|F%iTa3kZ;;5=679VvtMb1DLa`g_l6wD`#6uOZI`%u&EZ8o>aNRK1C@ zT)`X!sG{pRk$sE+pCGz8?h)5DVThODr{bf44ZcEcgAl58>@Nz=hT)s>|Q6wI40IL|ol z)Aq0u-7LXKnkAkwSqSV!I&8Ow&TdNS+mRgwhD8&aW?8y)O)fJfGz>jBST#mHEH1>b zJyfPpDj#H=Uh+z?l$qtP@B$wNmt3Y8q)+%mVWC)$nS=44@6UwsNV;mvJ2**X( zA~p`-!rlty%$)rjVK!kr&?yoFEGXo_VZspk2%gjQ0D<3RYcv>)gvS$Z7$pdFCnH?k zSR1Sufo}idJ1<>!K2GV`kZfk-z8;@*4LyEKkvaW2m(lgQE^~sDzu_~d)l!cLM|0!R z==Ul-k28lw<@gz-WGS%Tr`Jc^;W*@rF9OumJ;5^6Y8+QsqVR_ZeU4^?ZRv&A&*=b}e;(>I1 zy|AAvZ)}{RE>zWfpu0Qimj-sLaRp{sk)Ny7Iy%Tsexr-fwN0l`V{qfBmI|rRW`I$p z8<3L>N%KLu%amuG@ladlTvm4L*Qz11$!sYKNOO6pnx+vlKe?RNr_hEW&|0B9B>(D~ zf@TG_D065|6`^&_hLY^^wNketT;NZ=&VnZNRLS#;vg?$Kfs!Pmbw&B9}F;jDX&t+6ihxV&v{c{i6&TLFvlH zoA1GC13kZM^8o(+KOYMQ*J;LqE}S)>7&Xe#(&6JZ3}di4;3rN3|LNq#iKXuI)6>)E z&jr2mT^=N`!|@Awe)8<(3CJsl@nOdqenmUX_1=O`?p=xx4i*l!A3uBen;kdtaLYXb zc#oikZ)mFd#xIVp!}9XhjzD-vo~hxb2B%pq&D8Mj{YQ81W9$7Vdu*;+?xXx0?$5}0 zWAflKZ76%3PQg;>-uhav-&^bV`ULR28>MXozWRgw!GqQS>XrkMHra8cjYgNW%Xg{2 zs^!j?7_dSYZYo(U7_hh*MT%~~n-TSnzEBE*bI zk5Sz<812zpGRB#4Z!lMsX}2{1UlX;Rj%eD9GZHy0d}n12aKPfY1u34iapw}OB81AHp8w%uF{>H&VDv#fxaf4BtY+>vuTvrsB?Az=zcD@Jp9Q)5zovEWK~%;mKlPZ)(Zqd()u1Dr-q_5Cs%VleimIncUAh2DwOU#py%@yi6gy4))K*@`5! z3ydPm=0IP#Fab846F^X2fiLo_UH}kivKR4CCN`(nNICjF)Dc##03^_YDCDI_2Ah>g zwQ9Yi*KVX0Ult6|g{8)4=$bT$atReb`@9`73{s38oVVRPYAn zZXeT-h+H-u^|byO1{`)KL$lemMObG;(4NLGmmhZ_5COax&A*(ZFdo5q0?Zl147!z| z1&3IY{RVJgl&xJlVZj)TPqil83FwJLz)b5=t zoX9%Ew>5-y=9IM6t01oZ2UN`Uqp>lU4d#<9RRGJel(KJRGe8=BLu2n9^=!p9F#3K0FH_sQRN?s^nK9t7t@Y}#))yN9tW6{IM3`>7; z`ga|JNDnIcwi&M<9QL;lo;|utK!1+0hxfqY4-~|7zC60OwRJ;eFkGfN_Tl>N+raMi z{r&5=_}GCc-iIK@^ZhSH7w_M{`}y92^@D~h2ReD9Q}^ z%mcnU`*!t>-#u{jy~H7eORm03hZJsJ+UP5qVHb@&u$E|P!xDGh{5jByBrlP==%IUA z)vi(*s#s&sU@sn5@Sk_S_2!1Q`GUXN0!*;N1*=KFNx2$pO3AT=$orxxSilRjtc|6O z=4apb-d8>YOd-rP_sgPyTVqUP5V<-*4i;TWXhwpe2C9!S8CWRU(15MLu**roZN_KE z?B<~bWI`n!(VZ%yWRB>@3_N#r`Ve|*y93ax5p%?@=**a7{X{tq=?;z0cIjuZZ-Ta` zWXNg1l-iAWIMN{uNXNnfdc@$*&LkCqG%M;QW3l19s zfEwQW^z~nUH=8SX^@`WAH*@tnzS1Zw=78#BoGwP1&J&<;P;t@YA~iFd7O7LLE>G$N zpwi9E@}nj_%SMMqN=D;rm5fGnjn#{wNp8`Y<*5~-4#LL8ksU)JRtYp?W-<^G)>!)G zmeQa26+$|rFF)3}vjLcK={zv^JE_{vjhPeVMv<%7HvYPEJ=@%h=hQ-+ZwXH7&&24G z!1(owaiM^j`nOUzpFPzOdXde}LWAJY;(AqiZUJrNv#_K%SAocq-~P3S$k>K3fi4j@ zX8linipcFQMO~#6u5kN*$vVH+w$3w-=VGWAa@av+#m*7+QHcnt3bSaHW0Tn`bNfz~ z6FSvIVJ(`Ns6tovdW^M)-IygIBo}I7Dd;9%3oR}*Zpa#lWkM5-Jr+A87lD-3URlWq z4vbv(AK3H#KJPhFG9}p3k#x?{5%}|dpC8``1z4;b5*Cv)sZ^L!cL*QmOhFW-9O@wS z&>@pvN}}8umh@^fO{AgWV83!tDCWDAtp`r|sFOlnn9peLQbxUzX%qsT&UEkJP(H0| zhAzvmw91LSvJRC(GHo1^SE8_6%|)===b-&Fp;kcSl=lZIEsIhMjQ#r|rV$5@AXV{c zebwNR&(wID>lU;DL7h|ZvQi3iI1H$7xth>QG+C-J#VZQ}e%LM$8iCvyw`@UAFO+Wp z+KSMXM=8&xcjadUwJWF(JTD9b>b80)(39^(O%QuXSP4%xGK^ zg)vEJpDj-|hHkCRym#^Tmjd9;4d;ZleDmfPM_%l0JI>x4Kl1!0!Amtv=x!(S`2NoQ z9c8j^S5$9r|C=tDDD^7CuWDjyZGCv{-1;T~e2UrPZ~`LSw@xj7 zv?_A z7+u2Xz$%}9|E*u2{C^RwIbi3$;oO}OTGoEwiHSU{IL5{r9EHS@NqqthY9{x)X!+tAMpB?<=%2Y{9yHJtcEHE41WIY(hH-P^++IS)STWZl}hvmiXc$ z(#^(kX=8XU24pgJaL3rDbTy`Db=`n)vh67{NqMrHmrc*E$D{B7)+%-96CrKmqt@g| zK(rj!nwXB(Nm~cpqqZMBceGWVYI#u0U&cLCAE@kd7`J#8u9VfU#`dG}TwL_r6_r!q zcVy$Gka7EwGuz`K6AAtyN2-NC@}tWbwET4!{wz^?`i#<|aVC`C9zev{E37A>?_3NO zDPsW-Rh@c82*A4fVz@h@bJ*APYrwQ`6ezRcRLPcOpB2E&gF=kr#UaK60m%UlnFb}( zh~Xk^9;q`F)4g5lb(dh3wFD2(^#uMcp;-ycO6h6hN9I}dy+IGK?6*eYqGDuO zRQghY;5Xh70k%PatBPfi;8(t@FoXaW)<%33r9Am1qF5L#pDYZYJOA4u)qcgN0DKFD zS8Pujp(FClD3i0f36Z5UmB22Q$ z;y4F0&kCYGb7u5>VQtk)=WOcJQYD+oH11Z_22 z8*66Om-zILw$`!P^8GPX3C}wDX_T5yzFLPh%l*_CX?FYIClEecljvA39W38~ zlRR2?XtqRK&8qC~=@P^CWwgsDgRgisPGCS{*LwU6vbkq;X9g6nC!poos&wZ0x)V++ zw+v6*Rer^R@0xK~*K5Oog1pr1i2x4ylb-QHh(Dl!jtQ zWQOz%HCCO{#Ylj1G(@q%XeZRl5)y_K(3nyb@SoPp@Phtw(G4QR6r|jxJb#JV7d7Fh6o+X79(TG3mJ$d7^7Z6`Q2FI&% ze&rwY^VPjCzxWk=p%drl5l&yo&y`*4FQ)}N^?Ph=cr1To{+*{~@4)S)^o>dQS~!GG ziEL|=Z@CI9lPiT-x(ZWr9oRQw;6k%Q!{$=9f;L_hI78*OQ7^?-VIgaCvJG=b#(!Dh zg~>!Ecu!8bpYV2WW!sIcv%t(|lTKq%wTODRCRu6SYzuoUq<0Cy?OdzXqC;d!x0Nm- zdaNGRlbxpQSq@df8sfmA33<`mho-UzzW!Pk4yQl9aAme;-`)4ut6#nL{;Ti){G~T9 zcH}c&efiaA&H~oCN(VZ*f>BKE4yenSgCr_SqM^cZWtdhjHFWwf8;vWiQm3KO^ad)i zK9pfJ|o5}g;3YsxF5=L$7z!s!=1B@X|ESFPET8^;hNF6x%0L49+wbU8E`wli9J+hA;P6T zg|KUbfk5>&_sP4cMFuHUugc$kfDdpJ{6-)`k`BI;HI~}r%IMD7__C|?{&2*z+shj3|y$r=<0J+NeHVvUzfkh}szAJHN z_s|j*K1#has@8c5gv@`7f`48%^9zTBkUkyQz&R`CqT3`(gsUz~x$lDWZ z#ajgM-?c7kIUWFfb9sZkz;J^epANSkefNkRM_)`I?5P^w*||49zV|NB`-6b@oBP}M z0Nw{b?C#3{-CI!GIx+$GCOV?Ehu&Lb2wDd|Y%Mqw4mwVs(E$)FgN6cz@>P>d*j=t- z+%TYfn_R|SK4f|Hr=M>fANe0!*Z11iVMfa+ZbNK(QB08{CB9l>>Q)_=NEO9ombTcr zD7KtdF;-@n5omKs0@n@{E`iNBX~O)VEL#{}!C5>=U6_qY+>ts{nh@N<+_JpwAKI5PTkWY{lGcAiEb!TEc z$5945+K|kF6}}Sy4ks~KYtckpU0D-0`bZ!SN_4MgMcdehV3}t))u z*;xb&m)gEk6T;XVd2Nbfc4eLD4IQBlOIm{k?0W0K_eOX4ldOJ9)}^Yml`A8P8Tps0 z5ld6^E}+BrBF$HEtm=n#SI_vF;+oJ{s^0p>fMt25rYzA{DAt21pkir70VzZ^PZlUgt|(+H%z8?8 z^$7Y%5TUJ}Y|Q}IHw#rY1X&)mD!YX!ttY$bh1+>;y!T95wk!60d(`pmTF9EoU46Y= zy{))uo8kS(C-GQ>oov=>o4)VW+W4%{?}sLF0I>WQz6iievbyNF1P=%4!a-8`Dtcgq ztPv_4(AdE3P^B6rNnvQo#g)aFp*5MOyE~?Fmhxc-_=)WVTwRN{6nvr2n6+ky$}f0e z%td1?jawAAY436aO5K8d1xT?7V+0+i$(b9l*c@nQ4|XDClkGY%YVk23X0kN&q8rbim7UcFSD@_6yDy@c7}z$Xg2-iGVA@f>>|| zO}nsAIk=GyZOa8kXsh4ir{E{-Wllqpo8?`n5S=yPRr#ur}L;eEC|EX82|_OgacPH3l5 zJX;=MS5lZr8PATR^s8eCZ7d-(Ig}>LX9kZ7x}N?}5f{Yv6!d0!GYYp=mx|Be#eiIj z&qQdfAL;t>50;=ckM))`?rN&_@@vcc`+Dhf9vh2;9{1QNLX>?ug8}5XmvbA~3>^RD zy@>suc^-m?_deh-KEasP#zFKOQ2`e4fHfHb8^Q>M!yZgwW-xIU#n~yH&8yMLz(piT zG5#XY)Qw`3nHJQS2lK@`im+1|mWop_cI7d~fO8R=WjeZ$^$7E`HV&l`0ge78Xvjr+ zu2A!30}*`EpuhZ3lZti*h3d3&=gh6U>sOXrhvh?`{H(wGP}l8W-~A)4cK`q&07*na zRGo3Jr*0qXZ)I9Pbe4Yg(ob3&*I!R0gq#Ze?*b*BkHMc=7 zBD%_F&57%^E0m#lX@YRLt?z|vL#zskSi~#abyx*YZ?mcruNM+Ql~EOj6_6ESeFHep zWN5rrlnm->-D1--m>!t?SX>7b_18C75ZrNZY9(=7ZK+ydKFUD8{&z9{5@bg{@QFHV6e#2t=uV}UXN zF1C&lQDP_>lgd&=b~!G9qXKqQmqtZYPzEs)0%0J_KzH`g5^;YXV-Z$CHy~N0(aA+Z z2;w$CKwWOGAr@eoq~I}TR#-AJPS!y_GIVfZg)XC{lF7vwL#B2MXpy4^9Ta)dkzCLx z57?WM0ZrD9z;`maHwZfDn8I;znT+cMr6%#mD#7NJfLgp0z@a9OEh->TCLlG(M#9+L z6&D=Vbpn?)Xd1`SIuuhu*#U>eolgqd#vCfnF|L8+4Cr-8cfoWWK(=7D0~E$0hlChA z5fWT*_by!TVV6b!k-Ue{JN~!(+d2;edp&d-nfROX%v0u8Ogy?Fb6QH0&M}* z_nxf6=$yl$PIRgSjduyoLGCFr{;IRoC{dAy6H6H66=p#{*9k0N)#V5Ifp{6k-Ch8z z#azY9mQN|17!veA7Si<8L^u*SK45q)Z}LY+!h-LJ(cUgFUDKLJLO70o0TAnN%z{RN zw*(I~ka*z!I}1y@W+$@DogD8SFJ*HH@Lin=tg>@-56 zQw)(rpft7UG;7FZxQJy#EGd_Z44SM1%<`C~1luuVrMYd&!mVIvLU}fmSuJuf;8dQ` zkjU1^U>zHg>(iL9u=K&X;o(a44`(xA~zIeFrl~;d? z7T*oOwvo@=Jols5i^9^+elWaHE~hxTDX)GrWMeX`3kq`+!t*rapW*i+57(hfoL$J_ zgaqJBu`vbP*EBk?K0ffq@sQqDwNKRwwKHC=ZA0?B$Q;C%svojnLq>x`)t8m=g{z_l z9W@yHwXpnZ1kjKEvp3GF%c`pKLcb*?4}nJaZP@3Vc3ksK6E<2{@prIQqGKD?Laa6H zt#~NP%Fl|Oh60oENy3vSxN9d+@xy~fd^-Y1-*4~P3s1-nf?xZ6Q@A4(HU`UU3@=5A zccr2#ww;x~WB2VJ?O&)?6Z>s}ogGPgzupbc9#!mLfKMO1l#1Tdit=ibXMISq#|rKQ z611={fzLt^C?Ny$a~D}Ah3N|Fvc4|}B-2*~DoX8_wjo6&PQwEkLpw3JB?&Uiv(&8t zqS_!t4oMOzpjlw2D|&2g9|2ulV3{2Sl4T$(hBojFsaV5?y}LkDF zc>ItXv;ypBb=X*K2k5%oI|sTkP0A?YQd~yiH&6l`z_`o;FK|_Et}t3?$sO_n#D=>n zN&bt0xTpgR`MCbYnNqEi8QM-WF36QIzNgK>r6hnq;U=A2dcE2qMA-Ek}CvSZlzawIe^)7P+!g!>!UuJMiF{2B)> z-Jl4qsH>9?3BIaAuTAx^uuJ1rsnZ>mgdC8plNnTiFO7u^_}!=tDf~tsa1?|! z!M>vb=54@oMQOT}9mvX}Y+OeY#>>6EYMIs~EWzs8E`wGgE>RZ%OTNo~BbctR8ZRGe z1Cnafqa&wZJBy6Tk`7o9XuWlGd1=q=v^k(*vO*hDwgk&Fn}AECz9{{wRa!Xk-I+7r zhP<|{d+$2jQ1zxzHq0eVk#9oxMNe=#UoWGhr-&9=vR^dKqRA+qM(Bo6+h$rrEgEni z3ntg8Z|W_}Rwr%0Y@P=au~nqrskH0Jtg7&FSN0-ch8->^!E8|6Ht z9PB&P2ZwZiqc*dVKm6jktMc$s&J4ahd?_st2dGl7{*SKndu{7H0e-{x!7H9!mjoY?D>A5_dPmFHz&4bonO*1`15|B=leVlx^gvYHGm!V zG~SI4%7Yt-Kx6o^ymWcHY*NxdL+W~?$im+u4310Wd-^sy56FO1X zv>=g(L7e8G<&SB)=ZLQ$Qk)TW11=`}8x_Ka=(W5hXN`rUG1z9@t1_`>b%)`|Y;UA1 z26yEs{o3qvBF!!3Q-=;-K@gMF?hJZHV}Eidf04&-LyF6h;r+aC;*^@lyD_P?g3W82 zG|JPr+~vtl+#Jb-OaXU62ewEcF+p=k`o|!LRl_203uTHs0#R(a#NF$|f`E!oS2DD9QI z)dge`PzK*a{Z0`~42NM?wJ(9J)+i_0r=}}HiNEIwo#K? z$!Q2WcepyWy|caj>wkUqHz$A5pbE}pMxgmkSls)q28Mfx1@}anUg0c4gsUGt6G95I zum9uJh24wZu~oHPV+LZSGLxHXf08>suVqNK;ns@l`>~&DIK2-DKSJ|M z^x~oiY;PBsMQZxa-pcNkuN1m8Mgzj~Z+HK8g{(h}!rvKISm6^RpvYe|sGR4_LYlzw zcpha)sX<6C2>k&XacnG%YKtrQoZW-Q=mI@fQ^)~B6E95IExHE-*3iqCl5`4arRo); zQtX~5Y#DpLNx^G#!Lx@n9t{YeorMlQgjSU5gRX$Y=Puv7d+mpx)m<;>a~OtnyaLrb z&pIT|L1Hs#P7g-6j)~3XU%ps@l=^t(*uxr7))rZbo{N6Hvm}bJs>6N!2JO5UU<6g# zZuuakAeDY6#+=KP&Mg3!RYQn1a|3&5_3K5QK_~~K#CJ)<&gdKs%?lG&%P;puTh~=T z`i)wrt-T;o28HqVI*qW{TA~iGveP7{_AV7~myuwuu_bgHEh^=>wb?VPlWP~wyu5Zk z-Vi?DcqjWHjMvxx$#+)!Rkd^> zwcKGQT;4~c#p0@>-{@c}Ly=1WbjHFMWUb7q_WR{VwccSTN{(uTiiR+Mc;v+CNJG3< zU&gKiXU+vaBOCp-A#2i85c85jlv;^I={wqthP1oA|IHDkH5o_ElLw;H78(1Lzvo$&$iVKSY(%9J%5z|% z3Q-Jf6(nNT@?{+AuYd|(FVCQA#v|I0;}luf)x0N!G-Wf8L4On&4hV|o%}^z0JzB9S zpOH1y_KR2-FvTnw0u2A`(HShNnEozwgbbm*DSB0%ldZ%&)U@hOwV8>;htrrYFwvgf zuBunfI+wEYGXlf3n}N$fp}YgTECE=tI_PpiQQ-d)Z<4Gn*pLcW4jCdqTwiv)#qhDJ zR{*wKTJ#WGz*VSWOU&&;=rXaZyAiUBo&r~PvidjVa~Chd08JkAYsh^IS0~YkL*(t) z^soY+78N=VFOu+?eV}s~OE~6_9?tC`2mH_LySATmZ-tiRUA054kidL^1{sJ8!t6iL8sNdlOW93~lBawmauG?bwHXD*q#srQqm;JA29AEG z?)&I;fvE(2z*u1a7)!F>rHe_+ajPbMfouyGN_YAYcB=PgZ@1 z@VdIJ+Cp453&A=8wNPpfms`+gL>}#+8>l}*kB~mR-(}V~%W?&oY|LF+=#)3#I<{WuIFy7(9?NVpp>{CNa0a5bG-gjHFLO&6WjBXpKO(rKDqfZ>4Im+DqRNAn z8EDH4Q^Va*doq@o9|pG6{575>N@;k)-a;=bdm62P(+ppCiMt?_ozeKPh)VX^C}kmP zL%bKrdG@{Vyjum-AaN>!hq!cJ5vti*xw9n(5kS(A0cY0iGHKi8eGUOl2AsoCn`?NK zydJw-$*X6$8T%+`OKibmlfSx+3Rs97Ui896FN0EB1zPu3`hAJvjXL_?<$&a zVk2<;oolo@3uXnTYad-bbz^<&?#~6vqa2YWPs(b7MZoA2J#U*upJOL1c%sn{YyJO( zpe=w;JoFh}W-_+wFV)!2SsPygudVVASk-&GjHXc3y|yCAZ_6>P*%e^c8=ZE8*;2NI z;*)YsoQhzKLmug27I0sV)kamS}{%>qTaP zIWkZP-T>uj@}gLWQm0NXm+zjAH>>51xb)ejlSf6ofB62T&DVk-ZJht<`0TwC%U>M5 zF!E9mcwhQ=&CkxfGV=1ZC2H)W<7ZYIRdljMpKIi&5n{Jx&aPRsU)FXUG^sKDi`G{N zNEbO`vBe1z2#3oO1={%DTR;Al4LUb1R@H}W)0j=C#-cLR*jSXb<8P4G=@clnt*kL5T=1#VMW9-3)Mq7_FS(7Rz+NIp|1{$l!57 zv4jvaa0b_~oV*L}GF^)*VY+}RptUn2ihC(ES&WM~G_^6kN_p3gqMI3q_y$o6v?gU} zhhmKq{7@l{+a+zhg(_WLdU%CU7Y>NThj@4RPy;f;(tHaAcE%{tvz6gWrC=>qz^eyf zE<(xTkWkdRr%kN10!cp$>SM-(MQULWhvn6xMatrmp8XJ_-U?Ol!g5vMS6H&-R2QxG zwJKPk4N#BM1)XCX3b>&E{rvg!uL3NSgcnSDzw z%G_}iQO9H@wj8kKBsWEwYYS&&sk|Dtv@YvNqevS{vZ64_2q~I6O+oM?4N{Xu8IcMr zG*JYTpc1@5qEbM-XeI>GUhyyNJkR;w8;7-nB#!Uzn@IWG=lpn1s+(QHVfO049i!Xs zSc3xo8eY)1$Xr@u2!O%eRe>&2vhshzgrG(Io)_?*ANMGHYhoPZ1M!yjRu?Fwg|1JT zYi{9GVEGIvfN$P=a`}SiInB@2yLazCd8mfd8^-xkfcwnYPWx1T?C}_D?wgs2YN)la z{;;F1G0#*lxC`qoDq@Ud;N)Y0a!X$BINz8`>2!uv-v3oyn!aTtFLrqn^cN zv=F7&GZMWW`93x%MZKzLytH=Ym<6UQW%*oFlW-Nh&48|2a0QV|*7o$Kd(uWBe*zvG z4UF}fo~AwRed>Xg60FXi=t-xK4OpMasbei;V`JTTbPDUJ1{y!NYOWXyqS}Ro9B}`) z(39LOvVP|?bhK-XNo(|otpeX|72-k zI&|Xj&sT1Iu{VDGT6O8@;lH-)AmcZ`xBm=ks+e82?HmrtQ51SZXzXQ^5hfSU;}L~} zB-k{KjCrT59)!0D;^h^ZRLX;e{n^f+q&HP&F`KQ=P1dWX7ldfh1fadmpj@k_uBTe` z7gn>^43)Be64d=>5z4D@UPx!^4vt%gTF0nMPvnw+eulK@7}_|#OeVveErDT$k?Z=r z)xb2t>UhFhiA%n1IiVudHIOC+&3=wq%y0Of7eWTRJRXnf_>T@`wBxFBcAUE0ud{ix zn@3j|>#0xv@QXN#?{N*}%$meLxrc@8yQNJT~rd1zM=VT>0{B6%$2X_?Xm zYns_)gYmY_h{6Un2aOOoI3Lk4Hju_;LU|meGh2Sx ze+){qiF2QEQIHTCr2E!`ZM)M6LLZnhx@j1csfYEQ)py{tvX|5eq%7*izQ zLHAw&e<$Qcz&p;t3F8waFQzEqg~9BFr@%GwO{?5NHFWjn|J-oVb z=g^63k2&i>KJI_@)%s&CtM+N^Sxyto4`|euk)t2NDKF*Q$d>0+ zqt2daY0IMn2?=5C!)j?g`&QjJ;N!j#w0!hmS}7Bw8dO%kM(H+L(6-;!Xd&0(nM7+L zw0sSCgqCj(_E60>QQA`DYD_u8Js6-(vr7zBL1U{P>QSuOb5qAF5bV z9VZ|q+2G2Ffi{Nqaa=+zX~&0ZT3l7Gi6*UJ+ApBoImAj}?uofY99Nixn^g_P&$$Y0 z86j44nB5mbEp>d?-uK!+=#0xfU7B2;?L>h3%Fn7@U8UKwv@ninLWcb z4qHO25-}I2OURHsBiLv=&dq+}E?&P_OfPNQaTbJ}85mw%sW$9sx_UOdv*$1Euk6`> zu5(_%exrKo%GFGDCB}hDul%%Yk}?*7PznxyU6%I-hD@0SSsf8{kR>ue?Oi!}B!oURGnX6s^?TmE*tKGuBd z874TJ6m++4?=#2sufyFEJ}w%8YXD*}N5;8`6Fc77$TmHVUWL+`!cs-8-l|hI?}1)( z$YIy8R9BhMGEU%e&|IhP01ZI$zwfA81#MjgxLys<1(lXUo&dOUOr} z%ZSXupMUlp$x>u#8UGDheps5g7`0d))ExN->5LW}gos%|Wi?pMY7N1psKrb!g0etf z0%lKIzofNCS{x-SN+{VvmKNZ*g4)Alp(dIVQiIPh$^h!PQ$z4$(d!Vgu+l;ymN1R& zK^orG{#>d}#)X3{(1s{g&nP}qXla(bEj55~ggt}55xwD267*v{3Yh$?R!w2K)r^9v zIfTR;c(JmZ=4jEo%kn4<856E7oI*)7%ckT|1Bsx~vq6wF;RTYlP{+a^>B1=en+pn%ba zL=P;jxPlnQA5Gqb_$ z42BscI+B*M|4#w$*tfh3tYb+Pg=SfZo7DM)sGO?VP`oi3OJH)aY?xyXRP^3Z9ODgC zFWW4Nu8DMnUsTKna?$lmV+-ikd4zA1v06OdK6_;L%-MtAdHKgTreAZ14?F$)ZU|nF z9LT1(_jY~%w}5I6oyfHiZ9qavjN3)#7};oyF2=B5I97|~4b7`%NIY4|A?tkQ)Q7{> zVdvB7x4YiJj?+#3*RS_9y&jpllx|2L-L-4`@JZ3qvDmV6ZT7vlyWZ_YHo5&qaR2Vb z*?4>&!EDre>ySgy;)AR*)5(d9)aTGDjUQG{ma4Utq4Ea`gDSsbgJ4c)e(6(O+RAt==DXQlMC$XVnd|KFtgPQB6_{W(FV5ks_n_kH zy*PR&{=G*+Z$IGW1U2dWl=JzEFUJ?wHkSirL)vAdIV{kMPM0~X& zq7iC_mj$u#oCvA~lU5#Eqng=dbuUY!8O;?YG29GyM^g}t{4O=C$kREp2sTmFwMe0k znnEXSa0*7|Fk=9pmeQG}TRb^SqhRqE(Oz0=QIeIl+ZLt;ag7x;y*>b%uT_O`qhxYI z1t#v?z#I8+mTX&mu+ZQ!Z;lCQWR*)`DYMh$IRgkmOTQEK<=FrLAOJ~3K~&cevM`+@ zT^>pBL!tJa11{M(grm$^UOE>=SP3n-Qilx_Q?940?qdMqy0uL}iUGhTF$E?wd zA0Yk95xg&WLANmQ%#jT0je**vR4lNzww53H`pdun6O)NHyK{lwg;h4_uConz^>6s{ zrv-tqu7!8=IFT#L_q>pp+IM2Yj2c{cy4Dy*w7Z3d9N~_4x^LfJ8yOP-Ur;M7^c&+` zpTB$J+QRxBF1mB*ciT7wg0q!Qp8M{TM>>6J!^5s|o!;0`>*);*PHzO@01dX%@T!HT zSIBs$;JfLyC81Rqt5ZCzMjaIjX3n6gjV=UQ`;0h7 zt(LlG4VnaTpd%*>a=(WF&NP9sJ;?4t|u%{J3M*t?j*7yEi&Gle_Qbm&@7I^esRB+xWH> zysL^ij5&+>#=zrT3Ps>fIm>daTCJd?mCOfFDVLE8E^yM5TN^_b8@Y3OU2{@mdg<+V zPHQ$cDn)8;dLftk8x>UYZ@rKl>suH%o)TVD?FNm^GqkUymZOyge1FP&yAFFXVbydX zAE_5M3d5QNGtsYCH@afIG!TqS=@l=ixZi7#Y#EVkF=|#V8X{s^DYgJxLR7sWSUsc- zu2M2IL6$+(0US&Xvoi)`^OBOcl^8B_!5IXpjd)df(N|h4uX*&0cpl@-uyB^pxSlK~ z<;6*HgJc+*3fSy2&!DlDsWF;tC6gNZmC`8gAc5`}bv~lKMd=udX?t z7Uix?A%yoNH7;~-8>*tm)E5i$7~ucRV(2c>z=d8>w}V2}L6N$+OA@R4?E{nfT;Gu1 z`ttew;K$Rf!5SWB7<%a+yH{LTK(~!FDPVRS?bG?cFv9|cA%VMT2)%Rp2Xnw3Tb3Pa zRJOb_xy$JY>?wk|MnwkLGi~d#$Oz$SqxmW><`)vmg=#_MAtwpuaz;QOIB<&XO{x0( zhtB+H`9O9yF`06f`p>SV>aAy%H@A3)KH5B0pDA`+pSg3br|*tab314DrVTGw>0+5m z)pB&7a?_0Vra3TzLwzBnt1>~UlBR_;oG;uemYc2*9iP0@X;l4W5UZOlr;bldpFGlk z`m;}F{&GBAa@~*OyJvTN-MevHx32Pc(NocEif z=*QsTG$RFc2Qln5s=iVw6flvnR$!%8AZ62 z2&i&}VkHp$ErHoYK=wkzcMOn*tD@1WsiM=UoIqU%vvQd?gSbKx7Q(hg<;igAn=v5>8gb9(dMe;^)s^9F?OM0 zB=Nb!YuZstK!FGh-fAI`)&awd5^>X3h1rBM$vn=`2_qp2Eh(l=F-BJtoTo?W$(EW{ zrgL%Jd2~D>=*zq^Rj8z#8K!0361Fv}+(_Ro$;`Y&l}S0)7t2WcnAk8TMWDv0R9l%t zW^Q#p#>Qd}R}lQ^WyJ(80ZMeXNV0KvUb5P(jD|92&Q{Bf6G%PBc#@2GQi+I#b7X5~ zUINS$8Wm0?O121WWvLWajR{lN^ zKPv4G;?L6uFWIe20_zs|Bfr(MWAUo(W8!V`#U40tw8QaZ*of|t^27D@^(!#qkhu>s z2$-hO40sFrZ}o2ar&Kr_B;V@Y|971|{Bq;y!Pc9S7k>8qyC;tyzvMl*PCqxd^Um_RrhxgY zpnlN%PMpB>1v{rux{qjGX@0O#S9Ql=pHx31=A7^A6ZQ@%YHiLppBFd_g!6-WNeKTU zOJB(o90c5!zQ5z`sXAJXMw|%1SCqe;Mz~LgBJmM)FswLkkN!{}aL1ARE|ea|B^ao5 z(E>T0EwK2AIEFJ;u3U5A*MXX;y;9|j5VY7ur^}oRYz|=PQ$X+1^wRI&_~6Z{de(LC zPZ+HmAD=sUwCAl0sq4S=mI`+-Z(IFM$L7vUr?SrUxt>|qT^k);t~uqJk-qm%Z>uA( zjKPR7mohq(y+(yJT8@ndMd246sR}Myfauu;kE)cDb<>rxbUh#3V9Qv0J4`W?NJNALT-Itb*jUk>@LKzCP}SQ7W>j)JHR$p4K?| zex!JP{YM@Z@Mv5#RDtFDepIjP=_|I@NCd9u`<5MA0~JP@)lgHYR@yampYPiUtQX}+ z6~}UXMN6o`RbRu)K_rv42Fi=V$@aI`fV72WV3BM=X~_h63N#AO{jhPY&_0R|X^z6& zttEdXf-NxvIgvfGA3;9!nx2jLYPGZH*(JzDitHKac|yIG(1nD0B2SiLqXQ9ZeFbk6 zs<+Vs-(IVjyRR`SYd}(*5bOU$F-glN$ijK;i-Cqin3btkDFsSKO{hX^?Q^9pP1uea z?UoTvqKzpzPn)b*QCucu&}~emuEKlLd#)BSaC_(g>o>BRktf2CKc5grda>OS*k+(eqC20+z(F*)07Y zkSif)WP$rEfa=zVdLSc$uptp^K8ITCxxncqQ>;J2O_ur+db84(&;AX%ELyf(t^{t@-sSF(F zIP!0y3PQs!D{a(jnWoQ2chAM+9UZ}zx?4ZebLPF?GcCKVgcRJsSf3VldI*w7mlezTj<_wisTpu@-#o{jgE zuJTzlZdKtRR!&thzQSy>wEgwdp6^Em#UyGFMogAaupdd;P=lSSFGDNxJk6il8ec2s zM84V(uU0-$zX?Xe2IRs9b;Aau6eNMy#74g%A{Ci|-6haJL6c0i!P}q#J-mg$v%3TW z!9aQUidMx-VW4<54+1Z+s|o~offq?ri}MJ$0Z%74OLax6EQOU-o)A62R*kTBv)J~% zp6C+be{5avZ&TM9MioWX8Y(Z1s!+R%U14dJ+c^<6myFtOOhHb$p@oQ`YiyiJ^Stl#KCiEg+&!cpO%Qi7bPa@?Y!vi;{isby#+%BR+kt6)D!-{y z^|PCj8V2>q;Z*WtHv)i`WOW&v?go@dx>Iz#!Vzf?L77!jxTqJ`XtLl_;3)=E>dews z9xC>UL~bDP7P?Cj+&maMcQedO)aH7C#l`}u>>7bd*kil9W4bhe6IDzj)s?t}fjNHK zP9VU#B95?lQuNYv)r?EMEdiafDv?47qH7pDDWyV5ZF&$8z(w+$&T9+b|WB*nqE)FgQ|>TP#icAZwBYJ8(vVwp5O@iaph33 z#R71j7(f<70RE2vFv77~eS{9VU3Bco94;m6|wf;VUj)z^vBB8%)uwVgr=}Z?w&~%$-!gz(5=ZT4n z6BF(J4|tuOeDA%7bL&PNV6D24-^Ob1|ZKupQJu|VQou)u&J~7$Yp?!9X)Yw!8QJsK(nQ`>A@Ni znEj9j`(6D}Ev+sby^biWC)RF}R59*61pEcUTBrrb9U3AyBianuwV->-4h`WwN4M^J z6J@|y)6-G8b&)jv|pwE=j9rdOj1!QxN}2Q2Zz>hE1_KA87yZyi0>^Ym?a zHVd=>N8$5WPQjyjJKNh9#tZE93tvXN)hK`sLKihn(H1;15>kCrNR;cjaw4Bkd|K*> zfA{sQIeC1lIkuR1X7S+I)Izp8_u1yLeUI!sx9`;hn|mHljpwEdbCn&l)5kBAp1g!a za;Ep#o~yCp5X+A<8MJ-CDgk=xGIY}D!FxP|#)sFCw@suzJCVI^ zNpd;A{btZ(vM(L^bbC2*>$%4-l`|ht{r;&`=KYzOoyQCB+dI_D4f|j<1mE!(6pLM> z+N=SyN*H!!$~DH7%d`eVmkG$d%MDaU7gB7y2yI#_Q$tif1*2&6g#dJ02(K?%0QN&W z30427rdIy=Hl2)DGls_TD}iGXMmZpmIBC-bIR*dxD1kK5@U4krO&G>i(ug~SN1HYQ zd;pw$zhj{J;BI$*C$9R6jcrs6XQh}b=w^HcMK^Wdof6^~kGHhgnD&K?G2wy$^ili3O?@4->zrwDKsU0{Cq4 zJi$uwdUAeGv9`+-%`K8Ng#z%MPDq%cbI(F(*;*CPuFipN9? zMt-Y}gv4Hou8o?UwJ*eRQB_-w@v1I5oYcbFm@X;eNr7fb>!P+;$S`xsfy4mI`huI);Bg*@6XHYS0B#L-?*`H zS^Sy>iiyM%#M%i_NVh^O=e1VInQ`Pq>n^eTtFCRs;{Jg)NcgM=LO%DeAQoW1ySlpLR(yvRNbmoKke-TgWM_#O&?*PeJbY3cCS{JOVi z*SGI1v%@inJ@A%#Gf4uY4?_`62)AKl7@_IDzR}TvZT(Z59x&ig6h3yWIW=38Mo7%? zLXIVJtF&{39vNY)q_lG2vY14(3b;3o{P5sg7Gj6?i{Kfc3IrZv{F$s*c7g&6^x_L) z>HR+$I(2I6_h-=S2%V2Cx&8Ch3!8uB?LTzx@Mv#agf+|;@Ymrmf24aCvTyu< z^2^bl=dKqrHH$RUXnvFvw+-=iLN8#bkkKu$k%8^TIGglAY*a%LZ@s}zMWm$DXn2(2 ziMhn5*@L&9dHb~;r!W1k^xE6wxu+i4@z^KLgEwzJdg$QuJ5M&R9{6U@bF)(yZZ>vS zvoB6PJXZSYc3fsWGq-o|?E-?&78q0IdO-{>3aRNvBM(V5EGScWdu>{*G3=56&^KNK za86%KBxS1+blYISWTle0%o`-SB%nZ9duon~hP814swS<=k_%xmvKwrpZ26Ocq zy}FR!pp?M^Wwv?F_GRlvf6a9 zUPo8k+1IGXSCvKz+71W#$GaK9x~5*sZ_9}MtWzaLnV#{Z@#dx<;d4Uc1P*l;in9um z;X&CpQX0pEvmviFnmaX0WQ~d9dj!XPQ&M7VnvtCfZ^jSr5Z)k)?ncS1uRBck0aBb* z_%%(_0qh}BHj(v$QKD^{k<067DROt;JP_*6hWOsO$Z#_<8f;)HJ>2i>Cu)pQoNvna zCTEJla#gjSh-qe$m8@`-0>paay(AiAfgj1rQsdh#2u>{YVh*`^DJfox3sMuUv8N(& zSZxQy1%T?A1F~cZ7RM!C%ca3-N|h=5^+<|^XePxG+0*LXm`I={MJ!q3n0jgiv6zCk z%u^U{L^CBIDY9i*iG)5Er?u{uPas$LNIwPA;24)Df!JJO4PYTM8HkF??shf1dOWhZ zn2=WyEXJ&v%Z+J$5p-37u;IWdvA81?VpRaX)oP_`Poorz6uFZ8VCOdU8$^aT1YlZG zE_YcnXrTvbU`As}g9pmJ=k4pAe|)jFZYl8U>bwKtD_7>PU}JUFA~AK*t(L~89S$?( ztibD7@LlKbe7E)0FjzKHvTXlQ&M%$Wwk!a=qKzLW&YtB}XumZ9?kk?t7s-I7-QeV; z^cCuSEVt(z8EvvT3Vut{+5$Y|ODwAgfr{%X+G4G-p@5RxmAX36n_;*$Oj z5sQbohr<|s*|OkMLwxQ3)`8I?QoEyU^xL0#<FX~y7Z$eu^5yughxRQVfAx)? z9WM=?duDFy8>OBf?AZKqhS$!&IQGyCTs3l*U{8xA4CY#8bV;)KJ}CYEXxZFAe3$`Y zX(Gt3y@}k;4^GZZqkmzlo_S?v?#-MOH=}7nLtvGc#B8y|5LaiqX0nL{CNYg#W3(VF z%Z&<9W=+=#vnc#c!9ug%pc_d!MaekbNuYEwON{)`JC z8^;E-kzlmmGs1ldZpL&FNZo;BO1zvY8Rer<{49mHH%f^KTP6%-n-CIpM+kk{kN}4_ zEa?O^5UsCL1mQ~^({rm2zx~j{#7j}kk1&6oT^Kia1l|wfwsR2?-b!QSn-H0eu|m}o zXbsri?orQ$nUx2|r5CM~8!5$$J9i1@N0Z`)A?Ao)H{gWIu8)*cCP87zVR1GJiaY>i z5E>!3>t4eUt^m4dm6*+CZ~AyV8H*Yr3wtFQ<#6D2OA1yM(4Ja!uw)0>T%EtxF9k_u z|IY9cfpcZcw0MlXJO`p)o7H+jOpmD&XHn)W#|o1bjg{2t5~?NO93agr_?isdO+b1> zz?E&DTm`!Frw8#B{vEOV4^R2=~$ps{??M1Ew~sC=zLOYv}7k8Pa)? z^n8Bp(jRYs`KPOE8yoil!ygide~teHidV^rS3(1gyT55~g9EQ&NJuc=v@8SeVxZen zZWuC`x1U)WSvs?{wmJ{_l{kK^Fbf>2xI|ygcEA&8w(#C%X$Ne#Z`l7PFT4J~D{E`( z>wjTO#PyZ6XZJk0zMRH`q3#HFla}W~a8;Cb22$Q#qeY~Ku{0U&qdz5#IMe~U6QzzG z+c&#_(qD--izQ|GzieIaYg^|T&4(1W)GK#wDGt_ZX^Tcvm0p`7Yg!W-Uu5^%mMM-< z%rz1sY8}?Q+Ual-{AJjo!7eEI;Ege`9Yfq0=EMXWT(%`?yf`C2po~Jt0%Ki1gzoRy zd(QK|@4a$k66s31y7x*3pZA>SJm>KlvmuVGN_!bL=!%(`l-6h*1y-j0Ukm|vfv|*O zlHef{UInxLeN)t%MRi8~m-mEdVDVcYv%ZVy=iaVzesOE9r@f*GajhP;AxY$hU@p@r zIT5MM8$j^t!0CO+8{dBQ_jl0f3w)DNMA*m{&_R??oG(k|cLM3ha6|hwOeCmtJ}=BT$QZO4u~ zX-k>WZK<`ySSo!_3odEf?j-frQe3em!Lk(2P(;nlN`h9F8$Sn=4aeQb7X>CJEua__ z2`y9+B>`TB?|LHch6Z&*qXt{R4ntcJwl4sIHITY)3tU@B6@>L%fogq#QWz(|p5Dn| zeza=vEO3WL9Cstc4vj=z(w8R$J~W>>PI$F$%@dcxh~kH_GPh^X6IuX|eLl085CNcM zepLr7pVcYE67UpJJ%KJ0EaBKkIo*7tU~W7xO*e)R>L>|Th()0VCj=1=w9Qw@vDTus zi@HOL;4;@IN8?jcPa;Tavs0iuWw{DqAz4e=qMj!WJ|?a0*~rvRhjDM^4AYd2AQH*d zYvYbhf&>h+IVjf=bp`3evPf%WWtywxYal&6uf0@MxFI0tOeI&48E7d{Rw(0+bH|(` z5GyQ~_GV&rutM3HHQr#n%0q(rLYoE*SMmBdUUQ&KpI_+d?A~qT5Q0_!e$ZX+?qvvv zwkRad@mKWl#!7cQ6o`>&_pee?C#4<9~`5#k%`S8rUsy1xFoBF6WhEu)cFA>Vb0 zw31Y-hXTY3ejkzuKY7YTuHHdrPIq@=9N~k(`I)a20Aq^MZ#j4g)n0nGICn{Y_7wi^ z&0W6yx67cwGH!5LCKB$=5`^cFLcO;)H;XFr^7TKxd+Kg`r__2`=Iy2QjC${3Bw(Qu z+{=7Q8qnHcj_&Opxe~dcPun0Yg4F2dj_>EiPNlt76$WmkQ40pdDu6@aGe#v5lYP+R zbR}O)w@W}}<+UMV?y$z$;eL&_cm$*!HmEx!IE;Uq0QU|3x`*;JWazGu_B*FeIL;pz zmPSVMu^Mn!IgLq39>-+ zs2(!@8KVajEVE&$&Z$F^iQxk{;SyFz)|BD&*@=z%jyrYx$l^=kp-p#sZ6eb=exW#U z>y_e}4~ABMIJz)AbZha=19!KUdX6?0tHmojQ>6=VeKitmZ@aI(&xw8je7KGilCz8{ z5Lr%1$TYJBmS7W7xvouQkb>nW&?(_q;cNf^AOJ~3K~#+0QHq9xjJR1($oRr+og_Gg z;N}#PBIV5pre<{)hO$fr?YpGI>KOGph7L1K6Sk~u1|gVD16yc~UZPna5OzH;CVtE5 zbP3rOpi9y3$SgY|Jl1-_0cxflQpFTrDehy(R9}sltFSK@h(F1=b{%OOc5<=4R*rTM z7q3kz?yzHgG*;#;nt>7m_yX+@h8Y=Pk~5`WQeXjcZIUvP$qrprj@5+)Q%%XW0}!Wy zllpm5G-!P&BVWrA0@1)VW6f2CD?8>JaRhP$QyOMyq%lzCOvSwD^ma8PWf&8e4iuF2Ufm0oG2*~O!D^=jT;Bj(c5!4nPv8@vH zzcC33uB$c%Q?wzBLjhxVz6=GL*n2hx#b?jnD{p-JpMQMw&#!>Q&+fPI;q~>E&qSPl ztU&Y;@%NFT#ZRtlGuBfiE+cLWfmnxo^FJB9*VYXHUMKXz_B_YR?{$s6Uw&ybFV)@U zSxC^By)>(~X6FRDU|?TiA_bbd>6R8Q9&}IMyjbjC#4$JBzO^$0FTK8U>r(iG{_{&8{ruIp zjv%dKX{@+<U_!3tSe$8oJSwP-*aF^+)ixOwPBU021Q<;l1(9L9}JB`vg; z;#Q=%?MawrD=Tb4S>AY2B{gorl08aVgLPx_vD+fl0wN8X#@-pWsJ})-_N<;8hE{C0 zyw-K&1e4eq5z&&Cgk1~KVQ6o>I4m0~YC%wc1kdB1aw%Ty^aA2uM2Cf$V{b2vqrM2! zvh9TtJCEIy+uLj8UY=QEc%E5q#02ozBF2l3fqPG@1s3Toi0kk8fD^L_>9*9I?eqaE zUF#rXXsuPcXXt#s#`axMIE{x%)00D>>agvv4vo%9c|NHjENN=M3WGXCo0SX(2BfVQHxxj>Lsy*fq-8q8N*R#2KX zZ4QX7;K5?KQasl@gKMa+s0U+e3-#aXnA*Z!b^PTkizv8)adz*k0e4e_#=zWirvji( zx~1_{=b-wTnc3alRW~y;^Ya49!imq$Ke+ec+wX|PkDfgy5U;Edg>R4#e}3cYjo;mW zhC=Zk5m@~rC4Ta>6Z3!>f&m>mpBmil+MSQeli>LiFXVp8l}>WP?)}dwZFF1(lt1fH8J~#cxQ{ZG4O&!FYNw zedSza!a8kk2~SfOcF1@sDEsL6g#)?cK?_d zn(46u(rSzI)U@Wo25qOO`G9*&>sN+<#$gO_LYI5Hwhn%>w)NKwtGByG{DKAGPS$

X_suugRzAK*EZm_xw+(3{;Mlu%_iQ{k~1%y5a@>2XQOkir@ z@dAinA*JvcG=ZF#O}C&8h123q9|D z5Wai7kxFIOK6~e8;?C&FRdwnQS4-Y6j~#r2D*{e&Age^UB}%vo?MTW43rXAD*< zbKEa9)tj4Y!J!y>vj*W^9hnOeECu`q%gHIljuU=uLZ(L)I0dR%=P1L~L&*U*vKob^ zJ{lvlQOQ(`#UfpXrTyKlw%Qtot@YBl2dQNDuvQ=vxrpW(8992lh`IaaWnr!Iju!0F zknFi`j2xORBPT~yVhd27I-chW4r*ZY zRHX6Z0ahqY(K0C&PdK0g1}%2z{#j;CY92@bFr-??R$fiH7CNf-8$~5rVTDO)6N(_J zL)Uz9(yExHM4U#Bqt-l=U-=Fs<$E@DBB%gc|rH{|^^?JUZudQLuq73`$6+v36Y8}1RUPAchG<~ho zt&=Lnty!Ty15VN-jRxh3-JA_|)COp-3^PCl?)nHhGcXihDzG70D#|3FxfzV!Y`hka z9+bqbuLp{lyFT1jBy>}O9`E%7*1tutYLwN^kwHp`x5c%yhG2~)ZtaT3c3v!zn3w3>_&h*wwF=ua;~Vq)>y z?BL(fVfZ{88G-gt<;OR*9sVI{NK`g5hy>e}1$ z_a0rAAZYEU*1=m?xpYYc@cTCqK7En{wtg=XSd$pSmzNJqP5LH(brXva9}J*uQCsGH zPoi|kC3rG9UdrmpB$bc1o5^BM+vbp=`jw+l(kz-6(^Q%K!z^bVaavAVNs&l?Lw-f}^*p#S>k zmD%zb>DofM?(`xhXo=pCI4s=@M*kPTCMPC_`_{F7M~qlowy!kO>Ar+M!qkL-N%*YN zd8a>UI?fDYv52^NmxG`xXaz%)=26ncwgoTGxmh4LAr0Q*#8CY@6MtsusB^V*=&I|s z`adhax?_c2&+|vG?>RL0%Kn8Hi@(@EwXpcpMF4o=J3F5`>g3OFe(SAbacAe;OcO{4 zGt-GilWWbG@8NNvW`kD~qUhaf&3N!!(|3bLnpZVQptZXVc+O+ZF$8j&Hyt-YQA{$C zu5Egd@Lq)t?S$O|T^W}2HRt@~HoEGNtxsqjH~Ss}LHH4^It zSZAE)7%Z?I@5=D;)PZpLwY_g-SjA|heItEK@jBa%p-k?KmW@Lp8*QD28qA%gm}B0hPH$nP<@| zG;$v1QG(mH$Xxq$3}2=6@ieVfCOlt*Z$`U{Tq&5R)Yky|dCl3|H%VTD((kc(aS<<8 z+m`25Tfgh3%pTR>ILHQHj{r+0Hf{x^FqL6>A;sP-G4R%Wokn3KvbOqyDw~OMTgCNc zfSn8dN&#nYh=k@i4Jbhrw`+ccX(iXor%x3*RoIkK0yrDq51xu{ux1 zXX%jLAC1Bk9>Tn zk_;vh{0`=TWz<&`@K;6w-{#dout6tFSzcLK8qb!-*)xqrNwPGslq3w7#!E3B@CR6LGY_MtAuw%QGR?!b}<+y zHRov&d$H@`eG`0niT%(gNf?tHKJo6mCwTqRP3U1r;G2k^zKbO4GrWN5!L(SOF#w$` zNgfuz3q1bJ{;OC_lDW!Uh0YdGg8s3!KU+i{K5}UI32#)8Hn2u2#*Fm(g|V^8Nho3t zpkz)%{jwRFB{EUldtsN9oV(ioEavA9Yu>H_Fn#KDLmAv<9HSWht3@Izonir6cI5|4 zmC0Go+^9rc(6eO>AWh6lw-~X|6S9|ZRs)#Fkc`9IG`jV|i6h1BE8tAO<<|R&hTC8< z386>~Bz1@$sv`qAX?K7QD!0?melU+%Trj+Tbo;&alGYt z`<#2esye3x0CwyLs91e*V1!2cO-(>D;nA{|ZXIQg5W#Q`te!NUW|)1-dnGS%AAWinorm;o5vm)q z!w}74GN)y(5HhMg z@|q%-8hCa3Oy#9XwL84n2%lTtPG#PmNbOzssWXk8nk|8lw>e{C4n*3@G5O7q z@gbd^p#wDZV+FlAbas8|_7Y=B%la&GiO(`pRISzG2kEX=_E`B<)SF4~LN(X43A$zq z&-ey(CI-jPEnwFVLC2V|zWwjFqJUvY=AUy^WfBG@LL)2ULQFfQ#6JxXBf^S63@IHm z_37R^N!+`=_OEX~{}P(`j{;&6#B9_;v-s9$Jdey8I2kL9*VC)3*|quJ-~V#)3_d(G$`F z9%Ba61GsNYZ1%p(zN=l`ylh56~k56&BWPv-p=QnL! z*@34lmz%Z(on^^eC_u| zNH?MA8d&t}^yz+Sm&B>(HuJ4!pLh4UeKbj-M-yyXuDj^D4(GbpAQID48(;ot@q?*X z+Iy}h7IJUR4HL(TW7uxSak=02gm&bBDg$9)7yqesjYX`pvN%!F=ky7lQ+rOpc?%NUF< zCrfm3cE2}1(JJ)H^Yi!bNB=#~kL|}aQY)R8C4^YVK#2F4@D7he!vaocMb`lhRKEua zukIrFD$g_0aH#Ph(!h0wkNI=a0a1fN6$;jf7`5i%wzc6JvMJkGRT&kLyAe1<_#IJW zrXw0@sH&05a>lA>Wp!#uJB#bg2z4#wjLI}bi{h4^s%Q_`&L~sZwM>kX*79~ZT&~J!^4>83@-qb;T_*vWQZ$sL_ufBXmdxt5C{=n)M!`s%~eGW^NcN?^Th-B zt%~hvXyu=#js@4Ze)Lrc9|fGz+ETR+w^eHV9eBEKP-B74g&s(*jMI z;T^MrPbOe<;Ti!gHKp2{8*RNBr*ZgG+0F;1zZ3T(rCePr*4z2y%OEs7)dCZ8v6cJN zGR(tk4*VbtodU`=jsxG=tOB`)NJS=(=zhK=U5&(91%l)p0WyGimFtoqe3^kDzE+hd z5b+*xeg;mp#yJ}BRIv_*w5{>2uv`Ub_r{61nDoVOqHz_sRDpSb7C%NEx{3-kI80hN zIEaFD>fAz%9nK}QjNw0j&;TCC3@kB~{vX79`QX$laBKzXUIaA4n1wY4S-rFY#p5J2 za+bTqrDT#Jj5hH)60fe^{^sH5Uw(1#9)_6CUgq-jt!rWiLpv7uoBn5PZF03Ye(%vm zmcIns2bZG6mEh?=JqQ6D*+vY<)(ty>{2Q@QLkORd=;;TyIeCMZ5GD)by!9BBXxN`o zi7sF)iPV0XP0}37F?;Ix|Lc$*<|xW5*oK4@EU`iJ=n-O`xd=TyJy|C1lF+Tl2yjJP zrYFptus7|#u~(qG*YLL6!Mu^MSo*-7u5eh7AdxcebWnxvzWMr5p6lfugR^6&pLq7A z*M2!XR-UZqZ4d{ri#15I69p2%W84Lv74-`(JO%(8_8zfU85+pyrIkGK1`BXGbpxy; z2&cVDg6V=uAD6e=a-W#JMQ(GD$m51YBk$xJB77SIDMSwvPIIYvV9_OT^_@?4Z~5V= zpX^q@d(JtwX+!5)B7J)9qviaz_cnj{*z^A*>-t{Y%Ij#cxKF9%q2h!|$pj}z$wMY+ zHWZnJUNdW=PD>NA;oeEe8a4$(cXXYR4GUd%K&Ha1U>6Zwy0g2ZMY@%;i2LB~4xufS z78^zod{FU45Ty7&_&MkE{S|GeGr76<=H6tW=X=iQe9q_VdpEBgeR5t9bQKv~#RJY; zK+q#(=8>?_5oQ68)+@t`4g-`;+!t-j!ZBCTAeDtf3OzuSpcxXG&0t%Ekd$ulTlG)9_>WxJ(Pg zHs-QF7o}Ug`5x8#MCr12BJ~pvROqSuIiUqB(GM!tl5d)17qnQB76?tI+>Wsc%%!pKY#{_h(O^+KE%_nGZe!=Szw*6J9jzeHT3>s0?{s`-W96Q3 z@_aZCm~FqD$xufumi%3!Bn>89FC3QK(qij>Xs~RZ{qDz=tma**MX5%M(N3~k^ z@N3_Hb(lT6C%bCrFWp>y`Q>%N?P5)kOwNRyyw03SboU%&4^U~Y!EKyH%vCWv9t+0i z*(`-=!Ik_-(=&>e^;RGp7n_3tTyh0jl5|csPdX>}Pcrk?bUr_sYmIlF63UCO{mo8m zT88akp0r-W-QB@8jo>KeyJ&Al`qu#*RbyFeVAcZa&jR;|uavtR7Mr#4h{8Sm)I->$ z$I#;|#cp=>@bl?c!WP)56qaj^mg{xNQWQ$XQRFzQS3^sS_8$)>6JK(bmuZ;);DfSe zG+D&U$bm_~W(})sgi>-qYVAE3V2do{^t>~2d@__@^(qFi^%53a8y5J@r6aw(L+Z%r z!zwTPg#u4)_)V`!^UmzMDcPfVuDg=GhMrh*0PP8OBVgyYoNV4%$%3%EivJwU9pX3H zPzhmDYM2#4De~8u7=mqnho_7y*cy=7@3OMIFzUT;B|ET;+s zM$HoqN2~$=^>_b%?V0HVW;C;o2ZSUHN}I~nb2_m;MXMCTD$B4Fw~$r=VVd+6m0})% zS%xi+dcYGxi~+^7eKk*qNIbj$kIQQ~SM}$X0N_$>cE2;*Pd$C|5Du<~Z$Cutv?hBT zlMwshX>MpRhek}}5DsoQMs}qIU*>RW2W;k#l^E24P{p zxpF4g!7wCQRjl3k(N@?69K=@a9Db&y-mXp`ya1?enieCJgqJ{p2VIT}?!y0!KBcZD z$|xDHe%aWYcT`&D)|DMrfK_}}D3(8XZhM>mE&_iAk$-p&`ZMS+@~t|9n;(7lwB9qwKvG+eZgulx!={?>+ac=iWW4 zH7moP-8^3dO3}Yn1mcgGeOXh@8LYNh84aN^W2Dl!+te5g7MmHsQ9+L|Y}w-h+o9Op zTN_~_LVm1s0xzu9>rgxjos*Nf{R4#EpVv z;cAXi>upxl7mhMHooW!ki+4D-n1GEOO4*4S#qv4fgv)!UdoN6)pi;YFy*1je<6@=2 z_B)9jCtTpQmK_GHv*gQ*k)yMdMZ67orxQdCO^%{K^({3VueEg3bHho%{u)szHHT_$ z!-10HyzWuMp|O1;I5pCkN}Hm+*9lOuXe@PzY2E5A;R=P9l(yCQGmx{kwVs`kKY4CGwahzz-* zWoo=^6pCH@uc6l~x7g2XnvtD$?ouwyTEhT*qREd+Wm#s`8z)%Ot&Gp7m!^8Gfy}Wv zn>|74TMWq{j)KG{#9D$fn~3^2xv#I@?sJ&09Mxv!HdYC`f6Fu@3B&EFRGn1u5Q7E{ z-~xxicF&+WxSu{l;kg&%s2*C7(2cZw<9WtWWRw9vd++`CU;EFqXJo+4p-}A^4_Y~e zV&G|+Q-WCk&1AG}+M*E)4r!no!5Y8}nHtm>I(8X!Sq>5upUtN9YlZT3Da3!#9NiqX`N58{qSq9LE87Tok2azJW=2`|!6*1v3W;qkg+)GBAG(;EJx- zIVM;WD3{P7EU+sKj6mEKGMxXSE$qq<0apXJl$p1;mHqPj#Vdedda=lWvGZHsxYj`m z7WpsJD4|5JZ5FzGs>SC2k@ z=N#x`9*w+Ar^*Vz7xRNW4aI_*wWe_vbM#-4gB@x}bSw_?7>b~@m%GQD$~(&5DGss& z%uJ$L`T+9~gdYnlUP=L74eZWY;B{N`I(YBy+&l@@X8&Zqt7}HPaGX}o!Qy3eHsRwM z3aDZ@p&%>^<)a$&!Q^h3ztzl+hIx`-Bx~_T8@JU&F(aU~*52d#XrrKn z>Nu6Jn?{!Jni6CPu1dOP%kAm_03ZNKL_t(6&@G^@BXZtStnlfd@Bkcn_*eiyBFO@l zP8rx_BU zSqBw)V$ydO=eQcDoukUYuThe9V1W&mB3>p*;*D5+b#k-Fsx~U^#_eg=2B_;Y(=d4N z{R9S~5I-$C(R5)RaaGYpnBw#Z+(^uq91H0Qio|yPyl{W{t#_ER(Gpq<0RH*wZ+!EO*MIp; z09fz`@f0acBS20^ro}+03^S9M%9H$-*4oY_QK8!M4aM~IP$e@0Id z-aiAea%(rfwB@rXw|oV7>*~eB-&^IGPH3iGHFf4up$l!gfCvu2Z&STk*j>-+5#= zp@OzpJPsx3ReC}1GBp^}N{k|`2_tSd+r8Qcb2S$6ARM~fmo9(%?7bF4=ApSF=1_(O zqFZjaG+hB>t`^}Ce9%B`8dI>{4h*6bmVjIIgcJ)3rUu>IhHM&91sE&F^seQo=jqsC z@w!FQ+e)ShsV@@`EbGQ_ljV|d#Y|^#V=gg>#8NN%u^qcY0P)>tYD70_$cY^bi!ha> z(Z;k>6Q~W3L;SfW9QdT?wg%33=F`JauaV#B&k?-@wZ--Pfp!>(2Jr;^j<{R(LJ6M3)fI)oXdO=|@T?<3Z3NjCtwl+-FW#oK4>! zZsL>dRg6NeKW)CukmZ#H7X@4u9F5-@aMj5DlNK9KnmxuEPq9sWqhakJ5-_8?OjvT5 z=n&b**TGj4KH|QvO#IQVZ|&C`>;dQAc##!ZuYSrkuGV#1wRL(f&tqp~jSNuZsKOax zIN~WX;Ucil&D;&nx~6Lsf~#{zo4F3`6r9DW=9_-_r+x&cjZW#;Z?OWCwfU*+0@NYE3SHI<`22}WQdeX z0tB-RL%nui21_d`E3=17FrT3IoQo2gvqr%73E_6QlCc4-#}11j`o8!HCk-b<^nzEi zbJuTH=sZ!89`Kj{|LV8TpFgJv3jiqzfprc7BQ0o^lfjT#QF8^4ETArlF~)?E+c0o5 zw74oO&#T<3Q`PhUSiCCNL+-*lw+7U0NxK={WqU$xTbS{K?^>EeM>Bu zU>cw1U(>LHELCIU$g%MV?7msv@l4e2HOTl%NOngd`|g2H0k9FqrQ8U_fp=AO(gN3pou` zY_T5Ac4~#gOBQ{>u2I1TgNA&IrEH-1s`Q3Yw`NIufL1HR|LkiHR%_kE`2V}Z!@swG z@!9|W{lP!~fha`a@H_8_yVf0!GFfKKFeVsXary|_=_eM1A3yxv-6tN19}5aUJ05_+ ziwh+kIb=Zq(u-xq`Uoajl8w|GS(ZQQHLss>gGWIeERPIxz+38dr6CLOofLmcRG~+^ z7L+;SG9GILL$f(9w@84|25!8feP33cwe!1ku&2^zf!;l#zji}m`am8#@7>(Bm}{{Y zt=-1Ef4F&m)Pkz`j{GviaI1NH?t9ypE}b3-zP$0%j}}l^rF3j; zarnn_yv5W)V?w>rblYOl420IAUCD^T1*UW{h`XI|m!*e`29grGVx`O}9LTi*kd_zE zAWgDBoR*DoYWHzw*fLtc7GAMo;S@7GI2HRkGqPG>pv?B9F0n{rk8q1=YVkKo(o_g4 zZ75s&ji$iwwG*|~Q0VnPoSgVAQD4PwZ)CvZpDa4Cl5TN+c!8q2W#zNfu0KG>8~aHK zh;3o~2=`OcFFL`j=rINgvt7N$la!FGRtP3Wh%bqwt@?4=T z*YRwO&*n7Lz&aw_axNmNi8APdON`tl-V3hYk|!xf*3xkm`GYM9S*A;07jXaG?ye=#(yPr5QxhTu=IkJ4Fi!^ z+>T*3tlpp#7K*~70Kim146!{Mes}m3+R{_UB6oAY;8q2GZ^x^ zbXmpb0^`N&J&LOd&FceT`ha@rdgTEon^u_$+#U~JYCCNQ{KDhYH|A?t1Te~0s@Lcu#Ke&Fcg*d|1z<}G#KcWXEgBWT(&i_gv@NVsD z-!*(Md7YUygQ0?c^&{Xcunmzuo$XX22pY`JZA?*QwwOZ=bgQxGipMe7>H^ZE7QG>P z3{v~-#_VW@?1TLU=xrs7?w7FRqRsQPOV)|0;Dk;g;&;`sl(RKUn#-S%|fqG zn}2IB)`vs6GQ!Pyq#%AlaywTRXFRgH*&MC6o~|Ls-Pl-#qr5L?Ju!!?8 z01*W(vOIT29z?(%@0>GZE;?VOioS_DA>bFz!lKabZU~^)hA-HyT4&_BD*!vyw0K6T zuE|1^6I99c4~B1Zl{wS5f;JhfI#V_#Vq{6wRi6yeZjqdFchz-l$=EY@WdPx=styUU z7t2y{E(w8|P+yTyPXL`3d2@7W^IV$6B5y|PH=F2iQKkeolh_5Ssw}9&R3l%>=yrvJ z2-58M4yE7>KAo+&^0VC>7AQmKH*OMk2CM6%Q)5UpMINB#TOUx`++$A{ytP7i4rvji zZ(C>E6o894U{K^b(YgX8g{g9dDrgW}Y5byS4Wr8uy3cj~!7b=DD(m8f0RXQPs~@Of zOQBe$FvrIiJ_iyzhb@b{C{4c=Lop;BY#a$bP2FEZ0@gN(PmyM>xF&^9G3mug2z2u=aO z(%q%BN}%}4&J|_8>F1}f7cM@Ml zsPEE)lA0?jpGA8m357Mg$uXojaMAI6K4-r5F+01^PR(YC#lfVp-vj zTWDCQ32ge1vNRhAS-1I7VvJyEA2!?ePw749yZ6o=Maeq$NE%6g*fZyR=R2pnO8c~6 zJK)@(PIJYnTfklQ`@)19mil>P+MG?Xn1rUlI9@$cuZ>QluJ2=>tT4VQw3i-f3|+AY z6yq)R=l-dTfdzn1j0;OE(Yq%V1-#;XJ~`P{fV?yVp65GVOsw%ix^jN@7Gll0HO*)A zqqU}Rs;N({E-jiUB4l!>qRZ2k`b^9wfeyWT`)k$ng`HSON@xIfIAg(hqtMlQWjb8& zJ;RwJXPO$7-NN<>#sAzR8B2!6#B^H&f#XGv92?ZO!*91O9$D!*bdR_WsVFKBV(~h{ zF1HJ&Y3Qe+vn7-^JTxqTG%Dd^Xh7D1SPS6_(j%7!N6x5NzrDyo^fLH6*9h(vL}afD z?7Oiqi6^v+v)Xqgzw35b7SyBi*WwBWCq0vzF|06CU2O*gF*bU$BKE4LLyS|M^u&}V z=(Gk~HHHbJ{r1L&0pqiFl}NUM<#@IsASk-B$!<(ZR#R(dCdQ9#8!o|4mT6N>YHfwz zYjMhl+E<+l&=Rr7Wa)U%8>ysXC~yQ(%?!tdU71XmbYF(Irlu%m?9?H3=9&g)3}W@P zw?=RsCODfG!O3(JNp2Q~Ee}!HtZ=i&EUN^W&Oqrg5OrKlsL;2{|~t~xLjxE%sy zlWKKLzB^P822?9N=C=uEz(7%mzAH;fSQQr4vmF=QG+;^<=A%J{;Twodt~ZFkq{UFH z8D~Ltd7ZHq91+ulwZb%MtPhhC;}lZv0G5msuXB`49LL?g6((=3^L!`+4EkiFPl3gI z^YTFM@xT6a;nhDM{rly!=l`H%`eUt3fBZ*_#2+4idW9^uV4Suw`#w7v--hW5U&<4 zXbyj2!ov6$SgoU>>jK8!t_Ub-e2IiapkS zS)a~P>gai=-s#*(BEh+LCizjTyXpG`L9|4)&=(9XTbg=vMpcrZYbO{|L?%sd-T?s5 zjRz|@>2Vr-Vl-!R-(9_XG~er$6=-!V-L*}i(c)y?K4-old66eYl@Wx{0v zIC{Jp@6-1@Y2^sWQoJ~BstXaHM7i6&^=5M3k&z4Z6icw)TPd4%3x81PSdYyXOSJ9S zc?#7yvL+#oRPtgaWjHE^v<3+ab+$m%5|$LyI4Y^IkwrfNCcspl6Ct_wu!7nu zjtT8e$c)E0Si60|NMr!*QXjA+QuU;gPYRQe9mUKjP*z%*dkAqPuEI_%ytTpkFR)bt zEU|_JnYyPlIG!r{Yv^h^Vde<${7IJSUO*?bC!GvlelvW(FkM}CFj!1jZ#)!F5rUnY-7exUKdr3D(51ZWIIV-nCTj`LZrzOZ)4^KdES z)#I&P-A)&s#bROoPbly5*1NCuaY5 zPa*G~)|+>6U{`!sWXI&YrEGJ3Xr5mokZv;g8sN%?Lv@L<4?!Lur7PXP(3)q)HV(jL zlT-}IR=-Zj*5_`1Gc)1BMt*hXwARuTZI?Gs?F@67{f2IagyGSJkJq&XMb@+Il110* zR1m+?(@7KJ!_L3gnw(qL^ltKXq0H=j%nLJNC zN@ol8I5kEqPFbP7rg{xnFY1g90nUtx3!6SQNo?X;EpwoNt}41VSqcQ~f3 zoB(lADmdiU5x>97#b0`x39#s1P+(iFR>6GL(cv&vN7VP~r(ve}?+}QbeQ?m=^tQ27 zN2maJWksrw07~MRf_equT+p$Cc;5dcS76vBj;>r`Le{f@Z=cD>puReQ( ztjp)e_wRkk+-U{Gcda)4?5H6hd?c+40W+|8Ik7Il%!n-63r=Dzwxdd7cy`ap%bEm=<6i5WUs$yKgIi9SHDp`-omEhYxGsJGiF7 z7w{_t_}Y6HfBJh5(a%@|R!DsCN_)^?Sas3^ClK@Cb1%_e!k@+Mcbo_u(ozOVz$`kxqM5}%DDUPVsUPvps(Tbz+d{mf=U#Fr=l5kiyN)Rk?1u@E#%xN3d`t7l##gcH5l*J1^+|q;b>GUo!)?zA9H+whwiY zxh)@6f6{j3((bm)al>VNFMqn%nQ#gF9iVk5(aYB(=CNlaT|%6|;x7X0t650oyi=56 zx}&7mhca-YGb-4Vz_2F;fJv%r{b(tYCR-!#QWh3knaQ*?W5uovW^vb9X{Bc=khq{~ zVpmFKDYjPASSU1`ZYK_qGtFOXOpU4uH>JSLogiKk5Z>gXAd!$rvg1R&F{FiN&S=FD z4Ui;@Plbqz@2bX8twriIp%6YErX1d8T<6seDe&WjZYsbscaLOkm!oEIMt`x(w)eFSyg%&_LPo<&5 zFIO1j!CoTCi{vr&eGgkhcvsS~=c&6M>oKvlZ0+qn-h1MGb@0CjpWJ-;{KftISR}qn z9(?b4&i(~j$O2A!SqEGh1j^Iw>+VAg^%z23ib=Ca$=ceTLa?4w5rex|hww_Ge% zUe0PHR1i{vwsT^}RCY`c1AdO1-%xOS@y5W_myPvmAW%HG=1hJE?-6?k1muf9c~_BN z{23`c{p@=;E@rnM{os@On%{Kl2N4bG(mFVMb02vd&3vL^7ZnJ|tppH*B{O3KvB_~O&J{K(eBDA;r-EE> z0`I3zh zw^kJ_ujY6!@lliO$(#RY>v~?>$nR*_(wnrX5U4~IRBxjeGcA!Al%Os4kf|0%S!A!J zN`odERMbpKj7c%ug06w!i*o6y5S*TR3GJn2bLb`@LZD?^gqZ6>+r9Un==Z(PcfRu- zIcBkC{hE;%^5(tI`@BczHi{$?XLM08Ju`D-Ig-^R%Mx8I_R53m$0hg<)Y3lW=hQ{V{pa`oLvy8iw>+N$2h0srymYat(8|%igS{B zS{SC9$Blir*XtD=$y&&EdzR>&v9nVfoXzz0G}nABA-Ml^=u^7q_KdO8AiJ94$$Fu*WHCxoAnl{u|7_IFdWSl-BYsMt9MoqJ(?|j$ zMP81~ZZ2u0QTRHCjJ zsS!elE_35399|-AQs}M1T8x}A^DP6L)mJnG^(_kkm&;-0#dDx3T+X|Fz*LhPQixRR zdu%OK7)k=$rXCHtC_ZT|GIMGyPGW7624nT0DHEX;Wp1!MNw_ksuxb~ULt@X!RLuti-m=uX4}BfeOd{{HX(euGZLufBTs z?%kh`$(Gpw03ZNKL_t*k(Ji6uMp7na514^qicuqMqy$ObV=*B@u;|umKKt$c`&WI? zz~N7ye1U;3=e}KCI!KUZ{G?)a)zM(A%NQ6^*_Fp(%NnC?w%T<*)~mjH(FhAjT74Fo z`DAip^yrhvlL^_c{<{0)IjmIemWO2LS3mgnpMNqefAqIjE4C$QuPLC5W?PmJDze$k z3W8hJr#)kVHX^k7`K#XVzpRVOi%vmWkN3FHGneSAj%lxZION_giWgAvx8l-} zB7TPl9DYKRt}hm=WL%Z5zwWrT?P9br+NRsIlk)3Py1Lovj?*+aJ5Ci`Et237A9#?S zZ!G{m0Ifvp0{4s@iO}lK75XBQY7bk;F`I~;1&e|inF$;BC|@`t`>k!-%TZ&re!JP! zmKXj0vesB`mKbyFFkpe@-z+bJeRW=k3UbkZG-osLTt0aWTUoHcArX~Dv_&QulR?;a z=*XXNQKthuIDY!Uy<5Jq2Im=tzLgSX7FZ43S$NwM8ZBBg}NJe650%lSl5CSWsInSLjr=}ZW;&XNKgGb&Pw{VMDj ziiD}M-H)&+g@BRl1L3ZUAhSr%!mFoK04D|Ip>zg@;6i*>M#yn-M~m?L0nno!Kk<-?rD*oJ>nZzY-Paf zi7lEgXlT%!0k`QuF3Cigj4&jiydcXWq z@w|Gnz(Nq3{pvTtZsWO=BnhLY5~fFX6t7*OmH<&zD}{9|P6`+Zz3Qxx!m(l(eYI6< zSGNOztfIE7!DhQnZ+6p1=V^M>-KOL8=;m0#Zs+VMT_`G?5S1Z7=Ky@+o!?*%RU9nX zJlMgQwVu$B3>mz`-r-f9*oV{Gn=_qxUJnKt@!f3u3Tc;{wzpYs8l}<3^VB6=X}Rf_ zM(fhsrME`EW}cXOL77F}5gZ?`2&6$$Phw|*1tSMeti6|u7}n+lhHPlmFo-FxFGjOY zAjy>VMR0fsk93kK2K@0Sw>14bE!u_)3#UDaMY8bo)E+_d?$aHwP|lzH;>hyKPv0J9 z7I>e(8fNMR=en0;TL-x%v`6}N&i=LZ7ykBJS*{y3#jv#1pkCltDrYl}_ zWV1CZ85O#+mMb%nrn!ibkdTe=`xR|{B03`mSwvmzv`$eZq;=^E-Am$Bp6aeX*-M&5 zdi{vVJY|ak;d98*EU=XtcElrxdN~)aCk&4TeWlOu4rw{fQK1A*i8@`G0^1bfu9UNd zAl|}6{5?CMrgi-L6qf)b6yUE0kV9nS@{wxM+$ne^IMkp2kTXL5PI=U>;V&K z(QC9LK?@WScd;j16NfWU5(2Q!lJrQ6q2AWkZ5iUy7u}{P-ES~a3h~d}xz$276R>KU zY1U+WiM70a4f-Xs_MoX6mzfc`2vz2zbVzAPC6(}#sm;_0Lg^+}sAe*PZviysf~J$WOpW|{NC|4eH$ z{6n&p)FR(xWs>?W(34*#W~sa4X7vCjtjCkbC!g!V@5zY~qOFx?6*TK#%fF@Af7a`4uPNFb}B-5eENOa$h%wt!3itu7d7As5vJCgVwdvO)mcO0a* zQ~Z}UH=|~%81ONEZI078-B*7gg~MlOXx7XAyUh!G#==MZmU2huV5wHm;!0)19Th=E2KEmYY{~2hK5d z8t`lCA?O_p%dmcgD=-4K>!wpxd`kz;$;o zMtbfwnW-Wj5i~OM5knm%(u&zwX0dc2>+Zae{8tL%L4BtciI@mOf+wxNLT>31mc{|S zbc7xPinbieN@D>DE>RmCc_zc%EH9GPxFOepaKu@Zamyi9avZsmv1b_;OIC&WrYKc2 z)=>@=N>-JI^{H+f8bb4>WIWS}RlFB)TA}lp@QBWYkhde@#_IisjFlv(1u9SJh2nXD zESK49gk7R=8tU{aaO^S|t2m&^aYJz9awxrm{7K)HByEIzDwOCl0Jp53IJ{RD?#nxg z#5488=-G4fNBkor0Q~j;{+jgx1A@4w!#X7KCH0Z+%+L&-KPh}w0TftlzpqoZ+EkkX zte686=d^L!V@Crl&}?l$8kOF6>NgtF_`s1e%wI%Z=+6y_tOUq1Dw=+VF=dnU*eIa#m(b`ww z?!+%?xkAEp;vgy-iCqcCvIzHBbeKO0fS#*g{!iESytr}SQMV+Qb`%8FK>{s8U{PFM zBnHJ+!8`4shLMZ1Sc6tbp6OCimECq}6WYUG3&wkpFTSMEuH7E1Qhds#si~L-?54z> zEDk*cmlR6Q{TKRu@ALi6d`EH?@2)hOUy_aA_r1^iyiaezh>)N&9AaIzQLDhw*+#9e z!bJVsNf4kKD!8qA&L(j}FX<$WS|?NwCQ0IWo3r6P4AyL%-5a*A*6WhIMFn16RDC4s zT8m&2b6#<8y<%^aT0F$P{RuKinnwzW5%+~QV60W3CoFnzpTBYICsv$8ZYQ<`XiPk`mdj%Ql?;uUhRd>%hZ!uvu>$n@ z%D@6C;tIS0fGI^^*B&b-K+Sb85b5=FrpL@v^NzHT%+Ul9Bcteh0!fYNT+*K7smR&c z6ng?(By$xE&>QfbQ|hK8N~Rx3491M97-P!a=+ytVRbdvT zX^nzynL_$>dNJoOD#8R*^^hwGp}ZHo5L<+1sN6DnV=P>{gniLO#6f~3MmX~#K0ZYMM_7lTv1vD7%;dOY zjiS$*LN_C)Y493yml_E-?kAdV+h7J>URfB_veeZ3`M$#*nT+a(<@}+c+P_ z;Dmx8bu-745MtKfC*tYkR0e{dxap4Ab`G# z%H~S_s4rKDeqOc(m=r9c4$L6wU<3wynWhR?-$rkd^L%u9`8>XS7f&Xat62T)_XBLe z$23{)!G#44`tqJOBmc5>auX3#D@Ar!0N8qS+3W4!Z0{?Ax#S?g^{R>dsePH=5JRJG zHsfA>((&l5_rf$mNhEPluy~#{hDk^L)hD&?sGBNKcEU96RBK)*dHVF}I#Dbba`fhG zv)KfvZ8SY2t-2i}QL;Z#P}_{bw9(-lunP&7h3buUfcmjecd%I0_d%GK@Pjc!()Or0^)E$f4-NHT=6EkpD!0|8ra{U6D&B2g*XS%3Wzy4V%&`TL^wg?jFCuc+h=f?87P&jn8njV>^P^-x-e( z0#9)}n#t&0n5(Cp%PWLdT}|7MBbihbl@t$Vxmvo7F36`#B-K-{1{844W(?B6VfZuF zCESQMDh06k4B1&U2dJX>TY|VuoSjl=X8MM-BaQhGAS`Sc-}8qLF#4c|DYzPde=h)> z0Ee8e){;?c4ZECHz>Xvi6@)d}VX_9rTsG>G4YR`Q!QIr*?yQ;&59UwIDy(h9J6&sp zU1B^VD;t19hGU42y588#8CEz5G={+%>@Q+# zk$M-N2d}U&jZ7^K$_3v2j2j=U{w1h6F7MlR+Ot z2KzGUh$UdUvBFT7eW5&a{85XufC5FOHrg}H?60v<7#QoYu{>lS>^^7scP z_uBu;2b?Te4{pj#KscG&t0RTGFl5Dw3Qvw8y2dNmu8{T&V#q`)n3Io=kb)I7=@eFb z#T^B}9RTpPQ&_87-t&;iiz0Bf4?7k=tc3zx^@%Nm{wXb3*Dg=vGh>IU9$Z~=SVQ~h z2!N{?_IeTQx10Nl=Po%4ShwCTF%1Gv=^mU?&E>MXNm4IOyd+Fg^)FlfQb4SprlT|s zJL+kiK21|^vR+S49=v?{&lfK~{q)6uzWCzbq0=}UZj!S``v9foAYS$-z5ax{eydMP z94{B@*J`yyhca4#+xU1GOWEWELI!@ZIjYy(pY+-%4}W;e-)*k7LDaYYtM|7UZXs{6 zz%zY+7jb=eV0W5s*Kb{`PU&x7U^zt-XaPO za!#6|t>LW}zpWS!>t{P;z-&mT4Wt#}vHDV#?7daYNwU{mvv@EEWWa3EVhd%n!}7&~ zwN9|;zJA4b?L|iZ8RH3Rz*FJ4b2HMfJf|tRtovf;0*?|*S*D}7EZ7)HFx5;48&74b zu2hQIv=f!JG|aXi7Jdnkv?ND5FiLVfBrIx1$8ni$!)!AmHo_XkK3PT}3v{!=mLyi< zl!2IIpgagHn|bDVKBb5(k&gn%fX53)S45m9kfn(BJ$kyZOMa0T3 zP0l2_RHDJ2$09gS1#-0j%^)mww%Pp$B$Xg}8i0TIS(bz)HCRf=x&@fsu>#EEdX|Z~ z4myKsHEob)m=wKKv{BKgJk+mBD-!#P==`ebgpDo-FfiD1DCb2>FoUsbOt^Gtkye1* z6(9A`YslD!8d-8p7mZQS!W%AM^3u!3X!j_$rshciuB>_wVL0}?neNN#lmP!6g(mV?z_1;MNZPgorO z*Be0GUr<}7tgLIkhX7#N1O|La$_w+=p$13|mibJo@JO{fG6=s1>(u z0EXh+VgFI5CHxmPEE4qBKIk!OvbU$Has7Y8`Ml++tNx z+m@og>WZT@^hRkX4Z{@P@VHuCPu3@&zx*7i`^nu;KK|q1pZ)El|9<%4Z$EnW?Bjnt zczLjXnk1X%UcDcv8&vBW&pE?1uVG)k;YAEfHd8qe{@jbzooM?v#x_VYNWHg=R}xba zsEsG*-~N8)RJOfRwv6oiyR@~Cl{grD3A5dz&O4-Z%arTxnx|~Q%tchi?<$th*tHZ{ zUrM=^K~_U`EyQ#!HaRHbk3lZ;c#wfzUZiz-=8S;m_268QeDy~$FzN~Lr&RfZl z*OYwCm*L78GUxiVA=~;S6X(V}Qf^Dk{xq`8qy#}m);OcPwvS6HZ~QCZh^Iirv0PRB5eSS;Jh z@cPI^O~D2|HahfdOn8)Y!&Vi|gy+H)HD+^>+y?J&riT@$B!97#(3~FY#Ow ztN{7&Vd;s1IHn{;-LZsQL8%5Z6HMu_LK_lrH!4Z;hL)S=H)+>*ViI^cWX7f8=rvh2gpO2tyO;&s z;2J>I5iA(9A&CJa+7Qj7SPyQ=IKpG2KOY+!e0*Gb^giYeBIruG#lx34UM-VF-zT7IPdMlw+=N99}=E#zolM!=S@U#DE12# z`ZtfCy!Q29KSGf=$N>1B6Jq?J*AgSvNE}&w#&N}?s#OCnAhC8q|DUhxdu{8!qkGt1 zhAwm1rC6XK1ond`7#5e?p$+RYqq&lY7a}1GU8IR=b(^U{| z2uyQ5Ht1^F20}12c9v8TE89!j6vFbW!5a zuMvzlV1;4?vw=M%bfKlmH*X?0KQ_o|P`Edq9~-WVbEnbh7q9N`|Kp=CzkK@i@xzl7 z1G+DckB;{cK<6x(V^~(i*ZiO}`nnotTKE+6_a_uG*)r!h7aJtE%@NUt+6@hSaEk1tww84J4)3Uda(~IWD zDX2}jx4q)VVs-SEri5v)nz~c!jD!-jz)N9Ka23sP=qWw7qbMs9;I^Ht+O|G8fW=v9 zgqC@^6WZKnnyT$$F2H%lqM-7ZVO`##X{#$>wHrVVuKbAgdo*{oNzBa?QMFYkAOMv+ zK{774wG*Wi1X-D(UbnGP%Y&#M%kSDi?R?%uqm*={|bnUa_Y_xVNny1R%*rEBL*ZMN zK4+3lmH-pVXj7Kn!tXLv}01ZI$zY_-LS_YDyS^l8h4b~p%KX`aEtHckEo%wh8zcO5RDoF&O zH`*}Zlm+Vw0hn-nyYs!X4EUGHk2jVtd}c5WtF#3*0Q!AjUH4dR?H7k^Rp`^;R72)5gy%l02f;zn z+Y763&amPN9MntxB4@yc1Os(14WBfhERL^DT9d(K+%i14WiGL_HC~!v06g#qJ*)`h zXs#hKka>P{iS35II(at=6rOu99~X+ql z@yMX=`+t6TdUE;#scCyk6W=>9-+O@G1AQMKAKyMbK6-JAqOFsM=Ii9-^yK8>e@4H3 z??KQUUS#c4&L0iT`3E{Y!fL_TMvjlj@5vxXD1MtX5$2XSN$vXGp>U%~*>#-|i8CkMI--%Re9vL<;6 z^-E@?3F#B8d6BNn!%`^ey2)GeES+`JqgEU;MRDz=o4BiDAvwX;=$s((WZ^G*CO7pc zUUeF;69BhQuBUe89P<*+uLpB^ni9W$p0=crKc@N7Ndwl9I$US93$B!5yEG_qV%wFu zN^7$;QgJc39oo(XW>I2VD$f**Msg(6u4LDDL*_$vwet&P+YzyD$W2Uv+V%lq80`@8 zpmo#o+-Y>|3^$Z58#hqS1#0hfwRO~H)xA3JHG{>$)Q&^WY9UM;Cq5~aJ$a)gx z_6xGBl_D+z^Ctine#4%x-Lg z%I4pr!kn$sy^QVLd_GFn$Y*WUFHs#?7XUPRr6Kzo)=S!nDXtcG^QuZ>)+N`0vMLBh zor58v^^8#Kpm&sF-Ey|TGbp5(b4#=r&;IRhRqSlT<81W%f4+z9q3t;MzRwQ_5-48a^2yf#}a zw~AOz@(l|f8UVhbLWKF>RM-q$k^dTn4~W}hCNoFBBOkvQC>}5s8n4cr8(0`879=}jn>F(Cn;nv4nw!~xiuEAe}!REHx2YYvk#kY@;C4O{tdUSkh{=L{c zG)EtwKK}YfW|Nu>wMhxl8Z=_W^3V z001BWNkl2EC6R?p69&%2AJ48v!)f8rsrn{xJgX_wNnmmbQdEKSuIFTFHd zPQW(7)v9+ElA{~kly}K44JG?MF~fAdYD&2E+%#=XF(!H!tfFBcI zfSV%SV8C|%YG8oFT`dL!8yQDQRTgWiWWBT-(bY><%&9B;gRo76{|yulbh_$^CrFw* z@7PD3F=!OpZUeZDMSwfNNe3qa4tI;8Kezc(8l4^LzY17p{v(5t8=+1YG}8^0wXF2z zP&rqybpczujIxO0GU#%i+3E06qSc?aGB`jl;qrFW@u!*tYt(`q+}$DW!WVk^Zdpr4pUh#M?mi3>+?FqFmycfpWKioq6fwoDWmFrYS4K zbPZ-w<56`3ft6EVNZ=5c^CiYjnl}?DSR`m>7=wj-Wfd6RY-VSb1uf(S^y&-OyT9ie zQmZ##PKYq0IMlRIE;pMkWmFn~?(y#iS^Sor6&pOB`!TnCWp|Dc_Hvr?;`&NVdRHz- zzpkvWT)nx8Cg4D6l((+`ZTqkHDh6FkwO%pV(}uvqk+iydif04lHfP0 z-}%&Fo8hoNTWrx)R6vs+RMlK$UioJ^J7>Y{;bTt^*84{F`8Qo)TL9w=o zBBGW7U{c^=_DK-$AdMHzPjg{D^d~{teE1^+yrVKhvWAoK16xOQaea0e5}OlMXkEOsQh-G~R&ko7YnK_eUou$Hz0aO?07hge0f*!Jqc__6!u?r4oH`8xV}|BlGj_TU%QP2dDr1`o{g{;^+PxV@Fu|TN&tm zvT-5Dlb4z~@i3p+0H5Cgag>^)*9Nz4{_yIV+{NkKrD_~|7|F6z!nAkJ6cr~NdtP-q zX3Ut6h;aR&#~6@b0xa67e9<}yz0j2=|=eMPCu|~QC}}5 zIxKm3ynZj1)pc9S3uezmVwbc&(Qnbhq^U0b%nUQ`5Lmjb8R)P|-kOy{ZU9MehUH2D z7itjFT2a@6BdKo3*4&aG0$s73Lw4u@e0LhL&l!VR+J}*R(NH=@N4vM&BkGvj(XW6P z;)GIy6)V+X^8s&Z@UK|PMY9k$Y*E`6(t6dlLUPz?Fw8O3#t#n)fxn8j0L~K*I|kZ1 zuu{QD1wamUICwH1!P(KaaYK!O0A?mLBOWqz91-q@sC8S?v)HfGUUk~>1UDplwuPgS zE6Zu@2(V?fN@473TafJtht0*R1?JVp&&}2FC)*j3)7S;Q8}$L_W1|ujT1d_CJ!3%1 zb>OT7>;m#;6BI?vB`@&XT|}O2{+pc ztv%MUU@}}b(yC_Qhd=^N9{O+Wch2|y?!9uD>N>WiD_!a3+;hJ3og)~0N9lRBgaZ_I#GK5QBA_y683v$_WW zY;g=0B8zduI;bt8Hb{Zd`GW^EODlCku=Wx8!!niVGD?7orP%KxcR4&()79~~@>OWT z_}uaFZvnvZaXcR9LwlO}?(N&{{Lv_mPev!hRebx~&4x@Xyj%$Gd@YmAG(lV59 z))I9^8;AQCv*;CKVsWM9vp!-uu79%&yuH8q*!?2_EVtc#Krbn1>XDjmoI<+{@PSZmGY_yMbtiaAr_Aoyew( zvd-R=I)Qn(G1Y3i%#-fyq~tLOGC1l0(KsR~(ar*NS&le4OiqwdVJs!iM&O)x2y1oh zmFHs|K&L0fg9Alw+;2|3tVv%ny#{d4V~pS?50o>K^V`=#&|6(ApB0t z#8q<|F^i3~wh!$Gntu$ev<$Q(Dl*rM<%!8qIZy4$%TKG7S(M_A&T-ZKO#hSQXY@F% zmL7X7QgM|BHmXivH10kLG#ykq-QWeOS4K?I%NQzN4)87T$3E0#w)5g(hA(4!E5TOM zl>kt^+DUpo!RYU||o5 zWr&LMQe(({C#GJ4%o6CCR88(3azss&HBpvh;)Z>fQh!{bnY*ByOPnm*|Gc&Lo%!n8 zwX0bT`daJm=jy!jx`;RKQiMi0Wi21afacK4OYBuF2^@LpLdr{Ymc13fr^YMsIVS{I zoY3@MUAL$U#d$%rXZ{8dURb#C?yPkCT0+~d{rN|q{ow7l?m%NMCuIz)GYs8m^Kmlu zol_qc)1kfET_bGwYU+OeAcf%I>=#n5P)EDauvjlK(}Ey7ASDLTrS@B1;nEFrv0zFn z4eJABK*9zL1eYMK&@$k$j~Ot+DC2fJEW~8M!`K_coi#qrkG*mJI2^~dvAwQ28Fgd( zbIjqOKZz^|X(TU`v>M<=uP&0-_D z1dTb4S;-VP%YIxcE=vjWpoC1y0nZgDhI3l}=|}I}QnzphEUVdA25OV@F0Z&6Oge2- zp*PvFsb+&7++4J({-4aywwjDW=O@;UG7ckUcG(?RC7fAn@O)-a>W-=kQ_OmUO#*wT zEl*i(xO$o|I@#7t&{LC;%VbcTO2tMws5@0hm;(oEc!UY63I4swf{jw@Qx9;6s*pW- znc&1}N5F-cyDNeq)v}F|CkTuh!JHEertF>66K3$=b zEhrB3m1Mrwp1gg3NcNj%wfbU~wTXsv>_8FN_7LMEhd(Tm01BgSAg z#240}JT3RpLDmp9ToBlwd+`3R1$M9M==YjaqFZ-9bu|otRl(G5O~WZ6GZ)%IhRJ~Q zGB2*7qR<6We)ub8z3(MXX8~Y*7vrNN_GZB%f!MogENijDSIa51>F3 zdk>y&yxx1degBbVz^|XZT%9>QnmhTh?iaiGT*@oV-$L_5H^%TAF_eSiU@-KHBU~Gx z6uD`CKu1J*eeLI0<}+xS*`ukZ1}5e+%x8R0$vD?c%F019Ma(RqW-=-iywdom)A*ec zopnCzG9ojYa8ON7@C(rxphZB{jwv<7lqjD=3*hq?+8vsjR%NF+uvA38U5bW!xWA+U(v%pf9Lo zSYJ4Bqh`TqqtrNg33;kB!UkEkz||ls(liS%NuZ>&4NC~5K(Ww6<|HC5S+H}9aU6=S zJxSGw7)(K2w2#b*bln$SxhG_qDzohP^m|(!?iC3o-%|Njf+st=OT^~+7N^h=#bF53 z;H21w+QJKQ>Z>+nhDcIcCi3w<2gn`HbH&cwQ#rW>5{#HEO`PJr9W_07q_C(It?XXi?in`eiD_6D=0()NCWFnIO+Ua zb`RJ=FcA2cOLsr*dfix&Hx~O9D+#+4o13*cw90$hz<`dVTCM3x8xmUy<8yC227HCw zb|D@2?knlN0<6WzcL8kpI=Qb<;2S@lMZ#n|FS;43N?!-I@fV4n>K#bv)4qkL}`NF4h# zW3jWo>9dyCmyE_{vDnRjH8a(Y4=v(a;%iYi?1u3e%5yySyETis_GkM+0gLm#=lOBX z!tk+oaWrl`c>?-tzvbbA9$E;l4`3|D?hm$}5b|g*3z|iH#)CnO>1!OvC*>C}UOfEz zKmYyXH_yKO=bn&W`Fgy`5%A+p6{5HIxA(z;w<$z#!w0>yL+1O31Kge-yrvmzZ)5Y( zeG9;Uc{W;|svI3%yj-?d1m&2>-z3+E%Xvkn!ovZAq6dfptK$zoKQ?>c%KFWBZp~*l zVuOi%r<9QhzUP*2Ky#b8Iv`gH|1cHnupb2WK!pn z8-SX`fowALHyN>}Q&xwN86b9OncAUE<{%M_lS6rQU^41+id_lPRs{h~W_l}nuK;hL zcx;r$>JD)N((uXTQ4G#eB4&0Jhqyv+JCRfs z^u@hIqY^s?$+Ua@o{n(|xl!M({gD46-cfu`(@|%MVlbX?E0R-*q~Acsy2QaKatHAA zae0wrI}wdeimr56XABY?H*0c?R((__RQ9D;YScsguue@evjQE8@##iSl5X{6bmhb5YD80FP6P+>PI# zW)2wME1f{X<$y5YM%;)R@IU9+$$^>;xvrpiF_*(CLf`Bwg!P$lj9Kx?U!HRG=eIQi z>n{OZ0Ixu=LSgV=4bx+cmx=FU z&WG&GBCI)CN|>ATZ+QQQ{?Y~gtp|gJSh6(P2)1W9i3a&7tMIq8Am*!fAfsM+Ogi6) zWd0ds(G#iIaXT1w^9yb1qm0G3oDZb&aX!WjINqJeMSX$+39*7=xg*ZSlejc#Z&Xq&v#ai7?D}Gy&pp<%Hd5;6^;m!Z>i_e}(w)gRqCr`wA zb@h%wtx(=8LWA$B?{|U4S5J@x-?|F+3+&zAUSD5dUG1+9)z`z}aJVigydwa-wR7ta z0>C?upI;p39@VplJMtk!=}3`r_2H=Vk!T^^NvAvV2}N+GA&(?csg9usmmAY}jq$D24=_uulEfTr4u+=vbMGh8YYnU`DPk;mmUw@FbLYkW9~r7FFwt;$QNhiuVRg^{uj>54YY zT|js#-nNv&o?8TeA@}NjNuk#@&ZE&)ky0EP^JPSA(ND!WZmmh7xCK9!e226wC@tP7 zxpC<_^GjIyC#Y`mu|-^M5_hZOf3AVKE}JxOii6=4kJQ2j1Ubi$fo@8JYK`R`)Rmir zMfG}B-4UrD!Ye6@tELM}r-;O$1u|Qc;Vwa#*Q(X(am0T~d5_m9OdEO(R6bsa{L<6Ft1ZvH9_`LOLFQ8*3IFX; zgT~Kyzh9aI_yUFNZ{1sY@GBn!U(uJ`K8#FqfO;CV*mfZFeMKt3X&iKR?=4Kjwo#-8$MmeEITZk^}sX)wlTMA;m8x z_#0r}+Q6y^Si#Z@K{tymQa3pF+0(~6GR7sdHJ7_)@GHoBMP0jc0u-3YyS25o-XHc? zH`Z1kuC88C|5i61_7xDXuMUU(;ZQj6_6KCZ3V?rCSbS7pD2d-HKZr2z?TG!XAtwN` z9U==cKz(!~&j(RwprBbyZR%?G+RAHZ!(zCHf4aYh7KDqAJvcEW*@>v@QVQ+(aJo2g zDt(hAZAn&Lzf_p`oIL&Fp4EvxI+yI|QZv3{aheaiVlpLF2UT^{*3LyeCt&2dskESr z!{I2Fff}H-RMw!X=dje!;jQ}*Wz-namPF-!$Nfh zua}YI!90`fFet$yj&Kbqqxr%_b6ad;<^}`|byF?vq!R10F4fS; zX&85k5;crfjOw=NqLN(+&8lg%YBG5wiQZ<-BB<$=Oc8noXsb;P(n-+aTV|+rn3g~*>sbC{)*sC#wNm0z%9MrcLWHhBVTSNLQzthj=|y;0 z!EB`>H5r0*G;*ONtAgQi1qLa3oVwt4v|Cj;;N@xsoz$&>pI4Yw!oCL(an?OUQZDe+ zq0HS86%3vc40ypLCY0+Zk@s425O>XNYFkv10#s!&*#5>$`)-1 zxjpKnju`e;Kzm9s_vncpe)J$i3l#U>edD0?JcIu(&K-W^z=@@sCF#7b^Jc|%%LVOw zp7SvT7Iy5$UJ{(|K9oy=i2Gsx9?-2ynsks!nBG^1%5| zK7IMYovR<=pUisouvg&sbv+2a`VswBfBMU|f?nag8|#9;7uGJUs{b1bcsGW9g}bZ$ zet)MwT;J|*57!j}-@5buojW_9{`cae`b_!xK`G@_1i!?x4|P#&yxVEWn7Z5P1dX^8 z$hk^B-R`!<6&*z-bpo?_={slNoT@dp8JN%+v4*c`Yx2UxNbJOT>_n9@9CBf&8p^tV zLnl~k9&LE3Q|0J-rb5q_UwG5+$lz6&h^$`1U)_X{W`zlGg$bUSyIh4=v)9m2*o(RZ0TF;KeIN+HOLr0fzal10H@0-I)9 zsD{`t7R+OJE($P^&26y_QX7!qoT>)W)okxdf|#voY0x7JJ$wrX8gCU}I`V%|s?HPO0S)kZAbew@#% zHdn5(B!em3!c6*O=*>nPCS=JZRsn5gR-2vB&PZQVMt3(#Mks^s4%Rs9BCL$=az>wW zhWmg;6GlrkIBy2i+X}ZW6;R-THHU1V=7wQGX|8PG;>0r7KG5vUM@s=mft{2j$Fqz# zqx?gi1dLhVRp2X^!Q{DI0%_k2P`J$2%QEa>0^HJoJqR}|(Nr5~Ik^A&BGK4g0n`x(f$UI$Fra1MwNjirXOWrWeGc z6-(WdbYetV*)^~5S%J;MNWqR`qCuzK?LaG5&r`1)Pezm7(jkSvyYc*BG&lqo^q1=D zX!rTK&0k-;e;akoPyda^sV5@*4xc>y&$AaVz8p2iRs4IAz9jNn_ zY!`NLbs8d{i~8s`SN`~usiiwf=WytSQ^8tCL{7X@#?KSFnHi%cdr8@1=wyCe53`r} zy*vxguF;u!S}(NO)uQ97IM~Vrf^{fvnA)U@^xFYe9J&Ho=UR#L7WgOlxZwTCES8(4)!1t`vj8VGTHLU>ChH zc0&jQ*I~(W6U(#eY~JdqDGMakmRxwYSe+~(Bdp}64H<;~ANxJe`<^eko4+KV=+hT@ z&hx&{2m5ZPndgkfDe{uxLlQWgq6vwQhtI>B^jOz;NYOb1BVoJ+>xGP1D*V70DbdzN zwdP##H8e4Dl*+X?~(^IW%yM|GOei4qIx--%xcya_Qb%dWt?!Nse*RduRDMq!;hbBUM({{u|^OMSW`2henN5;*SaXBzPfBvU~$iNbnb9&>=4}SFf_dbc?*D5B{ z7&2$`c}lGWs5zb1SZGP7Ovk=i1uZyy=IpueKFBl;mmQT3+#)1b+bFxuG3|MTbLT`; zdXaMQ<<1eR6Pei*au{baDZ>s^&?_@cIu{%M*YLBE;b+eb>^?UboIA4e?81e?lUEH$+mm^DFDHoq0kR)_0iJa!@aOT* z23*4Y8X4zdOjWt0jnY`eSc+*i-cF0LM)br?h|*pnO>&+Rrw_9q8>G3@(@_b#s*7D% zLN6NfjlpwWJWP%@)=y2Bsi~f#|CWYil4g)iNt{Ax6d1Y$TacVe)?;0gFoat=;z!0t zJ31v2=LYA|s+HnsS}KRcz$9_cbvaJGRg`w2DOFQBk`_sb=Btlto`(CBLXNc(p&^VJ za5^1zBb&_w0xTVgd=^Su_M$W#{Z`F0ZeI@SoBh#qxh#rlU~NVCZ@E&&w7Oz`)Ljs+ zf4Jr-VpWG zTbw-4kGn`b?){j5`@IoSU=8IbCMG^v*!a%I!lfeC!Rfqo09PYPu7JUHC)^w?wjfC_ z(!@{>Bj_^$8MJQ#K6B=sv*&*Dms)X_5fWf>WO$hjQlr1XeDSr^T3zPla_i!vp}+XPf)TX&G(Wq`tA+%dJHZUx zH4n1cX}5b%wl9|=ySvXvkamS+kY)xREd+;|D@F4na5fsVq`4?%xdQ!6a&xj~M}i*7nqfe~;P`M| z2EBxC;vZmhU6^WJ8i=CIZf2-OUBWW-F~vcQ!7WKJpj+8F2Io-@kwMiZjhUz_`BY9_ z7qxn*q1A$%6gwJ|A$wUzaxw_5>jw7A5>QnaC0f*lbB1nc9M!apvnBM|QBtd=32x+- zq(`c=$PbRJE6O_2N&s>Jr7C|`He7c>*ihbzaAUx3nJZvn#-zr-s5odt%2u;+H&ywA zN(PJ)L){NQ6)KC$f-L!GDOt)Q(J?L=SU}5?q(vubu|>Eek&n5{ac*SI|NJ`kmoj-i>(8D^fXBuT zU%E$YQ7nz1$zi5%Xy9{^R;1zTP>rizZiWp;7X_gi)j<-xa!mQJz%6yp-0))h{FY08 z=Z||#n3g2HcK&-a%+xS^*Kpc9_k?*V%ufyQ{c)mmM}?77z^1@5)muO4q-u718d zGBqew#}j3+QJXc`{DheA|6-A zWch9$9oSmFb<_*Xuzc5#%W18!8^;QUL@d^wY`Fek_!M`g|Ng3qe^ z80-Iir~{nY8aTLYJ`v*Jc9@YLc#Z)AuzGc-R2_^xF4e)5LnG7z;On@om-|)>s0Eaw zhqYD!u!sHXl*5^eDXEjL8@#9XR|n0#?ZkymjXEJea~DI%(i6paR< zx)k~fmbxAz38w-rcFIzr;DIP#pD(Jys#err9`HIr^|CNqA<|`8_EvP~TX6(t1z{bL zM3-F#tSKF3!D5b}-&jl1*TaV1NWA*yxvN<*@Z>LD;s#V5J<{4sNX#>5BU@!M7Dmc| zFzFP=KsQT|5t%EEM3IQ%b5cgm9Ck-!3mkc0!n5M)8j7%ym+c5~sV^$&w0b9!RBI3= zV2FM$iE5b&ZAO7)spOKAh7uRPs`f(IMu{F{YMk@P2T6*+8K)HS64t&@JgXr}VxuX- zV!;xvSWLn?>rS7?-0`!)-?93}omx#oHi)k<_R2=MM*DA!J75(&6PVKstBiT=NW-Up zC}JxST1|@1Syj&SBDR`T;nn!O&w+9M`25>%0Dujy=3z2AdGGGg`nRwH9?DlG0D2;w zja1=Knn;T-S~IYq$pSGpzZ6d$639IhaszV!Z5Z(J*Kf|TVgX@J=6h6B&`g_Lp*_i5 z%QO=pzKG;7S7zY%P0gg}UCPa-3__z0sJN0y)DnYFAOF>$?kj4O-QDbQT61sw+5Fme zN5$OIwl$jhM*AaF6B!0;Sa1)Skljwl+~>2c4hj)=%)3fmNHKnSF0+y=Qn;PDvp#-Z zax^xHy>bZz1_ZB?1Gl=+HZL0jjCJo4CeBOC7Z=UP9t6wng^bLo!GE z#;Yg8mrMDf-PB+PB@92#H4_LTF;8AA&LASQh_&!ss>ptZOsYshIL=RIaV&Ln;pn6$ zGFYChsu0o>_r*m8Cdj^;*z#7l1<8c+4J?wa?DAO4qn`!a?$i6Y&l%W!28=bn=e8d< z?9iyx4r7V3(SCuk$C3TDYiJtmJ9aJW8-!5*aW#&~jv*cjbu3HZX!F&{c;9ToxhB8f}&C{DYXQDl6HR zuv*e&y?PC#!OMNs$WM_loEDgwk?0Y3U67y!rvZ{gBJR8t$1|n0Yhd5{%>2ozql@tiIniZxr zMo&%2;+N>lz$^V%aCb`fzv>P>!8i9r4JGgz_x?4$ozw&Ao1fdhT}+pRVlvuF=T32I zi~+L3EiWzy2zqj1YV=Ty)!^>8k}M&ELy{oXX%Ifgk@hT=gv7;4Tz1Evl==#Aiw9Xl zEIdn|lnTf7wwNRCbkaz*D8%L?ZAwZ?r()cb>j+*c(AkW`aTyUeHYa{^$fC6{jNlCJ z%S#G+l}0ZQE&e3RfHnS3er5Slel+YpYNS~-2(M8=VkrxS>6|VDF6bIy%%ep$jk)#c z=sT~{<2zyGRfgQo$da9UpRzJ&0>#K{-G*I|%53Uxbw&2|93osP+;(tg}~ckY?lv2G|r zCs9{XS)d;#$y-~UPUkVws6PJn@L~EebuI%P^1OmM^$Ax}`Gw3!yE~oD`-=K*5qr0u z5QM>BiN5P=P&MCD0DQ2tbf5rsY4z&*!RpfL6-9p^0D~3&{_ZN&Sn6eLg4dT2$)Qd{ zBy@Lcv-|w;di-#I`1J8azOhoK4|onzaBiX%`$dEa*59y5Wne?fH1ZNn!pnraufH~P zriVg)M3fxsnQ?pb++K)exOg28{iJ%SYv(5#Nv=NEW~1Q}HEPcB{l599J@WM<2<0D{ z9QPrJYmbIqd&3%wS?Bsu5mhXL@*%GJM5O4JJ(%ldx=z9Z@kG7KlDx43Xbpb3#Dvb3ok|cxzLKRN+7g=LmQJ-gHCC83?2! z)P*&*h6=G4)j(5We%zL9SaIDTVkwqA=qdv$u28}&R6UrLeCEIsC1WeyG#pi2N|F@W z3Y;EFOSXpyqXjElax|Wsm0S)ibX$%oD&m$`-H1yFchBlBBORN;m}dl7h3_LqU^9%K zGBRftEjTi9p3>SY37-@k4mglT6y>SyICC(-6ie|+VdTQYVabn*-#l}v_Ga}9|6sMQ zbneEb{g=5G9PuW(_@!hC6X1&EcEsxvH90J&hMH$slXTLghGrH6dSdJ4$k)T(wIUBt z_sbmUN*xYhVb$QVb!=zxpj4ODZd~NeOw1zDW$7Wi28HzwC-+$c?CDHPxf)2aj{%nu z>~EqN4Mr#yF~~)P$De|Iv8ND<&^x(kjh_j_lV4r_C(v~c8(pfL8=}D?+#*o1kxLiK zB*l{aoCZrS>u!d^+~{24^dDws#M>**qKS|Kljqh9@9o{xvbfFSiSwrl@EHlIO{Y(O zuzmaeM{GZ$(n?|Tbi5?Lh_dt|`)LN{-BcX#VA>Kw*Fetdm6SE!%tNt( zPd4v#U!5|7fJx^b?`kfWGPkrb7 zxNpyh`v=9A!zRoT_I*2~(MXNM%;Vld)hg%<4L&i0+&w*!#YrQ(%U;w)-@elCNs4Uy zj0GV65f%J?3ke8o)`%%sAMMl1V?Rx$*}QN!JZ0!$*f-WI1gDDF>d4+c8n=jxUv+j?=_?8P<>_ctrTPiRl{@x z$BNa^aUA+fw#3z{={^$bTNM@bS%(x^QaPpoz`|*z?Qi}~cUe3M>q!MOZVr_)S(5)nN zRvvf79`#w6L)ViG{lbR2ME4N~<#oug(toZLmB z2r*#Zdu6uuw_pA7gEYe_>oEJ~a+SDbLFe!gtqi5O*D|n1nSFbKTpw(^7(eV%#6xJ`RPc z=|^lh)}q&s7-=+E$85uEZ@25aeXG_evF+PyTBB>%CtZzhY2874&#^un8#s^ldoQ{c zt@T6d>$-y(ZEVntdCUe!_p=Cbgj(A~dcfNa^%3qd3%>Odeei`s@5dYikZq7?&SG^- zwGwLq38><*bqJ&M&}a>EE7T85XP*?}(wRgujUnr-7DKgk21ZNvwN0*pd-=*(3#)_P z5Y1N5lFz^(j;4UuEK`?Tl9tRBFOgBV7KsvBB*e0yH5CTL$(9pRPU3mh7<@So7ng36 zgj%3dCqA|`xCcQml^J_#^JJh6M|_8>&aSG4C4*$YO~*iYV3xdQk}bznL*#9S-XpAd z$#AP8x>787N=lDJ_l(;q*$RU?^L8rKVO5>W+XP9vZWWf+Upe!THXnsTH8Dg^|L|Z$;t1&{fJby&?d0XY1HLYWe%KkIfXr2D{V@6xmbjX#3z*#|E{iJ~KW0^hI0KwUxpMSSlF9BamrRmZ1 zpQ|Iz*`bNIZmY+Vy`ivq*rOPl$yWlqGJ?iTn)2wz>#k)3)^{#m)M&hz{pKE3O-P)~ zz~hUVvSN8F`T05QgcaDdQ>PQy2^Z1y({5w+TZ9-oh3eaeB8H88=95o;dhXLtKm6!F zFa8Gt+z|pS7_6hIc4Q3Q5e&Y=P{_v|L2qIHytdU{Ln8u(RJ$-J?VLd&LRT^1-==ei zC(a=VdJZU@C)sRgK3qq#m6R#qEYMc|>8?|Q#hos)CJzp-9$ZE8)he{l3V@#~*nRp` zeZNKw#_Lz`jZ%~`5IL*Mj=3`1fz@S4aV4?9sOr>0k-xe5 zb_y)`y*y&UR#JDr_3A{3eSlfrrx31XtvrfecEfn|p`C;nN|}0=RXb72w`R+Beq;Eu z??>D>zGaUMLDG$o^{9_1_A((+pLEKPNQHZmRFTJk!VulZqbItYKEDLAVy>AJyZ`6w zYG2#B&uBhPA0~0bFiZlqp1KOQso-1*hlXO`y~K?y*)0GKK=QwnNVEvK0)b2$mS!-< z23v62h4zEzt{5{`r<-eMsavNlDczb4YTU$-q-#GEGMbK*ZZO)vW509Gb6+GoRaM!# zzLswM<>)-md5Q4OOJICC-mczr>g+|oo20-VS+SRZQQ>>p^UC1Wdrrqcq8zhcacXa$ zORo&Q@krtmh5PP+q{SVPTaeC7H0SV&KYQKlnr z(n%SYIAqrJn0{O}3K4P}(sOkrbZW`3#A;o>KHl&o#nR#MmX07un+4j4i!#G)Ta^e( zgjC)X}(6}hqCO7WCw#VT`goF?b=HEO2#%2(YH+XLB~ zkhbDryb(s!a_o{ekM7VvBuw_T-SyRVl+LM+fvFwo5J8z-nNA}UdNfcJHN&IvxnKt+ zhye|~KAA45bQ4d>hN)}zeZEAX^{_v^!)joB{-7#b6KM>lo198>?2Z+&?+3+4sDhps z@M-`}6n^s9x1N6+o+E=@h@0`Xc-$7i?nqEXSMU*%U_^GXqd}@HQRRtW3t&z1JVTT3 z43T$C%y%qdKN{m59M~NnJN<))OFptSW}87VIP}-&|90iQ`~ULiz5`$YEO>FTnZwjM zU=qh6p)ZiPc*M#Hi*pYjFt(f61d9Ma0RaBVMqa|9IW!+EB7=Fnw}?3^3^t&8CH4Pd zuv$ezWg(A+aDHyCbo`UU|M~2*+qeI9{-c|JzjX_O=Syz_bUA#U!PiaFU>sNxEQgNW zHMH@*;s`6Yt|Y5V^Z@NT4!jP((xsJO3V34hG#>BeOWodLq0n_)^o#4D zzd+yh%S+t-F5@-iKZ2%t0bd=gp1Z!ajoa4N*>h)~J-hwevs>F+d;k(VD!c^{b`<#B z2bw|SlCG{h27JT4_qE``#U69M+{5dbKUW>;troBZhB=G;7k({=&RvJk?k`g)U|F4C z{n6J?SK<_>I3zfhDaZP(fw6F?7xpT9{5mn39vz6YsD#*4NyK67Cl?wX9ghsd@jm9- zJ>uX><=#K9++*$P?Xw`=56ivizfiwC_yS&%j@li&)^JO!L#cRD?2SaPhc78(;GP%p z>lB`ar=$ko2$ztGNpJ+X(PelsAeW;z2|v-4y}_&Z5?AF#|BM4223$4R9&dYEvOSX4 zM#FZ&bO|f7!l0A#Dygj0z$?E{hUc`kd~HjV++p>ty86Ue8|LISF>-@i>x_DRTeeo! zyUDoQ);hXDS5T&-fpex2W-zxRJ(ZB)vpIz0V5yTTLCAz-W$nH7av761Tc1%z zpG6EbTbV{|A|l|l3Z>Z@aVJb3=S<2Fu~zPYHC@R4v2?2s-Cq6<{kcv`#SVpzs- z{PFK8V&k+nzTxKg^vu|!0N-%o3(5;v2Jf|}?sft;B;qO_RhtI#!b*M{@i`t{W z51JG{7cGB-5m*>KBN>`WSdXNryo!g=l3|Gp&!77J26fN6%$~s zt*^iG%JRaikVU<~JM2LV*wrq5u;6$s=Ewlxl}+R^fBvhT*+Vxb?xPyJS77@RH_`vR zjvC)(yIsZLc?lA#3xHqnSwu`;xDFD$edo@{U%J~ncL2nH+_oFP0U0I^Bb&pW4)Ddp z+Dp41ItCovXukMh3E>|OUKu#q?Ly<+ud1uKKfZ`?=<&H~wTd9D0yo4^u$5N7|C^^r zMq>6?NmKzGjc3k#Xr|%e(aLbbQbIO-G>L_SNseCP#L7T+aYUepN$?(E-h-)?VFA$| zVe+t`s~&Q%mlV zU~gm?ucKEj^F+P6e$UQM!a2@Mpldn$3=n=mD31(mkG*IW?HI5F-jlMwc3P4q5jtyD z)5~Z`aL$YZAiv!t7|ULNVcX#~5fsnqUz_yi23~ zvPDj1%n&5vP4s4ZGB3oM`xF8V>MKi>)ho2(IID))gF{GcH4-6^Vd;>CSP6D*K^&`- zqndQ$)MXO0f|?tdS`;K%v)8R9Ft||x)rw`|37Mi|t=9#xQx>h!1or0!W25X%5 zO`DukpO6p`0w)}jFpC+Lv$2ebUhP*s))r4JoU#->d;E8-J~S5F==1bf_%JcEO6l$`%ozl|B5x zX|dhN=WE~0*y5LRs~M`Hg}lOEcbge|`k@KOZv*jLv;xl-S0AU`Ia_4d)uCcDJqr`C zf}xp?H7jE<+Zo(<)z?zt!q;ZcHiYJF{?xZuRmM=7oX8_$62Z>&){HaUDPPEU3x!E! zTowA&{6y(^shf8cw6{3fKYaV;Tk z{0oP>&q98@z%a-Qq^%H8X_UOa_R`w=+NIqOKYwngn7;POPrD8Q3uxQzmwJ)?$99Q}btZNf(0wcrOPlIU|(cKHD)85Ee%#$no`eFAwQW=hgstn9oziRL4 zg_5Y`;Z%9x^}SS5Km}N<49StbaH*RbG!qdmy#(MHFsC9UcE3OMTbg=Pq2Iadv zt=6J9HluchhU~+trDu~thst8&T8m=oPROLyS0H>O(n?olaZ>G&#bW*33WF^=Hs+Ne zx?|0N8LR6ByH;9qSjwAeTOgGTx!mXCjFv%Ui`wLd?PQ^w>L_mmuxWGhI4dKx8g&G% z+DfyOs5NDPDy-IQxFH11ggr*Y*p{5Ubz{vIqoMG~D11X)xAn3@ue9G4AGSesy>8>@ zhK|)Q*3EuYo3fwOr|PYTHwXpqG*$$!(7XL0E}y~7S(`i)3w8Of2GR-12N=^W&@IYn+v%QuW7 z;ZY8-M`s)NnN=pGR=|hGU;C!*d!Nwe*Z8lHcz*0V8z{I3uyj#s zTk7RYlVHHmWK|2j{KQ;gu`vER>I(DuK5{1ddD6W6%77?pnqt|9gvGU*uOUW7NF0g+Vfg$k#7y3374&Qr{7M@813Qr=PmV zyY2x8w(qZjcoYZr>i?4e9is2JlGVqc*yCbRF_C7mSK zj7lUTsXT+hp@ev49fiDf$wp}(G(&6hk~XxBv!*nrkUXSa86$NJP78f7bj%JO>!9Gj zW8ZVm=X-xRUT+l3`Yrk8=$y~_oRfag*eGFP4r^dqAIUH9#-3n$q>`{JjaZN@s0#|) zK%sQ!RD8}my~6y^6|fuf$lx|CqP!pGrob86D{#2oZb~5IN*x}{&S4j z>pBuX;z)J&M#G_!R)OS7W*Q^w_^^`1NT|LCzH>dFx!5;!?E94;Wk-=Mm-?1)!MKV( zkz5@^D%Vy16)Cc1Oi}1n0TLx=4rUpC(NlD?1zD6j>Fe`CPr`Hmy0s7yr>|Q8WXDR4 zY>8K`L)M>NNz9Jv+Ju8I&Fj8PMU+!rudvu-qcsc#AY9rQL;+G zPCoCdokDcUZxofxVx^mBKyH=sOtE>Uow}VhAO;PV7g`J%67(H5)H62{82tJ(0|it$ zU>&bj-@g0vdxo(rNunrBl&pA`N$y&KC99=mM>>p$)uY6&z+sY8xS?AVn;obDP`RFz z=+Ru=W#R@MRSciR=v8@>E&Ng;jKV&x%;pLUnyj~B*h&S>%cbhU7F(C}j8P~1J2hD0ioU@C;-S6~MKgtDh2z!6)*MS`a{@Xh+HR--cDw(9usR8(CYG#1JYtp8%y#-YufudZGFFRLOVVTk9akz!kIRhj;hmDDD>dIQ!qm> zt{ysirk>xp$>mGrFteUzVdVV6sm@&gJ|g=4%#+Hq>xdOyF(oA z1NJyiMDxo*aXO@p3nH^+K!!zuI>YiH8}1h7sX?j%7gveHAg@Ko#MI0rCHRfgd9wrM z*uP$oW8+k;^?>ZNm~d>XNkCYSyy?%BJjaINLBJ;ovJtntg4YFno}m)U5YF1rl{-MB z#Apd-BGlQwJX1ZE>M`r8q$G`V@)q~bnuXY#rUZ1B>1gHloGV`k<0Xgm9SG(sR@$`s z{k*jpc4@>Cd|^rZ0!l6+#MQ>iSY!x>m8p8SxVEDOSvju z+XK${F9h*Yn!{YmvYQdP!R)G@Z&666zkY1&A>6CR86FF7{Zi2>#%*{ko>Bb9OsXum z+cyFF~M4e>ydV)F}2GwXpE>-U-G%axrL3 zrl*QTT$!9eL`gdlBxS`4+5xJlsi@`2CO2%8XCKgdLM>qD&_p%VI@sz@>P-$ z(GzlP##bVUBYe?Mehq^Capd)TMAJFsZq&GNR7+VdyjPzYXV?*Ov({m`}mb0OMy;>XwQYuKl{_wa(U30ju2=JKlFSQIp`g5*QknU zXi&Upun?684vgo^OoK$?({$tBcMP{u>EDM`nbE6&R7kAkQf)>m)fb-;TREI{80_$t z446TXS1$kgvWkjSMzky!^xCbB6-0AfySC;4xU#;!K6Md&LxcJG#p%W(r>%`|0k^jw z&_DIy%ZI?P*Y2#hTfN#7H z27GDk{_No==gNzY=wb&7dOcL;0dlg-5Dql;GS@?2*&0u$|9(v-r$5NMaARO)s zbu6S=6m;G&L+h|u0gyNR){A>P`!SXR?qm9LjvI#ujeq0+8|;){5sHf&L61EkG_~0b z%whg*<}buKzMO}<%yJbNkbzLwO#%*#U&i^+j4;rQme}ei!J!R({oEIi4^m)tced9L z3%kQH?&2|;=xNW7=L-s(QX;$#yYZfk>FP&89LIefDhD=<9xC;f^vrHQs~a%0F!W=U z`VcbD%A5s}SEWKWn`H)N$#2+-FVB#s!iyy(TJesuF?D*zi7nQd-MsCdB~h7low}qt zC7%stK-uf3)L1YpjMQq8*_5?2rHm>qE$IX4yhoaA0NUx~#AYl0quGo5O6^is*elt) zUCKfCId5Bi`vtmR@-tD@yyO?4*-rS>(TMa~L>?4Itvdn*ZpwOEHl zTNjPl6KZfslus$T4JuxlFbd2!KpnZ#Qj#W16lKS1aqo!PU!4Eq6S;32MBs@rO@wg^ zfES&@B*GI)!uoY8KEIl3(61h08N+C89Pt}m@U6LYiJIhy6fH*vIfPTfdd z_5ZpX#wL&xO_x@egJ0jtz%mARcKWFyGeKt>^o!~F`DcH*TAr&mo{XTcR;L%Z3Jg4U z+zyDl&{XzS17TMYhM>5B4u(eb_l;{;Kcc1T20Dm7SOaD{-g*nhEh2;eXy(U*D{~b&)9;%mzVlrh~qJ z?_#b?iTUC7KLEd5+k0DkyF35f5w+blyan6UiFmv7hzj)fRtmzmPu531`V9DcC5_@( zS^IF~&CNHu>%*H4Es?34-pn*S46E%$0MtN?2&_F@NAevrWL|gIne6!h{ zf9F>}SSoVfedeT-BZXC?15z04g$6Rg<1Q{mkA(oDGyA`5Ik~^IJs% zcOW6~JIGt39g@c0r{(9oq^u6R&Gj5;$PCsh%1T%V%*K$ENBER+s%Xc0Lfe(XefiBH z9?^*~?LQh{YlygGdqQ$Lb(AgDv)p6K&+djcIpjG;YFzKj-rVsaj=XGsDJ44kz(x6* zs7Z6FNrYF!WUIIDak7iZjZVpz?D8^jx_!ORIcn#e*`3%fXdOf(qq(932Z(*IEPHPh z33t2GPDN%vAI9+5F9)?d8C~^o>c#Aowf55Q0(g_gd^Pgzw5_Pu7IwYr>@{aq3Yxb{ z!Ok5Gg)`Dydd897o4{4S@0+e6&FHt843bZgHai>^2Df<)Cd(&QD^zxehsTeE^$TZ? zEnO63wz_ZMd#6#Wy?GqrkQJ*pvUDr;9aM~!a=z+NEm3!{rn$0R@mHNxKRBi>riyG( zw#8dv(_u?R3M?fYR*F?caUR5DRRLSbWt#Ls(u+rcw#xEF(-*rR=+SO5ngaqk*mjqN zhDh>Y#ULQJ(#4Y{DiKZ)Bcd6$+K$KZ-2@;!HVFXEq-Pv|G!xd5H}8ts5_##r;_z3S zNTbar${3_QgD2yrxyeaWt>=K$r{DhT(h?n2;=GL75b-557UqijlJs8iC;T{bXgYzn z+5JlrqUtzn85F(Ym~VG>Y^+vGs61m5430c1{3TI#DBL*ysvK9T^~%C1dH&MUE30%l zMhXihhp4(qB-?7PlK%vYR(SIa>$hrm%e`h4S~t5$zet8$Ucrj(GM9}U7$YFV0q|=MfSCkI6V?N`ml;B}va-g2tCbJbNOUP#-z;BL z1ut+9T6DD;eY@lE)*X9ZO5WZAB5&<}v$OM!VJ@I}$7rukqP^dJ`ogC-A8zmM@`^8q zhJuqT@L+L-%st}I+-q-*UP?CCXMgrqbs^&S5BGne5zR%2q;&8L3)aUGZkStif0t%? z4ifo14Ovk%ediZHUfLJSe}IRnDEgj!jADklqMrI=^*cpWt%nD*?SqBu@Ug_i1I$wg zQR<)=&*;&sp6%9zxj-lnmT{bVntb{d@zA|%Z-nwFn~rQH*Mz)rl5Jk! zICa6U{DA^?=$}z)iBMmUU-4VG|);*$dk)UFK-Ch5D-B zs4foL-CdRI(UuM*`%wE6At=X$X;pLf4~Na_lJrL`Lgh+|!5$(T!-V z++#knx9WDO%gjhw*Vc*K4I8Inxv)e{0)~b5j>u5}a8tpTD6F66_DDmi@W_av!6OEM z$HjE?VBl!!)3?4i{N5xrQmIt%(YeyQjfs&vHDQ?nO-Vp03YNuVlo97pj^P(M4SwV@ zx5hBXT3I7BWM?c?lbs8|(3+4|+h-`Ro6?bWDyO(B)9MtXn}MlvJ(*mK$W0MfPKt>6 z?40d!VD>Z09Vi8Bag9wyRSlDGrM>|*V}XQUvO=lM0FI38iMd{GF`6w30H*M^WrxW zxs`PrmB@lm3;6~3iU{l6xeGta2cs=A*;XqcqT+8$a-P9>&5zI3uYfbdD0y3y(xAbe zAI`j=Ai(ecw8x8dw)Ep0$MZ!49Z(L1MIc9*4YOG&vZlkTL16>H#RX|QD(0sQ2ke+5 zn6g&?xnKJHFYBxEpB3{V!5CVLAmXbb=^QL3wp23&Le?p-h9F(gfEak%^L2B zKn-02udXhwZ=j4}do%dMF;04mXdx~l2XmqL;<2c!z;T}_+V1_!4w|2u`}Vl(-Q$>f z=d1mjJ7mMSbNMyLxy$N9VD?vIV+MfnRzUdgy{#?ofFBQDc~IWmJl>zLhSTAAwuAQ{ zXhIAP11>JW5LGn4w4rJ>kKK5FdNPCz`Zz;7i^b1=#u4;EOze$_@D6kjRN@t`kXuV7 zlgBj(x#A~uNNMk&f;lO7@_IE;=|eIjyof$~y`PsL^dVEWl!*$1lK2X#$jK1afH#)gM3*73-9*$gtSbb3Eg_>h5^fR zmsRsXTRM4N5in6hJfR9IcVc3>S#QgBR`{dJnyI^D?T|Q>Ak3<3_q?kaQ(DB!0B9nz zpye4Qn%WOU-!0>?;=Czy)&{1>MBKWdzP9^WX_TaDadV8(a&x(^+N-wPjMus5z6PT; zn)NuW8RWOEIZ|$0lv9nS-RI)qvz&26r_Lm|LV*dp!;$0)$AP`(>&S>0gD>7@x}(9x(eJ(+27P@)8I>jF zrvCQD)o*I9n=99t$E?9r zC>Z7#JCl->=@ttgG7O$%YBVO+EL*a48!s9V%XzvKdkIqT`F1R}efJFkW1o-C)!KY6B_VQoFb|l^- z&|aoOj}LZ2QAP&^$%h^fwStgk43uDnlw|e4&h>9>Eh-7&JssUH3F@9#-YfT<76$w& z`hc+l2JaoE%z0Fr2uC??HVhcjXgq=gXf^**iUs;>zAe5zmY6%o1|*@xXG^c%0GOb{ zHV+9j_L}0RF$jm-3kFPpJB9`iF@o7Z%+Q~KfYq<}KmK@WWo31JeIOK_^enQSmAl`lS=n+}(6Z5%Ks#GdlUHE}<{O*i1 zwnW`@x4YBb_}y#HJFABO&R&yB;A>lpi+9)e9~Z9Fwu9i=@oaT6zkrU$Ec{03VXRI~ zVsd~U27od~;%up?a+WZORI#DkuYP#)P$g4BPV`PfFID-!rk%>6QHci$bmcIKm2>b- zfSP0@*m#@v5aw5NwLZP5ouMJiiv7;kn!OnQ2>yT%ewknQ#P8zRf|zQ&V>|cjm1-97;4%fwL4+WoQhvhPOA$cDDIfuG)(l;skc#dWvT{TwM=~fwxNX2?tyN+n z7y~d@)@Thu+ze?md25cnM3i&!+@!DMzU(Mu{gR|Yvs@4_Q>OHa^$e7EQ3XbEws7=- zDRotmidVaSJMga@2LoV&5c(+ z`f{*O+XhiYC}qIoT1be01_or_JkG!@-YiH4R-prL@Zblpmt@?0ntNYJu1bo>I%&Vmi2hUohIrTH!+BIoDOmcaQhN&y!^ zfj1VnPzi_;bg;cy=sz|M`O{Pfq!T$I#p=KR`ZN(ojTPjD1FKJwo}0oi3~5*{vsHp4+Oys!Pk!np|h3ud+kuhV2%#Yh2e& z)F?FKO)+7Z;wgE^NZl@fZT5yzTs~y2ZimeVeTS)>9_F_MWkZ37@g@L49EiCn*9zbH zNhq0+8R_!Ny!qwZm;V@u6A0Xrut;GOJv?BeDQ)hRtto1MQ`)@$)+B?2 z`CI{YSh^slQY&aNJUXZ0np8lS18qLepp}8Sm93QYB4K!)8o289NS`r$mK#ToUcS>8 z>PQ*Diy^cGVX4z7G-x;|yqD`=l3o~-WMplg@r#=$x$w1+D{!kqXalo$3T>hI902%) z?toAJvMQP@_>EelbRg-5w*^B|86lO3-oTi;&n|vPg&iv)&i;NZVE|4zf%$p%{10xh zUcg}5kfFarMHK%6Px8}Y-XLur;TJ<9!>Wb|i$)SvwmQ^V$bP-QWEgO?1KzlWp)sI$ z(Kht57vUasS12Sh;0nv{L)wq#(1I{O$48?EDl~!SLMXUx4jCc}}#&ka>6iPdAqz?dk6K>4h1`xzH8+@7~@&(uT3DcJFs7 z*SdfAl$Tzbn?o9Ow|oE6C)do|fJ+cSV`q(A%Pm9f8AaLJ-0ts31ZH-+YJNSOI#;Xa zw-dssRpp?b>0!kz*5%b9@Z$xPRfM;{{b5N#)9W4kN+FJ4=`GCbsmZBW@O-%iw{kF} zF+y4IB|v_uPA@XI`UfD}kF-NvCC8b@GH>;~-VBZZ5q5R2ZQWsT~h7jbfJO$|Dqv-MDmxE@d_B!f{#2jMv3xqZezl zt~0?h^n-=btEG@_y(shFvETDN@9#)zyH1T#+4?xgx$twI_kBLXcqET;FeQ(vTnc?h zL8emn%+;8)#?3((4vV%p;+1XITYK;c_?G+Bz$VC?A;*CpU~3zY)&ect-+L0qjaw)EY1HfhIzfJzj1u>t(=@4%T^BsOPUeXD?u8KdR@K(nP zc*$Xx1Ywvh!UHat<1spgY<|pgAnOVO_`HS;3)T86s>ml-iWR{;RzsHzM9vGjLBG9U-OgLa zm1sK$&kdi%JhT?h4P3l7aYpvCWiq!kOE+q26Zb}z*xbl+tO&3>g9xjJ7cw_9nU#sD zWIsZL^G?n(uyWb@SM3UzB+n9`a}rj$x4qPy-2ryb&f417J>DVsLIjNsFo>~(=2P#E zQ<+pOPW}AJlkyO;E4P^Zx|xNGr$AyXSpH!fQxD;CQ*mrnMquA`hoLm zbtqZ`12{DqI4>9st8ql8Y_z#u&O25Jt_)!pK$n*R?s41RL!z7{%%iT1Pjd&n;y1s; zNPOQf-f?)F(%`EGByM_395FMGa;~J_BTBEP7r7pukP~=<;;hF`T*5}z60Us0#u==8 zGw9_E`t-6#U*pE^zq6NL2JB9h9Qry23^8;`_&UdwD|d5O6Q%Z?stD(#d)CsJLud!f zwTC*M^m_Ymrh;|=eE#>Zrs!cnmk*|><;hwvW$Lj*76-+Jo8>MFf(w&fWK)(WUv@AI zyy*W^V$f(Ckj_oYuiI=pf?et7sR z{F_wIl~bforaiPomFd#zK@V1~b{U*ajToZCFqkf*U+T@TedE%IZ8i8m;ZR?6i@*Ho zAp9(~jX$&J9V*_7qtQ6zfu}cv=aF{~QXD;W$3x1hU}(pxCkN`NF!UK1B8XYsqd=Kp zM|G4RIR{FuP@G2S?MD6qHnDLKcnOzbawuVP6hiV8bc~`4af6`a{l21{dRt_;N}LaM zd@^GaQyV4AAvBOTN8-e>4WMH^9ogzQFjTkC^b-Kni;1ZNt^Fm0J~)a4uY`7w#-vPM zP&}i2J8TP-2--kYB(~*)F{qiATUQAjO0&3d!SL?2dD9|iGhN@XtK{db9#^Z}Rzr#` znttXzwr4FyjJxtU3gtC0xRHZ%Ny$?~uH6h>=Vbu0akh6SIWSvj%r}NgiL6*~kPPWt zg|fM`A}2lS+LKMMU)F@V$rla$y(Y1;2H%{8XxLP{;SEOSKaxYZ;ooXO&lc@WL$H

=D1#Iv{qg`tAxTGbKF6K89ZODQ2E|Hl)*Ej;$ZiR*1)q`X9Va@wTM z+3@)7A|fm?Q%)+CdeQnB2*=~}?f_5|rb&b6(%XcfEnua2mL%sICpV_-iX0~uE41Ag+u?p@jEf&&$_Dw2<@;K?OuwF^kUaA3F8t)`#c z`}FNc&wQF?Ykc5-+kN+g<9n8LwKX=@dBYu+$35PAF=CeL|p7F>#P=TYzX|-aun!9x&!B0D>JOx1BgJD3tgr;uEnXTS8|-tX&LfKHaey zcch1miViv*klsi?NX*mlTV7slbRs)+U>6=SrUmpm1!G{I3udsfq$#Fpcu>nGxfYh3 z%Zdwf%3s#DmWk1N%|gqU3~8`!^wrp^l^&=lu;p_zvd!~?ac0}sE@;j?;N9Nigji_* zZjeX8q|K6BSzl4M_w^HKd~nl(tXkd}Qiqj zzN(VUoj9KYL8(1*5Y>MEPq!T!o%&6_T~T3@@+Gk&<<6D1BBn!g9m_ne+eM*uo>Z2* z)&%jCfU!#5vNJSbW}PpiH7cA`2#l^P{>qE3wb;eU0q^Td{=kx%7@Amw7OoJm zZbH9v6N6-LYsi42f zK45Hr4SvOHCl)7ClV(+>eF#TMQfW(xwteu#^bhVgY1OjO)0-H8_)i~^8~Z8)qyv~K94rRB zb#!eF8mB#!-LvSvfA{WzA|WvXJ~##s-B{h&*xNu9Gcb5>eGi?yA8xad7aQaoTNGg> z?Zc^uf9CMlomT-9@Lt;Ob_@Ty_qO{@wtxKbFaU4%-DhL!e7x&^iEdrn?ys${ul5i6 zn1ef*z52@P)s5Aw?!K|Qw;>ExD2U_0up%=K6BHOWB(@>Fce3V~Z4Ej#Or9A?i7h$s zwu?dZQd)R9ohjp)Ld~7uO-u>gi~jQCUtby!(?K%v|17Qz2P@S~eHDDZOecz?@N>0x z;c$D;a8P5G95KXeqs(g)j#`ICoI8;uPL?)-nQv^_ki#BbJsoEm$${aQSz&#=WN3jI zfnU)Ep%$qf6C#rxl5fVb&@#3kBMvRHLL@koK@pTYg7VPT$B~fNBw_^Vj?It-pMD=~ z0E$!Xh||WMj?f&ZAn={YPT8@=oD0#E-)!Zyq${v%!k!KB}xzAM!rF*&Z zIhy7#(h!MR|3dCn6wK#Ild&vL@+w2ban!j)2^FT+zHfw9sS809y$QGu>Jl01W5_Sq1CeMB>$lT%y8v)K?y}yJ5z>y?590neQDd z|B*K^;tjB3lHhf;A@tWlfq{faH~s(-)|K0(Qt5{eGipm z%R1)}CtCCocT_rwy47k%K&1pqDJ;;8W%+2y0$ELyyVPM@YJA}Yw)A2xA%qYaoCd}S z?7}M^bT{$evG;kN-}~yQ>D)Nc=h3k*`kd$Ydp@{~M(8AdL+iui(5ktUt3cG|E?th@ z{_d{bU!#wjV7c*EwzeUwV$X!rHuUy@XYk*k;d>*^i1IZDW%wk-d(^%6_O_2zp_otQ`8rvDhjlPf;Xw zaq1!5FOi8~Df5*Dst!K2bsdA9abuebN8YPMG)~jlqo+PdL|n6Hn^qU6+_9$$R9Nv$ zQx3ADaMfUPX;Nui5=5RflXs{30P%a!UVd~jjqJ)HjpzejV(gR$BOK=I}Uv2p0-2% z^r{EwPUsONSPES8stwHB#M!H>8Vy_d=B0NwQY$ACxGx}f|3wO|#EF$p$>B8dx3Sv5 zm&vqNfyRygPd+A0q5kK0M_;CA*BbuHfBNHMIVpeg%~=*LB-AalxB#S**v2r8IdNe| zI|J7!h{gn&dt!jGWk8!xY0fe_5I33Qac0z5)MBRtQ<}>HN7Fnj0tB=i1L<;40UYu{ zC1pC6q#FZqh5r~?)6iD6m>b>Fsfh;9QSYTkk=>D#^*7f`B#X|?^r-uWFpaZqptS&h zFGkQOwFC|hVE+02_us!wGq3s;rj@fXJ!?=4R8FdysA!Aem_{}h-iJx_i~X_Ec|3Jq z@XU8Sc3!Z13%o%TUU=oDI!ci6ov7%jM@1Hf(ds)|bojeyWrQ#U_t-_q;j}5SYEPZa z`j0X$B#xkWzwq&~L5U@U5EPZ_s2za4rj9(U+Ohhe?tlehSlASo81w|sjYI17$0Ncn z*S;GY8!Mv`a+nbf$v7!@??LE6@WlxDk`tGc;vFI}dyDR#Mkye(s34sN{$9DhcJ<0X zHZQa`@6SE=j^m&e#DF+TJ}ey@4x3+Yf9n3IRgSw0ltHt3e7$t%*DLHy-TUr8cRInj%Eb1B&P@$Ce24lW9^gBOM zBo)}lLSf^{GB6W}J^M|`hV8U)aiJYBQ>T1GfuUjFM9DJgE(tbCZTspcRF0KAvwbg) z?)&sfx_*CY46J*bb~@ult`amX zNF(29*z(u+Ett5utSY(Fh>!p3VzJN?%5cxDWXT^M%zx~(s>36>Ie!`eZ))UYMgjA^+(TLx zp4G%lYE6SJ34})e&mG%%TOlkJP8c5i;m=*(fS62FTW1?G=NCplD~v)%O^e+bT?sgFjbLz!0}(*)p?Co>vouwVT3 z({q1k2o~#qfv8Yfsd|9{9Y>}YXPdME;{{EIaJUDX*#8a)%Y&DH>8H!U)x%>cG~Gs` zzK0P#Nyz2wdBNRX;Eh)f45~f=x~D1htVpoh31^eVq}Ma=ud=Z$CVF~yuiU`Z+OJQ& z=4Z}<28TfCH{bf+WrrA!-fa`)p&{)O7hO=+@ z&n>1fvq2Z}k|O~w5}84IZv_0^_Q{Yt){gLnr9*C0u&gJx?ji~jg+ym;2Yhn_D(FX> z7jpME7oVPI{ced>yO{en=fB)uEB^N2)tkV~6?72N^@K=iL~g-tyzGD#AbfU&$d6?z zy@0>Vj{Dwy@ATaf2r#@*9)DGZuJ!Aa$GvPvUoDezrLBPhyPn6AYLnKTs3|Y?=V)1P$lQoBq#y@f- z4=jh&VNNbPZNX64q{Ln#Wfa$NRP*9uTJ#8NIw`vd(BX?pumZhIi*X7V6xqa4QX{Hy zY?z!n;;ibu_G*phJbdAA1ZqZOU5?IE#3b18!!OOO!tw#2h6+A@aFAB#L%V9`c z;0PP>9>Vh}T|Y!q{Y>7X*lb(*RSdFHGjBdL`$?&#vR(fUPdf7Wy=gF(0 z;9B+O`3-4v+fSl7ai%bOKc4{M?O+Q`Sa!GfI}q;w>{d?7sF~jLN9&e1rFMek-2VJC z`5(WCEhyP#B5G{=)0`@i$}>l#e5TeaAw-uI1WnYWq#9Wl3Wao}7ZPN&Au%J8f-68L z$TZio;Rwv=LJzfX69|>0=2?5xl?x`?&K6z+LDE$1n+wk-5wJ=JO+yPRa?+JqeI^*7%7;bpWiG|{Wqtkeescl#2E zU4?Z602x5$zt9^G*O`(vYirl9 zQ>}I7%4cM+08o5^0b~6;V$jwyw!auPJ1%_w?0Lt1xdL|Ir&&UXTc$L>V4y&%~Le$Ly&13E6Zs_SYH$$C)>>>4!i8!H@ZcGDjPi`*`0_!4iuj zvn)lvDVM@0u2^M+E&6cff=|uRyxFoV;vlLj+9)?FSZIc2Rq%MJWh`shES9TZhaizN zZaaj*oh4aB{*D)L6>a-kR7i8=SH*M+6{m_KwwgGL_8JMDN@D@Kkk(@|Foyk+JJSVFKa}#HR}W6u6p39ibTEQZUg1bg!w2!0K@Ybxe`) zdZ>Qh522SVuQDjL!oQZLjBW#?)=NHys_)^|Pn<<+m-?Z%-V^8vX>vQ;USy`;VE1iz zg}tF?sOt;w#e2Kv>Ft=)m!Q}WVHtT-HyfqptKk(2Gv|((d&z3u>0j*HNZGQmI^9(t z6=_i#jl8L|Fi|!cm5G`8IG4a}^&YX|R}`BU&YiHbP*xY)*J{+*@ zj(6Y|3k{N_JpHYsAHx5tAPfTTowtAV(nm~8mO?nE88Wjvh-ljRmL=U%EHq@%4rN;^ z`6J0~u~Cpv+rq$@j-s5)7y-IqR*f{z z&Q4e7Up+MGL7IT!H-3KLBg&evwnWpyx?^^vxQ@adr!}e0;j;rDY&`eX*h4>P9vcoz z|9Q0K0e8!8lJxFuA&uGab|+LK;QL>`nCOe`?Hdn1fB0YvF9HVdtid$|%v|w_&>Np! zXCCu~WV5hFqyL+?=d3k+`_&d2gwdQ_W zm$7(+&8T)4^WpJ?MMw^c$5Y7RfLW{g_wRjwKIAWkgvH`oZr;h`Yl04yAtZUkqiM^D zg8fxEYpKQ|(<&+EIhXwdW#3hh*YC-$q?RBX&sJ>`>nF}qZ>>;BPZ$hVEo7ov44{fL z%iACf*|LqX)I>VFSt$SjAOJ~3K~&1L0+a12ffVddvAvb0JSKLAvd`2=v;rLF!FW;G zyO=osE&EgC{-;<*s-#SvxGI@hgKMr6`6C6InP4!{&M!zfPpcuWdzx1gC9FH~X*jRK zr9gN~quz-ymRft}K|Y2>+W4>Fn3H9S(YzWc4V9+s8*tSt6x|#K_mpK+oQ@>-`UELf zA*~8q`#u$V)u^dnWNSskJdVmXp3Ks$&0F6wG%SeKe(6YaV0+R;<6z+82)G||u+(#J zPAqris%3nH9^NPlW%q+Xb4Md-+XJ#&+X&8O>o69EI;{K-hC>1;KS3sB)Hi#xk!Et= zn=0}hSYD)`NyAAs8bsFKEA)*lX;N7m)@g*AUu_NFRL&&NwP^K6i$3>RksR(0v}dqm z2hq{{_eeM~zKz3n3l$D=4TZ%>`=D0hTz^#&k{U%pygGn)WHI`n0X0_8>`4Y z;ytZf0%kIHW^bV-V#WQ_Q!GJaFW7y=v}XfqQe*ZOvXhWOU@MJrm;t+6DR*GGJ3m1k zVG9!Tn3#J~)eJ3EGAIJN-U2lqw@8U0P9v^zJXRnybn0uPg1dQx>%MYb;mf?t&eKMK z-ECoh+5zu0omlhpr>=~(eKbS;IYk&&Yew17GqgW1H&Si3(;2VS4^c3uFH7;N=&a4uDlm zxJ^)feElw6(5xf;>a8QQ?b~hUUBD9N80PG^k5C_cUAY}sAG3Jr{QYe@z|NoNS`p~) zh2LLz^oa0F%KPx68?b%dxCjyYBl@7_!*a)BVVUbwSFa-r`sv=K4}0lOdgNV(VZ&P0 z?XJ7uju5Xm-46nLNRvr(Y08macU`i!HUUU?F#`rr=-yKQ*cVf zNwKuf=C^SO(I^M8IPCH!aV{h0@ygXuS|8iDi4jr0j0`gi>qo}E%Z1L|VEB@@?3Zgb ze>S(V3{!9(`4O&WxV$)stvw;6V!(cs805v`ko;7PTxQOOxT#>XY_hjdRb$g6iH#(e zJq<4_T1p>)BCq+F32>SCY?gU|Bw%O6TrU!rOPNAFAR_COe7sc6%+y>B18DwbC(HC+ z2GV+yIQKsry^W3K+Mn3H8Gb^gOfSf!hr2f`S@=fSA&TI%@8fk`RKgaEdT@XJ(n{qLV`5cDsg$JW%&`K6Pc4CimkWH04j-#% z`U}cmx3weEV2z|Z64@*AO|vGLyjd>kdhJT}j6>g&AN+dsEuGl>!^eN~dNZcHKvj-* zPx|7)lPeUY0nzTErCMvO1z=`o)t1J!lkdLyj$$@wtR? zvp@U1eYxqVT(j-)w(S6grSlFz)*a!zeViFtC?R0plY^I|*uHT9-JM$h=QD3}-g~+4 zu=ZOeK|0*s^D?vh{@Z;LUkAZ2Zhi2JyI;GbnGSidbs{cLZ?nty&Ye3?zHt8?ZC$-^ z9y&05$ak?+y!Gc7d$%v8GrKcKe}fRNH3n6~i9Md0diLnLcTB-~_4q!6oVTxXBD}rL z;V-!@mYg2mq1zg_8}1iwA6>lo=nj{VanvL1D`5v}d;2kc-M8+(*xS9-+ud!wbrja` zHGnT*xH~&Ra`tie({dQ>P`J&OrnT{eTUt$gO!s4J&OUhkwT)^L$N#Gum#hC*5Fc_n z%GJEmprBOS5Vo4wa!)?^jg4UXEn5TCq*|=#vjc6t=wwwj$Q`rxQGx?wmqhk}4GkL0F)2t;ndx2ZvY`7k0hV6D# zR*gML4(QLU5IiWF>~(E}ZM>>P<#|<2zkb@w)g#YlBUSxUgtkHjMm9#OJu2)J=^&u= z>L^TgNBxlXm}f1^y+v9$^mAN3#YN!0uh8ue3#T{!+V3lcI%H4{^Q6b2fRXuKQ5eV? zr46OLQOJoT_zwHN{b*o=;G2F-YwZeAVYO(W2BW?)QlvRYmeCyf1gw5Rtrj5beQ!_I;vzU&=GKRmP}W6MaHlm*QEg4 z+*eX8bVZB4Onm0lx~?Q@^fRz|B1Hotnid=N+K=Cs32XDvt@Orb_N$NoBE!{~5_9WV z&2p~F5Xe%VjhvII&~sIfJCZB=%w>5X|m+ocB@NV~AHupzAF+!w;LgX4v1 zV)DYm!u-$w*hRSWjO1iyK(D}zg^eVw9j&A()Ms`iIU3wTNpP#R(n^)q;edGdmCg4K z-+o#6{><5PpLUUe<=CwQnI>m1ugutPf=*iblpML#P(NqTqFF$er)0};ZN%0emhriq`#aqb9U?sx#Ru)&c*w(-# z==+~x#dzyakDvVG((dl=%8}!*MYO znH;DkUPpu&0zBczLJ(GSYU(ngDp4Udo_g^5>G|06({dbC;9L#X+N!6&zVl9FR0CTZ z$i{Kbkn`*epKg4puHH|5$)A(M)eFAnKzqH?eZ8_Q<5f8j=0tWXtE9IvvD$xZ+-s4@ ziP)_VTI5y`KSE+8HiRX|8iztxw)jT95oO-YRARnuZ2sV~$I+ykg!Niu)E4wC95h4^ z)7x_3xiUTnM6L$*t0yzc!!|S4!zTW+v6|Wg^lB^_|Hzr_SAMMisDRpiGjH{6ZJ5bY zk)QVVeKfP3VHkxu@6etUlbr)F4t>xDD~zH!^%e2%z^7dS69)rDI0r=TE3*pD=E!d+ zk>twEMPD;NoBDkti?~AZ(Lfu)ju+37`T~aMm_SL@8E=h8=N5H~etOU9`x>0<(hpTv zm_}MVUZ1%(Q=wK|Nh^wz>ToHif;!!fT6_tp4Ih8Lp^5o5yONcNZWz8v-v7pxyn24L-=* zsVnW7@V=X&6eDu{5hnA0u!O#wXPo4Xe z!fJD!oktFdyAuZ~lV*2}$O%^OVz;%8`XjXcj2*jM`!88n{MyESN3X2gjUjOpJ0gZH+@*3Dr1| zO<;$t?%S_%~ zn5Kd3<-)Nz4ULoX;L2X3Fw>JmBgl~skjZ4#M$H9RO})^TA9Az0ZQm%MS~o$YExdF~ zV^OEhk^%aVH1UblIL-8BKxADRGoURp2XbV)vmo55WjBMqDq;nQROXmjfl^j^#a~5a zM1}{}gX&5$l|&o3Qq@keMx^d)x#Bd{akbnU>%~(;81nsKpGb#L9}ayNF2}Y}KXUJZ%-d z(^>SS>A$wEB(#vimbLO}&fogOD9ODEau#a+tFc}vhpB({0W zGBsMUPmLtt#<6cp;2IMQS}jj;^Lg_~Bma?M90^O6C?_k6?GldjJ_Z`8RxKlX*>c z06xvAYOGh~df5AwHD`$h!&|7KAW1A|4HK89`KN&?^p${Y296-3Cl*m=SLRIU)7`{4caRwo0O)Ta*t47A;2;N zUcAjv$sRY4dXpf#?x4q7hRT^-4IZo>c(8_Xa1#j-JXAS-OoD!a3jgel3yZ%;474!X zd53GIx$?N9w=(l|Xg6M-E0x=GtL5?jc*!A5Nkr<=Sx1)LgHJs>BJGv7Kd|3Nf0>xL z{^fIH!4EH7j>5Z$-$3TZ#;?-w*4nZ|+a2MZ?-y?Ucw02$D`-VJZ~zDo)DnzUh_&36 zHl%%NL%M(No3eydZKLt8G&NowAAhp6%K@;spB-`@9O$<1m4lrf2f(5`%gx^47o(v6 zIe1E-8V{8?4#~o#6>DSjv(NXh4mb9PPMs>1+QPeMZXuR6eW z2t0qgFUmcP;%)aq;UC{Pao(p=Y3EOU(73tr#P} zbWekz)-3=la=7GPS%lew(ptWPTC8&Pla>!Pm(ZG|2s!&Jw$IPhUs z!jgk9e9_1p`5~?!_40wg%(P~LIcT$iDY&jl&Up5>^+&~KO3z@ypwg+nkqpgc4M{D` zT`Iy>3#3_8dW%5GX{*B3vcH+Gd5z;4O=8Z^aNVYx4RSsB9q$gzuozh!-R`lbK>rKJ z2E5*i1jMQc}4q6J4f@y)lgAjvG@iWR>t9SviIt6pZNO}4nEgt6}gl;;@SH=Y3dg%~}7 zr)o_=fEGF~C-UF@P|65|=^>u622?^lQt?0ETKW68|MazY5#cOT(+=8&U>HV?U=da( zgm(-Z)h*_9WtTaXIe}-L|8hcH>}Z}9Hi?9hN;XvoU`O@g#fr$AX6_|y zX^lpIv3b$!&N2!lDclM5pNT$rzbyga~(W|I>1nB-7aWa+m@=Q9E+8=%92v6ICj znhBA=fpiXcwt;FSbwsaz<+T?G@Zi@QmmC8|+aSW7W&s{BMbFNI<~qKIgE{f_&X;8m zcC{+qdk$!x9X);U>8HPY02lLP2f7dMIwrDx2)_ID=;&}HNW;650lkMTjt%#}`Hl4( zOE;F5#S68zzIJnIS)!PinF4*l2`nXG;O_^L$J~=W;QQrs^RQo)rbgRy=>3~}BFzmF zo^c?Gvm?F^fu-C*zDdlq%y;(yz&nIlgIguQ{>DA{Py#t5L*ziN=D`}jubx;)tpT=P*I}bd1(YzY8PRas6wDBu}aqRQ(zaH%Aq}R znhvPgzGMlY96@Csbbpzuou>Xl1D_K3Ey(+5tLZHJ*(^{4s`N}ZI|c-5s5AKO3?{lB zxixt?=GJZ&V)cj2I2HTtBd+>b{$w2I2gbfhw&Lp}G7{fNWc$5IoGtdMC0Ro>C=Tam zw0)N#tclJ_W=)FDt2a5(U@E*^O94_7G`NNv+kjZ{G#~4duG*L-9ZN-K>dA?=`_jA4wZQO2 zH_r5jbTL?K3mL{SCG~|e5&lJ<36w&7HEg4)an>gu!SU9i1E_7+tpqrN#$Dlb^ z*ah6{O|oV|Cc!wGtkfE3%yotE$w~gezp@=Q`pRqnhrQY1#S4q?mgdCxEM2#bUrO*~ zX;rFx%JZ{mn0H_^U!D_kTpmXofsBRAju7{seQ~(GaCYI#r&@<_bhr>i(Z=3$T|GM7 z2%_-4b+JP2NDJWR#`gC54Uu`5mv2Y_#xkl9mKj7PS-uH47hRs zx2MZ}WKGFBE`i6(rynlPn=lN1n6;kus)dvmmoT}?bLSeHOO>*Mte4ADRvuRj}FFf?6Ly2%t~ zTfL$FtdrJ)r76}Uw(u1!i_(%SH9S!*SE1&3kOUXF0$Z1cUE6h)EJ)Ryks%pUx=yqG zU7aXLnW8%oi4h)~k%qdin|h5G{FK)Yr!js@j9Qt`N%xaH&IA5{vSg$-B~GJ2{aE0- zDVb?x4yiz2GYvD}a++qWJV=$0rvrwoD5T3-8MD`<)jA!8UbHq`4gkPj&1GPuKa1W$CFEFh zs}glUCj+s~LNxur*ie&h={WXzlU?6Xq`%_{a1!g}x0UE((pEn4z;DgGp5?EO~tzGOWwRCU4sezU)ObExTV^(!g~wZ8{&1I zcvHr~K;9OQTC$NOmB6q5xxvgT0bjwQA{z!BuB}|_edkW@Z!0zJE|N7}`OeaNoAl=H zApxsH@P?&X0yU)4LGTx$7c4Hs+E9o3HRv(|DjNuN?tl;1=-PssTmwaBQ4(;qh>pWy z4gDa9ON*fZFFqb zYV1d6MS%_iQK8j;by8qBh`uL#z%2XK+c9%tRnUvn?}^o!OG)a3#@&4h>F7Hc9(%nz z;&*&U=y_H^ZerjIri(w#=2`s-04xWWe)GCeURgh?G#n9b5RMT#DV{8MzQ(o&giiu? z@rR8J|KscWUfa5_xab&nl&jqru|%LC%&J0Am@OHt@q;B~tVOzaW>mVa*@z|((-?-5 zhb7D|1bbsR0Z*X~dQl8Bp7B)6G^`IxNZA%_gOluG1X>m{mNsb~`fu!eKIfe8y(x4i zzKO1{epnCr=yT5J2ax#}|G4lC0xaGEpS!i$A=Puf-szI6h<2=~A0#}P;7X(t&0i_z ziAsLj^=^jF=kuRGe=upt$T3A*0fV0`UoimOUq2e71@Or*H5zT-B~U$DGrV_ejqE{v zLf|#boec!9Qxp{fsyI1vt>0%?FTwA@&YiuNPflnI+XiUc5F$T)uzfTy2|1RiDKLYi=3h@u=2g%Zl2wAi<52aUr=EMU_1lqh5sKE2TpukMbO=S@xh>)>;NfEwCwR&*i8q&Hq>W z%d6F*`g$E33$4*oy!K_v?Qv0(qnVD_+Old(waku}iV_wj_ff+aIjoU!8#~{kr*X^7 z%w>8k4S))^A-i+{m~6cTc1fTXAXWj448)G?REu)TQ=s%jkQ^%t3~^e@6s&ER3AzD5 zg+m5XA->FKy@Z^kmy?K5S0S+P3HDlvvw0o3l2fMjXCZ)ApxXT3B6p{!4gtWh;VN;B zF<(rjL1F!5WGa&3Gy~d_a@?h4G6sg~2fBz2Y%D)n12ohcEPn@0F(wf|y_k&8p0#z? z25|VQlX_)H?eFpjf$v7rJK-eFjM`aB@eQ`y3jagM~+9 zgk(si*TP}W4axCph&34UY1oPzT-4xVtt*uiC|82`i>K!F0VB)nU%IX$Rfa@`-I+g3 zllS)&LGS9R3s=m?SMzOPcr|?U+C9Nr9WJAcaFMVV2^^|ebDM_Gb$EprIS7kJ z(7r5t=cQ-?i(jU>%y#LpJg+0@`MG(SK%0YMzzgIrTBu0DLQBG)xdCaRQkilqQkIlk zXo(pZVrXoDX*oRmonQU@o4#3ISnIEuFU)nkCg`)7&#_DY=|?Vl&iYn**P2L2u~4AVm( z%yNttCLHOL05;AF!pw;2KrH#lydvT>7rweZMpKbz_0^8uIWsIq`5c~fC4`RZu{=-L$y&dl zxm?mqq`A+`c*WXVT{hTy zq17{osW28zX@$mux|D7~DO0PugC#oZS>g(koQlY_KxRnS$Ifs+A=`8n)gy4%1#yB; zhA}yHY_F?#iw4grJQfB4A#a?S7!w1Qkc=feeolUE8H;r;>!p0gWm`+sjHN7#Myd^Q zDeM3MAOJ~3K~xzp)LM$oL53L*)! zjhhU_iW_Z?lbZV|z#K@CpyX}Hvemzyv?YljALLE<#&z1XoVaU;w>1g9~$#i^c5?G=#pDT;?&edX2<%1fn|$ zn3X@~ds>lq8nk%s-Sh1Q;WQ)y|mvWKTtbU zfA;jrocV8jXfSi_2=sEt@W-A0F`}INH>q8SI4@@`6TRiAiyH*MG=Qd1NTR}ARdgi1 zg?_57PIDYWp@uy#`T;AB&sGK!C z*L>nIzdogJ)L}%PMe{;F-|fPpg?}%04DGFF%sW96`m3lL*LgJv z+S3GPwcl!Vl#GPMo$G}f)|`^CC{{xiZ7+i4O{H`M%_iKGsHTb{!&cZA7jM+zhpZ?b zYID>@u~;l>hLxk`xzcY`L=to4l1(@^xRKYnPD)dwu+O#O7V*$z9usp~l&3sXm#YeR z#b`DiDp&QwSPWGd4V+cC4E#>TroFgZ>XbF=@?`+hRlBDJu~xbohIahSf@m;VVde=L zE$gGv`A8_H_mtobyFlhAWG?LC9tj=_Q@?_hN7-2ACVF|9{RR<-H7A258CW-e7Awb% zHomacN;gqckWO2Yd|z!$sw{W*HXo-72>XG60jyw}w;?J^??l&w}VG*C(+D$uQw6jiIZ_@BN8PHgF&v zo*bfOq2jWjx%a_eZ=Zkjt=|?3x)V*aG73Z9O16~-(@g^f5nv^~3-=8+x(yaf!R&({ zRiJ<_$c7k{m7POCcWG^K5eN;Q+@MAy{xp!~z(|}FzK)1!1HTWeTW~ag_l7f41-kxMZoMYuCz%7O}Lx5f@zQ;z)r$& z-~>ciq_;XP17@-J=5myV#dcqg+(7yUu0d&`7?TVIt}p&1APW*O7dotEyWwT6)%2X; zFG2G(X3^%pz{d9d@>kKtYKy*jja@sKB$P zRrUeL!l1PYFy-i~R)EwIWfeahDXojVJeEPV=V_}@N;~WY@5x;&7ea^Sh`icii6d`e78j#)+||7(d0KSH4cTurtGI5LUtGgeax~%YvNdi4uuW?-5#) zkx=b0JS8%$m=~D|wFlBkK%E+$BytF=Ju34M@Tu>hM3s=vlanhsTnpqWVvK{f#V31}X{&zJvs@#4joUww6w z=I%ZYNuHVlLv+bRL=X)6Sdbj(ihExoFw$Icgk38U5zc6FbS7t-~aJ-eXniZ zcl34-yL-^>WgxHxHwcYtkZDj$MrGP&32Ra#>Ee~zS2K(VgFquQ8+l2HT?h?na12UI z67rH}#bm)Xw$`zRvapt6oPg?dVJ`_TGg+264F4PZem>{(`Cj>9QKCrEPs_wP_ngo9 zoI_vYb~=xB;uJncLfm7RDkl)ug|LylG$2><+iaw+a3EIcbnOHQ&|?mTZ;XvahW+|9 z5suuSUj7@5&)h`VVP_TQ!EA|cm&WI^+3_qQvMBz!(`a`Zh6`uM0nVlNwOMHwguYy@ zk@p#=N%1--0l|}mz&r{zmy@-mx%T$ywsbF4IFNEev}a1h8lPavIgy&nvLVZm;u0dE z=~UrI{qcKMw|v;>5m+(+H|{Y`K9i`T(6re2Nc#}pxGcb z<#zn{+pPiG5aKvyszvzlIu#NjlM3`#2=IlA47{X4e{_*eQ&dF6<|#5`kyd@{eN+K+ z&Eah-W1vQ&($389-sl+KTkZy#saywQ_`itp-ru?ayd@xp9)14)?)|N=Q4m3~(hrDA zuigBNH0J7!8|OAQ&Jo`w%4^u}+WPAHgO?9?zkXzJ_nSZd`)X-uc<-6`w33+O;}C+} z9CtNRM@5%cf@v4HzYz3_y?_M*Dg-9$+7vP3h0nitvRZIO;bp8#Dn?3uPXTa=4O(_u zA=X$r>!Bn^WJ`|g16`4t3s~bt!GZd=lm;tu7i>$ttJ%$(A1$l6QgZ~=TBfpy*brXq zy6TzsH8+Irbdq9R#*>xyy4u_4#-Wg|j&6mH^Ewhi(|gHLv#`3GG)2R=kgIMj1MZP~ z6vszWrJR^%iYdy8Q9FvPKN?qAVTQd~bz%UfBST^FU%|_z@a+iB$~&pT5Wu@xry2#Sg;V=Gz0dK0ZbFgntcg^{LyX=urk)NqlkRipRTLxS1 zM@Zxmv5a1WJo}-b`clCH7JoR!8T^t_I8WKkXf)#74;s>@VYW*1{t!KdC&$~MtCd7r z$F@9xW|Es=0~ed588n-+^-GNsT!uuRYR29KA3B)hg#2~_AAo}>Y1<0r3ykPw&PquF zbzXGqv~(JBf;5Ecbm>a%#0mQ8IqNudUS4*_q)^tFXvamrvuk5eWH zSaXK)=JxjXf}X+J;sTklx&~}I)IHxTHM*Pq2KjvZC_}hyesd?V?M1l9o4NN4lxoEv zGMNqP-a7x0L104P4-EQpDX;m1N$^EVg48a;dxXD(!GP9~c9s&uotdj;4x;2*2s$Ka z1bff7P+%x@S4P11X`jgeuX*ZhEniY>NeFxtAF%DZO?8~${KmS>C@DcEeK5UBmRqXXKA>`nG=h|O*k9ohF$uaH>esUPWp7aZ5h*AZUE`k+}Zckq(S%PuEeNA`^)b$9{z9ao?0*rN`4Zsh!7 ze!g|m6Pn0%1B9R_#Xk&FvBz;$C#}0`UKHc`SrwnP#lRBi*hLiwaB#XuOZDkcih|-A z-j=1qF;CVMN%9ECfmJr7O6*OZ#z1-_PZSPHz&xwO)qIfpEJLVQAL#`QTX#GWr9;~| zT@D&*Xq^nX|cjdK&0!uC0cxAAiXO3pA1)4i66x4i5J3zDQtJ%Cpcbm$E=0 z>L%jlAfk`#vr3_3m&T;zB4%fCnq!)q;FM{^Me?vXfubV{!l2xZL{rnN67W*dT(=^+ zGT)z4nL5ROX}X;a&uKAj=h4@Y;H0c39}jTW1{<)Mh8qBHrqPE;z`V`N$LLn#&@3@K zV|A)22L&lqD&@Hbi9Sh%a!BadVf+fsfE_~Jv*gAwKMf8avO4~EFMU};&<5mX7NXn8 zyh21)D$7;DJp1iX6N3TfP8(`8?<;*A){wUWv-6u(#9tw8gD)4wh-IiSA@d|4nh?19 z_T>gE(7fb3qX}4ZFhY~WOnty)&?3tfH0K$_V9jt22f=aqwNw8$h>`&K%3G8g(eL-W z-G%|(XU`7lpUVq69nu9d=bCXmiAjnFxAg>QTy*^l5fB9r{WoK@C_|7rfy)|D= zvE9#+Q7qVe{Ox%`-G|J4A2ROVUR!6jyYc3tp}OY`;#LF9U%*|`-iJ!Tnx;p|?rH;6`SXSa7kMDHqG# z4m-k&{o)%zkxb+PeajkM1J*(Cr|)|;UrO|n$`Ba`eQ6v*0<%D`@5*0&?!eV7tODDk z=?+Kxk6c;v1u(~^u7U(!h%HM-!v&-?f*#90FZ-$hss%X|AnwhNRAJke{xUm`5dGwf z>TC<;aTLL>sVK7kDW>zR_eODTkZ-R?aiIZvc4PAsr9Qjrb&8N&VJF6sm6d%g5IH09 zR8C~e7IgUPtB(tlR(=@<)F>L^!b)VL5&slXTBybjbZETFm|aiO7!JkQ2!7@Wnlk3Z zjvPt=%t^HNqgble`{+UQI`nOg1Y5LVhngP|f(-!9>qag^r#P;pn~ zQ@VAuIAJzMYzET#QSDml{A8`yyjjS`s?du$veH@|6RYVMb-K14LEO!{AIx{nic^_O zi|(|rhGe~3g222aGz*TawyHW>doktpx-^A@ZK5ISIPO!IPZ8LBSk6`o)sU2jqodW`*YJHWv=UDusGoR0K0DHj%1K9lvaVYRY41bX#G%n~?TG4x3Cc zrCs92U}+o#FgH<9OfS%6(V5nmFj*!~Ra26-IOB>aZIeq8@j3=Hw-dbA#QrTbEW+E2 zh)Q;anGc_?PzV@DWTjIx%*OLnfkf#eoU%#ro2d#((3CtmM#$@oopt2L$#MN3UHS^R zn;jRH%Q#DGzCwB{82PrD^HLrqdXU&LP0p>xwYuyS@z_^(jts!^#!)S{Uoqq5OFma? zg~{6FyO(p7IrI*iUlqO}1D4vY<|eXKF`+1Iqq#{6#fTWuUoNtj2i!|d8*$530`m@!Se;%IM*%@Zb$J%UzBIxUL zJ>b>nTNlJpWnlOA`uduoyEoWQMJltQyo(z&+`V~o?XT;rg9i_HcYk*I$@9lguRYrw zVY`I826mUWw}%ti&GAlVZ*S`A@u~9h<5N@R@BEZUNxyvnZ~iQjt~?sqxrJBEmVc zff_t5E)@JDzAE3^rg&_OIs(;}9o40i5?o;|QlO*0^yP|ISmo$ATI0RgoVAQ(t4KF; zeHD=H@~*>lmdU0cYt(>E0(h}W1C|{c?ph180I}>DIg!O}61SJFnyfKdjJQ5V$c7TT z?ijruP+PrM?y|37@5Ej&XH*r|Sjkz@lQkU@wyD{8OG#FjJiTTCT=#*I7j-1fO6!P_ zDQSbTq#)4nYpV)}s5qD%Nt2ZNp)lsAI@cBM9$L$@7uOWs}2{v7^~uj_kl>pa7!yU{MBiZQWRpiBrXMy9d&$f)3DmL?M|`VrS)N%SVdprIR+ zwS_Irz6k4RaR#cP4Pg-6FjkYLuDh)(-MTdiA}+Wyj8a(eMM$$IFhUt)|H8iKdEfUt z$Au*#wtOTXB_Y;xp7(uzsN<+D92m}BrP?}zrop$~mJP3Xj2uv==XP6AR{Vo^8Eqy0o#g(b zd-opgGa5OYoH@*f#ih}dSdS2XMQL%E>_W;U?L$QAq=26+j>$sv#wn#EFfYO_!Y>0R zTZBc{ERdomrJF%zRG~_(vm&0BwxqlSc4Q?)S`15|#S#XR&sx4li*sidJHVe*6ARLW z<|p?bhiX7>iEY?))hubi-+%7Z!Wjv{k{uF09pg_(`P;92Xzt&s zesgX{X)YNtMOUyPaY5YYoO)2CGOMXjjoglB+hQ}apbatkBJp|FzMka`2t2#sZW(t6 zzh`GppM0@j>@L=3D1Tnm42~HJq6x1Kcf*<eF^m6Z}wsB+^bI&TM`?|t-J!ASt|F4b3Hah`n1qT1!+}b=~A;aYlsDefs)qZh$-r-!eS)~@a z!sYATt;@R(cQH?PpnKzIS3q|$YIYcW#n`T+yWH-6a{t7Gop56#0$t+nWRk4y&+Rk^ zg~DNB`nBn$`RU`w9q%m=df__WaTgqw6%4;o(uh1vbVm(y+zO8|u%9n5q0`~AdlC{$ zaMc1~+pVvjTTlhEf@!8F8YL<51&xy|$f%@O!jseUpQ=@5*MG zF%?>wq_s;KqoHzI6)koY7A9;m#g;OpqGxQu0XN0>cVszcukg{4-1HzM<__d6Q^v}>vJAt>9GKcS^b^9n+Evi!Q>Nv(>dJsURF)|VE^0{U9`Cv6EfBKFkR zTXl6vylg(+7^)g)_T9bKYY^e!a-^#|XSt7UBi>S!)X^odxqMS*>BUIg0xra7M5?>p zjy3ICV{bd)Z9z_isu81Ci+QLq~tJ9OJqpH(w}ruRZ^*0qsP2EM&9N&Byt2Hmka2 z20&{E5;nBSymTr^-i9SV=VfP%{jH>6Wu;_+rwZxr&9c2WpVU-m37l+EGTjnd9FqLD zB-x6W4U!B^y))u9T6r-iQ`SW#bdBjAa-aLeNU)|&v*b|B!dbN_)i_0mx|?og z66XO#SiNH;z?>3^bOS$PPhIJJYv?*c7<6~h&{+By!jRR!Mc-K{5m@vr zaT|R8$qe|1*PcbaeRDW^d@q9De+vNT9LZ}s?uT?N7=h71;2?O2I-pUm@cB#J{_c_j zixg{F>)7#CRKg7|vXxHKbTuTbDOCxdy)e%Y(aj z)@pa|%*Y6u6nI!F3`^BY^_AVLS5KZ?y>jx#>MA|FH?ZCP^L1os92~s$@uzoheRBV^ z2ZxUCu0`A3pKh#8+^t)iE6%~wTs?7kxb)h22cy+oH8-BmRnY((K;yrAm>X3J)xiid zD|`uWFLEaF`tD-I{pH8dMURnsRYm%WvMYpODkYG;~6u9JQC)p^<55voYphX#L9%mS8;63Zoo1}%a}fkJgcl^JE3%2 zz*-xKGV!Wi(=M|)LCSqH8tj;kw+<;AwneLz9mM=a>4YcLJxP^BT2`;8759p#|>diOXcX!Y)lm6~nwlFZL=?LZqOhWN-w27u*xbj>4aN z>+%jE7YM--^>c7c^<0Xx>j^{Pz%CXD!tz@3Rukw21ly2wJ?mxA%h3+D{hTj6uqNMS z<&$hah?cIRfnL^S@N&x5%AI(1FWByL9UnubdtiHxG2o-#BWp)UofG?yJ|Z*eBbi!W z?(B<+I;n=`adaB0WtIk`hV62<)!FOWX`?QBX?+Q;?qwRYtbsWXPNfnzd&Bh@+c z`%QthO-d}Sz8WW~eP)ZR()FQ$b?!8N8FKES*2MBuERuoo7E%J`4pfQRxtpC==iFVm?OD24>J$ zGD{>E9l&`Re$y!|B@8VSfF-2|ky#sIjjhHl#(^Ov8kL1%R&qF!$b_ziC}X%lvjOCa z$5aRjw?O(wm;Oo{FgCvfj-gRJXoX0SJu3juX=Tz}5nzqIa9@2&&nz3*E*ReOjv%s# zofnJ;XK*+(3-D#k@2b02Lh^GL(yQ(weMU2k!nrXc=Jd&k!Ok4xS;qg6dgH z02%Dee91kSblC~`(%V4Ym$jkjqAv*KF?RAgAVw7A9%^}iE`c1E5k>jY-N{B+tW6z1 zUSSUAs8VfKhAWO{R{ze>Do1wDp8eg`tJi=1#vcy;_7?}cfBeV&&;I#fe=sq=YjpQc zt=8?%3`+fGrF1wyJ-xJ4b?g;$=IXdK7%>7nhuWuM6Qzp`wi=H{Bgm@U>%j^DVYJixmQtq9n&z&~mu!yKKR$Snhu&O#vYe;2+ zRMe!>8DBnRI%FZs!g$NRKS@Pb0^CHqjGS3SS)#5^h#5&*4LL_HXB3HL16)=ck#yUq z%gQQXhk~AOC8ARg4DrM3U?vxSa65TSd4Sk(GUL z&%X^StG6za>hU)I}o{4&v4jQyU~(ZX3=umKo19z zk4Zn{jl`D3Jr2RwBbSmr)7^LPIONE2gKxC8wJfaE5dpF;gWqU(q6x36raL}3npqo` zP|3Bhj*H_$Xn)quvVVP;i8|hL#Fef$5orO@vSl%MJpbh~Ru;${X6x~kj(9mx-cB*r zS%%6Elee|(ud^+RY5{A!64$P}+f~_B2MR5V;81QXjlB(X7In1dsH19;MLx;^03ZNK zL_t(7|7Az&jDX=hvA{5yY&(vu9nF}O8is~|Hgh|~fW+?u-G$w^v#lHBx+V;Cg> z`x`e2G7vRAdhgz&{r&wU>wojv?pwFQQ@>jI{nw#X%F1e28;?S5;Drw;->TJw;;Jb) zL|=l4nKe0@+GiFQ94Nwzh??3?PTEPcO8Sr0P{D`}!@Dx=zJHCI|7|$TZMak zaO(7h3-%MnpdGykPp7|j=})rCRc1?k6~fyWk#ns$kjSfke}Hm^D3)Ui-3)`N*Xsn> zRUf#q8sogMBF&26D#M3og(}ZF40gyo`{Ne|;J!07B1zy?7dv4?wKbs;QFO!N~Im(S{#7?`vn;=Xdl!@4q4EA%ke8Rs8AqWsLne8-rQsd zAcf9b{S6%G!zHX*`7Bhh58 zJGV4lBJP)%!c}spIR5lE*RSvH?nWM>f4#Z1v%j&i5nJwJyPI_XJr^C_?KkJA=L;w1 z3)9nuYN1dWkKKpqY7Qpo%BWPRG@EnS-&RokgxVwIeKf}_$d;@OR*;vig;2vGo`7Na z00On9ySWn}y2PEa;2?aQLnzk!Pp1}0LNmS-S1GMlACz@3tQGR*vc^Pf?3Iw%jP6(^ zD^fzWxGB~#wsi<5RKq1-nrA5Cldyz9O9P@Aj+A?=RZ4RysaP)ip>sK^8}K7)OQ#~= zRS?c3BGGa>5v#KIJp>}}O8Y_tHSVO->8LM3Mat_quJ&1jJx^zenLex8B+dq{vWrdk zVm2Xh2$Q)69!#nE@NpeIW5I!alVEWWh>a-d1;)y`x%KnxC=m;<9wYF=mDhdHhhxa= zMvnts8wb2ZI2Hs#E&-FejP;SpQ7A^kXJh!F%H^2%*OD&0xN6zzhW^Lb^}V)rp5Zen z=tk;+A&>_k%QuwoJ2Sk&{TKL>#35v@yN!-e$7P*{-ZyN(Qdm5C)3my1XXT?>=+ z1;0ABZ{@!jEt~6C@soYa-XK}Wa(J}g2QuSZ0WiI>4wjz6f&?${vugR+QOYa7seS!M z`J=BvN}Mlmg9zriaJ764N}~yIRg0q1vbb!?9SKcFKwrmKHSa}eq{CbiSSr2pRq;++ z|KjbKR$SiFQ{Z$0Og)xQD6!rI!{~(OC5)G4KCV{BOxI}Qpe8;;Yh}o;s^T&;w0a2> zG@xP3Bbc-t!nipM3>?7NyJnFDWw1Lj1zJ_bdWSWekqhI#{hw zDR9OfxZb2NnyP2Gf0OBG8iTyM#J1HNbu^* zZ!2ALg&OEykCSKRYxv^9o-|p^=P(tPvEUVb_j~{b14g^;L3{XR0RGIuE%UG(`GXS{ z{Lrz%16q|FHh*#F@!?y)<~uMLSM-A-*@sU6HKwDUF&+H&_YR}!rX?&Zd9$MzkR!gti3 zJDi;{1=}67V7~&|86ma8ARb=nHY=nYaf#pmDlU>3S7((Msl3cn}-NSt_$S zg?wLv+`_q5>=D{$H(RffYK!DdYMIxzC0SIzi%$5|ow8Q^8c68tFpOO+bN;wUib7mIisZofBmS`FPteoXdx^`d9oI{(z9ki5A z1x|c{IaX>**i1Kkrn86BbmRrkmUS_(M6A$r6fo86whS<{bd3RNbb4e9*+Lo&yV=`@ z*0VnE`6vx~YU1ah;NvMdAs%6U>+xKfR0CgDM9@778{E_&d60@<8Q-uOY5(u&ZN2O8th{RZHj3z z-qFR2V8v*gIwJ%G3s!q&e(b@0$8tAwd^od>TO{yGM1(&wM8 zGU=+gp6z_O>P6;8@hliG#?R~Mk9F5TgH|QK#$qNF!mNC0&IEAwj}l- zSq$Zv5@}4N0mi@l)^mNpgLmI)!_M0HDh7PJ-G%X|GTcH`hvRtj17tE{FS<4CcK>(( z;UN~jY!mz)>JSbs(;4X)4>3_@)q?UMca0CT17Vl(%=h)Rd#C>S@Y=Pzw{G1+X2#3c zY1h5^!RL?vy}h@ce^5XDn&X@^hrC+{4m&%5;I&7O_D)!LvEALSCho~kr|ow4v}5Uw z-=8|&>DD^#)UJE=P+35}?4DD1AzioQsauP!E+RD0HVkc71#L#CqNr>QD|3g%TaY@p zx7fqb#+cfHv_t554U`-PCHI?|F}`!*ev=1{ZmqFEbXMih-zltxC5b1qU} zBz$I7p^bw{f^%^wD9ptcv#iXFT%4skTfvZq*@~)Si9*o|4_ekfAZ1o7SM(mIxaj+h zQsh)o#;o`&W}UiO*p+n&1|;{(SA}`xg2~AK?sk?< zM}oSE_tDZ~wBrkovYbdyfFrBk^*CuPGs-606SgY^2M}(`M#WMkN205xaJP0Z{xs7@ z>or4E3Tt4|b;>w%MAgWHwduWLofj~@q^+=n?&yRfIrRG)aW!{vkVgyC0`1-OX5lnc zHH1QkbZL>i>^{nJBdMPnq=n^Pg>*R!EA`ROL2acevgqz0vN9_q9JhvP5Ujm(`W9&w;W0M@oIBgNP1h zDYW|gfejxC#z*9>qpwz4nb;Qi7lBTpLd9C!y^!+z9TL#*$g6L9brSFUDMM5sX7N83S zv_t4(3>h?t@VTpGz+-Bh$JAQY4QT23b;z5H&*(bZkGTESXZV%y^^bo1JQ3C_{j1*w zpPLRBUjpF&JZ%qe&m7i3f(6wtL`djGssX3kjkW_|USKq`6souG*albuks*qC*FGK^ z5K9>C4mx~%c=x?)@7=t4>-t~*zzb!}$f<&!>VwB0|7-hFa-6Tf-oejA>T;Vc#qQEH z*xftcJ}x&=(YUsPGUM(+=QYQ7Pjwx-&Ks3^w>E27lruES?HW?P+$)Pl1LEcx2z6z? zIH)Wdi)m$uvlf6~p|Ga#?)cl4d3!dSVG>_sFcu8bTMdrI-NV9adhST_R%HufX*iM` z1KwP>$!|-cld;7|s;yq>&z9&I3L2EF(JE$rM=jZeZ9y9npZT4p)~x{4v86QUywHor zq=`+W$%DzSL#9^F>K8H;HlZK}Kv=;Z}%< zG7`L05FApHvjMX4SL3vklEqn_sQfk3%Xx3f0GQ+9F!c2a&UQm?l7(kQlMJ3CFI@IB zX${azLhgu?W%sdz$04ni?RkAIfEZ`6f;$t_^}4IHWBz z!I^;^1s{WD^++Mv**lc{$hi=Vyjj-Ore#5A60gux#9MIcNHCs`g3l=P6e-(TG}!#S zMq%Am8$SE0kd-aSkW>iy%xUV|d9er9tQkQdgAhO|R}fHA18qyR8Vm}38zhq~J02^e zF5)Nq;=uiZHv*$c&^Et)iM95b5?LsOR--iJNfJG|#ywIZM=Gz8tiWWy1mM&(R{ShU zR^R->{n5x@H?lZr-1tWNgL_qujA7fsTaOkavc$FVY@9#;*B@%kT=u-SOhFX4woOZt z6wX2!EketjWhG}JUXoHNdXN&<93}al;b9`hbJceNCrW-+S@3aQks4K|TM|@dDXt>d z67-j)O!5#Xy?kCjme@|)RK6*$i_vwDD`EH0*sWAmO(EsiI;KaV7>Wy(rvMe(9gZouk}7&A<~y7Mu+^T+7gWj`S7z`KuknN;=LKhZ;U6BeRhF(A@i&eFSk?z+1gQsz%k zh=5)0_W0CG4aYCLLq|d#elq>y%=Y&2gXW|0+6w06wfXICr_()MsZ}~i@T%b83IMV; zb!Xre#BApNnbi=lf#>A7tmC$GU~RiLt2p?awP)CL!&HRK>qXnqT)2B1H3e)S`FY5> zHD=6U#vS*qJICFx`)O!VKA2S;mZLLx@zRYKUtP5*N8134?OH@eQJSoYht!-8UAD*$ z^9Z-p)@$)s+#9zzL=MdhIo~qWD*C)EDW&3;HThZHZ!ttg+8Hv=`gixxd}p8E>T1MY zJh=dlC%F@Ke=PyCC%x_gL{^4N?~#w_hzY$AKQHZwgSAb!sCzR!=0O>lJj=;#??mXvrtFe4!daGUDRmFK*u=3Lx;(AW78`}THfd6Vt9L_}gb`U9taX8*&BU_k z+*bDzqm~JNk?mnfEK8xpLuZ^pn3yJ(;U>k*8YbCRL{_;~Th_gTmV(7?J9rPZw#d-i zOlZ|tw!BF7RZXXImIz8o;t)Hq^6F5I3hQk$7fYAMglgK5B%=e*xe)%~7IjtVQ!v!` z-o1Ugj10w1&u^c5vr!Pk&{P_B3;*1_e(`v|PYITkD=-#v%E@$BLM5xE#)OMknM=!u za8=at%KRFS=SeiX(i;e_ONbZVOCNAaH_W_JL#EIA-KyxEp`XHUn2d3R@XA56WOazr zniUKbO`C&Lu`ibzC;%q!6)Clhpat5ijKl)d2e4Q1&tXm&Zm*ou1RrmpX@U4JYkoX_ z<;q>z<&N@FiL_Lq$Qc?e=3eC+8V$`)X-a}+IEn4p5dfyU2qS2!uBdfxt&;-_{l(WS zR6gf|7DYEe<2OzkRIM^|l1txJgg~!K@MK@YI7&>T1{ym77QSYI1AM}jZ#{Pe{o@l? zelkR`v0oGbK0G{p^5m%%VPODUgw( zP)ozr&D{V;;(k7lRdl&{{5UbSNP6u1b-z9aT`xljRfCteL%NF*bJ1|(QEYA=kmKAj zOm{1eM`c6ox4>UJamPILYvXZ^o+nJ1I{@Hf-8bi96cEDd{Oq<$@t4$B|1}n}A{M!J50A)kH|!R-X%$(&pUhYCv+TX_oNj1e&!M zA+RH58vsH#Qp#2$36W(ahtv;QWEJsqPFev61Z)eeI(5!!lviLgt7y*+1gN>M_FPAx zmMNTXdUBw;b@Ws^c9jcC?RqSQ=EGv4wU_q3EsoP>|thFx!lLF?0Jb1w#2 zwJ#-NE0-Ec+KRz&D(iVOh9cp}o;oFTr)%?ih`Y$nJC&OA67J12yg4;Cy6eb}SeW&k znw5BE=4eD2mnRv`45OXL7I$%Cs{HU5=!mHO}5$?!LvaU*HU^RD$Kk+w>okVIU8>bLoH z9saWL0CCV9OWU$voAW#q2@O{g4>xu1i$BcscFA^k37AZmY-(IH%|~=Ig%Y7b^Kpc8 zRb3ScAaf!u$WCZ)A_V$^E{5A;8gA;MSTZOjs)OJD?j1^|pbGx%-FGR%di+0j<(8H= zkKG)m(S#u8*lMZ&Vrt=yU;X^gKRWl1TNn58)xKn2ab67I)A{e!V|fEtixRb5(#0;# z!{&_B>>TWN#j6Ce*|q4*&jMNoWk1}Vf>k$!Ka1YPI_EaYIgH`jZKNv3Xy0AN;lKj|63F1W?S*$MrZKL&IDKyy7oq03F(^(Gb|Z zY$!4bGZL*u9!Odi8S_AVy)Yhm zS%y4jH9=r<(9w!+kF#s4z%ii;K~K%SKvKU zm@BN2={Qlov~vx9WW293)oWywWrvOmpjA3wbFII?i}A3(|Z|+hI1)$&_q`xt zl+CsniP;WJ%#Ca+B^^rUVdjT-q;c0k(PO3yg3uI%PcH4eedJDs0agWOWA%R-thdaa z;i+t{^=kCBw>NLz-YLfohB}wn`Uh#&>XFxOm8Lg;Hs8%}{&aYqh+5Dz=&o9UMMqV# zny#)bWni%aE~bryGzBZ93Qrb;5^Ia-N0z9`lH^5;5UixBmwbL&X62IA!L&)4hRfxc z8j?;+t`?TRWaAA+P&Xu6y1*5=xxmOUVEJ#!J=?(6m71SWUp;@v0BI+$0<6lAQCHFg zJf!k!z9Ng?VTaLJ6hRxF+_Cx4OSew6)`7h1xt3;MQQy3UqgJWtU#KVJm`7Q-v$QK>`THKi_hNyzjfu! zBDbm>K_43Iefq^0Pl&$;fPqs;$zrZkG42d&BV=H~9&Dfx04%FsgR^H3Y%zjuLqJZ| zJAb`)iMVSpw*}ypc;=NAmfl}`XZMBw{_Fn92M-^9@CXT!t5ay0ou71J3pL^);4b#rdn%yWW3Y*Ex$=GSaT9u?l2_mzIJBiM+G0wBo=$W!1jgnMvlB1ihS7C<7O0b5P zSak;pJyn5K%I0^Vlhjiiv4W+e!?M#=G=<<3-1*WfUCB($|34no~?N~hT&AZ88!B|#Hin*-A+&AaMW~KmCBK=rgK6Q`)(4E|v~5-;scTz|OBY=3b7;9H zMb&Q1Os%mZY$%T3wnb6|Q8leRE24s0kX8|z%?Z+(5Y8x`3FILkHk*pN5naP-K#~Bg zOxUyxmy&3)AT^s}Zld#u{R;{2Z8oh=s~LUgE*t1qfj|5EtYi4>u>qVuv8i(B#go_j zjkL~w8(&|)d-wLaU%%W7*B5dSBIQ<2^uGPa?W?yJm**+dGPH5|``rfG5NI%!pv>S*aZIxXm9gk$2?O0oRW=S%BVE!eVChmsLKdx21x7}LJr^1c{H?0f{C4Y< z%ARqr&YvH=XV2x1Y~L2wFUQT|{}sNQXWYhUSXjdRcS(;Me6C}Wjps&9rTi*qZ zoLs?-nJZxgPnvHGIBkaUmx5@Zv!THTna$6M|vO(w-!iz3I88g5C{@)GVJ@@d#M|VH{_)qiu zrRj{8`8U6xPESwM`~CestC#aj9Rqno%ziO7hW{4BU{1zsol%T5W)NCKemekOKp;?* zsEUnlQGm6MEK9#u#}QCpbSoL6TQAqm+3~1cTLw6f{1}NGBfqn3u-2T~DN=uCUZ`B# z13se-k*Os03I1tdkw!*zXN;hb{}Xn-uWj6SSY@R*HVL`QZIU)M7qKd9Dn=xEO7Xx_ zWuoqMiVLw$HG>K-+QcAqFd*gM9M6N51SDVuV$;&8m$C_1)#h zmMDzj^@`4kcUgg?$r_52nO-ItL+^H!NJfzs9S~o6{WgWl8AfJgxSy3B>n@YB?C!YN zv4&uK0-O#Is#YZuTNrkcts!tK=~$rFvR)=r26M*T3S+4N03ZNKL_t)jnwwn~00U(+ z;I=(Y*}y8e4SAO+vslFtS;H`dUQgW%C^5n|RkXj$&^57`J{{zzpWAMV69=FB%-KmH zT@IE9i<7sfx4-lG=)#hp^HOzh{_@3Bm)586Ow4)i%x#~jb*Eog4!-y8JLQw>{kP_} z5I~imKC*r_eIw|LIX4hPFjl|?)mLHp%!#%XAyKu3bumTJ!f1tN-%wKAlDV}A!Q@5{ zY6aaggC0Y}EEDDfkXa;3YYU=)eHxV#1=bJNpcV_PytWO}X@o$^vY=}SOH!eXQ8e^dbpH+%vWJvJ?_3n5h3e`&Vm1Ve>*fQ2 zT`YQq`_{9D44*%rHNUQ3_Mw=?Hu%D;qiVm;qz&X>p%u7gO9%VqYE8Vs{A-n;QNpaT z(B<+=Pk$-{?%doGv>JvL0PuhQJ(C6fuTrTZ9em>vDhMQ*Vk8kz4TEDtgNYCRdY`jq zY2E$VuYU^%k*JtCUzTiUnK&;Yn)!FX#CG?+*Z=bVhaY~h^U+@Q@Zg4Z?uyK+D^XR4 zg~O_3h#fVC2FpZ8Wq{t`+i-DQ8B5cjOqs)>1aXC-)HDh3iUp`CpeU6Ijgo=T5=wcY zRBn{QK?S2_h^1ukJi^yfG6;+Y-y+PwV{@evvNVL;k4u$sZBw?#6%MA&&6GscC4ET4 z%5V+tEKxu=#zW}>7Cp4Nx4nje{{=a?SPD0%k4E#>psSIQNrSEG+cdm{6yj z3fo{$cgOrwSMICnS={i>D5khqw%v!mZ!JZtb+&NtW5V+$7IDloGofIrE z*V3j=!o5>hNtO3WK^>Gcs=+t*UE{9nFUnf_tJ7YX4-)-V?9C{gv_!~DQXQR-*JgLP zfXS5RI14y#c+T7FNHkzIt5F*%i@ye&bBV*(jh-3Em2<;vtAo~Rh7AwRY36%{u#OFi zu+kwwiD{%O#a!^B4XBrmZ@O4hw=vap@UBJpSL7h82>*jTN80sKC zwowL`-HmR|+Kf7ymO&ShLORhHK3j$H$li^{bf{LDSJer0q~TSOw)?7~$6_yr(>BwJ zBB|N#L8pfnBFdb}Hn^{qLhtr$lojX38TJV(^)*0v3t$fT76F$aYnz*2Kz@fole8*f zl?z>T2W+}yNpnvVH_UBZqc@50st#d9VacKFAY@OlL}K+i*JQCA^`5$0K!;#U%}6!$ z_61VGm*09~ty)`X?w>2LN1>4Z#n}nwyKwauTGhqLAbkr-C1u0!6aWj>X*geRJc*Ivt_ETsNd>p z7e|zpl!mkGcIT%B_b}<0A|Ruk*+1tnXN+MK*|iE!!Fp?VT`1OG;4^6 z7@3d(Ez@>7mSLc3i9xH7ZY|ti;?I>7ocW{!KE`wY2?M}HTm!acN}y5n%j`)5u#$u& z;T-wKfXF+P&&w2gI7B4Y)s{HLFBp!wd9-J)DnjN`rP*v0n`_19XwP7p>~fKYX&wgl z#E~nd_wel+fZQ`ww#bf#ai!TXd{lsex{H&in&N7f{|_B_tg8&hJfY&hlyHmgc!&y9w?SdB_fYpi)#zFqkG-UbKASyzx7 zv;D~CX4G}ktU52IRe5fjoOpYcDU0d-&IaW%JIbN1KygnnoN^w-3auhk`^jwf*2{V=*@ajzZ zq^(s*5*?#seF_Ndh-Q#j!>!b<6wL-dXEMoiOg_S>Nmm}LqXVk)B~ zlagM7Fe5Y2CkT$bi&V_EI)mDgCUUe9FKsiN+v*!~&dOVZ`}Oi$rqpddf6Pby)`#!O;4B8XEHm%6RThAZDFLmaO(Td@64^I@2#He zmM`tUz4G+4H{U2S1DYYtUCr2l@wg@-(FMB!w*Mxkp)L}#m=G(SPc(z7pc+eErtY4E&;`s*rX)in#yiT;egMoeEahCn35I^ywCc&{`&0p zJtg?wwFJSa<0mJ6qp=;%Q{3^A!L=XZLXHzVfxGD$G!%=0>K_94B> z0*!Nq6{}L!_v8A~D+>a&k^$XcZVCJC=ljcy&>G@uKLWo1@SmqU3AH7i54~jvQl4ENNAurNRQ) zV6$QTV^KyMqHNf-!TYuGron6^aLDv|vr(k|cQ^p|AA>kc7lZ7U8^yIoXfRzWq6}3= zTZ6f%xsseymd4|eY>=DN$9tN(VVPytx`xpIXU)3?Eb;KC80@J?%d6`+y6*O^bxn@s zcv{k%J)0*SJ4~;5s=_f^SC2FHn>aNolj|O~^oz%vp1f17UkSnK8053_E70(KWU&kRyZl zGWWTy@y`%s(K?J(?==gy3cYQsy+({Qmci!eXQdC=pf9`VQFYKtW1|{e-CuwFRP@~T zGTRjlZR~$@X;PqXNKj5-3@}Bta5>*Rw-|J*D_?r+E7RKa$K}GA=w8s;UixVj`l`vT zJ3)H?*15YY#h^d;%Fgc}^Dka`GmT^nxr3m~rLU-;x-4a2zBAg8FtXMXB-)>(`$3L} zjk#<6PRO}L4hVP4)_j}>zJl-+AG`d|lsb zTlXEkD`WRXLhTSp0u5IzD(NmImRzL^!`779aHU(ft1S}>xo8OVu&hnlJcE_DL0AIn zi`i4mk_VeTn0kBaVDSPbjHTNi`jWTMG^8-{u#Wx<`<`1-n&f>q7k*x z>~lcfL^w1JO4TZx7?^~`f%FG&zF35HhQ5^7cWvb|xb0WsST&(QRy_>DVM)B&p6r&Mi@Or? zdLHZ*W5an?Tw;tI6TkfEmbV5aFMtZIypQ*l635@OFYRP{$$tzlc*{xawEgUJS^k)2Bki-vS>*dnZjA4o7Ar1+71xPh`ASbko(nBB6RZgLS)8QR z_L9!_WHU;pUm^I_YGp2&(A2+D(>-0dQW zqXvV{vu+C&1*hs+Kq;R?iM@BRG^J5?q4v_-`vrwMlD2Z@+b^(UcY&!Dj%4m#z1q9- z)AirHy1oDg+&^ADCc`Xzx-l*k_AcK$N#cd(TX$-;lMnyAzgVzx1uc3dPc9UE$Q3>+ z;z}S~v(5$ijm-0l?Jn5(Zl9-ZPr?On7VF_|Mn!}UgbItao4e&M1=KA^t(*OVx`=Da zwPuYHKDWB=y@MTa3Ee36r?F(F#<2W-?0_Mzq6+Im)09;V+yK_04JoEk2|3Zt3#k~e zjzSx7H9go~y|P3Pu#{E~bQwMg{3QwIT6h(3e~nCdDOeho+e;TKjt_r$9i(@YU4v*M z1nO@3fiomni|d6hu@(Tmj=Ze(rlKjERb^u}fBwb`ZAi(-9}woE*o&~-+kZ_3%@!c= z$Y^ERaX;|Dv_7uaF@>H?mLLA@)~!Fd{|-OFm>CwLhyVKg$>XD=_1(F?d$rx~?iSp2 z#Qm)cX>$vd@u)FFP-KK?NJMKzgw$w^J*)%485XrMqb)issbk?IcOJ{!{;oi4g`T36 z&*K1dd4iUvi95j&80@Tpuxf0oW899}@Hkp=_r>FhW7TnI)_{B1(OF=9iff4xOCIVR zWlJjUkT*WlNeSc)*oQk4{2m;l*I5G02aJH+vlVwTjRwcjB-MeXWCU6kUm%XJ2+mrHgv?WgS(VI@G|ZO0!#r#< z3vSF=aOUjIKAIO;5FN|~O?uguf2>7IdG4L1ESs0e+(x-P*|f-0=0FOWy-F*XPJ{Wz zz={_tmogGdzRFp4kS~cVp7Bn(0G=A_^&DD?X+I9nSviBE17>vv0e~?v*t?twlhqfP zVPPH-`G1{8gE>bqCdHRLoj!yk*q&j{?{f2!LX&DGv>nY6*qc__>*vX9O2_gKI2;Iw zP3~;^t75jqm2Ha4-YjTi;5|si%n6)iT54-0R0;3EVw@8QrzOtH`isPowc+KsSgnKu za~>g%xu*y#tMly%sSho`3Uv5TI%aa?9+6tvlH$+~uWuqtGSSp|O;v*fab6Z4B}RPJ zv<=b2#>&mKJhq&@iReu2F~(cR7N-lzMV<*KE(`>QK^P$+e| zVm+;$c3XXlk8z_l64j2sbAJEE`^$g&ZnJ;Bc+jtY``pjElrA0(MgMdG19|)oHeoz&F&^YJ{*hzArJ*k?4^{U@8v4rZ zzcL8A8K(@JWZ^;;L090!TkgAllLxSqFwP?=t)HRVY#!XC^{A}2g|Y=uI?@|*>r3G? zn6P_AgipG^zWjuqx24j#+cBvx(T-n8I>(jMZv=g0{o)45drRyo8$<)?03C z(Q%N%g^MKS$Q^_}gz>13{cwY2MiWeh(WW4D#!MPAsXB_mdH3C{GQy$2I9eR(XvukT`;1u#{lh-dj%$Uz$QJ4 zM`!N5(pxo-+vd7oUAE=6QmZn!%=#KiC9?pRe1%fGG?!GRBe?Y~2R<63%_4=e-xKrwo)c-*zL!_pIA;b{yI|W!#=|i0IO1Vtb0Nw8J1m76>iO}ph;SCs>;oz_ zq7AYN-u5sjxLILQIQK+>*HkH~GO&b7!%8Jl`Y6cfh0C@s77WfCh;sn+@+xBFwQz21 zoRtbzhE_=Eo@MIyyA?loM!scbDDzPT@skx#Yn6ND_;1B4r+s9{ln5Q}cwKhI&SC1l zsNfruDGw}6!+UdmC4+hv20q+5^DJfNV9W7Haysmb66OOsL}$&6l=ua$UN2{~#NiFr z3>8_faG2S7%`i;Y@0!{Y5?^w72{|E@9qR-v?m3Zl7YtdRVgq-DXeG%_?=hxox<_yD zA$u2;jHO;d8j=nZG#4_jlDcKmXl;ot!pgmG+w@qQY#$YAIaVaO;>;>ikabrJUN5nt z8Vk#B261d#wg%&|6oQ3AZ}vQ`9td*vFjC;&p!kcE7W)w#>OFn*06v^&kDe{CMez7+ z+V3~X0=N|R`<~bW@OQ^M2Mzznj$Rr48rug zO2&&GB=~^a*#EZM7nkrCa!DbA#uzf2SiX2H6X&zU)9cE9AsR&(9`LXe(ZchI^58*gJ=Z){N-)tMo}qK>sL^veWD z!lt`*)B$=&{Mk>byQ|bs0O()PwJ4l^@ z-a7OiBk>AA9$`-GKCZCa5Nllb(~Y882L*%fq$8FOuHcFz8oSGdt%#>hvu_G2tnVXs zDK{qLaec&qOb6vN1cYqi{J(eSwO;NY%HY+$r>0q<8D>rrZwyRarFk=fR2VK5H0~N2 zdYAJW11hH5ek)7ou)T;layv`Y&_JBvRPsU8rj@oXq@nluDhfIedd{pw!;CPO^2A7} zq)KKC8kXlGHjKLxxQE#&*`PYKVXxgB`l9=xjjp|?Xqeai&h`6d*!!G3+M9oTsUWd+ z8U%hf9av|uaoM3ILk5{{YbWpwSD!;$+5*?77AIM8&$crcdj(k4kb8K|dyVi4l5YvU zHNYm~s*Axdode&5kjzoqf#<=T@@@z?&8kEWdWltk8(AE*g=Tr=KAyK0Enbo% zU@EZI)Ha+XnP*r{gQ^m=kc}d3#K28J>OlFDO7bvaRdQ(A7+Mlj?wt6jN-3t8($O>W zs)T2SW9dt2uGB)PkV_F@uYKO`Stypwzyr&uq#yXlCz~zx+24Qq^nZk%&ubg`8OEou z>Ck1g6SivQ0d2LSnJ(?LjU=Ppb&E$RNJT$L+C-zKgbZqDt3yl^vlK(po&u&0$k3Ql z76Qq^J{dyTg`{9-!T8ck554t}TXN~4?Eld3^StkOMxl_hN!Gt)i5&9ydEe*#JXFKK zzjzs-dv~()#CtY6{&=Uu&+~W(AuJ&{(^w8=!3yE!+7@5a`Rs}3y?6cT{nGBG?T@0# zJD;_$Z!?&DbagSTt)G2*RElepuRro?`~3&Bqm#Y3F+u;5nA6}k#r(D)GH7uFQCPdt zC4XZm!({#*lD6duTvArYLpf%`FuM~-Rg-6nm$2|zalSK*Z3*)=GL1F^DF?>*^Xa3n)O#tL7`ZOnBT8dfVqUl zd>XLEcG^y-^Qw`ibC964S`YtJwA~|Cb#iL{qQegV#!|qjV0aN_s*|N`WH1`wq{mpv zdB!ST+%#2F43!7bTnJJa=SBl*UqT@O4M6h0QPtQ|pq~j~2Ir!hVi&t;M^mhJqZq<# zz94P$&ghV&suUUK0j_r2EKW2wx0=n2J_90>QsGhgi=@{qN?C%0jB~_iGA?;=nBn*+ zn&M@*=a6)njN|o2(-e7W@;uCQ&Ee6Z=<_(Of`es#E=W`3?c;xK|D@l`$0|JOQU0^* z+74h1BTF5yenD`RebeZfS^ezv7iEFzeF4PX0|Mm;#< z7cFrnU0ajj+dgbg%0=ImwbA06P9hBqxlevAA)TKRiAnaCD3e7ZI>`@qi&8*|LgSZH zwCdU>1UF}4IIo=#vr*Sw4mnv`q<)oxA6XS>E0AQOe8+jcs3E`7y^{x}WX0W<$-BbHRzzZWaChJ{ae^-{C6O1$2_^E$Y)__=(TQXoJXlFVv9PfW94zarWSh( zxYU&cdt5voTe$Q{wR5D63JjEK)q$8=89+<9g7B&GdtqjmWxort(>CC4Zf-@J1=37v zH1zi#4f;KaDVOxJNb!?$FwAlV`DkB5%@*xEQVO(%Zs;_+D>TaSJ*qU+cPv|EV~6du zx~o8}?;c_L3_E!G;*~LaMxkE5JjGPHv-`C3!LKLB-x8cMGEd%_oBM1-Iw90by8R%Q zvSk&p^NoKRL3{Yb+r512{BH34;JCT@mk5@5@9a^nws+;|^K0u~cKykTw}0z~H$15Y zU;ORnyWjis_Ot!_ai}D$Aswy9e6wIX1i(R8%2q_)>M|hRl-8pmiy26S4k*WhqV}Xm zDPS7fvz#rYvYH*3-KL;9JZ*!(nG(C8n$2NTdZ3JB9tM+OvbK4_aVt0mX_XUOGlT!F zmcO?9T$0TQVv#p#&yhk5qs<#$BVDnV!c1zx|H{mosp;^j+hYLB=0Zb7s z;(GiZcBJk4eOS?yFb{y4SzC_A`?q6!?jNa1VY@9zo&h+k-Tf2jPOr{7hh87^dk{^S!=r9B{9d zLn7toNRE4%eJa~blm@Nz3Rk=@^;2sGc^6!6xvH_M$P7nI9YbE<=NAZQUJ<#rny4(O zRo`)~`szb`qASZSd%epkOk(RCa(hfz7Ats_h?VF!kzujB1jVxNhzqtIfywe0BsPha zxWyJYFBWu*CGnC-Gw^$ z$dNtk9os}RR8|X;h}am7^53Pr)>mqOj-EuJ001BWNklPxSv3k^{%vYYD7H?~XT8@pbh^*5->sVQOisZd<$+q{(b4l8YGiDN-`^6O# znH+s$x0I2kh-L*#Y6mbrcF>o-?@05=BeAje5~-g*n5Rq-@2--z#)7)CG)ai7ES!a0 zso*O~cZud&3yin#NrKA~E62J7HlqH)aR3Oiks#xMPl=>_`Qnu6;iqSwU;WbCf14?2 zFrjOmZ`|C&0Qh8x)u<=MgMlqb5W?gMN4Jwkt?_L0Q6qTt&f4(7=m;7a{@@oY7w=v> zw_p0Ows!WBH{9z!prC%)bGEj&Dt>RH`_U&mkDu+;(@95$%A&v!`Uca`Luou@G+Jqt zH73aLWgTR}hKi;3YSOa+|0*+boG;7cG#HRSSFjIW(D3!gG<@;Hgv zEb1*L(Ru?cbLbC$^nV2S=j}m;81bwBZ9}5DtRm4=O;bT&K_-Ex02E^d&y7HH3PNR_ zn^**xjdhKUOwUNdh%m%PiYepfI5QuO@vd>l2nyE+RUGgRvUC>B7YnFpm2yhV24uM& zXVrMllOu>_yr^e~$VJsNx$`xeM?huFSn{0NX-<`4-cjZRVaIrw6iPJwns1c>@Ihu3 zZ8E<%eq@Lw8Eu|=Hb|$i)kcalWSpzhwyi?WB%%#|Co^2EaHwWrNFxcI;Tese9<1N} zalfY-WLF9pRP$VcSjpZO39FWyN1jQ}VkpaA_9Bv%wDgF$tmnOMONm*&wk9~b*cECA zn359eYRN^DakpjdZqP;~;d@}RT+SE2D&sABQ9sW+CoMleArfF54}_V#P6YIkSh3A7 zck>?rFq!73D~?+%iv@FKZ+nUkU)S+-buN-wMKr78D*xFkWMZrC6LHIK-s)S_3l>?Z zB?hI6^O9wz*WOYYmRz*Nlq>l_n)>PHu`c~yZvK|zSldk6l`pDZ5ep4%cI@p@MITNp ztqs2@QMhVH$0d8ji@TzJJ}WLQD{4t96Ri5$yI#dg9*o2_k8__o%IkecN=8=at5RL? zu~gF!^irs=&n`qr9Zds(rI9P^l8b!yxDVilo&fXdEF@B6R=Owdi?~w^54x5~X*a`t zX=1RfN-lFXN!?YhGm92DSLR+=?}Dh)_h_D_HV~s~lr!LtNIa`BCPg`AEZvoYB#x`~ zG|BFN$3on=HD=SH+$Qx$7FKERm-@0-F8%6Qs^^W^ynOL*h^!G}2wTwn?O%WPe!KSg zW2CT}l8pM@7ZWj%HCelA%b?Mx6KVe)(wlNzJ;XY87>2{z#Yab+S|9hn`NQtFz4_J0 zoxRetVeR?v_c;%qez~*xo9ma)ue!8x--cE<11__hq+!WvlgB)lP^ziT#tb)C zetO9TlZT&6888>TMrj6E1{(`JW!Bjk+yJH+K`atDG$6eqscE1o z*YaP0A7ti_3u(A>jdTpGvmRbVK1@M_s zD4mf1m$2)3apS(D1EHM|q{xR!B~ei^G}{E!kd?M$>>5eccGXClDrt5{HIxoZM0KzW z2_Y<4r5D3O0?MJj8r*~T6bQzY*azTlQi~|A~Izd!O%&(nGo!@2;fzVITDL zKA-m^Fzxkj(xhML`j9LOku0^<-UICG?eT4$734Rg7&t6Dd&3>@6_nPrdo2nDEe105 z`BH0nmdY`8f#CM|x-b$2KDjbjuN`Dtv?Lb1Mx!-#4(jWmNZ6=TEagj$!d>*$!In80 z1Z%S$8(7nn3_sG&g4!n7>ylv4c0|dxujNGgcvkfFl`X-*MT^-GDLpQ2#Afm-+JDR3 z4TVPvCy&itR1`O)yG4Yl#d7&2anTxhtcVWV7c*|Mm{6ClVhfN={e0WIj%~SXeZAIj z#4Ag$@^=L z&FVsqrBMOR)-z~98(`j}i=DzG1wu>2HBu)-T9}l6^Ms0L#}Rm za`f68vs=^V!}lMP%0h)aY~;7Te02V!pI-UhVHCU-I3PZJ^ZlD|Jlz3X-2}m37otAP z-PRo%mZW`dTXjPdL6@pBEOx^%Jhz)l{h$FDo8Jm=O~IF4g@AOMGDb5t8q66XT9w2x zV8t1T`PORk2-Tvamp}cAvS-P#P<5nsLXMj0HR|qDf@Q*I2iCAE<%`AyYAq1qhwpOQ zOy%=o&9UFx^!*Bhds*+G*JDCf#0KDu?#~0=OO_p-H}>WyY#>DJv#G827>uQatdrp! z%izYGs5@6`mK4+MW@zl+`{6dE(fNn1&IV-l`7Qwe$AUO=)q-E$+!qBJ$%BZ-N zygKO&CVli2w2}db!63%cYb9{-Bot8t6JcT^^eyuVyNWvfcmYdO(t<6?!E}!L14x)B zr%Q0l<TiI>m#!wq z&RIuD<57G{Uc3OUmBAPSZMvLV{S}mAlMVj$4yQ4db~nQR5=Wck4L$+jmT}g6kR$!$ z6rVqspp`E-dFw6!*u={{^WoMMvl7;PEfOCldP)+-ESR1}H1~WmTh!YbRO5xr;E2k2 zXBGEab5Z1@Ea?%7!crBbyD>pk+2HGSS>{Ko8Ia;bX<$NT5Zan2%8Zlltp&NN5UyoA zB@9_9kJc~7uh(=7`+UkU+s%cxqoa&>C*m4@Kk&lv&=00V+wa<_xURFU*K4JF1l;=y z-4$2G^>W#P5bl&L0N*(h4%hX-i?gGYNBQ!)0F6jKNw3Tcnn$uWScAd*!QXWvf7n?&Y&*-=PxeITxtS>CjQb z`MseWvnsKdXQxt8LbGI7Z8aPyiP=x0Nm)5Ywhc0w<)%M$a2LOxj=mU9rw`Nn?XF&m zr7I4b?+udsU*7%gdsjwp9!25V*$3WJgpdD zuVeV^JAVbTl3Pg!eS%Fe;y3oVCf?gyIyBCO)O!H$`y*iQ;n5*dux#^t)Z-f1{a8EV zHkeM4z((KT-h9KVhrhqOn5zevZ46lON)WBT0mRL@3K~viM#8!nBkGd|=g^J)#?_zw zAOo(Rze7Y@wsrvc->PJ|1WGmF^5LWxxW-^gO?Mr2b!^hHVn=(y5c`W3iv9pct2mxG zhR88-pAfZh&^AaG?j=~6s?K1tVmK95%-H*4X1&P)v&jZsMohXQKV8u?gf(q~@i3wu zq03%4kpGM=49RIrGO5Wa(wrxp5Cd`hiDTvyhtjJ7p%#~oNwg=YjLm>7OnJ~aHC$F| zH*DqDD6hcg<7Eu3b|+pfk($LSL|hHgmdvYOE%31f|4{dl#Qhb=(10zI{`s#*2O+IQ zMI5w)w4P_8QCMPUxgr=B3a* z-@cG}dR$X#hvk5T%|?!LP!f5Odp8oN{&Tl}8Wn5B9B7sj1Ha#M*ZE ztDMw@1Lp&2{*KL2U}I~RG3_muSyeUd~0CD>@Xam*cAj%I_Nz?1H%b_ z0OSuV&E&>mCh8mg&)2~VpFU;-66mj5kQT~=zRr=f1K|@&vgS6ZrbG)*%Z~(TzW2w2 z==PCiU8xaCS(Fh=8HDx+4v(`V3R@43R2l1@3hTG8DS2|}4M;TlB5#A0!1%2)-1m+o zfiecu*2chf@V&qP5CE^o53V}Y%pLCS0Pw$5iFDZ+Y#du%CKwANa?#s170~mJ^V<62n?*wH??s}W+Xc2Vi*k1slV~|k9UUBT*Z><2;1BbVZeDxVF z7PnUL8cm8k=}tdCg(u1#I8a%zWH|!kj!EIa~<+ zz()Z`q&M%Jzc-2$JXPx%@)?juHjy?pb7Zos2&Uf1Iu}AKQu5IoYH=|1R?vk{jf}jk zsuy`iU95j`zFy5|Nk#}7x7TE4p&)~^_?pZkuFtjbUBJ9>V02d2p<1b{%KYONQuV!_ z-*6|_IUva`ce|P-7oCDyEt^|M>61Yamho6V32SW$Ac4oowKXRd&A~#~x|Je{?ADEt zq8IoqD}+%p=GKJaUY(^YofTv4wcT$$D7;Jl+CFO9T9E4Xa$$T{8ktJ$mLR&0G547U z)q$lsdkJ&3TJ!*$0oW|T$G+#cP+yr($h&yCL!KG@nq{c?Gb=S(#gtj6KCXJ@lZW%P z>U~H%0W!ml*zFYv#P$4VQlRToJxN}PcSJg7rP@uGmS#tzss%%iJ`4e5J!9h zzDuvKy?!K&mE3vc{Yc`-sZFU9&n#LQb5wZP846Z-JOB1SCq+%ey6HGMTwDZElCkn{3}U;N2C$?@qf=JTtkHHfN5trJsf}O-3Y2xwvMY z+;}tKd*FeZ-i-bN7+-ww_&V}7kU+Wb@KpM$9I`9sax5GGFBaxI!kjuM>@pCG#^FW& z)#!*hSOnigP~n;*y^%0jQY@hD0WW;y-XH(w-c*^46deTbo?EX1byk!*lMpvBWj=>8bdu8rcB2yveGzxzV9%jB%5sy{rbE*(?6HzMCGZ+`7_EUL829LantmW?it`Tb zL=OB|%$q~jwOZv#jH+IwXC$mc#H%|S+JF}h<0pu!iXF>#;0>)-j61|vJV7)DE{-Nc zWH+C-29EQt+zqTmcZul(jLrYc*ZI7*m0wZ(k(RzJ^!)ncwX&#MRq1HbRD@XaD8#gu zkg+DxQyYls}PkaKShESJg& zbJkMm{MEMfp>JK(op@j^)mb+~-!ZvjSEeAhXCsx4mk|)4p<{QaV<}f;WNBT3j?ALE z9KE?+=4*EX8$k;C_Q5e%zqkPhv3j=pc03o8bF6}!`JXxA?g&b{Eqz9P9ZzF5U1<@L zgpLlSO;C#mztK!+z=g%-Eie5@JFPns*T{WpEsudI=$$M=on!Dvw|eA&Nx1_?WE3-& z2Vsrh97upN35dN@>hG}_f{TSS5Tzo}Q?8(0CM z;>=>6DT;inxU$BMLbr|)vY^+Rl*j-dYB=m zlzt_I%S79jG7?r|y;pwd4!NPH8)*BHiBRuk1j(YI^Lh!Ux_ZgGPjjFTi=O13S5rok zw$&Ln@8Z7dfHvO&6m^rAU3ac^_zq65^1`CIGQs8(%bJuwsHJ)`rU8ptVaff|3xMhCid<|S8Ewxd^E>tR;yhk>~-31C()bu@LogV~nuMTL`S4cO;9n7E2I`AS~{|wWW}r>vsI#^=JfPUq4&+%8BJNW zt^JwvKWQERswHHLT<_}O!>RU5u^B^oX9N*RNaTiucS}8sku;CrC@G*y1X!98%r5|_ zm>A-aT+oBD489xk5P4qjDEXu&UjhNA)tkRNI5>Iy;Bx=I5#sUn>t0e{xIegXe(SFJ z^wi%v$ED*zdplRU`_s$8YN>bQ;dbq*zt_s8pB{uVr9(iH7uw6m>Z%Zv# zFkQ{GkU6SIJFuB}v4YN;8e|N%9%x2_|M9)|39uJDz62wb1#!GP0mF6FERHyxg7$=- zTNr77}Y_>K$=UwS|Ml28VWE(!{}`wi613Qr%iofYi~5QY=m>Z5fnS zLCp_q-S3W?sZfZ>;ao*kv%libl2{W0NMh8A)iSM2tTs=~{fjRoo?`^??9}`^d;Qj^ zF#XO?f4<*&o_p~l3X{>l+(~@3`}sQd%sd7cul@MHPhZ>+8i&(fnz3F%NngoQxyJji z=&VMHUctJI-|1quwk@7zDZMrEH}`TU5pKXGef9aZo0p)GOO@5*XZw5S?mWD*=;yCr zA4ezV$v^n+oyWPOA9l<)_!uEUz(=vYDWB3+7Mi8DWzjZ=vUJW4&yPErD?{HF8t|z0^HgD06XU5u={@m7&~BG zHI25E2~I}YU!%AJJvILfQ!uSY5JccN8lx3X%wREB8SQ~78i*^{sZ#S|=mDHJl8Ffz zCsgyyvU60P0LNto{N}!S6BqW6Yyx10_iayNu^7KVdex zv5R_OqpM{ecvFy>DgAIk!&8O7;hjKn1+>T&fI)!XYVh0(=%)FO*)`F`fQ{hiWVr1TZK=C<|^OlXb5zTHx*XK+W^9NtuzPvUo<7QMBLo@y_Rw>_-Hhi63BMtQW zLblT9MS|q;E$lh8o+##z1gn*e!IqyPL}&e1yTkVFgdJ%Nipy?24%c;A?73l`=x3Uz zL(dU3>avKALg&HCdJx`aVmUSzjAxU8tVGGq$pnBSboE0MTnd1EfccYcX05@#opR;CD+BRZt= zZc8EwnjZY}MM+T5x!jx6v$NATZ~lGywnQSu^tqeYTDk4LmZWS;rLP9NrN_Un$b?$! zrC*y#^xjACHE$@cf{rMtjHvhaHS(|&OD-I36yp-y`jD=eCT9$9iwyM z75!3;_WiP0w(wgkw={on@YNR=F9e-uxx&&vKm5;B<&!_$-l`S0g5%rUh2GtVMv)iq zZNjR5Z*%&}HbTaYR!M&hJP)<#;Ht4-7MTp^2cnv(lJzOL`Jjr59YVcThogeW^j z5}BfEiL>3Ewy`88MO$oDsV9syxW=~Rkb+Pb*#t^p+dpF8yf6JX`kiy{_l*i6j&U@yW@Nwk%(?gcU?CwMFe>Z3$HlM8py>s+ zdC(|DGEm%FV>vKJ(CzXX_Q8f0n?GA^&wu#&h!f}aW$8QGrXXv3NwX+HehoWbUjji! zP=^6r>l0=f5=ijd8SwtS;~yhTq7eme7(ru7j3{Twg%jpOjwvxR*pmgPXg(N4RA}M5 zonQ)iaxzL1IA>v2Lf!@Uy+OkeSnN?zlS__jt_0at26`MNl5f?ZzFFKt*z{(oKETkJ zUSf066?3g=IG&EtN}Q}tnN`(5|8K*v=}GX^+y#J@M&!&$C($Y7%VP?u zPQz$KQ8lLD3HQ)Z!n6<2$xx8l=8!}w1`qd@|&yIdwwv{{(ey$^E zjm#=o4m@lP7xi7PPFHG;%DI5bmHUz+t0!#uC>d z7NmJBVU)4hjI`xb`2H%$_#|<}7uB&*e55<*%(E~nT zv*YG|@qloBP?Sz1{iu_43QevX2K*OIqXaf@Ji7CtXuz02EsV9^tVSE#2leU?KR$Z@ z)~8=w`&E7E?>|_6_tWM2#_niqbV-*k$<|6R3K|LyaO z@a)ya`GbyBKB4xv2CFbTk!uI6SOh8VV#yrt-RECKZey(h39@B>?Y+GV3b2rYg=j0d zi$)`DWMD(X_A-bs<AqZ+{Q~*YkFbgt+Fv%ohNpOTIFKQE3%@M;PiDTIPBCdnIe^Q!& z01V2fIkFY`aU7psUDgzt_ zz;+<*siLc*?qHc#^H#xTQ1Uu|%}v4PPQvr{vXx_edorLk56h8Y6-XPo|R^#x;#D~Y~J~7 zL*~Wuif+xJu|!56^fg7RsQX`C_!ezql?bs!+T5>Sw!e?FYf?QJ?(PN#$EAa~FYSZo zvIo3+^Ly`}Z#}zqk)G6^Y<}m(UT;=>&^zj%ee!JQY@>9{dxqk(oiA$j>hsN6_q}*r zti9a1Jn!AVd9(M?*|Pa%Aj2Z{WknLySrBRAunT|ic<jN1X`Of2)fL8o7 zBzHvOTh)Cpg;v!rC0A5rjSc8xNxVeyRi{HWR_9{ivkr-$ZK-1*1NIFT`+~ye&}&IY z@LG#T6nw+5;X9uj!n?jCif0mEdVIUvbR|_Gg|5+r)TJQHaAS$TS{DxzZAi0wZ`}cJ z9c^H=Yxv+B81Pdx{}~v~*ofPhqKXKNcx)&kdhHG9tR@ne+z?e0#>gX#tTP5+iBdR} zz~uyXTHr6!sSJ0V5VZ_&J`Kkc)FMENg|`5I4ucVD5I|!gqJlIEPhuw>HUP7ctaD{2 zOr;ldAd$536x|X0i4Der_eL3xz^H>&+zDiG9)nmXtT<-l;#e$6VbEbF2WdKfz#th% zE9TUo!I^U?x-4^JFv+G&zdW5H=W4JpZ5%zZA2lPK2Cz=2JI9!Niu zO=VUtyO_@G%u8Gc->kWy_L3snx=%h4Kv9RLxVqVhgz?JJgmCN_}^3W(7J$8YL!RF&C?eSV|vK ztxb}oO_EXx?~o>6P3+JnK@#Nw#LlT2mPBJE=fuLJCGDB(U!7bJgfjOu5X)w9P<|z? z3?IDEG|4VX7>eJ1^SUnP*jn+{wfOGr^!SVwet5QfwA0&~_4_(z1~UF(k66ttjOMR@ zIeYQb4I#c5-(Ft6nEkDPfS{@aYc1lnw8dAzmoh8@^S}Bkj;`B!!OQmZdY$?%VE*;q z=5;x-Db6D4E)>M?e)jK;(jRZE-h14CcKhMOo2^&MfPrbPIskiS)Uxp1{3orMr#0do!MB?rE39^L1WMPr{7 z82(_IlUnVz`HPB(Xam7J$Iv;G)UL00x7Vw102^>cKcP9U8feB2xW=jTI*76%!BtrZ zBdW4$9?$;qHUJ*pJ=$PFU-%{w7AC=yQG)J15LE$4`I>Rd85opgR&;1kHR=E-4d_K# zX5b9cDCA@WtSnfCRysUQm>LyC6fnV|1f-ixlQF7&CGaC->o1};LPlfJhYLU(3**Gn zIGbkZKbj(bD$7OzOM4S@TDXFM5LP#^yV#I&hG<2sa{$&(F`fo#9Y@)i-MtCOcxLe1 z+!T!292_*zuVj$E1JxGjF=3wg&d3gge?g-)nsDh&XEB&~DA6Ac3D4R91Ex9GZ~2z% zYM0Sai?_6WA)grQD_S(B50#Tj{-p2HnXRC?>^w-4W$8P^lIWb>Hn%0NW4n%3{IsI2 z;ZUhCcf3AhKMF$|H|g2DD?P8EI87J@M*23_ipLhCwOp{Qxmvbr!OP7|HW16!8x=e| z{PhkQ^jyZ!mtt&DGcTlKDZ|tpDh-=dEwlzxxl!`r|5hT4!Nnz}oZi=TVm_xWKP7P!~7{lP)>t%eecV%Rk6o4>sC+ zOIwF`zi4i-ps;$=Q0RE$R`727XU+2lfbSkTPW8dk)@;7WTZk;vz9c#%EA0$ufpVT< z4&5~XtQj1FyKG8eaK;-Cj=K`5fw;-8?IpB@zvihbfSFTjrN-1`&2~e>(n)Xe0w9=w zu?eOUdf_7ZuXus63>GX-r54N=ZA%<7UU=BOMzY%mxz!#*NxstRg|-t%@>QGl42;Uk z#g_|+@RfDH~IM49Q#V2O-zHvF+mZi}5N`-%*X z4c)RVRcEE7uRLU}f%ye1bg>6!W->4vZNCPe1|*8J93T4(nKWe5@0Jm@)$dneZ-T~& zP>Lb7H|UqUjG^-3`JJ#~$pE)Gc7j}K=4qf?(CtDig=H~PDo5pkhl}~{2nk(ST;~S< z1bb`H`hI2L(wS_Ym>}&^(w$XYMT0N2*F$zA<#Lmo$ z<6!O(-rxMiQVP4Jhqj zL;Q|hNw#z_5@Cr>T9&m*+x#o**7Qt-+S-)BV2!o4*mV7`O}vso44DHPU<(mjyh$C~ z@Ee+mBV`pcqGR8>9LL6MS|_YeP_UeiayZgy1>~`+q`CMFI}bYw+8v?72BXJ>U>t5o z)3y~U5vE^Ed39~JWYZ>Y$Z|Acn}HKiBBd&or`^4F7LB>IfrM5wXzBX69tCGHSklHw zC$z`c=4)A*b0Xx>Ha<&K&}7(k{v!yY^>c{Ob+z`YQHU|p28nk9+c<2|HX(tMb!&G5 z_iTMTJF8~UH6gwq;O@>2Q!%;nO)y7ehf?SIj?Sn#@>cn?5M{~EtVxmwAzM_;#8I1M zWg#`ePNn*N;kGv7OSmw$!Q2DOG+MGfIEfBpDVu*fj)PF5o&J>nnIeud%M`1<2hPcr zv)fG8z(BV8>AUT7@BK92SdFV~x3PbwB8(LY90&CS&At*zm0Nqbzqzj)-lB-0W~

5. Manually land and disarm to apply the new tuning parameters. @@ -104,6 +112,13 @@ The test steps are: 5. The tuning will be immediately/automatically be applied and tested in flight (by default). PX4 will then run a 4 second test and revert the new tuning if a problem is detected. +The figure below shows how steps 4 and 5 might look in flight on the pitch axis. +The pitch rate gradually increases up until it reaches the target. +This amplitude is then held while the signal frequency is increased. +You can then see how the tuned system is able to follow the setpoint in the test signal. + + +
::: warning @@ -170,9 +185,23 @@ Fast oscillations (more than 1 oscillation per second): this is because the gain ### The auto-tuning sequence fails +
+ If the drone was not moving enough during auto-tuning, the system identification algorithm might have issues to find the correct coefficients. -Increase the
[MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_SYSID_AMP)
[FW_AT_SYSID_AMP](../advanced_config/parameter_reference.md#FW_AT_SYSID_AMP)
parameter by steps of 1 and trigger the auto-tune again. +Increase the [MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_SYSID_AMP) parameter by steps of 1 and trigger the auto-tune again. + +
+
+ +By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification. The target rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. + +If the signal-to-noise ratio of the vehicle is low, the system identification algorithm might have issues finding the correct coefficients. Ensure that there is no excessive noise and/or platform vibration. + + + +
+ ### The drone oscillates after auto-tuning From 86f2fdfd7de7f5e5d29ab61f60d81e892a557376 Mon Sep 17 00:00:00 2001 From: mahima-yoga Date: Thu, 2 Oct 2025 13:59:31 +0200 Subject: [PATCH 141/812] docs: add description to AutotuneAttitudeControlStatus.msg --- msg/AutotuneAttitudeControlStatus.msg | 71 +++++++++++++++------------ 1 file changed, 39 insertions(+), 32 deletions(-) diff --git a/msg/AutotuneAttitudeControlStatus.msg b/msg/AutotuneAttitudeControlStatus.msg index 15e9478e6d..63cc07d576 100644 --- a/msg/AutotuneAttitudeControlStatus.msg +++ b/msg/AutotuneAttitudeControlStatus.msg @@ -1,38 +1,45 @@ -uint64 timestamp # time since system start (microseconds) +# Autotune attitude control status +# +# This message is published by the fw_autotune_attitude_control and mc_autotune_attitude_control modules when the user engages autotune, +# and is subscribed to by the respective attitude controllers to command rate setpoints. +# +# The rate_sp field is consumed by the controllers, while the remaining fields (model coefficients, gains, filters, and autotune state) are used for logging and debugging. -float32[5] coeff # coefficients of the identified discrete-time model -float32[5] coeff_var # coefficients' variance of the identified discrete-time model -float32 fitness # fitness of the parameter estimate -float32 innov -float32 dt_model +uint64 timestamp # [us] Time since system start -float32 kc -float32 ki -float32 kd -float32 kff -float32 att_p +float32[5] coeff # [-] Coefficients of the identified discrete-time model +float32[5] coeff_var # [-] Coefficients' variance of the identified discrete-time model +float32 fitness # [-] Fitness of the parameter estimate +float32 innov # [rad/s] Innovation (residual error between model and measured output) +float32 dt_model # [s] Model sample time used for identification -float32[3] rate_sp -float32 u_filt -float32 y_filt +float32 kc # [-] Proportional rate-loop gain (ideal form) +float32 ki # [-] Integral rate-loop gain (ideal form) +float32 kd # [-] Derivative rate-loop gain (ideal form) +float32 kff # [-] Feedforward rate-loop gain +float32 att_p # [-] Proportional attitude gain -uint8 STATE_IDLE = 0 -uint8 STATE_INIT = 1 -uint8 STATE_ROLL_AMPLITUDE_DETECTION = 2 -uint8 STATE_ROLL = 3 -uint8 STATE_ROLL_PAUSE = 4 -uint8 STATE_PITCH_AMPLITUDE_DETECTION = 5 -uint8 STATE_PITCH = 6 -uint8 STATE_PITCH_PAUSE = 7 -uint8 STATE_YAW_AMPLITUDE_DETECTION = 8 -uint8 STATE_YAW = 9 -uint8 STATE_YAW_PAUSE = 10 -uint8 STATE_VERIFICATION = 11 -uint8 STATE_APPLY = 12 -uint8 STATE_TEST = 13 -uint8 STATE_COMPLETE = 14 -uint8 STATE_FAIL = 15 -uint8 STATE_WAIT_FOR_DISARM = 16 +float32[3] rate_sp # [rad/s] Rate setpoint commanded to the attitude controller. -uint8 state +float32 u_filt # [-] Filtered input signal (normalized torque setpoint) used in system identification. +float32 y_filt # [rad/s] Filtered output signal (angular velocity) used in system identification. + +uint8 state # [@enum STATE] Current state of the autotune procedure. +uint8 STATE_IDLE = 0 # Idle (not running) +uint8 STATE_INIT = 1 # Initialize filters and setup +uint8 STATE_ROLL_AMPLITUDE_DETECTION = 2 # FW only: determine required excitation amplitude (roll) +uint8 STATE_ROLL = 3 # Roll-axis excitation and model identification +uint8 STATE_ROLL_PAUSE = 4 # Pause to return to level flight +uint8 STATE_PITCH_AMPLITUDE_DETECTION = 5 # FW only: determine required excitation amplitude (pitch) +uint8 STATE_PITCH = 6 # Pitch-axis excitation and model identification +uint8 STATE_PITCH_PAUSE = 7 # Pause to return to level flight +uint8 STATE_YAW_AMPLITUDE_DETECTION = 8 # FW only: determine required excitation amplitude (yaw) +uint8 STATE_YAW = 9 # Yaw-axis excitation and model identification +uint8 STATE_YAW_PAUSE = 10 # Pause to return to level flight +uint8 STATE_VERIFICATION = 11 # Verify model and candidate gains +uint8 STATE_APPLY = 12 # Apply gains +uint8 STATE_TEST = 13 # Test gains in closed-loop +uint8 STATE_COMPLETE = 14 # Tuning completed successfully +uint8 STATE_FAIL = 15 # Tuning failed (model invalid or controller unstable) +uint8 STATE_WAIT_FOR_DISARM = 16 # Waiting for disarm before finalizing From 3712af8b7f7d13535e7f723c2c85fd7fae4fe8c8 Mon Sep 17 00:00:00 2001 From: Marco Hauswirth Date: Thu, 11 Sep 2025 16:58:06 +0200 Subject: [PATCH 142/812] * avoid gnss-based altitude reset in DR-mode * add hysteresis for re-enabling fusion * disable lat/lon/vel fusion on gnss_hgt_fault --- .../aid_sources/gnss/gnss_height_control.cpp | 61 +++++++++++++++---- .../ekf2/EKF/aid_sources/gnss/gps_control.cpp | 6 +- src/modules/ekf2/EKF/common.h | 4 +- src/modules/ekf2/EKF/ekf.h | 5 +- 4 files changed, 59 insertions(+), 17 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp index c604e416b8..8481ed8b0c 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp @@ -106,7 +106,7 @@ void Ekf::controlGnssHeightFusion(const gnssSample &gps_sample) const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.hgt_fusion_timeout_max); - if (isHeightResetRequired() && (_height_sensor_ref == HeightSensor::GNSS)) { + if (isHeightResetRequired() && (_height_sensor_ref == HeightSensor::GNSS) && isGnssHgtResetAllowed()) { // All height sources are failing ECL_WARN("%s height fusion reset required, all height sources failing", HGT_SRC_NAME); @@ -120,17 +120,18 @@ void Ekf::controlGnssHeightFusion(const gnssSample &gps_sample) } else if (is_fusion_failing) { // Some other height source is still working ECL_WARN("stopping %s height fusion, fusion failing", HGT_SRC_NAME); - stopGpsHgtFusion(); + stopGpsHgtFusion(&aid_src); } } else { ECL_WARN("stopping %s height fusion, continuing conditions failing", HGT_SRC_NAME); - stopGpsHgtFusion(); + stopGpsHgtFusion(&aid_src); } } else { if (starting_conditions_passing) { - if (_params.ekf2_hgt_ref == static_cast(HeightSensor::GNSS)) { + + if (_params.ekf2_hgt_ref == static_cast(HeightSensor::GNSS) && isGnssHgtResetAllowed()) { ECL_INFO("starting %s height fusion, resetting height", HGT_SRC_NAME); _height_sensor_ref = HeightSensor::GNSS; @@ -140,16 +141,36 @@ void Ekf::controlGnssHeightFusion(const gnssSample &gps_sample) bias_est.reset(); resetAidSourceStatusZeroInnovation(aid_src); - } else { - ECL_INFO("starting %s height fusion", HGT_SRC_NAME); - bias_est.setBias(-_gpos.altitude() + measurement); } - aid_src.time_last_fuse = _time_delayed_us; - bias_est.setFusionActive(); - _control_status.flags.gps_hgt = true; + bool is_gnss_hgt_consistent = true; - } if (altitude_initialisation_conditions_passing) { + if (_control_status.flags.gnss_hgt_fault) { + if (aid_src.innovation_rejected) { + _gnss_hgt_hysteresis_time = 0; + + } else if (_gnss_hgt_hysteresis_time == 0) { + _gnss_hgt_hysteresis_time = aid_src.timestamp_sample; + } + + is_gnss_hgt_consistent = isTimedOut(_gnss_hgt_hysteresis_time, _params.hgt_fusion_timeout_max) + && isRecent(_gnss_hgt_hysteresis_time, 2 * _params.hgt_fusion_timeout_max); + + } + + if (is_gnss_hgt_consistent) { + if (_params.ekf2_hgt_ref != static_cast(HeightSensor::GNSS)) { + bias_est.setBias(-_gpos.altitude() + measurement); + } + + aid_src.time_last_fuse = _time_delayed_us; + bias_est.setFusionActive(); + _control_status.flags.gps_hgt = true; + _control_status.flags.gnss_hgt_fault = false; + } + } + + if (altitude_initialisation_conditions_passing && !_control_status.flags.gnss_hgt_fault) { // Do not start GNSS altitude aiding, but use measurement // to initialize altitude and bias of other height sensors @@ -164,11 +185,11 @@ void Ekf::controlGnssHeightFusion(const gnssSample &gps_sample) && !isNewestSampleRecent(_time_last_gps_buffer_push, 2 * GNSS_MAX_INTERVAL)) { // No data anymore. Stop until it comes back. ECL_WARN("stopping %s height fusion, no data", HGT_SRC_NAME); - stopGpsHgtFusion(); + stopGpsHgtFusion(&aid_src); } } -void Ekf::stopGpsHgtFusion() +void Ekf::stopGpsHgtFusion(estimator_aid_source1d_s *aid_src) { if (_control_status.flags.gps_hgt) { @@ -179,5 +200,19 @@ void Ekf::stopGpsHgtFusion() _gps_hgt_b_est.setFusionInactive(); _control_status.flags.gps_hgt = false; + + if (aid_src != nullptr && aid_src->innovation_rejected && !isGnssHgtResetAllowed()) { + _control_status.flags.gnss_hgt_fault = true; + _gnss_hgt_hysteresis_time = 0; + } + } } + +bool Ekf::isGnssHgtResetAllowed() +{ + const bool allowed = !(static_cast(_params.ekf2_gps_mode) == GnssMode::kDeadReckoning + && isOtherSourceOfVerticalPositionAidingThan(_control_status.flags.gps_hgt)); + + return allowed; +} diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp index 76936556a4..60ed3f74ce 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp @@ -124,7 +124,8 @@ void Ekf::controlGnssVelFusion(estimator_aid_source3d_s &aid_src, const bool for const bool continuing_conditions_passing = (_params.ekf2_gps_ctrl & static_cast(GnssCtrl::VEL)) && _control_status.flags.tilt_align && _control_status.flags.yaw_align - && !_control_status.flags.gnss_fault; + && !_control_status.flags.gnss_fault + && !_control_status.flags.gnss_hgt_fault; const bool starting_conditions_passing = continuing_conditions_passing && _gnss_checks.passed(); if (_control_status.flags.gnss_vel) { @@ -180,7 +181,8 @@ void Ekf::controlGnssPosFusion(estimator_aid_source2d_s &aid_src, const bool for const bool continuing_conditions_passing = gnss_pos_enabled && _control_status.flags.tilt_align - && _control_status.flags.yaw_align; + && _control_status.flags.yaw_align + && !_control_status.flags.gnss_hgt_fault; const bool starting_conditions_passing = continuing_conditions_passing && _gnss_checks.passed(); const bool gpos_init_conditions_passing = gnss_pos_enabled && _gnss_checks.passed(); diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 63655750f5..c8d61754aa 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -607,8 +607,10 @@ uint64_t mag_heading_consistent : uint64_t baro_fault : 1; ///< 43 - true when the baro has been declared faulty and is no longer being used uint64_t gnss_vel : 1; ///< 44 - true if GNSS velocity measurement fusion is intended uint64_t gnss_fault : - 1; ///< 45 - true if GNSS measurements have been declared faulty and are no longer used + 1; ///< 45 - true if GNSS measurements (lat, lon, vel) have been declared faulty and are no longer used uint64_t yaw_manual : 1; ///< 46 - true if yaw has been reset manually +uint64_t gnss_hgt_fault : + 1; ///< 47 - true if GNSS measurements (alt) have been declared faulty and are no longer used } flags; uint64_t value; }; diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 3c5f7ba3f5..099827f6dc 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -581,6 +581,8 @@ private: estimator_aid_source2d_s _aid_src_gnss_pos{}; estimator_aid_source3d_s _aid_src_gnss_vel{}; + uint64_t _gnss_hgt_hysteresis_time{0}; + # if defined(CONFIG_EKF2_GNSS_YAW) estimator_aid_source1d_s _aid_src_gnss_yaw {}; # endif // CONFIG_EKF2_GNSS_YAW @@ -885,7 +887,8 @@ private: void resetHorizontalPositionToGnss(estimator_aid_source2d_s &aid_src); void controlGnssHeightFusion(const gnssSample &gps_sample); - void stopGpsHgtFusion(); + void stopGpsHgtFusion(estimator_aid_source1d_s *aid_src=nullptr); + bool isGnssHgtResetAllowed(); # if defined(CONFIG_EKF2_GNSS_YAW) void controlGnssYawFusion(const gnssSample &gps_sample); From c2c721a2d6c5fb5fb114b5cecc09384879c44392 Mon Sep 17 00:00:00 2001 From: Marco Hauswirth Date: Wed, 17 Sep 2025 15:17:47 +0200 Subject: [PATCH 143/812] * add gnss-fault flags to estimator-status msg * react to comments --- msg/EstimatorStatusFlags.msg | 3 +- .../aid_sources/gnss/gnss_height_control.cpp | 29 ++++++++----------- src/modules/ekf2/EKF/ekf.h | 4 +-- src/modules/ekf2/EKF2.cpp | 1 + 4 files changed, 17 insertions(+), 20 deletions(-) diff --git a/msg/EstimatorStatusFlags.msg b/msg/EstimatorStatusFlags.msg index ef85dbaf7c..3f8435b6e5 100644 --- a/msg/EstimatorStatusFlags.msg +++ b/msg/EstimatorStatusFlags.msg @@ -49,8 +49,9 @@ bool cs_valid_fake_pos # 41 - true if a valid constant position is bein bool cs_constant_pos # 42 - true if the vehicle is at a constant position bool cs_baro_fault # 43 - true when the current baro has been declared faulty and is no longer being used bool cs_gnss_vel # 44 - true if GNSS velocity measurement fusion is intended -bool cs_gnss_fault # 45 - true if GNSS measurements have been declared faulty and are no longer used +bool cs_gnss_fault # 45 - true if GNSS true if GNSS measurements (lat, lon, vel) have been declared faulty bool cs_yaw_manual # 46 - true if yaw has been set manually +bool cs_gnss_hgt_fault # 47 - true if GNSS true if GNSS measurements (alt) have been declared faulty # fault status uint32 fault_status_changes # number of filter fault status (fs) changes diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp index 8481ed8b0c..60eaefec33 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp @@ -120,12 +120,17 @@ void Ekf::controlGnssHeightFusion(const gnssSample &gps_sample) } else if (is_fusion_failing) { // Some other height source is still working ECL_WARN("stopping %s height fusion, fusion failing", HGT_SRC_NAME); - stopGpsHgtFusion(&aid_src); + stopGpsHgtFusion(); + + if (!isGnssHgtResetAllowed()) { + _control_status.flags.gnss_hgt_fault = true; + _time_last_gnss_hgt_rejected = _time_delayed_us; + } } } else { ECL_WARN("stopping %s height fusion, continuing conditions failing", HGT_SRC_NAME); - stopGpsHgtFusion(&aid_src); + stopGpsHgtFusion(); } } else { @@ -146,16 +151,12 @@ void Ekf::controlGnssHeightFusion(const gnssSample &gps_sample) bool is_gnss_hgt_consistent = true; if (_control_status.flags.gnss_hgt_fault) { - if (aid_src.innovation_rejected) { - _gnss_hgt_hysteresis_time = 0; - } else if (_gnss_hgt_hysteresis_time == 0) { - _gnss_hgt_hysteresis_time = aid_src.timestamp_sample; + if (aid_src.innovation_rejected) { + _time_last_gnss_hgt_rejected = _time_delayed_us; } - is_gnss_hgt_consistent = isTimedOut(_gnss_hgt_hysteresis_time, _params.hgt_fusion_timeout_max) - && isRecent(_gnss_hgt_hysteresis_time, 2 * _params.hgt_fusion_timeout_max); - + is_gnss_hgt_consistent = isTimedOut(_time_last_gnss_hgt_rejected, _params.hgt_fusion_timeout_max); } if (is_gnss_hgt_consistent) { @@ -185,11 +186,11 @@ void Ekf::controlGnssHeightFusion(const gnssSample &gps_sample) && !isNewestSampleRecent(_time_last_gps_buffer_push, 2 * GNSS_MAX_INTERVAL)) { // No data anymore. Stop until it comes back. ECL_WARN("stopping %s height fusion, no data", HGT_SRC_NAME); - stopGpsHgtFusion(&aid_src); + stopGpsHgtFusion(); } } -void Ekf::stopGpsHgtFusion(estimator_aid_source1d_s *aid_src) +void Ekf::stopGpsHgtFusion() { if (_control_status.flags.gps_hgt) { @@ -200,12 +201,6 @@ void Ekf::stopGpsHgtFusion(estimator_aid_source1d_s *aid_src) _gps_hgt_b_est.setFusionInactive(); _control_status.flags.gps_hgt = false; - - if (aid_src != nullptr && aid_src->innovation_rejected && !isGnssHgtResetAllowed()) { - _control_status.flags.gnss_hgt_fault = true; - _gnss_hgt_hysteresis_time = 0; - } - } } diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 099827f6dc..1a8466c96d 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -581,7 +581,7 @@ private: estimator_aid_source2d_s _aid_src_gnss_pos{}; estimator_aid_source3d_s _aid_src_gnss_vel{}; - uint64_t _gnss_hgt_hysteresis_time{0}; + uint64_t _time_last_gnss_hgt_rejected{0}; # if defined(CONFIG_EKF2_GNSS_YAW) estimator_aid_source1d_s _aid_src_gnss_yaw {}; @@ -887,7 +887,7 @@ private: void resetHorizontalPositionToGnss(estimator_aid_source2d_s &aid_src); void controlGnssHeightFusion(const gnssSample &gps_sample); - void stopGpsHgtFusion(estimator_aid_source1d_s *aid_src=nullptr); + void stopGpsHgtFusion(); bool isGnssHgtResetAllowed(); # if defined(CONFIG_EKF2_GNSS_YAW) diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index ec2c975500..f93f59085f 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1955,6 +1955,7 @@ void EKF2::PublishStatusFlags(const hrt_abstime ×tamp) status_flags.cs_gnss_vel = _ekf.control_status_flags().gnss_vel; status_flags.cs_gnss_fault = _ekf.control_status_flags().gnss_fault; status_flags.cs_yaw_manual = _ekf.control_status_flags().yaw_manual; + status_flags.cs_gnss_hgt_fault = _ekf.control_status_flags().gnss_hgt_fault; status_flags.fault_status_changes = _filter_fault_status_changes; status_flags.fs_bad_mag_x = _ekf.fault_status_flags().bad_mag_x; From 6e579cb75a349be5a7ff46932f38759168928a31 Mon Sep 17 00:00:00 2001 From: Marco Hauswirth Date: Wed, 1 Oct 2025 13:42:43 +0200 Subject: [PATCH 144/812] improve gnss altitude fusion starting logic --- .../aid_sources/gnss/gnss_height_control.cpp | 73 ++++++++++--------- 1 file changed, 40 insertions(+), 33 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp index 60eaefec33..80ec82a883 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp @@ -134,52 +134,58 @@ void Ekf::controlGnssHeightFusion(const gnssSample &gps_sample) } } else { - if (starting_conditions_passing) { + if (altitude_initialisation_conditions_passing) { + // Altitude not initialized, GNSS is the configured height reference + _information_events.flags.reset_hgt_to_gps = true; + initialiseAltitudeTo(measurement, measurement_var); + bias_est.reset(); - if (_params.ekf2_hgt_ref == static_cast(HeightSensor::GNSS) && isGnssHgtResetAllowed()) { - ECL_INFO("starting %s height fusion, resetting height", HGT_SRC_NAME); + // Start fusion if GPS vertical position control is also enabled + if (starting_conditions_passing) { _height_sensor_ref = HeightSensor::GNSS; + resetAidSourceStatusZeroInnovation(aid_src); + aid_src.time_last_fuse = _time_delayed_us; + bias_est.setFusionActive(); + _control_status.flags.gps_hgt = true; + } + } else if (starting_conditions_passing) { + if (_params.ekf2_hgt_ref == static_cast(HeightSensor::GNSS) && isGnssHgtResetAllowed()) { + _height_sensor_ref = HeightSensor::GNSS; _information_events.flags.reset_hgt_to_gps = true; - initialiseAltitudeTo(measurement, measurement_var); + resetAltitudeTo(measurement, measurement_var); bias_est.reset(); resetAidSourceStatusZeroInnovation(aid_src); - } - - bool is_gnss_hgt_consistent = true; - - if (_control_status.flags.gnss_hgt_fault) { - - if (aid_src.innovation_rejected) { - _time_last_gnss_hgt_rejected = _time_delayed_us; - } - - is_gnss_hgt_consistent = isTimedOut(_time_last_gnss_hgt_rejected, _params.hgt_fusion_timeout_max); - } - - if (is_gnss_hgt_consistent) { - if (_params.ekf2_hgt_ref != static_cast(HeightSensor::GNSS)) { - bias_est.setBias(-_gpos.altitude() + measurement); - } - aid_src.time_last_fuse = _time_delayed_us; bias_est.setFusionActive(); _control_status.flags.gps_hgt = true; _control_status.flags.gnss_hgt_fault = false; + + } else { + bool is_gnss_hgt_consistent = true; + + if (_control_status.flags.gnss_hgt_fault) { + if (aid_src.innovation_rejected) { + _time_last_gnss_hgt_rejected = _time_delayed_us; + } + + is_gnss_hgt_consistent = isTimedOut(_time_last_gnss_hgt_rejected, _params.hgt_fusion_timeout_max); + } + + if (is_gnss_hgt_consistent) { + if (_params.ekf2_hgt_ref != static_cast(HeightSensor::GNSS)) { + bias_est.setBias(-_gpos.altitude() + measurement); + } + + aid_src.time_last_fuse = _time_delayed_us; + bias_est.setFusionActive(); + _control_status.flags.gps_hgt = true; + _control_status.flags.gnss_hgt_fault = false; + } } } - - if (altitude_initialisation_conditions_passing && !_control_status.flags.gnss_hgt_fault) { - - // Do not start GNSS altitude aiding, but use measurement - // to initialize altitude and bias of other height sensors - _information_events.flags.reset_hgt_to_gps = true; - - initialiseAltitudeTo(measurement, measurement_var); - bias_est.reset(); - } } } else if (_control_status.flags.gps_hgt @@ -207,7 +213,8 @@ void Ekf::stopGpsHgtFusion() bool Ekf::isGnssHgtResetAllowed() { const bool allowed = !(static_cast(_params.ekf2_gps_mode) == GnssMode::kDeadReckoning - && isOtherSourceOfVerticalPositionAidingThan(_control_status.flags.gps_hgt)); + && isOtherSourceOfVerticalPositionAidingThan(_control_status.flags.gps_hgt)) + || !PX4_ISFINITE(_local_origin_alt); return allowed; } From 849819629afc84d1a7681f756874497372ef1653 Mon Sep 17 00:00:00 2001 From: QiTao Weng <47102225+qtweng@users.noreply.github.com> Date: Fri, 3 Oct 2025 13:01:40 -0500 Subject: [PATCH 145/812] dds: add adsb topic (#25652) --- src/modules/uxrce_dds_client/dds_topics.yaml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/modules/uxrce_dds_client/dds_topics.yaml b/src/modules/uxrce_dds_client/dds_topics.yaml index e315a7f1d5..ef7ba8fc0b 100644 --- a/src/modules/uxrce_dds_client/dds_topics.yaml +++ b/src/modules/uxrce_dds_client/dds_topics.yaml @@ -50,6 +50,9 @@ publications: type: px4_msgs::msg::TimesyncStatus rate_limit: 10. + - topic: /fmu/out/transponder_report + type: px4_msgs::msg::TransponderReport + # - topic: /fmu/out/vehicle_angular_velocity # type: px4_msgs::msg::VehicleAngularVelocity From 1a3cdecb3913c8070e36723a7585abea5bfc66d0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Maciej=20Ma=C5=82ecki?= Date: Fri, 3 Oct 2025 20:03:40 +0200 Subject: [PATCH 146/812] boards/mro/pixracerpro: enable additional UARTs (#22516) The UARTs themselves were already present, just not configured under any alias. Follow [ArduPilot UART naming for this board](https://ardupilot.org/plane/docs/common-pixracer-pro.html#default-uart-order), out of necessity: it's the only combination that makes sense and is understood by QGroundControl. (For example, I've attempted configuring the additional UARTs as `_EXT1` and `_EXT2`, but only `_EXT2` was understood by QGC.) Trying to actually use the FrSky telemetry port for anything without configuring FrSky telemetry on a different port may be impossible without modifying the board's `init/rc.board_extras`. (Should that script be modified to check if the port is used for anything else?) Skip naming the RC input port. Fixes #21455. --- boards/mro/pixracerpro/default.px4board | 3 +++ 1 file changed, 3 insertions(+) diff --git a/boards/mro/pixracerpro/default.px4board b/boards/mro/pixracerpro/default.px4board index 401f42f36f..f6106d42af 100644 --- a/boards/mro/pixracerpro/default.px4board +++ b/boards/mro/pixracerpro/default.px4board @@ -1,8 +1,11 @@ CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" CONFIG_BOARD_ARCHITECTURE="cortex-m7" CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS6" CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1" CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS0" +CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS5" CONFIG_BOARD_PARAM_FILE="/fs/microsd/params" CONFIG_DRIVERS_ADC_ADS1115=y CONFIG_DRIVERS_ADC_BOARD_ADC=y From 6be7abb13de9fabdd17e594453504dd11924292d Mon Sep 17 00:00:00 2001 From: JoelJ18 <101486509+JoelJ18@users.noreply.github.com> Date: Fri, 3 Oct 2025 23:13:04 -0400 Subject: [PATCH 147/812] MicroStrain driver: Expanded aiding support (#25673) * External mag + Optical flow aiding * Adding autostart * global position eph fix * write fix * configureAidingSources split + frame fixes + params cleanup * configureGnssAiding fix + params cleanup * Redundant param removal * External Heading fix --- src/drivers/ins/microstrain/MicroStrain.cpp | 437 +++++++++++++------- src/drivers/ins/microstrain/MicroStrain.hpp | 52 ++- src/drivers/ins/microstrain/module.yaml | 419 +++++++++++-------- 3 files changed, 587 insertions(+), 321 deletions(-) diff --git a/src/drivers/ins/microstrain/MicroStrain.cpp b/src/drivers/ins/microstrain/MicroStrain.cpp index 428e404b36..a46639e4ff 100755 --- a/src/drivers/ins/microstrain/MicroStrain.cpp +++ b/src/drivers/ins/microstrain/MicroStrain.cpp @@ -91,13 +91,35 @@ MicroStrain::MicroStrain(const char *uart_port) : (double)_param_ms_gnss_offset2_y.get(), (double)_param_ms_gnss_offset2_z.get()); - rotation.euler[0] = _param_ms_sensor_roll.get(); - rotation.euler[1] = _param_ms_sensor_pitch.get(); - rotation.euler[2] = _param_ms_sensor_yaw.get(); + optical_flow_offset[0] = _param_ms_oflow_offset_x.get(); + optical_flow_offset[1] = _param_ms_oflow_offset_y.get(); + optical_flow_offset[2] = _param_ms_oflow_offset_z.get(); + PX4_DEBUG("Optical flow offset: %f/%f/%f", (double)_param_ms_oflow_offset_x.get(), + (double)_param_ms_oflow_offset_y.get(), + (double)_param_ms_oflow_offset_z.get()); + + rotation_sens.euler[0] = _param_ms_sensor_roll.get(); + rotation_sens.euler[1] = _param_ms_sensor_pitch.get(); + rotation_sens.euler[2] = _param_ms_sensor_yaw.get(); PX4_DEBUG("Device Roll/Pitch/Yaw: %f/%f/%f", (double)_param_ms_sensor_roll.get(), (double)_param_ms_sensor_pitch.get(), (double)_param_ms_sensor_yaw.get()); + rotation_ext_mag.euler[0] = _param_ms_emag_roll.get(); + rotation_ext_mag.euler[1] = _param_ms_emag_pitch.get(); + rotation_ext_mag.euler[2] = _param_ms_emag_yaw.get(); + PX4_DEBUG("External magnetometer Roll/Pitch/Yaw: %f/%f/%f", (double)_param_ms_emag_roll.get(), + (double)_param_ms_emag_pitch.get(), + (double)_param_ms_emag_yaw.get()); + + rotation_ext_heading.euler[2] = _param_ms_ehead_yaw.get(); + PX4_DEBUG("External heading yaw: %f", (double)_param_ms_ehead_yaw.get()); + + ext_mag_uncert = _param_ms_emag_uncert.get(); + opt_flow_uncert = _param_ms_oflow_uncert.get(); + PX4_DEBUG("External Mag Uncertainty: %f", (double)_param_ms_emag_uncert.get()); + PX4_DEBUG("Optical Flow Uncertainty: %f", (double)_param_ms_oflow_uncert.get()); + _sensor_baro_pub.advertise(); _sensor_selection_pub.advertise(); _vehicle_local_position_pub.advertise(); @@ -106,9 +128,6 @@ MicroStrain::MicroStrain(const char *uart_port) : _vehicle_global_position_pub.advertise(); _vehicle_odometry_pub.advertise(); _estimator_status_pub.advertise(); - _sensor_gps_pub[0].advertise(); - _sensor_gps_pub[1].advertise(); - } MicroStrain::~MicroStrain() @@ -156,9 +175,9 @@ bool mipInterfaceUserRecvFromDevice(mip_interface *device, uint8_t *buffer, size bool mipInterfaceUserSendToDevice(mip_interface *device, const uint8_t *data, size_t length) { - int res = device_uart.write(const_cast(data), length); + size_t res = device_uart.write(const_cast(data), length); - if (res >= 0) { + if (res == length) { return true; } @@ -239,7 +258,7 @@ mip_cmd_result MicroStrain::getSupportedDescriptors() return res; } - if (mip_cmd_result_is_ack(res_extended)) { + if (!mip_cmd_result_is_ack(res_extended)) { PX4_DEBUG("Device does not support the extended descriptors command."); } @@ -531,7 +550,6 @@ mip_cmd_result MicroStrain::configureImuMessageFormat() imu_descriptors); return res; - } mip_cmd_result MicroStrain::configureFilterMessageFormat() @@ -635,6 +653,11 @@ mip_cmd_result MicroStrain::configureFilterMessageFormat() mip_cmd_result MicroStrain::configureGnssMessageFormat(uint8_t descriptor_set) { + if (_param_ms_gnss_aid_src_ctrl.get() == MIP_FILTER_GNSS_SOURCE_COMMAND_SOURCE_EXT) { + PX4_DEBUG("External GNSS aiding source detected, skipping GNSS message format config"); + return MIP_ACK_OK; + } + PX4_DEBUG("Configuring GNSS Message Format"); uint8_t num_gnss_descriptors = 0; @@ -700,34 +723,174 @@ mip_cmd_result MicroStrain::configureGnssMessageFormat(uint8_t descriptor_set) gnss_descriptors); return res; - } mip_cmd_result MicroStrain::configureAidingMeasurement(uint16_t aiding_source, bool enable) { - mip_cmd_result res; - - // Configures the aiding measurement if the device support it - if (supportsDescriptor(MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE)) { - res = mip_filter_write_aiding_measurement_enable(&_device, aiding_source, enable); - - // If the device doesnt support the aiding source but the command is to disable it, we consider it a success - if (res == MIP_NACK_INVALID_PARAM && !enable) { - res = MIP_ACK_OK; - } - - } else { + // If the device doesn’t support aiding measurements + if (!supportsDescriptor(MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_AIDING_MEASUREMENT_ENABLE)) { PX4_WARN("Aiding measurements are not supported"); - // If the command was to disable, we consider it a success - if (!enable) { - res = MIP_ACK_OK; + // disabling is always OK + return enable ? MIP_PX4_ERROR : MIP_ACK_OK; + } + + // Try to configure aiding measurement + mip_cmd_result res = mip_filter_write_aiding_measurement_enable(&_device, aiding_source, enable); + + // If the device doesnt support the aiding source but the command is to disable it, we consider it a success + if (res == MIP_NACK_INVALID_PARAM && !enable) { + return MIP_ACK_OK; + } + + return res; +} + +mip_cmd_result MicroStrain::enableAidingSource(uint16_t source, + bool enabled, + uint8_t frame_id, + uint8_t frame_format, + const float offset[3], + mip_aiding_frame_config_command_rotation rotation, + uint16_t aiding_cmd_desc, + bool &aiding_flag, + const char *name) +{ + mip_cmd_result res = configureAidingMeasurement(source, enabled); + + if (!mip_cmd_result_is_ack(res)) { + PX4_ERR("Could not configure %s aiding", name); + return res; + } + + // Frame 0 is used to handle the internal aiding scenario + if (frame_id == 0) { + return res; + } + + // True if the aiding message supported & requested + aiding_flag = supportsDescriptor(MIP_AIDING_CMD_DESC_SET, aiding_cmd_desc) && enabled; + + // Error if requested but unsupported. + if (enabled && !aiding_flag) { + PX4_ERR("Sending %s aiding messages not supported", name); + return MIP_PX4_ERROR; + } + + // Write the frame config if enabled + if (aiding_flag) { + res = mip_aiding_write_frame_config(&_device, frame_id, frame_format, false, offset, &rotation); + + if (!mip_cmd_result_is_ack(res)) { + PX4_ERR("Could not write %s frame config", name); + return res; + } + } + + return res; +} + +mip_cmd_result MicroStrain::configureGnssAiding() +{ + // Enables GNSS Position & Velocity as an aiding measurement + mip_cmd_result res = configureAidingMeasurement(MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_GNSS_POS_VEL, + true); + + if (!mip_cmd_result_is_ack(res)) { + if (res != MIP_NACK_INVALID_PARAM && res != MIP_PX4_ERROR) { + PX4_ERR("Error enabling GNSS Position & Velocity aiding"); + return res; } else { - res = MIP_PX4_ERROR; + // AR and AHRS edge case + PX4_WARN("Could not enable GNSS Position & Velocity aiding"); + return MIP_ACK_OK; } } + else { + // Check to see if sending GNSS position and velocity as an aiding measurement is supported + bool pos_aiding = supportsDescriptor(MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_POS_LLH); + bool vel_aiding = supportsDescriptor(MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_NED); + _ext_pos_vel_aiding = pos_aiding && vel_aiding; + + if (!_ext_pos_vel_aiding) { + PX4_ERR("Sending GNSS pos/vel aiding messages is not supported"); + return MIP_PX4_ERROR; + } + } + + // Prioritizing setting up multi antenna offsets if it is supported + if (supportsDescriptor(MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET)) { + + // Sets up the GNSS aiding source + if (supportsDescriptor(MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL)) { + if (!mip_cmd_result_is_ack(res = mip_filter_write_gnss_source(&_device, (uint8_t)_param_ms_gnss_aid_src_ctrl.get()))) { + PX4_ERR("Could not write the gnss aiding source"); + return res; + } + + // Checks if the gnss aiding source is external + if (_param_ms_gnss_aid_src_ctrl.get() == MIP_FILTER_GNSS_SOURCE_COMMAND_SOURCE_EXT) { + _ext_pos_vel_aiding = true; + + // Sets up the aiding frame for the external source + if (supportsDescriptor(MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG)) { + if (!mip_cmd_result_is_ack(res = mip_aiding_write_frame_config(&_device, 1, + MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER, false, + gnss_antenna_offset1, &rotation_gnss))) { + PX4_ERR("Could not write aiding frame config"); + return res; + } + } + } + + else { + // Sets up the antenna offsets if the source is internal + mip_cmd_result res1 = mip_filter_write_multi_antenna_offset(&_device, 1, gnss_antenna_offset1); + mip_cmd_result res2 = mip_filter_write_multi_antenna_offset(&_device, 2, gnss_antenna_offset2); + + if (!mip_cmd_result_is_ack(res1)) { + PX4_ERR("Could not write multi antenna (1) offsets"); + return res1; + } + + else if (!mip_cmd_result_is_ack(res2)) { + PX4_ERR("Could not write multi antenna (2) offsets"); + return res2; + } + } + } + + else { + PX4_ERR("Does not support GNSS source control"); + return MIP_PX4_ERROR; + } + + // Selectively enables dual antenna heading as an aiding measurement + if (!mip_cmd_result_is_ack(res = enableAidingSource( + MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_GNSS_HEADING, + _param_ms_int_heading_en.get(), + 0, 0, nullptr, mip_aiding_frame_config_command_rotation{0}, + 0, _int_aiding, "dual antenna heading"))) { + return res; + } + } + + // Otherwise sets up the aiding frame + else if (supportsDescriptor(MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG)) { + if (!mip_cmd_result_is_ack(res = mip_aiding_write_frame_config(&_device, 1, + MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER, false, + gnss_antenna_offset1, &rotation_gnss))) { + PX4_ERR("Could not write aiding frame config"); + return res; + } + } + + else { + PX4_WARN("Aiding frames are not supported"); + } + return res; } @@ -736,116 +899,53 @@ mip_cmd_result MicroStrain::configureAidingSources() PX4_DEBUG("Configuring aiding sources"); mip_cmd_result res; - // Selectively turn on the magnetometer aiding source - if (!mip_cmd_result_is_ack(res = configureAidingMeasurement( + // Selectively turn on internal magnetometer as an aiding source + if (!mip_cmd_result_is_ack(res = enableAidingSource( MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_MAGNETOMETER, - _param_ms_int_mag_en.get()))) { - PX4_ERR("Could not configure magnetometer aiding"); + _param_ms_int_mag_en.get(), + 0, 0, nullptr, mip_aiding_frame_config_command_rotation{0}, + 0, _int_aiding, "internal magnetometer"))) { return res; } - // Enables GNSS Position & Velocity as an aiding measurement - res = configureAidingMeasurement(MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_GNSS_POS_VEL, - true); - - if (!mip_cmd_result_is_ack(res)) { - if (res != MIP_NACK_INVALID_PARAM && res != MIP_PX4_ERROR) { - PX4_ERR("Error enabling GNSS Position & Velocity aiding"); - return res; - - } else { - PX4_WARN("Could not enable GNSS Position & Velocity aiding"); - } - - } else { - // Check to see if sending GNSS position and velocity as an aiding measurement is supported - bool pos_aiding = supportsDescriptor(MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_POS_LLH); - bool vel_aiding = supportsDescriptor(MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_VEL_NED); - _ext_pos_vel_aiding = pos_aiding && vel_aiding; - - if (!_ext_pos_vel_aiding) { - PX4_ERR("Sending GNSS pos/vel aiding messages is not supported"); - return MIP_PX4_ERROR; - } - - } - - // Selectively turn on external heading as an aiding measurement - if (!mip_cmd_result_is_ack(res = configureAidingMeasurement( - MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_GNSS_HEADING, - _param_ms_ext_heading_en.get()))) { - PX4_ERR("Could not configure external heading aiding"); + // Selectively turn on external magnetometer as an aiding source + if (!mip_cmd_result_is_ack(res = enableAidingSource( + MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_EXTERNAL_MAGNETOMETER, + _param_ms_ext_mag_en.get(), + 2, MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER, + ext_mag_offset, rotation_ext_mag, + MIP_CMD_DESC_AIDING_MAGNETIC_FIELD, + _ext_mag_aiding, + "external magnetometer"))) { return res; - - } else { - // Check to see if sending external heading as an aiding measurement is supported - _ext_heading_aiding = supportsDescriptor(MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_HEADING_TRUE) - && _param_ms_ext_heading_en.get(); - - if (!_ext_heading_aiding && _param_ms_ext_heading_en.get()) { - PX4_ERR("Sending external heading aiding messages is not supported"); - return MIP_PX4_ERROR; - } - } - // Prioritizing setting up multi antenna offsets if it is supported - if (supportsDescriptor(MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_MULTI_ANTENNA_OFFSET)) { - mip_cmd_result res1 = mip_filter_write_multi_antenna_offset(&_device, 1, gnss_antenna_offset1); - mip_cmd_result res2 = mip_filter_write_multi_antenna_offset(&_device, 2, gnss_antenna_offset2); - - if (!mip_cmd_result_is_ack(res1)) { - PX4_ERR("Could not write multi antenna offsets"); - return res1; - - } - - else if (!mip_cmd_result_is_ack(res2)) { - PX4_ERR("Could not write multi antenna offsets"); - return res2; - - } - - if (supportsDescriptor(MIP_FILTER_CMD_DESC_SET, MIP_CMD_DESC_FILTER_GNSS_SOURCE_CONTROL)) { - if (!mip_cmd_result_is_ack(res = mip_filter_write_gnss_source(&_device, (uint8_t)_param_ms_gnss_aid_src_ctrl.get()))) { - PX4_ERR("Could not write the gnss aiding source"); - return res; - - } - - _ext_pos_vel_aiding = (_param_ms_gnss_aid_src_ctrl.get() == MIP_FILTER_GNSS_SOURCE_COMMAND_SOURCE_EXT); - - - } else { - PX4_ERR("Does not support GNSS source control"); - return MIP_PX4_ERROR; - } - - // Selectively enables dual antenna heading as an aiding measurement - if (!mip_cmd_result_is_ack(res = configureAidingMeasurement( - MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_GNSS_HEADING, - _param_ms_int_heading_en.get()))) { - PX4_ERR("Could not configure dual antenna heading aiding"); - return res; - } - + // Selectively turn on body frame velocity as an aiding source + if (!mip_cmd_result_is_ack(res = enableAidingSource( + MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_VEHICLE_FRAME_VEL, + _param_ms_ext_opt_flow_en.get(), + 3, MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER, + optical_flow_offset, rotation_oflow, + MIP_CMD_DESC_AIDING_VEL_ODOM, + _ext_optical_flow_aiding, + "optical flow"))) { + return res; } - // Otherwise sets up the aiding frame - else if (supportsDescriptor(MIP_AIDING_CMD_DESC_SET, MIP_CMD_DESC_AIDING_FRAME_CONFIG)) { - if (!mip_cmd_result_is_ack(res = mip_aiding_write_frame_config(&_device, 1, - MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER, false, - gnss_antenna_offset1, &rotation))) { - PX4_ERR("Could not write aiding frame config"); - return res; - } + // Selectively turn on external heading as an aiding source + if (!mip_cmd_result_is_ack(res = enableAidingSource( + MIP_FILTER_AIDING_MEASUREMENT_ENABLE_COMMAND_AIDING_SOURCE_EXTERNAL_HEADING, + _param_ms_ext_heading_en.get(), + 4, MIP_AIDING_FRAME_CONFIG_COMMAND_FORMAT_EULER, + ext_heading_offset, rotation_ext_heading, + MIP_CMD_DESC_AIDING_HEADING_TRUE, + _ext_heading_aiding, + "external heading"))) { + return res; } - else { - PX4_WARN("Aiding frames are not supported"); - } - - _ext_aiding = (_ext_pos_vel_aiding || _ext_heading_aiding); + // Configures GNSS Aiding + res = configureGnssAiding(); return res; } @@ -985,8 +1085,8 @@ bool MicroStrain::initializeIns() PX4_DEBUG("Writing SVT"); if (!mip_cmd_result_is_ack(res = mip_3dm_write_sensor_2_vehicle_transform_euler(&_device, - math::radians(rotation.euler[0]), - math::radians(rotation.euler[1]), math::radians(rotation.euler[2])))) { + math::radians(rotation_sens.euler[0]), + math::radians(rotation_sens.euler[1]), math::radians(rotation_sens.euler[2])))) { MS_PX4_ERROR(res, "Could not set sensor-to-vehicle transformation!"); return false; } @@ -1047,29 +1147,23 @@ void MicroStrain::sensorCallback(void *user, const mip_packet *packet, mip::Time accel.updated = true; break; - case MIP_DATA_DESC_SENSOR_GYRO_SCALED: extract_mip_sensor_scaled_gyro_data_from_field(&field, &gyro.sample); gyro.updated = true; break; - case MIP_DATA_DESC_SENSOR_MAG_SCALED: extract_mip_sensor_scaled_mag_data_from_field(&field, &mag.sample); mag.updated = true; break; - case MIP_DATA_DESC_SENSOR_PRESSURE_SCALED: extract_mip_sensor_scaled_pressure_data_from_field(&field, &baro.sample); baro.updated = true; break; - default: break; - - } } @@ -1078,7 +1172,6 @@ void MicroStrain::sensorCallback(void *user, const mip_packet *packet, mip::Time ref->_px4_accel.update(t, accel.sample.scaled_accel[0]*CONSTANTS_ONE_G, accel.sample.scaled_accel[1]*CONSTANTS_ONE_G, accel.sample.scaled_accel[2]*CONSTANTS_ONE_G); - } if (gyro.updated) { @@ -1201,8 +1294,8 @@ void MicroStrain::filterCallback(void *user, const mip_packet *packet, mip::Time gp.alt_valid = is_fullnav && pos_llh.sample.valid_flags; - gp.eph = sqrtf(sq(llh_uncert.sample.north) + sq(llh_uncert.sample.east) + sq(ref->_gps_origin_ep[0])); - gp.epv = sqrtf(sq(llh_uncert.sample.down) + sq(ref->_gps_origin_ep[1])); + gp.eph = sqrtf(sq(llh_uncert.sample.north) + sq(llh_uncert.sample.east)); + gp.epv = llh_uncert.sample.down; // ------- Fields we cannot obtain ------- gp.delta_alt = 0; @@ -1625,9 +1718,6 @@ void MicroStrain::initializeRefPos() _pos_ref.initReference(gps.latitude_deg, gps.longitude_deg, t); _ref_alt = gps.altitude_msl_m; - _gps_origin_ep[0] = gps.eph; - _gps_origin_ep[1] = gps.epv; - PX4_DEBUG("Reference position initialized"); } @@ -1646,7 +1736,7 @@ void MicroStrain::updateGeoidHeight(float geoid_height, float t) } } -void MicroStrain::sendAidingMeasurements() +void MicroStrain::sendGPSAiding() { sensor_gps_s gps{0}; @@ -1667,13 +1757,13 @@ void MicroStrain::sendAidingMeasurements() mip_time t; t.timebase = MIP_TIME_TIMEBASE_TIME_OF_ARRIVAL; - t.reserved = 0x01; + t.reserved = 0x00; t.nanoseconds = 0; // Sends GNSS position and velocity aiding data if they are both supported if (_ext_pos_vel_aiding) { float llh_uncertainty[3] = {gps.eph, gps.eph, gps.epv}; - mip_aiding_llh_pos(&_device, &t, MIP_FILTER_REFERENCE_FRAME_LLH, gps.latitude_deg, + mip_aiding_llh_pos(&_device, &t, 1, gps.latitude_deg, gps.longitude_deg, gps.altitude_ellipsoid_m, llh_uncertainty, MIP_AIDING_LLH_POS_COMMAND_VALID_FLAGS_ALL); @@ -1684,7 +1774,7 @@ void MicroStrain::sendAidingMeasurements() if (gps.vel_ned_valid) { float ned_v[3] = {gps.vel_n_m_s, gps.vel_e_m_s, gps.vel_d_m_s}; float ned_velocity_uncertainty[3] = {sqrtf(gps.s_variance_m_s), sqrtf(gps.s_variance_m_s), sqrtf(gps.s_variance_m_s)}; - mip_aiding_ned_vel(&_device, &t, MIP_FILTER_REFERENCE_FRAME_LLH, ned_v, ned_velocity_uncertainty, + mip_aiding_ned_vel(&_device, &t, 1, ned_v, ned_velocity_uncertainty, MIP_AIDING_NED_VEL_COMMAND_VALID_FLAGS_ALL); } } @@ -1692,7 +1782,60 @@ void MicroStrain::sendAidingMeasurements() // Sends external heading aiding data if they are both supported if (_ext_heading_aiding && PX4_ISFINITE(gps.heading)) { float heading = gps.heading + gps.heading_offset; - mip_aiding_true_heading(&_device, &t, MIP_FILTER_REFERENCE_FRAME_LLH, heading, gps.heading_accuracy, 0xff); + mip_aiding_true_heading(&_device, &t, 4, heading, gps.heading_accuracy, 0xff); + } +} + +void MicroStrain::sendMagAiding() +{ + vehicle_magnetometer_s mag{0}; + + if (!_vehicle_magnetometer_sub.update(&mag)) { + return; + } + + mip_time t; + t.timebase = MIP_TIME_TIMEBASE_TIME_OF_ARRIVAL; + t.reserved = 0x00; + t.nanoseconds = 0; + + float uncert[3] = {ext_mag_uncert, ext_mag_uncert, ext_mag_uncert}; + + mip_aiding_magnetic_field(&_device, &t, 2, mag.magnetometer_ga, uncert, + MIP_AIDING_MAGNETIC_FIELD_COMMAND_VALID_FLAGS_ALL); +} + +void MicroStrain::sendOpticalFlowAiding() +{ + vehicle_optical_flow_vel_s ofv{0}; + + if (!_vehicle_optical_flow_vel_sub.update(&ofv)) { + return; + } + + mip_time t; + t.timebase = MIP_TIME_TIMEBASE_TIME_OF_ARRIVAL; + t.reserved = 0x00; + t.nanoseconds = 0; + + float vel[3] = {ofv.vel_body[0], ofv.vel_body[1], 0}; + float uncert[3] = {opt_flow_uncert, opt_flow_uncert, 0.0}; + + mip_aiding_vehicle_fixed_frame_velocity(&_device, &t, 3, vel, uncert, 0x0003); +} + +void MicroStrain::sendAidingMeasurements() +{ + if (_ext_pos_vel_aiding || _ext_heading_aiding) { + sendGPSAiding(); + } + + if (_ext_mag_aiding) { + sendMagAiding(); + } + + if (_ext_optical_flow_aiding) { + sendOpticalFlowAiding(); } } @@ -1706,7 +1849,6 @@ bool MicroStrain::init() void MicroStrain::Run() { - if (should_exit()) { ScheduleClear(); exit_and_cleanup(); @@ -1742,8 +1884,7 @@ void MicroStrain::Run() //Initializes reference position if there is gps data if (_vehicle_gps_position_sub.updated() && !_pos_ref.isInitialized()) {initializeRefPos();} - // Sends aiding data only if external aiding was set up - if (_ext_aiding) {sendAidingMeasurements();} + sendAidingMeasurements(); perf_end(_loop_perf); } diff --git a/src/drivers/ins/microstrain/MicroStrain.hpp b/src/drivers/ins/microstrain/MicroStrain.hpp index af4c707d82..3cba872793 100755 --- a/src/drivers/ins/microstrain/MicroStrain.hpp +++ b/src/drivers/ins/microstrain/MicroStrain.hpp @@ -62,6 +62,8 @@ #include #include #include +#include +#include #include #include @@ -145,6 +147,18 @@ private: mip_cmd_result configureAidingMeasurement(uint16_t aiding_source, bool enable); + mip_cmd_result enableAidingSource(uint16_t source, + bool enabled, + uint8_t frame_id, + uint8_t frame_format, + const float offset[3], + mip_aiding_frame_config_command_rotation rotation, + uint16_t aiding_cmd_desc, + bool &aiding_flag, + const char *name); + + mip_cmd_result configureGnssAiding(); + mip_cmd_result configureAidingSources(); mip_cmd_result writeFilterInitConfig(); @@ -153,6 +167,12 @@ private: void updateGeoidHeight(float geoid_height, float t); + void sendGPSAiding(); + + void sendMagAiding(); + + void sendOpticalFlowAiding(); + void sendAidingMeasurements(); bool init(); @@ -170,11 +190,23 @@ private: bool _ext_pos_vel_aiding{false}; bool _ext_heading_aiding{false}; - bool _ext_aiding{false}; + bool _ext_mag_aiding{false}; + bool _ext_optical_flow_aiding{false}; + bool _int_aiding{false}; float gnss_antenna_offset1[3] = {0}; float gnss_antenna_offset2[3] = {0}; - mip_aiding_frame_config_command_rotation rotation = {0}; + float ext_mag_offset[3] = {0}; + float optical_flow_offset[3] = {0}; + float ext_heading_offset[3] = {0}; + mip_aiding_frame_config_command_rotation rotation_sens = {0}; + mip_aiding_frame_config_command_rotation rotation_gnss = {0}; + mip_aiding_frame_config_command_rotation rotation_ext_mag = {0}; + mip_aiding_frame_config_command_rotation rotation_oflow = {0}; + mip_aiding_frame_config_command_rotation rotation_ext_heading = {0}; + + float ext_mag_uncert = 0.0; + float opt_flow_uncert = 0.0; AlphaFilter _geoid_height_lpf; uint64_t _last_geoid_height_update_us{0}; @@ -182,7 +214,6 @@ private: MapProjection _pos_ref{}; double _ref_alt = 0; - float _gps_origin_ep[2] = {0}; template struct SensorSample { @@ -217,8 +248,10 @@ private: (ParamInt) _param_ms_alignment, (ParamInt) _param_ms_gnss_aid_src_ctrl, (ParamInt) _param_ms_int_mag_en, + (ParamInt) _param_ms_ext_mag_en, (ParamInt) _param_ms_int_heading_en, (ParamInt) _param_ms_ext_heading_en, + (ParamInt) _param_ms_ext_opt_flow_en, (ParamInt) _param_ms_svt_en, (ParamInt) _param_ms_accel_range_setting, (ParamInt) _param_ms_gyro_range_setting, @@ -230,7 +263,16 @@ private: (ParamFloat) _param_ms_gnss_offset2_z, (ParamFloat) _param_ms_sensor_roll, (ParamFloat) _param_ms_sensor_pitch, - (ParamFloat) _param_ms_sensor_yaw + (ParamFloat) _param_ms_sensor_yaw, + (ParamFloat) _param_ms_emag_roll, + (ParamFloat) _param_ms_emag_pitch, + (ParamFloat) _param_ms_emag_yaw, + (ParamFloat) _param_ms_oflow_offset_x, + (ParamFloat) _param_ms_oflow_offset_y, + (ParamFloat) _param_ms_oflow_offset_z, + (ParamFloat) _param_ms_ehead_yaw, + (ParamFloat) _param_ms_emag_uncert, + (ParamFloat) _param_ms_oflow_uncert ) // Sensor types needed for message creation / updating / publishing @@ -256,4 +298,6 @@ private: // Subscriptions uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; // subscription limited to 1 Hz updates uORB::Subscription _vehicle_gps_position_sub{ORB_ID(vehicle_gps_position)}; + uORB::Subscription _vehicle_magnetometer_sub{ORB_ID(vehicle_magnetometer)}; + uORB::Subscription _vehicle_optical_flow_vel_sub{ORB_ID(vehicle_optical_flow_vel)}; }; diff --git a/src/drivers/ins/microstrain/module.yaml b/src/drivers/ins/microstrain/module.yaml index 6c91ee0d40..786db17094 100644 --- a/src/drivers/ins/microstrain/module.yaml +++ b/src/drivers/ins/microstrain/module.yaml @@ -1,310 +1,391 @@ module_name: MICROSTRAIN +serial_config: + - command: sleep 1; microstrain start -d ${SERIAL_DEV} + port_config_param: + name: SENS_MS_CFG + group: Sensors + parameters: - group: Sensors definitions: MS_MODE: description: - short: Toggles using the device as the primary EKF + short: MicroStrain device mode long: | - Setting to 1 will publish data from the device to the vehicle topics (global_position, attitude, local_position, odometry), estimator_status and sensor_selection - Setting to 0 will publish data from the device to the external_ins topics (global position, attitude, local position) - Restart Required - - This parameter is specific to the MicroStrain driver. - type: int32 - default: 1 + Sensor mode publishes raw IMU data to be used by EKF2. INS data from the device is published to the external INS topics. + INS mode publishes the INS data to the vehicle topics to be used for navigation. + type: enum + values: + 0: Sensor Mode + 1: INS Mode + reboot_required: true + default: 0 MS_IMU_RATE_HZ: description: - short: IMU Data Rate + short: MicroStrain IMU data rate long: | - IMU (Accelerometer and Gyroscope) data rate - The INS driver will be scheduled at a rate 2*MS_IMU_RATE_HZ - Max Limit: 1000 - 0 - Disable IMU datastream - The max limit should be divisible by the rate - eg: 1000 % MS_IMU_RATE_HZ = 0 - Restart required - - This parameter is specific to the MicroStrain driver. + Accelerometer and Gyroscope data rate (Hz). + Valid rates: 0 or any factor of 1000. type: int32 + max: 1000 + min: 0 + reboot_required: true default: 500 MS_MAG_RATE_HZ: description: - short: Magnetometer Data Rate + short: MicroStrain magnetometer data rate long: | - Magnetometer data rate - Max Limit: 1000 - 0 - Disable magnetometer datastream - The max limit should be divisible by the rate - eg: 1000 % MS_MAG_RATE_HZ = 0 - Restart required - - This parameter is specific to the MicroStrain driver. + Magnetometer data rate (Hz). + Valid rates: 0 or any factor of 1000. type: int32 + max: 1000 + min: 0 + reboot_required: true default: 50 MS_BARO_RATE_HZ: description: - short: Barometer data rate + short: MicroStrain barometer data rate long: | - Barometer data rate - Max Limit: 1000 - 0 - Disable barometer datastream - The max limit should be divisible by the rate - eg: 1000 % MS_BARO_RATE_HZ = 0 - Restart required - - This parameter is specific to the MicroStrain driver. + Barometer data rate (Hz). + Valid rates: 0 or any factor of 1000. type: int32 + max: 1000 + min: 0 + reboot_required: true default: 50 MS_FILT_RATE_HZ: description: - short: EKF data Rate + short: MicroStrain EKF data rate long: | - EKF data rate - Max Limit: 1000 - 0 - Disable EKF datastream - The max limit should be divisible by the rate - eg: 1000 % MS_FILT_RATE_HZ = 0 - Restart required - - This parameter is specific to the MicroStrain driver. + The rate at which the INS data is published (Hz). + Valid rates: 0 or any factor of 1000. type: int32 + max: 1000 + min: 0 + reboot_required: true default: 250 MS_GNSS_RATE_HZ: description: - short: GNSS data Rate + short: MicroStrain GNSS data rate long: | - GNSS receiver 1 and 2 data rate - Max Limit: 5 - The max limit should be divisible by the rate - 0 - Disable GNSS datastream - eg: 5 % MS_GNSS_RATE_HZ = 0 - Restart required - - This parameter is specific to the MicroStrain driver. + GNSS receiver 1 and 2 data rate (Hz). + Valid rates: 0, 1 or 5. type: int32 + max: 5 + min: 0 + reboot_required: true default: 5 MS_ALIGNMENT: description: - short: Alignment type + short: MicroStrain heading alignment type long: | - Select the source of heading alignment - This is a bitfield, you can use more than 1 source - Bit 0 - Dual-antenna GNSS - Bit 1 - GNSS kinematic (requires motion, e.g. a GNSS velocity) - Bit 2 - Magnetometer - Bit 3 - External Heading (first valid external heading will be used to initialize the filter) - Restart required - - This parameter is specific to the MicroStrain driver. - type: int32 + Select the source of heading alignment. + type: bitmask + bit: + 0: Dual-antenna GNSS + 1: GNSS kinematic (requires motion, e.g. a GNSS velocity) + 2: Magnetometer + 3: External Heading (first valid external heading will be used to initialize the filter) + max: 15 + min: 1 + reboot_required: true default: 2 MS_GNSS_AID_SRC: description: - short: GNSS aiding source control + short: MicroStrain GNSS aiding source control long: | - Select the source of gnss aiding (GNSS/INS) - 1 = All internal receivers, - 2 = External GNSS messages, - 3 = GNSS receiver 1 only - 4 = GNSS receiver 2 only - Restart required - - This parameter is specific to the MicroStrain driver. - type: int32 + Select the source of gnss aiding (GNSS/INS). + type: enum + values: + 1: All internal receivers + 2: External GNSS messages + 3: GNSS receiver 1 only + 4: GNSS receiver 2 only + reboot_required: true default: 1 MS_INT_MAG_EN: description: - short: Toggles internal magnetometer aiding in the device filter + short: Enable MicroStrain internal magnetometer long: | - 0 = Disabled, - 1 = Enabled - Restart required + Toggles internal magnetometer aiding in the device filter. + type: enum + values: + 0: Disabled + 1: Enabled + reboot_required: true + default: 0 - This parameter is specific to the MicroStrain driver. - type: int32 + MS_EXT_MAG_EN: + description: + short: Enable MicroStrain external magnetometer aiding + long: | + Toggles external magnetometer aiding in the device filter. + type: enum + values: + 0: Disabled + 1: Enabled + reboot_required: true default: 0 MS_INT_HEAD_EN: description: - short: Toggles internal heading as an aiding measurement + short: Enable MicroStrain internal heading aiding long: | - 0 = Disabled, - 1 = Enabled + Toggles internal heading as an aiding measurement. If dual antennas are supported (CV7-GNSS/INS). The filter will be configured to use dual antenna heading as an aiding measurement. - Restart required - - This parameter is specific to the MicroStrain driver. - type: int32 + type: enum + values: + 0: Disabled + 1: Enabled + reboot_required: true default: 0 MS_EXT_HEAD_EN: description: - short: Toggles external heading as an aiding measurement + short: Enable MicroStrain external heading aiding long: | - 0 = Disabled, - 1 = Enabled + Toggles external heading as an aiding measurement. If enabled, the filter will be configured to accept external heading as an aiding meaurement. - Restart required + type: enum + values: + 0: Disabled + 1: Enabled + reboot_required: true + default: 0 - This parameter is specific to the MicroStrain driver. - type: int32 + MS_OPT_FLOW_EN: + description: + short: Enable MicroStrain optical flow aiding + long: | + Toggles body frame velocity as an aiding measurement. + The driver uses the body frame velocity from the optical flow sensor as the aiding measurements. + type: enum + values: + 0: Disabled + 1: Enabled + reboot_required: true default: 0 MS_SVT_EN: description: - short: Enables sensor to vehicle transform + short: Enables Microstrain sensor to vehicle transform long: | - 0 = Disabled, - 1 = Enabled If the sensor has a different orientation with respect to the vehicle. This will enable a transform to correct itself. - The transform is described by MS_SENSOR_ROLL, MS_SENSOR_PITCH, MS_SENSOR_YAW - Restart required - - This parameter is specific to the MicroStrain driver. - type: int32 + The transform is described by MS_SENSOR_ROLL, MS_SENSOR_PITCH, MS_SENSOR_YAW. + type: enum + values: + 0: Disabled + 1: Enabled + reboot_required: true default: 0 MS_ACCEL_RANGE: description: - short: Sets the range of the accelerometer + short: MicroStrain accelerometer range long: | - -1 = Will not be configured, and will use the device default range, - Each adjustable range has a corresponding integer setting. Refer to the device's User Manual to check the available adjustment ranges. - https://www.hbkworld.com/en/products/transducers/inertial-sensors#!ref_microstrain.com - Restart required - - This parameter is specific to the MicroStrain driver. + -1 = Will not be configured, and will use the device default range. + Ranges vary by device and map to integer codes. Check the device's [User Manual](https://www.hbkworld.com/en/products/transducers/inertial-sensors#!ref_microstrain.com) for supported ranges and set the corresponding integer. type: int32 + reboot_required: true default: -1 MS_GYRO_RANGE: description: - short: Sets the range of the gyro + short: MicroStrain gyroscope range long: | - -1 = Will not be configured, and will use the device default range, - Each adjustable range has a corresponding integer setting. Refer to the device's User Manual to check the available adjustment ranges. - https://www.hbkworld.com/en/products/transducers/inertial-sensors#!ref_microstrain.com - Restart required - - This parameter is specific to the MicroStrain driver. + -1 = Will not be configured, and will use the device default range. + Ranges vary by device and map to integer codes. Check the device's [User Manual](https://www.hbkworld.com/en/products/transducers/inertial-sensors#!ref_microstrain.com) for supported ranges and set the corresponding integer. type: int32 + reboot_required: true default: -1 MS_GNSS_OFF1_X: description: - short: GNSS lever arm offset 1 (X) + short: MicroStrain GNSS lever arm offset 1 (X) long: | - Lever arm offset (m) in the X direction for the external GNSS receiver - In the case of a dual antenna setup, this is antenna 1 - Restart required - - This parameter is specific to the MicroStrain driver. + Lever arm offset (m) in the X direction for the external GNSS receiver. + In the case of a dual antenna setup, this is antenna 1. type: float + reboot_required: true default: 0.0 MS_GNSS_OFF1_Y: description: - short: GNSS lever arm offset 1 (Y) + short: MicroStrain GNSS lever arm offset 1 (Y) long: | - Lever arm offset (m) in the Y direction for the external GNSS receiver - In the case of a dual antenna setup, this is antenna 1 - Restart required - - This parameter is specific to the MicroStrain driver. + Lever arm offset (m) in the Y direction for the external GNSS receiver. + In the case of a dual antenna setup, this is antenna 1. type: float + reboot_required: true default: 0.0 MS_GNSS_OFF1_Z: description: - short: GNSS lever arm offset 1 (Z) + short: MicroStrain GNSS lever arm offset 1 (Z) long: | - Lever arm offset (m) in the Z direction for the external GNSS receiver - In the case of a dual antenna setup, this is antenna 1 - Restart required - - This parameter is specific to the MicroStrain driver. + Lever arm offset (m) in the Z direction for the external GNSS receiver. + In the case of a dual antenna setup, this is antenna 1. type: float + reboot_required: true default: 0.0 MS_GNSS_OFF2_X: description: - short: GNSS lever arm offset 2 (X) + short: MicroStrain GNSS lever arm offset 2 (X) long: | Lever arm offset (m) in the X direction for antenna 2 - This will only be used if the device supports a dual antenna setup - Restart required - - This parameter is specific to the MicroStrain driver. + This will only be used if the device supports a dual antenna setup. type: float + reboot_required: true default: 0.0 MS_GNSS_OFF2_Y: description: - short: GNSS lever arm offset 2 (Y) + short: MicroStrain GNSS lever arm offset 2 (Y) long: | - Lever arm offset (m) in the Y direction for antenna 2 - This will only be used if the device supports a dual antenna setup - Restart required - - This parameter is specific to the MicroStrain driver. + Lever arm offset (m) in the Y direction for antenna 2. + This will only be used if the device supports a dual antenna setup. type: float + reboot_required: true default: 0.0 MS_GNSS_OFF2_Z: description: - short: GNSS lever arm offset 2 (Z) + short: MicroStrain GNSS lever arm offset 2 (Z) long: | - Lever arm offset (m) in the X direction for antenna 2 - This will only be used if the device supports a dual antenna setup - Restart required - - This parameter is specific to the MicroStrain driver. + Lever arm offset (m) in the X direction for antenna 2. + This will only be used if the device supports a dual antenna setup. type: float + reboot_required: true default: 0.0 MS_SENSOR_ROLL: description: - short: Sensor to Vehicle Transform (Roll) + short: MicroStrain Sensor to vehicle transform (Roll) long: | - The orientation of the device (Radians) with respect to the vehicle frame around the x axis - Requires MS_SVT_EN to be enabled to be used - Restart required - - This parameter is specific to the MicroStrain driver. + The orientation of the device (Radians) with respect to the vehicle frame around the x axis. + Requires MS_SVT_EN to be enabled to be used. type: float + reboot_required: true default: 0.0 MS_SENSOR_PTCH: description: - short: Sensor to Vehicle Transform (Pitch) + short: MicroStrain Sensor to Vehicle Transform (Pitch) long: | - The orientation of the device (Radians) with respect to the vehicle frame around the y axis - Requires MS_SVT_EN to be enabled to be used - Restart required - - This parameter is specific to the MicroStrain driver. + The orientation of the device (Radians) with respect to the vehicle frame around the y axis. + Requires MS_SVT_EN to be enabled to be used. type: float + reboot_required: true default: 0.0 MS_SENSOR_YAW: description: - short: Sensor to Vehicle Transform (Yaw) + short: MicroStrain Sensor to Vehicle Transform (Yaw) long: | - The orientation of the device (Radians) with respect to the vehicle frame around the z axis - Requires MS_SVT_EN to be enabled to be used - Restart required - - This parameter is specific to the MicroStrain driver. + The orientation of the device (Radians) with respect to the vehicle frame around the z axis. + Requires MS_SVT_EN to be enabled to be used. type: float + reboot_required: true default: 0.0 + + MS_EMAG_ROLL: + description: + short: MicroStrain External Magnetometer Orientation (Roll) + long: | + The orientation of the device (Radians) with respect to the vehicle frame around the x axis. + Requires MS_EXT_MAG_EN to be enabled to be used. + type: float + reboot_required: true + default: 0.0 + + MS_EMAG_PTCH: + description: + short: MicroStrain External Magnetometer Orientation (Pitch) + long: | + The orientation of the device (Radians) with respect to the vehicle frame around the y axis. + Requires MS_EXT_MAG_EN to be enabled to be used. + type: float + reboot_required: true + default: 0.0 + + MS_EMAG_YAW: + description: + short: MicroStrain External Magnetometer Orientation (Yaw) + long: | + The orientation of the device (Radians) with respect to the vehicle frame around the z axis. + Requires MS_EXT_MAG_EN to be enabled to be used. + type: float + reboot_required: true + default: 0.0 + + MS_OFLW_OFF_X: + description: + short: MicroStrain optical flow offset (X) + long: | + Offset (m) in the X direction if an Optical Flow sensor is connected. + Requires MS_OPT_FLOW_EN to be enabled to be used. + type: float + reboot_required: true + default: 0.0 + + MS_OFLW_OFF_Y: + description: + short: MicroStrain optical flow offset (Y) + long: | + Offset (m) in the Y direction if an Optical Flow sensor is connected. + Requires MS_OPT_FLOW_EN to be enabled to be used. + type: float + reboot_required: true + default: 0.0 + + MS_OFLW_OFF_Z: + description: + short: MicroStrain optical flow offset (Z) + long: | + Offset (m) in the Z direction if an Optical Flow sensor is connected. + Requires MS_OPT_FLOW_EN to be enabled to be used. + type: float + reboot_required: true + default: 0.0 + + MS_EHEAD_YAW: + description: + short: MicroStrain External Heading Orientation (Yaw) + long: | + The orientation of the device (Radians) with respect to the vehicle frame around the z axis. + Requires MS_EXT_HEAD_EN to be enabled to be used. + type: float + reboot_required: true + default: 0.0 + + MS_EMAG_UNCERT: + description: + short: MicroStrain external magnetometer uncertainty + long: | + The 1-sigma uncertainty (in Gauss) for all axes, which will remain constant across all aiding measurements. + Requires MS_EXT_MAG_EN to be enabled to be used. + type: float + reboot_required: true + default: 0.1 + + MS_OFLW_UNCERT: + description: + short: MicroStrain optical flow uncertainty + long: | + The 1-sigma uncertainty (in m/s) for the X and Y axes, which will remain constant across all aiding measurements. + The Z axis is not used for aiding. + Requires MS_OPT_FLOW_EN to be enabled to be used. + type: float + reboot_required: true + default: 0.1 From 66436a980c2a75754a541bdc5405731a80784ce6 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Sun, 5 Oct 2025 15:24:37 +1100 Subject: [PATCH 148/812] New Crowdin translations - ko (#25706) Co-authored-by: Crowdin Bot --- docs/ko/config/_autotune.md | 68 +++++++++++++++++++++---------- docs/ko/frames_rover/index.md | 3 +- docs/ko/releases/main.md | 6 ++- docs/ko/sim_gazebo_gz/index.md | 33 +++++++-------- docs/ko/sim_gazebo_gz/vehicles.md | 12 +++++- 5 files changed, 82 insertions(+), 40 deletions(-) diff --git a/docs/ko/config/_autotune.md b/docs/ko/config/_autotune.md index a6eab14e0e..5c35b38bfe 100644 --- a/docs/ko/config/_autotune.md +++ b/docs/ko/config/_autotune.md @@ -43,13 +43,13 @@ To make sure the vehicle is stable enough for auto-tuning: 2. Take off and
hover at 1m above ground in [Altitude mode](../flight_modes_mc/altitude.md) or [Stabilized mode](../flight_modes_mc/manual_stabilized.md)
fly at cruise speed in [Position mode](../flight_modes_fw/position.md) or [Altitude mode](../flight_modes_fw/altitude.md)
. 3. Use the RC transmitter roll stick to perform the following maneuver, tilting the vehicle just a few degrees: _roll left > roll right > center_ (The whole maneuver should take about 3 seconds). - 기체는 2번의 진동 이내에서 안정화되어야 합니다. + 기체는 2번의 진동 이내에서 안정화되어야 합니다. 4. 각각의 시도에서 더 큰 진폭으로 기울이면서 기동을 반복합니다. - 기체가 ~20도에서 2번의 진동 내에서 안정화될 수 있으면 다음 단계로 이동합니다. + 기체가 ~20도에서 2번의 진동 내에서 안정화될 수 있으면 다음 단계로 이동합니다. 5. 피치 축에서 동일한 동작을 반복합니다. - As above, start with small angles and confirm that the vehicle can stabilise itself within 2 oscillations before increasing the tilt. + As above, start with small angles and confirm that the vehicle can stabilise itself within 2 oscillations before increasing the tilt. If the drone can stabilize itself within 2 oscillations it is ready for the [auto-tuning procedure](#auto-tuning-procedure). @@ -72,41 +72,56 @@ The test steps are: 1. Perform the [pre-tuning test](#pre-tuning-test). 2. Takeoff using RC control
in [Altitude mode](../flight_modes_mc/altitude.md). - Hover the vehicle at a safe distance and at a few meters above ground (between 4 and 20m).
- Once flying at cruise speed, activate [Hold mode](../flight_modes_fw/hold.md). - This will guide the plane to fly in circle at constant altitude and speed.
+ Hover the vehicle at a safe distance and at a few meters above ground (between 4 and 20m).
3. Enable autotune. -
-

TIP

+
+

TIP

- If an [Enable/Disable Autotune Switch](#enable-disable-autotune-switch) is configured you can just toggle the switch to the "enabled" position. + If an [Enable/Disable Autotune Switch](#enable-disable-autotune-switch) is configured you can just toggle the switch to the "enabled" position. -
+
- 1. In QGroundControl, open the menu **Vehicle setup > PID Tuning**: + 1. In QGroundControl, open the menu **Vehicle setup > PID Tuning**: - ![Tuning Setup > Autotune Enabled](../../assets/qgc/setup/autotune/autotune.png) + ![Tuning Setup > Autotune Enabled](../../assets/qgc/setup/autotune/autotune.png) - 2. Select either the _Rate Controller_ or _Attitude Controller_ tabs. + 2. Select either the _Rate Controller_ or _Attitude Controller_ tabs. - 3. Ensure that the **Autotune enabled** button is enabled (this will display the **Autotune** button and remove the manual tuning selectors). + 3. Ensure that the **Autotune enabled** button is enabled (this will display the **Autotune** button and remove the manual tuning selectors). - 4. Read the warning popup and click on **OK** to start tuning. - -4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. - The progress is shown in the progress bar, next to the _Autotune_ button. + 4. Read the warning popup and click on **OK** to start tuning.
+4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. + The progress is shown in the progress bar, next to the _Autotune_ button. + +
+ +4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. + The progress is shown in the progress bar, next to the _Autotune_ button. + +
+
+ 5. Manually land and disarm to apply the new tuning parameters. - Takeoff carefully and manually test that the vehicle is stable. + Takeoff carefully and manually test that the vehicle is stable.
5. The tuning will be immediately/automatically be applied and tested in flight (by default). - PX4 will then run a 4 second test and revert the new tuning if a problem is detected. + PX4 will then run a 4 second test and revert the new tuning if a problem is detected. + +The figure below shows how steps 4 and 5 might look in flight on the pitch axis. +The pitch rate gradually increases up until it reaches the target. +This amplitude is then held while the signal frequency is increased. +You can then see how the tuned system is able to follow the setpoint in the test signal. + +
@@ -174,9 +189,20 @@ Fast oscillations (more than 1 oscillation per second): this is because the gain ### 자동 튜닝 실패 +
+ If the drone was not moving enough during auto-tuning, the system identification algorithm might have issues to find the correct coefficients. -Increase the
[MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_SYSID_AMP)
[FW_AT_SYSID_AMP](../advanced_config/parameter_reference.md#FW_AT_SYSID_AMP)
parameter by steps of 1 and trigger the auto-tune again. +Increase the [MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_SYSID_AMP) parameter by steps of 1 and trigger the auto-tune again. + +
+
+ +By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification. The target rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. + +If the signal-to-noise ratio of the vehicle is low, the system identification algorithm might have issues finding the correct coefficients. Ensure that there is no excessive noise and/or platform vibration. + +
### The drone oscillates after auto-tuning diff --git a/docs/ko/frames_rover/index.md b/docs/ko/frames_rover/index.md index c97c33b8b9..7cf786c054 100644 --- a/docs/ko/frames_rover/index.md +++ b/docs/ko/frames_rover/index.md @@ -64,9 +64,10 @@ Each wheel is driven by its own motor, and by controlling the speed and directio ## 시뮬레이션 -[Gazebo](../sim_gazebo_gz/index.md) provides simulations for ackermann and differential rovers: +PX4 provides synthetic simulation models for [Gazebo](../sim_gazebo_gz/index.md) of all three rover types to test the software and validate changes and new features: - [Ackermann rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) - [Differential rover](../sim_gazebo_gz/vehicles.md#differential-rover) +- [Mecanum rover](../sim_gazebo_gz/vehicles.md#mecanum-rover) ![Rover gazebo simulation](../../assets/airframes/rover/rover_simulation.png) diff --git a/docs/ko/releases/main.md b/docs/ko/releases/main.md index f77ccd22fa..e041703029 100644 --- a/docs/ko/releases/main.md +++ b/docs/ko/releases/main.md @@ -58,7 +58,10 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### 시뮬레이션 -- TBD +- Overhaul rover simulation: + - Add synthetic differential rover model: [PX4-gazebo-models#107](https://github.com/PX4/PX4-gazebo-models/pull/107) + - Add synthetic mecanum rover model: [PX4-gazebo-models#113](https://github.com/PX4/PX4-gazebo-models/pull/113) + - Update synthetic ackermann rover model: [PX4-gazebo-models#117](https://github.com/PX4/PX4-gazebo-models/pull/117) ### Ethernet @@ -91,6 +94,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). - Removed deprecated rover module ([PX4-Autopilot#25054](https://github.com/PX4/PX4-Autopilot/pull/25054)). - Add support for [Apps & API](../flight_modes_rover/api.md) ([PX4-Autopilot#25074](https://github.com/PX4/PX4-Autopilot/pull/25074), [PX4-ROS2-Interface-Lib#140](https://github.com/Auterion/px4-ros2-interface-lib/pull/140)). +- Update [rover simulation](../frames_rover/index.md#simulation) ([PX4-Autopilot#25644](https://github.com/PX4/PX4-Autopilot/pull/25644)) (see [Simulation](#simulation) release note for details). ### ROS 2 diff --git a/docs/ko/sim_gazebo_gz/index.md b/docs/ko/sim_gazebo_gz/index.md index 2ef2f45036..d93011de4c 100644 --- a/docs/ko/sim_gazebo_gz/index.md +++ b/docs/ko/sim_gazebo_gz/index.md @@ -50,22 +50,23 @@ This runs both the PX4 SITL instance and the Gazebo client. The supported vehicles and `make` commands are listed below. Note that all gazebo make targets have the prefix `gz_`. -| Vehicle | 통신 | `PX4_SYS_AUTOSTART` | -| ------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ----------------------------------- | ------------------- | -| [Quadrotor (x500)](../sim_gazebo_gz/vehicles.md#x500-quadrotor) | `make px4_sitl gz_x500` | 4001 | -| [X500 Quadrotor with Depth Camera (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-depth-camera-front-facing) | `make px4_sitl gz_x500_depth` | 4002 | -| [Quadrotor(x500) with Vision Odometry](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-visual-odometry) | `make px4_sitl gz_x500_vision` | 4005 | -| [Quadrotor(x500) with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing) | `make px4_sitl gz_x500_lidar_down` | 4016 | -| [Quadrotor(x500) with 2D LIDAR](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar) | `make px4_sitl gz_x500_lidar_2d` | 4013 | -| [Quadrotor(x500) with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing) | `make px4_sitl gz_x500_lidar_front` | 4017 | -| [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) | `make px4_sitl gz_x500_gimbal` | 4019 | -| [VTOL](../sim_gazebo_gz/vehicles.md#standard-vtol) | `make px4_sitl gz_standard_vtol` | 4004 | -| [Plane](../sim_gazebo_gz/vehicles.md#standard-plane) | `make px4_sitl gz_rc_cessna` | 4003 | -| [Advanced Plane](../sim_gazebo_gz/vehicles.md#advanced-plane) | `make px4_sitl gz_advanced_plane` | 4008 | -| [Differential Rover](../sim_gazebo_gz/vehicles.md#differential-rover) | `make px4_sitl gz_r1_rover` | 4009 | -| [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) | `make px4_sitl gz_rover_ackermann` | 4012 | -| [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) | `make px4_sitl gz_quadtailsitter` | 4018 | -| [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) | `make px4_sitl gz_tiltrotor` | 4020 | +| Vehicle | 통신 | `PX4_SYS_AUTOSTART` | +| ------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------- | ------------------- | +| [Quadrotor (x500)](../sim_gazebo_gz/vehicles.md#x500-quadrotor) | `make px4_sitl gz_x500` | 4001 | +| [X500 Quadrotor with Depth Camera (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-depth-camera-front-facing) | `make px4_sitl gz_x500_depth` | 4002 | +| [Quadrotor(x500) with Vision Odometry](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-visual-odometry) | `make px4_sitl gz_x500_vision` | 4005 | +| [Quadrotor(x500) with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing) | `make px4_sitl gz_x500_lidar_down` | 4016 | +| [Quadrotor(x500) with 2D LIDAR](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar) | `make px4_sitl gz_x500_lidar_2d` | 4013 | +| [Quadrotor(x500) with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing) | `make px4_sitl gz_x500_lidar_front` | 4017 | +| [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) | `make px4_sitl gz_x500_gimbal` | 4019 | +| [VTOL](../sim_gazebo_gz/vehicles.md#standard-vtol) | `make px4_sitl gz_standard_vtol` | 4004 | +| [Plane](../sim_gazebo_gz/vehicles.md#standard-plane) | `make px4_sitl gz_rc_cessna` | 4003 | +| [Advanced Plane](../sim_gazebo_gz/vehicles.md#advanced-plane) | `make px4_sitl gz_advanced_plane` | 4008 | +| [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) | `make px4_sitl gz_quadtailsitter` | 4018 | +| [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) | `make px4_sitl gz_tiltrotor` | 4020 | +| [Differential Rover](../sim_gazebo_gz/vehicles.md#differential-rover) | `make px4_sitl gz_rover_differential` | 50000 | +| [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) | `make px4_sitl gz_rover_ackermann` | 51000 | +| [Mecanum Rover](../sim_gazebo_gz/vehicles.md#mecanum-rover) | `make px4_sitl gz_rover_mecanum` | 52000 | All [vehicle models](../sim_gazebo_gz/vehicles.md) (and [worlds](#specify-world)) are included as a submodule from the [Gazebo Models Repository](../sim_gazebo_gz/gazebo_models.md) repository. diff --git a/docs/ko/sim_gazebo_gz/vehicles.md b/docs/ko/sim_gazebo_gz/vehicles.md index 5638f9b63f..6c93b94d49 100644 --- a/docs/ko/sim_gazebo_gz/vehicles.md +++ b/docs/ko/sim_gazebo_gz/vehicles.md @@ -185,7 +185,7 @@ make px4_sitl gz_tiltrotor [Differential Rover](../frames_rover/index.md#differential) uses the [rover world](../sim_gazebo_gz/worlds.md#rover) by default. ```sh -make px4_sitl gz_r1_rover +make px4_sitl gz_rover_differential ``` ![Differential Rover in Gazebo](../../assets/simulation/gazebo/vehicles/rover_differential.png) @@ -199,3 +199,13 @@ make px4_sitl gz_rover_ackermann ``` ![Ackermann Rover in Gazebo](../../assets/simulation/gazebo/vehicles/rover_ackermann.png) + +### Mecanum Rover + +[Mecanum Rover](../frames_rover/index.md#mecanum) uses the [rover world](../sim_gazebo_gz/worlds.md#rover) by default. + +```sh +make px4_sitl gz_rover_mecanum +``` + +![Mecanum Rover in Gazebo](../../assets/simulation/gazebo/vehicles/rover_mecanum.png) From 39837d44b1cb0e11dc5ea1c511eb640966ca823a Mon Sep 17 00:00:00 2001 From: Jacopo Panerati Date: Mon, 6 Oct 2025 03:03:09 -0400 Subject: [PATCH 149/812] upload_log.py: add server as an argument (#25702) --- Tools/upload_log.py | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/Tools/upload_log.py b/Tools/upload_log.py index a13f1b14b0..453c1538ea 100755 --- a/Tools/upload_log.py +++ b/Tools/upload_log.py @@ -25,10 +25,6 @@ except ImportError as e: sys.exit(1) -SERVER = 'https://logs.px4.io' -#SERVER = 'http://localhost:5006' # for testing locally -UPLOAD_URL = SERVER+'/upload' - quiet = False def ask_value(text, default=None): @@ -60,6 +56,8 @@ def main(): parser = ArgumentParser(description=__doc__) parser.add_argument('--quiet', '-q', dest='quiet', action='store_true', default=False, help='Quiet mode: do not ask for values which were not provided as parameters') + parser.add_argument('--server', dest='server', type=str, default='https://logs.px4.io', + help='Server URL (default: https://logs.px4.io), use http://localhost:5006 for testing locally') parser.add_argument("--description", dest="description", type=str, help="Log description", default=None) parser.add_argument("--feedback", dest="feedback", type=str, @@ -99,6 +97,9 @@ def main(): else: email = args.email + server = args.server + upload_url = server + '/upload' + payload = {'type': args.type, 'description': description, 'feedback': feedback, 'email': email, 'source': args.source} @@ -113,13 +114,13 @@ def main(): print('Uploading '+file_name+'...') with open(file_name, 'rb') as f: - r = requests.post(UPLOAD_URL, data=payload, files={'filearg': f}, + r = requests.post(upload_url, data=payload, files={'filearg': f}, allow_redirects=False) if r.status_code == 302: # redirect if 'Location' in r.headers: plot_url = r.headers['Location'] if len(plot_url) > 0 and plot_url[0] == '/': - plot_url = SERVER + plot_url + plot_url = server + plot_url print('URL: '+plot_url) From a4439972644af2391fb5c18e7b1deeebcb08a4b8 Mon Sep 17 00:00:00 2001 From: annoybot Date: Mon, 6 Oct 2025 03:11:54 -0400 Subject: [PATCH 150/812] docs: add a new rust ULOG parser to the list of known parsers --- docs/en/dev_log/ulog_file_format.md | 1 + 1 file changed, 1 insertion(+) diff --git a/docs/en/dev_log/ulog_file_format.md b/docs/en/dev_log/ulog_file_format.md index c24eec2a1c..a1caea44e9 100644 --- a/docs/en/dev_log/ulog_file_format.md +++ b/docs/en/dev_log/ulog_file_format.md @@ -497,6 +497,7 @@ A valid ULog parser must fulfill the following requirements: - [ulogreader](https://github.com/maxsun/ulogreader): Javascript, ULog reader and parser outputs log in JSON object format. - [Foxglove](https://foxglove.dev): an integrated visualization and diagnosis tool for robotics data that supports ULog files. - [TypeScript ULog parser](https://github.com/foxglove/ulog): TypeScript, ULog reader that outputs JS objects. +- [yule_log](https://crates.io/crates/yule_log): A streaming ULog parser written in Rust. ## File Format Version History From be29f647cbd8f899bb3b46ca974700ec7179812c Mon Sep 17 00:00:00 2001 From: mahima-yoga Date: Thu, 2 Oct 2025 11:35:05 +0200 Subject: [PATCH 151/812] logging: log sensor_baro with add_topic_multi Ensures external barometers (e.g., over UAVCAN) are also logged. --- src/modules/logger/logged_topics.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index 822191ac20..bdca16eae3 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -195,7 +195,7 @@ void LoggedTopics::add_default_topics() add_topic_multi("differential_pressure", 1000, 2); add_topic_multi("distance_sensor", 1000, 2); add_optional_topic_multi("sensor_accel", 1000, 4); - add_optional_topic_multi("sensor_baro", 1000, 4); + add_topic_multi("sensor_baro", 1000, 4); add_topic_multi("sensor_gps", 1000, 2); add_topic_multi("sensor_gnss_relative", 1000, 1); add_optional_topic_multi("sensor_gyro", 1000, 4); From fa706c905f8ba402ce52aa759c02fe0ad711d82a Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Wed, 8 Oct 2025 15:58:35 +1100 Subject: [PATCH 152/812] New Crowdin translations - uk (#25660) Co-authored-by: Crowdin Bot --- docs/uk/SUMMARY.md | 2 + docs/uk/config/_autotune.md | 30 +++- docs/uk/debug/failure_injection.md | 42 ++--- docs/uk/flight_modes/offboard.md | 128 +++++++++----- docs/uk/flight_modes_rover/api.md | 29 ++++ docs/uk/frames_rover/index.md | 6 +- docs/uk/releases/main.md | 8 +- docs/uk/ros2/offboard_control.md | 4 +- docs/uk/ros2/px4_ros2_control_interface.md | 37 ++++ docs/uk/ros2/px4_ros2_interface_lib.md | 7 +- docs/uk/ros2/px4_ros2_waypoint_missions.md | 190 +++++++++++++++++++++ docs/uk/sim_gazebo_gz/index.md | 35 ++-- docs/uk/sim_gazebo_gz/vehicles.md | 12 +- 13 files changed, 439 insertions(+), 91 deletions(-) create mode 100644 docs/uk/flight_modes_rover/api.md create mode 100644 docs/uk/ros2/px4_ros2_waypoint_missions.md diff --git a/docs/uk/SUMMARY.md b/docs/uk/SUMMARY.md index a438e6bfeb..accfcd8598 100644 --- a/docs/uk/SUMMARY.md +++ b/docs/uk/SUMMARY.md @@ -436,6 +436,7 @@ - [Attitude Tuning](config_rover/attitude_tuning.md) - [Velocity Tuning](config_rover/velocity_tuning.md) - [Position Tuning](config_rover/position_tuning.md) + - [Apps & API](flight_modes_rover/api.md) - [Complete Vehicles](complete_vehicles_rover/index.md) - [Aion Robotics R1](complete_vehicles_rover/aion_r1.md) - [Submarines (experimental)](frames_sub/index.md) @@ -872,6 +873,7 @@ - [Інтерфейсна бібліотека PX4 ROS 2](ros2/px4_ros2_interface_lib.md) - [Керування інтерфейсом](ros2/px4_ros2_control_interface.md) - [Навігаційний інтерфейс](ros2/px4_ros2_navigation_interface.md) + - [Waypoint Missions](ros2/px4_ros2_waypoint_missions.md) - [ROS 2 Message Translation Node](ros2/px4_ros2_msg_translation_node.md) - [ROS 1 (Deprecated)](ros/ros1.md) - [Посібник із встановлення ROS/MAVROS](ros/mavros_installation.md) diff --git a/docs/uk/config/_autotune.md b/docs/uk/config/_autotune.md index f03800852a..7c31b3604b 100644 --- a/docs/uk/config/_autotune.md +++ b/docs/uk/config/_autotune.md @@ -95,9 +95,17 @@ The RC sticks cannot be used during autotuning (moving the sticks will stop the 4. Read the warning popup and click on **OK** to start tuning. -4. Дрон спочатку почне виконувати швидкі рухи кочення, а потім рухи тангажу та рухи курсу. +
+ +4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. The progress is shown in the progress bar, next to the _Autotune_ button. +
+ +4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. + The progress is shown in the progress bar, next to the _Autotune_ button. + +
5. Manually land and disarm to apply the new tuning parameters. @@ -108,6 +116,13 @@ The RC sticks cannot be used during autotuning (moving the sticks will stop the 5. The tuning will be immediately/automatically be applied and tested in flight (by default). PX4 will then run a 4 second test and revert the new tuning if a problem is detected. +The figure below shows how steps 4 and 5 might look in flight on the pitch axis. +The pitch rate gradually increases up until it reaches the target. +This amplitude is then held while the signal frequency is increased. +You can then see how the tuned system is able to follow the setpoint in the test signal. + + +
:::warning @@ -174,9 +189,20 @@ Fast oscillations (more than 1 oscillation per second): this is because the gain ### Послідовність автоматичної настройки не вдається +
+ Якщо безпілотник не рухався достатньо під час автоматичного налаштування, алгоритм ідентифікації системи може мати проблеми з визначенням правильних коефіцієнтів. -Increase the
[MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_SYSID_AMP)
[FW_AT_SYSID_AMP](../advanced_config/parameter_reference.md#FW_AT_SYSID_AMP)
parameter by steps of 1 and trigger the auto-tune again. +Increase the [MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_SYSID_AMP) parameter by steps of 1 and trigger the auto-tune again. + +
+
+ +By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification. The target rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. + +If the signal-to-noise ratio of the vehicle is low, the system identification algorithm might have issues finding the correct coefficients. Ensure that there is no excessive noise and/or platform vibration. + +
### The drone oscillates after auto-tuning diff --git a/docs/uk/debug/failure_injection.md b/docs/uk/debug/failure_injection.md index aaa939dc0c..7fc066c5da 100644 --- a/docs/uk/debug/failure_injection.md +++ b/docs/uk/debug/failure_injection.md @@ -9,7 +9,7 @@ Failure injection is disabled by default, and can be enabled using the [SYS_FAIL Failure injection still in development. На момент написання (PX4 v1.14): -- Це можна використовувати лише в симуляції (підтримка як для впровадження в реальному польоті запланована). +- Support may vary by failure type and between simulatiors and real vehicle. - Потребує підтримки в симуляторі. Це підтримується в Gazebo Classic - Багато типів відмов не широко реалізовані. @@ -33,31 +33,31 @@ failure [-i ] - _component_: - Датчики: - - `gyro`: Gyro. - - `accel`: Accelerometer. + - `gyro`: Gyroscope + - `accel`: Accelerometer - `mag`: Magnetometer - `baro`: Barometer - - `gps`: GPS + - `gps`: Global navigation satellite system - `optical_flow`: Optical flow. - - `vio`: Visual inertial odometry. + - `vio`: Visual inertial odometry - `distance_sensor`: Distance sensor (rangefinder). - - `airspeed`: Airspeed sensor. + - `airspeed`: Airspeed sensor - Системи: - - `battery`: Battery. - - `motor`: Motor. - - `servo`: Servo. - - `avoidance`: Avoidance. - - `rc_signal`: RC Signal. - - `mavlink_signal`: MAVLink signal (data telemetry). + - `battery`: Battery + - `motor`: Motor + - `servo`: Servo + - `avoidance`: Avoidance + - `rc_signal`: RC Signal + - `mavlink_signal`: MAVLink data telemetry connection - _failure_type_: - - `ok`: Publish as normal (Disable failure injection). - - `off`: Stop publishing. - - `stuck`: Report same value every time (_could_ indicate a malfunctioning sensor). - - `garbage`: Publish random noise. Це схоже на читання неініціалізованої пам'яті. - - `wrong`: Publish invalid values (that still look reasonable/aren't "garbage"). - - `slow`: Publish at a reduced rate. - - `delayed`: Publish valid data with a significant delay. - - `intermittent`: Publish intermittently. + - `ok`: Publish as normal (Disable failure injection) + - `off`: Stop publishing + - `stuck`: Constantly report the same value which _can_ happen on a malfunctioning sensor + - `garbage`: Publish random noise. This looks like reading uninitialized memory + - `wrong`: Publish invalid values that still look reasonable/aren't "garbage" + - `slow`: Publish at a reduced rate + - `delayed`: Publish valid data with a significant delay + - `intermittent`: Publish intermittently - _instance number_ (optional): Instance number of affected sensor. 0 (за замовчуванням) вказує на всі сенсори вказаного типу. @@ -65,7 +65,7 @@ failure [-i ] Щоб симулювати втрату сигналу RC без вимкнення вашого пульта керування RC: -1. Enable the parameter [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN). +1. Enable the parameter [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN). And specifically to turn off motors also [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE). 2. Enter the following commands on the MAVLink console or SITL _pxh shell_: ```sh diff --git a/docs/uk/flight_modes/offboard.md b/docs/uk/flight_modes/offboard.md index c9d04c0255..e2c100783d 100644 --- a/docs/uk/flight_modes/offboard.md +++ b/docs/uk/flight_modes/offboard.md @@ -62,6 +62,11 @@ bool thrust_and_torque bool direct_actuator ``` +:::warning +The following list shows the `OffboardControlMode` options for copter, fixed-wing, and VTOL. +For rovers see the [rover section](#rover). +::: + The fields are ordered in terms of priority such that `position` takes precedence over `velocity` and later fields, `velocity` takes precedence over `acceleration`, and so on. Перше поле, яке має ненульове значення (зверху вниз), визначає, яка допустима оцінка необхідна для використання режиму безпілотного керування, а також повідомлення заданих значень, які можуть бути використані. For example, if the `acceleration` field is the first non-zero value, then PX4 requires a valid `velocity estimate`, and the setpoint must be specified using the `TrajectorySetpoint` message. @@ -90,20 +95,93 @@ Before using offboard mode with ROS 2, please spend a few minutes understanding - Velocity setpoint (`velocity` different from `NaN` and `position` set to `NaN`). Non-`NaN` values acceleration are used as feedforward terms for the inner loop controllers. - Acceleration setpoint (`acceleration` different from `NaN` and `position` and `velocity` set to `NaN`) - - Всі значення інтерпретуються в NED (Nord, East, Down) координатну систему і одиниці вимірювання, є \[m/s\] і \[m/s^2\] для позиції, швидкості і прискорення, відповідно. + - All values are interpreted in NED (Nord, East, Down) coordinate system and the units are `[m]`, `[m/s]` and `[m/s^2]` for position, velocity and acceleration, respectively. - [px4_msgs::msg::VehicleAttitudeSetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAttitudeSetpoint.msg) - Підтримується наступна комбінація введення: - quaternion `q_d` + thrust setpoint `thrust_body`. - Non-`NaN` values of `yaw_sp_move_rate` are used as feedforward terms expressed in Earth frame and in \[rad/s\]. + Non-`NaN` values of `yaw_sp_move_rate` are used as feedforward terms expressed in Earth frame and in `[rad/s]`. - - Кватерніон представляє обертання між корпусом дрона у системі координат FRD (перед, праворуч, вниз) та системою координат NED. Тяга у корпусі дрона виражена у системі координат FRD та у нормалізованих значеннях. + - Кватерніон представляє обертання між корпусом дрона у системі координат FRD (перед, праворуч, вниз) та системою координат NED. + Тяга у корпусі дрона виражена у системі координат FRD та у нормалізованих значеннях. - [px4_msgs::msg::VehicleRatesSetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleRatesSetpoint.msg) - Підтримується наступна комбінація введення: - `roll`, `pitch`, `yaw` and `thrust_body`. - - Всі значення подані в для дрона в системі FRD. Значення в \[rad/s\] і thrust_body нормалізовано в \[-1, 1\]. + - Всі значення подані в для дрона в системі FRD. + The rates are in `[rad/s]` while thrust_body is normalized in `[-1, 1]`. + +### Ровер + +Rover modules must set the control mode using `OffboardControlMode` and use the appropriate messages to configure the corresponding setpoints. +The approach is similar to other vehicle types, but the allowed control mode combinations and setpoints are different: + +| Category | Використання | Setpoints | +| -------------------------------------------------------------------------------------- | ----------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| (Recommended) [Rover Setpoints](#rover-setpoints) | General rover control | [RoverPositionSetpoint](../msg_docs/RoverPositionSetpoint.md), [RoverSpeedSetpoint](../msg_docs/RoverSpeedSetpoint.md), [RoverAttitudeSetpoint](../msg_docs/RoverAttitudeSetpoint.md), [RoverRateSetpoint](../msg_docs/RoverRateSetpoint.md), [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md), [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md) | +| [Actuator Setpoints](#actuator-setpoints) | Direct actuator control | [ActuatorMotors](../msg_docs/ActuatorMotors.md), [ActuatorServos](../msg_docs/ActuatorServos.md) | +| (Deprecated) [Trajectory Setpoint](#deprecated-trajectory-setpoint) | General vehicle control | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) | + +#### Rover Setpoints + +The rover modules use a hierarchical structure to propagate setpoints: + +![Rover Control Structure](../../assets/middleware/ros2/px4_ros2_interface_lib/rover_control_structure.svg) + +The "highest" setpoint that is provided will be used within the PX4 rover modules to generate the setpoints that are below it (overriding them!). +With this hierarchy there are clear rules for providing a valid control input: + +- Provide a position setpoint **or** +- One of the setpoints on the "left" (speed **or** throttle) **and** one of the setpoints on the "right" (attitude, rate **or** steering). + All combinations of "left" and "right" setpoints are valid. + +The following are all valid setpoint combinations and their respective control flags that must be set through [OffboardControlMode](../msg_docs/OffboardControlMode.md) (set all others to _false_). +Additionally, for some combinations we require certain setpoints to be published with `NAN` values so that the setpoints of interest are not overridden by the rover module (due to the hierarchy above). +✓ are the relevant setpoints we publish, and ✗ are the setpoint that need to be published with `NAN` values. + +| Setpoint Combination | Control Flag | [RoverPositionSetpoint](../msg_docs/RoverPositionSetpoint.md) | [RoverSpeedSetpoint](../msg_docs/RoverSpeedSetpoint.md) | [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md) | [RoverAttitudeSetpoint](../msg_docs/RoverAttitudeSetpoint.md) | [RoverRateSetpoint](../msg_docs/RoverRateSetpoint.md) | [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md) | +| -------------------- | ----------------------------------------------------------- | ------------------------------------------------------------- | ------------------------------------------------------- | ------------------------------------------------------------- | ------------------------------------------------------------- | ----------------------------------------------------- | ------------------------------------------------------------- | +| Положення | положення | ✓ | | | | | | +| Speed + Attitude | швидкість | | ✓ | | ✓ | | | +| Speed + Rate | швидкість | | ✓ | | ✗ | ✓ | | +| Speed + Steering | швидкість | | ✓ | | ✗ | ✗ | ✓ | +| Throttle + Attitude | attitude | | | ✓ | ✓ | | | +| Throttle + Rate | body_rate | | | ✓ | | ✓ | | +| Throttle + Steering | thrust_and_torque | | | ✓ | | | ✓ | + +:::info +If you intend to use the rover setpoints, we recommend using the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) instead since it simplifies the publishing of these setpoints. +::: + +#### Actuator Setpoints + +Instead of controlling the vehicle using position, speed, rate and other setpoints, you can directly control the motors and actuators using [ActuatorMotors](../msg_docs/ActuatorMotors.md) and [ActuatorServos](../msg_docs/ActuatorServos.md). +In [OffboardControlMode](../msg_docs/OffboardControlMode.md) set `direct_actuator` to _true_ and all other flags to _false_. + +:::info +This bypasses the rover modules including any limits on steering rates or accelerations and the inverse kinematics step. +We recommend using [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md) and [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md) instead for low level control (see [Rover Setpoints](#rover-setpoints)). +::: + +#### (Deprecated) Trajectory Setpoint + +:::warning +The [Rover Setpoints](#rover-setpoints) are a replacement for the [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) and we highly recommend using those instead as they have a well defined behaviour and offer more flexibility. +::: + +The rover modules support the _position_, _velocity_ and _yaw_ fields of the [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md). +However, only one of the fields is active at a time and is defined by the flags of [OffboardControlMode](../msg_docs/OffboardControlMode.md): + +| Control Mode Flag | Active Trajectory Setpoint Field | +| ----------------- | -------------------------------- | +| положення | положення | +| швидкість | швидкість | +| attitude | yaw | + +:::info +Ackermann rovers do not support the yaw setpoint. +::: ### Універсальний апарат @@ -116,8 +194,10 @@ Before using offboard mode with ROS 2, please spend a few minutes understanding - [px4_msgs::msg::ActuatorMotors](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorMotors.msg) + [px4_msgs::msg::ActuatorServos](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorServos.msg) - Ви безпосередньо керуєте вихідними сигналами моторів та/або сервоприводів. - - Currently works at lower level than then `control_allocator` module. Do not publish these messages when not in offboard mode. - - Усі значення нормалізовані у діапазоні \[-1, 1\]. For outputs that do not support negative values, negative entries map to `NaN`. + - Currently works at lower level than then `control_allocator` module. + Do not publish these messages when not in offboard mode. + - All the values normalized in `[-1, 1]`. + For outputs that do not support negative values, negative entries map to `NaN`. - `NaN` maps to disarmed. ## Повідомлення MAVLink @@ -206,41 +286,7 @@ Before using offboard mode with ROS 2, please spend a few minutes understanding ### Ровер -- [SET_POSITION_TARGET_LOCAL_NED](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_LOCAL_NED) - - The following input combinations are supported (in `type_mask`): - - Position setpoint (only `x`, `y`, `z`) - - Specify the _type_ of the setpoint in `type_mask`: - - ::: info - The _setpoint type_ values below are not part of the MAVLink standard for the `type_mask` field. - :: - - Значення: - - - 12288: задане значення Loiter (пристрій зупиняється, коли вже достатньо близько, щоб встановити точку). - - - Velocity setpoint (only `vx`, `vy`, `vz`) - - - PX4 supports the coordinate frames (`coordinate_frame` field): [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED) and [MAV_FRAME_BODY_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_BODY_NED). - -- [SET_POSITION_TARGET_GLOBAL_INT](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT) - - The following input combinations are supported (in `type_mask`): - - Position setpoint (only `lat_int`, `lon_int`, `alt`) - - - Specify the _type_ of the setpoint in `type_mask` (not part of the MAVLink standard). - Значення: - - Якщо наступні біти не встановлені, то виконується звичайна поведінка. - - 12288: задане значення Loiter (пристрій зупиняється, коли вже достатньо близько, щоб встановити точку). - - - PX4 supports the coordinate frames (`coordinate_frame` field): [MAV_FRAME_GLOBAL](https://mavlink.io/en/messages/common.html#MAV_FRAME_GLOBAL). - -- [SET_ATTITUDE_TARGET](https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET) - - Підтримуються наступні вхідні комбінації: - - Attitude/orientation (`SET_ATTITUDE_TARGET.q`) with thrust setpoint (`SET_ATTITUDE_TARGET.thrust`). - ::: info - Only the yaw setting is actually used/extracted. - -::: +Rover does not support a MAVLink offboard API (ROS2 is supported). ## Параметри для відключення diff --git a/docs/uk/flight_modes_rover/api.md b/docs/uk/flight_modes_rover/api.md new file mode 100644 index 0000000000..e32de3e8ee --- /dev/null +++ b/docs/uk/flight_modes_rover/api.md @@ -0,0 +1,29 @@ +# Apps & API + +The rover modules have been tested and integrated with a subset of the available [Apps & API](../middleware/index.md) methods. +We specifically provide guides for using [ROS 2](../ros2/index.md) to interface a companion computer with PX4 via [uXRCE-DDS](../middleware/uxrce_dds.md). + +| Method | Опис | +| ---------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| [PX4 ROS 2 Interface](#px4-ros-2-interface) (Recommended) | Register a custom mode and publish [RoverSetpointTypes](../ros2/px4_ros2_control_interface.md#rover-setpoints). | +| [ROS 2 Offboard Control](#ros-2-offboard-control) | Use the PX4 internal [Offboard Mode](../flight_modes/offboard.md) and publish messages defined in [dds_topics.yaml](../middleware/dds_topics.md). | + +## PX4 ROS 2 Interface + +We recommend the use of the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) which allows you to register a custom drive mode and exposes [RoverSetpointTypes](../ros2/px4_ros2_control_interface.md#rover-setpoints). + +By using these setpoints (instead of the PX4 internal rover setpoints), you are guaranteed to send valid control inputs to your vehicle and the control flags for the setpoints you are using are automatically set for you. +Registering a custom drive mode instead of using [ROS 2 Offboard Control](#ros-2-offboard-control) additionally provides the advantages listed [here](../concept/flight_modes.md#internal-vs-external-modes). + +To get familiar with this method, read through the guide for the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) where we also provide an example app for rover. + +## ROS 2 Offboard Control + +[ROS 2 Offboard Control](../ros2/offboard_control.md) uses the PX4 internal [Offboard Mode](../flight_modes/offboard.md). + +While you can subscribe/publish to all topics specified in [dds_topics.yaml](../middleware/dds_topics.md), not all rover modules support all of these topics (see [Supported Setpoints](../flight_modes/offboard.md#rover)). +Unlike the [RoverSetpointTypes](../ros2/px4_ros2_control_interface.md#rover-setpoints) exposed through the [PX4 ROS 2 Interface](#px4-ros-2-interface), there is no guarantee that the published setpoints lead to a valid control input. + +In addition, the correct control mode flags must be set through [OffboardControlMode](../msg_docs/OffboardControlMode.md). +This requires a deeper understanding of PX4 and the structure of the rover modules. +For general information on setting up offboard mode read through [Offboard Mode](../flight_modes/offboard.md) and then consult [Supported Setpoints](../flight_modes/offboard.md#rover). diff --git a/docs/uk/frames_rover/index.md b/docs/uk/frames_rover/index.md index 39f404f32c..f2d7e9e4b7 100644 --- a/docs/uk/frames_rover/index.md +++ b/docs/uk/frames_rover/index.md @@ -57,15 +57,17 @@ Each wheel is driven by its own motor, and by controlling the speed and directio ## Дивіться також -- [Drive Modes](../flight_modes_rover/index.md). +- [Drive Modes](../flight_modes_rover/index.md) - [Configuration/Tuning](../config_rover/index.md) +- [Apps & API](../flight_modes_rover/api.md) - [Complete Vehicles](../complete_vehicles_rover/index.md) ## Симуляція -[Gazebo](../sim_gazebo_gz/index.md) provides simulations for ackermann and differential rovers: +PX4 provides synthetic simulation models for [Gazebo](../sim_gazebo_gz/index.md) of all three rover types to test the software and validate changes and new features: - [Ackermann rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) - [Differential rover](../sim_gazebo_gz/vehicles.md#differential-rover) +- [Mecanum rover](../sim_gazebo_gz/vehicles.md#mecanum-rover) ![Rover gazebo simulation](../../assets/airframes/rover/rover_simulation.png) diff --git a/docs/uk/releases/main.md b/docs/uk/releases/main.md index dd3875875b..dbce991f2c 100644 --- a/docs/uk/releases/main.md +++ b/docs/uk/releases/main.md @@ -58,7 +58,10 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Симуляція -- Уточнюється +- Overhaul rover simulation: + - Add synthetic differential rover model: [PX4-gazebo-models#107](https://github.com/PX4/PX4-gazebo-models/pull/107) + - Add synthetic mecanum rover model: [PX4-gazebo-models#113](https://github.com/PX4/PX4-gazebo-models/pull/113) + - Update synthetic ackermann rover model: [PX4-gazebo-models#117](https://github.com/PX4/PX4-gazebo-models/pull/117) ### Ethernet @@ -67,6 +70,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### uXRCE-DDS / ROS2 - [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [Fixed Wing lateral/longitudinal setpoint](../ros2/px4_ros2_control_interface.md#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype) (`FwLateralLongitudinalSetpointType`) and [VTOL transitions](../ros2/px4_ros2_control_interface.md#controlling-a-vtol). ([PX4-Autopilot#24056](https://github.com/PX4/PX4-Autopilot/pull/24056)). +- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [ROS-based waypoint missions](../ros2/px4_ros2_waypoint_missions.md). ### MAVLink @@ -89,6 +93,8 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### Ровер - Removed deprecated rover module ([PX4-Autopilot#25054](https://github.com/PX4/PX4-Autopilot/pull/25054)). +- Add support for [Apps & API](../flight_modes_rover/api.md) ([PX4-Autopilot#25074](https://github.com/PX4/PX4-Autopilot/pull/25074), [PX4-ROS2-Interface-Lib#140](https://github.com/Auterion/px4-ros2-interface-lib/pull/140)). +- Update [rover simulation](../frames_rover/index.md#simulation) ([PX4-Autopilot#25644](https://github.com/PX4/PX4-Autopilot/pull/25644)) (see [Simulation](#simulation) release note for details). ### ROS 2 diff --git a/docs/uk/ros2/offboard_control.md b/docs/uk/ros2/offboard_control.md index 142c9931cb..2a6b62079d 100644 --- a/docs/uk/ros2/offboard_control.md +++ b/docs/uk/ros2/offboard_control.md @@ -1,6 +1,6 @@ # ROS 2 Offboard Control Приклад -The following C++ example shows how to do position control in [offboard mode](../flight_modes/offboard.md) from a ROS 2 node. +The following C++ example shows how to do multicopter position control in [offboard mode](../flight_modes/offboard.md) from a ROS 2 node. Приклад починає відправляти установочні точки, входить у режим offboard, озброюється, піднімається на 5 метрів і чекає. Незважаючи на простоту, він демонструє основні принципи використання offboard control і способи надсилання команд транспортному засобу. @@ -22,7 +22,7 @@ To subscribe to data coming from nodes that publish in a different frame (for ex ## Випробування -Follow the instructions in [ROS 2 User Guide](../ros2/user_guide.md) to install PX and run the simulator, install ROS 2, and start the XRCE-DDS Agent. +Follow the instructions in [ROS 2 User Guide](../ros2/user_guide.md) to install PX and run the multicopter simulator, install ROS 2, and start the XRCE-DDS Agent. After that we can follow a similar set of steps to those in [ROS 2 User Guide > Build ROS 2 Workspace](../ros2/user_guide.md#build-ros-2-workspace) to run the example. diff --git a/docs/uk/ros2/px4_ros2_control_interface.md b/docs/uk/ros2/px4_ros2_control_interface.md index 1bf129ee18..0905f468a6 100644 --- a/docs/uk/ros2/px4_ros2_control_interface.md +++ b/docs/uk/ros2/px4_ros2_control_interface.md @@ -348,6 +348,7 @@ private: - [MulticopterGotoSetpointType](#go-to-setpoint-multicoptergotosetpointtype): Smooth position and (optionally) heading control - [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics - DirectActuatorsSetpointType: Пряме керування моторами та установками сервоприводів польотних поверхонь +- [Rover Setpoints](#rover-setpoints): Direct access to rover control setpoints (Position, Speed, Attitude, Rate, Throttle and Steering). :::tip The other setpoint types are currently experimental, and can be found in: [px4_ros2/control/setpoint_types/experimental](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/experimental). @@ -359,6 +360,8 @@ The other setpoint types are currently experimental, and can be found in: [px4_r + + :::info This setpoint type is currently only supported for multicopters. ::: @@ -552,6 +555,40 @@ and [`FW_THR_MAX`](../advanced_config/parameter_reference.md#FW_THR_MAX). Якщо ви хочете керувати клапаном, який не контролює рух транспортного засобу, але, наприклад, сервопривід навантаження, подивіться нижче. ::: +#### Rover Setpoints + + + +The rover modules use a hierarchical structure to propagate setpoints: + +![Rover Control Structure](../../assets/middleware/ros2/px4_ros2_interface_lib/rover_control_structure.svg) + +:::info +The "highest" setpoint that is provided will be used within the PX4 rover modules to generate the setpoints that are below it (Overriding them!). +With this hierarchy there are clear rules for providing a valid control input: + +- Provide a position setpoint, **or** +- One of the setpoints on the "left" (speed **or** throttle) **and** one of the setpoints on the "right" (attitude, rate **or** steering). All combinations of "left" and "right" setpoints are valid. + +For ease of use we expose these valid combinations as new SetpointTypes. +::: + +The RoverSetpointTypes exposed through the control interface are combinations of these setpoints that lead to a valid control input: + +| SetpointType | Положення | Speed | Тяга | Attitude | Rate | Steering | Control Flags | +| ----------------------------------------------------------------------------------------------------------------------------------- | --------------------------- | ------------------------------------------------ | ------------------------------------------------ | ------------------------------------------------ | ------------------------------------------------ | ------------------------------------------------ | ------------------------------------------------------ | +| [RoverPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverPositionSetpointType.html#details) | ✓ | (✓) | (✓) | (✓) | (✓) | (✓) | Position, Velocity, Attitude, Rate, Control Allocation | +| [RoverSpeedAttitude](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverSpeedAttitudeSetpointType.html) | | ✓ | (✓) | ✓ | (✓) | (✓) | Velocity, Attitude, Rate, Control Allocation | +| [RoverSpeedRate](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverSpeedRateSetpointType.html) | | ✓ | (✓) | | ✓ | (✓) | Velocity, Rate, Control Allocation | +| [RoverSpeedSteering](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverSpeedSteeringSetpointType.html) | | ✓ | (✓) | | | ✓ | Velocity, Control Allocation | +| [RoverThrottleAttitude](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverThrottleAttitudeSetpointType.html) | | | ✓ | ✓ | (✓) | (✓) | Attitude, Rate, Control Allocation | +| [RoverThrottleRate](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverThrottleRateSetpointType.html) | | | ✓ | | ✓ | (✓) | Rate, Control Allocation | +| [RoverThrottleSteering](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverThrottleSteeringSetpointType.html) | | | ✓ | | | ✓ | Control Allocation | + +✓ are the setpoints we publish, and (✓) are generated internally by the PX4 rover modules according to the hierarchy above. + +An example for a rover specific drive mode using the `RoverSpeedAttitudeSetpointType` is provided [here](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/rover_velocity). + ### Controlling a VTOL diff --git a/docs/uk/ros2/px4_ros2_interface_lib.md b/docs/uk/ros2/px4_ros2_interface_lib.md index 1829bd5d64..c392c93f85 100644 --- a/docs/uk/ros2/px4_ros2_interface_lib.md +++ b/docs/uk/ros2/px4_ros2_interface_lib.md @@ -9,15 +9,12 @@ [PX4 ROS 2 Інтерфейс бібліотеки](https://github.com/Auterion/px4-ros2-interface-lib) є бібліотекою C+++, яка спрощує контроль і взаємодіє з PX4 з ROS 2. -Бібліотека надає два інтерфейси високого рівня для розробників: +The library provides three high-level interfaces for developers: 1. [Control Interface](./px4_ros2_interface.md) дозволяє розробникам створювати та динамічно реєструвати режими, написані з використанням ROS 2. Бібліотека також надає класи для надсилання різних типів налаштувань, починаючи від багаторівневих навігаційних завдань на високому рівні аж до прямого контролю приводу. 2. [Навігаційний інтерфейс](./px4_ros2_navigation_interface.md) дозволяє надсилати позицію автомобіля з позиції PX4 з ROS 2 додатків, таких як система VIO. - - +3. [Waypoint Missions](./px4_ros2_waypoint_missions.md) allows waypoint missions to run entirely in ROS 2. ## Встановлення в робочому просторі ROS 2 diff --git a/docs/uk/ros2/px4_ros2_waypoint_missions.md b/docs/uk/ros2/px4_ros2_waypoint_missions.md new file mode 100644 index 0000000000..e1a3b16bbc --- /dev/null +++ b/docs/uk/ros2/px4_ros2_waypoint_missions.md @@ -0,0 +1,190 @@ +# PX4 ROS 2 Waypoint Missions + + + +The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) provides a high-level interface for executing ROS-based waypoint missions in ROS 2. +The main use-case is for creating missions where a custom behavior is required, such as a pickup action within a mission. + +:::warning +ROS 2 missions are not compatible with MAVLink mission definitions, plan files, or ground stations. +They completely bypass the existing PX4 mission mode and waypoint logic, and cannot be planned or displayed within a ground station. +::: + +ROS 2 waypoint missions are effectively special PX4 ROS 2 custom modes that are run based on the content of a [JSON mission definition](#mission-definition). +Mission definitions can contain actions that reference existing PX4 modes, such as Takeoff mode or RTL, and can also be extended with arbitrary custom actions written in ROS. +A [mode executor](px4_ros2_control_interface.md#mode-executor) is used to schedule the modes. + +Mission definitions can be hard coded in the custom mission mode (either in code or statically loaded from a JSON string), or directly generated within the application. +They can also be dynamically loaded based on modification of a particular JSON file — this allows for building a more generic mission framework with a fixed set of custom actions. +The file can then be written by any other application, for example a HTTP or MAVFTP server. + +The current implementation only supports multicopters but is designed to be extendable to any other vehicle type. + +## Comparison to PX4/MAVLink Missions + +There are some benefits and drawbacks to using ROS-based missions, which are provided in the following paragraphs. + +### Переваги + +- Allows to extend mission capabilities by registering custom actions. +- More control over how the mission is executed. + A custom trajectory executor can be implemented, which can use any of the existing PX4 setpoint types to track the trajectory. +- Reduced complexity on the flight controller side by running non-safety-critical and non-real-time code on a more high-level companion computer. +- It can be extended to support other trajectory types, like Bezier or Dubin curves. + +### Drawbacks + +- QGroundControl currently does not display the mission or progress during execution, and cannot upload or download a mission. + Therefore you will need another mechanism to provide a mission, such as from a web server, a custom GCS, or by generating it directly inside the application. +- The current implementation only supports multicopters (it uses the [GotoSetpointType](../ros2/px4_ros2_control_interface.md#go-to-setpoint-gotosetpointtype), which only works for multicopters, and VTOL in MC mode). + It is designed to be extendable to any other vehicle type. + +## Загальний огляд + +This diagram provides a conceptual overview of the main classes and their interactions: + +![Waypoint missions overview diagram](../../assets/middleware/ros2/px4_ros2_interface_lib/waypoint_missions.svg) + + + +Missions can be defined in [JSON](#mission-definition), either as a file, or directly inside the application. +There is a file change monitor (`MissionFileMonitor`), that can be used to automatically load a mission from a specific file whenever it is created by another application (e.g. upload via MAVFTP or a cloud service). + +The **`MissionExecutor`** class contains the state machine to progress the mission index, and is at the core of the implementation: + +- Internally, it builds on top of the [Modes and Mode Executors](px4_ros2_control_interface.md#overview) and registers itself through a custom mode and executor with PX4. +- It handles switching in and out of missions: it gets activated when the user switches to the custom mode that represents the mission and the vehicle is armed. + The mode name can be customized (`My Mission` in the example below). + The mission can be paused, which makes the vehicle switch into _Hold mode_. + To resume the mission, the custom mode has to be selected again. +- When an action switches into another mode (for example Takeoff), QGroundControl will display this mode until it is completed. + The mission executor will then automatically continue. +- Custom actions can be registered. +- The mission can be set. + It then checks that all the actions which the mission defines are available and can be run. +- The state can be stored persistently by providing a file name, allowing for battery swapping. + +The **`ActionInterface`** is an interface class for custom actions. +They are identified by a name, and any number of these can be registered with the `MissionExecutor`. +A custom action is then run whenever a mission item with matching name is executed, and any extra arguments from the JSON definition are passed as arguments (for example an altitude for a takeoff action). +Actions can call other actions, run any mode (PX4 or external by its ID), run a trajectory, or run any other external action before deciding when to continue the mission. + +There is a set of default actions, for example for RTL, Land, etc. +These simply trigger the corresponding PX4 mode. +They can be disabled or replaced with custom implementations. +There are also some special actions (which can be replaced as well): + +- `OnFailure`: this is called in case of a failure, e.g. a mode switch failed, a non-existing action is called (by another action) or by an explicit call to `MissionExecutor::abort()`. + The default is to run RTL, with fallback to Land. +- `OnResume`: this is called when resuming a mission (either from the ground or in-air). + It handles a number of cases: + - when called with an argument `action="storeState"`: this can be used to store the current position when the mission is deactivated, so it can be resumed from the same position. + Currently it does not store anything. + - otherwise, when called without a valid mission index or 0, it directly continues. + - otherwise, when called while in-air, it also directly continues. + - otherwise, if landed and if the current mission item is an action that supports resuming from landed, it continues to let the action handle the resuming. + - otherwise, if landed, it finds the takeoff action from the mission, runs it, and then flies to the previous waypoint from the current index to continue the mission. +- `ChangeSettings`: this can be used to change the mission settings, such as the velocity. + The settings are applied to all following items in the mission. + +The **`TrajectoryExecutorInterface`** is an interface class to execute segments of a trajectory. +It can use any setpoint that PX4 and the current vehicle supports for tracking the trajectory. +This class is vehicle-type specific. +The current default implementation (`multicopter::WaypointTrajectoryExecutor`) uses a Goto setpoint (and thus is limited to multicopters). +The default can be replaced with a custom implementation. + +## Використання + +The following provides a small example. +It defines a custom action and a mission that uses it. + +```c++ +class CustomAction : public px4_ros2::ActionInterface { +public: + CustomAction(px4_ros2::ModeBase & mode) : _node(mode.node()) { } + + std::string name() const override {return "customAction";} + + void run( + const std::shared_ptr & handler, + const px4_ros2::ActionArguments & arguments, + const std::function & on_completed) override + { + RCLCPP_INFO(_node.get_logger(), "Running custom action"); + // Do something... + + on_completed(); + } +private: + rclcpp::Node & _node; +}; + +class MyMission { +public: + MyMission(const std::shared_ptr & node) : _node(node) + { + const auto mission = px4_ros2::Mission(nlohmann::json::parse(R"( + { + "version": 1, + "mission": { + "items": [ + { + "type": "takeoff" + }, + { + "type": "navigation", + "navigationType": "waypoint", + "x": 47.3977419, + "y": 8.5455939, + "z": 500, + "frame": "global" + }, + { + "type": "navigation", + "navigationType": "waypoint", + "x": 47.39791657, + "y": 8.54595214, + "z": 500, + "frame": "global" + }, + { + "type": "customAction" + }, + { + "type": "rtl" + } + ] + } + } +)")); + _mission_executor = std::make_unique("My Mission", + px4_ros2::MissionExecutor::Configuration().addCustomAction(), *node); + + if (!_mission_executor->doRegister()) { + throw std::runtime_error("Failed to register mission executor"); + } + _mission_executor->setMission(mission); + + _mission_executor->onProgressUpdate([&](int current_index) { + RCLCPP_INFO(_node->get_logger(), "Current mission index: %i", current_index); + }); + _mission_executor->onCompleted([&] { + RCLCPP_INFO(_node->get_logger(), "Mission completed callback"); + }); + } + +private: + std::shared_ptr _node; + std::unique_ptr _mission_executor; +}; +``` + +A full example with a few custom actions can be found under [github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/mission/include](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/mission/include). + +## Mission Definition + +The mission JSON file can contain mission defaults and a list of mission items, including user-defined types with custom arguments. +Waypoint coordinates currently need to be defined in global frame, and other frame types might be added in future. + +The schema can be found under [github.com/Auterion/px4-ros2-interface-lib/blob/main/mission/schema.yaml](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/mission/schema.yaml). +It provides more details and can be used to validate a JSON file. diff --git a/docs/uk/sim_gazebo_gz/index.md b/docs/uk/sim_gazebo_gz/index.md index 01fbe74cbe..a05e18c158 100644 --- a/docs/uk/sim_gazebo_gz/index.md +++ b/docs/uk/sim_gazebo_gz/index.md @@ -20,6 +20,8 @@ See [Simulation](../simulation/index.md) for general information about simulator Gazebo Harmonic is installed by default on Ubuntu 22.04 as part of the normal [development environment setup](../dev_setup/dev_env_linux_ubuntu.md#simulation-and-nuttx-pixhawk-targets). +Gazebo versions Harmonic, Ionic, and Jetty are supported on Ubuntu 24.04. The latest installed Gazebo release is used by default. + :::info The PX4 installation scripts are based on the instructions: [Binary Installation on Ubuntu](https://gazebosim.org/docs/harmonic/install_ubuntu/) (gazebosim.org). ::: @@ -48,22 +50,23 @@ make px4_sitl gz_x500 The supported vehicles and `make` commands are listed below. Note that all gazebo make targets have the prefix `gz_`. -| Транспортний засіб | Команда | `PX4_SYS_AUTOSTART` | -| ------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ----------------------------------- | ------------------- | -| [Quadrotor (x500)](../sim_gazebo_gz/vehicles.md#x500-quadrotor) | `make px4_sitl gz_x500` | 4001 | -| [X500 Quadrotor with Depth Camera (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-depth-camera-front-facing) | `make px4_sitl gz_x500_depth` | 4002 | -| [Quadrotor(x500) with Vision Odometry](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-visual-odometry) | `make px4_sitl gz_x500_vision` | 4005 | -| [Quadrotor(x500) with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing) | `make px4_sitl gz_x500_lidar_down` | 4016 | -| [Quadrotor(x500) with 2D LIDAR](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar) | `make px4_sitl gz_x500_lidar_2d` | 4013 | -| [Quadrotor(x500) with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing) | `make px4_sitl gz_x500_lidar_front` | 4017 | -| [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) | `make px4_sitl gz_x500_gimbal` | 4019 | -| [VTOL](../sim_gazebo_gz/vehicles.md#standard-vtol) | `make px4_sitl gz_standard_vtol` | 4004 | -| [Plane](../sim_gazebo_gz/vehicles.md#standard-plane) | `make px4_sitl gz_rc_cessna` | 4003 | -| [Advanced Plane](../sim_gazebo_gz/vehicles.md#advanced-plane) | `make px4_sitl gz_advanced_plane` | 4008 | -| [Differential Rover](../sim_gazebo_gz/vehicles.md#differential-rover) | `make px4_sitl gz_r1_rover` | 4009 | -| [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) | `make px4_sitl gz_rover_ackermann` | 4012 | -| [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) | `make px4_sitl gz_quadtailsitter` | 4018 | -| [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) | `make px4_sitl gz_tiltrotor` | 4020 | +| Транспортний засіб | Команда | `PX4_SYS_AUTOSTART` | +| ------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------- | ------------------- | +| [Quadrotor (x500)](../sim_gazebo_gz/vehicles.md#x500-quadrotor) | `make px4_sitl gz_x500` | 4001 | +| [X500 Quadrotor with Depth Camera (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-depth-camera-front-facing) | `make px4_sitl gz_x500_depth` | 4002 | +| [Quadrotor(x500) with Vision Odometry](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-visual-odometry) | `make px4_sitl gz_x500_vision` | 4005 | +| [Quadrotor(x500) with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing) | `make px4_sitl gz_x500_lidar_down` | 4016 | +| [Quadrotor(x500) with 2D LIDAR](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar) | `make px4_sitl gz_x500_lidar_2d` | 4013 | +| [Quadrotor(x500) with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing) | `make px4_sitl gz_x500_lidar_front` | 4017 | +| [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) | `make px4_sitl gz_x500_gimbal` | 4019 | +| [VTOL](../sim_gazebo_gz/vehicles.md#standard-vtol) | `make px4_sitl gz_standard_vtol` | 4004 | +| [Plane](../sim_gazebo_gz/vehicles.md#standard-plane) | `make px4_sitl gz_rc_cessna` | 4003 | +| [Advanced Plane](../sim_gazebo_gz/vehicles.md#advanced-plane) | `make px4_sitl gz_advanced_plane` | 4008 | +| [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) | `make px4_sitl gz_quadtailsitter` | 4018 | +| [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) | `make px4_sitl gz_tiltrotor` | 4020 | +| [Differential Rover](../sim_gazebo_gz/vehicles.md#differential-rover) | `make px4_sitl gz_rover_differential` | 50000 | +| [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) | `make px4_sitl gz_rover_ackermann` | 51000 | +| [Mecanum Rover](../sim_gazebo_gz/vehicles.md#mecanum-rover) | `make px4_sitl gz_rover_mecanum` | 52000 | All [vehicle models](../sim_gazebo_gz/vehicles.md) (and [worlds](#specify-world)) are included as a submodule from the [Gazebo Models Repository](../sim_gazebo_gz/gazebo_models.md) repository. diff --git a/docs/uk/sim_gazebo_gz/vehicles.md b/docs/uk/sim_gazebo_gz/vehicles.md index 25a52f2447..1660045bed 100644 --- a/docs/uk/sim_gazebo_gz/vehicles.md +++ b/docs/uk/sim_gazebo_gz/vehicles.md @@ -185,7 +185,7 @@ make px4_sitl gz_tiltrotor [Differential Rover](../frames_rover/index.md#differential) uses the [rover world](../sim_gazebo_gz/worlds.md#rover) by default. ```sh -make px4_sitl gz_r1_rover +make px4_sitl gz_rover_differential ``` ![Differential Rover in Gazebo](../../assets/simulation/gazebo/vehicles/rover_differential.png) @@ -199,3 +199,13 @@ make px4_sitl gz_rover_ackermann ``` ![Ackermann Rover in Gazebo](../../assets/simulation/gazebo/vehicles/rover_ackermann.png) + +### Mecanum Rover + +[Mecanum Rover](../frames_rover/index.md#mecanum) uses the [rover world](../sim_gazebo_gz/worlds.md#rover) by default. + +```sh +make px4_sitl gz_rover_mecanum +``` + +![Mecanum Rover in Gazebo](../../assets/simulation/gazebo/vehicles/rover_mecanum.png) From d3bcdf8ba78d9f1182696fdf3902421e8e4a3634 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Wed, 8 Oct 2025 16:19:27 +1100 Subject: [PATCH 153/812] New Crowdin translations - zh-CN (#25661) Co-authored-by: Crowdin Bot --- docs/zh/SUMMARY.md | 2 + docs/zh/companion_computer/pixhawk_rpi.md | 2 +- docs/zh/config/_autotune.md | 28 +- docs/zh/debug/failure_injection.md | 42 +-- docs/zh/flight_modes/offboard.md | 128 +++++--- docs/zh/flight_modes_rover/api.md | 29 ++ docs/zh/frames_rover/index.md | 12 +- docs/zh/middleware/uxrce_dds.md | 20 +- docs/zh/releases/main.md | 8 +- docs/zh/ros2/index.md | 14 +- docs/zh/ros2/multi_vehicle.md | 38 +-- docs/zh/ros2/offboard_control.md | 10 +- docs/zh/ros2/px4_ros2_control_interface.md | 55 +++- docs/zh/ros2/px4_ros2_interface_lib.md | 5 +- docs/zh/ros2/px4_ros2_msg_translation_node.md | 2 +- docs/zh/ros2/px4_ros2_waypoint_missions.md | 190 ++++++++++++ docs/zh/ros2/user_guide.md | 280 +++++++++--------- docs/zh/sim_gazebo_gz/index.md | 35 ++- docs/zh/sim_gazebo_gz/vehicles.md | 12 +- docs/zh/telemetry/telemetry_wifi.md | 2 +- 20 files changed, 631 insertions(+), 283 deletions(-) create mode 100644 docs/zh/flight_modes_rover/api.md create mode 100644 docs/zh/ros2/px4_ros2_waypoint_missions.md diff --git a/docs/zh/SUMMARY.md b/docs/zh/SUMMARY.md index cbe5e1a28b..1a4deb2d9c 100644 --- a/docs/zh/SUMMARY.md +++ b/docs/zh/SUMMARY.md @@ -436,6 +436,7 @@ - [Attitude Tuning](config_rover/attitude_tuning.md) - [Velocity Tuning](config_rover/velocity_tuning.md) - [Position Tuning](config_rover/position_tuning.md) + - [Apps & API](flight_modes_rover/api.md) - [Complete Vehicles](complete_vehicles_rover/index.md) - [Aion Robotics R1](complete_vehicles_rover/aion_r1.md) - [Submarines (experimental)](frames_sub/index.md) @@ -872,6 +873,7 @@ - [PX4 ROS 2 Interface Library](ros2/px4_ros2_interface_lib.md) - [Control Interface](ros2/px4_ros2_control_interface.md) - [Navigation Interface](ros2/px4_ros2_navigation_interface.md) + - [Waypoint Missions](ros2/px4_ros2_waypoint_missions.md) - [ROS 2 Message Translation Node](ros2/px4_ros2_msg_translation_node.md) - [ROS 1 (Deprecated)](ros/ros1.md) - [ROS/MAVROS安装指南](ros/mavros_installation.md) diff --git a/docs/zh/companion_computer/pixhawk_rpi.md b/docs/zh/companion_computer/pixhawk_rpi.md index beb8a1f7fe..73406d2a8d 100644 --- a/docs/zh/companion_computer/pixhawk_rpi.md +++ b/docs/zh/companion_computer/pixhawk_rpi.md @@ -266,7 +266,7 @@ The configuration steps are: ``` [MAV_1_CONFIG=0](../advanced_config/parameter_reference.md#MAV_1_CONFIG) and [UXRCE_DDS_CFG=102](../advanced_config/parameter_reference.md#UXRCE_DDS_CFG) disable MAVLink on TELEM2 and enable the uXRCE-DDS client on TELEM2, respectively. - The `SER_TEL2_BAUD` rate sets the comms link data rate.\ + The `SER_TEL2_BAUD` rate sets the comms link data rate. You could similarly configure a connection to `TELEM1` using either `MAV_1_CONFIG` or `MAV_0_CONFIG`. ::: info diff --git a/docs/zh/config/_autotune.md b/docs/zh/config/_autotune.md index 8c5df070ae..6a75da6380 100644 --- a/docs/zh/config/_autotune.md +++ b/docs/zh/config/_autotune.md @@ -95,9 +95,17 @@ The test steps are: 4. Read the warning popup and click on **OK** to start tuning. +
+ 4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. The progress is shown in the progress bar, next to the _Autotune_ button. +
+ +4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. + The progress is shown in the progress bar, next to the _Autotune_ button. + +
5. Manually land and disarm to apply the new tuning parameters. @@ -108,6 +116,13 @@ The test steps are: 5. The tuning will be immediately/automatically be applied and tested in flight (by default). PX4 will then run a 4 second test and revert the new tuning if a problem is detected. +The figure below shows how steps 4 and 5 might look in flight on the pitch axis. +The pitch rate gradually increases up until it reaches the target. +This amplitude is then held while the signal frequency is increased. +You can then see how the tuned system is able to follow the setpoint in the test signal. + + +
:::warning @@ -174,9 +189,20 @@ Fast oscillations (more than 1 oscillation per second): this is because the gain ### The auto-tuning sequence fails +
+ If the drone was not moving enough during auto-tuning, the system identification algorithm might have issues to find the correct coefficients. -Increase the
[MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_SYSID_AMP)
[FW_AT_SYSID_AMP](../advanced_config/parameter_reference.md#FW_AT_SYSID_AMP)
parameter by steps of 1 and trigger the auto-tune again. +Increase the [MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_SYSID_AMP) parameter by steps of 1 and trigger the auto-tune again. + +
+
+ +By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification. The target rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. + +If the signal-to-noise ratio of the vehicle is low, the system identification algorithm might have issues finding the correct coefficients. Ensure that there is no excessive noise and/or platform vibration. + +
### The drone oscillates after auto-tuning diff --git a/docs/zh/debug/failure_injection.md b/docs/zh/debug/failure_injection.md index e013753243..772e67c1a3 100644 --- a/docs/zh/debug/failure_injection.md +++ b/docs/zh/debug/failure_injection.md @@ -9,7 +9,7 @@ Failure injection is disabled by default, and can be enabled using the [SYS_FAIL Failure injection still in development. At time of writing (PX4 v1.14): -- It can only be used in simulation (support for both failure injection in real flight is planned). +- Support may vary by failure type and between simulatiors and real vehicle. - It requires support in the simulator. It is supported in Gazebo Classic - Many failure types are not broadly implemented. @@ -33,31 +33,31 @@ where: - _component_: - 传感器: - - `gyro`: Gyro. - - `accel`: Accelerometer. + - `gyro`: Gyroscope + - `accel`: Accelerometer - `mag`: Magnetometer - `baro`: Barometer - - `gps`: GPS + - `gps`: Global navigation satellite system - `optical_flow`: Optical flow. - - `vio`: Visual inertial odometry. + - `vio`: Visual inertial odometry - `distance_sensor`: Distance sensor (rangefinder). - - `airspeed`: Airspeed sensor. + - `airspeed`: Airspeed sensor - Systems: - - `battery`: Battery. - - `motor`: Motor. - - `servo`: Servo. - - `avoidance`: Avoidance. - - `rc_signal`: RC Signal. - - `mavlink_signal`: MAVLink signal (data telemetry). + - `battery`: Battery + - `motor`: Motor + - `servo`: Servo + - `avoidance`: Avoidance + - `rc_signal`: RC Signal + - `mavlink_signal`: MAVLink data telemetry connection - _failure_type_: - - `ok`: Publish as normal (Disable failure injection). - - `off`: Stop publishing. - - `stuck`: Report same value every time (_could_ indicate a malfunctioning sensor). - - `garbage`: Publish random noise. This looks like reading uninitialized memory. - - `wrong`: Publish invalid values (that still look reasonable/aren't "garbage"). - - `slow`: Publish at a reduced rate. - - `delayed`: Publish valid data with a significant delay. - - `intermittent`: Publish intermittently. + - `ok`: Publish as normal (Disable failure injection) + - `off`: Stop publishing + - `stuck`: Constantly report the same value which _can_ happen on a malfunctioning sensor + - `garbage`: Publish random noise. This looks like reading uninitialized memory + - `wrong`: Publish invalid values that still look reasonable/aren't "garbage" + - `slow`: Publish at a reduced rate + - `delayed`: Publish valid data with a significant delay + - `intermittent`: Publish intermittently - _instance number_ (optional): Instance number of affected sensor. 0 (default) indicates all sensors of specified type. @@ -65,7 +65,7 @@ where: To simulate losing RC signal without having to turn off your RC controller: -1. Enable the parameter [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN). +1. Enable the parameter [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN). And specifically to turn off motors also [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE). 2. Enter the following commands on the MAVLink console or SITL _pxh shell_: ```sh diff --git a/docs/zh/flight_modes/offboard.md b/docs/zh/flight_modes/offboard.md index 63e474ed76..da076bf211 100644 --- a/docs/zh/flight_modes/offboard.md +++ b/docs/zh/flight_modes/offboard.md @@ -62,6 +62,11 @@ bool thrust_and_torque bool direct_actuator ``` +:::warning +The following list shows the `OffboardControlMode` options for copter, fixed-wing, and VTOL. +For rovers see the [rover section](#rover). +::: + The fields are ordered in terms of priority such that `position` takes precedence over `velocity` and later fields, `velocity` takes precedence over `acceleration`, and so on. 第一个非零字段(从上到下) 定义了Offboard模式所需的有效估计以及可用的设定值消息。 For example, if the `acceleration` field is the first non-zero value, then PX4 requires a valid `velocity estimate`, and the setpoint must be specified using the `TrajectorySetpoint` message. @@ -90,20 +95,93 @@ Before using offboard mode with ROS 2, please spend a few minutes understanding - Velocity setpoint (`velocity` different from `NaN` and `position` set to `NaN`). Non-`NaN` values acceleration are used as feedforward terms for the inner loop controllers. - Acceleration setpoint (`acceleration` different from `NaN` and `position` and `velocity` set to `NaN`) - - 所有值都是基于NED(北, 东, 地)坐标系,位置、速度和加速的单位分别为\[m\], \[m/s\] 和\[m/s^2\] 。 + - All values are interpreted in NED (Nord, East, Down) coordinate system and the units are `[m]`, `[m/s]` and `[m/s^2]` for position, velocity and acceleration, respectively. - [px4_msgs::msg::VehicleAttitudeSetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAttitudeSetpoint.msg) - 支持以下输入组合: - quaternion `q_d` + thrust setpoint `thrust_body`. - Non-`NaN` values of `yaw_sp_move_rate` are used as feedforward terms expressed in Earth frame and in \[rad/s\]. + Non-`NaN` values of `yaw_sp_move_rate` are used as feedforward terms expressed in Earth frame and in `[rad/s]`. - - 姿态四元数表示无人机机体坐标系FRD(前、右、下) 与NED坐标系之间的旋转。 这个推力是在无人机体轴FRD坐标系下,并归一化为 \[-1, 1\] 。 + - 姿态四元数表示无人机机体坐标系FRD(前、右、下) 与NED坐标系之间的旋转。 + 这个推力是在无人机体轴FRD坐标系下,并归一化为 \[-1, 1\] 。 - [px4_msgs::msg::VehicleRatesSetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleRatesSetpoint.msg) - 支持以下输入组合: - `roll`, `pitch`, `yaw` and `thrust_body`. - - 所有值都表示在无人机体轴FRD坐标系下。 角速率(roll, pitch, yaw) 单位为\[rad/s\] ,thrust_body归一化为 \[-1, 1\]。 + - 所有值都表示在无人机体轴FRD坐标系下。 + The rates are in `[rad/s]` while thrust_body is normalized in `[-1, 1]`. + +### 无人车 + +Rover modules must set the control mode using `OffboardControlMode` and use the appropriate messages to configure the corresponding setpoints. +The approach is similar to other vehicle types, but the allowed control mode combinations and setpoints are different: + +| Category | 用法 | Setpoints | +| -------------------------------------------------------------------------------------- | ----------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| (Recommended) [Rover Setpoints](#rover-setpoints) | General rover control | [RoverPositionSetpoint](../msg_docs/RoverPositionSetpoint.md), [RoverSpeedSetpoint](../msg_docs/RoverSpeedSetpoint.md), [RoverAttitudeSetpoint](../msg_docs/RoverAttitudeSetpoint.md), [RoverRateSetpoint](../msg_docs/RoverRateSetpoint.md), [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md), [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md) | +| [Actuator Setpoints](#actuator-setpoints) | Direct actuator control | [ActuatorMotors](../msg_docs/ActuatorMotors.md), [ActuatorServos](../msg_docs/ActuatorServos.md) | +| (Deprecated) [Trajectory Setpoint](#deprecated-trajectory-setpoint) | General vehicle control | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) | + +#### Rover Setpoints + +The rover modules use a hierarchical structure to propagate setpoints: + +![Rover Control Structure](../../assets/middleware/ros2/px4_ros2_interface_lib/rover_control_structure.svg) + +The "highest" setpoint that is provided will be used within the PX4 rover modules to generate the setpoints that are below it (overriding them!). +With this hierarchy there are clear rules for providing a valid control input: + +- Provide a position setpoint **or** +- One of the setpoints on the "left" (speed **or** throttle) **and** one of the setpoints on the "right" (attitude, rate **or** steering). + All combinations of "left" and "right" setpoints are valid. + +The following are all valid setpoint combinations and their respective control flags that must be set through [OffboardControlMode](../msg_docs/OffboardControlMode.md) (set all others to _false_). +Additionally, for some combinations we require certain setpoints to be published with `NAN` values so that the setpoints of interest are not overridden by the rover module (due to the hierarchy above). +✓ are the relevant setpoints we publish, and ✗ are the setpoint that need to be published with `NAN` values. + +| Setpoint Combination | Control Flag | [RoverPositionSetpoint](../msg_docs/RoverPositionSetpoint.md) | [RoverSpeedSetpoint](../msg_docs/RoverSpeedSetpoint.md) | [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md) | [RoverAttitudeSetpoint](../msg_docs/RoverAttitudeSetpoint.md) | [RoverRateSetpoint](../msg_docs/RoverRateSetpoint.md) | [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md) | +| -------------------- | ----------------------------------------------------------- | ------------------------------------------------------------- | ------------------------------------------------------- | ------------------------------------------------------------- | ------------------------------------------------------------- | ----------------------------------------------------- | ------------------------------------------------------------- | +| 安装位置 | 位置 | ✓ | | | | | | +| Speed + Attitude | 速度 | | ✓ | | ✓ | | | +| Speed + Rate | 速度 | | ✓ | | ✗ | ✓ | | +| Speed + Steering | 速度 | | ✓ | | ✗ | ✗ | ✓ | +| Throttle + Attitude | attitude | | | ✓ | ✓ | | | +| Throttle + Rate | body_rate | | | ✓ | | ✓ | | +| Throttle + Steering | thrust_and_torque | | | ✓ | | | ✓ | + +:::info +If you intend to use the rover setpoints, we recommend using the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) instead since it simplifies the publishing of these setpoints. +::: + +#### Actuator Setpoints + +Instead of controlling the vehicle using position, speed, rate and other setpoints, you can directly control the motors and actuators using [ActuatorMotors](../msg_docs/ActuatorMotors.md) and [ActuatorServos](../msg_docs/ActuatorServos.md). +In [OffboardControlMode](../msg_docs/OffboardControlMode.md) set `direct_actuator` to _true_ and all other flags to _false_. + +:::info +This bypasses the rover modules including any limits on steering rates or accelerations and the inverse kinematics step. +We recommend using [RoverSteeringSetpoint](../msg_docs/RoverSteeringSetpoint.md) and [RoverThrottleSetpoint](../msg_docs/RoverThrottleSetpoint.md) instead for low level control (see [Rover Setpoints](#rover-setpoints)). +::: + +#### (Deprecated) Trajectory Setpoint + +:::warning +The [Rover Setpoints](#rover-setpoints) are a replacement for the [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) and we highly recommend using those instead as they have a well defined behaviour and offer more flexibility. +::: + +The rover modules support the _position_, _velocity_ and _yaw_ fields of the [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md). +However, only one of the fields is active at a time and is defined by the flags of [OffboardControlMode](../msg_docs/OffboardControlMode.md): + +| Control Mode Flag | Active Trajectory Setpoint Field | +| ----------------- | -------------------------------- | +| 位置 | 位置 | +| 速度 | 速度 | +| attitude | yaw | + +:::info +Ackermann rovers do not support the yaw setpoint. +::: ### Generic Vehicle @@ -116,8 +194,10 @@ Before using offboard mode with ROS 2, please spend a few minutes understanding - [px4_msgs::msg::ActuatorMotors](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorMotors.msg) + [px4_msgs::msg::ActuatorServos](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorServos.msg) - 直接控制电机输出和/或伺服系统(舵机)输出。 - - Currently works at lower level than then `control_allocator` module. Do not publish these messages when not in offboard mode. - - 所有值归一化为\[-1, 1\]。 For outputs that do not support negative values, negative entries map to `NaN`. + - Currently works at lower level than then `control_allocator` module. + Do not publish these messages when not in offboard mode. + - All the values normalized in `[-1, 1]`. + For outputs that do not support negative values, negative entries map to `NaN`. - `NaN` maps to disarmed. ## MAVLink 消息 @@ -207,41 +287,7 @@ Before using offboard mode with ROS 2, please spend a few minutes understanding ### 无人车 -- [SET_POSITION_TARGET_LOCAL_NED](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_LOCAL_NED) - - The following input combinations are supported (in `type_mask`): - - Position setpoint (only `x`, `y`, `z`) - - Specify the _type_ of the setpoint in `type_mask`: - - ::: info - The _setpoint type_ values below are not part of the MAVLink standard for the `type_mask` field. - :: - - 值为: - - - 12288:悬停设定值(无人机足够接近设定值时会停止)。 - - - Velocity setpoint (only `vx`, `vy`, `vz`) - - - PX4 supports the coordinate frames (`coordinate_frame` field): [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED) and [MAV_FRAME_BODY_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_BODY_NED). - -- [SET_POSITION_TARGET_GLOBAL_INT](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT) - - The following input combinations are supported (in `type_mask`): - - Position setpoint (only `lat_int`, `lon_int`, `alt`) - - - Specify the _type_ of the setpoint in `type_mask` (not part of the MAVLink standard). - 值为: - - 下面的比特位没有置位,是正常表现。 - - 12288:悬停设定值(无人机足够接近设定值时会停止)。 - - - PX4 supports the coordinate frames (`coordinate_frame` field): [MAV_FRAME_GLOBAL](https://mavlink.io/en/messages/common.html#MAV_FRAME_GLOBAL). - -- [SET_ATTITUDE_TARGET](https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET) - - 支持以下输入组合: - - Attitude/orientation (`SET_ATTITUDE_TARGET.q`) with thrust setpoint (`SET_ATTITUDE_TARGET.thrust`). - ::: info - Only the yaw setting is actually used/extracted. - -::: +Rover does not support a MAVLink offboard API (ROS2 is supported). ## Offboard参数 diff --git a/docs/zh/flight_modes_rover/api.md b/docs/zh/flight_modes_rover/api.md new file mode 100644 index 0000000000..1783ee9344 --- /dev/null +++ b/docs/zh/flight_modes_rover/api.md @@ -0,0 +1,29 @@ +# Apps & API + +The rover modules have been tested and integrated with a subset of the available [Apps & API](../middleware/index.md) methods. +We specifically provide guides for using [ROS 2](../ros2/index.md) to interface a companion computer with PX4 via [uXRCE-DDS](../middleware/uxrce_dds.md). + +| Method | 描述 | +| ---------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| [PX4 ROS 2 Interface](#px4-ros-2-interface) (Recommended) | Register a custom mode and publish [RoverSetpointTypes](../ros2/px4_ros2_control_interface.md#rover-setpoints). | +| [ROS 2 Offboard Control](#ros-2-offboard-control) | Use the PX4 internal [Offboard Mode](../flight_modes/offboard.md) and publish messages defined in [dds_topics.yaml](../middleware/dds_topics.md). | + +## PX4 ROS 2 Interface + +We recommend the use of the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) which allows you to register a custom drive mode and exposes [RoverSetpointTypes](../ros2/px4_ros2_control_interface.md#rover-setpoints). + +By using these setpoints (instead of the PX4 internal rover setpoints), you are guaranteed to send valid control inputs to your vehicle and the control flags for the setpoints you are using are automatically set for you. +Registering a custom drive mode instead of using [ROS 2 Offboard Control](#ros-2-offboard-control) additionally provides the advantages listed [here](../concept/flight_modes.md#internal-vs-external-modes). + +To get familiar with this method, read through the guide for the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) where we also provide an example app for rover. + +## ROS 2 Offboard Control + +[ROS 2 Offboard Control](../ros2/offboard_control.md) uses the PX4 internal [Offboard Mode](../flight_modes/offboard.md). + +While you can subscribe/publish to all topics specified in [dds_topics.yaml](../middleware/dds_topics.md), not all rover modules support all of these topics (see [Supported Setpoints](../flight_modes/offboard.md#rover)). +Unlike the [RoverSetpointTypes](../ros2/px4_ros2_control_interface.md#rover-setpoints) exposed through the [PX4 ROS 2 Interface](#px4-ros-2-interface), there is no guarantee that the published setpoints lead to a valid control input. + +In addition, the correct control mode flags must be set through [OffboardControlMode](../msg_docs/OffboardControlMode.md). +This requires a deeper understanding of PX4 and the structure of the rover modules. +For general information on setting up offboard mode read through [Offboard Mode](../flight_modes/offboard.md) and then consult [Supported Setpoints](../flight_modes/offboard.md#rover). diff --git a/docs/zh/frames_rover/index.md b/docs/zh/frames_rover/index.md index 79d212bdca..76b1749d4f 100644 --- a/docs/zh/frames_rover/index.md +++ b/docs/zh/frames_rover/index.md @@ -21,7 +21,7 @@ The supported frames can be seen in [Airframes Reference > Rover](../airframes/a ## Ackermann -<0/> <1/> + An Ackermann rover controls its direction by pointing the front wheels in the direction of travel — the [Ackermann steering geometry](https://en.wikipedia.org/wiki/Ackermann_steering_geometry) compensates for the fact that wheels on the inside and outside of the turn move at different rates. This kind of steering is used on most commercial vehicles, including cars, trucks etc. @@ -34,7 +34,7 @@ PX4 does not require that the vehicle uses the Ackermann geometry and will work ## Differential -<0/> <1/> + A differential rover's motion is controlled using a differential drive mechanism, where the left and right wheel speeds are adjusted independently to achieve the desired forward speed and yaw rate. Forward motion is achieved by driving both wheels at the same speed in the same direction. @@ -48,7 +48,7 @@ The differential setup also work for rovers with skid or tank steering. ## Mecanum -<0/> <1/> + A Mecanum rover is a type of mobile robot that uses Mecanum wheels to achieve omnidirectional movement. These wheels are unique because they have rollers mounted at a 45-degree angle around their circumference, allowing the rover to move not only forward and backward but also side-to-side and diagonally without needing to rotate first. Each wheel is driven by its own motor, and by controlling the speed and direction of each motor, the rover can move in any direction or spin in place. @@ -57,15 +57,17 @@ Each wheel is driven by its own motor, and by controlling the speed and directio ## See Also -- [Drive Modes](../flight_modes_rover/index.md). +- [Drive Modes](../flight_modes_rover/index.md) - [Configuration/Tuning](../config_rover/index.md) +- [Apps & API](../flight_modes_rover/api.md) - [Complete Vehicles](../complete_vehicles_rover/index.md) ## 仿真 -[Gazebo](../sim_gazebo_gz/index.md) provides simulations for ackermann and differential rovers: +PX4 provides synthetic simulation models for [Gazebo](../sim_gazebo_gz/index.md) of all three rover types to test the software and validate changes and new features: - [Ackermann rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) - [Differential rover](../sim_gazebo_gz/vehicles.md#differential-rover) +- [Mecanum rover](../sim_gazebo_gz/vehicles.md#mecanum-rover) ![Rover gazebo simulation](../../assets/airframes/rover/rover_simulation.png) diff --git a/docs/zh/middleware/uxrce_dds.md b/docs/zh/middleware/uxrce_dds.md index fbf9244522..65b014b0c1 100644 --- a/docs/zh/middleware/uxrce_dds.md +++ b/docs/zh/middleware/uxrce_dds.md @@ -389,12 +389,12 @@ While most releases should support a very similar set of messages, to be certain Note that ROS 2/DDS needs to have the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware in order to interpret the messages. The message definitions are stored in the ROS 2 interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs), and they are automatically synchronized by CI on the `main` and release branches. -Note that all the messages from PX4 source code are present in the repository, but only those listed in `dds_topics.yaml` will be available as ROS 2 topics. -Therefore, +需要注意的是,PX4 源代码中的所有消息均存在于该代码仓库中,但只有在dds_topics.yaml文件中列出的消息,才会作为 ROS 2 话题可用。 +因此 -- If you're using a main or release version of PX4 you can get the message definitions by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your workspace. -- If you're creating or modifying uORB messages you must manually update the messages in your workspace from your PX4 source tree. - Generally this means that you would update [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), clone the interface package, and then manually synchronize it by copying the new/modified message definitions from [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to its `msg` folders. +- 如果您正在使用 PX4 的主要版本或发布版本,您可以通过克隆接口包[PX4/px4_msgs](https://github.com/PX4/px4_msgs)获得消息定义。 +- 如果您要创建或修改 uORB 消息,必须从 PX4 源代码树中手动更新工作空间中的消息。 + 一般来说,这意味着您将更新 [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml),克隆接口包。 然后手动同步,将新的/修改的消息定义从 [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg)复制到它的 `msg` 文件夹。 Assuming that PX4-Autopilot is in your home directory `~`, while `px4_msgs` is in `~/px4_ros_com/src/`, then the command might be: ```sh @@ -412,13 +412,13 @@ Therefore, Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](../middleware/dds_topics.md)), at runtime, or through a parameter (which is useful for multi vehicle operations): -- One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line. - This technique can be used both in simulation and real vehicles. -- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation. +- 一种可能性是在从命令行启动[uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client)时使用 "-n" 选项。 + 这种技术既可用于模拟,也可用于实际机体。 +- 在开始模拟前,可以通过设置环境变量 `PX4_UXRCE_DDS_NS`来提供自定义命名空间 (仅限) :::info Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](../middleware/dds_topics.md) and all [service servers](#dds-ros-2-services). -Therefore, commands like: +因此,命令如下: ```sh uxrce_dds_client start -n uav_1 @@ -430,7 +430,7 @@ uxrce_dds_client start -n uav_1 PX4_UXRCE_DDS_NS=uav_1 make px4_sitl gz_x500 ``` -will generate topics under the namespaces: +将在以下命名空间下生成话题: ```sh /uav_1/fmu/in/ # for subscribers diff --git a/docs/zh/releases/main.md b/docs/zh/releases/main.md index 6166e251c5..cd60a90e55 100644 --- a/docs/zh/releases/main.md +++ b/docs/zh/releases/main.md @@ -58,7 +58,10 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### 仿真 -- TBD +- Overhaul rover simulation: + - Add synthetic differential rover model: [PX4-gazebo-models#107](https://github.com/PX4/PX4-gazebo-models/pull/107) + - Add synthetic mecanum rover model: [PX4-gazebo-models#113](https://github.com/PX4/PX4-gazebo-models/pull/113) + - Update synthetic ackermann rover model: [PX4-gazebo-models#117](https://github.com/PX4/PX4-gazebo-models/pull/117) ### Ethernet @@ -67,6 +70,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### uXRCE-DDS / ROS2 - [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [Fixed Wing lateral/longitudinal setpoint](../ros2/px4_ros2_control_interface.md#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype) (`FwLateralLongitudinalSetpointType`) and [VTOL transitions](../ros2/px4_ros2_control_interface.md#controlling-a-vtol). ([PX4-Autopilot#24056](https://github.com/PX4/PX4-Autopilot/pull/24056)). +- [PX4 ROS 2 Interface Library](../ros2/px4_ros2_control_interface.md) support for [ROS-based waypoint missions](../ros2/px4_ros2_waypoint_missions.md). ### MAVLink @@ -89,6 +93,8 @@ Please continue reading for [upgrade instructions](#upgrade-guide). ### 无人车 - Removed deprecated rover module ([PX4-Autopilot#25054](https://github.com/PX4/PX4-Autopilot/pull/25054)). +- Add support for [Apps & API](../flight_modes_rover/api.md) ([PX4-Autopilot#25074](https://github.com/PX4/PX4-Autopilot/pull/25074), [PX4-ROS2-Interface-Lib#140](https://github.com/Auterion/px4-ros2-interface-lib/pull/140)). +- Update [rover simulation](../frames_rover/index.md#simulation) ([PX4-Autopilot#25644](https://github.com/PX4/PX4-Autopilot/pull/25644)) (see [Simulation](#simulation) release note for details). ### ROS 2 diff --git a/docs/zh/ros2/index.md b/docs/zh/ros2/index.md index a99b6c3963..0e35981d71 100644 --- a/docs/zh/ros2/index.md +++ b/docs/zh/ros2/index.md @@ -6,23 +6,23 @@ 小提示 PX4 开发团队强烈建议您使用此 ROS 版本,或将现有系统迁移至此 ROS 版本! -这是最新版本的 [ROS](https://www.ros.org/) (机器人操作系统)。 +这是最新版本的 [ROS](https://www.ros.org/)(机器人操作系统)。 它在 ROS “1” 的基础上进行了显著改进,尤其能够实现与 PX4 更深度、更低延迟的集成。 ::: ROS的优势在于拥有活跃的开发者生态系统 —— 该生态系统致力于解决各类常见的机器人技术问题,同时还能调用其他为 Linux 系统编写的软件库。 -例如,它可以用于 [computer vision](../computer_vision/index.md)解决问题。 +例如,它可以用于 [计算机试图](../computer_vision/index.md) 解决问题。 ROS 2 能够实现与 PX4 极深度的集成,你可以在 ROS 2 中创建飞行模式,这些模式与 PX4 内部原生飞行模式毫无区别;同时还能以高速率直接读取和写入 PX4 内部的 uORB 主题。 (尤其)建议在以下场景中使用:从伴飞计算机进行控制与通信(且低延迟至关重要时)、需借助 Linux 系统的现有库时,或编写新的高级飞行模式时。 ROS 2 与 PX4 之间的通信使用的中间件需实现 [XRCE-DDS protocol](../middleware/uxrce_dds.md). -这个中间件将以 ROS 2 消息和类型显示 PX4 [uORB messages](../msg_docs/index.md) 会转换为 ROS 2 消息和数据类型,从而切实支持从 ROS 2 工作流与节点直接访问 PX4。 +这个中间件将以 ROS 2 消息和类型显示 PX4 [uORB messages](../msg_docs/index.md) 会转换为 ROS 2 消息和数据类型,从而切实支持从 ROS 2 工作流与节点直接访问 PX4。 中间件使用 uORB 消息定义生成代码来序列化和反序列化来处理PX4 的收发消息。 这些相同的消息定义也用于 ROS 2 应用程序中以便能够解析这些消息。 :::info -ROS 2 也可以使用 [MAVROS](https://github.com/mavlink/mavros/tree/ros2/mavros而不是 XRCE-DDS连接到 PX4。 +ROS 2 也可以使用 [MAVROS](https://github.com/mavlink/mavros/tree/ros2/mavros)而不是 XRCE-DDS连接到 PX4。 该选项受 MAVROS 项目支持(本文档未对此进行说明)。 ::: @@ -33,9 +33,9 @@ ROS 2 也可以使用 [MAVROS](https://github.com/mavlink/mavros/tree/ros2/mavro 本节的主要主题是: -- ROS 2 用户指南: PX4 视角下的 ROS 2,包括安装、设置和如何构建与 PX4 通信的 ROS 2 应用。 -- [ROS 2 离板控制示例](../ros2/offboard_control.md):一个 C++ 教程示例显示如何在 [离板模式] (../flight_modes/offboard.md) 中使用 ROS 2 节点进行位置控制。 -- [ROS 2 多车辆模拟](../ros2/multi_vehicle.md):通过单独的ROS2 代理商连接到多极PX4 模拟的说明。 +- [ROS 2 用户指南](../ros2/user_guide.md): PX4 视角下的 ROS 2,包括安装、设置和如何构建与 PX4 通信的 ROS 2 应用。 +- [ROS 2 离板控制实例](../ros2/offboard_control.md):一个 C++ 教程示例显示如何在 [离板模式] (../flight_modes/offboard.md) 中使用 ROS 2 节点进行位置控制。 +- [ROS 2 多载具模拟](../ros2/multi_vehicle.md):通过单独的ROS2 代理商连接到多极PX4 模拟的说明。 - [PX4 ROS2 接口库](../ros2/px4_ros2_interface_lib.md):一个C++ 库,它与ROS2的 PX4 交互。 可以使用 ROS 2 创建和注册飞行模式,并从 ROS2 应用程序如VIO 系统发送位置估计数。 - [ROS 2 消息翻译节点](../ros2/px4_ros2_msg_translation_node.md):一个 ROS 2 消息翻译节点,它允许在 PX4 和 ROS 2 应用程序之间共享,这些应用程序被编译成不同的消息版本。 diff --git a/docs/zh/ros2/multi_vehicle.md b/docs/zh/ros2/multi_vehicle.md index a525a32445..16f02d9deb 100644 --- a/docs/zh/ros2/multi_vehicle.md +++ b/docs/zh/ros2/multi_vehicle.md @@ -1,54 +1,54 @@ -# 使用 ROS 2 进行多车辆模拟 +# 使用 ROS 2 的多载具模拟 -[XRCE-DDS](../middleware/uxrce_dds.md) 支持多个客户端通过 UDP 协议连接到同一个代理。 +[XRCE-DDS](../middleware/uxrce_dds.md)支持多个客户端通过 UDP 协议连接到同一个代理。 这在模拟中特别有用,因为只有一个代理需要启动。 ## 设置和要求 唯一的要求是 -- 能够在不依赖 ROS 2 的情况下,使用所需的仿真器([Gazebo](../sim_gazebo_gz/multi_vehicle_simulation.md), [Gazebo Classic](../sim_gazebo_classic/multi_vehicle_simulation.md#multiple-vehicle-with-gazebo-classic), [FlightGear](../sim_flightgear/multi_vehicle.md) 和 [JMAVSim](../sim_jmavsim/multi_vehicle.md))运行多车辆仿真[multi-vehicle simulation](../simulation/multi-vehicle-simulation.md)。 -- 能够在单一车辆仿真中使用ROS 2(机器人操作系统 2) +- 能够在不依赖 ROS 2 的情况下,使用所需的仿真器([Gazebo](../sim_gazebo_gz/multi_vehicle_simulation.md), [Gazebo Classic](../sim_gazebo_classic/multi_vehicle_simulation.md#multiple-vehicle-with-gazebo-classic), [FlightGear](../sim_flightgear/multi_vehicle.md) and [JMAVSim](../sim_jmavsim/multi_vehicle.md))运行多载具模拟 [multi-vehicle simulation](../simulation/multi-vehicle-simulation.md) 。 +- 能够在单一载具模拟中使用 [ROS 2](../ros2/user_guide.md) ## 工作原理 -在仿真中,每个 PX4 实例都会获得一个唯一的px4_instance编号,编号从0开始。 +在模拟中,每个 PX4 实例都会获得一个唯一的`px4_instance`编号,编号从`0`开始。 该值用于为 [UXRCE_DDS_KEY](../advanced_config/parameter_reference.md#UXRCE_DDS_KEY)分配一个唯一值: ```sh -参数设置 UXRCE_DDS_KEY $(px4_instance+1)) +参数设置UXRCE_DDS_KEY $((px4_instance+1)) ``` :::info -通过这种方式,UXRCE_DDS_KEY 将始终与 [MAV_SYS_ID] 保持一致(../advanced_config/parameter_reference.md#MAV_SYS_ID) +通过这种方式, `UXRCE_DDS_KEY` 将始终与 [MAV_SYS_ID] 保持一致(../advanced_config/parameter_reference.md#MAV_SYS_ID) ::: -此外,当 px4_instance 大于 0 时,会添加一个格式为 px4_$px4_instance 的唯一 ROS 2 命名空间前缀: +此外,当 `px4_instance` 大于 0 时,会添加一个格式为 `px4_$px4_instance` 的唯一 ROS 2[namespace prefix](../middleware/uxrce_dds.md#customizing-the-namespace): ```sh uxrce_dds_ns="-n px4_$px4_instance" ``` :::info -环境变量 PX4_UXRCE_DDS_NS 若已设置,将覆盖上文所述的命名空间行为。 +环境变量`PX4_UXRCE_DDS_NS` 若已设置,将覆盖上文所述的命名空间行为。 ::: -第一个实例(px4_instance=0)没有额外的命名空间,此举是为了与真实载具上 xrce-dds 客户端的默认行为保持一致。 -这种不匹配可以通过手动使用 `PX4_UXRCE_DDS_NS` 来修复,或者通过从索引 `1` 中添加车辆而不是 `0` (这是Gazebo Classic的 [sitl_multiple_run.sh](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/simulation/gazebo-classic/sitl_multiple_run.sh) 的默认行为)。 +第一个实例(`px4_instance=0`)没有额外的命名空间,此举是为了与真实载具上 xrce-dds 客户端的默认行为保持一致。 +这种不匹配可以通过手动使用 `PX4_UXRCE_DDS_NS` 来修复,或者通过从索引 `1` 中添加车辆而不是 `0` (这是Gazebo Classic的 [sitl_multiple_run.sh](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/simulation/gazebo-classic/sitl_multiple_run.sh) 的默认行为)。 模拟中的默认客户端配置概述如下: -| `PX4_UXRCE_DDS_NS` | `px4_instance` | `UXRCE_DDS_KEY` | 客户端命名空间 | +| `PX4_UXRCE_DDS_NS` | `px4_instance` | `UXRCE_DDS_KEY` | client namespace | | ------------------ | -------------- | ---------------- | --------------------- | -| 未提供 | 0 | `px4_instance+1` | 无 | -| 已提供 | 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | -| 未提供 | > 0 | `px4_instance+1` | `px4_${px4_instance}` | -| 已提供 | > 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | +| not provided | 0 | `px4_instance+1` | 无 | +| provided | 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | +| not provided | > 0 | `px4_instance+1` | `px4_${px4_instance}` | +| provided | > 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | ## 调整 `target_system` 值 -PX4 只在他们的 `target_system` 字段为 0 (路由通信) 或与 `MAV_SYS_ID` 一致时,才接受 [VehicleCommand](../msg_docs/VehicleCommand.md)。 +PX4 只在他们的 `target_system` 字段为 0`(路由通信) 或与`MAV_SYS_ID` 一致时,才接受[VehicleCommand](../msg_docs/VehicleCommand.md)。 在所有其他情况下,信息都被忽视。 -因此,当 ROS 2 节点需向 PX4 发送 VehicleCommand(载具指令)消息时,必须确保消息中填写了合适的 target_system(目标系统)字段值。 +因此,当 ROS 2 节点需向 PX4 发送`VehicleCommand`消息时,必须确保消息中填写了合适的`target_system\`字段值。 -例如,若你想向 px4_instance=2 的第三台飞行器发送指令,则需要在所有 VehicleCommand消息中设置 target_system=3。 +例如,若你想向 `px4_instance=2` 的第三台飞行器发送指令,则需要在所有`VehicleCommand`消息中设置 `target_system=3`。 diff --git a/docs/zh/ros2/offboard_control.md b/docs/zh/ros2/offboard_control.md index 03dcfc63dd..681d4bd155 100644 --- a/docs/zh/ros2/offboard_control.md +++ b/docs/zh/ros2/offboard_control.md @@ -1,6 +1,6 @@ # ROS 2 Offboard 控制示例 -以下的 C++ 示例展示了如何在 [离板模式] (../flight_modes/offboard.md) 中从 ROS 2 节点进行位置控制。 +以下的 C++ 示例展示了如何在 [离板模式] (../flight_modes/offboard.md) 中从 ROS 2 节点进行多轴位置控制。 示例将首先发送设置点、进入offboard模式、解锁、起飞至5米,并悬停等待。 虽然简单,但它显示了如何使用offboard控制以及如何向无人机发送指令。 @@ -16,13 +16,13 @@ _Offboard_ control is dangerous. ROS 与 PX4 存在若干不同的预设(假设),尤其是在坐标系约定([frame conventions])方面../ros/external_position_estimation.md#reference-frames-and-ros 当主题发布或订阅时,坐标系类型之间没有隐含转换! -这个例子按照PX4的预期在NED坐标系下发布位置。 +这个例子按照 PX4 的预期在NED坐标系下发布位置。 若要订阅来自在不同框架内发布的节点的数据(例如ENU, 这是ROS/ROS 2中的标准参考框架,使用 [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/src/lib/frame_transforms.cpp)库中的辅助函数。 ::: ## 小試身手 -请遵循 ROS 2 用户指南 (../ros2/user_guide.md)中的说明,完成安装 PX4和运行模拟器,安装 ROS 2和启动 XRCE-DDS 代理(Agent)。 +按照 [ROS 2 User Guide](../ros2/user_guide.md)中的说明来安装PX 并运行多轴模拟器,安装ROS 2, 并启动XRCE-DDS代理。 之后,我们可参照 ROS 2 用户指南 > 构建 ROS 2 工作空间 (../ros2/user_guide.md#build-ros-2-workspace)中的相似的步骤来运行这个例子。 @@ -95,7 +95,7 @@ ROS 与 PX4 存在若干不同的预设(假设),尤其是在坐标系约 ros2 run px4_ros_com offboard_control ``` -飞行器将解锁、起飞至5米并悬停等待(永久)。 +飞行器将解锁、起飞至 5 米并悬停等待(永久)。 ## 实现 @@ -133,7 +133,7 @@ timer_ = this->create_wall_timer(100ms, timer_callback); ``` 循环运行在一个100毫秒计时器。 -在最初的 10 个循环中,它会调用 publish_offboard_control_mode() 和 publish_trajectory_setpoint() 这两个函数,向 PX4 发送 OffboardControlMode(离板控制模式)(../msg_docs/OffboardControlMode.md) 和 TrajectorySetpoint(轨迹设定点)(../msg_docs/TrajectorySetpoint.md) 消息。 +在最初的 10 个循环中,它会调用 `publish_offboard_control_mode()` 和 `publish_trajectory_setpoint()` 这两个函数,向 PX4 发送 OffboardControlMode[OffboardControlMode](../msg_docs/OffboardControlMode.md) 和 [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) 消息。 OffboardControlMode消息会持续发送,以便 PX4 切换到离板模式后允许解锁;而 TrajectorySetpoint消息会被忽略(直到载具处于离板模式) 10 个循环后,会调用 publish_vehicle_command() 函数切换至离板模式,并调用 arm() 函数对载具进行解锁。 diff --git a/docs/zh/ros2/px4_ros2_control_interface.md b/docs/zh/ros2/px4_ros2_control_interface.md index 3fa4820ae6..5be7fedde0 100644 --- a/docs/zh/ros2/px4_ros2_control_interface.md +++ b/docs/zh/ros2/px4_ros2_control_interface.md @@ -327,7 +327,7 @@ private: }; ``` -- `[1]`: 首先创建一个从 [`px4_ros2::ModeExecutorBase`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1ModeExecutorBase.html) 继承的类。 +- `[1]`: 首先创建一个继承 [`px4_ros2::ModeExecutorBase`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1ModeExecutorBase.html)。 - `[2]`: 构造函数采用与执行器相关联的自定义模式,并传递给`ModeExecutorBase`的构造函数。 - `[3]`: 我们为想要运行的状态定义一个枚举。 - `[4]`: `onActivate` 在执行器激活时被调用。 此时,我们可以开始遍历这些状态了。 @@ -344,9 +344,10 @@ private: 以下章节提供了支持的设置点类型列表: -- [MulticopterGotoSetpointType](#go-to-setpoint-multicoptergotosetpointtype): Smooth position and (optionally) heading control -- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): Direct control of lateral and longitudinal fixed wing dynamics +- [MulticopterGotoSetpointType](#go-to-setpoint-multicoptergotosetpointtype): 平滑的位置控制以及(可选的)航向控制 +- [FwLateralLongitudinalSetpointType](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype): 对横向和纵向固定翼动态的直接控制 - [DirectActuatorsSetpointType](#direct-actuator-control-setpoint-directactuatorssetpointtype):直接控制发动机和飞行地面servo setpoints +- [Rover Setpoints](#rover-setpoints): Direct access to rover control setpoints (Position, Speed, Attitude, Rate, Throttle and Steering). :::tip 其他设置点类型目前是实验性的,可在以下网址找到:[px4_ros2/control/setpoint_types/experimental](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/experimental)。 @@ -354,18 +355,20 @@ private: 您可以通过添加一个从 `px4_ros2::SetpointBase` 继承的类来添加您自己的 setpoint 类型, 根据设置点的要求设置配置标志,然后发布任何包含设置点的主题。 ::: -#### Go-to Setpoint (MulticopterGotoSetpointType) +#### 转到设置点 (MulticopterGotoSetpointType) + + :::info -This setpoint type is currently only supported for multicopters. +当前,此设定点类型仅支持多旋翼飞行器。 ::: -Smoothly control position and (optionally) heading setpoints with the [`px4_ros2::MulticopterGotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp) setpoint type. -The setpoint type is streamed to FMU based position and heading smoothers formulated with time-optimal, maximum-jerk trajectories, with velocity and acceleration constraints. +可通过[`px4_ros2::MulticopterGotoSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp)设定点类型,对位置设定点以及(可选的)航向设定点进行平滑控制。 +设定点类型会被传输至飞控主模块(FMU),该模块基于采用时间最优、最大加加速度轨迹构建的位置及航向平滑器。 -There is also a [`px4_ros2::MulticopterGotoGlobalSetpointType`](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp) class that allows to send setpoints in global coordinates. +还有一个 [\`px4_ros2::MulticopterGotoGlobalSetpootType'(https://github.com/Auterion/px4-ros2-interface-lib/blob/main/px4_ros2_cpp/include/px4_ros2/control/setpoint_types/multicopter/goto.hpp), 该类支持在全局坐标系下发送设定点。 最简单的用法就是直接向update method中输入一个3D 位置 @@ -551,13 +554,47 @@ _fw_lateral_longitudinal_setpoint->update(setpoint_s, config_s); 若你想控制的执行器并非用于控制飞行器的运动(例如,而是用于控制有效载荷舵机),请参阅 [below](#controlling-an-independent-actuator-servo)。 ::: +#### Rover Setpoints + + + +The rover modules use a hierarchical structure to propagate setpoints: + +![Rover Control Structure](../../assets/middleware/ros2/px4_ros2_interface_lib/rover_control_structure.svg) + +:::info +The "highest" setpoint that is provided will be used within the PX4 rover modules to generate the setpoints that are below it (Overriding them!). +With this hierarchy there are clear rules for providing a valid control input: + +- Provide a position setpoint, **or** +- One of the setpoints on the "left" (speed **or** throttle) **and** one of the setpoints on the "right" (attitude, rate **or** steering). All combinations of "left" and "right" setpoints are valid. + +For ease of use we expose these valid combinations as new SetpointTypes. +::: + +The RoverSetpointTypes exposed through the control interface are combinations of these setpoints that lead to a valid control input: + +| SetpointType | 安装位置 | Speed | 油门 | Attitude | 频率 | Steering | Control Flags | +| ----------------------------------------------------------------------------------------------------------------------------------- | --------------------------- | ------------------------------------------------ | ------------------------------------------------ | ------------------------------------------------ | ------------------------------------------------ | ------------------------------------------------ | ------------------------------------------------------ | +| [RoverPosition](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverPositionSetpointType.html#details) | ✓ | (✓) | (✓) | (✓) | (✓) | (✓) | Position, Velocity, Attitude, Rate, Control Allocation | +| [RoverSpeedAttitude](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverSpeedAttitudeSetpointType.html) | | ✓ | (✓) | ✓ | (✓) | (✓) | Velocity, Attitude, Rate, Control Allocation | +| [RoverSpeedRate](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverSpeedRateSetpointType.html) | | ✓ | (✓) | | ✓ | (✓) | Velocity, Rate, Control Allocation | +| [RoverSpeedSteering](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverSpeedSteeringSetpointType.html) | | ✓ | (✓) | | | ✓ | Velocity, Control Allocation | +| [RoverThrottleAttitude](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverThrottleAttitudeSetpointType.html) | | | ✓ | ✓ | (✓) | (✓) | Attitude, Rate, Control Allocation | +| [RoverThrottleRate](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverThrottleRateSetpointType.html) | | | ✓ | | ✓ | (✓) | Rate, Control Allocation | +| [RoverThrottleSteering](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1RoverThrottleSteeringSetpointType.html) | | | ✓ | | | ✓ | Control Allocation | + +✓ are the setpoints we publish, and (✓) are generated internally by the PX4 rover modules according to the hierarchy above. + +An example for a rover specific drive mode using the `RoverSpeedAttitudeSetpointType` is provided [here](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/rover_velocity). + ### 控制VTOL 要在外部飞行模式下控制VTOL,需确保根据当前飞行配置返回正确的设定值类型: -- 多旋翼模式:使用与多旋翼控制兼容的设定值类型。 For example: either the [`MulticopterGotoSetpointType`](#go-to-setpoint-multicoptergotosetpointtype) or the [`TrajectorySetpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html). +- 多旋翼模式:使用与多旋翼控制兼容的设定值类型。 例如:要么[`MulticopterGotoSetpootType`](#go-to-setpoint-multicoptergotosetpointtype) 要么[`TrattorySettpointType`](https://auterion.github.io/px4-ros2-interface-lib/classpx4__ros2_1_1TrajectorySetpointType.html)。 - 固定翼形模式:使用 [`FwLateralLongitudinalSetpointType` ](#fixed-wing-lateral-and-longitudinal-setpoint-fwlaterallongitudinalsetpointtype)。 只要VTOL在整个外部模式期间始终处于多旋翼模式或固定翼模式中的任意一种,就无需额外处理。 diff --git a/docs/zh/ros2/px4_ros2_interface_lib.md b/docs/zh/ros2/px4_ros2_interface_lib.md index 5be98766c8..e73f8efffe 100644 --- a/docs/zh/ros2/px4_ros2_interface_lib.md +++ b/docs/zh/ros2/px4_ros2_interface_lib.md @@ -14,10 +14,7 @@ Experimental 1. [Control Interface](./px4_ros2_control_interface.md) 允许开发者创建并动态注册使用 ROS2 编写的模式。 它为发送不同类型的设置点提供了课程,涵盖范围从高级导航任务一直到直接执行器控制。 2. [导航界面](./px4_ros2_navigation_interface.md) 允许从ROS 2应用程序(如VIO系统)向PX4发送车辆位置估计数。 - - +3. [Waypoint Missions](./px4_ros2_waypoint_missions.md) 允许航点飞行任务完全在ROS2中运行。 ## 在 ROS 2 工作区中安装 diff --git a/docs/zh/ros2/px4_ros2_msg_translation_node.md b/docs/zh/ros2/px4_ros2_msg_translation_node.md index c496de825e..f60083a53e 100644 --- a/docs/zh/ros2/px4_ros2_msg_translation_node.md +++ b/docs/zh/ros2/px4_ros2_msg_translation_node.md @@ -1,6 +1,6 @@ # PX4 ROS 2 消息翻译节点 -<0/> <1/> + 消息翻译节点允许针对不同版本的 PX4 消息编译的 ROS 2 应用程序与更新版本的 PX4 交互。 反之亦然,而不必更改应用程序或PX4一侧。 diff --git a/docs/zh/ros2/px4_ros2_waypoint_missions.md b/docs/zh/ros2/px4_ros2_waypoint_missions.md new file mode 100644 index 0000000000..8fcd7986f4 --- /dev/null +++ b/docs/zh/ros2/px4_ros2_waypoint_missions.md @@ -0,0 +1,190 @@ +# PX4 ROS 2 Waypoint Missions + + + +The [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) provides a high-level interface for executing ROS-based waypoint missions in ROS 2. +The main use-case is for creating missions where a custom behavior is required, such as a pickup action within a mission. + +:::warning +ROS 2 missions are not compatible with MAVLink mission definitions, plan files, or ground stations. +They completely bypass the existing PX4 mission mode and waypoint logic, and cannot be planned or displayed within a ground station. +::: + +ROS 2 waypoint missions are effectively special PX4 ROS 2 custom modes that are run based on the content of a [JSON mission definition](#mission-definition). +Mission definitions can contain actions that reference existing PX4 modes, such as Takeoff mode or RTL, and can also be extended with arbitrary custom actions written in ROS. +A [mode executor](px4_ros2_control_interface.md#mode-executor) is used to schedule the modes. + +Mission definitions can be hard coded in the custom mission mode (either in code or statically loaded from a JSON string), or directly generated within the application. +They can also be dynamically loaded based on modification of a particular JSON file — this allows for building a more generic mission framework with a fixed set of custom actions. +The file can then be written by any other application, for example a HTTP or MAVFTP server. + +The current implementation only supports multicopters but is designed to be extendable to any other vehicle type. + +## Comparison to PX4/MAVLink Missions + +There are some benefits and drawbacks to using ROS-based missions, which are provided in the following paragraphs. + +### Benefits + +- Allows to extend mission capabilities by registering custom actions. +- More control over how the mission is executed. + A custom trajectory executor can be implemented, which can use any of the existing PX4 setpoint types to track the trajectory. +- Reduced complexity on the flight controller side by running non-safety-critical and non-real-time code on a more high-level companion computer. +- It can be extended to support other trajectory types, like Bezier or Dubin curves. + +### Drawbacks + +- QGroundControl currently does not display the mission or progress during execution, and cannot upload or download a mission. + Therefore you will need another mechanism to provide a mission, such as from a web server, a custom GCS, or by generating it directly inside the application. +- The current implementation only supports multicopters (it uses the [GotoSetpointType](../ros2/px4_ros2_control_interface.md#go-to-setpoint-gotosetpointtype), which only works for multicopters, and VTOL in MC mode). + It is designed to be extendable to any other vehicle type. + +## 综述 + +This diagram provides a conceptual overview of the main classes and their interactions: + +![Waypoint missions overview diagram](../../assets/middleware/ros2/px4_ros2_interface_lib/waypoint_missions.svg) + + + +Missions can be defined in [JSON](#mission-definition), either as a file, or directly inside the application. +There is a file change monitor (`MissionFileMonitor`), that can be used to automatically load a mission from a specific file whenever it is created by another application (e.g. upload via MAVFTP or a cloud service). + +The **`MissionExecutor`** class contains the state machine to progress the mission index, and is at the core of the implementation: + +- Internally, it builds on top of the [Modes and Mode Executors](px4_ros2_control_interface.md#overview) and registers itself through a custom mode and executor with PX4. +- It handles switching in and out of missions: it gets activated when the user switches to the custom mode that represents the mission and the vehicle is armed. + The mode name can be customized (`My Mission` in the example below). + The mission can be paused, which makes the vehicle switch into _Hold mode_. + To resume the mission, the custom mode has to be selected again. +- When an action switches into another mode (for example Takeoff), QGroundControl will display this mode until it is completed. + The mission executor will then automatically continue. +- Custom actions can be registered. +- The mission can be set. + It then checks that all the actions which the mission defines are available and can be run. +- The state can be stored persistently by providing a file name, allowing for battery swapping. + +The **`ActionInterface`** is an interface class for custom actions. +They are identified by a name, and any number of these can be registered with the `MissionExecutor`. +A custom action is then run whenever a mission item with matching name is executed, and any extra arguments from the JSON definition are passed as arguments (for example an altitude for a takeoff action). +Actions can call other actions, run any mode (PX4 or external by its ID), run a trajectory, or run any other external action before deciding when to continue the mission. + +There is a set of default actions, for example for RTL, Land, etc. +These simply trigger the corresponding PX4 mode. +They can be disabled or replaced with custom implementations. +There are also some special actions (which can be replaced as well): + +- `OnFailure`: this is called in case of a failure, e.g. a mode switch failed, a non-existing action is called (by another action) or by an explicit call to `MissionExecutor::abort()`. + The default is to run RTL, with fallback to Land. +- `OnResume`: this is called when resuming a mission (either from the ground or in-air). + It handles a number of cases: + - when called with an argument `action="storeState"`: this can be used to store the current position when the mission is deactivated, so it can be resumed from the same position. + Currently it does not store anything. + - otherwise, when called without a valid mission index or 0, it directly continues. + - otherwise, when called while in-air, it also directly continues. + - otherwise, if landed and if the current mission item is an action that supports resuming from landed, it continues to let the action handle the resuming. + - otherwise, if landed, it finds the takeoff action from the mission, runs it, and then flies to the previous waypoint from the current index to continue the mission. +- `ChangeSettings`: this can be used to change the mission settings, such as the velocity. + The settings are applied to all following items in the mission. + +The **`TrajectoryExecutorInterface`** is an interface class to execute segments of a trajectory. +It can use any setpoint that PX4 and the current vehicle supports for tracking the trajectory. +This class is vehicle-type specific. +The current default implementation (`multicopter::WaypointTrajectoryExecutor`) uses a Goto setpoint (and thus is limited to multicopters). +The default can be replaced with a custom implementation. + +## 用法 + +The following provides a small example. +It defines a custom action and a mission that uses it. + +```c++ +class CustomAction : public px4_ros2::ActionInterface { +public: + CustomAction(px4_ros2::ModeBase & mode) : _node(mode.node()) { } + + std::string name() const override {return "customAction";} + + void run( + const std::shared_ptr & handler, + const px4_ros2::ActionArguments & arguments, + const std::function & on_completed) override + { + RCLCPP_INFO(_node.get_logger(), "Running custom action"); + // Do something... + + on_completed(); + } +private: + rclcpp::Node & _node; +}; + +class MyMission { +public: + MyMission(const std::shared_ptr & node) : _node(node) + { + const auto mission = px4_ros2::Mission(nlohmann::json::parse(R"( + { + "version": 1, + "mission": { + "items": [ + { + "type": "takeoff" + }, + { + "type": "navigation", + "navigationType": "waypoint", + "x": 47.3977419, + "y": 8.5455939, + "z": 500, + "frame": "global" + }, + { + "type": "navigation", + "navigationType": "waypoint", + "x": 47.39791657, + "y": 8.54595214, + "z": 500, + "frame": "global" + }, + { + "type": "customAction" + }, + { + "type": "rtl" + } + ] + } + } +)")); + _mission_executor = std::make_unique("My Mission", + px4_ros2::MissionExecutor::Configuration().addCustomAction(), *node); + + if (!_mission_executor->doRegister()) { + throw std::runtime_error("Failed to register mission executor"); + } + _mission_executor->setMission(mission); + + _mission_executor->onProgressUpdate([&](int current_index) { + RCLCPP_INFO(_node->get_logger(), "Current mission index: %i", current_index); + }); + _mission_executor->onCompleted([&] { + RCLCPP_INFO(_node->get_logger(), "Mission completed callback"); + }); + } + +private: + std::shared_ptr _node; + std::unique_ptr _mission_executor; +}; +``` + +A full example with a few custom actions can be found under [github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/mission/include](https://github.com/Auterion/px4-ros2-interface-lib/tree/main/examples/cpp/modes/mission/include). + +## Mission Definition + +The mission JSON file can contain mission defaults and a list of mission items, including user-defined types with custom arguments. +Waypoint coordinates currently need to be defined in global frame, and other frame types might be added in future. + +The schema can be found under [github.com/Auterion/px4-ros2-interface-lib/blob/main/mission/schema.yaml](https://github.com/Auterion/px4-ros2-interface-lib/blob/main/mission/schema.yaml). +It provides more details and can be used to validate a JSON file. diff --git a/docs/zh/ros2/user_guide.md b/docs/zh/ros2/user_guide.md index 4fe01ae40d..61f68b440f 100644 --- a/docs/zh/ros2/user_guide.md +++ b/docs/zh/ros2/user_guide.md @@ -376,7 +376,7 @@ accelerometer_integral_dt: 4739 #### (可选) 启动转化节点 -<0/> <1/> + 此示例由 PX4 和ROS 2 版本构建,它们使用相同的消息定义。 若你要使用不兼容的 [message versions](../middleware/uorb.md#message-versioning),则在运行示例之前,还需要安装并运行[Message Translation Node](./px4_ros2_msg_translation_node.md): @@ -448,60 +448,60 @@ See [REP105: Coordinate Frames for Mobile Platforms](https://www.ros.org/reps/re ![Reference frames](../../assets/lpe/ref_frames.png) -The FRD (NED) conventions are adopted on **all** PX4 topics unless explicitly specified in the associated message definition. -Therefore, ROS 2 nodes that want to interface with PX4 must take care of the frames conventions. +除非在相关消息定义中明确指定,否则所有PX4 话题均采用 FRD(即 NED)坐标系约定。 +因此,想要与 PX4 进行交互的 ROS 2 节点,必须妥善处理坐标系约定问题。 -- To rotate a vector from ENU to NED two basic rotations must be performed: - - first a pi/2 rotation around the `Z`-axis (up), - - then a pi rotation around the `X`-axis (old East/new North). +- 要将一个向量从ENU坐标系旋转到NED坐标系,必须执行两个基本旋转操作: + - 首先是绕 Z 轴(朝上方向)旋转 π/2 弧度。 + - 然后是绕 X 轴(原东向 / 新北向)旋转 π 弧度 -- To rotate a vector from NED to ENU two basic rotations must be performed: +- 要将一个向量从NED坐标系旋转到ENU坐标系,必须执行两个基本旋转操作: -- - first a pi/2 rotation around the `Z`-axis (down), - - then a pi rotation around the `X`-axis (old North/new East). Note that the two resulting operations are mathematically equivalent. +- - 首先是绕 Z 轴(朝下方向)旋转 π/2 弧度。 + - 然后是绕 X 轴(原北向 / 新东向)旋转 π 弧度。 需注意,这两种最终得到的操作在数学上是等效的 -- To rotate a vector from FLU to FRD a pi rotation around the `X`-axis (front) is sufficient. +- 将向量从 FLU坐标系旋转到 FRD坐标系,仅需绕 X 轴(朝前方向)旋转 π 弧度即可。 -- To rotate a vector from FRD to FLU a pi rotation around the `X`-axis (front) is sufficient. +- 将向量从 FRD坐标系旋转到 FLU坐标系,仅需绕 X 轴(朝前方向)旋转 π 弧度即可。 -Examples of vectors that require rotation are: +需要进行旋转处理的向量示例包括: -- all fields in [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) message; ENU to NED conversion is required before sending them. -- all fields in [VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md) message; FLU to FRD conversion is required before sending them. +- [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md)消息中的所有字段;发送这些字段前,需先将其从 ENU坐标系转换为 NED坐标系。 +- [VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md)消息中的所有字段;发送这些字段前,需先将其从 FLU坐标系转换为 FRD坐标系。 -Similarly to vectors, also quaternions representing the attitude of the vehicle (body frame) w.r.t. the world frame require conversion. +与向量类似,用于表示飞行器(机体坐标系)相对于(w.r.t.)姿态的四元数也是如此。 (相对于)世界坐标系(的四元数)需要进行转换。 -[PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) provides the shared library [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/include/px4_ros_com/frame_transforms.h) to easily perform such conversions. +[PX4/px4_ros_com](https://github.com/PX4/px4_ros_com) 提供了名为 [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/include/px4_ros_com/frame_transforms.h)的共享库,可便捷地执行此类转换操作。 -### ROS, Gazebo and PX4 time synchronization +### ROS, Gazebo 和 PX4 时间同步 -By default, time synchronization between ROS 2 and PX4 is automatically managed by the [uXRCE-DDS middleware](https://micro-xrce-dds.docs.eprosima.com/en/latest/time_sync.html) and time synchronization statistics are available listening to the bridged topic `/fmu/out/timesync_status`. -When the uXRCE-DDS client runs on a flight controller and the agent runs on a companion computer this is the desired behavior as time offsets, time drift, and communication latency, are computed and automatically compensated. +默认情况下,ROS 2 与 PX4 之间的时间同步由[uXRCE-DDS middleware](https://micro-xrce-dds.docs.eprosima.com/en/latest/time_sync.html) 自动管理;若需查看时间同步统计信息,可监听已桥接的话题 /fmu/out/timesync_status。 +当 uXRCE-DDS 客户端运行在飞控器上,且代理运行在机载计算机上时,这便是理想的运行状态 —— 此时时间偏移、时间漂移以及通信延迟会被自动计算并补偿。 -For Gazebo simulations the GZBridge sets the PX4 time on every sim step (see [Change simulation speed](../sim_gazebo_gz/index.md#change-simulation-speed)). -Note that this is different from the [simulation lockstep](../sim_gazebo_classic/index.md#lockstep) procedure adopted with Gazebo Classic. +在 Gazebo 仿真中,GZBridge 会在每个仿真步长(sim step)为 PX4 设置时间[Change simulation speed](../sim_gazebo_gz/index.md#change-simulation-speed)。 +需注意,这与 Gazebo Classic所采用的仿真锁步[simulation lockstep](../sim_gazebo_classic/index.md#lockstep)流程不同。 -ROS2 users have then two possibilities regarding the [time source](https://design.ros2.org/articles/clock_and_time.html) of their nodes. +对于 ROS 2 用户而言,其节点的[time source](https://design.ros2.org/articles/clock_and_time.html)有两种选择。 -#### ROS2 nodes use the OS clock as time source +#### ROS2 节点使用操作系统时钟作为时间源 -This scenario, which is the one considered in this page and in the [offboard_control](./offboard_control.md) guide, is also the standard behaviour of the ROS2 nodes. -The OS clock acts as time source and therefore it can be used only when the simulation real time factor is very close to one. -The time synchronizer of the uXRCE-DDS client then bridges the OS clock on the ROS2 side with the Gazebo clock on the PX4 side. -No further action is required by the user. +本文档以及[offboard_control](./offboard_control.md)指南中所采用的便是此场景,同时,该场景也是 ROS 2 节点的标准行为 +操作系统时钟作为时间来源,因此它只能在模拟实时系数非常接近时才能使用。 +uXRCE-DDS 客户端的时间同步器随后会将 ROS 2 端的操作系统时钟(OS clock)与 PX4 端的 Gazebo 时钟进行桥接同步。 +用户不需要进一步操作。 -#### ROS2 nodes use the Gazebo clock as time source +#### ROS2 节点使用 Gazebo 时钟作为时间源 -In this scenario, ROS2 also uses the Gazebo `/clock` topic as time source. -This approach makes sense if the Gazebo simulation is running with real time factor different from one, or if ROS2 needs to directly interact with Gazebo. -On the ROS2 side, direct interaction with Gazebo is achieved by the [ros_gz_bridge](https://github.com/gazebosim/ros_gz) package of the [ros_gz](https://github.com/gazebosim/ros_gz) repository. +在这种情况下,ROS2还使用Gazebo\`/时钟主题作为时间来源。 +若 Gazebo 仿真的实时因子(real time factor)不为 1,或 ROS 2 需直接与 Gazebo 交互,则该方法具有合理性。 +在 ROS 2 端,可通过[ros_gz](https://github.com/gazebosim/ros_gz)代码仓库中的[ros_gz_bridge](https://github.com/gazebosim/ros_gz) 功能包,实现与 Gazebo 的直接交互。 -Use the following commands to install the correct ROS 2/gz interface packages (not just the bridge) for the ROS2 and Gazebo version(s) supported by PX4. +请使用以下命令,为 PX4 所支持的 ROS 2 和 Gazebo 版本安装正确的 ROS 2/gz 接口功能包(不仅限于桥接功能包)。 :::: tabs :::tab humble -To install the bridge for use with ROS 2 "Humble" and Gazebo Harmonic (on Ubuntu 22.04): +在 Ubuntu 22.04 系统上,若需安装用于搭配 ROS 2 “Humble”与 Gazebo Harmonic的桥接功能包,可执行以下操作: ```sh sudo apt install ros-humble-ros-gzharmonic @@ -510,9 +510,9 @@ sudo apt install ros-humble-ros-gzharmonic ::: :::tab foxy -First you will need to [install Gazebo Garden](../sim_gazebo_gz/index.md#installation-ubuntu-linux), as by default Foxy comes with Gazebo Classic 11. +首先,您需要 [install Gazebo Garden](../sim_gazebo_gz/index.md#installation-ubuntu-linux),因为默认情况下,Foxy预装的是 Gazebo Classic 11 -Then to install the interface packages for use with ROS 2 "Foxy" and Gazebo (Ubuntu 20.04): +接下来,若要在 Ubuntu 20.04 系统上安装用于搭配 ROS 2 "Foxy"与 Gazebo的接口功能包,操作如下: ```sh sudo apt install ros-foxy-ros-gzgarden @@ -523,40 +523,40 @@ sudo apt install ros-foxy-ros-gzgarden :::: :::info -The [repo](https://github.com/gazebosim/ros_gz#readme) and [package](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_bridge#readme) READMEs show the package versions that need to be installed depending on your ROS2 and Gazebo versions. +[repo](https://github.com/gazebosim/ros_gz#readme) 和 [package](https://github.com/gazebosim/ros_gz/tree/ros2/ros_gz_bridge#readme) README显示了需要安装的软件包版本,取决于您的 ROS2 和 Gazebo 版本。 ::: -Once the packages are installed and sourced, the node `parameter_bridge` provides the bridging capabilities and can be used to create an unidirectional `/clock` bridge: +功能包安装并完成环境配置后,parameter_bridge节点会提供桥接能力,可用于创建一个单向的/clock桥接。 ```sh ros2 run ros_gz_bridge parameter_bridge /clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock ``` -At this point, every ROS2 node must be instructed to use the newly bridged `/clock` topic as time source instead of the OS one, this is done by setting the parameter `use_sim_time` (of _each_ node) to `true` (see [ROS clock and Time design](https://design.ros2.org/articles/clock_and_time.html)). +此时,必须指示每个 ROS 2 节点使用新桥接的/clock话题作为时间源,而非操作系统时钟(OS clock);要实现这一点,需将(每个节点的)use_sim_time参数设置为true(详见[ROS clock and Time design](https://design.ros2.org/articles/clock_and_time.html))。 -This concludes the modifications required on the ROS2 side. On the PX4 side, you are only required to stop the uXRCE-DDS time synchronization, setting the parameter [UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT) to `false`. -By doing so, Gazebo will act as main and only time source for both ROS2 and PX4. +至此,ROS 2 端所需的修改已全部完成。 在 PX4 端,你只需停止 uXRCE-DDS 时间同步功能,将参数[UXRCE_DDS_SYNCT](../advanced_config/parameter_reference.md#UXRCE_DDS_SYNCT)设置为false即可。 +通过此操作,Gazebo 将成为 ROS 2 和 PX4 两者共同的、唯一的主时间源。 -## ROS 2 Example Applications +## ROS 2 示例应用程序 ### ROS 2 Listener -The ROS 2 [listener examples](https://github.com/PX4/px4_ros_com/tree/main/src/examples/listeners) in the [px4_ros_com](https://github.com/PX4/px4_ros_com) repo demonstrate how to write ROS nodes to listen to topics published by PX4. +[px4_ros_com](https://github.com/PX4/px4_ros_com中的 ROS 2 [listener examples](https://github.com/PX4/px4_ros_com/tree/main/src/examples/listeners) repo展示了如何编写 ROS 节点,以监听由 PX4 发布的话题 -Here we consider the [sensor_combined_listener.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/listeners/sensor_combined_listener.cpp) node under `px4_ros_com/src/examples/listeners`, which subscribes to the [SensorCombined](../msg_docs/SensorCombined.md) message. +此处我们以 px4_ros_com/src/examples/listeners 路径下的 [sensor_combined_listener.cpp](https://github.com/PX4/px4_ros_com/blob/main/src/examples/listeners/sensor_combined_listener.cpp) 节点为例,该节点会订阅 [SensorCombined](../msg_docs/SensorCombined.md) 消息。 :::info -[Build ROS 2 Workspace](#build-ros-2-workspace) shows how to build and run this example. +[Build ROS 2 Workspace](#build-ros-2-workspace) 显示如何构建和运行这个例子。 ::: -The code first imports the C++ libraries needed to interface with the ROS 2 middleware and the header file for the `SensorCombined` message to which the node subscribes: +代码首先导入了与 ROS 2 中间件进行交互所需的 C++ 库,以及该节点所订阅的SensorCombined消息对应的头部文件: ```cpp -#include -#include +#include <0> +#include <1> ``` -Then it creates a `SensorCombinedListener` class that subclasses the generic `rclcpp::Node` base class. +随后,代码创建了一个 SensorCombinedListener 类,该类继承自通用的 rclcpp::Node 基类。 ```cpp /** @@ -566,7 +566,7 @@ class SensorCombinedListener : public rclcpp::Node { ``` -This creates a callback function for when the `SensorCombined` uORB messages are received (now as micro XRCE-DDS messages), and outputs the content of the message fields each time the message is received. +这会创建一个回调函数,用于处理SensorCombined uORB 消息(当前以微型 XRCE-DDS 消息格式传输)的接收事件;每当接收到该消息时,该函数会输出消息字段的内容 ```cpp public: @@ -595,12 +595,12 @@ public: ``` :::info -The subscription sets a QoS profile based on `rmw_qos_profile_sensor_data`. -This is needed because the default ROS 2 QoS profile for subscribers is incompatible with the PX4 profile for publishers. -For more information see: [ROS 2 Subscriber QoS Settings](#ros-2-subscriber-qos-settings), +该订阅会基于 rmw_qos_profile_sensor_data 设置一个 QoS 配置文件。 +之所以需要这样做,是因为 ROS 2 订阅者的默认 QoS(服务质量)配置文件,与 PX4 发布者的配置文件不兼容。 +欲了解更多信息,请参阅:[ROS 2 Subscriber QoS Settings](#ros-2-subscriber-qos-settings), ::: -The lines below create a publisher to the `SensorCombined` uORB topic, which can be matched with one or more compatible ROS 2 subscribers to the `fmu/sensor_combined/out` ROS 2 topic. +以下代码行创建了一个发布者,用于向 SensorCombined uORB 话题发布数据;该发布者可与一个或多个兼容的 ROS 2 订阅者匹配,这些订阅者监听的是 fmu/sensor_combined/out ROS 2 话题。 ````cpp private: @@ -623,14 +623,14 @@ int main(int argc, char *argv[]) } ```` -This particular example has an associated launch file at [launch/sensor_combined_listener.launch.py](https://github.com/PX4/px4_ros_com/blob/main/launch/sensor_combined_listener.launch.py). -This allows it to be launched using the [`ros2 launch`](#ros2-launch) command. +此特殊示例在[launch/sensor_combined_listener.launch.py](https://github.com/PX4/px4_ros_com/blob/main/launch/sensor_combined_listener.launch.py).有一个相关的启动文件。 +这使得它可以通过 [`ros2 launch`](#ros2-launch) 命令启动 -### ROS 2 Advertiser +### ROS 2 发布者 -A ROS 2 advertiser node publishes data into the DDS/RTPS network (and hence to the PX4 Autopilot). +一个 ROS 2 发布者节点会将数据发布到 DDS/RTPS 网络中(进而传递给 PX4 自动驾驶仪)。 -Taking as an example the `debug_vect_advertiser.cpp` under `px4_ros_com/src/advertisers`, first we import required headers, including the `debug_vect` msg header. +以 px4_ros_com/src/advertisers 路径下的 debug_vect_advertiser.cpp(文件)为例,首先我们会导入所需的headers,其中包括 `debug_vect` msg header。 ```cpp #include @@ -640,15 +640,15 @@ Taking as an example the `debug_vect_advertiser.cpp` under `px4_ros_com/src/adve using namespace std::chrono_literals; ``` -Then the code creates a `DebugVectAdvertiser` class that subclasses the generic `rclcpp::Node` base class. +随后,代码创建了一个 DebugVectAdvertiser 类,该类继承自通用的 rclcpp::Node 基类。 ```cpp class DebugVectAdvertiser : public rclcpp::Node { ``` -The code below creates a function for when messages are to be sent. -The messages are sent based on a timed callback, which sends two messages per second based on a timer. +这段代码创建了一个用来发送消息的回调函数。 +发送消息的回调函数由定时器触发的,每秒钟发送两次消息。 ```cpp public: @@ -676,7 +676,7 @@ private: }; ``` -The instantiation of the `DebugVectAdvertiser` class as a ROS node is done on the `main` function. +这段代码在 main 函数中将 DebugVectAdvertiser 类实例化成一个ROS节点。 ```cpp int main(int argc, char *argv[]) @@ -693,31 +693,31 @@ int main(int argc, char *argv[]) ### Offboard控制 -[ROS 2 Offboard control example](../ros2/offboard_control.md) provides a complete C++ reference example of how to use [offboard control](../flight_modes/offboard.md) of PX4 with ROS2. +[ROS 2 Offboard control example](../ros2/offboard_control.md)提供了一个完整的 C++ 参考示例,说明如何使用 PX4 的 [offboard control](../flight_modes/offboard.md) 与 ROS 2。 -[Python ROS2 offboard examples with PX4](https://github.com/Jaeyoung-Lim/px4-offboard) (Jaeyoung-Lim/px4-offboard) provides a similar example for Python, and includes the scripts: +[Python ROS2 offboard examples with PX4](https://github.com/Jaeyoung-Lim/px4-offboard) (Jaeyoung-Lim/px4-offboard) 为Python 提供了一个类似的示例,并包含脚本: -- `offboard_control.py`: Example of offboard position control using position setpoints -- `visualizer.py`: Used for visualizing vehicle states in Rviz +- `offboard_control.py`: 使用位置设定值进行离板位置控制的示例 +- “visualizer.py\`:用于可视化载体状态的 Rviz -## Using Flight Controller Hardware +## 使用飞行控制器硬件 -ROS 2 with PX4 running on a flight controller is almost the same as working with PX4 on the simulator. -The only difference is that you need to start both the agent _and the client_, with settings appropriate for the communication channel. +在飞行控制器上运行的 PX4 号ROS2与在模拟器上运行的 PX4 几乎相同。 +唯一的区别是您需要同时启动agent _and the client_,并设置适合通信频道。 -For more information see [Starting uXRCE-DDS](../middleware/uxrce_dds.md#starting-agent-and-client). +更多信息详见[Starting uXRCE-DDS](../middleware/uxrce_dds.md#starting-agent-and-client) -## Custom uORB Topics +## 自定义 uORB 主题 -ROS 2 needs to have the _same_ message definitions that were used to create the uXRCE-DDS client module in the PX4 Firmware in order to interpret the messages. -The definition are stored in the ROS 2 interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) and they are automatically synchronized by CI on the `main` and release branches. -Note that all the messages from PX4 source code are present in the repository, but only those listed in `dds_topics.yaml` will be available as ROS 2 topics. -Therefore, +ROS 2需要有用于在 PX4 固件中创建 uXRCE-DDS客户端模块的 _sam_message 定义,以便解释消息。 +这些定义存储在 ROS 2 接口包[PX4/px4_msgs](https://github.com/PX4/px4_msgs)中,并且会通过CI在 main(主)分支和发布分支上自动同步。 +需要注意的是,PX4 源代码中的所有消息均存在于该代码仓库中,但只有在dds_topics.yaml文件中列出的消息,才会作为 ROS 2 话题可用。 +因此 -- If you're using a main or release version of PX4 you can get the message definitions by cloning the interface package [PX4/px4_msgs](https://github.com/PX4/px4_msgs) into your workspace. -- If you're creating or modifying uORB messages you must manually update the messages in your workspace from your PX4 source tree. - Generally this means that you would update [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), clone the interface package, and then manually synchronize it by copying the new/modified message definitions from [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg) to its `msg` folders. - Assuming that PX4-Autopilot is in your home directory `~`, while `px4_msgs` is in `~/ros2_ws/src/`, then the command might be: +- 如果您正在使用 PX4 的主要版本或发布版本,您可以通过克隆接口包[PX4/px4_msgs](https://github.com/PX4/px4_msgs)获得消息定义。 +- 如果您要创建或修改 uORB 消息,必须从 PX4 源代码树中手动更新工作空间中的消息。 + 一般来说,这意味着您将更新 [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml),克隆接口包。 然后手动同步,将新的/修改的消息定义从 [PX4-Autopilot/msg](https://github.com/PX4/PX4-Autopilot/tree/main/msg)复制到它的 `msg` 文件夹。 + 假定PX4-Autopilot在你的主目录`~`中,而`px4_msgs`则在`~/ros2_ws/src/`中,命令可能是: ```sh rm ~/ros2_ws/src/px4_msgs/msg/*.msg @@ -725,22 +725,22 @@ Therefore, ``` ::: info - Technically, [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) completely defines the relationship between PX4 uORB topics and ROS 2 messages. - For more information see [uXRCE-DDS > DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml). + 从技术角度而言,[dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) 这个文件完整定义了 PX4 uORB 话题与 ROS 2 消息之间的对应关系。 + 欲了解更多信息,请参阅[uXRCE-DDS > DDS Topics YAML](../middleware/uxrce_dds.md#dds-topics-yaml)。 ::: ## Customizing the Namespace -Custom topic and service namespaces can be applied at build time (changing [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml)) or at runtime (useful for multi vehicle operations): +自定义主题和服务命名空间可以在构建时间(更改 [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml))或运行时间(对多载体操作有用): -- One possibility is to use the `-n` option when starting the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) from command line. - This technique can be used both in simulation and real vehicles. -- A custom namespace can be provided for simulations (only) by setting the environment variable `PX4_UXRCE_DDS_NS` before starting the simulation. +- 一种可能性是在从命令行启动[uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client)时使用 "-n" 选项。 + 这种技术既可用于模拟,也可用于实际机体。 +- 在开始模拟前,可以通过设置环境变量 `PX4_UXRCE_DDS_NS`来提供自定义命名空间 (仅限) :::info -Changing the namespace at runtime will append the desired namespace as a prefix to all `topic` fields in [dds_topics.yaml](../middleware/dds_topics.md) and all [service servers](#px4-ros-2-service-servers). -Therefore, commands like: +更改运行时的命名空间将会将所需的命名空间作为一个前缀附加到 [dds_topics.yaml](../middleware/dds_topics.md) 中所有的 "topic " 字段和所有 [service servers](#px4-ros-2-service-servers)。 +因此,命令如下: ```sh uxrce_dds_client start -n uav_1 @@ -752,7 +752,7 @@ uxrce_dds_client start -n uav_1 PX4_UXRCE_DDS_NS=uav_1 make px4_sitl gz_x500 ``` -will generate topics under the namespaces: +将在以下命名空间下生成话题: ```sh /uav_1/fmu/in/ # for subscribers @@ -766,27 +766,27 @@ will generate topics under the namespaces: PX4 uXRCE-DDS middleware supports [ROS 2 services](https://docs.ros.org/en/jazzy/Concepts/Basic/About-Services.html). -Services are remote procedure calls, from one node to another, that return a result. +服务(Services)是一种远程过程调用(remote procedure calls),由一个节点发起,向另一个节点请求调用,最终会返回一个结果。 A service server is the entity that will accept a remote procedure request, perform some computation on it, and return the result. They simplify communication between ROS 2 nodes and PX4 by grouping the request and response behaviour, and ensuring that replies are only returned to the specific requesting user. -This is much easier that publishing the request, subscribing to the reply, and filtering out any unwanted responses. +这比发布请求、订阅回复并过滤掉所有不需要的响应要容易得多。 -The service servers that are built into the PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) module include: +构建在 PX4 [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) 模块中的服务服务器包括: - `/fmu/vehicle_command` (definition: [`px4_msgs::srv::VehicleCommand`](https://github.com/PX4/px4_msgs/blob/main/srv/VehicleCommand.srv).) - This service can be called by ROS 2 applications to send PX4 [VehicleCommand](../msg_docs/VehicleCommand.md) uORB messages and receive PX4 [VehicleCommandAck](../msg_docs/VehicleCommandAck.md) uORB messages in response. + 此服务可以被 ROS 2 应用程序调用来发送 PX4[VehicleCommand](../msg_docs/VehicleCommand.md) uORB 消息,并相应接收 PX4 [VehicleCommandAck](../msg_docs/VehicleCommandAck.md)uORB 消息。 -All PX4 service names follow the convention `{extra_namespace}/fmu/{server_specific_name}` where `{extra_namespace}` is the same [custom namespace](#customizing-the-namespace) that can be given to the PX4 topics. +所有 PX4 服务名称均遵循 `{extra_namespace}/fmu/{server_specific_name}` 这一约定,其中 {extra_namespace} 与可分配给 PX4 话题的 [custom namespace](#customizing-the-namespace)相同。 -Details and specific examples are provided in the following sections. +具体细节和示例将在以下章节中提供。 -### VehicleCommand service +### 载体指挥服务 -This can be used to send commands to the vehicle, such as "take off", "land", change mode, and "orbit", and receive a response. +这可用于向飞行器发送指令(例如 “起飞”“着陆”“切换模式” 和 “盘旋”),并接收响应。 -The service type is defined in [`px4_msgs::srv::VehicleCommand`](https://github.com/PX4/px4_msgs/blob/main/srv/VehicleCommand.srv) as: +服务类型在 [`px4_msgs::srv::VehicleCommand`](https://github.com/PX4/px4_msgs/blob/main/srv/VehicleCommand.srv) 中定义如下: ```txt VehicleCommand request @@ -794,30 +794,30 @@ VehicleCommand request VehicleCommandAck reply ``` -Users can make service requests by sending [VehicleCommand](../msg_docs/VehicleCommand.md) messages, and receive a [VehicleCommandAck](../msg_docs/VehicleCommandAck.md) message in response. -The service ensures that only the `VehicleCommandAck` reply generated for the specific request made by the user is sent back. +用户可通过发送 [VehicleCommand](../msg_docs/VehicleCommand.md)消息发起服务请求,并会收到一条[VehicleCommandAck](../msg_docs/VehicleCommandAck.md) 消息作为响应。 +该服务可确保仅将针对用户发起的特定请求所生成的 VehicleCommandAck回复返回。 -#### VehicleCommand Service Offboard Control Example +#### 载体指挥服务离板控制示例 -A complete _offboard control_ example using the VehicleCommand service is provided by the [offboard_control_srv](https://github.com/PX4/px4_ros_com/blob/main/src/examples/offboard/offboard_control_srv.cpp) node available in the `px4_ros_com` package. +在 px4_ros_com 功能包中,有一个[offboard_control_srv](https://github.com/PX4/px4_ros_com/blob/main/src/examples/offboard/offboard_control_srv.cpp) 节点,该节点提供了一个完整的、使用 VehicleCommand 服务实现离板控制的示例。 -The example closely follows the _offboard control_ example described in [ROS 2 Offboard Control Example](../ros2/offboard_control.md) but uses the `VehicleCommand` service to request mode changes, vehicle arming and vehicle disarming. +该示例与[ROS 2 Offboard Control Example](../ros2/offboard_control.md) 中描述的离板控制示例高度相似,但使用 VehicleCommand 服务来请求模式切换、飞行器上锁和飞行器解锁。 -First the ROS 2 application declares a service client of type `px4_msgs::srv::VehicleCommand` using `rclcpp::Client()` as shown (this is the same approach used for all ROS2 service clients): +首先,ROS 2 应用程序会使用 rclcpp::Client() 声明一个类型为 px4_msgs::srv::VehicleCommand 的服务客户端,具体如下(所有 ROS 2 服务客户端均采用此方法) ```cpp -rclcpp::Client::SharedPtr vehicle_command_client_; +rclcpp::Client<0>::SharedPtr vehicle_command_client_; ``` -Then the client is initialized to the right ROS 2 service (`/fmu/vehicle_command`). -As the application assumes the standard PX4 namespace is used, the code to do this looks like this: +然后客户端初始化到正确的 ROS 2 服务 (`/fmu/vehicle_command` )。 +当应用程序假设使用标准的 PX4 命名空间时,这样做的代码看起来就像这样: ```cpp vehicle_command_client_{this->create_client("/fmu/vehicle_command")} ``` -After that, the client can be used to send any vehicle command request. -For example, the `arm()` function is used to request the vehicle to arm: +此后,客户可以用来发送任何机体命令请求。 +例如,`arm()`函数用于请求机体放置: ```cpp void OffboardControl::arm() @@ -827,7 +827,7 @@ void OffboardControl::arm() } ``` -where `request_vehicle_command` handles formatting the request and sending it over in _asynchronous_ [mode](https://docs.ros.org/en/humble/How-To-Guides/Sync-Vs-Async.html#asynchronous-calls): +`request_vehicle_command`处理请求格式化并在_asynchronous_ [mode](https://docs.ros.org/en/humble/How-To-Guides/Sync-Vs-Async.html#asynchronous-calls): ```cpp void OffboardControl::request_vehicle_command(uint16_t command, float param1, float param2) @@ -853,7 +853,7 @@ void OffboardControl::request_vehicle_command(uint16_t command, float param1, fl } ``` -The response is finally captured asynchronously by the `response_callback` method which checks for the request result: +最终,响应由 response_callback 方法以异步方式捕获,该方法会检查请求结果: ```cpp void OffboardControl::response_callback( @@ -872,20 +872,20 @@ void OffboardControl::response_callback( ## ros2 CLI -The [ros2 CLI](https://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools.html) is a useful tool for working with ROS. -You can use it, for example, to quickly check whether topics are being published, and also inspect them in detail if you have `px4_msg` in the workspace. -The command also lets you launch more complex ROS systems via a launch file. -A few possibilities are demonstrated below. +[ros2 CLI](https://docs.ros.org/en/humble/Tutorials/Beginner-CLI-Tools.html)是一个有用的工具来处理ROS。 +例如,您可以使用它快速检查话题是否正在发布;如果您的工作空间中包含 px4_msg,还可以详细查看这些话题的内容。 +该命令还允许您通过启动文件(launch file)启动更复杂的 ROS 系统。 +下文显示了几种可能性。 -### ros2 topic list +### ros2 topic list(ROS 2 话题列表命令) -Use `ros2 topic list` to list the topics visible to ROS 2: +使用 ros2 topic list 命令列出 ROS 2 可识别的话题: ```sh -ros2 topic list +ros2 topic list(ROS 2 话题列表命令) ``` -If PX4 is connected to the agent, the result will be a list of topic types: +若 PX4 已连接至代理,输出结果将是一份话题类型列表: ```sh /fmu/in/obstacle_distance @@ -894,19 +894,19 @@ If PX4 is connected to the agent, the result will be a list of topic types: ... ``` -Note that the workspace does not need to build with `px4_msgs` for this to succeed; topic type information is part of the message payload. +请注意,工作区不需要使用 px4_msgs 构建才能成功;主题类型信息是消息有效载荷的一部分。 ### ros2 topic echo -Use `ros2 topic echo` to show the details of a particular topic. +使用 `ros2 topic echo`"来显示特定主题的详细信息。 -Unlike with `ros2 topic list`, for this to work you must be in a workspace has built the `px4_msgs` and sourced `local_setup.bash` so that ROS can interpret the messages. +与 ros2 topic list 命令不同,要让该功能正常工作,你必须处于一个已编译 px4_msgs且已执行 local_setup.bash 脚本的工作空间中,这样 ROS 才能解析相关消息 ```sh ros2 topic echo /fmu/out/vehicle_status ``` -The command will echo the topic details as they update. +该命令将在主题细节更新时响应它们的详细信息。 ```sh --- @@ -927,14 +927,14 @@ hil_state: 0 ### ros2 topic hz -You can get statistics about the rates of messages using `ros2 topic hz`. -For example, to get the rates for `SensorCombined`: +你可以使用 ros2 topic hz 命令获取消息速率相关的统计信息。 +例如,获取`SensorCombined`速率: ```sh ros2 topic hz /fmu/out/sensor_combined ``` -The output will look something like: +输出会看起来像这样: ```sh average rate: 248.187 @@ -953,30 +953,30 @@ min: 0.000s max: 0.012s std dev: 0.00148s window: 3960 ### ros2 launch -The `ros2 launch` command is used to start a ROS 2 launch file. -For example, above we used `ros2 launch px4_ros_com sensor_combined_listener.launch.py` to start the listener example. +ros2 launch 命令用于启动一个 ROS 2 启动文件 +例如,前面我们使用 ros2 launch px4_ros_com sensor_combined_listener.launch.py 命令启动了监听器示例。 -You don't need to have a launch file, but they are very useful if you have a complex ROS 2 system that needs to start several components. +你并非必须使用启动文件,但如果你的 ROS 2 系统较为复杂,需要启动多个组件,那么启动文件会非常实用。 -For information about launch files see [ROS 2 Tutorials > Creating launch files](https://docs.ros.org/en/humble/Tutorials/Intermediate/Launch/Creating-Launch-Files.html) +关于启动文件的信息,请参阅 [ROS 2 Tutorials > Creating launch files](https://docs.ros.org/en/humble/Tutorials/Intermediate/Launch/Creating-Launch-Files.html) ## 故障处理 -### Missing dependencies +### 缺少依赖项 -The standard installation should include all the tools needed by ROS 2. +标准安装应包含 ROS 2 所需的所有工具。 -If any are missing, they can be added separately: +如果有任何缺失,可以单独添加: -- **`colcon`** build tools should be in the development tools. - It can be installed using: +- **`colcon`** 构建工具应该在开发工具中。 + 可以使用以下方式安装它: ```sh sudo apt install python3-colcon-common-extensions ``` -- The Eigen3 library used by the transforms library should be in the both the desktop and base packages. - It should be installed as shown: +- 变换库(transforms library)所使用的 Eigen3 库,应同时存在于桌面版(desktop)功能包和基础版(base)功能包中。 + 它应该安装在显示中: :::: tabs @@ -1002,10 +1002,10 @@ If any are missing, they can be added separately: ### ros_gz_bridge not publishing on the \clock topic -If your [ROS2 nodes use the Gazebo clock as time source](../ros2/user_guide.md#ros2-nodes-use-the-gazebo-clock-as-time-source) but the `ros_gz_bridge` node doesn't publish anything on the `/clock` topic, you may have the wrong version installed. -This might happen if you install ROS 2 Humble with the default "Ignition Fortress" packages, rather than using those for PX4, which uses "Gazebo Harmonic". +如果你的[ROS2 nodes use the Gazebo clock as time source](../ros2/user_guide.md#ros2-nodes-use-the-gazebo-clock-as-time-source) 但`ros_gz_bridge` 节点没有发布任何关于\`/时钟' 主题的内容。 您可能安装了错误的版本。 +若你在安装 ROS 2 Humble 时,使用的是默认的 “Ignition Fortress” 功能包,而非 PX4 所使用的、适配 “Gazebo Harmonic” 的功能包,就可能出现这种情况。 -The following commands uninstall the default Ignition Fortress topics and install the correct bridge and other interface topics for **Gazebo Harmonic** with ROS2 **Humble**: +以下命令会卸载默认的 Ignition Fortress 功能包,并为搭配 ROS 2 Humble 版本的 Gazebo Harmonic 安装正确的桥接功能包及其他接口功能包: ```bash # Remove the wrong version (for Ignition Fortress) @@ -1015,7 +1015,7 @@ sudo apt remove ros-humble-ros-gz sudo apt install ros-humble-ros-gzharmonic ``` -## Additional information +## 更多信息 - [ROS 2 in PX4: Technical Details of a Seamless Transition to XRCE-DDS](https://www.youtube.com/watch?v=F5oelooT67E) - Pablo Garrido & Nuno Marques (youtube) - [DDS and ROS middleware implementations](https://github.com/ros2/ros2/wiki/DDS-and-ROS-middleware-implementations) diff --git a/docs/zh/sim_gazebo_gz/index.md b/docs/zh/sim_gazebo_gz/index.md index 127701dc05..f9dfc91f12 100644 --- a/docs/zh/sim_gazebo_gz/index.md +++ b/docs/zh/sim_gazebo_gz/index.md @@ -20,6 +20,8 @@ See [Simulation](../simulation/index.md) for general information about simulator Gazebo Harmonic is installed by default on Ubuntu 22.04 as part of the normal [development environment setup](../dev_setup/dev_env_linux_ubuntu.md#simulation-and-nuttx-pixhawk-targets). +Gazebo versions Harmonic, Ionic, and Jetty are supported on Ubuntu 24.04. The latest installed Gazebo release is used by default. + :::info The PX4 installation scripts are based on the instructions: [Binary Installation on Ubuntu](https://gazebosim.org/docs/harmonic/install_ubuntu/) (gazebosim.org). ::: @@ -48,22 +50,23 @@ This runs both the PX4 SITL instance and the Gazebo client. The supported vehicles and `make` commands are listed below. Note that all gazebo make targets have the prefix `gz_`. -| Vehicle | 通信 | `PX4_SYS_AUTOSTART` | -| ------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ----------------------------------- | ------------------- | -| [Quadrotor (x500)](../sim_gazebo_gz/vehicles.md#x500-quadrotor) | `make px4_sitl gz_x500` | 4011 | -| [X500 Quadrotor with Depth Camera (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-depth-camera-front-facing) | `make px4_sitl gz_x500_depth` | 4002 | -| [Quadrotor(x500) with Vision Odometry](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-visual-odometry) | `make px4_sitl gz_x500_vision` | 4005 | -| [Quadrotor(x500) with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing) | `make px4_sitl gz_x500_lidar_down` | 4016 | -| [Quadrotor(x500) with 2D LIDAR](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar) | `make px4_sitl gz_x500_lidar_2d` | 4013 | -| [Quadrotor(x500) with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing) | `make px4_sitl gz_x500_lidar_front` | 4017 | -| [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) | `make px4_sitl gz_x500_gimbal` | 4019 | -| [VTOL](../sim_gazebo_gz/vehicles.md#standard-vtol) | `make px4_sitl gz_standard_vtol` | 4004 | -| [Plane](../sim_gazebo_gz/vehicles.md#standard-plane) | `make px4_sitl gz_rc_cessna` | 4003 | -| [Advanced Plane](../sim_gazebo_gz/vehicles.md#advanced-plane) | `make px4_sitl gz_advanced_plane` | 4008 | -| [Differential Rover](../sim_gazebo_gz/vehicles.md#differential-rover) | `make px4_sitl gz_r1_rover` | 4009 | -| [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) | `make px4_sitl gz_rover_ackermann` | 4012 | -| [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) | `make px4_sitl gz_quadtailsitter` | 4018 | -| [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) | `make px4_sitl gz_tiltrotor` | 4020 | +| Vehicle | 通信 | `PX4_SYS_AUTOSTART` | +| ------------------------------------------------------------------------------------------------------------------------------------------------------------------ | ------------------------------------- | ------------------- | +| [Quadrotor (x500)](../sim_gazebo_gz/vehicles.md#x500-quadrotor) | `make px4_sitl gz_x500` | 4011 | +| [X500 Quadrotor with Depth Camera (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-depth-camera-front-facing) | `make px4_sitl gz_x500_depth` | 4002 | +| [Quadrotor(x500) with Vision Odometry](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-visual-odometry) | `make px4_sitl gz_x500_vision` | 4005 | +| [Quadrotor(x500) with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing) | `make px4_sitl gz_x500_lidar_down` | 4016 | +| [Quadrotor(x500) with 2D LIDAR](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar) | `make px4_sitl gz_x500_lidar_2d` | 4013 | +| [Quadrotor(x500) with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing) | `make px4_sitl gz_x500_lidar_front` | 4017 | +| [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) | `make px4_sitl gz_x500_gimbal` | 4019 | +| [VTOL](../sim_gazebo_gz/vehicles.md#standard-vtol) | `make px4_sitl gz_standard_vtol` | 4004 | +| [Plane](../sim_gazebo_gz/vehicles.md#standard-plane) | `make px4_sitl gz_rc_cessna` | 4003 | +| [Advanced Plane](../sim_gazebo_gz/vehicles.md#advanced-plane) | `make px4_sitl gz_advanced_plane` | 4008 | +| [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) | `make px4_sitl gz_quadtailsitter` | 4018 | +| [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) | `make px4_sitl gz_tiltrotor` | 4020 | +| [Differential Rover](../sim_gazebo_gz/vehicles.md#differential-rover) | `make px4_sitl gz_rover_differential` | 50000 | +| [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) | `make px4_sitl gz_rover_ackermann` | 51000 | +| [Mecanum Rover](../sim_gazebo_gz/vehicles.md#mecanum-rover) | `make px4_sitl gz_rover_mecanum` | 52000 | All [vehicle models](../sim_gazebo_gz/vehicles.md) (and [worlds](#specify-world)) are included as a submodule from the [Gazebo Models Repository](../sim_gazebo_gz/gazebo_models.md) repository. diff --git a/docs/zh/sim_gazebo_gz/vehicles.md b/docs/zh/sim_gazebo_gz/vehicles.md index a449199159..ba9b16be4a 100644 --- a/docs/zh/sim_gazebo_gz/vehicles.md +++ b/docs/zh/sim_gazebo_gz/vehicles.md @@ -185,7 +185,7 @@ make px4_sitl gz_tiltrotor [Differential Rover](../frames_rover/index.md#differential) uses the [rover world](../sim_gazebo_gz/worlds.md#rover) by default. ```sh -make px4_sitl gz_r1_rover +make px4_sitl gz_rover_differential ``` ![Differential Rover in Gazebo](../../assets/simulation/gazebo/vehicles/rover_differential.png) @@ -199,3 +199,13 @@ make px4_sitl gz_rover_ackermann ``` ![Ackermann Rover in Gazebo](../../assets/simulation/gazebo/vehicles/rover_ackermann.png) + +### Mecanum Rover + +[Mecanum Rover](../frames_rover/index.md#mecanum) uses the [rover world](../sim_gazebo_gz/worlds.md#rover) by default. + +```sh +make px4_sitl gz_rover_mecanum +``` + +![Mecanum Rover in Gazebo](../../assets/simulation/gazebo/vehicles/rover_mecanum.png) diff --git a/docs/zh/telemetry/telemetry_wifi.md b/docs/zh/telemetry/telemetry_wifi.md index b1f435c36d..84d13ddd32 100644 --- a/docs/zh/telemetry/telemetry_wifi.md +++ b/docs/zh/telemetry/telemetry_wifi.md @@ -1,6 +1,6 @@ # WiFi 数传电台 -WiFi telemetry enables MAVLink communication between a WiFi radio on a vehicle and a GCS.\ +WiFi telemetry enables MAVLink communication between a WiFi radio on a vehicle and a GCS. WiFi typically offers shorter range than a normal telemetry radio, but supports higher data rates, and makes it easier to support FPV/video feeds. Usually only a single radio unit for the vehicle is needed (assuming the ground station already has WiFi). From 60dd34315227150bc6cd7ed873541af28d81052a Mon Sep 17 00:00:00 2001 From: Andrew Wilkins Date: Wed, 8 Oct 2025 14:02:03 -0500 Subject: [PATCH 154/812] updated test cards for optical flow flights (#25676) * updated test cards for optical flow flights * Update docs/en/test_cards/mc_07_optical_flow_failure.md Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> * updated docs * fixed mis-type in url * subedit * Update docs/en/test_cards/mc_06_optical_flow.md Co-authored-by: Hamish Willee * updated test card * changes to file name and some instructions --------- Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Co-authored-by: Hamish Willee --- docs/en/SUMMARY.md | 4 +- docs/en/_sidebar.md | 4 +- docs/en/test_and_ci/test_flights.md | 4 +- docs/en/test_cards/mc_06_optical_flow.md | 29 +++++--- .../mc_07_optical_flow_low_mount.md | 45 +++++++++++ docs/en/test_cards/mc_08_dshot.md | 10 +-- .../test_cards/{mc_07_vio.md => mc_09_vio.md} | 14 ++-- .../mc_10_optical_flow_gps_mixed.md | 74 +++++++++++++++++++ 8 files changed, 159 insertions(+), 25 deletions(-) create mode 100644 docs/en/test_cards/mc_07_optical_flow_low_mount.md rename docs/en/test_cards/{mc_07_vio.md => mc_09_vio.md} (75%) create mode 100644 docs/en/test_cards/mc_10_optical_flow_gps_mixed.md diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index c1913bf6f2..1285360522 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -831,8 +831,10 @@ - [Test MC_04 - Failsafe Testing](test_cards/mc_04_failsafe_testing.md) - [Test MC_05 - Manual Modes (Inside)](test_cards/mc_05_indoor_flight_manual_modes.md) - [Test MC_06 - Optical Flow (Inside)](test_cards/mc_06_optical_flow.md) - - [Test MC_07 - VIO (Inside)](test_cards/mc_07_vio.md) + - [Test MC_07 - Optical Flow Low Mount](test_cards/mc_07_optical_flow_low_mount.md) - [Test MC_08 - DSHOT ESC](test_cards/mc_08_dshot.md) + - [Test MC_09 - VIO (Visual-Inertial Odometry)](test_cards/mc_09_vio.md) + - [Test MC_10 - Optical Flow / GPS Mixed](test_cards/mc_10_optical_flow_gps_mixed.md) - [Unit Tests](test_and_ci/unit_tests.md) - [Fuzz Tests](test_and_ci/fuzz_tests.md) - [Continuous Integration](test_and_ci/continous_integration.md) diff --git a/docs/en/_sidebar.md b/docs/en/_sidebar.md index 2d1ed64e69..949c3bc253 100644 --- a/docs/en/_sidebar.md +++ b/docs/en/_sidebar.md @@ -829,8 +829,10 @@ - [Test MC_04 - Failsafe Testing](/test_cards/mc_04_failsafe_testing.md) - [Test MC_05 - Manual Modes (Inside)](/test_cards/mc_05_indoor_flight_manual_modes.md) - [Test MC_06 - Optical Flow (Inside)](/test_cards/mc_06_optical_flow.md) - - [Test MC_07 - VIO (Inside)](/test_cards/mc_07_vio.md) + - [Test MC_07 - Optical Flow Low Mount](/test_cards/mc_07_optical_flow_low_mount.md) - [Test MC_08 - DSHOT ESC](/test_cards/mc_08_dshot.md) + - [Test MC_09 - VIO (Visual-Inertial Odometry)](/test_cards/mc_09_vio.md) + - [Test MC_10 - Optical Flow / GPS Mixed](/test_cards/mc_10_optical_flow_gps_mixed.md) - [Unit Tests](/test_and_ci/unit_tests.md) - [Fuzz Tests](/test_and_ci/fuzz_tests.md) - [Continuous Integration](/test_and_ci/continous_integration.md) diff --git a/docs/en/test_and_ci/test_flights.md b/docs/en/test_and_ci/test_flights.md index f9579c1ccb..91a7681f97 100644 --- a/docs/en/test_and_ci/test_flights.md +++ b/docs/en/test_and_ci/test_flights.md @@ -28,5 +28,7 @@ These are run by the test team as part of release testing, and for more signific - [MC_04 - Failsafe Testing](../test_cards/mc_04_failsafe_testing.md) - [MC_05 - Indoor Flight (Manual Modes)](../test_cards/mc_05_indoor_flight_manual_modes.md) - [MC_06 - Indoor Flight (Optical Flow)](../test_cards/mc_06_optical_flow.md) -- [MC_07 - VIO (Visual-Inertial Odometry)](../test_cards/mc_07_vio.md) +- [MC_07 - Optical Flow Low Mount](../test_cards/mc_07_optical_flow_low_mount.md) - [MC_08 - DSHOT ESC](../test_cards/mc_08_dshot.md) +- [MC_09 - VIO (Visual-Inertial Odometry)](../test_cards/mc_09_vio.md) +- [MC_10 - Optical Flow / GPS Mixed](../test_cards/mc_10_optical_flow_gps_mixed.md) diff --git a/docs/en/test_cards/mc_06_optical_flow.md b/docs/en/test_cards/mc_06_optical_flow.md index 8a7eb71211..22877115e6 100644 --- a/docs/en/test_cards/mc_06_optical_flow.md +++ b/docs/en/test_cards/mc_06_optical_flow.md @@ -2,25 +2,23 @@ ## Objective -To test that optical flow works as expected +Test that optical flow works as expected ## Preflight -Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation -([Setup Information here](../sensor/optical_flow.md)) +Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation ([setup information here](../sensor/optical_flow.md)) -Ensure there are no other sources of positioning besides optical flow +Ensure there are no other sources of positioning besides optical flow: - [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` - [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` - [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` -- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` -Ensure that the drone can go into Altitude / Position flight mode while still on the ground +Ensure that the drone can go into Altitude / Position mode while still on the ground ## Flight Tests -❏ Altitude flight mode +❏ [Altitude mode](../flight_modes_mc/altitude.md)     ❏ Vertical position should hold current value with stick centered @@ -28,7 +26,7 @@ Ensure that the drone can go into Altitude / Position flight mode while still on     ❏ Throttle response set to climb/descent rate -❏ Position flight mode +❏ [Position mode](../flight_modes_mc/position.md)     ❏ Horizontal position should hold current value with stick centered @@ -38,6 +36,16 @@ Ensure that the drone can go into Altitude / Position flight mode while still on     ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates +❏ Varying height terrain + +    ❏ Put boxes on the ground to create varying heights in terrain + +    ❏ Take off in position mode and fly over the boxes such that the downward facing rangefinder varies in value + +    ❏ Do a few passes with varying amounts of time over the boxes (1-30 seconds if possible) + +    ❏ Drone should not raise in height when flying over boxes + ## Landing ❏ Land in either Position or Altitude mode with the throttle below 40% @@ -47,7 +55,8 @@ Ensure that the drone can go into Altitude / Position flight mode while still on ## Expected Results - Take-off should be smooth as throttle is raised -- Drone should hold altitude in Altitude Flight mode without wandering -- Drone should hold position within 1 meter in Position Flight mode without pilot moving sticks +- Drone should hold altitude in Altitude mode without wandering (over surface with many features) +- Drone should hold position within 1 meter in Position mode without pilot moving sticks - No oscillations should present in any of the above flight modes +- Drone should not raise in height when flying over boxes - Upon landing, copter should not bounce on the ground diff --git a/docs/en/test_cards/mc_07_optical_flow_low_mount.md b/docs/en/test_cards/mc_07_optical_flow_low_mount.md new file mode 100644 index 0000000000..73c06f4e4a --- /dev/null +++ b/docs/en/test_cards/mc_07_optical_flow_low_mount.md @@ -0,0 +1,45 @@ +# Test MC_07 - Optical Flow Low Sensor + +## Objective + +Test that optical flow works as expected with a low mounted optical flow sensor + +## Preflight + +Ensure that the drone's optical flow sensor is mounted more than an inch off of the ground + +Ensure that [MPC_THR_MIN](../advanced_config/parameter_reference.md#MPC_THR_MIN) is tuned correctly for landing + +Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation +([Setup Information here](../sensor/optical_flow.md)) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` + +Ensure that the drone can go into [Position mode](../flight_modes_mc/position.md) while still on the ground + +## Flight Tests + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## Landing + +❏ Land in Position mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## Expected Results + +- Take-off should be smooth as throttle is raised +- Drone should stay in Position mode, NOT fall into [altitude](../flight_modes_mc/altitude.md) mode diff --git a/docs/en/test_cards/mc_08_dshot.md b/docs/en/test_cards/mc_08_dshot.md index 1ce413b34f..d2012aabd5 100644 --- a/docs/en/test_cards/mc_08_dshot.md +++ b/docs/en/test_cards/mc_08_dshot.md @@ -6,22 +6,22 @@ Regression test for DSHOT working with PX4 ## Preflight -- Ensure vehicle is using a DSHOT ESC. +- Ensure vehicle is using a DSHOT ESC - Parameter [DSHOT_BIDIR_EN](../advanced_config/parameter_reference.md#DSHOT_BIDIR_EN) is enabled - Parameter [DSHOT_TEL_CFG](../advanced_config/parameter_reference.md#DSHOT_TEL_CFG) is configured (if ESC supports telemetry) - Parameter [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) has Debug (`5`) checked ## Flight Tests -❏ Stabilized Flight mode +❏ [Stabilized mode](../flight_modes_mc/manual_stabilized.md) -    ❏ Takeoff in stabilized flight mode to ensure correct motor spin +    ❏ Takeoff in stabilized mode to ensure correct motor spin     ❏ Pitch/Roll/Yaw response 1:1     ❏ Throttle response 1:1 -❏ Position flight mode +❏ [Position mode](../flight_modes_mc/position.md)     ❏ Horizontal position should hold current value with stick centered @@ -41,6 +41,6 @@ Regression test for DSHOT working with PX4 - Download flight logs - Load into Data Plot Juggler -- Ensure data is logged for esc_status/esc.0x/esc_rpm +- Ensure data is logged for `esc_status`/`esc.0x`/`esc_rpm` ![Reference frames](../../assets/test_cards/dshot_log_output.png) diff --git a/docs/en/test_cards/mc_07_vio.md b/docs/en/test_cards/mc_09_vio.md similarity index 75% rename from docs/en/test_cards/mc_07_vio.md rename to docs/en/test_cards/mc_09_vio.md index 24743eaf7e..994fa9e4cf 100644 --- a/docs/en/test_cards/mc_07_vio.md +++ b/docs/en/test_cards/mc_09_vio.md @@ -1,14 +1,14 @@ -# Test MC_07 - VIO (Visual-Inertial Odometry) +# Test MC_09 - VIO (Visual-Inertial Odometry) ## Objective -To test that external vision (VIO) works as expected +Test that external vision (VIO) works as expected ## Preflight Disconnect all GPS / compasses and ensure vehicle is using VIO for navigation -Ensure that the drone can go into Altitude / Position flight mode while still on the ground +Ensure that the drone can go into [Altitude](../flight_modes_mc/altitude.md) / [Position](../flight_modes_mc/position.md) mode while still on the ground Ensure there are no other sources of positioning besides VIO: @@ -19,7 +19,7 @@ Ensure there are no other sources of positioning besides VIO: ## Flight Tests -❏ Altitude flight mode +❏ [Altitude mode](../flight_modes_mc/altitude.md)     ❏ Vertical position should hold current value with stick centered @@ -27,7 +27,7 @@ Ensure there are no other sources of positioning besides VIO:     ❏ Throttle response set to climb/descent rate -❏ Position flight mode +❏ [Position mode](../flight_modes_mc/position.md)     ❏ Horizontal position should hold current value with stick centered @@ -46,7 +46,7 @@ Ensure there are no other sources of positioning besides VIO: ## Expected Results - Take-off should be smooth as throttle is raised -- Drone should hold altitude in Altitude Flight mode without wandering -- Drone should hold position within 1 meter in Position Flight mode without pilot moving sticks +- Drone should hold altitude in Altitude mode without wandering +- Drone should hold position within 1 meter in Position mode without pilot moving sticks - No oscillations should present in any of the above flight modes - Upon landing, copter should not bounce on the ground diff --git a/docs/en/test_cards/mc_10_optical_flow_gps_mixed.md b/docs/en/test_cards/mc_10_optical_flow_gps_mixed.md new file mode 100644 index 0000000000..740900f911 --- /dev/null +++ b/docs/en/test_cards/mc_10_optical_flow_gps_mixed.md @@ -0,0 +1,74 @@ +# Test MC_10 - Optical Flow / GPS Mixed + +## Objective + +Test that optical flow mixed with GPS works as expected + +## Preflight + +[Setup optical flow and GPS](../sensor/optical_flow.md) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `7` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `1` +- [EKF2_HGT_REF](../advanced_config/parameter_reference.md#EKF2_HGT_REF): `1` (GPS) + +Ensure that the drone can go into [Altitude](../flight_modes_mc/altitude.md) / [Position](../flight_modes_mc/position.md) mode while still on the ground + +## Flight Tests + +❏ [Altitude mode](../flight_modes_mc/altitude.md) + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response set to climb/descent rate + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +❏ GPS Cutout + +    ❏ Takeoff in position mode in GPS rich environment (outdoors) + +    ❏ Open QGC and navigate to MAVLink Console + +    ❏ Type `gps off` to disable GPS + +    ❏ Drone should maintain position hold via optical flow + +❏ GPS Degredation + +    ❏ Takeoff in position mode in GPS rich environment (outdoors) + +    ❏ Fly under a metal surface (or other GPS blocking structure) + +    ❏ Ensure drone does not lose position hold or start drifting + +    ❏ Fly out of metal structure to regain GPS + +❏ GPS Acquisition + +    ❏ Takeoff in position mode in non-GPS environment + +    ❏ Fly into a GPS rich environment (outdoors) + +    ❏ Ensure drone acquires GPS position + +## Expected Results + +- Take-off should be smooth as throttle is raised +- Drone should hold position within 1 meter in Position mode without pilot moving sticks +- Drone should hold position in GPS rich environment as well as non-GPS environment +- No oscillations should present in any of the above flight modes From d85994b521d5e9da7d376b2f8d71260c42cee9e2 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 8 Oct 2025 16:32:19 +1100 Subject: [PATCH 155/812] Make Github docs-deploy workflow only run manually --- .github/workflows/docs_deploy.yml | 19 +------------------ 1 file changed, 1 insertion(+), 18 deletions(-) diff --git a/.github/workflows/docs_deploy.yml b/.github/workflows/docs_deploy.yml index 13a0df6f6d..b8991e38c9 100644 --- a/.github/workflows/docs_deploy.yml +++ b/.github/workflows/docs_deploy.yml @@ -1,23 +1,6 @@ -name: Docs - Deploy PX4 User Guide +name: Docs - Deploy PX4 User Guide to Github pages (Manual) on: - push: - branches: - - 'main' - - 'release/**' - paths: - - 'docs/en/**' - - 'docs/uk/**' - - 'docs/zh/**' - pull_request: - branches: - - '**' - paths: - - 'docs/en/**' - - 'docs/uk/**' - - 'docs/zh/**' - - # Allows you to run this workflow manually from the Actions tab workflow_dispatch: # Sets permissions of the GITHUB_TOKEN to allow deployment to GitHub Pages From 2eac99cd20cb7962e92896f9513ec767ef8c68f5 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Fri, 12 Sep 2025 10:04:31 -0700 Subject: [PATCH 156/812] ci: AWS instance review and improved build caching * Tone down the performance of some runners from 8cpu+ down to 4cpu+ * Improve and document caching on PX4 builds with an improved ccache key strategy * Review and document artifact upload logic for binaries uploaded to S3 and github releases * Future Improvement, introduce runners configuration file so we can control more precesily which instances are allocated. Signed-off-by: Ramon Roche --- .github/runs-on.yml | 24 ++++ .github/workflows/build_all_targets.yml | 119 +++++++++++++++----- .github/workflows/compile_ubuntu.yml | 2 +- .github/workflows/dev_container.yml | 6 +- .github/workflows/docs_deploy.yml | 4 +- .github/workflows/docs_deploy_aws.yml | 2 +- .github/workflows/flash_analysis.yml | 4 +- .github/workflows/itcm_check.yml | 2 +- .github/workflows/ros_integration_tests.yml | 2 +- .github/workflows/ros_translation_node.yml | 2 +- .github/workflows/sitl_tests.yml | 2 +- 11 files changed, 127 insertions(+), 42 deletions(-) create mode 100644 .github/runs-on.yml diff --git a/.github/runs-on.yml b/.github/runs-on.yml new file mode 100644 index 0000000000..f68d406c8a --- /dev/null +++ b/.github/runs-on.yml @@ -0,0 +1,24 @@ +runners: + x86-small-runner: + cpu: [1, 2] + ram: [1, 4] + disk: default + spot: price-capacity-optimized + image: ubuntu24-full-x64 + extras: s3-cache + x86-firmware-builder: + cpu: [4, 8] + ram: [8, 16] + disk: default + family: ["c7i", "m7i", "r7i"] + spot: price-capacity-optimized + image: ubuntu24-full-x64 + extras: s3-cache + arm64-firmware-builder: + cpu: [4, 8] + ram: [8, 16] + disk: default + family: ["c7g", "m7g", "r7g"] + spot: price-capacity-optimized + image: ubuntu24-full-arm64 + extras: s3-cache diff --git a/.github/workflows/build_all_targets.yml b/.github/workflows/build_all_targets.yml index ef3b4d1470..e2646be336 100644 --- a/.github/workflows/build_all_targets.yml +++ b/.github/workflows/build_all_targets.yml @@ -26,6 +26,10 @@ concurrency: group: ${{ github.workflow }}-${{ github.ref }} cancel-in-progress: true +permissions: + contents: write + actions: read + jobs: group_targets: name: Scan for Board Targets @@ -48,12 +52,15 @@ jobs: path: "./Tools/setup/requirements.txt" - id: set-matrix - run: echo "::set-output name=matrix::$(./Tools/ci/generate_board_targets_json.py --group)" + name: Generate Build Matrix + run: echo "matrix=$(./Tools/ci/generate_board_targets_json.py --group)" >> $GITHUB_OUTPUT - id: set-timestamp - run: echo "::set-output name=timestamp::$(date +"%Y%m%d%H%M%S")" + name: Save Current Timestamp + run: echo "timestamp=$(date +"%Y%m%d%H%M%S")" >> $GITHUB_OUTPUT - id: set-branch + name: Save Current Branch Name run: | echo "branchname=${{ github.event_name == 'pull_request' && @@ -70,7 +77,7 @@ jobs: echo "$(./Tools/ci/generate_board_targets_json.py --group --verbose)" setup: - name: Build Group [${{ matrix.group }}][${{ matrix.arch == 'nuttx' && 'x86' || 'arm64' }}] + name: Build [${{ matrix.runner }}][${{ matrix.group }}] # runs-on: ubuntu-latest runs-on: [runs-on,"runner=8cpu-linux-${{ matrix.runner }}","image=ubuntu24-full-${{ matrix.runner }}","run-id=${{ github.run_id }}",spot=false] needs: group_targets @@ -80,6 +87,7 @@ jobs: container: image: ${{ matrix.container }} steps: + - uses: runs-on/action@v2 - uses: actions/checkout@v4 with: fetch-depth: 0 @@ -87,14 +95,24 @@ jobs: - name: Git ownership workaround run: git config --system --add safe.directory '*' - - name: Setup ccache - uses: actions/cache@v4 + # ccache key breakdown: + # ccache---- + # ccache---- + # ccache---- + - name: Restore ccache from key + id: cc_restore + uses: actions/cache/restore@v4 with: path: ~/.ccache - key: ${{ matrix.group }}-ccache-${{ needs.group_targets.outputs.timestamp }} - restore-keys: ${{ matrix.group }}-ccache-${{ needs.group_targets.outputs.timestamp }} + key: ${{ format('ccache-{0}-{1}-{2}', runner.os, matrix.runner, matrix.group) }} + restore-keys: | + ccache-${{ runner.os }}-${{ matrix.runner }}-${{ matrix.group }}- + ccache-${{ runner.os }}-${{ matrix.runner }}- + ccache-${{ runner.os }}-${{ matrix.runner }}- + ccache-${{ runner.os }}- + ccache- - - name: Configure ccache + - name: Set ccache defaults and show stats run: | mkdir -p ~/.ccache echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf @@ -102,10 +120,11 @@ jobs: echo "compression_level = 6" >> ~/.ccache/ccache.conf echo "max_size = 120M" >> ~/.ccache/ccache.conf echo "hash_dir = false" >> ~/.ccache/ccache.conf + echo "compiler_check = content" >> ~/.ccache/ccache.conf ccache -s ccache -z - - name: Building [${{ matrix.group }}] + - name: Building [${{ matrix.targets }}] run: | ./Tools/ci/build_all_runner.sh ${{matrix.targets}} ${{matrix.arch}} @@ -119,15 +138,27 @@ jobs: name: px4_${{matrix.group}}_build_artifacts path: artifacts/ + - name: Post Build Cache Stats + if: always() + run: | + ccache -s + ccache -z + - name: Cache Save - run: ccache -s + if: always() + uses: actions/cache/save@v4 + with: + path: ~/.ccache + key: ${{ steps.cc_restore.outputs.cache-primary-key }} artifacts: - name: Upload Artifacts to S3 + name: Upload Artifacts # runs-on: ubuntu-latest runs-on: [runs-on,runner=1cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] needs: [setup, group_targets] - if: contains(fromJSON('["main", "stable", "beta"]'), needs.group_targets.outputs.branchname) + if: startsWith(github.ref, 'refs/tags/v') || contains(fromJSON('["main","stable","beta"]'), needs.group_targets.outputs.branchname) + outputs: + uploadlocation: ${{ steps.upload-location.outputs.uploadlocation }} steps: - name: Download Artifacts uses: actions/download-artifact@v4 @@ -135,11 +166,36 @@ jobs: path: artifacts/ merge-multiple: true - - name: Branch Name + - name: Upload Location + id: upload-location run: | - echo "${{ needs.group_targets.outputs.branchname }}" + # Determine upload location based on branch or tag with the following considerations: + # Destination: AWS S3 bucket px4-travis in folder Firmware/ + # - If branch is main -> upload to master/ + # - Older versions of QGC are hardocded to look for master/ + # - If branch is stable or beta -> upload to stable/ or beta/ + # - If a tag vX.Y.Z -> upload to vX.Y.Z/ + # - Also update stable/ to point to the same version + #. - Older versions of QGC are hardocded to look for stable/ + # - If a pull request -> do not upload + set -euo pipefail - - name: Uploading Artifacts to S3 [${{ needs.group_targets.outputs.branchname == 'main' && 'master' || needs.group_targets.outputs.branchname }}] + ref="${GITHUB_REF}" + branch=${{ needs.group_targets.outputs.branchname }} + location="$branch" + + if [[ "$branch" == "main" ]]; then + location="master" + fi + + if [[ "$ref" == refs/tags/v[0-9]* ]]; then + tag="${ref#refs/tags/}" + location="$tag" + fi + + echo "uploadlocation=$location" >> $GITHUB_OUTPUT + + - name: Uploading Artifacts to S3 [${{ steps.upload-location.outputs.uploadlocation }}] uses: jakejarvis/s3-sync-action@master with: args: --acl public-read @@ -149,25 +205,30 @@ jobs: AWS_SECRET_ACCESS_KEY: ${{ secrets.AWS_SECRET_ACCESS_KEY }} AWS_REGION: 'us-west-1' SOURCE_DIR: artifacts/ - DEST_DIR: Firmware/${{ needs.group_targets.outputs.branchname == 'main' && 'master' || needs.group_targets.outputs.branchname }}/ + DEST_DIR: Firmware/${{ steps.upload-location.outputs.uploadlocation }}/ - release: - name: Create Release and Upload Artifacts - permissions: - contents: write - # runs-on: ubuntu-latest - runs-on: [runs-on,runner=1cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] - needs: [setup, group_targets] - if: startsWith(github.ref, 'refs/tags/') - steps: - - name: Download Artifacts - uses: actions/download-artifact@v4 + # if we are uploading artifacts to a versioned folder + # we should also update the stable folder in the s3 bucket + - name: Uploading Artifacts to S3 [stable] + uses: jakejarvis/s3-sync-action@master + if: startsWith(github.ref, 'refs/tags/v') with: - path: artifacts/ - merge-multiple: true + args: --acl public-read + env: + AWS_S3_BUCKET: 'px4-travis' + AWS_ACCESS_KEY_ID: ${{ secrets.AWS_ACCESS_KEY_ID }} + AWS_SECRET_ACCESS_KEY: ${{ secrets.AWS_SECRET_ACCESS_KEY }} + AWS_REGION: 'us-west-1' + SOURCE_DIR: artifacts/ + DEST_DIR: Firmware/stable/ + # if build is a release triggered by a versioned tag then create a github release + # and upload the build artifacts. A draft release is created so that the release + # can be reviewed before publishing - name: Upload Binaries to Release uses: softprops/action-gh-release@v2 + if: startsWith(github.ref, 'refs/tags/v') with: draft: true files: artifacts/*.px4 + name: ${{ steps.upload-location.outputs.uploadlocation }} diff --git a/.github/workflows/compile_ubuntu.yml b/.github/workflows/compile_ubuntu.yml index b213a5beaa..019081b9f6 100644 --- a/.github/workflows/compile_ubuntu.yml +++ b/.github/workflows/compile_ubuntu.yml @@ -29,7 +29,7 @@ jobs: fail-fast: false matrix: version: ['ubuntu:22.04', 'ubuntu:24.04'] - runs-on: [runs-on,runner=8cpu-linux-x64,"image=ubuntu24-full-x64","run-id=${{ github.run_id }}",spot=false] + runs-on: [runs-on,runner=4cpu-linux-x64,"image=ubuntu24-full-x64","run-id=${{ github.run_id }}",spot=false] container: image: ${{ matrix.version }} volumes: diff --git a/.github/workflows/dev_container.yml b/.github/workflows/dev_container.yml index a8dd32388e..ee61d80c3c 100644 --- a/.github/workflows/dev_container.yml +++ b/.github/workflows/dev_container.yml @@ -39,7 +39,7 @@ jobs: name: Set Tags and Variables permissions: contents: read - runs-on: [runs-on,"runner=1cpu-linux-x64","image=ubuntu24-full-x64","run-id=${{ github.run_id }}",spot=false,extras=s3-cache] + runs-on: [runs-on,"runner=1cpu-linux-x64","image=ubuntu24-full-x64","run-id=${{ github.run_id }}",extras=s3-cache,spot=false] outputs: px4_version: ${{ steps.px4_version.outputs.px4_version }} meta_tags: ${{ steps.meta.outputs.tags }} @@ -87,7 +87,7 @@ jobs: - platform: linux/amd64 arch: amd64 runner: x64 - runs-on: [runs-on,"runner=8cpu-linux-${{ matrix.runner }}","image=ubuntu24-full-${{ matrix.runner }}","run-id=${{ github.run_id }}",spot=false,extras=s3-cache] + runs-on: [runs-on,"runner=4cpu-linux-${{ matrix.runner }}","image=ubuntu24-full-${{ matrix.runner }}","run-id=${{ github.run_id }}",extras=s3-cache,spot=false] steps: - uses: runs-on/action@v1 - uses: actions/checkout@v4 @@ -138,7 +138,7 @@ jobs: permissions: contents: read packages: write - runs-on: [runs-on,"runner=8cpu-linux-x64","image=ubuntu24-full-x64","run-id=${{ github.run_id }}",spot=false,extras=s3-cache] + runs-on: [runs-on,"runner=4cpu-linux-x64","image=ubuntu24-full-x64","run-id=${{ github.run_id }}",extras=s3-cache,spot=false] needs: [build, setup] if: ${{ startsWith(github.ref, 'refs/tags/') || (github.event_name == 'workflow_dispatch' && github.event.inputs.deploy_to_registry) }} steps: diff --git a/.github/workflows/docs_deploy.yml b/.github/workflows/docs_deploy.yml index b8991e38c9..bdf729b2b3 100644 --- a/.github/workflows/docs_deploy.yml +++ b/.github/workflows/docs_deploy.yml @@ -20,7 +20,7 @@ env: jobs: build: - runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false,extras=s3-cache] + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",extras=s3-cache,spot=false] steps: - uses: runs-on/action@v1 - name: Checkout @@ -55,7 +55,7 @@ jobs: deploy: if: ${{ github.event_name == 'push' || (github.event_name == 'pull_request' && github.event.pull_request.merged) || github.event_name == 'workflow_dispatch' }} needs: build - runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] steps: - name: Download Artifact diff --git a/.github/workflows/docs_deploy_aws.yml b/.github/workflows/docs_deploy_aws.yml index 304100fd81..788a303d5e 100644 --- a/.github/workflows/docs_deploy_aws.yml +++ b/.github/workflows/docs_deploy_aws.yml @@ -30,7 +30,7 @@ concurrency: jobs: build: - runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false,extras=s3-cache] + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false,extras=s3-cache] outputs: branchname: ${{ steps.set-branch.outputs.branchname }} releaseversion: ${{ steps.set-version.outputs.releaseversion }} diff --git a/.github/workflows/flash_analysis.yml b/.github/workflows/flash_analysis.yml index e909e24822..143d54790c 100644 --- a/.github/workflows/flash_analysis.yml +++ b/.github/workflows/flash_analysis.yml @@ -24,7 +24,7 @@ env: jobs: analyze_flash: name: Analyzing ${{ matrix.target }} - runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] container: image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556 strategy: @@ -97,7 +97,7 @@ jobs: # Track this issue https://github.com/PX4/PX4-Autopilot/issues/24408 post_pr_comment: name: Publish Results - runs-on: [runs-on,runner=1cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] + runs-on: [runs-on,runner=1cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}"] needs: [analyze_flash] env: V5X-SUMMARY-MAP-ABS: ${{ fromJSON(fromJSON(needs.analyze_flash.outputs.px4_fmu-v5x-bloaty-summary-map).vm-absolute) }} diff --git a/.github/workflows/itcm_check.yml b/.github/workflows/itcm_check.yml index f6d5c4fd8c..5a1b0ecddc 100644 --- a/.github/workflows/itcm_check.yml +++ b/.github/workflows/itcm_check.yml @@ -22,7 +22,7 @@ concurrency: jobs: check_itcm: name: Checking ${{ matrix.target }} - runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] container: image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556 strategy: diff --git a/.github/workflows/ros_integration_tests.yml b/.github/workflows/ros_integration_tests.yml index e15aa081e7..022b46fb10 100644 --- a/.github/workflows/ros_integration_tests.yml +++ b/.github/workflows/ros_integration_tests.yml @@ -23,7 +23,7 @@ concurrency: jobs: build: - runs-on: [runs-on,runner=16cpu-linux-x64,image=ubuntu22-full-x64,"run-id=${{ github.run_id }}",spot=false] + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu22-full-x64,"run-id=${{ github.run_id }}",spot=false] container: image: px4io/px4-dev-ros2-galactic:2021-09-08 options: --privileged --ulimit core=-1 --security-opt seccomp=unconfined diff --git a/.github/workflows/ros_translation_node.yml b/.github/workflows/ros_translation_node.yml index 9b161dae90..64bae13f83 100644 --- a/.github/workflows/ros_translation_node.yml +++ b/.github/workflows/ros_translation_node.yml @@ -21,7 +21,7 @@ concurrency: jobs: build_and_test: name: Build and test - runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] strategy: fail-fast: false matrix: diff --git a/.github/workflows/sitl_tests.yml b/.github/workflows/sitl_tests.yml index 6dc6eccd2d..68e16bed71 100644 --- a/.github/workflows/sitl_tests.yml +++ b/.github/workflows/sitl_tests.yml @@ -24,7 +24,7 @@ concurrency: jobs: build: name: Testing PX4 ${{ matrix.config.model }} - runs-on: [runs-on,runner=16cpu-linux-x64,image=ubuntu22-full-x64,"run-id=${{ github.run_id }}",spot=false] + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu22-full-x64,"run-id=${{ github.run_id }}",spot=false] container: image: px4io/px4-dev-simulation-focal:2021-09-08 options: --privileged --ulimit core=-1 --security-opt seccomp=unconfined From d6f7519df0c9b7528abe8c98916c519a09385a6d Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 8 Oct 2025 15:14:05 -0700 Subject: [PATCH 157/812] ci: builds all cache pip Signed-off-by: Ramon Roche --- .github/workflows/build_all_targets.yml | 22 +++++++++++++++------- 1 file changed, 15 insertions(+), 7 deletions(-) diff --git a/.github/workflows/build_all_targets.yml b/.github/workflows/build_all_targets.yml index e2646be336..56e6a6ee1a 100644 --- a/.github/workflows/build_all_targets.yml +++ b/.github/workflows/build_all_targets.yml @@ -34,7 +34,7 @@ jobs: group_targets: name: Scan for Board Targets # runs-on: ubuntu-latest - runs-on: [runs-on,runner=1cpu-linux-x64,image=ubuntu22-full-x64,"run-id=${{ github.run_id }}",spot=false] + runs-on: [runs-on,runner=1cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false] outputs: matrix: ${{ steps.set-matrix.outputs.matrix }} timestamp: ${{ steps.set-timestamp.outputs.timestamp }} @@ -42,6 +42,14 @@ jobs: steps: - uses: actions/checkout@v4 + - name: Cache Python pip + uses: actions/cache@v4 + with: + path: ~/.cache/pip + key: ${{ runner.os }}-pip-${{ hashFiles('**./Tools/setup/requirements.txt') }} + restore-keys: | + ${{ runner.os }}-pip- + - name: Update python packaging to avoid canonicalize_version() error run: | pip3 install -U packaging @@ -99,7 +107,7 @@ jobs: # ccache---- # ccache---- # ccache---- - - name: Restore ccache from key + - name: Cache Restore from Key id: cc_restore uses: actions/cache/restore@v4 with: @@ -112,7 +120,7 @@ jobs: ccache-${{ runner.os }}- ccache- - - name: Set ccache defaults and show stats + - name: Cache Config and Stats run: | mkdir -p ~/.ccache echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf @@ -124,7 +132,7 @@ jobs: ccache -s ccache -z - - name: Building [${{ matrix.targets }}] + - name: Building Artifacts for [${{ matrix.targets }}] run: | ./Tools/ci/build_all_runner.sh ${{matrix.targets}} ${{matrix.arch}} @@ -138,7 +146,7 @@ jobs: name: px4_${{matrix.group}}_build_artifacts path: artifacts/ - - name: Post Build Cache Stats + - name: Cache Post Build Stats if: always() run: | ccache -s @@ -166,7 +174,7 @@ jobs: path: artifacts/ merge-multiple: true - - name: Upload Location + - name: Choose Upload Location id: upload-location run: | # Determine upload location based on branch or tag with the following considerations: @@ -225,7 +233,7 @@ jobs: # if build is a release triggered by a versioned tag then create a github release # and upload the build artifacts. A draft release is created so that the release # can be reviewed before publishing - - name: Upload Binaries to Release + - name: Upload Artifacts to GitHub Release uses: softprops/action-gh-release@v2 if: startsWith(github.ref, 'refs/tags/v') with: From 2f48cb4ef2373ee4a36b4f1bdb53be9404c7e5a2 Mon Sep 17 00:00:00 2001 From: Peter van der Perk <57130844+PetervdPerk-NXP@users.noreply.github.com> Date: Fri, 10 Oct 2025 09:28:43 +0200 Subject: [PATCH 158/812] MR-CANHUBK344 NXP B3RB Rover support (#23897) * s32k3xx: EMIOS allow independent frequencies for each channel * mr-canhubk3: update config * mr-canhubk344: Fix adap board detect * mr-canhubk344: Use LPSPI1 (Port P1A) for SD card * airframes: Add B3RB Ackermann rover config See https://nxp.gitbook.io/mr-b3rb for more information about the NXP B3RB platform. PX4 Support basic control for now --- .../init.d/airframes/51002_nxp_b3rb | 31 ++++++++++ .../init.d/airframes/CMakeLists.txt | 1 + boards/nxp/mr-canhubk3/fmu.px4board | 10 ++- .../mr-canhubk3/nuttx-config/nsh/defconfig | 15 +++++ boards/nxp/mr-canhubk3/src/board_config.h | 2 +- boards/nxp/mr-canhubk3/src/init.c | 10 +-- boards/nxp/mr-canhubk3/src/timer_config.cpp | 25 +++++--- .../s32k3xx/include/px4_arch/hw_description.h | 62 +++++++++++++++++-- .../nxp/s32k3xx/include/px4_arch/io_timer.h | 3 +- .../px4_arch/io_timer_hw_description.h | 41 ++++++++---- .../src/px4/nxp/s32k3xx/io_pins/io_timer.c | 5 ++ .../src/px4/nxp/s32k3xx/io_pins/pwm_servo.c | 4 +- 12 files changed, 170 insertions(+), 39 deletions(-) create mode 100644 ROMFS/px4fmu_common/init.d/airframes/51002_nxp_b3rb diff --git a/ROMFS/px4fmu_common/init.d/airframes/51002_nxp_b3rb b/ROMFS/px4fmu_common/init.d/airframes/51002_nxp_b3rb new file mode 100644 index 0000000000..09cf32a72e --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/airframes/51002_nxp_b3rb @@ -0,0 +1,31 @@ +#!/bin/sh +# +# @name NXP B3RB Rover Ackermann +# +# @type Rover +# @class Rover +# +# @board px4_fmu-v2 exclude +# @board bitcraze_crazyflie exclude +# + +. ${R}etc/init.d/rc.rover_ackermann_defaults + +param set-default BAT1_N_CELLS 3 + +# Set geometry & output configration +param set-default PWM_MAIN_FUNC1 201 +param set-default PWM_MAIN_FUNC2 101 +param set-default PWM_MAIN_FUNC3 101 +param set-default PWM_MAIN_DIS1 1500 +param set-default PWM_MAIN_DIS2 0 +param set-default PWM_MAIN_DIS3 1500 +param set-default PWM_MAIN_MIN1 1000 +param set-default PWM_MAIN_MIN2 2500 +param set-default PWM_MAIN_MIN3 0 +param set-default PWM_MAIN_MAX1 2000 +param set-default PWM_MAIN_MAX2 2500 +param set-default PWM_MAIN_MAX3 50 +param set-default PWM_MAIN_TIM0 400 +param set-default PWM_MAIN_TIM1 400 +param set-default PWM_MAIN_TIM2 20000 diff --git a/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt index 6728f842ce..8f13aa55b1 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt @@ -153,6 +153,7 @@ if(CONFIG_MODULES_ROVER_ACKERMANN) # [51000, 51999] Ackermann rovers 51000_generic_rover_ackermann 51001_axial_scx10_2_trail_honcho + 51002_nxp_b3rb ) endif() diff --git a/boards/nxp/mr-canhubk3/fmu.px4board b/boards/nxp/mr-canhubk3/fmu.px4board index 366fac4e09..7f7e146fd2 100644 --- a/boards/nxp/mr-canhubk3/fmu.px4board +++ b/boards/nxp/mr-canhubk3/fmu.px4board @@ -1,6 +1,8 @@ # CONFIG_BOARD_ROMFSROOT is not set CONFIG_DRIVERS_BAROMETER_BMP388=n CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=n +CONFIG_ARCH_CHIP_S32K3XX=y +CONFIG_BOARD_PWM_FREQ=1000000 CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS1" CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS4" CONFIG_BOARD_SERIAL_RC="/dev/ttyS5" @@ -20,6 +22,7 @@ CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_SF45_SERIAL=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IRLOCK=y CONFIG_DRIVERS_RC_INPUT=y +CONFIG_DRIVERS_ROBOCLAW=y CONFIG_DRIVERS_SAFETY_BUTTON=y CONFIG_DRIVERS_UAVCAN=y CONFIG_EXAMPLES_FAKE_GPS=y @@ -33,9 +36,10 @@ CONFIG_MODULES_EVENTS=y CONFIG_MODULES_FLIGHT_MODE_MANAGER=y CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y -CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_GYRO_FFT=y CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y @@ -50,8 +54,10 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y -CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_ROVER_ACKERMANN=y +CONFIG_MODULES_ROVER_DIFFERENTIAL=y +CONFIG_MODULES_ROVER_MECANUM=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y CONFIG_MODULES_UXRCE_DDS_CLIENT=y CONFIG_MODULES_VTOL_ATT_CONTROL=y diff --git a/boards/nxp/mr-canhubk3/nuttx-config/nsh/defconfig b/boards/nxp/mr-canhubk3/nuttx-config/nsh/defconfig index 45821d6c6f..c397305d7e 100644 --- a/boards/nxp/mr-canhubk3/nuttx-config/nsh/defconfig +++ b/boards/nxp/mr-canhubk3/nuttx-config/nsh/defconfig @@ -94,6 +94,7 @@ CONFIG_FAT_LFN_ALIAS_HASH=y CONFIG_FDCLONE_STDIO=y CONFIG_FS26_SPI_FREQUENCY=5000000 CONFIG_FSUTILS_IPCFG=y +CONFIG_FS_BINFS=y CONFIG_FS_CROMFS=y CONFIG_FS_FAT=y CONFIG_FS_FATTIME=y @@ -126,16 +127,24 @@ CONFIG_LPUART0_IFLOWCONTROL=y CONFIG_LPUART0_OFLOWCONTROL=y CONFIG_LPUART0_RXBUFSIZE=640 CONFIG_LPUART0_RXDMA=y +CONFIG_LPUART0_TXBUFSIZE=1100 CONFIG_LPUART0_TXDMA=y CONFIG_LPUART13_RXDMA=y CONFIG_LPUART13_TXDMA=y CONFIG_LPUART14_RXDMA=y CONFIG_LPUART14_TXDMA=y +CONFIG_LPUART1_RXBUFSIZE=600 CONFIG_LPUART1_RXDMA=y +CONFIG_LPUART1_TXBUFSIZE=1100 CONFIG_LPUART1_TXDMA=y CONFIG_LPUART2_RXDMA=y CONFIG_LPUART2_SERIAL_CONSOLE=y CONFIG_LPUART2_TXDMA=y +CONFIG_LPUART4_RXBUFSIZE=600 +CONFIG_LPUART4_TXBUFSIZE=600 +CONFIG_LPUART7_RXDMA=y +CONFIG_LPUART7_TXBUFSIZE=1500 +CONFIG_LPUART7_TXDMA=y CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y @@ -197,6 +206,7 @@ CONFIG_NSH_LINELEN=128 CONFIG_NSH_MAXARGUMENTS=15 CONFIG_NSH_MMCSDSPIPORTNO=1 CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_READLINE=y CONFIG_NSH_QUOTE=y CONFIG_NSH_ROMFSETC=y CONFIG_NSH_ROMFSSECTSIZE=128 @@ -213,6 +223,8 @@ CONFIG_PTHREAD_STACK_MIN=512 CONFIG_RAM_SIZE=272000 CONFIG_RAM_START=0x20400000 CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y CONFIG_S32K3XX_DTCM_HEAP=y CONFIG_S32K3XX_EDMA=y CONFIG_S32K3XX_EDMA_EDBG=y @@ -280,7 +292,10 @@ CONFIG_STACK_COLORATION=y CONFIG_START_DAY=30 CONFIG_START_MONTH=11 CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_SYSTEM_CLE=y CONFIG_SYSTEM_DHCPC_RENEW=y CONFIG_SYSTEM_NSH=y CONFIG_SYSTEM_PING=y +CONFIG_SYSTEM_SYSTEM=y CONFIG_TASK_NAME_SIZE=24 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/nxp/mr-canhubk3/src/board_config.h b/boards/nxp/mr-canhubk3/src/board_config.h index 7ea2a91e8b..47f1ca3c36 100644 --- a/boards/nxp/mr-canhubk3/src/board_config.h +++ b/boards/nxp/mr-canhubk3/src/board_config.h @@ -112,7 +112,7 @@ __BEGIN_DECLS /* To detect MR-CANHUBK3-ADAP board */ #define BOARD_HAS_HW_VERSIONING 1 -#define CANHUBK3_ADAP_DETECT (PIN_PTA12 | GPIO_INPUT | GPIO_PULLUP) +#define CANHUBK3_ADAP_DETECT (PIN_PTA11 | GPIO_INPUT | GPIO_PULLUP) /* diff --git a/boards/nxp/mr-canhubk3/src/init.c b/boards/nxp/mr-canhubk3/src/init.c index 97a41f8430..15148c7845 100644 --- a/boards/nxp/mr-canhubk3/src/init.c +++ b/boards/nxp/mr-canhubk3/src/init.c @@ -105,18 +105,18 @@ __EXPORT int board_app_initialize(uintptr_t arg) /* Configure LPSPI1 peripheral chip select */ - s32k3xx_pinconfig(PIN_LPSPI2_PCS); + s32k3xx_pinconfig(PIN_LPSPI1_PCS); /* Initialize the SPI driver for LPSPI1 */ - struct spi_dev_s *g_lpspi2 = s32k3xx_lpspibus_initialize(2); + struct spi_dev_s *g_lpspi1 = s32k3xx_lpspibus_initialize(1); - if (g_lpspi2 == NULL) { - spierr("ERROR: FAILED to initialize LPSPI2\n"); + if (g_lpspi1 == NULL) { + spierr("ERROR: FAILED to initialize LPSPI1\n"); return -ENODEV; } - rv = mmcsd_spislotinitialize(0, 0, g_lpspi2); + rv = mmcsd_spislotinitialize(0, 0, g_lpspi1); if (rv < 0) { mcerr("ERROR: Failed to bind SPI port %d to SD slot %d\n", diff --git a/boards/nxp/mr-canhubk3/src/timer_config.cpp b/boards/nxp/mr-canhubk3/src/timer_config.cpp index 607917f614..24b29ca071 100644 --- a/boards/nxp/mr-canhubk3/src/timer_config.cpp +++ b/boards/nxp/mr-canhubk3/src/timer_config.cpp @@ -51,18 +51,25 @@ constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { - initIOTimer(Timer::EMIOS0) + initIOTimer(Timer::EMIOS0_Channel0, Timer::Channel0), + initIOTimer(Timer::EMIOS0_Channel1, Timer::Channel1), + initIOTimer(Timer::EMIOS0_Channel2, Timer::Channel2), + initIOTimer(Timer::EMIOS0_Channel3, Timer::Channel3), + initIOTimer(Timer::EMIOS0_Channel4, Timer::Channel4), + initIOTimer(Timer::EMIOS0_Channel5, Timer::Channel5), + initIOTimer(Timer::EMIOS0_Channel6, Timer::Channel6), + initIOTimer(Timer::EMIOS0_Channel7, Timer::Channel7), }; constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { - initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel0}, PIN_EMIOS0_CH0_1), - initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel1}, PIN_EMIOS0_CH1_1), - initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel2}, PIN_EMIOS0_CH2_1), - initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel3}, PIN_EMIOS0_CH3_2), - initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel4}, PIN_EMIOS0_CH4_2), - initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel5}, PIN_EMIOS0_CH5_2), - initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel6}, PIN_EMIOS0_CH6_1), - initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel7}, PIN_EMIOS0_CH7_2), + initIOTimerChannel(io_timers, {Timer::EMIOS0_Channel0, Timer::Channel0}, PIN_EMIOS0_CH0_1), + initIOTimerChannel(io_timers, {Timer::EMIOS0_Channel1, Timer::Channel1}, PIN_EMIOS0_CH1_1), + initIOTimerChannel(io_timers, {Timer::EMIOS0_Channel2, Timer::Channel2}, PIN_EMIOS0_CH2_1), + initIOTimerChannel(io_timers, {Timer::EMIOS0_Channel3, Timer::Channel3}, PIN_EMIOS0_CH3_2), + initIOTimerChannel(io_timers, {Timer::EMIOS0_Channel4, Timer::Channel4}, PIN_EMIOS0_CH4_2), + initIOTimerChannel(io_timers, {Timer::EMIOS0_Channel5, Timer::Channel5}, PIN_EMIOS0_CH5_2), + initIOTimerChannel(io_timers, {Timer::EMIOS0_Channel6, Timer::Channel6}, PIN_EMIOS0_CH6_1), + initIOTimerChannel(io_timers, {Timer::EMIOS0_Channel7, Timer::Channel7}, PIN_EMIOS0_CH7_2), }; constexpr io_timers_channel_mapping_t io_timers_channel_mapping = diff --git a/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/hw_description.h b/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/hw_description.h index e6d854bef3..09559f950b 100644 --- a/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/hw_description.h +++ b/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/hw_description.h @@ -46,10 +46,34 @@ namespace Timer { + + +// Just to keep def extract_timer(line): happy enum Timer { - EMIOS0 = 0, - EMIOS1, - EMIOS2, + EMIOS0_Channel0, + EMIOS0_Channel1, + EMIOS0_Channel2, + EMIOS0_Channel3, + EMIOS0_Channel4, + EMIOS0_Channel5, + EMIOS0_Channel6, + EMIOS0_Channel7, + EMIOS1_Channel0, + EMIOS1_Channel1, + EMIOS1_Channel2, + EMIOS1_Channel3, + EMIOS1_Channel4, + EMIOS1_Channel5, + EMIOS1_Channel6, + EMIOS1_Channel7, + EMIOS2_Channel0, + EMIOS2_Channel1, + EMIOS2_Channel2, + EMIOS2_Channel3, + EMIOS2_Channel4, + EMIOS2_Channel5, + EMIOS2_Channel6, + EMIOS2_Channel7, }; enum Channel { Channel0 = 0, @@ -70,11 +94,37 @@ struct TimerChannel { static inline constexpr uint32_t timerBaseRegister(Timer::Timer timer) { switch (timer) { - case Timer::EMIOS0: return S32K3XX_EMIOS0_BASE; + case Timer::EMIOS0_Channel0: + case Timer::EMIOS0_Channel1: + case Timer::EMIOS0_Channel2: + case Timer::EMIOS0_Channel3: + case Timer::EMIOS0_Channel4: + case Timer::EMIOS0_Channel5: + case Timer::EMIOS0_Channel6: + case Timer::EMIOS0_Channel7: + return S32K3XX_EMIOS0_BASE; - case Timer::EMIOS1: return S32K3XX_EMIOS1_BASE; - case Timer::EMIOS2: return S32K3XX_EMIOS2_BASE; + + case Timer::EMIOS1_Channel0: + case Timer::EMIOS1_Channel1: + case Timer::EMIOS1_Channel2: + case Timer::EMIOS1_Channel3: + case Timer::EMIOS1_Channel4: + case Timer::EMIOS1_Channel5: + case Timer::EMIOS1_Channel6: + case Timer::EMIOS1_Channel7: + return S32K3XX_EMIOS1_BASE; + + case Timer::EMIOS2_Channel0: + case Timer::EMIOS2_Channel1: + case Timer::EMIOS2_Channel2: + case Timer::EMIOS2_Channel3: + case Timer::EMIOS2_Channel4: + case Timer::EMIOS2_Channel5: + case Timer::EMIOS2_Channel6: + case Timer::EMIOS2_Channel7: + return S32K3XX_EMIOS2_BASE; } return 0; diff --git a/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/io_timer.h b/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/io_timer.h index d6e0ad6eb5..e569349dd5 100644 --- a/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/io_timer.h +++ b/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/io_timer.h @@ -45,7 +45,7 @@ #pragma once __BEGIN_DECLS /* configuration limits */ -#define MAX_IO_TIMERS 1 +#define MAX_IO_TIMERS 8 #define MAX_TIMER_IO_CHANNELS 8 #define MAX_LED_TIMERS 2 @@ -88,6 +88,7 @@ typedef struct io_timers_t { uint32_t vectorno_12_15; /* IRQ number */ uint32_t vectorno_16_19; /* IRQ number */ uint32_t vectorno_20_23; /* IRQ number */ + uint32_t channel; } io_timers_t; typedef struct io_timers_channel_mapping_element_t { diff --git a/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/io_timer_hw_description.h b/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/io_timer_hw_description.h index b689593a53..724d944792 100644 --- a/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/io_timer_hw_description.h +++ b/platforms/nuttx/src/px4/nxp/s32k3xx/include/px4_arch/io_timer_hw_description.h @@ -55,15 +55,7 @@ static inline constexpr timer_io_channels_t initIOTimerChannel(const io_timers_t ret.timer_channel = (int)timer.channel + 1; // find timer index - ret.timer_index = 0xff; - const uint32_t timer_base = timerBaseRegister(timer.timer); - - for (int i = 0; i < MAX_IO_TIMERS; ++i) { - if (io_timers_conf[i].base == timer_base) { - ret.timer_index = i; - break; - } - } + ret.timer_index = timer.channel; constexpr_assert(ret.timer_index != 0xff, "Timer not found"); @@ -80,13 +72,20 @@ static inline constexpr timer_io_channels_t initIOTimerChannel(const io_timers_t * Ch20 - Ch23 = vectorno - 5 */ -static inline constexpr io_timers_t initIOTimer(Timer::Timer timer) +static inline constexpr io_timers_t initIOTimer(Timer::Timer timer, Timer::Channel channel) { bool nuttx_config_timer_enabled = false; io_timers_t ret{}; switch (timer) { - case Timer::EMIOS0: + case Timer::EMIOS0_Channel0: + case Timer::EMIOS0_Channel1: + case Timer::EMIOS0_Channel2: + case Timer::EMIOS0_Channel3: + case Timer::EMIOS0_Channel4: + case Timer::EMIOS0_Channel5: + case Timer::EMIOS0_Channel6: + case Timer::EMIOS0_Channel7: ret.base = S32K3XX_EMIOS0_BASE; ret.clock_register = 0; ret.clock_bit = 0; @@ -96,12 +95,20 @@ static inline constexpr io_timers_t initIOTimer(Timer::Timer timer) ret.vectorno_12_15 = S32K3XX_IRQ_EMIOS0_12_15; ret.vectorno_16_19 = S32K3XX_IRQ_EMIOS0_16_19; ret.vectorno_20_23 = S32K3XX_IRQ_EMIOS0_20_23; + ret.channel = channel; #ifdef CONFIG_S32K3XX_EMIOS0 nuttx_config_timer_enabled = true; #endif break; - case Timer::EMIOS1: + case Timer::EMIOS1_Channel0: + case Timer::EMIOS1_Channel1: + case Timer::EMIOS1_Channel2: + case Timer::EMIOS1_Channel3: + case Timer::EMIOS1_Channel4: + case Timer::EMIOS1_Channel5: + case Timer::EMIOS1_Channel6: + case Timer::EMIOS1_Channel7: ret.base = S32K3XX_EMIOS1_BASE; ret.clock_register = 0; ret.clock_bit = 0; @@ -116,7 +123,15 @@ static inline constexpr io_timers_t initIOTimer(Timer::Timer timer) #endif break; - case Timer::EMIOS2: + + case Timer::EMIOS2_Channel0: + case Timer::EMIOS2_Channel1: + case Timer::EMIOS2_Channel2: + case Timer::EMIOS2_Channel3: + case Timer::EMIOS2_Channel4: + case Timer::EMIOS2_Channel5: + case Timer::EMIOS2_Channel6: + case Timer::EMIOS2_Channel7: ret.base = S32K3XX_EMIOS2_BASE; ret.clock_register = 0; ret.clock_bit = 0; diff --git a/platforms/nuttx/src/px4/nxp/s32k3xx/io_pins/io_timer.c b/platforms/nuttx/src/px4/nxp/s32k3xx/io_pins/io_timer.c index 2a3a0afce5..1a56a5338a 100644 --- a/platforms/nuttx/src/px4/nxp/s32k3xx/io_pins/io_timer.c +++ b/platforms/nuttx/src/px4/nxp/s32k3xx/io_pins/io_timer.c @@ -868,6 +868,11 @@ int io_timer_set_ccr(unsigned channel, uint16_t value) } else { //FIXME why multiple by 2 + + if ((rC(channels_timer(channel), channel) & EMIOS_C_UCPRE_MASK) == 0) { + value = value * 4; + } + /* configure the channel */ irqstate_t flags = px4_enter_critical_section(); rA(channels_timer(channel), timer_io_channels[channel].timer_channel - 1) = EMIOS_A(value * 2); diff --git a/platforms/nuttx/src/px4/nxp/s32k3xx/io_pins/pwm_servo.c b/platforms/nuttx/src/px4/nxp/s32k3xx/io_pins/pwm_servo.c index 6f613b2149..6178c86c64 100644 --- a/platforms/nuttx/src/px4/nxp/s32k3xx/io_pins/pwm_servo.c +++ b/platforms/nuttx/src/px4/nxp/s32k3xx/io_pins/pwm_servo.c @@ -128,13 +128,13 @@ int up_pwm_servo_set_rate_group_update(unsigned channel, unsigned rate) if (rate != 0) { - /* limit update rate to 1..10000Hz; somewhat arbitrary but safe */ + /* limit update rate to 1..20000Hz; somewhat arbitrary but safe */ if (rate < 1) { return -ERANGE; } - if (rate > 10000) { + if (rate > 20000) { return -ERANGE; } } From b95784e8042176b15a082ad8b5e4ddf841d7c77e Mon Sep 17 00:00:00 2001 From: Jaeyoung Lim Date: Fri, 10 Oct 2025 10:00:43 -0700 Subject: [PATCH 159/812] Consume speedweight from FW longitudinal config (#25709) * Consume speedweight from longitudinal config * Constrain speed weight --- .../FwLateralLongitudinalControl.cpp | 6 ++++++ .../FwLateralLongitudinalControl.hpp | 1 + 2 files changed, 7 insertions(+) diff --git a/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp b/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp index 73df2a8683..9c5647f1a5 100644 --- a/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp +++ b/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.cpp @@ -827,6 +827,12 @@ void FwLateralLongitudinalControl::updateLongitudinalControlConfiguration(const } else { _long_configuration.sink_rate_target = _param_sinkrate_target.get(); } + + if (PX4_ISFINITE(configuration_in.speed_weight)) { + _long_configuration.speed_weight = math::constrain(configuration_in.speed_weight, 0.f, 2.f); + } else { + _long_configuration.speed_weight = _param_t_spdweight.get(); + } } float FwLateralLongitudinalControl::getLoadFactor() const diff --git a/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.hpp b/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.hpp index 590054ae89..87b94b1bf3 100644 --- a/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.hpp +++ b/src/modules/fw_lateral_longitudinal_control/FwLateralLongitudinalControl.hpp @@ -157,6 +157,7 @@ private: (ParamFloat) _param_fw_t_vert_acc, (ParamFloat) _param_ste_rate_time_const, (ParamFloat) _param_seb_rate_ff, + (ParamFloat) _param_t_spdweight, (ParamFloat) _param_speed_standard_dev, (ParamFloat) _param_speed_rate_standard_dev, (ParamFloat) _param_process_noise_standard_dev, From 12f6005c5cea42a8c8135d17cfa5db8eb2fc0327 Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Fri, 10 Oct 2025 09:29:27 -0800 Subject: [PATCH 160/812] romfs: allow target level airframe selection (#25677) --- ROMFS/CMakeLists.txt | 22 ++++++++++++++++++++++ boards/ark/pi6x/init/rc.board_airframes | 2 ++ 2 files changed, 24 insertions(+) create mode 100644 boards/ark/pi6x/init/rc.board_airframes diff --git a/ROMFS/CMakeLists.txt b/ROMFS/CMakeLists.txt index e1b08d078b..9b282339fd 100644 --- a/ROMFS/CMakeLists.txt +++ b/ROMFS/CMakeLists.txt @@ -85,10 +85,32 @@ endif() if(PX4_ETHERNET) set(added_arguments ${added_arguments} --ethernet) endif() +# Check if board has an rc.board_airframes file to filter airframes +set(board_airframes_file "${PX4_BOARD_DIR}/init/rc.board_airframes") +set(airframes_whitelist "") +if(EXISTS "${board_airframes_file}") + message(STATUS "ROMFS: Using board-specific airframes list: ${board_airframes_file}") + file(STRINGS "${board_airframes_file}" airframes_whitelist) + # Remove comments and empty lines + list(FILTER airframes_whitelist EXCLUDE REGEX "^[ \t]*#") + list(FILTER airframes_whitelist EXCLUDE REGEX "^[ \t]*$") +endif() + # create list of relative romfs file names set(romfs_copy_files_relative) foreach(romfs_file IN LISTS romfs_copy_files) string(REPLACE "${romfs_src_dir}/" "" romfs_file_rel ${romfs_file}) + + # If we have an airframes whitelist, filter airframe files + if(airframes_whitelist AND romfs_file_rel MATCHES "^init.d/airframes/") + # Extract just the filename + get_filename_component(airframe_name "${romfs_file_rel}" NAME) + # Check if it's in the whitelist + if(NOT "${airframe_name}" IN_LIST airframes_whitelist) + continue() + endif() + endif() + list(APPEND romfs_copy_files_relative ${romfs_file_rel}) endforeach() # copy the ROMFS files by creating a tar and extracting it to the build diff --git a/boards/ark/pi6x/init/rc.board_airframes b/boards/ark/pi6x/init/rc.board_airframes new file mode 100644 index 0000000000..4468c66ee4 --- /dev/null +++ b/boards/ark/pi6x/init/rc.board_airframes @@ -0,0 +1,2 @@ +4001_quad_x +4601_droneblocks_dexi_5 From 2fba5b4c1a16a39868245b0fa90860094ed5ae26 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Fri, 10 Oct 2025 10:43:20 -0700 Subject: [PATCH 161/812] ci: pull emscripten v4.0.15 to avoid c++17 errors (#25739) https://github.com/emscripten-core/emscripten/issues/24850 Signed-off-by: Ramon Roche --- .github/workflows/failsafe_sim.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/failsafe_sim.yml b/.github/workflows/failsafe_sim.yml index edf3d1cd67..24cdb49550 100644 --- a/.github/workflows/failsafe_sim.yml +++ b/.github/workflows/failsafe_sim.yml @@ -48,6 +48,7 @@ jobs: run: | git clone https://github.com/emscripten-core/emsdk.git _emscripten_sdk cd _emscripten_sdk + git checkout 4.0.15 ./emsdk install latest ./emsdk activate latest From edc7a2bb80656f64fa44baf63dfb57e106070a13 Mon Sep 17 00:00:00 2001 From: Peter van der Perk <57130844+PetervdPerk-NXP@users.noreply.github.com> Date: Fri, 10 Oct 2025 19:46:26 +0200 Subject: [PATCH 162/812] fmu-v6xrt: Add DTCM to heap (#25733) Move ramvectors from DTCM to ITCM, this seems to better in general. Also ITCM is marked as RO so is safer anyhow, now that DTCM is fully unused we add DTCM region of 256kB to memory allocator. Increases usable memory from 1536kB to 1792kB and decrease system load a bit since DTCM is faster --- boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig | 6 ++++-- boards/px4/fmu-v6xrt/nuttx-config/scripts/script.ld | 9 ++------- 2 files changed, 6 insertions(+), 9 deletions(-) diff --git a/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig index 0ab458bed6..855c435833 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6xrt/nuttx-config/nsh/defconfig @@ -78,7 +78,8 @@ CONFIG_HAVE_CXXINITIALIZE=y CONFIG_I2C=y CONFIG_I2C_RESET=y CONFIG_IDLETHREAD_STACKSIZE=2048 -CONFIG_IMXRT_DTCM=0 +CONFIG_IMXRT_DTCM=256 +CONFIG_IMXRT_DTCM_HEAP=y CONFIG_IMXRT_EDMA=y CONFIG_IMXRT_EDMA_EDBG=y CONFIG_IMXRT_EDMA_ELINK=y @@ -104,7 +105,7 @@ CONFIG_IMXRT_GPIO6_0_15_IRQ=y CONFIG_IMXRT_GPIO6_16_31_IRQ=y CONFIG_IMXRT_GPIO_IRQ=y CONFIG_IMXRT_INIT_FLEXRAM=y -CONFIG_IMXRT_ITCM=0 +CONFIG_IMXRT_ITCM=256 CONFIG_IMXRT_LPI2C1=y CONFIG_IMXRT_LPI2C2=y CONFIG_IMXRT_LPI2C3=y @@ -190,6 +191,7 @@ CONFIG_MEMSET_64BIT=y CONFIG_MEMSET_OPTSPEED=y CONFIG_MMCSD=y CONFIG_MMCSD_SDIO=y +CONFIG_MM_REGIONS=2 CONFIG_MTD=y CONFIG_MTD_BYTE_WRITE=y CONFIG_MTD_PARTITION=y diff --git a/boards/px4/fmu-v6xrt/nuttx-config/scripts/script.ld b/boards/px4/fmu-v6xrt/nuttx-config/scripts/script.ld index 70d861f30a..f9eb6915d0 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/scripts/script.ld +++ b/boards/px4/fmu-v6xrt/nuttx-config/scripts/script.ld @@ -35,7 +35,7 @@ MEMORY { flash (rx) : ORIGIN = 0x30020000, LENGTH = 4M-128K /* We have 64M but we do not want to wait to program it all */ - sram (rwx) : ORIGIN = 0x20240000, LENGTH = 2M-256k-512k + sram (rwx) : ORIGIN = 0x20240000, LENGTH = 2M-256k itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 256K /* TODO FlexRAM partition */ dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 256K } @@ -83,6 +83,7 @@ SECTIONS _sitcmfuncs = ABSOLUTE(.); FILL(0xFF) . = 0x40 ; + *(.ram_vectors) INCLUDE "itcm_static_functions.ld" INCLUDE "itcm_functions_includes.ld" . = ALIGN(8); @@ -91,12 +92,6 @@ SECTIONS _fitcmfuncs = LOADADDR(.itcmfunc); - /* The RAM vector table (if present) should lie at the beginning of SRAM */ - - .ram_vectors (COPY) : { - *(.ram_vectors) - } > dtcm - .text : ALIGN(4) { _stext = ABSOLUTE(.); From 96904636f3dd288d39963b547fcbbf3892e703af Mon Sep 17 00:00:00 2001 From: Mahima Yoga Date: Fri, 10 Oct 2025 19:59:26 +0200 Subject: [PATCH 163/812] commander: prevent setting nav_state to takeoff after disarming (#25735) * commander: prevent setting nav_state after disarming to takeoff * wrap in function --- src/modules/commander/UserModeIntention.cpp | 3 ++- src/modules/commander/UserModeIntention.hpp | 1 + 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/src/modules/commander/UserModeIntention.cpp b/src/modules/commander/UserModeIntention.cpp index 556bddbd18..2085995d6c 100644 --- a/src/modules/commander/UserModeIntention.cpp +++ b/src/modules/commander/UserModeIntention.cpp @@ -77,7 +77,8 @@ bool UserModeIntention::change(uint8_t user_intended_nav_state, ModeChangeSource // Special case termination state: even though this mode prevents arming, // still don't switch out of it after disarm and thus store it in _nav_state_after_disarming. - if (!_health_and_arming_checks.modePreventsArming(user_intended_nav_state) + if ((!_health_and_arming_checks.modePreventsArming(user_intended_nav_state) + && !isTakeOffIntended(user_intended_nav_state)) || user_intended_nav_state == vehicle_status_s::NAVIGATION_STATE_TERMINATION) { _nav_state_after_disarming = user_intended_nav_state; } diff --git a/src/modules/commander/UserModeIntention.hpp b/src/modules/commander/UserModeIntention.hpp index cfb4e3998b..e37bf467b1 100644 --- a/src/modules/commander/UserModeIntention.hpp +++ b/src/modules/commander/UserModeIntention.hpp @@ -91,6 +91,7 @@ public: private: bool isArmed() const { return _vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED; } + bool isTakeOffIntended(uint8_t user_intented_nav_state) const {return user_intented_nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF || user_intented_nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF;} const vehicle_status_s &_vehicle_status; const HealthAndArmingChecks &_health_and_arming_checks; From 3336050f844a6c417178c373b4fe4a22d5b6f90d Mon Sep 17 00:00:00 2001 From: Farhang <46557204+farhangnaderi@users.noreply.github.com> Date: Fri, 10 Oct 2025 13:57:24 -0400 Subject: [PATCH 164/812] First commit --- Tools/setup/requirements.txt | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Tools/setup/requirements.txt b/Tools/setup/requirements.txt index a15da9b9e9..b9d83da852 100644 --- a/Tools/setup/requirements.txt +++ b/Tools/setup/requirements.txt @@ -6,6 +6,7 @@ future jinja2>=2.8 jsonschema kconfiglib +lark lxml matplotlib>=3.0 numpy>=1.13 @@ -14,8 +15,8 @@ packaging pandas>=0.21 pkgconfig psutil +pycryptodome pygments -wheel>=0.31.1 pymavlink pyros-genmsg pyserial @@ -24,7 +25,6 @@ pyyaml requests setuptools>=39.2.0 six>=1.12.0 -toml>=0.9 sympy>=1.10.1 -pycryptodome -lark +toml>=0.9 +wheel>=0.31.1 From d6fc448a36e900a7979d516d5b595091ac907d59 Mon Sep 17 00:00:00 2001 From: Connor Denihan <188690869+cdenihan@users.noreply.github.com> Date: Sat, 11 Oct 2025 16:54:32 -0400 Subject: [PATCH 165/812] Update supported Ubuntu versions in dev environment docs (#25743) --- docs/en/dev_setup/dev_env.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/en/dev_setup/dev_env.md b/docs/en/dev_setup/dev_env.md index fddacba0cc..7a6db718af 100644 --- a/docs/en/dev_setup/dev_env.md +++ b/docs/en/dev_setup/dev_env.md @@ -2,7 +2,7 @@ The _supported platforms_ for PX4 development are: -- [Ubuntu Linux (22.04/20.04/18.04)](../dev_setup/dev_env_linux_ubuntu.md) — Recommended +- [Ubuntu Linux (24.04/22.04)](../dev_setup/dev_env_linux_ubuntu.md) — Recommended - [Windows (10/11)](../dev_setup/dev_env_windows_wsl.md) — via WSL2 - [Mac OS](../dev_setup/dev_env_mac.md) From 9a6e4b5ace0140f4f02269395025861d0e8c392f Mon Sep 17 00:00:00 2001 From: Connor Denihan <188690869+cdenihan@users.noreply.github.com> Date: Sat, 11 Oct 2025 18:23:55 -0400 Subject: [PATCH 166/812] docs: Fix capitalization of macOS (#25744) * Fix formatting and capitalization in dev_env_mac.md Updated formatting and capitalization for consistency in the macOS development environment documentation. * Correct 'Mac OS' to 'macOS' in documentation * Fix capitalization of 'macOS' in documentation --- docs/en/concept/system_startup.md | 4 ++-- docs/en/dev_setup/dev_env.md | 4 ++-- docs/en/dev_setup/dev_env_mac.md | 8 ++++---- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/docs/en/concept/system_startup.md b/docs/en/concept/system_startup.md index 4ef80d0de1..d425d35173 100644 --- a/docs/en/concept/system_startup.md +++ b/docs/en/concept/system_startup.md @@ -1,7 +1,7 @@ # System Startup The PX4 startup is controlled by shell scripts. -On NuttX they reside in the [ROMFS/px4fmu_common/init.d](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d) folder - some of these are also used on Posix (Linux/MacOS). +On NuttX they reside in the [ROMFS/px4fmu_common/init.d](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d) folder - some of these are also used on Posix (Linux/macOS). The scripts that are only used on Posix are located in [ROMFS/px4fmu_common/init.d-posix](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d-posix). All files starting with a number and underscore (e.g. `10000_airplane`) are predefined airframe configurations. @@ -13,7 +13,7 @@ The first executed file is the [init.d/rcS](https://github.com/PX4/PX4-Autopilot The following sections are split according to the operating system that PX4 runs on. -## POSIX (Linux/MacOS) +## POSIX (Linux/macOS) On POSIX, the system shell is used as script interpreter (e.g. /bin/sh, being symlinked to dash on Ubuntu). For that to work, a few things are required: diff --git a/docs/en/dev_setup/dev_env.md b/docs/en/dev_setup/dev_env.md index 7a6db718af..33069072c6 100644 --- a/docs/en/dev_setup/dev_env.md +++ b/docs/en/dev_setup/dev_env.md @@ -4,13 +4,13 @@ The _supported platforms_ for PX4 development are: - [Ubuntu Linux (24.04/22.04)](../dev_setup/dev_env_linux_ubuntu.md) — Recommended - [Windows (10/11)](../dev_setup/dev_env_windows_wsl.md) — via WSL2 -- [Mac OS](../dev_setup/dev_env_mac.md) +- [macOS](../dev_setup/dev_env_mac.md) ## Supported Targets The table below shows what PX4 targets you can build on each OS. -| Target | Linux (Ubuntu) | Mac | Windows | +| Target | Linux (Ubuntu) | macOS | Windows | | -------------------------------------------------------------------------------------------------------------------------------------- | :------------: | :-: | :-----: | | **NuttX based hardware:** [Pixhawk Series](../flight_controller/pixhawk_series.md), [Crazyflie](../complete_vehicles_mc/crazyflie2.md) | ✓ | ✓ | ✓ | | **Linux-based hardware:** [Raspberry Pi 2/3](../flight_controller/raspberry_pi_navio2.md) | ✓ | | | diff --git a/docs/en/dev_setup/dev_env_mac.md b/docs/en/dev_setup/dev_env_mac.md index a77be14982..fee66f554e 100644 --- a/docs/en/dev_setup/dev_env_mac.md +++ b/docs/en/dev_setup/dev_env_mac.md @@ -1,4 +1,4 @@ -# MacOS Development Environment +# macOS Development Environment The following instructions set up a PX4 development environment for macOS. This environment can be used to build PX4 for: @@ -21,8 +21,8 @@ The "base" macOS setup installs the tools needed for building firmware, and incl ### Environment Setup -:::details Apple Silicon Macbook users! -If you have an Apple M1, M2 etc. Macbook, make sure to run the terminal as x86 by setting up an x86 terminal: +:::details Apple Silicon MacBook users! +If you have an Apple M1, M2 etc. MacBook, make sure to run the terminal as x86 by setting up an x86 terminal: 1. Locate the Terminal application within the Utilities folder (**Finder > Go menu > Utilities**) 2. Select _Terminal.app_ and right-click on it, then choose **Duplicate**. @@ -47,7 +47,7 @@ First set up the environment 1. Enforce Python 3 by appending the following lines to `~/.zshenv` ```sh - # Point pip3 to MacOS system python 3 pip + # Point pip3 to macOS system python 3 pip alias pip3=/usr/bin/pip3 ``` From 54679f11d091d0cf015fbd5777aa817dba08b719 Mon Sep 17 00:00:00 2001 From: Alexander Sherikov Date: Sun, 12 Oct 2025 02:24:30 +0400 Subject: [PATCH 167/812] px_update_git_header: fix nuttx version detection (#25742) use fake nuttx version tag when the real one cannot be detected --- src/lib/version/px_update_git_header.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/src/lib/version/px_update_git_header.py b/src/lib/version/px_update_git_header.py index bd1836fb03..024563b598 100755 --- a/src/lib/version/px_update_git_header.py +++ b/src/lib/version/px_update_git_header.py @@ -129,8 +129,12 @@ if (os.path.exists('src/modules/mavlink/mavlink/.git')): if (os.path.exists('platforms/nuttx/NuttX/nuttx/.git')): nuttx_git_tags = subprocess.check_output('git -c versionsort.suffix=- tag --sort=v:refname'.split(), cwd='platforms/nuttx/NuttX/nuttx', stderr=subprocess.STDOUT).decode('utf-8').strip() - nuttx_git_tag = re.findall(r'nuttx-[0-9]+\.[0-9]+\.[0-9]+', nuttx_git_tags)[-1].replace("nuttx-", "v") - nuttx_git_tag = re.sub('-.*', '.0', nuttx_git_tag) + # may be empty if shallow clone + if (len(nuttx_git_tags) > 0): + nuttx_git_tag = re.findall(r'nuttx-[0-9]+\.[0-9]+\.[0-9]+', nuttx_git_tags)[-1].replace("nuttx-", "v") + nuttx_git_tag = re.sub('-.*', '.0', nuttx_git_tag) + else: + nuttx_git_tag = "v0.0.0" nuttx_git_version = subprocess.check_output('git rev-parse --verify HEAD'.split(), cwd='platforms/nuttx/NuttX/nuttx', stderr=subprocess.STDOUT).decode('utf-8').strip() nuttx_git_version_short = nuttx_git_version[0:16] From dc500c4d0440d61ee26e62dca49c72a86693ce93 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Mon, 13 Oct 2025 09:08:00 +1100 Subject: [PATCH 168/812] New Crowdin translations - ko (#25745) Co-authored-by: Crowdin Bot --- docs/ko/SUMMARY.md | 4 +- docs/ko/concept/system_startup.md | 4 +- docs/ko/dev_log/ulog_file_format.md | 1 + docs/ko/dev_setup/dev_env.md | 20 ++--- docs/ko/dev_setup/dev_env_mac.md | 84 +++++++++---------- docs/ko/test_and_ci/test_flights.md | 4 +- docs/ko/test_cards/mc_06_optical_flow.md | 29 ++++--- .../mc_07_optical_flow_low_mount.md | 45 ++++++++++ docs/ko/test_cards/mc_08_dshot.md | 10 +-- docs/ko/test_cards/mc_09_vio.md | 52 ++++++++++++ .../mc_10_optical_flow_gps_mixed.md | 74 ++++++++++++++++ 11 files changed, 256 insertions(+), 71 deletions(-) create mode 100644 docs/ko/test_cards/mc_07_optical_flow_low_mount.md create mode 100644 docs/ko/test_cards/mc_09_vio.md create mode 100644 docs/ko/test_cards/mc_10_optical_flow_gps_mixed.md diff --git a/docs/ko/SUMMARY.md b/docs/ko/SUMMARY.md index d0a8f566c2..3d24afef3c 100644 --- a/docs/ko/SUMMARY.md +++ b/docs/ko/SUMMARY.md @@ -851,8 +851,10 @@ - [시험 MC_04 - 안전 장치 시험](test_cards/mc_04_failsafe_testing.md) - [Test MC_05 - Manual Modes (Inside)](test_cards/mc_05_indoor_flight_manual_modes.md) - [Test MC_06 - Optical Flow (Inside)](test_cards/mc_06_optical_flow.md) - - [Test MC_07 - VIO (Inside)](test_cards/mc_07_vio.md) + - [Test MC_07 - Optical Flow Low Mount](test_cards/mc_07_optical_flow_low_mount.md) - [Test MC_08 - DSHOT ESC](test_cards/mc_08_dshot.md) + - [Test MC_09 - VIO (Visual-Inertial Odometry)](test_cards/mc_09_vio.md) + - [Test MC_10 - Optical Flow / GPS Mixed](test_cards/mc_10_optical_flow_gps_mixed.md) - [단위 테스트](test_and_ci/unit_tests.md) - [Fuzz Tests](test_and_ci/fuzz_tests.md) - [지속 통합](test_and_ci/continous_integration.md) diff --git a/docs/ko/concept/system_startup.md b/docs/ko/concept/system_startup.md index 79fd6cb79b..058b7577c7 100644 --- a/docs/ko/concept/system_startup.md +++ b/docs/ko/concept/system_startup.md @@ -1,7 +1,7 @@ # 시스템 시작 PX4 시작은 쉘 스크립트에 의해 제어됩니다. -On NuttX they reside in the [ROMFS/px4fmu_common/init.d](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d) folder - some of these are also used on Posix (Linux/MacOS). +On NuttX they reside in the [ROMFS/px4fmu_common/init.d](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d) folder - some of these are also used on Posix (Linux/macOS). The scripts that are only used on Posix are located in [ROMFS/px4fmu_common/init.d-posix](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d-posix). All files starting with a number and underscore (e.g. `10000_airplane`) are predefined airframe configurations. @@ -13,7 +13,7 @@ The first executed file is the [init.d/rcS](https://github.com/PX4/PX4-Autopilot 다음 섹션은 PX4가 실행되는 운영 체제에 따라 달라집니다. -## POSIX (Linux/MacOS) +## POSIX (Linux/macOS) On POSIX, the system shell is used as script interpreter (e.g. /bin/sh, being symlinked to dash on Ubuntu). 동작하기 위한 몇가지 조건이 있습니다. diff --git a/docs/ko/dev_log/ulog_file_format.md b/docs/ko/dev_log/ulog_file_format.md index 70e1ac0510..9e8a29b7e7 100644 --- a/docs/ko/dev_log/ulog_file_format.md +++ b/docs/ko/dev_log/ulog_file_format.md @@ -502,6 +502,7 @@ Since the Definitions and Data Sections use the same message header format, they - [ulogreader](https://github.com/maxsun/ulogreader): Javascript, ULog reader and parser outputs log in JSON object format. - [Foxglove](https://foxglove.dev): an integrated visualization and diagnosis tool for robotics data that supports ULog files. - [TypeScript ULog parser](https://github.com/foxglove/ulog): TypeScript, ULog reader that outputs JS objects. +- [yule_log](https://crates.io/crates/yule_log): A streaming ULog parser written in Rust. ## 파일 형식 버전 이력 diff --git a/docs/ko/dev_setup/dev_env.md b/docs/ko/dev_setup/dev_env.md index 427f28d302..9ed3e0cfd8 100644 --- a/docs/ko/dev_setup/dev_env.md +++ b/docs/ko/dev_setup/dev_env.md @@ -2,22 +2,22 @@ The _supported platforms_ for PX4 development are: -- [Ubuntu Linux (22.04/20.04/18.04)](../dev_setup/dev_env_linux_ubuntu.md) — Recommended +- [Ubuntu Linux (24.04/22.04)](../dev_setup/dev_env_linux_ubuntu.md) — Recommended - [Windows (10/11)](../dev_setup/dev_env_windows_wsl.md) — via WSL2 -- [Mac OS](../dev_setup/dev_env_mac.md) +- [macOS](../dev_setup/dev_env_mac.md) ## 지원 대상 아래 표는 각 OS에서 구축 가능한 PX 대상을 보여줍니다. -| 대상 | Linux (Ubuntu) | Mac | 윈도우 | -| ------------------------------------------------------------------------------------------------------------------------------------------------------ | :-------------------------------: | :-: | :-: | -| **NuttX based hardware:** [Pixhawk Series](../flight_controller/pixhawk_series.md), [Crazyflie](../complete_vehicles_mc/crazyflie2.md) | ✓ | ✓ | ✓ | -| **Linux-based hardware:** [Raspberry Pi 2/3](../flight_controller/raspberry_pi_navio2.md) | ✓ | | | -| **Simulation:** [Gazebo SITL](../sim_gazebo_gz/index.md) | ✓ | ✓ | ✓ | -| **Simulation:** [Gazebo Classic SITL](../sim_gazebo_classic/index.md) | ✓ | ✓ | ✓ | -| **Simulation:** [ROS with Gazebo Classic](../simulation/ros_interface.md) | ✓ | | ✓ | -| **Simulation:** ROS 2 with Gazebo | ✓ | | ✓ | +| 대상 | Linux (Ubuntu) | macOS | 윈도우 | +| ------------------------------------------------------------------------------------------------------------------------------------------------------ | :-------------------------------: | :---: | :-: | +| **NuttX based hardware:** [Pixhawk Series](../flight_controller/pixhawk_series.md), [Crazyflie](../complete_vehicles_mc/crazyflie2.md) | ✓ | ✓ | ✓ | +| **Linux-based hardware:** [Raspberry Pi 2/3](../flight_controller/raspberry_pi_navio2.md) | ✓ | | | +| **Simulation:** [Gazebo SITL](../sim_gazebo_gz/index.md) | ✓ | ✓ | ✓ | +| **Simulation:** [Gazebo Classic SITL](../sim_gazebo_classic/index.md) | ✓ | ✓ | ✓ | +| **Simulation:** [ROS with Gazebo Classic](../simulation/ros_interface.md) | ✓ | | ✓ | +| **Simulation:** ROS 2 with Gazebo | ✓ | | ✓ | Experienced Docker users can also build with the containers used by our continuous integration system: [Docker Containers](../test_and_ci/docker.md) diff --git a/docs/ko/dev_setup/dev_env_mac.md b/docs/ko/dev_setup/dev_env_mac.md index 5b31516462..63e8e3ca38 100644 --- a/docs/ko/dev_setup/dev_env_mac.md +++ b/docs/ko/dev_setup/dev_env_mac.md @@ -1,4 +1,4 @@ -# MacOS 개발 환경 +# macOS Development Environment 아래에서 macOS용 PX4 개발 환경 설정 방법을 설명합니다. PX4 빌드에 사용되어 집니다. @@ -22,8 +22,8 @@ The "base" macOS setup installs the tools needed for building firmware, and incl ### Environment Setup :::details -Apple Silicon Macbook users! -If you have an Apple M1, M2 etc. Macbook, make sure to run the terminal as x86 by setting up an x86 terminal: +Apple Silicon MacBook users! +If you have an Apple M1, M2 etc. MacBook, make sure to run the terminal as x86 by setting up an x86 terminal: 1. Locate the Terminal application within the Utilities folder (**Finder > Go menu > Utilities**) 2. Select _Terminal.app_ and right-click on it, then choose **Duplicate**. @@ -38,21 +38,21 @@ First set up the environment 1. Enable more open files by appending the following line to the `~/.zshenv` file (creating it if necessary): - ```sh - echo ulimit -S -n 2048 >> ~/.zshenv - ``` + ```sh + echo ulimit -S -n 2048 >> ~/.zshenv + ``` - ::: info - If you don't do this, the build toolchain may report the error: `"LD: too many open files"` + ::: info + If you don't do this, the build toolchain may report the error: `"LD: too many open files"` ::: 2. Enforce Python 3 by appending the following lines to `~/.zshenv` - ```sh - # Point pip3 to MacOS system python 3 pip - alias pip3=/usr/bin/pip3 - ``` + ```sh + # Point pip3 to macOS system python 3 pip + alias pip3=/usr/bin/pip3 + ``` ### 공통 도구 @@ -62,19 +62,19 @@ To setup the environment to be able to build for Pixhawk/NuttX hardware (and ins 2. Run these commands in your shell to install the common tools: - ```sh - brew tap PX4/px4 - brew install px4-dev - ``` + ```sh + brew tap PX4/px4 + brew install px4-dev + ``` 3. Install the required Python packages: - ```sh - # install required packages using pip3 - python3 -m pip install --user pyserial empty toml numpy pandas jinja2 pyyaml pyros-genmsg packaging kconfiglib future jsonschema - # if this fails with a permissions error, your Python install is in a system path - use this command instead: - sudo -H python3 -m pip install --user pyserial empty toml numpy pandas jinja2 pyyaml pyros-genmsg packaging kconfiglib future jsonschema - ``` + ```sh + # install required packages using pip3 + python3 -m pip install --user pyserial empty toml numpy pandas jinja2 pyyaml pyros-genmsg packaging kconfiglib future jsonschema + # if this fails with a permissions error, your Python install is in a system path - use this command instead: + sudo -H python3 -m pip install --user pyserial empty toml numpy pandas jinja2 pyyaml pyros-genmsg packaging kconfiglib future jsonschema + ``` ## Gazebo Classic Simulation @@ -82,35 +82,35 @@ To setup the environment for [Gazebo Classic](../sim_gazebo_classic/index.md) si 1. Run the following commands in your shell: - ```sh - brew unlink tbb - sed -i.bak '/disable! date:/s/^/ /; /disable! date:/s/./#/3' $(brew --prefix)/Library/Taps/homebrew/homebrew-core/Formula/tbb@2020.rb - brew install tbb@2020 - brew link tbb@2020 - ``` + ```sh + brew unlink tbb + sed -i.bak '/disable! date:/s/^/ /; /disable! date:/s/./#/3' $(brew --prefix)/Library/Taps/homebrew/homebrew-core/Formula/tbb@2020.rb + brew install tbb@2020 + brew link tbb@2020 + ``` - ::: info - September 2021: The commands above are a workaround to this bug: [PX4-Autopilot#17644](https://github.com/PX4/PX4-Autopilot/issues/17644). - They can be removed once it is fixed (along with this note). + ::: info + September 2021: The commands above are a workaround to this bug: [PX4-Autopilot#17644](https://github.com/PX4/PX4-Autopilot/issues/17644). + They can be removed once it is fixed (along with this note). ::: 2. To install SITL simulation with Gazebo Classic: - ```sh - brew install --cask temurin - brew install --cask xquartz - brew install px4-sim-gazebo - ``` + ```sh + brew install --cask temurin + brew install --cask xquartz + brew install px4-sim-gazebo + ``` 3. Run the macOS setup script: `PX4-Autopilot/Tools/setup/macos.sh` - The easiest way to do this is to clone the PX4 source, and then run the script from the directory, as shown: + The easiest way to do this is to clone the PX4 source, and then run the script from the directory, as shown: - ```sh - git clone https://github.com/PX4/PX4-Autopilot.git --recursive - cd PX4-Autopilot/Tools/setup - sh macos.sh - ``` + ```sh + git clone https://github.com/PX4/PX4-Autopilot.git --recursive + cd PX4-Autopilot/Tools/setup + sh macos.sh + ``` ## 다음 단계 diff --git a/docs/ko/test_and_ci/test_flights.md b/docs/ko/test_and_ci/test_flights.md index eabc3c3176..b0c65c3a6d 100644 --- a/docs/ko/test_and_ci/test_flights.md +++ b/docs/ko/test_and_ci/test_flights.md @@ -28,5 +28,7 @@ These are run by the test team as part of release testing, and for more signific - [MC_04 - Failsafe Testing](../test_cards/mc_04_failsafe_testing.md) - [MC_05 - Indoor Flight (Manual Modes)](../test_cards/mc_05_indoor_flight_manual_modes.md) - [MC_06 - Indoor Flight (Optical Flow)](../test_cards/mc_06_optical_flow.md) -- [MC_07 - VIO (Visual-Inertial Odometry)](../test_cards/mc_07_vio.md) +- [MC_07 - Optical Flow Low Mount](../test_cards/mc_07_optical_flow_low_mount.md) - [MC_08 - DSHOT ESC](../test_cards/mc_08_dshot.md) +- [MC_09 - VIO (Visual-Inertial Odometry)](../test_cards/mc_09_vio.md) +- [MC_10 - Optical Flow / GPS Mixed](../test_cards/mc_10_optical_flow_gps_mixed.md) diff --git a/docs/ko/test_cards/mc_06_optical_flow.md b/docs/ko/test_cards/mc_06_optical_flow.md index 901e113218..9378bf2e4d 100644 --- a/docs/ko/test_cards/mc_06_optical_flow.md +++ b/docs/ko/test_cards/mc_06_optical_flow.md @@ -2,25 +2,23 @@ ## Objective -To test that optical flow works as expected +Test that optical flow works as expected ## Preflight -Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation -([Setup Information here](../sensor/optical_flow.md)) +Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation ([setup information here](../sensor/optical_flow.md)) -Ensure there are no other sources of positioning besides optical flow +Ensure there are no other sources of positioning besides optical flow: - [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` - [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` - [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` -- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` -Ensure that the drone can go into Altitude / Position flight mode while still on the ground +Ensure that the drone can go into Altitude / Position mode while still on the ground ## Flight Tests -❏ Altitude flight mode +❏ [Altitude mode](../flight_modes_mc/altitude.md)     ❏ Vertical position should hold current value with stick centered @@ -28,7 +26,7 @@ Ensure that the drone can go into Altitude / Position flight mode while still on     ❏ Throttle response set to climb/descent rate -❏ Position flight mode +❏ [Position mode](../flight_modes_mc/position.md)     ❏ Horizontal position should hold current value with stick centered @@ -38,6 +36,16 @@ Ensure that the drone can go into Altitude / Position flight mode while still on     ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates +❏ Varying height terrain + +    ❏ Put boxes on the ground to create varying heights in terrain + +    ❏ Take off in position mode and fly over the boxes such that the downward facing rangefinder varies in value + +    ❏ Do a few passes with varying amounts of time over the boxes (1-30 seconds if possible) + +    ❏ Drone should not raise in height when flying over boxes + ## 착륙 ❏ Land in either Position or Altitude mode with the throttle below 40% @@ -47,7 +55,8 @@ Ensure that the drone can go into Altitude / Position flight mode while still on ## 예상 결과 - 추력을 올릴 때 서서히 이륙한다 -- Drone should hold altitude in Altitude Flight mode without wandering -- Drone should hold position within 1 meter in Position Flight mode without pilot moving sticks +- Drone should hold altitude in Altitude mode without wandering (over surface with many features) +- Drone should hold position within 1 meter in Position mode without pilot moving sticks - 위에 언급한 어떤 비행 모드에서도 떨림이 나타나서는 안됨 +- Drone should not raise in height when flying over boxes - 지면에 착륙시, 콥터가 지면에서 튀면 안됨 diff --git a/docs/ko/test_cards/mc_07_optical_flow_low_mount.md b/docs/ko/test_cards/mc_07_optical_flow_low_mount.md new file mode 100644 index 0000000000..5ac887e804 --- /dev/null +++ b/docs/ko/test_cards/mc_07_optical_flow_low_mount.md @@ -0,0 +1,45 @@ +# Test MC_07 - Optical Flow Low Sensor + +## Objective + +Test that optical flow works as expected with a low mounted optical flow sensor + +## Preflight + +Ensure that the drone's optical flow sensor is mounted more than an inch off of the ground + +Ensure that [MPC_THR_MIN](../advanced_config/parameter_reference.md#MPC_THR_MIN) is tuned correctly for landing + +Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation +([Setup Information here](../sensor/optical_flow.md)) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` + +Ensure that the drone can go into [Position mode](../flight_modes_mc/position.md) while still on the ground + +## Flight Tests + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## 착륙 + +❏ Land in Position mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## 예상 결과 + +- 추력을 올릴 때 서서히 이륙한다 +- Drone should stay in Position mode, NOT fall into [altitude](../flight_modes_mc/altitude.md) mode diff --git a/docs/ko/test_cards/mc_08_dshot.md b/docs/ko/test_cards/mc_08_dshot.md index e5b7f8f073..0df821802b 100644 --- a/docs/ko/test_cards/mc_08_dshot.md +++ b/docs/ko/test_cards/mc_08_dshot.md @@ -6,22 +6,22 @@ Regression test for DSHOT working with PX4 ## Preflight -- Ensure vehicle is using a DSHOT ESC. +- Ensure vehicle is using a DSHOT ESC - Parameter [DSHOT_BIDIR_EN](../advanced_config/parameter_reference.md#DSHOT_BIDIR_EN) is enabled - Parameter [DSHOT_TEL_CFG](../advanced_config/parameter_reference.md#DSHOT_TEL_CFG) is configured (if ESC supports telemetry) - Parameter [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) has Debug (`5`) checked ## Flight Tests -❏ Stabilized Flight mode +❏ [Stabilized mode](../flight_modes_mc/manual_stabilized.md) -    ❏ Takeoff in stabilized flight mode to ensure correct motor spin +    ❏ Takeoff in stabilized mode to ensure correct motor spin     ❏ Pitch/Roll/Yaw response 1:1     ❏ Throttle response 1:1 -❏ Position flight mode +❏ [Position mode](../flight_modes_mc/position.md)     ❏ Horizontal position should hold current value with stick centered @@ -41,6 +41,6 @@ Regression test for DSHOT working with PX4 - Download flight logs - Load into Data Plot Juggler -- Ensure data is logged for esc_status/esc.0x/esc_rpm +- Ensure data is logged for `esc_status`/`esc.0x`/`esc_rpm` ![Reference frames](../../assets/test_cards/dshot_log_output.png) diff --git a/docs/ko/test_cards/mc_09_vio.md b/docs/ko/test_cards/mc_09_vio.md new file mode 100644 index 0000000000..966073fafd --- /dev/null +++ b/docs/ko/test_cards/mc_09_vio.md @@ -0,0 +1,52 @@ +# Test MC_09 - VIO (Visual-Inertial Odometry) + +## Objective + +Test that external vision (VIO) works as expected + +## Preflight + +Disconnect all GPS / compasses and ensure vehicle is using VIO for navigation + +Ensure that the drone can go into [Altitude](../flight_modes_mc/altitude.md) / [Position](../flight_modes_mc/position.md) mode while still on the ground + +Ensure there are no other sources of positioning besides VIO: + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `0` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `15` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` + +## Flight Tests + +❏ [Altitude mode](../flight_modes_mc/altitude.md) + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response set to climb/descent rate + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## 착륙 + +❏ Land in either Position or Altitude mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## 예상 결과 + +- 추력을 올릴 때 서서히 이륙한다 +- Drone should hold altitude in Altitude mode without wandering +- Drone should hold position within 1 meter in Position mode without pilot moving sticks +- 위에 언급한 어떤 비행 모드에서도 떨림이 나타나서는 안됨 +- 지면에 착륙시, 콥터가 지면에서 튀면 안됨 diff --git a/docs/ko/test_cards/mc_10_optical_flow_gps_mixed.md b/docs/ko/test_cards/mc_10_optical_flow_gps_mixed.md new file mode 100644 index 0000000000..0f53829de9 --- /dev/null +++ b/docs/ko/test_cards/mc_10_optical_flow_gps_mixed.md @@ -0,0 +1,74 @@ +# Test MC_10 - Optical Flow / GPS Mixed + +## Objective + +Test that optical flow mixed with GPS works as expected + +## Preflight + +[Setup optical flow and GPS](../sensor/optical_flow.md) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `7` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `1` +- [EKF2_HGT_REF](../advanced_config/parameter_reference.md#EKF2_HGT_REF): `1` (GPS) + +Ensure that the drone can go into [Altitude](../flight_modes_mc/altitude.md) / [Position](../flight_modes_mc/position.md) mode while still on the ground + +## Flight Tests + +❏ [Altitude mode](../flight_modes_mc/altitude.md) + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response set to climb/descent rate + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +❏ GPS Cutout + +    ❏ Takeoff in position mode in GPS rich environment (outdoors) + +    ❏ Open QGC and navigate to MAVLink Console + +    ❏ Type `gps off` to disable GPS + +    ❏ Drone should maintain position hold via optical flow + +❏ GPS Degredation + +    ❏ Takeoff in position mode in GPS rich environment (outdoors) + +    ❏ Fly under a metal surface (or other GPS blocking structure) + +    ❏ Ensure drone does not lose position hold or start drifting + +    ❏ Fly out of metal structure to regain GPS + +❏ GPS Acquisition + +    ❏ Takeoff in position mode in non-GPS environment + +    ❏ Fly into a GPS rich environment (outdoors) + +    ❏ Ensure drone acquires GPS position + +## 예상 결과 + +- 추력을 올릴 때 서서히 이륙한다 +- Drone should hold position within 1 meter in Position mode without pilot moving sticks +- Drone should hold position in GPS rich environment as well as non-GPS environment +- 위에 언급한 어떤 비행 모드에서도 떨림이 나타나서는 안됨 From 7fb8ea051f29d803ab0f11caefec829db696a521 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Mon, 13 Oct 2025 09:08:14 +1100 Subject: [PATCH 169/812] New Crowdin translations - uk (#25746) Co-authored-by: Crowdin Bot --- docs/uk/SUMMARY.md | 4 +- docs/uk/concept/system_startup.md | 4 +- docs/uk/dev_log/ulog_file_format.md | 1 + docs/uk/dev_setup/dev_env.md | 20 ++--- docs/uk/dev_setup/dev_env_mac.md | 8 +- docs/uk/test_and_ci/test_flights.md | 4 +- docs/uk/test_cards/mc_06_optical_flow.md | 29 +++++--- .../mc_07_optical_flow_low_mount.md | 45 +++++++++++ docs/uk/test_cards/mc_08_dshot.md | 10 +-- docs/uk/test_cards/mc_09_vio.md | 52 +++++++++++++ .../mc_10_optical_flow_gps_mixed.md | 74 +++++++++++++++++++ 11 files changed, 218 insertions(+), 33 deletions(-) create mode 100644 docs/uk/test_cards/mc_07_optical_flow_low_mount.md create mode 100644 docs/uk/test_cards/mc_09_vio.md create mode 100644 docs/uk/test_cards/mc_10_optical_flow_gps_mixed.md diff --git a/docs/uk/SUMMARY.md b/docs/uk/SUMMARY.md index accfcd8598..10aa436752 100644 --- a/docs/uk/SUMMARY.md +++ b/docs/uk/SUMMARY.md @@ -851,8 +851,10 @@ - [Тест MC_04 - Тестування відмовостійкості](test_cards/mc_04_failsafe_testing.md) - [Test MC_05 - Manual Modes (Inside)](test_cards/mc_05_indoor_flight_manual_modes.md) - [Test MC_06 - Optical Flow (Inside)](test_cards/mc_06_optical_flow.md) - - [Test MC_07 - VIO (Inside)](test_cards/mc_07_vio.md) + - [Test MC_07 - Optical Flow Low Mount](test_cards/mc_07_optical_flow_low_mount.md) - [Test MC_08 - DSHOT ESC](test_cards/mc_08_dshot.md) + - [Test MC_09 - VIO (Visual-Inertial Odometry)](test_cards/mc_09_vio.md) + - [Test MC_10 - Optical Flow / GPS Mixed](test_cards/mc_10_optical_flow_gps_mixed.md) - [Модульні Тести](test_and_ci/unit_tests.md) - [Fuzz Tests](test_and_ci/fuzz_tests.md) - [Безперервна інтеграція](test_and_ci/continous_integration.md) diff --git a/docs/uk/concept/system_startup.md b/docs/uk/concept/system_startup.md index e1cc0abd18..f94b70aa7c 100644 --- a/docs/uk/concept/system_startup.md +++ b/docs/uk/concept/system_startup.md @@ -1,7 +1,7 @@ # Запуск системи Запуск PX4 контрольований скриптами оболонки. -На NuttX вони знаходяться у директорії [ROMFS/px4fmu_common/init.d](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d), деякі з них також використовуються на Posix системах (Linux/MacOS). +On NuttX they reside in the [ROMFS/px4fmu_common/init.d](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d) folder - some of these are also used on Posix (Linux/macOS). Скрипти які використовуються тільки на Posix системах знаходяться у [ROMFS/px4fmu_common/init.d-posix](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d-posix). Усі файли, які починаються з числа і підкреслення (наприклад, `10000_airaipl`) є попередньо визначеними конфігураціями планерів. @@ -13,7 +13,7 @@ They are exported at build-time into an `airframes.xml` file which is parsed by Наступні секції розділені відповідно до операційної системи, на яких виконується PX4. -## POSIX (Linux/MacOS) +## POSIX (Linux/macOS) On POSIX, the system shell is used as script interpreter (e.g. /bin/sh, being symlinked to dash on Ubuntu). Щоб це працювало потрібно кілька речей: diff --git a/docs/uk/dev_log/ulog_file_format.md b/docs/uk/dev_log/ulog_file_format.md index 12df33315d..4e15845983 100644 --- a/docs/uk/dev_log/ulog_file_format.md +++ b/docs/uk/dev_log/ulog_file_format.md @@ -502,6 +502,7 @@ struct message_dropout_s { - [ulogreader](https://github.com/maxsun/ulogreader): Javascript, ULog reader and parser outputs log in JSON object format. - [Foxglove](https://foxglove.dev): an integrated visualization and diagnosis tool for robotics data that supports ULog files. - [TypeScript ULog parser](https://github.com/foxglove/ulog): TypeScript, ULog reader that outputs JS objects. +- [yule_log](https://crates.io/crates/yule_log): A streaming ULog parser written in Rust. ## Історія версій формату файлу diff --git a/docs/uk/dev_setup/dev_env.md b/docs/uk/dev_setup/dev_env.md index 46bcc54138..6a23af23fa 100644 --- a/docs/uk/dev_setup/dev_env.md +++ b/docs/uk/dev_setup/dev_env.md @@ -2,22 +2,22 @@ The _supported platforms_ for PX4 development are: -- [Ubuntu Linux (22.04/20.04/18.04)](../dev_setup/dev_env_linux_ubuntu.md) — Recommended +- [Ubuntu Linux (24.04/22.04)](../dev_setup/dev_env_linux_ubuntu.md) — Recommended - [Windows (10/11)](../dev_setup/dev_env_windows_wsl.md) — via WSL2 -- [Mac OS](../dev_setup/dev_env_mac.md) +- [macOS](../dev_setup/dev_env_mac.md) ## Цільові платформи що підтримуються Таблиця нижче показує, які цільові платформи PX4 можна побудувати на кожній ОС. -| Цільова платформа | Linux (Ubuntu) | Mac | Windows | -| ------------------------------------------------------------------------------------------------------------------------------------------------------ | :-------------------------------: | :-: | :-----: | -| **NuttX based hardware:** [Pixhawk Series](../flight_controller/pixhawk_series.md), [Crazyflie](../complete_vehicles_mc/crazyflie2.md) | ✓ | ✓ | ✓ | -| **Linux-based hardware:** [Raspberry Pi 2/3](../flight_controller/raspberry_pi_navio2.md) | ✓ | | | -| **Simulation:** [Gazebo SITL](../sim_gazebo_gz/index.md) | ✓ | ✓ | ✓ | -| **Simulation:** [Gazebo Classic SITL](../sim_gazebo_classic/index.md) | ✓ | ✓ | ✓ | -| **Simulation:** [ROS with Gazebo Classic](../simulation/ros_interface.md) | ✓ | | ✓ | -| **Simulation:** ROS 2 with Gazebo | ✓ | | ✓ | +| Цільова платформа | Linux (Ubuntu) | macOS | Windows | +| ------------------------------------------------------------------------------------------------------------------------------------------------------ | :-------------------------------: | :---: | :-----: | +| **NuttX based hardware:** [Pixhawk Series](../flight_controller/pixhawk_series.md), [Crazyflie](../complete_vehicles_mc/crazyflie2.md) | ✓ | ✓ | ✓ | +| **Linux-based hardware:** [Raspberry Pi 2/3](../flight_controller/raspberry_pi_navio2.md) | ✓ | | | +| **Simulation:** [Gazebo SITL](../sim_gazebo_gz/index.md) | ✓ | ✓ | ✓ | +| **Simulation:** [Gazebo Classic SITL](../sim_gazebo_classic/index.md) | ✓ | ✓ | ✓ | +| **Simulation:** [ROS with Gazebo Classic](../simulation/ros_interface.md) | ✓ | | ✓ | +| **Simulation:** ROS 2 with Gazebo | ✓ | | ✓ | Experienced Docker users can also build with the containers used by our continuous integration system: [Docker Containers](../test_and_ci/docker.md) diff --git a/docs/uk/dev_setup/dev_env_mac.md b/docs/uk/dev_setup/dev_env_mac.md index 65f1453411..214f44b7f3 100644 --- a/docs/uk/dev_setup/dev_env_mac.md +++ b/docs/uk/dev_setup/dev_env_mac.md @@ -1,4 +1,4 @@ -# Середовище розробки MacOS +# macOS Development Environment Наступні інструкції для встановлення середовища розробки PX4 для macOS. Це середовище може бути використане для збірки PX4 для: @@ -22,8 +22,8 @@ To build other targets you will need to use a [different OS](../dev_setup/dev_en ### Налаштування середовища :::details -Apple Silicon Macbook users! -If you have an Apple M1, M2 etc. Macbook, make sure to run the terminal as x86 by setting up an x86 terminal: +Apple Silicon MacBook users! +If you have an Apple M1, M2 etc. MacBook, make sure to run the terminal as x86 by setting up an x86 terminal: 1. Locate the Terminal application within the Utilities folder (**Finder > Go menu > Utilities**) 2. Select _Terminal.app_ and right-click on it, then choose **Duplicate**. @@ -50,7 +50,7 @@ If you have an Apple M1, M2 etc. Macbook, make sure to run the terminal as x86 b 2. Enforce Python 3 by appending the following lines to `~/.zshenv` ```sh - # Point pip3 to MacOS system python 3 pip + # Point pip3 to macOS system python 3 pip alias pip3=/usr/bin/pip3 ``` diff --git a/docs/uk/test_and_ci/test_flights.md b/docs/uk/test_and_ci/test_flights.md index 6771beac6e..103549e361 100644 --- a/docs/uk/test_and_ci/test_flights.md +++ b/docs/uk/test_and_ci/test_flights.md @@ -28,5 +28,7 @@ When submitting [Pull Requests](../contribute/code.md#pull-requests) for new fun - [MC_04 - Failsafe Testing](../test_cards/mc_04_failsafe_testing.md) - [MC_05 - Indoor Flight (Manual Modes)](../test_cards/mc_05_indoor_flight_manual_modes.md) - [MC_06 - Indoor Flight (Optical Flow)](../test_cards/mc_06_optical_flow.md) -- [MC_07 - VIO (Visual-Inertial Odometry)](../test_cards/mc_07_vio.md) +- [MC_07 - Optical Flow Low Mount](../test_cards/mc_07_optical_flow_low_mount.md) - [MC_08 - DSHOT ESC](../test_cards/mc_08_dshot.md) +- [MC_09 - VIO (Visual-Inertial Odometry)](../test_cards/mc_09_vio.md) +- [MC_10 - Optical Flow / GPS Mixed](../test_cards/mc_10_optical_flow_gps_mixed.md) diff --git a/docs/uk/test_cards/mc_06_optical_flow.md b/docs/uk/test_cards/mc_06_optical_flow.md index 6a10870404..3ade1bd015 100644 --- a/docs/uk/test_cards/mc_06_optical_flow.md +++ b/docs/uk/test_cards/mc_06_optical_flow.md @@ -2,25 +2,23 @@ ## Objective -To test that optical flow works as expected +Test that optical flow works as expected ## Preflight -Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation -([Setup Information here](../sensor/optical_flow.md)) +Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation ([setup information here](../sensor/optical_flow.md)) -Ensure there are no other sources of positioning besides optical flow +Ensure there are no other sources of positioning besides optical flow: - [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` - [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` - [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` -- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` -Ensure that the drone can go into Altitude / Position flight mode while still on the ground +Ensure that the drone can go into Altitude / Position mode while still on the ground ## Flight Tests -❏ Altitude flight mode +❏ [Altitude mode](../flight_modes_mc/altitude.md)     ❏ Vertical position should hold current value with stick centered @@ -28,7 +26,7 @@ Ensure that the drone can go into Altitude / Position flight mode while still on     ❏ Throttle response set to climb/descent rate -❏ Position flight mode +❏ [Position mode](../flight_modes_mc/position.md)     ❏ Horizontal position should hold current value with stick centered @@ -38,6 +36,16 @@ Ensure that the drone can go into Altitude / Position flight mode while still on     ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates +❏ Varying height terrain + +    ❏ Put boxes on the ground to create varying heights in terrain + +    ❏ Take off in position mode and fly over the boxes such that the downward facing rangefinder varies in value + +    ❏ Do a few passes with varying amounts of time over the boxes (1-30 seconds if possible) + +    ❏ Drone should not raise in height when flying over boxes + ## Посадка ❏ Land in either Position or Altitude mode with the throttle below 40% @@ -47,7 +55,8 @@ Ensure that the drone can go into Altitude / Position flight mode while still on ## Очікувані результати - Зліт повинен бути плавним, коли газ піднято -- Drone should hold altitude in Altitude Flight mode without wandering -- Drone should hold position within 1 meter in Position Flight mode without pilot moving sticks +- Drone should hold altitude in Altitude mode without wandering (over surface with many features) +- Drone should hold position within 1 meter in Position mode without pilot moving sticks - Немає коливання в жодному з перерахованих режимів польоту +- Drone should not raise in height when flying over boxes - Після посадки, коптер не повинен підскакувати на землі diff --git a/docs/uk/test_cards/mc_07_optical_flow_low_mount.md b/docs/uk/test_cards/mc_07_optical_flow_low_mount.md new file mode 100644 index 0000000000..1679a2c8d4 --- /dev/null +++ b/docs/uk/test_cards/mc_07_optical_flow_low_mount.md @@ -0,0 +1,45 @@ +# Test MC_07 - Optical Flow Low Sensor + +## Objective + +Test that optical flow works as expected with a low mounted optical flow sensor + +## Preflight + +Ensure that the drone's optical flow sensor is mounted more than an inch off of the ground + +Ensure that [MPC_THR_MIN](../advanced_config/parameter_reference.md#MPC_THR_MIN) is tuned correctly for landing + +Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation +([Setup Information here](../sensor/optical_flow.md)) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` + +Ensure that the drone can go into [Position mode](../flight_modes_mc/position.md) while still on the ground + +## Flight Tests + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## Посадка + +❏ Land in Position mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## Очікувані результати + +- Зліт повинен бути плавним, коли газ піднято +- Drone should stay in Position mode, NOT fall into [altitude](../flight_modes_mc/altitude.md) mode diff --git a/docs/uk/test_cards/mc_08_dshot.md b/docs/uk/test_cards/mc_08_dshot.md index 422482bbc9..148534cae8 100644 --- a/docs/uk/test_cards/mc_08_dshot.md +++ b/docs/uk/test_cards/mc_08_dshot.md @@ -6,22 +6,22 @@ Regression test for DSHOT working with PX4 ## Preflight -- Ensure vehicle is using a DSHOT ESC. +- Ensure vehicle is using a DSHOT ESC - Parameter [DSHOT_BIDIR_EN](../advanced_config/parameter_reference.md#DSHOT_BIDIR_EN) is enabled - Parameter [DSHOT_TEL_CFG](../advanced_config/parameter_reference.md#DSHOT_TEL_CFG) is configured (if ESC supports telemetry) - Parameter [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) has Debug (`5`) checked ## Flight Tests -❏ Stabilized Flight mode +❏ [Stabilized mode](../flight_modes_mc/manual_stabilized.md) -    ❏ Takeoff in stabilized flight mode to ensure correct motor spin +    ❏ Takeoff in stabilized mode to ensure correct motor spin     ❏ Pitch/Roll/Yaw response 1:1     ❏ Throttle response 1:1 -❏ Position flight mode +❏ [Position mode](../flight_modes_mc/position.md)     ❏ Horizontal position should hold current value with stick centered @@ -41,6 +41,6 @@ Regression test for DSHOT working with PX4 - Download flight logs - Load into Data Plot Juggler -- Ensure data is logged for esc_status/esc.0x/esc_rpm +- Ensure data is logged for `esc_status`/`esc.0x`/`esc_rpm` ![Reference frames](../../assets/test_cards/dshot_log_output.png) diff --git a/docs/uk/test_cards/mc_09_vio.md b/docs/uk/test_cards/mc_09_vio.md new file mode 100644 index 0000000000..29ab4a0253 --- /dev/null +++ b/docs/uk/test_cards/mc_09_vio.md @@ -0,0 +1,52 @@ +# Test MC_09 - VIO (Visual-Inertial Odometry) + +## Objective + +Test that external vision (VIO) works as expected + +## Preflight + +Disconnect all GPS / compasses and ensure vehicle is using VIO for navigation + +Ensure that the drone can go into [Altitude](../flight_modes_mc/altitude.md) / [Position](../flight_modes_mc/position.md) mode while still on the ground + +Ensure there are no other sources of positioning besides VIO: + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `0` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `15` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` + +## Flight Tests + +❏ [Altitude mode](../flight_modes_mc/altitude.md) + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response set to climb/descent rate + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## Посадка + +❏ Land in either Position or Altitude mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## Очікувані результати + +- Зліт повинен бути плавним, коли газ піднято +- Drone should hold altitude in Altitude mode without wandering +- Drone should hold position within 1 meter in Position mode without pilot moving sticks +- Немає коливання в жодному з перерахованих режимів польоту +- Після посадки, коптер не повинен підскакувати на землі diff --git a/docs/uk/test_cards/mc_10_optical_flow_gps_mixed.md b/docs/uk/test_cards/mc_10_optical_flow_gps_mixed.md new file mode 100644 index 0000000000..a1a165e322 --- /dev/null +++ b/docs/uk/test_cards/mc_10_optical_flow_gps_mixed.md @@ -0,0 +1,74 @@ +# Test MC_10 - Optical Flow / GPS Mixed + +## Objective + +Test that optical flow mixed with GPS works as expected + +## Preflight + +[Setup optical flow and GPS](../sensor/optical_flow.md) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `7` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `1` +- [EKF2_HGT_REF](../advanced_config/parameter_reference.md#EKF2_HGT_REF): `1` (GPS) + +Ensure that the drone can go into [Altitude](../flight_modes_mc/altitude.md) / [Position](../flight_modes_mc/position.md) mode while still on the ground + +## Flight Tests + +❏ [Altitude mode](../flight_modes_mc/altitude.md) + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response set to climb/descent rate + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +❏ GPS Cutout + +    ❏ Takeoff in position mode in GPS rich environment (outdoors) + +    ❏ Open QGC and navigate to MAVLink Console + +    ❏ Type `gps off` to disable GPS + +    ❏ Drone should maintain position hold via optical flow + +❏ GPS Degredation + +    ❏ Takeoff in position mode in GPS rich environment (outdoors) + +    ❏ Fly under a metal surface (or other GPS blocking structure) + +    ❏ Ensure drone does not lose position hold or start drifting + +    ❏ Fly out of metal structure to regain GPS + +❏ GPS Acquisition + +    ❏ Takeoff in position mode in non-GPS environment + +    ❏ Fly into a GPS rich environment (outdoors) + +    ❏ Ensure drone acquires GPS position + +## Очікувані результати + +- Зліт повинен бути плавним, коли газ піднято +- Drone should hold position within 1 meter in Position mode without pilot moving sticks +- Drone should hold position in GPS rich environment as well as non-GPS environment +- Немає коливання в жодному з перерахованих режимів польоту From 87559f717be6e497b0e63fdbf640324c8dc60912 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Mon, 13 Oct 2025 09:08:22 +1100 Subject: [PATCH 170/812] New Crowdin translations - zh-CN (#25747) Co-authored-by: Crowdin Bot --- docs/zh/SUMMARY.md | 4 +- docs/zh/concept/system_startup.md | 4 +- docs/zh/dev_log/ulog_file_format.md | 1 + docs/zh/dev_setup/dev_env.md | 6 +- docs/zh/dev_setup/dev_env_mac.md | 8 +- docs/zh/ros2/offboard_control.md | 20 ++--- docs/zh/ros2/px4_ros2_control_interface.md | 2 +- docs/zh/test_and_ci/test_flights.md | 4 +- docs/zh/test_cards/mc_06_optical_flow.md | 29 +++++--- .../mc_07_optical_flow_low_mount.md | 45 +++++++++++ docs/zh/test_cards/mc_08_dshot.md | 10 +-- docs/zh/test_cards/mc_09_vio.md | 52 +++++++++++++ .../mc_10_optical_flow_gps_mixed.md | 74 +++++++++++++++++++ 13 files changed, 222 insertions(+), 37 deletions(-) create mode 100644 docs/zh/test_cards/mc_07_optical_flow_low_mount.md create mode 100644 docs/zh/test_cards/mc_09_vio.md create mode 100644 docs/zh/test_cards/mc_10_optical_flow_gps_mixed.md diff --git a/docs/zh/SUMMARY.md b/docs/zh/SUMMARY.md index 1a4deb2d9c..0028ccf78b 100644 --- a/docs/zh/SUMMARY.md +++ b/docs/zh/SUMMARY.md @@ -851,8 +851,10 @@ - [测试 MC_04 -故障安全测试](test_cards/mc_04_failsafe_testing.md) - [Test MC_05 - Manual Modes (Inside)](test_cards/mc_05_indoor_flight_manual_modes.md) - [Test MC_06 - Optical Flow (Inside)](test_cards/mc_06_optical_flow.md) - - [Test MC_07 - VIO (Inside)](test_cards/mc_07_vio.md) + - [Test MC_07 - Optical Flow Low Mount](test_cards/mc_07_optical_flow_low_mount.md) - [Test MC_08 - DSHOT ESC](test_cards/mc_08_dshot.md) + - [Test MC_09 - VIO (Visual-Inertial Odometry)](test_cards/mc_09_vio.md) + - [Test MC_10 - Optical Flow / GPS Mixed](test_cards/mc_10_optical_flow_gps_mixed.md) - [单元测试](test_and_ci/unit_tests.md) - [Fuzz Tests](test_and_ci/fuzz_tests.md) - [持续集成](test_and_ci/continous_integration.md) diff --git a/docs/zh/concept/system_startup.md b/docs/zh/concept/system_startup.md index 3986658e97..28456ce738 100644 --- a/docs/zh/concept/system_startup.md +++ b/docs/zh/concept/system_startup.md @@ -1,7 +1,7 @@ # 系统启动 PX4 系统的启动由 shell 脚本文件控制。 -On NuttX they reside in the [ROMFS/px4fmu_common/init.d](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d) folder - some of these are also used on Posix (Linux/MacOS). +On NuttX they reside in the [ROMFS/px4fmu_common/init.d](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d) folder - some of these are also used on Posix (Linux/macOS). The scripts that are only used on Posix are located in [ROMFS/px4fmu_common/init.d-posix](https://github.com/PX4/PX4-Autopilot/tree/main/ROMFS/px4fmu_common/init.d-posix). All files starting with a number and underscore (e.g. `10000_airplane`) are predefined airframe configurations. @@ -13,7 +13,7 @@ The first executed file is the [init.d/rcS](https://github.com/PX4/PX4-Autopilot 根据 PX4 运行的操作系统将本文后续内容分成了如下各小节。 -## POSIX (Linux/MacOS) +## POSIX (Linux/macOS) On POSIX, the system shell is used as script interpreter (e.g. /bin/sh, being symlinked to dash on Ubuntu). 为了使 PX4 可以在 Posix 中正常运行,需要做到以下几点: diff --git a/docs/zh/dev_log/ulog_file_format.md b/docs/zh/dev_log/ulog_file_format.md index 177ebdfff4..80c4b720b9 100644 --- a/docs/zh/dev_log/ulog_file_format.md +++ b/docs/zh/dev_log/ulog_file_format.md @@ -502,6 +502,7 @@ Since the Definitions and Data Sections use the same message header format, they - [ulogreader](https://github.com/maxsun/ulogreader): Javascript, ULog reader and parser outputs log in JSON object format. - [Foxglove](https://foxglove.dev): an integrated visualization and diagnosis tool for robotics data that supports ULog files. - [TypeScript ULog parser](https://github.com/foxglove/ulog): TypeScript, ULog reader that outputs JS objects. +- [yule_log](https://crates.io/crates/yule_log): A streaming ULog parser written in Rust. ## 文件格式版本历史 diff --git a/docs/zh/dev_setup/dev_env.md b/docs/zh/dev_setup/dev_env.md index fadf7c8dca..b53b801540 100644 --- a/docs/zh/dev_setup/dev_env.md +++ b/docs/zh/dev_setup/dev_env.md @@ -2,15 +2,15 @@ The _supported platforms_ for PX4 development are: -- [Ubuntu Linux (22.04/20.04/18.04)](../dev_setup/dev_env_linux_ubuntu.md) — Recommended +- [Ubuntu Linux (24.04/22.04)](../dev_setup/dev_env_linux_ubuntu.md) — Recommended - [Windows (10/11)](../dev_setup/dev_env_windows_wsl.md) — via WSL2 -- [Mac OS](../dev_setup/dev_env_mac.md) +- [macOS](../dev_setup/dev_env_mac.md) ## 支持的编译目标 下表显示了您可以在每个操作系统上构建何种 PX平台的固件编译。 -| 平台 | Linux (Ubuntu) | Mac | Windows | +| 平台 | Linux (Ubuntu) | macOS | Windows | | ------------------------------------------------------------------------------------------------------------------------------------------------------ | :-------------------------------: | :-------------------------: | :-------------------------: | | **NuttX based hardware:** [Pixhawk Series](../flight_controller/pixhawk_series.md), [Crazyflie](../complete_vehicles_mc/crazyflie2.md) | ✓ | ✓ | ✓ | | **Linux-based hardware:** [Raspberry Pi 2/3](../flight_controller/raspberry_pi_navio2.md) | ✓ | | | diff --git a/docs/zh/dev_setup/dev_env_mac.md b/docs/zh/dev_setup/dev_env_mac.md index 8d1b5a0c74..4c52a89da8 100644 --- a/docs/zh/dev_setup/dev_env_mac.md +++ b/docs/zh/dev_setup/dev_env_mac.md @@ -1,4 +1,4 @@ -# Mac 上的开发环境 +# macOS Development Environment MacOS 是受支持的 PX4 开发平台。 根据本文的指示构建的开发环境可以用编译: @@ -22,8 +22,8 @@ The "base" macOS setup installs the tools needed for building firmware, and incl ### Environment Setup :::details -Apple Silicon Macbook users! -If you have an Apple M1, M2 etc. Macbook, make sure to run the terminal as x86 by setting up an x86 terminal: +Apple Silicon MacBook users! +If you have an Apple M1, M2 etc. MacBook, make sure to run the terminal as x86 by setting up an x86 terminal: 1. Locate the Terminal application within the Utilities folder (**Finder > Go menu > Utilities**) 2. Select _Terminal.app_ and right-click on it, then choose **Duplicate**. @@ -50,7 +50,7 @@ First set up the environment 2. Enforce Python 3 by appending the following lines to `~/.zshenv` ```sh - # Point pip3 to MacOS system python 3 pip + # Point pip3 to macOS system python 3 pip alias pip3=/usr/bin/pip3 ``` diff --git a/docs/zh/ros2/offboard_control.md b/docs/zh/ros2/offboard_control.md index 681d4bd155..5ae2e2973d 100644 --- a/docs/zh/ros2/offboard_control.md +++ b/docs/zh/ros2/offboard_control.md @@ -1,6 +1,6 @@ # ROS 2 Offboard 控制示例 -以下的 C++ 示例展示了如何在 [离板模式] (../flight_modes/offboard.md) 中从 ROS 2 节点进行多轴位置控制。 +以下的 C++ 示例展示了如何在[offboard mode](../flight_modes/offboard.md) 中从 ROS 2 节点进行多轴位置控制。 示例将首先发送设置点、进入offboard模式、解锁、起飞至5米,并悬停等待。 虽然简单,但它显示了如何使用offboard控制以及如何向无人机发送指令。 @@ -13,18 +13,18 @@ _Offboard_ control is dangerous. ::: :::info -ROS 与 PX4 存在若干不同的预设(假设),尤其是在坐标系约定([frame conventions])方面../ros/external_position_estimation.md#reference-frames-and-ros +ROS 与 PX4 存在若干不同的预设(假设),尤其是在 [frame conventions](../ros/external_position_estimation.md#reference-frames-and-ros) 当主题发布或订阅时,坐标系类型之间没有隐含转换! 这个例子按照 PX4 的预期在NED坐标系下发布位置。 -若要订阅来自在不同框架内发布的节点的数据(例如ENU, 这是ROS/ROS 2中的标准参考框架,使用 [frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/src/lib/frame_transforms.cpp)库中的辅助函数。 +若要订阅来自在不同框架内发布的节点的数据(例如ENU, 这是ROS/ROS 2中的标准参考框架),使用[frame_transforms](https://github.com/PX4/px4_ros_com/blob/main/src/lib/frame_transforms.cpp)库中的辅助函数。 ::: -## 小試身手 +## 小试身手 -按照 [ROS 2 User Guide](../ros2/user_guide.md)中的说明来安装PX 并运行多轴模拟器,安装ROS 2, 并启动XRCE-DDS代理。 +按照 [ROS 2 用户指南](../ros2/user_guide.md)中的说明来安装PX 并运行多轴模拟器,安装ROS 2, 并启动XRCE-DDS代理。 -之后,我们可参照 ROS 2 用户指南 > 构建 ROS 2 工作空间 (../ros2/user_guide.md#build-ros-2-workspace)中的相似的步骤来运行这个例子。 +之后,我们可参照 [ROS 2 用户指南 > 构建 ROS 2 工作空间](../ros2/user_guide.md#build-ros-2-workspace)中的相似的步骤来运行这个例子。 :::tip 运行 ROS 2 节点前,请确保 QGC已连接到 PX4。 @@ -42,14 +42,14 @@ ROS 与 PX4 存在若干不同的预设(假设),尤其是在坐标系约 cd ~/ws_offboard_control/src/ ``` -3. 将 px4_msgs 代码仓库克隆到 /src 目录下(每个 ROS 2 PX4 工作空间都需要该仓库!): +3. 将[px4_msgs](https://github.com/PX4/px4_msgs)代码仓库克隆到 /src 目录下(每个 ROS 2 PX4 工作空间都需要该仓库!): ```sh git clone https://github.com/PX4/px4_msgs.git - #若未使用 PX4 的 main 分支,请切换到对应的发布分支 + # checkout the matching release branch if not using PX4 main. ``` -4. 将示例代码仓库 px4_ros_com (https://github.com/PX4/px4_ros_com)克隆到 /src 目录下: +4. 将示例代码仓库 [px4_ros_com](https://github.com/PX4/px4_ros_com)克隆到 /src 目录下: ```sh git clone https://github.com/PX4/px4_ros_com.git @@ -213,7 +213,7 @@ void OffboardControl::publish_vehicle_command(uint16_t command, float param1, fl ``` :::info -[VehicleCommand](../msg_docs/VehicleCommand.md是命令PX4的最简单和最高效的方式之一。 通过订阅 [VehicleCommandAck](../msg_docs/VehicleCommandAck.md),您也可以确认设置特定命令是否成功。 +[VehicleCommand](../msg_docs/VehicleCommand.md) 是命令PX4的最简单和最高效的方式之一。 通过订阅 [VehicleCommandAck](../msg_docs/VehicleCommandAck.md),您也可以确认设置特定命令是否成功。 参数字段和 指令字段对应于 [MAVLink commands](https://mavlink.io/en/messages/common.html#mav_commands)以及他们的参数值 ::: diff --git a/docs/zh/ros2/px4_ros2_control_interface.md b/docs/zh/ros2/px4_ros2_control_interface.md index 5be7fedde0..2f03f76e2a 100644 --- a/docs/zh/ros2/px4_ros2_control_interface.md +++ b/docs/zh/ros2/px4_ros2_control_interface.md @@ -24,7 +24,7 @@ Experimental 这些类对 PX4 所使用的内部设定点进行了抽象处理,因此可用于为未来的 PX4 和 ROS 版本提供统一的 ROS 2 接口。 PX4 ROS 2 模式相较于 PX4 内部模式,更易于实现和维护,并且在处理能力与既有代码库资源方面,能为开发者提供更丰富的支持。 -除非该模式属于安全关键型、对时序有严格要求或需要极高的更新速率,或者你的飞行器没有搭载伴随计算机,否则你应优先[考虑使用 PX4 ROS 2 模式,而非 PX4 内部模式](参考链接:../concept/flight_modes.md#internal-vs-external-modes)。 +除非该模式属于安全关键型、对时序有严格要求或需要极高的更新速率,或者你的飞行器没有搭载伴随计算机,否则你应优先[考虑使用 PX4 ROS 2 模式,而非 PX4 内部模式](../concept/flight_modes.md#internal-vs-external-modes)。 ## 综述 diff --git a/docs/zh/test_and_ci/test_flights.md b/docs/zh/test_and_ci/test_flights.md index 094b9cb45f..654ab39b1e 100644 --- a/docs/zh/test_and_ci/test_flights.md +++ b/docs/zh/test_and_ci/test_flights.md @@ -28,5 +28,7 @@ These are run by the test team as part of release testing, and for more signific - [MC_04 - Failsafe Testing](../test_cards/mc_04_failsafe_testing.md) - [MC_05 - Indoor Flight (Manual Modes)](../test_cards/mc_05_indoor_flight_manual_modes.md) - [MC_06 - Indoor Flight (Optical Flow)](../test_cards/mc_06_optical_flow.md) -- [MC_07 - VIO (Visual-Inertial Odometry)](../test_cards/mc_07_vio.md) +- [MC_07 - Optical Flow Low Mount](../test_cards/mc_07_optical_flow_low_mount.md) - [MC_08 - DSHOT ESC](../test_cards/mc_08_dshot.md) +- [MC_09 - VIO (Visual-Inertial Odometry)](../test_cards/mc_09_vio.md) +- [MC_10 - Optical Flow / GPS Mixed](../test_cards/mc_10_optical_flow_gps_mixed.md) diff --git a/docs/zh/test_cards/mc_06_optical_flow.md b/docs/zh/test_cards/mc_06_optical_flow.md index c63bebba16..a5c415366c 100644 --- a/docs/zh/test_cards/mc_06_optical_flow.md +++ b/docs/zh/test_cards/mc_06_optical_flow.md @@ -2,25 +2,23 @@ ## Objective -To test that optical flow works as expected +Test that optical flow works as expected ## Preflight -Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation -([Setup Information here](../sensor/optical_flow.md)) +Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation ([setup information here](../sensor/optical_flow.md)) -Ensure there are no other sources of positioning besides optical flow +Ensure there are no other sources of positioning besides optical flow: - [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` - [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` - [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` -- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` -Ensure that the drone can go into Altitude / Position flight mode while still on the ground +Ensure that the drone can go into Altitude / Position mode while still on the ground ## Flight Tests -❏ Altitude flight mode +❏ [Altitude mode](../flight_modes_mc/altitude.md)     ❏ Vertical position should hold current value with stick centered @@ -28,7 +26,7 @@ Ensure that the drone can go into Altitude / Position flight mode while still on     ❏ Throttle response set to climb/descent rate -❏ Position flight mode +❏ [Position mode](../flight_modes_mc/position.md)     ❏ Horizontal position should hold current value with stick centered @@ -38,6 +36,16 @@ Ensure that the drone can go into Altitude / Position flight mode while still on     ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates +❏ Varying height terrain + +    ❏ Put boxes on the ground to create varying heights in terrain + +    ❏ Take off in position mode and fly over the boxes such that the downward facing rangefinder varies in value + +    ❏ Do a few passes with varying amounts of time over the boxes (1-30 seconds if possible) + +    ❏ Drone should not raise in height when flying over boxes + ## 降落 ❏ Land in either Position or Altitude mode with the throttle below 40% @@ -47,7 +55,8 @@ Ensure that the drone can go into Altitude / Position flight mode while still on ## 预期成果 - 当油门升高时,起飞应该是平稳的 -- Drone should hold altitude in Altitude Flight mode without wandering -- Drone should hold position within 1 meter in Position Flight mode without pilot moving sticks +- Drone should hold altitude in Altitude mode without wandering (over surface with many features) +- Drone should hold position within 1 meter in Position mode without pilot moving sticks - 在上述任何飞行模式中都不应出现振荡 +- Drone should not raise in height when flying over boxes - 着陆时,直升机不应在地面上反弹 diff --git a/docs/zh/test_cards/mc_07_optical_flow_low_mount.md b/docs/zh/test_cards/mc_07_optical_flow_low_mount.md new file mode 100644 index 0000000000..d6458d7adc --- /dev/null +++ b/docs/zh/test_cards/mc_07_optical_flow_low_mount.md @@ -0,0 +1,45 @@ +# Test MC_07 - Optical Flow Low Sensor + +## Objective + +Test that optical flow works as expected with a low mounted optical flow sensor + +## Preflight + +Ensure that the drone's optical flow sensor is mounted more than an inch off of the ground + +Ensure that [MPC_THR_MIN](../advanced_config/parameter_reference.md#MPC_THR_MIN) is tuned correctly for landing + +Disconnect all GPS / compasses and ensure vehicle is using optical flow for navigation +([Setup Information here](../sensor/optical_flow.md)) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` + +Ensure that the drone can go into [Position mode](../flight_modes_mc/position.md) while still on the ground + +## Flight Tests + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## 降落 + +❏ Land in Position mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## 预期成果 + +- 当油门升高时,起飞应该是平稳的 +- Drone should stay in Position mode, NOT fall into [altitude](../flight_modes_mc/altitude.md) mode diff --git a/docs/zh/test_cards/mc_08_dshot.md b/docs/zh/test_cards/mc_08_dshot.md index 2f0ef74bdb..ca740ca877 100644 --- a/docs/zh/test_cards/mc_08_dshot.md +++ b/docs/zh/test_cards/mc_08_dshot.md @@ -6,22 +6,22 @@ Regression test for DSHOT working with PX4 ## Preflight -- Ensure vehicle is using a DSHOT ESC. +- Ensure vehicle is using a DSHOT ESC - Parameter [DSHOT_BIDIR_EN](../advanced_config/parameter_reference.md#DSHOT_BIDIR_EN) is enabled - Parameter [DSHOT_TEL_CFG](../advanced_config/parameter_reference.md#DSHOT_TEL_CFG) is configured (if ESC supports telemetry) - Parameter [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) has Debug (`5`) checked ## Flight Tests -❏ Stabilized Flight mode +❏ [Stabilized mode](../flight_modes_mc/manual_stabilized.md) -    ❏ Takeoff in stabilized flight mode to ensure correct motor spin +    ❏ Takeoff in stabilized mode to ensure correct motor spin     ❏ Pitch/Roll/Yaw response 1:1     ❏ Throttle response 1:1 -❏ Position flight mode +❏ [Position mode](../flight_modes_mc/position.md)     ❏ Horizontal position should hold current value with stick centered @@ -41,6 +41,6 @@ Regression test for DSHOT working with PX4 - Download flight logs - Load into Data Plot Juggler -- Ensure data is logged for esc_status/esc.0x/esc_rpm +- Ensure data is logged for `esc_status`/`esc.0x`/`esc_rpm` ![Reference frames](../../assets/test_cards/dshot_log_output.png) diff --git a/docs/zh/test_cards/mc_09_vio.md b/docs/zh/test_cards/mc_09_vio.md new file mode 100644 index 0000000000..a1438f8967 --- /dev/null +++ b/docs/zh/test_cards/mc_09_vio.md @@ -0,0 +1,52 @@ +# Test MC_09 - VIO (Visual-Inertial Odometry) + +## Objective + +Test that external vision (VIO) works as expected + +## Preflight + +Disconnect all GPS / compasses and ensure vehicle is using VIO for navigation + +Ensure that the drone can go into [Altitude](../flight_modes_mc/altitude.md) / [Position](../flight_modes_mc/position.md) mode while still on the ground + +Ensure there are no other sources of positioning besides VIO: + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `0` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `0` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `15` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `0` + +## Flight Tests + +❏ [Altitude mode](../flight_modes_mc/altitude.md) + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response set to climb/descent rate + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +## 降落 + +❏ Land in either Position or Altitude mode with the throttle below 40% + +❏ Upon touching ground, copter should disarm automatically within 2 seconds (default: see [COM_DISARM_LAND](../advanced_config/parameter_reference.md#COM_DISARM_LAND)) + +## 预期成果 + +- 当油门升高时,起飞应该是平稳的 +- Drone should hold altitude in Altitude mode without wandering +- Drone should hold position within 1 meter in Position mode without pilot moving sticks +- 在上述任何飞行模式中都不应出现振荡 +- 着陆时,直升机不应在地面上反弹 diff --git a/docs/zh/test_cards/mc_10_optical_flow_gps_mixed.md b/docs/zh/test_cards/mc_10_optical_flow_gps_mixed.md new file mode 100644 index 0000000000..61097c8568 --- /dev/null +++ b/docs/zh/test_cards/mc_10_optical_flow_gps_mixed.md @@ -0,0 +1,74 @@ +# Test MC_10 - Optical Flow / GPS Mixed + +## Objective + +Test that optical flow mixed with GPS works as expected + +## Preflight + +[Setup optical flow and GPS](../sensor/optical_flow.md) + +Ensure there are no other sources of positioning besides optical flow + +- [EKF2_OF_CTRL](../advanced_config/parameter_reference.md#EKF2_OF_CTRL): `1` +- [EKF2_GPS_CTRL](../advanced_config/parameter_reference.md#EKF2_GPS_CTRL): `7` +- [EKF2_EV_CTRL](../advanced_config/parameter_reference.md#EKF2_EV_CTRL): `0` +- [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG): `1` +- [EKF2_HGT_REF](../advanced_config/parameter_reference.md#EKF2_HGT_REF): `1` (GPS) + +Ensure that the drone can go into [Altitude](../flight_modes_mc/altitude.md) / [Position](../flight_modes_mc/position.md) mode while still on the ground + +## Flight Tests + +❏ [Altitude mode](../flight_modes_mc/altitude.md) + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Pitch/Roll/Yaw response 1:1 + +    ❏ Throttle response set to climb/descent rate + +❏ [Position mode](../flight_modes_mc/position.md) + +    ❏ Horizontal position should hold current value with stick centered + +    ❏ Vertical position should hold current value with stick centered + +    ❏ Throttle response set to climb/descent rate + +    ❏ Pitch/Roll/Yaw response set to pitch/roll/yaw rates + +❏ GPS Cutout + +    ❏ Takeoff in position mode in GPS rich environment (outdoors) + +    ❏ Open QGC and navigate to MAVLink Console + +    ❏ Type `gps off` to disable GPS + +    ❏ Drone should maintain position hold via optical flow + +❏ GPS Degredation + +    ❏ Takeoff in position mode in GPS rich environment (outdoors) + +    ❏ Fly under a metal surface (or other GPS blocking structure) + +    ❏ Ensure drone does not lose position hold or start drifting + +    ❏ Fly out of metal structure to regain GPS + +❏ GPS Acquisition + +    ❏ Takeoff in position mode in non-GPS environment + +    ❏ Fly into a GPS rich environment (outdoors) + +    ❏ Ensure drone acquires GPS position + +## 预期成果 + +- 当油门升高时,起飞应该是平稳的 +- Drone should hold position within 1 meter in Position mode without pilot moving sticks +- Drone should hold position in GPS rich environment as well as non-GPS environment +- 在上述任何飞行模式中都不应出现振荡 From 2c62caeb7dd3763b461fa953a03818add2791807 Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Mon, 13 Oct 2025 19:56:23 -0800 Subject: [PATCH 171/812] flight task auto: fix offtrack mission landing bug (#25725) During a mission the last waypoint is often a LAND. If the previous waypoint is not directly above the land waypoint the offtrack calculation is incorrect. This regression was introduced when the offtrack calculation switched from 2D to 3D. --- src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp index 2eceae9353..47807bffb6 100644 --- a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp +++ b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp @@ -612,6 +612,7 @@ State FlightTaskAuto::_getCurrentState() const Vector3f u_prev_to_target = (_triplet_target - _triplet_prev_wp).unit_or_zero(); const Vector3f prev_to_pos = _position - _triplet_prev_wp; const Vector3f pos_to_target = _triplet_target - _position; + // Calculate the closest point to the vehicle position on the line prev_wp - target _closest_pt = _triplet_prev_wp + u_prev_to_target * (prev_to_pos * u_prev_to_target); @@ -629,10 +630,9 @@ State FlightTaskAuto::_getCurrentState() // Previous is in front return_state = State::previous_infront; - } else if ((_position - _closest_pt).longerThan(_target_acceptance_radius)) { + } else if (_type != WaypointType::land && (_position - _closest_pt).longerThan(_target_acceptance_radius)) { // Vehicle too far from the track return_state = State::offtrack; - } return return_state; From 2f06f037284fabbfafa1ed14bd3fb72b8ea118f5 Mon Sep 17 00:00:00 2001 From: Marco Hauswirth <58551738+haumarco@users.noreply.github.com> Date: Tue, 14 Oct 2025 06:51:25 +0200 Subject: [PATCH 172/812] calibration: mag: only allow mag calibration when at least one mag is available and enabled (i.e. not prio=0) (#25714) --- src/modules/commander/mag_calibration.cpp | 35 +++++++++++++++++++++-- 1 file changed, 32 insertions(+), 3 deletions(-) diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp index 7aeadeab55..fb6dfa0282 100644 --- a/src/modules/commander/mag_calibration.cpp +++ b/src/modules/commander/mag_calibration.cpp @@ -520,12 +520,36 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_ma const unsigned int calibration_points_maxcount = worker_data.calibration_sides * worker_data.calibration_points_perside; + uORB::SubscriptionMultiArray mag_sub{ORB_ID::sensor_mag}; + int mag_available_enabled_count = 0; + for (uint8_t cur_mag = 0; cur_mag < MAX_MAGS; cur_mag++) { - uORB::SubscriptionData mag_sub{ORB_ID(sensor_mag), cur_mag}; + if (!mag_sub[cur_mag].advertised()) { + continue; + } - if (mag_sub.advertised() && (mag_sub.get().device_id != 0) && (mag_sub.get().timestamp > 0)) { - worker_data.calibration[cur_mag].set_device_id(mag_sub.get().device_id); + sensor_mag_s mag_data; + + if (!mag_sub[cur_mag].copy(&mag_data) || mag_data.device_id == 0) { + continue; + } + + int calibration_index = calibration::FindCurrentCalibrationIndex("MAG", mag_data.device_id); + + if (calibration_index >= 0) { + int priority = calibration::GetCalibrationParamInt32("MAG", "PRIO", calibration_index); + + if (priority != 0) { + ++mag_available_enabled_count; + } + + } else { + ++mag_available_enabled_count; + } + + if ((mag_data.device_id != 0) && (mag_data.timestamp > 0)) { + worker_data.calibration[cur_mag].set_device_id(mag_data.device_id); } // reset calibration index to match uORB numbering @@ -547,6 +571,11 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_ma } } + if (mag_available_enabled_count <= 0) { + calibration_log_critical(mavlink_log_pub, "Failed: No magnetometer available or enabled"); + return calibrate_return_error; + } + if (result == calibrate_return_ok) { result = calibrate_from_orientation(mavlink_log_pub, // uORB handle to write output worker_data.side_data_collected, // Sides to calibrate From aa0668663aa2aa34745f3866ef921ca765b9f95a Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 13 Oct 2025 21:52:41 -0700 Subject: [PATCH 173/812] docs: clean urls for vitepress builds (#25718) Signed-off-by: Ramon Roche --- docs/.vitepress/config.mjs | 1 + 1 file changed, 1 insertion(+) diff --git a/docs/.vitepress/config.mjs b/docs/.vitepress/config.mjs index 95831b347a..e9190be018 100644 --- a/docs/.vitepress/config.mjs +++ b/docs/.vitepress/config.mjs @@ -31,6 +31,7 @@ export default defineConfig({ tabsPlugin(md); //https://github.com/Red-Asuka/vitepress-plugin-tabs }, }, + cleanUrls: true, vite: { plugins: [ From 33301764e4fd6fd03246ca4654c8541b429600dc Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 14 Oct 2025 06:56:27 +0200 Subject: [PATCH 174/812] Handle `SYS_AUTOSTART` 0 the same as no valid airframe being available (#25645) * ROMFS: do not exit airframe loading if SYS_AUTOSTART is 0 Do not treat 0 as a magic value that skips the aiframe loading. Instead leave it tot he rc.autostart to load an airframe that if finds appropriate (can be defined in external aiframe). Signed-off-by: Silvan * ROMFS: adjust airframe load spacing and message/comment wording --------- Signed-off-by: Silvan Co-authored-by: Silvan --- ROMFS/px4fmu_common/init.d/rcS | 36 +++++++++++++++------------------- 1 file changed, 16 insertions(+), 20 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index f747966e03..1337a777c8 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -228,30 +228,26 @@ else fi unset BOARD_RC_ADDITIONAL_INIT - # Load airframe configuration based on SYS_AUTOSTART parameter - if ! param compare SYS_AUTOSTART 0 + # Load airframe configuration based on SYS_AUTOSTART parameter if successful VEHICLE_TYPE gets set + # Run autogenerated ROMFS airframe script + . ${R}etc/init.d/rc.autostart + + if [ ${VEHICLE_TYPE} = none ] then - # rc.autostart directly run the right airframe script which sets the VEHICLE_TYPE - # Look for airframe in ROMFS - . ${R}etc/init.d/rc.autostart - - if [ ${VEHICLE_TYPE} = none ] + # Run external airframe script on SD card + if [ $STORAGE_AVAILABLE = yes ] then - # Use external startup file - if [ $STORAGE_AVAILABLE = yes ] - then - . ${R}etc/init.d/rc.autostart_ext - else - echo "ERROR [init] SD card not mounted - can't load external airframe" - fi + . ${R}etc/init.d/rc.autostart_ext + else + echo "ERROR [init] SD not mounted, skipping external airframe" fi + fi - if [ ${VEHICLE_TYPE} = none ] - then - echo "ERROR [init] No airframe file found for SYS_AUTOSTART value" - param set SYS_AUTOSTART 0 - tune_control play error - fi + if [ ${VEHICLE_TYPE} = none ] + then + echo "ERROR [init] No airframe file found for SYS_AUTOSTART value" + param set SYS_AUTOSTART 0 + tune_control play error fi # Check parameter version and reset upon airframe configuration version mismatch. From 12035682d79fc71872a0570a7d04c40c9ce737d9 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 14 Oct 2025 06:58:34 +0200 Subject: [PATCH 175/812] Use MAVLink v1 only as opt-in (#25583) * Remove support for MAVLink 1 * Add back support for MAVLink 1 but don't default to it * Update src/modules/mavlink/mavlink_params.c Co-authored-by: Hamish Willee --------- Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Co-authored-by: Hamish Willee --- .../6011_gazebo-classic_typhoon_h480 | 1 - ROMFS/px4fmu_common/init.d-posix/rcS | 1 - boards/ark/dist/init/rc.board_sensors | 1 - .../amovlabf410_drone_v1.15.4.params | 1 - docs/en/dev_log/logging.md | 2 +- docs/en/gps_compass/rtk_gps.md | 2 +- src/modules/mavlink/mavlink_main.cpp | 22 ++++--------------- src/modules/mavlink/mavlink_main.h | 12 ++-------- src/modules/mavlink/mavlink_params.c | 7 +++--- src/modules/mavlink/mavlink_receiver.cpp | 6 ++--- 10 files changed, 14 insertions(+), 41 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/6011_gazebo-classic_typhoon_h480 b/ROMFS/px4fmu_common/init.d-posix/airframes/6011_gazebo-classic_typhoon_h480 index f75374b15c..1904832613 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/6011_gazebo-classic_typhoon_h480 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/6011_gazebo-classic_typhoon_h480 @@ -26,7 +26,6 @@ param set-default TRIG_INTERFACE 3 param set-default TRIG_MODE 4 param set-default MNT_MODE_IN 4 param set-default MNT_MODE_OUT 2 -param set-default MAV_PROTO_VER 2 param set-default CA_AIRFRAME 0 param set-default CA_ROTOR_COUNT 6 diff --git a/ROMFS/px4fmu_common/init.d-posix/rcS b/ROMFS/px4fmu_common/init.d-posix/rcS index bbbc55930c..a2d331ba1e 100644 --- a/ROMFS/px4fmu_common/init.d-posix/rcS +++ b/ROMFS/px4fmu_common/init.d-posix/rcS @@ -173,7 +173,6 @@ param set-default COM_RC_IN_MODE 1 param set-default EKF2_REQ_GPS_H 0.5 param set-default IMU_GYRO_FFT_EN 1 -param set-default MAV_PROTO_VER 2 # Ensures QGC does not drop the first few packets after a SITL restart due to MAVLINK 1 packets param set-default -s MC_AT_EN 1 diff --git a/boards/ark/dist/init/rc.board_sensors b/boards/ark/dist/init/rc.board_sensors index 0b7d52a6f1..16a809054c 100644 --- a/boards/ark/dist/init/rc.board_sensors +++ b/boards/ark/dist/init/rc.board_sensors @@ -11,7 +11,6 @@ param set-default SENS_AFBR_HYSTER 1 param set-default MAV_SYS_ID 158 param set-default MAV_COMP_ID 158 -param set-default MAV_PROTO_VER 2 param set-default MAV_0_MODE 14 param set-default MAV_0_FORWARD 0 diff --git a/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params b/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params index 2b611958b9..3a27322f74 100644 --- a/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params +++ b/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params @@ -571,7 +571,6 @@ 1 1 MAV_FWDEXTSP 1 6 1 1 MAV_HASH_CHK_EN 1 6 1 1 MAV_HB_FORW_EN 1 6 -1 1 MAV_PROTO_VER 0 6 1 1 MAV_RADIO_TOUT 5 6 1 1 MAV_SIK_RADIO_ID 0 6 1 1 MAV_SYS_ID 1 6 diff --git a/docs/en/dev_log/logging.md b/docs/en/dev_log/logging.md index e2c91e56d5..47d4d6f385 100644 --- a/docs/en/dev_log/logging.md +++ b/docs/en/dev_log/logging.md @@ -161,7 +161,7 @@ There are different clients that support ulog streaming: - If log streaming does not start, make sure the `logger` is running (see above), and inspect the console output while starting. - If it still does not work, make sure that MAVLink 2 is used. - Enforce it by setting `MAV_PROTO_VER` to 2. + `MAV_PROTO_VER` needs to be set to 2. - Log streaming uses a maximum of 70% of the configured MAVLink rate (`-r` parameter). If more is needed, messages are dropped. The currently used percentage can be inspected with `mavlink status` (1.8% is used in this example): diff --git a/docs/en/gps_compass/rtk_gps.md b/docs/en/gps_compass/rtk_gps.md index fcaea1c01b..b24cf96c77 100644 --- a/docs/en/gps_compass/rtk_gps.md +++ b/docs/en/gps_compass/rtk_gps.md @@ -203,7 +203,7 @@ This should be enabled by default on recent builds. To ensure MAVLink2 is used: - Update the telemetry module firmware to the latest version (see [QGroundControl > Setup > Firmware](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/firmware.html)). -- Set [MAV_PROTO_VER](../advanced_config/parameter_reference.md#MAV_PROTO_VER) to 2 (see [QGroundControl Setup > Parameters](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/parameters.html)) +- Ensure [MAV_PROTO_VER](../advanced_config/parameter_reference.md#MAV_PROTO_VER) is set to 2 (see [QGroundControl Setup > Parameters](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/parameters.html)) #### Tuning diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 3b4c39a73e..0312a0b6b2 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -187,12 +187,7 @@ Mavlink::mavlink_update_parameters() { updateParams(); - int32_t proto = _param_mav_proto_ver.get(); - - if (_protocol_version_switch != proto) { - _protocol_version_switch = proto; - set_proto_version(proto); - } + set_protocol_version(_param_mav_proto_ver.get()); if (_param_mav_type.get() < 0 || _param_mav_type.get() >= MAV_TYPE_ENUM_END) { _param_mav_type.set(0); @@ -277,16 +272,13 @@ Mavlink::set_instance_id() return false; } -void -Mavlink::set_proto_version(unsigned version) +void Mavlink::set_protocol_version(unsigned version) { - if ((version == 1 || version == 0) && - ((_protocol_version_switch == 0) || (_protocol_version_switch == 1))) { + if (version == 1) { get_status()->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1; _protocol_version = 1; - } else if (version == 2 && - ((_protocol_version_switch == 0) || (_protocol_version_switch == 2))) { + } else { get_status()->flags &= ~(MAVLINK_STATUS_FLAG_OUT_MAVLINK1); _protocol_version = 2; } @@ -1156,13 +1148,7 @@ Mavlink::send_protocol_version() //memcpy(&msg.spec_version_hash, &mavlink_spec_git_version_binary, sizeof(msg.spec_version_hash)); memcpy(&msg.library_version_hash, &mavlink_lib_git_version_binary, sizeof(msg.library_version_hash)); - // Switch to MAVLink 2 - int curr_proto_ver = _protocol_version; - set_proto_version(2); - // Send response - if it passes through the link its fine to use MAVLink 2 mavlink_msg_protocol_version_send_struct(get_channel(), &msg); - // Reset to previous value - set_proto_version(curr_proto_ver); } int diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 0379bd2c11..18058bd54b 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -157,14 +157,7 @@ public: mavlink_status_t *get_status() { return &_mavlink_status; } - /** - * Set the MAVLink version - * - * Currently supporting v1 and v2 - * - * @param version MAVLink version - */ - void set_proto_version(unsigned version); + void set_protocol_version(unsigned version); static int destroy_all_instances(); @@ -620,8 +613,7 @@ private: uint64_t _last_write_success_time{0}; uint64_t _last_write_try_time{0}; uint64_t _mavlink_start_time{0}; - int32_t _protocol_version_switch{-1}; - int32_t _protocol_version{0}; + int32_t _protocol_version = 0; ///< after initialization the only values are 1 and 2 unsigned _bytes_tx{0}; unsigned _bytes_txerr{0}; diff --git a/src/modules/mavlink/mavlink_params.c b/src/modules/mavlink/mavlink_params.c index 8a793f5e5f..f616bd01d6 100644 --- a/src/modules/mavlink/mavlink_params.c +++ b/src/modules/mavlink/mavlink_params.c @@ -52,11 +52,10 @@ PARAM_DEFINE_INT32(MAV_COMP_ID, 1); /** * MAVLink protocol version * @group MAVLink - * @value 0 Default to 1, switch to 2 if GCS sends version 2 - * @value 1 Always use version 1 - * @value 2 Always use version 2 + * @value 1 Version 1 with auto-upgrade to v2 if detected + * @value 2 Version 2 */ -PARAM_DEFINE_INT32(MAV_PROTO_VER, 0); +PARAM_DEFINE_INT32(MAV_PROTO_VER, 2); /** * MAVLink SiK Radio ID diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 4673ed6e72..2aaad09a19 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -3228,10 +3228,10 @@ MavlinkReceiver::run() for (ssize_t i = 0; i < nread; i++) { if (mavlink_parse_char(_mavlink.get_channel(), buf[i], &msg, &_status)) { - /* check if we received version 2 and request a switch. */ + // If we receive a complete MAVLink 2 packet, also switch the outgoing protocol version if (!(_mavlink.get_status()->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1)) { - /* this will only switch to proto version 2 if allowed in settings */ - _mavlink.set_proto_version(2); + PX4_INFO("Upgrade to MAVLink v2 because of incoming packet"); + _mavlink.set_protocol_version(2); } switch (_mavlink.get_mode()) { From 4842c542b80e7dcc433424984aed98907e054052 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 14 Oct 2025 07:41:11 +0200 Subject: [PATCH 176/812] rc_update: remove 1% deadzone for RC channels 1-8 (#25502) * rc_update: remove 1% deadzone for all channels this should be handled higher level. * Remove all references to the RC{n}_DZ parameters Regular expression: RC.{0,2}_DZ --------- Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> --- .../amovlabf410_drone_v1.15.4.params | 18 -- docs/en/flight_modes_mc/altitude.md | 1 - docs/en/flight_modes_mc/position.md | 1 - .../checks/rcCalibrationCheck.cpp | 29 +-- .../checks/rcCalibrationCheck.hpp | 4 +- src/modules/rc_update/params.c | 202 ------------------ src/modules/rc_update/rc_update.cpp | 19 +- src/modules/rc_update/rc_update.h | 2 - 8 files changed, 6 insertions(+), 270 deletions(-) diff --git a/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params b/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params index 3a27322f74..53b68cdeb4 100644 --- a/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params +++ b/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params @@ -803,92 +803,74 @@ 1 1 PWM_MAIN_TIM1 400 6 1 1 PWM_MAIN_TIM2 -1 6 1 1 PWM_SBUS_MODE 0 6 -1 1 RC10_DZ 0.000000000000000000 9 1 1 RC10_MAX 2000.000000000000000000 9 1 1 RC10_MIN 1000.000000000000000000 9 1 1 RC10_REV 1.000000000000000000 9 1 1 RC10_TRIM 1500.000000000000000000 9 -1 1 RC11_DZ 0.000000000000000000 9 1 1 RC11_MAX 2000.000000000000000000 9 1 1 RC11_MIN 1000.000000000000000000 9 1 1 RC11_REV 1.000000000000000000 9 1 1 RC11_TRIM 1500.000000000000000000 9 -1 1 RC12_DZ 0.000000000000000000 9 1 1 RC12_MAX 2000.000000000000000000 9 1 1 RC12_MIN 1000.000000000000000000 9 1 1 RC12_REV 1.000000000000000000 9 1 1 RC12_TRIM 1500.000000000000000000 9 -1 1 RC13_DZ 0.000000000000000000 9 1 1 RC13_MAX 2000.000000000000000000 9 1 1 RC13_MIN 1000.000000000000000000 9 1 1 RC13_REV 1.000000000000000000 9 1 1 RC13_TRIM 1500.000000000000000000 9 -1 1 RC14_DZ 0.000000000000000000 9 1 1 RC14_MAX 2000.000000000000000000 9 1 1 RC14_MIN 1000.000000000000000000 9 1 1 RC14_REV 1.000000000000000000 9 1 1 RC14_TRIM 1500.000000000000000000 9 -1 1 RC15_DZ 0.000000000000000000 9 1 1 RC15_MAX 2000.000000000000000000 9 1 1 RC15_MIN 1000.000000000000000000 9 1 1 RC15_REV 1.000000000000000000 9 1 1 RC15_TRIM 1500.000000000000000000 9 -1 1 RC16_DZ 0.000000000000000000 9 1 1 RC16_MAX 2000.000000000000000000 9 1 1 RC16_MIN 1000.000000000000000000 9 1 1 RC16_REV 1.000000000000000000 9 1 1 RC16_TRIM 1500.000000000000000000 9 -1 1 RC17_DZ 0.000000000000000000 9 1 1 RC17_MAX 2000.000000000000000000 9 1 1 RC17_MIN 1000.000000000000000000 9 1 1 RC17_REV 1.000000000000000000 9 1 1 RC17_TRIM 1500.000000000000000000 9 -1 1 RC18_DZ 0.000000000000000000 9 1 1 RC18_MAX 2000.000000000000000000 9 1 1 RC18_MIN 1000.000000000000000000 9 1 1 RC18_REV 1.000000000000000000 9 1 1 RC18_TRIM 1500.000000000000000000 9 -1 1 RC1_DZ 10.000000000000000000 9 1 1 RC1_MAX 1996.000000000000000000 9 1 1 RC1_MIN 999.000000000000000000 9 1 1 RC1_REV 1.000000000000000000 9 1 1 RC1_TRIM 1498.000000000000000000 9 -1 1 RC2_DZ 10.000000000000000000 9 1 1 RC2_MAX 1998.000000000000000000 9 1 1 RC2_MIN 1000.000000000000000000 9 1 1 RC2_REV 1.000000000000000000 9 1 1 RC2_TRIM 1499.000000000000000000 9 -1 1 RC3_DZ 10.000000000000000000 9 1 1 RC3_MAX 1997.000000000000000000 9 1 1 RC3_MIN 1000.000000000000000000 9 1 1 RC3_REV 1.000000000000000000 9 1 1 RC3_TRIM 1000.000000000000000000 9 -1 1 RC4_DZ 10.000000000000000000 9 1 1 RC4_MAX 1997.000000000000000000 9 1 1 RC4_MIN 1000.000000000000000000 9 1 1 RC4_REV 1.000000000000000000 9 1 1 RC4_TRIM 1498.000000000000000000 9 -1 1 RC5_DZ 10.000000000000000000 9 1 1 RC5_MAX 2000.000000000000000000 9 1 1 RC5_MIN 1000.000000000000000000 9 1 1 RC5_REV 1.000000000000000000 9 1 1 RC5_TRIM 1500.000000000000000000 9 -1 1 RC6_DZ 10.000000000000000000 9 1 1 RC6_MAX 2000.000000000000000000 9 1 1 RC6_MIN 1000.000000000000000000 9 1 1 RC6_REV 1.000000000000000000 9 1 1 RC6_TRIM 1500.000000000000000000 9 -1 1 RC7_DZ 10.000000000000000000 9 1 1 RC7_MAX 2000.000000000000000000 9 1 1 RC7_MIN 1000.000000000000000000 9 1 1 RC7_REV 1.000000000000000000 9 1 1 RC7_TRIM 1500.000000000000000000 9 -1 1 RC8_DZ 10.000000000000000000 9 1 1 RC8_MAX 2000.000000000000000000 9 1 1 RC8_MIN 1000.000000000000000000 9 1 1 RC8_REV 1.000000000000000000 9 1 1 RC8_TRIM 1500.000000000000000000 9 -1 1 RC9_DZ 0.000000000000000000 9 1 1 RC9_MAX 2000.000000000000000000 9 1 1 RC9_MIN 1000.000000000000000000 9 1 1 RC9_REV 1.000000000000000000 9 diff --git a/docs/en/flight_modes_mc/altitude.md b/docs/en/flight_modes_mc/altitude.md index fda7dde9bb..7d35590443 100644 --- a/docs/en/flight_modes_mc/altitude.md +++ b/docs/en/flight_modes_mc/altitude.md @@ -47,5 +47,4 @@ The mode is affected by the following parameters: | ----------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | |
[MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | Maximum vertical ascent velocity. Default: 3 m/s. | | [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | Maximum vertical descent velocity. Default: 1 m/s. | -| `RCX_DZ` | RC dead zone for channel X. The value of X for throttle will depend on the value of [RC_MAP_THROTTLE](../advanced_config/parameter_reference.md#RC_MAP_THROTTLE). For example, if the throttle is channel 4 then [RC4_DZ](../advanced_config/parameter_reference.md#RC4_DZ) specifies the deadzone. | | `MPC_XXXX` | Most of the MPC_xxx parameters affect flight behaviour in this mode (at least to some extent). For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | diff --git a/docs/en/flight_modes_mc/position.md b/docs/en/flight_modes_mc/position.md index 69367bc4b1..75fae4ab21 100644 --- a/docs/en/flight_modes_mc/position.md +++ b/docs/en/flight_modes_mc/position.md @@ -67,7 +67,6 @@ All the parameters in the [Multicopter Position Control](../advanced_config/para | [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | Maximum vertical descent velocity. Default: 1 m/s. | | [MPC_LAND_ALT1](../advanced_config/parameter_reference.md#MPC_LAND_ALT1) | Altitude for triggering first phase of slow landing. Below this altitude descending velocity gets limited to a value between [MPC_Z_VEL_MAX_DN](#MPC_Z_VEL_MAX_DN) (or `MPC_Z_V_AUTO_DN`) and [MPC_LAND_SPEED](#MPC_LAND_SPEED). Value needs to be higher than [MPC_LAND_ALT2](#MPC_LAND_ALT2). Default 10m. | | [MPC_LAND_ALT2](../advanced_config/parameter_reference.md#MPC_LAND_ALT2) | Altitude for second phase of slow landing. Below this altitude descending velocity gets limited to [`MPC_LAND_SPEED`](#MPC_LAND_SPEED). Value needs to be lower than "MPC_LAND_ALT1". Default 5m. | -| `RCX_DZ` | RC dead zone for channel X. The value of X for throttle will depend on the value of [RC_MAP_THROTTLE](../advanced_config/parameter_reference.md#RC_MAP_THROTTLE). For example, if the throttle is channel 4 then [RC4_DZ](../advanced_config/parameter_reference.md#RC4_DZ) specifies the deadzone. | | `MPC_XXXX` | Most of the MPC_xxx parameters affect flight behaviour in this mode (at least to some extent). For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | | [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE) | Stick input to movement translation strategy. From PX4 v1.12 the default (`Acceleration based`) is that stick position controls acceleration (in a similar way to a car accelerator pedal). Other options allow stick deflection to directly control speed over ground, with and without smoothing and acceleration limits. | | [MPC_ACC_HOR_MAX](../advanced_config/parameter_reference.md#MPC_ACC_HOR_MAX) | Maximum horizontal acceleration. | diff --git a/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.cpp index d1008d3253..f16505e4a2 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2019 PX4 Development Team. All rights reserved. + * Copyright (c) 2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -33,11 +33,6 @@ #include "rcCalibrationCheck.hpp" -/** - * Maximum deadzone value - */ -#define RC_INPUT_MAX_DEADZONE_US 500 - /** * Minimum value */ @@ -61,9 +56,6 @@ RcCalibrationChecks::RcCalibrationChecks() snprintf(nbuf, sizeof(nbuf), "RC%d_MAX", i + 1); _param_handles[i].max = param_find(nbuf); - - snprintf(nbuf, sizeof(nbuf), "RC%d_DZ", i + 1); - _param_handles[i].dz = param_find(nbuf); } updateParams(); @@ -84,7 +76,6 @@ void RcCalibrationChecks::checkAndReport(const Context &context, Report &reporte float param_min = _param_values[i].min; float param_max = _param_values[i].max; float param_trim = _param_values[i].trim; - float param_dz = _param_values[i].dz; /* assert min..center..max ordering */ if (param_min < RC_INPUT_LOWEST_MIN_US) { @@ -148,22 +139,6 @@ void RcCalibrationChecks::checkAndReport(const Context &context, Report &reporte (int)param_trim, (int)param_max); } } - - /* assert deadzone is sane */ - if (param_dz > RC_INPUT_MAX_DEADZONE_US) { - /* EVENT - * @description - * Recalibrate the RC. - */ - reporter.armingCheckFailure(NavModes::All, health_component_t::remote_control, - events::ID("check_rc_dz_too_high"), - events::Log::Error, "RC calibration for channel {1} invalid: DZ greater than {2}", i + 1, RC_INPUT_MAX_DEADZONE_US); - - if (reporter.mavlink_log_pub()) { - mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: RC ERROR: RC%d_DZ > %u", i + 1, - RC_INPUT_MAX_DEADZONE_US); - } - } } } @@ -176,11 +151,9 @@ void RcCalibrationChecks::updateParams() _param_values[i].min = 0.0f; _param_values[i].max = 0.0f; _param_values[i].trim = 0.0f; - _param_values[i].dz = RC_INPUT_MAX_DEADZONE_US * 2.0f; param_get(_param_handles[i].min, &_param_values[i].min); param_get(_param_handles[i].trim, &_param_values[i].trim); param_get(_param_handles[i].max, &_param_values[i].max); - param_get(_param_handles[i].dz, &_param_values[i].dz); } } diff --git a/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.hpp b/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.hpp index 6a2d30a83f..d0b4a80d8d 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.hpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/rcCalibrationCheck.hpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2022 PX4 Development Team. All rights reserved. + * Copyright (c) 2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -53,13 +53,11 @@ private: param_t min; param_t trim; param_t max; - param_t dz; }; struct ParamValues { float min; float trim; float max; - float dz; }; ParamHandles _param_handles[input_rc_s::RC_INPUT_MAX_CHANNELS]; diff --git a/src/modules/rc_update/params.c b/src/modules/rc_update/params.c index d764ae5d34..3709a3a841 100644 --- a/src/modules/rc_update/params.c +++ b/src/modules/rc_update/params.c @@ -87,18 +87,6 @@ PARAM_DEFINE_FLOAT(RC1_MAX, 2000.0f); */ PARAM_DEFINE_FLOAT(RC1_REV, 1.0f); -/** - * RC channel 1 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @unit us - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC1_DZ, 10.0f); - /** * RC channel 2 minimum * @@ -148,18 +136,6 @@ PARAM_DEFINE_FLOAT(RC2_MAX, 2000.0f); */ PARAM_DEFINE_FLOAT(RC2_REV, 1.0f); -/** - * RC channel 2 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @unit us - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC2_DZ, 10.0f); - /** * RC channel 3 minimum * @@ -209,18 +185,6 @@ PARAM_DEFINE_FLOAT(RC3_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC3_REV, 1.0f); -/** - * RC channel 3 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @unit us - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC3_DZ, 10.0f); - /** * RC channel 4 minimum * @@ -270,18 +234,6 @@ PARAM_DEFINE_FLOAT(RC4_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC4_REV, 1.0f); -/** - * RC channel 4 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @unit us - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC4_DZ, 10.0f); - /** * RC channel 5 minimum * @@ -331,17 +283,6 @@ PARAM_DEFINE_FLOAT(RC5_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC5_REV, 1.0f); -/** - * RC channel 5 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC5_DZ, 10.0f); - /** * RC channel 6 minimum * @@ -391,17 +332,6 @@ PARAM_DEFINE_FLOAT(RC6_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC6_REV, 1.0f); -/** - * RC channel 6 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC6_DZ, 10.0f); - /** * RC channel 7 minimum * @@ -451,17 +381,6 @@ PARAM_DEFINE_FLOAT(RC7_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC7_REV, 1.0f); -/** - * RC channel 7 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC7_DZ, 10.0f); - /** * RC channel 8 minimum * @@ -511,17 +430,6 @@ PARAM_DEFINE_FLOAT(RC8_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC8_REV, 1.0f); -/** - * RC channel 8 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC8_DZ, 10.0f); - /** * RC channel 9 minimum * @@ -571,17 +479,6 @@ PARAM_DEFINE_FLOAT(RC9_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC9_REV, 1.0f); -/** - * RC channel 9 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC9_DZ, 0.0f); - /** * RC channel 10 minimum * @@ -631,17 +528,6 @@ PARAM_DEFINE_FLOAT(RC10_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC10_REV, 1.0f); -/** - * RC channel 10 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC10_DZ, 0.0f); - /** * RC channel 11 minimum * @@ -691,17 +577,6 @@ PARAM_DEFINE_FLOAT(RC11_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC11_REV, 1.0f); -/** - * RC channel 11 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC11_DZ, 0.0f); - /** * RC channel 12 minimum * @@ -751,17 +626,6 @@ PARAM_DEFINE_FLOAT(RC12_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC12_REV, 1.0f); -/** - * RC channel 12 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC12_DZ, 0.0f); - /** * RC channel 13 minimum * @@ -811,17 +675,6 @@ PARAM_DEFINE_FLOAT(RC13_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC13_REV, 1.0f); -/** - * RC channel 13 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC13_DZ, 0.0f); - /** * RC channel 14 minimum * @@ -871,17 +724,6 @@ PARAM_DEFINE_FLOAT(RC14_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC14_REV, 1.0f); -/** - * RC channel 14 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC14_DZ, 0.0f); - /** * RC channel 15 minimum * @@ -931,17 +773,6 @@ PARAM_DEFINE_FLOAT(RC15_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC15_REV, 1.0f); -/** - * RC channel 15 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC15_DZ, 0.0f); - /** * RC channel 16 minimum * @@ -991,17 +822,6 @@ PARAM_DEFINE_FLOAT(RC16_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC16_REV, 1.0f); -/** - * RC channel 16 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC16_DZ, 0.0f); - /** * RC channel 17 minimum * @@ -1051,17 +871,6 @@ PARAM_DEFINE_FLOAT(RC17_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC17_REV, 1.0f); -/** - * RC channel 17 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC17_DZ, 0.0f); - /** * RC channel 18 minimum * @@ -1111,17 +920,6 @@ PARAM_DEFINE_FLOAT(RC18_MAX, 2000); */ PARAM_DEFINE_FLOAT(RC18_REV, 1.0f); -/** - * RC channel 18 dead zone - * - * The +- range of this value around the trim value will be considered as zero. - * - * @min 0.0 - * @max 100.0 - * @group Radio Calibration - */ -PARAM_DEFINE_FLOAT(RC18_DZ, 0.0f); - /** * RC channel count * diff --git a/src/modules/rc_update/rc_update.cpp b/src/modules/rc_update/rc_update.cpp index 7c8960a357..52d65bf915 100644 --- a/src/modules/rc_update/rc_update.cpp +++ b/src/modules/rc_update/rc_update.cpp @@ -87,10 +87,6 @@ RCUpdate::RCUpdate() : /* channel reverse */ snprintf(nbuf, sizeof(nbuf), "RC%d_REV", i + 1); _parameter_handles.rev[i] = param_find(nbuf); - - /* channel deadzone */ - snprintf(nbuf, sizeof(nbuf), "RC%d_DZ", i + 1); - _parameter_handles.dz[i] = param_find(nbuf); } // RC to parameter mapping for changing parameters with RC @@ -145,10 +141,6 @@ void RCUpdate::updateParams() float rev = 0.f; param_get(_parameter_handles.rev[i], &rev); _parameters.rev[i] = (rev < 0.f); - - float dz = 0.f; - param_get(_parameter_handles.dz[i], &dz); - _parameters.dz[i] = dz; } for (int i = 0; i < rc_parameter_map_s::RC_PARAM_MAP_NCHAN; i++) { @@ -449,12 +441,9 @@ void RCUpdate::Run() const float min = _parameters.min[i]; const float trim = _parameters.trim[i]; const float max = _parameters.max[i]; - const float dz = _parameters.dz[i]; // piecewise linear function to apply RC calibration - _rc.channels[i] = math::interpolateNXY(value, - {min, trim - dz, trim + dz, max}, - {-1.f, 0.f, 0.f, 1.f}); + _rc.channels[i] = math::interpolateNXY(value, {min, trim, max}, {-1.f, 0.f, 1.f}); if (_parameters.rev[i]) { _rc.channels[i] = -_rc.channels[i]; @@ -725,11 +714,11 @@ int RCUpdate::print_status() PX4_INFO_RAW("Running\n"); if (_channel_count_max > 0) { - PX4_INFO_RAW(" # MIN MAX TRIM DZ REV\n"); + PX4_INFO_RAW(" # MIN MAX TRIM REV\n"); for (int i = 0; i < _channel_count_max; i++) { - PX4_INFO_RAW("%2d %4d %4d %4d %3d %3d\n", i, _parameters.min[i], _parameters.max[i], _parameters.trim[i], - _parameters.dz[i], _parameters.rev[i]); + PX4_INFO_RAW("%2d %4d %4d %4d %3d\n", + i, _parameters.min[i], _parameters.max[i], _parameters.trim[i], _parameters.rev[i]); } } diff --git a/src/modules/rc_update/rc_update.h b/src/modules/rc_update/rc_update.h index 812408debe..2ebdebb4c0 100644 --- a/src/modules/rc_update/rc_update.h +++ b/src/modules/rc_update/rc_update.h @@ -148,7 +148,6 @@ protected: uint16_t min[RC_MAX_CHAN_COUNT]; uint16_t trim[RC_MAX_CHAN_COUNT]; uint16_t max[RC_MAX_CHAN_COUNT]; - uint16_t dz[RC_MAX_CHAN_COUNT]; bool rev[RC_MAX_CHAN_COUNT]; int32_t rc_map_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN]; @@ -159,7 +158,6 @@ protected: param_t trim[RC_MAX_CHAN_COUNT]; param_t max[RC_MAX_CHAN_COUNT]; param_t rev[RC_MAX_CHAN_COUNT]; - param_t dz[RC_MAX_CHAN_COUNT]; param_t rc_map_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN]; param_t rc_param[rc_parameter_map_s::RC_PARAM_MAP_NCHAN]; /**< param handles for the parameters which are bound From 7706aae67dac477111c3ba7bb792779ce2ac7cfb Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 14 Oct 2025 17:36:48 +0200 Subject: [PATCH 177/812] mavlink_receiver: only switch outgoing MAVLink version to 2 if it was 1 before to avoid the message that comes with it being spammed. --- src/modules/mavlink/mavlink_receiver.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 2aaad09a19..49ce052c01 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -3229,7 +3229,8 @@ MavlinkReceiver::run() if (mavlink_parse_char(_mavlink.get_channel(), buf[i], &msg, &_status)) { // If we receive a complete MAVLink 2 packet, also switch the outgoing protocol version - if (!(_mavlink.get_status()->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1)) { + if (!(_mavlink.get_status()->flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) + && (_mavlink.get_status()->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1)) { PX4_INFO("Upgrade to MAVLink v2 because of incoming packet"); _mavlink.set_protocol_version(2); } From e8fbc30cf62ed64f76a6c5e2a49d2962cc2195cd Mon Sep 17 00:00:00 2001 From: Alexander Lerach Date: Wed, 8 Oct 2025 15:58:21 +0200 Subject: [PATCH 178/812] boards: add auterion v6x target --- Makefile | 2 + .../init.d/airframes/4017_nxp_hovergames | 1 + .../airframes/4020_holybro_px4vision_v1_5 | 1 + .../init.d/airframes/4041_beta75x | 1 + .../init.d/airframes/4061_atl_mantis_edu | 1 + ROMFS/px4fmu_common/init.d/airframes/4071_ifo | 1 + .../px4fmu_common/init.d/airframes/4073_ifo-s | 1 + .../init.d/airframes/4601_droneblocks_dexi_5 | 1 + .../init.d/airframes/4901_crazyflie21 | 1 + .../extras/auterion_fmu-v6s_bootloader.bin | Bin 32944 -> 32888 bytes boards/auterion/fmu-v6x/bootloader.px4board | 3 + boards/auterion/fmu-v6x/cmake/upload.cmake | 49 ++ boards/auterion/fmu-v6x/default.px4board | 101 ++++ .../extras/auterion_fmu-v6x_bootloader.bin | Bin 0 -> 46892 bytes .../fmu-v6x/extras/px4_io-v2_default.bin | Bin 0 -> 40160 bytes boards/auterion/fmu-v6x/firmware.prototype | 13 + .../auterion/fmu-v6x/flash-analysis.px4board | 1 + .../auterion/fmu-v6x/init/rc.board_defaults | 31 + boards/auterion/fmu-v6x/init/rc.board_mavlink | 10 + boards/auterion/fmu-v6x/init/rc.board_sensors | 93 +++ boards/auterion/fmu-v6x/multicopter.px4board | 13 + boards/auterion/fmu-v6x/nuttx-config/Kconfig | 17 + .../fmu-v6x/nuttx-config/bootloader/defconfig | 95 +++ .../fmu-v6x/nuttx-config/include/board.h | 566 ++++++++++++++++++ .../nuttx-config/include/board_dma_map.h | 87 +++ .../fmu-v6x/nuttx-config/nsh/defconfig | 332 ++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 215 +++++++ .../scripts/flash-analysis-script.ld | 6 + .../fmu-v6x/nuttx-config/scripts/script.ld | 229 +++++++ .../fmu-v6x/performance-test.px4board | 31 + boards/auterion/fmu-v6x/rover.px4board | 17 + boards/auterion/fmu-v6x/spacecraft.px4board | 21 + boards/auterion/fmu-v6x/src/CMakeLists.txt | 76 +++ boards/auterion/fmu-v6x/src/board_config.h | 520 ++++++++++++++++ boards/auterion/fmu-v6x/src/bootloader_main.c | 62 ++ boards/auterion/fmu-v6x/src/can.c | 142 +++++ boards/auterion/fmu-v6x/src/hw_config.h | 128 ++++ boards/auterion/fmu-v6x/src/i2c.cpp | 41 ++ boards/auterion/fmu-v6x/src/init.cpp | 299 +++++++++ boards/auterion/fmu-v6x/src/led.c | 235 ++++++++ boards/auterion/fmu-v6x/src/mtd.cpp | 136 +++++ boards/auterion/fmu-v6x/src/sdio.c | 177 ++++++ boards/auterion/fmu-v6x/src/spi.cpp | 62 ++ boards/auterion/fmu-v6x/src/timer_config.cpp | 80 +++ boards/auterion/fmu-v6x/src/usb.c | 105 ++++ boards/auterion/fmu-v6x/uuv.px4board | 23 + boards/auterion/fmu-v6x/zenoh.px4board | 4 + boards/px4/fmu-v6x/default.px4board | 2 - boards/px4/fmu-v6x/init/rc.board_defaults | 38 +- boards/px4/fmu-v6x/init/rc.board_mavlink | 13 - boards/px4/fmu-v6x/init/rc.board_sensors | 55 +- boards/px4/fmu-v6x/nuttx-config/nsh/defconfig | 1 - boards/px4/fmu-v6x/src/CMakeLists.txt | 1 - boards/px4/fmu-v6x/src/board_config.h | 5 - boards/px4/fmu-v6x/src/init.cpp | 8 - boards/px4/fmu-v6xrt/default.px4board | 1 - boards/px4/fmu-v6xrt/init/rc.board_sensors | 16 +- 57 files changed, 4058 insertions(+), 112 deletions(-) create mode 100644 boards/auterion/fmu-v6x/bootloader.px4board create mode 100644 boards/auterion/fmu-v6x/cmake/upload.cmake create mode 100644 boards/auterion/fmu-v6x/default.px4board create mode 100755 boards/auterion/fmu-v6x/extras/auterion_fmu-v6x_bootloader.bin create mode 100755 boards/auterion/fmu-v6x/extras/px4_io-v2_default.bin create mode 100644 boards/auterion/fmu-v6x/firmware.prototype create mode 100644 boards/auterion/fmu-v6x/flash-analysis.px4board create mode 100644 boards/auterion/fmu-v6x/init/rc.board_defaults create mode 100644 boards/auterion/fmu-v6x/init/rc.board_mavlink create mode 100644 boards/auterion/fmu-v6x/init/rc.board_sensors create mode 100644 boards/auterion/fmu-v6x/multicopter.px4board create mode 100644 boards/auterion/fmu-v6x/nuttx-config/Kconfig create mode 100644 boards/auterion/fmu-v6x/nuttx-config/bootloader/defconfig create mode 100644 boards/auterion/fmu-v6x/nuttx-config/include/board.h create mode 100644 boards/auterion/fmu-v6x/nuttx-config/include/board_dma_map.h create mode 100644 boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig create mode 100644 boards/auterion/fmu-v6x/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/auterion/fmu-v6x/nuttx-config/scripts/flash-analysis-script.ld create mode 100644 boards/auterion/fmu-v6x/nuttx-config/scripts/script.ld create mode 100644 boards/auterion/fmu-v6x/performance-test.px4board create mode 100644 boards/auterion/fmu-v6x/rover.px4board create mode 100644 boards/auterion/fmu-v6x/spacecraft.px4board create mode 100644 boards/auterion/fmu-v6x/src/CMakeLists.txt create mode 100644 boards/auterion/fmu-v6x/src/board_config.h create mode 100644 boards/auterion/fmu-v6x/src/bootloader_main.c create mode 100644 boards/auterion/fmu-v6x/src/can.c create mode 100644 boards/auterion/fmu-v6x/src/hw_config.h create mode 100644 boards/auterion/fmu-v6x/src/i2c.cpp create mode 100644 boards/auterion/fmu-v6x/src/init.cpp create mode 100644 boards/auterion/fmu-v6x/src/led.c create mode 100644 boards/auterion/fmu-v6x/src/mtd.cpp create mode 100644 boards/auterion/fmu-v6x/src/sdio.c create mode 100644 boards/auterion/fmu-v6x/src/spi.cpp create mode 100644 boards/auterion/fmu-v6x/src/timer_config.cpp create mode 100644 boards/auterion/fmu-v6x/src/usb.c create mode 100644 boards/auterion/fmu-v6x/uuv.px4board create mode 100644 boards/auterion/fmu-v6x/zenoh.px4board delete mode 100644 boards/px4/fmu-v6x/init/rc.board_mavlink diff --git a/Makefile b/Makefile index 996ffd47e5..80e0ee1f64 100644 --- a/Makefile +++ b/Makefile @@ -325,6 +325,8 @@ bootloaders_update: \ ark_fmu-v6x_bootloader \ ark_fpv_bootloader \ ark_pi6x_bootloader \ + auterion_fmu-v6s_bootloader \ + auterion_fmu-v6x_bootloader \ cuav_nora_bootloader \ cuav_x7pro_bootloader \ cuav_7-nano_bootloader \ diff --git a/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames b/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames index 150c7410d1..7830e5487e 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames +++ b/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames @@ -9,6 +9,7 @@ # @board px4_fmu-v5x exclude # @board auterion_fmu-v6s exclude # @board ark_fmu-v6x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # @board bitcraze_crazyflie exclude # diff --git a/ROMFS/px4fmu_common/init.d/airframes/4020_holybro_px4vision_v1_5 b/ROMFS/px4fmu_common/init.d/airframes/4020_holybro_px4vision_v1_5 index c1b3c9a9ba..bc9ff44679 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4020_holybro_px4vision_v1_5 +++ b/ROMFS/px4fmu_common/init.d/airframes/4020_holybro_px4vision_v1_5 @@ -7,6 +7,7 @@ # # @board px4_fmu-v2 exclude # @board bitcraze_crazyflie exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # diff --git a/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x b/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x index 0e9b9df654..5dbd5ea3ee 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x +++ b/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x @@ -15,6 +15,7 @@ # @board px4_fmu-v5x exclude # @board auterion_fmu-v6s exclude # @board ark_fmu-v6x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # @board px4_fmu-v6xrt exclude # @board bitcraze_crazyflie exclude diff --git a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu index fe40b95aa0..0d8ddaf2d8 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu +++ b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu @@ -10,6 +10,7 @@ # @board cuav_x7pro exclude # @board px4_fmu-v4pro exclude # @board px4_fmu-v5x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # diff --git a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo index 141ca861c4..25353b2a4c 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo +++ b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo @@ -12,6 +12,7 @@ # @board px4_fmu-v4pro exclude # @board px4_fmu-v5 exclude # @board px4_fmu-v5x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # @board bitcraze_crazyflie exclude # @board cuav_x7pro exclude diff --git a/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s b/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s index 276e1b45db..ecc7ed5078 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s +++ b/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s @@ -10,6 +10,7 @@ # @board px4_fmu-v4pro exclude # @board px4_fmu-v5 exclude # @board px4_fmu-v5x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # @board bitcraze_crazyflie exclude # @board cuav_x7pro exclude diff --git a/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 b/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 index 38ffa06896..1d5b47608d 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 +++ b/ROMFS/px4fmu_common/init.d/airframes/4601_droneblocks_dexi_5 @@ -14,6 +14,7 @@ # @board px4_fmu-v4pro exclude # @board px4_fmu-v5 exclude # @board px4_fmu-v5x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # @board bitcraze_crazyflie exclude # @board diatone_mamba-f405-mk2 exclude diff --git a/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 b/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 index 85b045e84a..3a69a846af 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 +++ b/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 @@ -13,6 +13,7 @@ # @board px4_fmu-v4pro exclude # @board px4_fmu-v5 exclude # @board px4_fmu-v5x exclude +# @board auterion_fmu-v6x exclude # @board px4_fmu-v6x exclude # @board diatone_mamba-f405-mk2 exclude # diff --git a/boards/auterion/fmu-v6s/extras/auterion_fmu-v6s_bootloader.bin b/boards/auterion/fmu-v6s/extras/auterion_fmu-v6s_bootloader.bin index ab4a99d348b866fbab23f634dc01159b2422e2ea..2c79c4b1bab5367e36ca229181ada79f098e7877 100755 GIT binary patch delta 21450 zcmag`3wRXO*#M5eXJ&SHav{4R0Ya{`y9sWxL>3YxfXHSyISC1xaM7aFvJlk4SV%?N zh;4TftteV4qirNrQPiS%VFT$$z!(&)mukDqrA>&GDB2+jm$PJHCcD|4-*YzDe&7H3 z|DIo-C$neHdC%=V?|ILAJF{;yqxu;1wjcE|NR;{+yEnTI%-QvlYubsa_1SgVi?+E6 zPXIBG0=YW^ynf6pqkkQQdVoWcu*-v4F@g}2omRc(ohwYvLCi;q&a!Mfxag_UI*U2ob3!#0 zT8M#h5tcbh)AclmAr(wk$!PF|y1dX5b}n^=Vd+tIdEp6l1$}?e6@~|osw)alsErge zE?3yM^r+hS!@I>5_WEXxXRIi+kO7yAPykvX(cnZ^7$*L&250@JG2%=#bdwA{;AB>) zGkynaJRZ2ru!b27LXY!300JyEbrvrM0a;F}Q0^v(J*Gl=QT6UKBjs&Aiq>KEPG7tEkCJ#U4Bgcy8NViviz8O zvizhvQ0^waWp45cdrTcDKdGKCKc=29KdD|QKc-$NKdF-P@m@&zN%gz(W9oP1C)IFy z{xLONZt5PN1^8geeV5}y02*qk(JnX+NWRj^JM`R|DfL;4PN-l@*~)}{54ZYJS$ju{ z?_vL6{a~fk|6Rx9Bk5a@`Z>Yz0g%RnEB$ExMLA_F*e?b6dRN%@;87K9$a-Fe((eP7 zu(p5~mD9UrvR(B7q==yL_bqM!;D*068mM=Df+nX8}bJJGRaBz>!u3TK~abO_V)MAnTZjNSlfpxlQ z_XxP98+yiAD7-w9xy4O5cFRcS*703lKEpyN&6dwNp>8d8gef<<5u?rI?JPaB zD`esdrt@F3A&;BAy4s!MLDt>Q3{TR)!s$t0=Ph$!>)Pl_$G_w0Ef`lQs1>wm_Eu&?Y( z+1n6?vd`s)u+RDznXji^e=Ii;&GDtoeFFphH!zU;4GfsRfq}w{Fkl*h0Xi%5A_`;b zTq&}|$ljI9hAOP9%i5t*Y}46pVvTqGmolSc}LaUyrZg+w+v<0jZbu~ z+of`Ab0k+Z2!*El^hGIx1?PHzydSaPv_-4{){K@8l1d=ist!XTkQ}vvAb!RseI6g-MhaYf;10DAY<^uRm0hM5I#_>O4JzlR zUzYApo#IW6fbE?grVRw$zPnW}TG2^c5ily(lMkba{Bn$+t^}c!>(>k2=PR6ueDYyM zH^n~RsVV2RBr{XneV%vf$%}`f=g21DZ(fY7H{ZJ5!i65vZ|MZHfbA^|sfe-GEX$ll z4s89!occKp#|Cv}dh5A)TNv_aZ1y4n-{N7&Bhj*Y^p=RrZp-yBR(lH~d1Ge=0WoCV zC}%D6l!?e*ea0dBfFZw@W=zOI?@9F&tlq9jZheX$$Ur=&KE;p72hr@rZ$8`11Ynxna&G0-|3uNAyfSG-i zP~LbDc+;kFI9+{17}mtE!&LqUW@Z}jf;2bnhH0x}7Hn9|*I(;!tFxW#@F(nDp5Kh5 zZv~;HdjpvSQ5kxYjM8t?Zc6)MWJyL!FqEF8fiynHz6toW`Z=8(&J!DmRt6UI7AqhL zNUg*gtyzB?qZKPUQ}MGRSU(cy`kxkGa3zbNJ|o z4Uq~A<#UbAivyG@;%a#Z8;^{3am7;;ig498*W24PHAJE!2O z^_27GiJDR&y^>yuZjio7&+*cxrqs{rr1`A&zymf6WJdfuH|Ipp7j|h%k|tnwpQ9V? z0kT1L=W^H-Kp5>|$jVVOrqB~r4mreQo6*$!(qsnDrIL_m?2fVC1ZNt3Dx7bivm7(PqS#f7p%M2B2pMl z5Z|;T(vulAsfb+Egs$bahzx4d>5LNo6^$;#VOjEJPM+_qz1D%qM_QtW?NrbtAaW%J zw%q|_WjB5$Yl<8zZrvpUnGw_D75m*{{eB?xV_;h$t;$@Ou}rfr5-=hQuJ@@aA4~qs zQt!i&RgtagR=NphObS}PIy)QW%#`k2V^*)ht_#{*c{>xNIY*-o+GDYWmdhiiCm;Ot(l|V+mRfg z!$suFIBI7-OncMghJD@V$#c3kL_pJHuw4p#yKNDsg59@U5cxQMQmxw8Db^3^boZ>K zbvKIoP%7efIv(}5)m$D)-^#XM9x-hh?{LeAX)7x&!soU*FvX2E3>(jFX?oyp=a!)q zHqZIQP>SxJwTN`aX;Ydq5~D)HV`IDJ(m}0Khqnt`@nl?p5s8d(c)$T1~S{C>hkrc>B5{Gvtf?TW3zz27lHh8^qRbZr07PZ&66{7{;F~N zOx*>YhCedT>;L%GAe3j|WXzZ~0>j|p|QW)X#Q~RIvFU51Q4I}czD3`D6r~Bp5D3_mc`bU16zC3Ckn1z=lAl_5C z{7a|zHiJDBn3>3#GI~KyXueZ)4`jE><$pV)KXqqiViUfua{2vei7eWz7u1ff?22bz6TUAnl{HKE@m9sxuu z$7a>(FxXr{t>ej&^sO663fwe+O4G%IJ*WuHEp{$b&HE0Az<6WOt(u)$$M>EuRA{8I zsQp^UOR7V-6SKm!hwgpo*r0CixovAk5X*(C7%TC3*>hVo<=B{jA6IktA+l&xQ)1C6 ziCr=jF8%F zH2y(uRHs8~2&HC=ABkvQva?#XfGpE9ZqM~Ij-GXkOb1?4DR;YD>?yCOD1ze5 zo~^hI8!!}3!j(A7@{j|O!GQpZEu()#FPdwujab7`FZ&wQeY=Ho}36V!MY1&jv;eDD9 zqZb9thY*iQl~z?1kT;OK;1nf7I4(OL1zy^oo5dm`NKa0^T~`@X<&)AkQ}fUcNt;@U zPD+*8GmSQF{7A?$a~OzM+MGS5vhQ$9rye(iceEgKG{WH{ejszBx_mA{_ismRxTTv5 zO@{*>hAbSTdtq-3S-{MNk^zbk`J2?2U0psoQSwrZmbXOC%RoLl45a6u&83m!D8+sD* zhxBZ29{R1cH+R)dyCPr}uyrkvJLBU=00`g8h2n7Hc-pZrCVbQ#ozo;Y1a+dwMby7A8YsZZeE>Ug>A~ zv(Z%PPx-Uc?u!g`nQAHDMP&7%gmPA(&siFw%9pJxOF-mtmG>hn`>?5-$_|B+xuA%N zk4k}wj-o{eq34H&D>^w0p~X7NDJDc3ySUKuMA{&|R8TZ0JZkF_$|({rk7jjMbOZU* z=oML0?jH@yEj7A&Q)jNIDU%ZCaO>#!F_3@oq%>Mk@DoZSe5X&eIS~1I1Z*dJKtKZD z4c4SOQ|Cmr%*hNNMUT6I3IkQKzUw#)wc2F%GaNt=OtiKaiW}#E*;>@nyuGFv7#p15-vNIN4kWDxl6M3u1R*k2A zC;r~Gdl<2=53}5>!yNjZCpnn3h_=Y}g{>>bi0o5G5|n&(fn1&tTP7^F zif;c-5sJ{fogS;0;cpkg4ri#`gGje(6?6PM#m!=J)lQFFto9rc+iHeoX|ctHc1q7# zrrh$ldL_|fNX`+pf6+$4%3x%s(qR^6$fpsoTCm=X1crQcJ%80z|BD%t$Qo5$90NoQ*zL-Ah;S23=|n(~L39&26C`)?4@j9I~XxEMELO<5Z^;O7qC z;&DE9vD}();V2X(B{|aczJZ~Iqr-LWt@oL3!haarS^64O08S7!s z3He6rq| zkiTepylo_X>sfW{zMuH%fE;-CLqL9`{lepI68C#{izA*6xlsTz7}Mh;{_CRC)^SN@ z>xgM9gc=zKz7uEO^wl6^1+q?KcCziicZGxf37ZM6fp#*|xF}2oE~*=>z-R}MCpD&B zkH_J9u1otA%T&EFNS_quc%RTBGT8*YuAcFlI+v-lOqA_!*T8E11zi(b24r~`Q5tzf9vOsLPj{{G@E*fJj(A0`6IqX?%kBAS5C93L zZkNa8sr7&`Dw{kjJQ10iS-AQf>As?LZ}<`5S$)dMBO~lYef=`kB9!=n7y((+{ac*U z>XsUlBO*i3^N&&)gw&XbPtV~aBW#wF^!e7;FH>!ePzvOP55i6>5TjxLRhR+fe|-C| zI%fds^zFauo8ct;eMd&XO!XXOzC4ot7+4bugcK_>dSCNphFcnrjj*?52CRk#Voa*< z`BR8z=i@>_5Za+p)g4KSu%l@ac4YccQmT6>m31#^7^+ESt*2Dj&K9$g)RE#LHfh5U z3n-F0;vPz3?Vi>E7j~BIzv^4~aA5aUnA;Zu);*lWu7p!+>ULTOhLV!p-k~IR*z;is zj2Xd1_sKtW-#`k}8iSml`-Ck7O?8ywA z(@i|ZkyNe+jAkyhugXAD4JTE;yvxZ)461bqv9&|gGRc=8?|3Ysc2nt)F)x!@^AdR` zZjc)Yq&*~qb-RqLzm=J3Ju*A3Tec1X`&ELw{QLSk9_i4ONj=&HM$cl?$s^toHl43q zs+wViA6cmF3aw)z>`00$v&V!%XsMz9lmPfnhHQ(1z;|mGOr3mv0~sg;i(ygIYNPPl z>bO!FHCT;;bu~S&;>wYO+EN4b-7s!5`e_W2<`^RDViW4K#H_B=`W!Jw+}H&I$C2CP z2^)c6A6@7!r!i#T=$A<(BvaTHnu*XoPcr*KxByxjtK* z<^N1=5lX~~8?rr=UE4)I)B;mCbf2fTs5cJMHb1+r^jCClX->sDoQ~VOsCxE!bWhWs z=6%v`+p?6GqgF9%0}w_%DWT$0v{;%^JPB=)s*9~tX&dz5r>xo6EcnlD>*vrZAPv&y z;z@a5Wt$0$(yMfJ+gx0bpVN(f-KZ)gyH(CE?JKz{-Q9fBa-_K! zpPZjnCEN$(CTX-}P8sx2W?<@kY(0llaHK1zZld^@D>sWTh?a2ggBfnC$F*J( zSC0TIc}(4jlSos((Z-G2rf%&5>3ppD@<_T5tO<+DmT`*<)hd^*&l8IXLOO!Dsh;2e zbjtdTJUd*&?vGv@S!*xrLuEx_s9edL2|~B8FZSHNe%K?_r#N@0OHHV_H0TZ=Y1*MK zYfLI-0(@ynaM6Bu*tcxSPu3slNby+RcdXx`E;l_aE^-xxowuVfEGc&X%yawtw?uQ; z`Lnk?OV?+3sI7x^A02V&ti;GxhM_Wt%SpAnKb4tczQ-N*HT_NQP?wtgR|humJ=9t7 zcga{wDK7898EVsj28>u?e?}cdv6^K^ZT)-f7ka z{8u-7a{?Pk7F2Za-2c3~)FJur%3tPMR(TiG5cX|+UR`d=cDsf)PjnFn^O)z=p8_e3 zfgsD-n8?TdJ4A*!SciR5aAMfEkqb-|!{ANrVXVmdxVqG_MLas<%XnN}?f`OQY}Y+D ztSMvhvk5-&7unSLc=Pk>k0GY4kAa1z(i66bm=f-(=zOACzo-PikSM>PaX71MJpDk7 zii2I!t2dgbd@_1Kz0HxW*Pl9|E_USTnNw60dR*$e(K;))ey58Knk+fBG39J@*LqF4 zBRa5NQ+rR%{u(J+Gx5wlKvZ?B?XTQ1C&EjsuA$D4oxYGQ_IiZ=DXG>*Y9+3!DO6NYcj`_ zC!%ZCXNXoZfz9yHah#0~tnWVG;?$JWhkxkD+nKUR#6Z%=z?yVxRW80=<#Oiwf0FAc z6Y;ZZk^{&rtqh}betIa#?Q7|FZvy_nqrlT+HW?$#)>6CpQkALC^6=fzbK53qmg7d$ zBCU2z_QGm$?^M1>phxaBN>#f;Cd28R^eWT5V}odlQ#JkgRq-~@t`Lu$DnEU9h-Yr~ zeCu(m{Er(|{$>GxE0(#Jd4Q}^1>AjJbply>5QU6vOXq7>UweqQ*bsj0!PKfO4CXxi zT{e65wVwmQQ5Hi;V5Dn~8*l!+OS@pIpVOHu>hNMedJD+uQPlQ>VnNM@apj3Iu%-6f za9pubH&Z_nuE;=DFVD=Zf>3u$4dsc{fX9o}d^JgRNCzdPAPG{rXL2=XKPI&pYZfmsoc%9VxcBrwYx|(V+Wp&HD$5(fjm+8O3uZ9lPfwWU`=_2 z5~-i^VIUb1N~GEazB8u$QM#wBbtVSU=4Zrg57Tv*2du28r6yTqF^Eh3wf;KsF;@ct zM&DEKNykW>>R~)mT6x{A6`gJ|73)O4u5ZfsQD$ZqHq;yHj$}0uU@Jp_SaKvPc*YfE z_+sb$g)SpFT}GIIC*yHXNm_*3gm%@$l)p=Fl;7{Qu;SCs4EN3+)&l~SxLaxpieKqL ziG1n*aNr@?aVetBTBAs1bnVCsKa|AXC+o z>iNc^#KE^ub>NonPPL%Q(QaT*I&i6|#~~S+sWnTdg6-<*tFj(nko>c!OnF^>VBMJi z(z*jKLy(q#pk7$lyzV>c?CePe^GCrp;q(hCcDM<{KA~cVro0>H#I-I8`HGZrQ`wK2 zV_;)XQ{RlHZ2ge$uINM-4uiSep(!_N4Mdv_RxVTl-!~l_tSJL>v&w}Yhhys2Mj$t- zTqpp?)RT?W=L6)%gH*>Zcf=H@^wLdbUQPKQjS|oPv2*gcSv{sS#lRNnH+9FAd58H< zFjKDsvhWVH+3nGkf5rbhnvxIsZi+laE|2N(IkC;f2CYw{GV5d1zQXGrIHuejWAhEC zH6=67ik$sw;2HZ!V5JM}7lX+9eX?gT(Jdl>msZW0vSKs>Hr?rQ)qSKJ&9^>g>V}f4 zfQcX@i{}N8u<=MK2rP?U){5=2=x{C0jDJ@5ct+unte|$t=jkZk203 zfGwCCX49lE=S=_6d&7)@pZDn?{NB>-%otAS087is=71d{Ut;j|drfxLvYLIEUB(18L?R9jf)U9JhZsae47_qWx6Z8Xr-T#N;r zbAR{w7HQkuhtb;-nm2DsawCo@Pe*n6>-(Xof%sBT`%5m*aq0ef^Su9(CzOl^Gr~S^ zR!_1eEJNwsuX|PA0ro|KUKLE~#EEKxmq*f{8aJv_g_0W8*E9=wRphDB9qYE&tbX>j zXOlW6cKptDLvT$qG7I?s<}!h&M$)&wB_j(L%7WKgVoGt8=78;$+fG9%-?M?RIywzx zZeQ0{(}?3rNVQ!zol?N2M5DCqNqGZl)SZ_%kYwHWGR5{5@h9u_p-i0($CS9Va(*@1 zFTFZ{uD3!Dp<3M?D%bE!f0Ou{INzD!-tDRPqql^0nzCh#`gWMFg>`Xdv-+NED9G+3 z-KB%7dyANcC*dEj<3icI6UUUD5kr1;Ka|!5xKITH)}<=93QA`Mx#2C0v5X7lCUL`C z*nc$D;*G0gN@wKUwgaOUAxFCN=BX>|)LI-PBr$Q##z{YoIu^YH4+ z(pNX%o|_%v@<~6neJ{d(Y{OfKlW%VRY{Zwf@_y--1r}tGRxijXh{cl4L>?BWs3@n` zz@C~=oE*$HB%gF)$}ZxPw7`rmN}UUCKrcvV7EICkM|JtLqz&dNlIa%P&CiWCHR~{# zSKcq+wi+mvPmf!K(i))jpDJumJ5ABFT(eQ{&XWz{O)ZFAROgGkhm%<8p<8O#=%eHI zSQ}^xTu*0$rbHrOslZ$)OP`K4Wh4R?2d1e@k#YEJ(3JBLFjrtiPDH>=4QPLlSg{R{ zZ-;TMrnEcvS5p4MeDuAvU||6|CEdNStn}5rf4=JS-V|_NNh*8Ubz8uB#ZdOLD>)%f zN&{^*rqER5*8#8rdC|8`>RvbpZIG@m{Oc01{XRg;7KYcq&kjH-L%mec(%mG2ef0D_ zo+oJ-L|Kz(i%bPmDy+WjN(ub=>SphSAe5dD*u~wRX7QY7ShTMGnGB_8rS!_%Gh#}y zYHdY!eIJ@{ZJ~_xQ|Xb)rb-TH5Cm)>x$1W=6r`3c+7EXorIod_fowY)Kr=&fvT#K< z2t;n_gdz^#h`-%teP*1L(xp7tl&SA_T=Y}Xhe~bU5C6*zWU1a|HcWdQ&HkI*B5icp z(-+3)_~&Ae2&5@t#hxR*@45kbrGL7L8STOjcV=D-4IUF(YD}G(n8)cD$PSHqf_WTQ zo{(m`^Sn=M1}ysDX!QwkWqZ6vErOOVv|xAZUYG7n1&%8}k8dE8LGAvLS_E-rL!8KH z_Iob5_dd^?Eg(=U-xRnk(*@R)7Y?eO9Dbq|EifGSh;d~_d|ZSZQ~u|}_n~E4lh}Kw zqsnv(5Nl*|$Yi`0Z1Re|cgB^fINke7!x`1F>nWU%(GCL!VvOnVnDSkm%U{@kCcnf&y=ARj_0Z?{6>UDYFB^C1S&!7SFe{I33HF*(E~qn!;yf8~~`$&RBc zY;P86>Mqat? zHgAc8Ewdk{Pw3y>cpJU@8lnR{nP~#SI)=(8+rg_uX_a2aS*T9>A6$%jq;K#tFVo6mafAVN}Mn&M1ilT58lzR^)JY z>x>dUP*RuaC|LyL-FVYFu;YN$W2>JkT18sw3PRD1xUwr5Zy*RPtB(!B%wvPhJ!T4&4`@l?_NXB2w z6wUiJ7DMX_{})d&#K^EEeBfzu0tWN9ayFidKa;Z){~&yl@Xmdj(0Px^&_m~a_a=#{ z{jqmW=Omnp@ARX$G{q4I8`ocg%^0<5${CF+M3gN?66-f~-Gvob9*X^U{ir`#pT8An z;sShk|HLjJ<|v1m8>fD~*!sG-(OprNTg8P66W-K&Jx!~vYhG8Ye8&d$)>P}`D)u^H zhBF97w(CA%^cGcgF2r>Cd_QV$6L9f3Bwyf36CZG3C@KE%`^> z>z6-Qb1O&Wn>`=UeWCkGE*%`HG~hJ69p_<9DM;)v^mZk#z?$;wIG3N)kJ_Q|^i$*E zvWPi4$lY^#v!+asUw340rqX(&UsF(Am(TU@ehQWC-mEFPaT~7a*5PPEc>c_a z+5d$Bo!Tj`@uw38QUd)V*i(BpkW>Icx~Z<#`06N^KeeBEWl3W6N2F)#rcPZl3N{X> zp9X6M-s{nnXElAB=#ML3Nj-J$yuA@w-avF5b?Z*zzLlxy`I~)Imjm*yR8VhDSv1Dw zGpCt7nzBl&uPPkJgc>3ub92=et&c5qVw1Snv#m>0$e4h&LgiHaOF79pD05a>W~|@Kto59%vwkBR ztY_t&PoY^mHxEj;E-olD1?}r{n%!McNSX7yaR-homquwMCk@MKtKsk!d6&rhHRY8! zC6$5ELFv`S?y^^_*{@;xNdH5gkZfN^>B4q>dZ-_jUzRz1S$@@ZsOMcV6Zfioqo&*; zO}RBMsW(9B=eGDsX~C`4_L5Q2Gokh`gN%;qSo8=X-Kj!cd2p1)jefKp3U!`6Vw*=( zbke)Gno}ZCES^+j?gH_UUs6p+(tr6(b!y)d@#r9!mvk-jAYt+^Sc~10{flfoAItJYaY#<_ zEb}mytMW2Y``38b*Jsi zWrw=s#*~*-8qp+GHDnh5L8YO0Fn#0#Ac8Fkul{xl?JOg#$}ByW#aC&T_G^e3iPQQaG^pzzYeS) zP3co%z?XGaZ9S4xM@=)AqNxax^)V|(cuJiUk17As1gtm5l$)bemS1we`n>vM6Ict1 zcdt$FrF&rSsL%hr`eP52{v~kkr*@BZeY58yS#PHFWQkJVkgTVymepUp?&|x&-eX<@ zJhlH&?pK{9wDSIUToA12M&&W(V*Hx4Vd*5V0q?*Qu(^vGS=ENPl74VjS4`>98VIDU zpn1Mq=!bcBc~4M4K zvHJGoyN6R*dhjj_?#0svUUo%~x94==;20VRZfU0g&G&)Q>a*)6Ih0mhV{@l$V~j5C*9wtdQ*ijJQnd~ zS9X=fb7SAN>{qkiY_y8?9(O`hEOWa(6*#7_8hxtqyQ>$5AAWyNh-ZrN3LI6cqd%pt zuVlZx6F1@aWQ*7&x~k}10E?%I4#YwA%?vsa#|QFwn;CAm=btidFA!g1!8EZ#+k(Ni zFkJh7F{X`2m8sFQ}g_ zkF}+S8u@rU(_fp9Y|r#iL16=V0$OU)4zQi<+e=k0hkA!~Dnmn?huM8CHKg;|eVKRy zHehBCExSKv!Nr)_17wP-dl}tCHKs!`4tx9v&+=mZ9w3!5w6i#o(yKRnChQ}L=;w%R z=!6|$NlB$r>R^2IV#f@ol!mernW*c5O}<(*bqQvjARuBjAr-Ywwl3nl8Sci z%smt;GBP`^1mK2S@Iibqw9r`FdnjZ#&I_1&4~1$4V@2Rl$ZDJ)I20-|t_Ws@ecqKS zH@_}m9Xj_5!@!|Xsj(z*DC96Yg0%$kOnZik_A(M(``+N&p=y?~!<9eyq|>+OdSCXT znYCeG?dKg}d1auMFnlfH_&&Lo@ccjIT4Lf)$Oo^2xA6GeAqU&vkz_yEOFL{J$xL!j zE%EV8)G&vM>Tl|i!TzU2PCovLtCno#|12L0-Dq@@pKqZxoaE6hwP9cDUinaHlhGJB z6ne;*ni)70y5Fb|+QL4uAhK1h4GUts^ynRV=o#t7JMzrGk`IMijGKeDuyDN`T9e6H zcA4Etj&1J4uStV<OG+ z=i{9?TSYmQU6*rWS#J$AkkaHYeb{xFwYd})= z@odb$r7KIRLN8ABXQ(Jo(yyqi8_5Q17D+M|1oLs`0D2M4{k#MH?h6^Uugd?I3^#l& zXAzSzs|S_IvS1c4C!t%m*Kq9?5pKK|%&VdlpbK{3+5u_%ipkzkfNcl+iqrO?;Z2Xa z_6{dAoP^qwL)tv<#htF3dicGL8%|^~A;eVlta_w5_vva@vWnAA(@yk(Lm_P;8@$m> z$IiZVqB=SFl3L`LZMXI6f)s5T#AM`qX5N5iTgADULe0U02>-K+X!ero?(}k80K}!!v0FMO25ldVfJklRLg4JX5@h)>N4`@CPNoDawcK086lHPr=?rz6ghgTAUOCMMdE zGQ=>Z5;kZj=_v(~ZINtZG6LD}<3kk;#n#m6juI!??JEf%sVgC-WLi5rv3)vx*#sH& zftOv*k-zvxyxHt9Zy4!VnX@XgCHnF}AI=Jc_fC~dX&4&#*&iuy+VEl^D-0V_dYmIi zW;#cXq(g_Z<2jkmE${!|+=xEqP-um*AhIo56L>qcfj!-kR8rTQWUo!g-Ait$si~>S zs;Q~S3d7HSk`m&Q`c(iF0P{C;R@m1Rq1`p1ps(Yqe5B)_vW-mUldT1jtx<{mBywAk$8Hv0Ka*4LguXEuz02dtpGD_2Y8yrUBmixqJ{Wklpw+ zUMjnBqnsV~HJ~6Wg8`TFomGG;;_~9jL+c+D{Kh+!H+#d+z4OXJtQ8&O$y)$d(e=DHu+l|%)N#p> z^2)`6M-N>3G%*OSzvB}3D4OlNWJocDxRkT%L)*`)5A9lV!IT0dP1`_Nb}NSM{W&mK^U0%ieejQ$hp^cgk&cz*$B^V~}NKuio4cFpi3s`~l#y8`q@xP^+s|r>)e+~TB zUjyIzE8xNRm)C#&EDIH#M@1d3TK8S{^DbLYCWh(BXJDNLXH`X%4Y6UdWF45TRl}a( za_VR`bRx^Ms=+iNWI#01V_YPW-dUBK)U*ot*{gv6ND8jX@xDq^tAM8>6!jy=6g-9; zF{N7Nu*qLcfDNT#&oKRX^O1v z3JL5A*NRHMdn0uXz6V8X1x@MKz-H)2v-K)U;YzOtQ9B4$53{eOTf4v}I;KNeewgYu zv>Q`r`eLhy%JKqhL}UF<*VH~^eY?nppozT-WjkHz#}P58Ku&1jB~zk6&S*g1NQ78V zPI&ccF!HH`rfvX+*EGbx4zy9QrYv5rS_O-rKGD1?`Yhw@;h?@gr?sqWw`lER1VnbK zv#h&4G@y`9Zf!agGWETl(;}3N1zT!p9+eQ^uYYbI6nXXdta{|JycYI_v+8HB^{TuR z$U|D1{|gm7XVnjOG!Sjh7b@TQlnRYVK;*~jH2-N89AF1>-(w(X%B>o=oofgCm3~@& zv&yxb=NH(|_oCO9s#XF$-D`k9u?G0rYk>Ez{_p?YO~89;Mzjg|&b7dwTMNAP9^iN1 z1AO&8z;C<b`+|uQ0P?LyeT2JR_w=&uP)M(~KBa<_mA+7UC)<8^-FTB3 zt$Ytm%jmkRKBqOKrSi%|mND!1ysKt8H05I4Bhz7g6{o{EvYBnC3JdF%&dStnMCQ!S zS|aBb*)TU7NT$Y__1pD(G-Y3WdTBWLy^M+;l~>?moDxDQKrY3fmIYi71T^Guk|mqD z@@M5)f~MS;7)Zhr>tHJi_>f82K`e%qB9{7j%x zz;sSOlKf3mymVkZ`*dPbUky^P$4zl=JJ$xbBUct|=GxGUuoI~$1R(hT`pu z)93#9N|m#3cR2~OnJe#2VC%+2%jV5cv=_Sve%Qj4L(wg<2cYmBfWk%-6kaEFZ{dWl zM{;jY#42oyKUJ^azEV8gbym&&I2-e3*9ZWbE07(HLin;Egxfs=F@SGqDH95!vc)QA z-+$HT9SrK<0t@x0qgjvC(rZjyNq~($K%bE3izEZRHY09-2 zow$khrpXofs0>!!9-X8q|BQjnNj~<`Mg2TRvGjpY*9N3E{=?#&j{WoBKR_QzK<`aJ zcO;i<}YrprCj{MTPUOJ+sF|bt!8p44VAfLvz;D+$= z79bzTZm4gso*SH2-{!h0cvfxOMbYbG2@PZk8hBY z81X-vJ0VE-m3|Ln9^Y5hb1?|i5kj9^V^6xy1$yPm zD-+B9yCw5uU}dG}z8{x38dIULd6RVL-dyj?V>yfT7|83RI$W_oYY}bYcITIaU0oz z4;sSXlmKKF?wqf zjww(6AMeD!65a{wSGsiFFEOV4?SJ_tk}Wg_3Jz}Uq*p4?_U-%WjnMB@)SlN`T8aYp z(uqMDW;!e3?Eq4wmX;cW`$Evb_l+rU#Vl6V(?DRdlO2Gf3-V~d=~~`p8lZlpF=eN; zP0U$E&%x3`;(lTu4J6<&+77mc0PW^Y6}1<%md-!{`;4iHZfuxFn^mj2{EX9M%7z#e zPPVe1pYLDjN7QOC{g8|6VMAIO6=2FdmI1iodkL+}^ERj}{8iO#FWYVkzF3`hdQ7Q~ z(ObK8c%?Ir2iLmb#$Zsu<9AHBsIGiGdiIPA#a{(eaY%0IWbg!>D(>mBwmR&E!KT)G zb6IkhU18^fCiAXVAbG0LRgQU!2~YR5bTj29%cyL!B?Yam4#6G{Hnom}Uk)k5sU!!D${U7N9yH>_O-e$4}czddZRA&p^{9 zd-IZ&2~0VGlpUPE4(xvqtXv27F9Yap=atkYREGpxpuc-G)lugAk~)Oob2;t6FFFnH zqPK2Wxn_7Fro2AJ0G$hqtOj|)L=5e*45sMK&e3BH%1 zXZt34DQVoqJyV+dz#Q~X>1PjQ_s%>C6Mg`OkE{8{$)cI>`MEi0%K>(=L3xLlS<9y=j=kMhy14;Pd#I>W;``S3G?# z|HmPL{ex48up_AvW~{*dyt82__qKw_GuQqn8V^}h)1v9Wa1R;WD5@uIuH?SlVU|T9 zZH|vj+T7-HUYWR=ncGyAll^+f{%D+}MNMT@Lu?g9_1E4^Kyw^~v@#z7@8&mM&MPtB z+A5~PIfR_A=YToSf6@uoPX@tF<43l+bbS;2p9}&5Gmo#z`y*RIP>h57UCfEcTyW*8 z@A2$=hgk**Q!xF|$0vhO^Q{aeP9phU9ZqE%hH`5PBG1H;d4E*7W{6I9SX13Y;7&^n z-ODG&t`BJy%<(oCTnYFv9v`+Ii(M-+Lh@t*L7Fa8lCi9bHi}0?~{YtA>)Q*aR}i z2gQaohj{!=*S&qr{Iyl?p)}{~IlH3FzYn-JVn1Gbq9Jg%|KKpotQ}6`xQIcqM9@fq z`%C91gI;(D%!}oZLjn>aD6!hpA}I8GXPNs4#QDcDF?nig<&eG-qG{KD>*69zn0Ad2 zgtUs%|<_es#=+ihoJH% zuRIrD{C5^+WK#X^@ehX?_TJ%CJ*x2IH)V`3$SiJ?o%n?O5BzJH(nyWW;|Vftpj4*X zL`ElA(-wn-B#@x}Q+rAuYFlf8_D1(zmSyfX*Yk<}Pe1M;;HdIt)Z`!Md*gQqzLzDj zCCwX%lnPPhtB6~ODqlp{ditdoU*S=;w~$6B({JtYotyyV;HbWy9<}}A3OA59MuD74 z_@saw?t&gFaM93$6Qe*5kJ2M?*C@RtM-_(Wy0i<%#Mg?bGvJ4B87(zLPl4sAS2ZO* zZDb*PmRiCl3oX|D=i^6~urHC*QbPwqKa<0EHW2Utxj)iCkY~JuwTEce;plit-Tx}7 zIs}9}OuuGwROKhM)EKYxL?_o$xK5PUtecauHv%2OY@ zbU{>@TBM6|Wp|6Yn<}rc>`s>uaCxsFcBd;p;7VlV1}YQpe9v8lu6(p01t(WYt|`YS zsc6HB++TN1FM7B^wS3m(7V#J4;Bb7MSKJyL+$4s6tz+1 zg)UufRN0ZpWokd~kiL8{i+&KuGP|~=^SHWoLHVuja0~mfx^+QWeOcWJ)mOn@^=7bF zf4!`okvvhwJ36B_s{C^F#@eXz$S4vZ+-iVNWyL_2dV}YDh&CVD6pDWhWW~$>ud7g55&O*}BhQ3xXINW0>CmfZ zm%h;T9qQNvEbkt>5UU(>1~Ao?YOJWp*%og0w8!>joX}$X!dqfDulN?D8fDU<6+HZW zm61szeqkJ3i-4*{CZ^N2K%lh9hLoA@y84y*y$7{m;A#xIL#B&3BRr+ z=wB8pKKI2Shkwpm*`T50;rW*vdwg(v*>S(c72oAAFM|6v~? z{teJDLlg98r{N1PGinTNCq?sT#h2GuJv>gg6!URHLD>z;Jyp{An{d?;SIU8s8S?a2 zhHXtJj-{5O{e~~tiS{XZRK%s-=#FKDEw8RpEoi_+`B;3Mqobo^spab9Wc!p9m!;k4 ziDgCVNg;)U6nCUezG_)c4Al$V$-0O7z zyGA!^72D!mpA>yEYT2poOBS5{s8o&9*KLOCaa!8Fvfe1P(<6oyL95bU%l+zH!*v1* zt&_M~l9nxaBwbQy@@`D6SGSk%n(t9Ju-2+LYcu_s1R9<3u0^yQOQ|3XoT}bW{_t6j zG|70BRH4B8ZKjJ3T~``XWb|JEr#aP>p=0p9X%_Adc_MOHr2m1$Mm4{9a3}DTP<~1j9Wau!4LPO~8Y4dlE zwl=l?ys71tLmPVg4jpdq4Q({fjc+%7W9<)%)@rzC+;1kW@?>2#-X#)S&3%<<@zTXQz;RXN53x3H9{*U5i-aVU%kn=?DP2g)bSrG&l ztuM+Ow}3zQEO_;1@EcnT_T4+cb6X1XGacY`QKRxA|9m%iuoL`^U_t*@C-`rRGLcR< zU_B(Fb5{?%TF$CyMv3Tgp};W-@X58CODD~iNYn)sg4JmHQ1^=p^S|S|n*^`bM)B1$ z;KvN8Vn8(mY8ddT8H+T!C<#D;m~ROh?wJoGKdnN=ItK-&m5!96Y`7F7K*QEo!OfOv s9qTrCM{5If)^`Dy#=v&~=vIL%MVU;N*^Rw`i(4a)7Ihlw3WFy4AGQh&@Bjb+ delta 21505 zcmagGeS8$v)i{3c%NW5=FnF zw(jy`MbQe3ts$u`inb`WW`pUIfN`;ETeY^kAU=UWiBcVsfZQdEJK4?dd_Q-i?ely; zpWo;A$IjllFXx_n?z!ild(OF|d6=$k4Elo?on}y@GRWB6*^OYyZc?0 zrE#e)jY}O+k7q!s22ctBrM+(8X?o8U7`nY_dsm)Z67sl9oFUJgJn6PZv=4Pa1&sa1 zgF3n~C*|A=fGR^Q6@pU+LPY@s*j00?%p} z`3;*XWh4skknfO8iF`AgDWxa!@;2tJ<@>=$N5pS~l@z%jU5SqX=%})mX&IIIRO{;PZESjMiyUQV#T1Ei^UnHMd%tU|>VzboX~Vry1Pi5C z#Ui%i2XDzjE#K2Sws={YiUsHtna4&6FtoxmUnFWU`ujW}iC{G;_t3DQDTB zwHWcR4jKUvWkQ8B!CJWGqV+@+2Tf zB2Z#l#tK0G5D{gOxLqzXNZ9h?4!~WZ-|C z418vfM?`OI#2nVcE0rH7&zy0CF7%ly&ke(D=3K7Cbea3}jsDxTQpoY%s+HPVZ+ktO%T)%I z-=t-`r$oT|rjKa{!O(S=#zkv-C=3CkxkeI;BJ%VEUl|TS6*p)U`Y+Zv5b?iT)30Bm z^TGG%VO3AIFb(||d54kw_c8D}9s_>yawIOkX-^3ke8^~P+tC9S0W;**7%S$K%wHxx zV#o8F<~M&ZY^XLa7BB2z$cwRg%LII*#E`ww>L&EMjH_=hkQmX{hRDo`bHjib;vVP3 zYN=XAwz_k6*#iuDLD@VdAN4A`r-<$^A_YyUULZs9{H9bdB7chJCH`|XL`I^B9FH;N zFELI`Zm_ih`D@%D(*FgTG4byjM`TBQLamn9K(`7$o`cdu9F(qq4ET@IfCmmrdpRgQ z&Ozy`9F)GzLFoYwN*CkfOLz#ms0O`kdAu2>09TFy6o+wIWiIbifda7sTL%h&}% zTmNP<4WcUeK1x^qoPK@!_n3W@P8mjdH+i}unE3op9s@qTX?_of3*}~_S3?PUofVJ* z1S>9+m@_az8@Ba;n1+8Yzb7y7J}0Nhe{d>Kn2HQ-4u-TUFPmnf%gRS48&Z^OCX3}q zks1u-SS+UxyqoK*60jaulfZH`A5I43m|eXfAb{WU$)n+jxQPsw!mfS28s-wif)7aP>8^SfD( z;T#CU`pex-A+WdMBg4S0k9Ik!}*O$DKnbr%G|?Y0qfyUbha?! zH}{)+^zer|S7bc1-pP<}v_!{tb3X_Zs@9W@bDNAf4HwFKc%gD3W2w7b7qHfEkvH8} zGJ=>ZYKeTALgy~2;G;vyX|nee%1?IbVNSpAJ}U-dkN?ZXIoKCU`}A;%E?`5Ky`Mb< zq)l@bAZ+%dJ?tTdJUou})7qIDhwWZeNYk4&O1$edwi9e$1@!P}92tf4v?JxUsg{a| zyd{r5<1_}?pn&XsJZ8wt8aE{1QaPwHNv`R5$&d%$67krf|P+FP- zrF2cBQVX_XhD;w~0=}@JRTl3B@!)zyu8Su4Y{uKlUoz{{ z7-G0qxb|!W8UnI}3z=nN@OxFz^lmwUjU+gyQTN;7~zSyx8Bl3CtGp)9(M{XK17&fe@ z5Vpw1pgRp2I_!_P*V8V!4uf)K%)EWF)9qvCUEIE<_{-gPToQr@zua-peYZNckEAlw z98Zp<8aAv)`TF)4x_ms=3+hksq&BMx$fgS*JbX{?BRa(=`hUA#89G#M|CO)tA@wwf9BqW4R|k} zjf?R)&3XXHxpA&&;h+^832OvW65)!{2A}e-!V9n!Bl6rhS7aEZOQm<5E6P0c120Wq z9=8n5!7CFr{-|+9-<&zz3bvqsHnvj27LQ+2Q#+U8ltwFtUjlhVrC7ra+BPNk2L7=sVg)KpxI|M5Z;&3 z!c0e#Cc@V$_~<6|{f0z!01l_)J-8U_;TLoR=8s+29qfKd%MnDfjEeR5%!M5v3>%)(!}}%#T=oberQ>?|?@>cyJ)VqlVw3oY9{xOPO)NX`wR2E9x2bA4 z+zjPezFoK-Ct)a^hL_@;l85YwoYx)rDeYMYA}4fQaMQ6$%*?I9#?hS!k#)+H+~S3O zI)}ZrOEH?e0weNs{g&F(b@>4h8Z|EMsJv?9Z4#SUF^;P!_g1YG!0PuS@@pO0m3wnb zN_XoXjP?td4B_!*jGC3x`HF$66|X7}6u5GK8mD{L0-XXH z90#GMAAE^@d> zIjne#=Aqe&S~M@+9U1B~H}qdLI}myFsN!FoEj0YA8<9;Bx;U(TIRYXb8t+9S`>?s6 zO7bjaZE+bhJ))R1?PYiOg716KH9Z`L;Bo_%6J?PVeO&OCM7mfxS6ntfEn@8x=29{y zMRNLT`hgrCzpCotP2(Z8t=`aN?kSM<@U+AR{F8BtkRC4T?Nt^C#XqE6!uNP&s~wR& z5wL#d0|5zqKZtzeRIS>)&1noUqwljVTaUYdAZV*c)v2~%010jNmmUMYrsqld4ljs# zv^H#W<|b+zf>yXwey5KLm^}JI$6cQoHrR}Mq;E3nIPB!&7_1BYP%+;R<@1!cEQRj1TJbV8_kJl|{!mNv z6!lSJ4{Mb}c031zxL012gHC10v-=J@v(9G7<$eFk%UpIzHRBXa)Lk-LJDEyvEXRnP z)67FuPn$ZlSN^5*;3#5W9c8(fM>(`tx*RYpqp&~J-jwuix*3Adf05K}o0~#a)%4|} z+~n<$%P`D93p*rH&h&Q5V1sjQ{j}L^h-AR}xOggBpK;J57m{n7rqg_AS6GupU-o9Ny43{TK*WRj`EusWP$! z{d#y=9ITfEU#kmn3)aImal02pRPy04h>Unx`dY2@u9I!jLAh1BAb;ytKOBbIH>E*! zo{Xw80u^|&*`l}sKiLPBe!qZIf;kAtKXodF_UnI9p=7d7dHk|^sqe~I#%@muh*!qU zJ0ASw_OXmzJI2hrW;6g9)H!^2WcL_7KzmBgYrDG8zB|1Xnt*3ML^*GRlbQ@lv^3ZKq8?G(9s}Oc z#JJ5ptF<|1x);2ngD5^iXNHymxvh_B%#=~}r1@lV3f(nQW#%VGyahjb!D&2khkQ@p z@nM+LBJon@P`-RsrEg}bK>{IdXfoX*X=0@Cd{a?LRdNSEixHP0*u`Ge>97+Cc1pLJxpGM2F& zlv9}*Zl>HpUh-sx+L}KYW9`{~F{zoDlAC;of;{WO&7?G~nFwi}aHnP*N{+DO5Mjrz z8%a)gjij^7HKVCVKi6Q0EoURiW7mza>6=H`G!#i5qjjpK&3-QAs6KMdv*bSi zk!!Fd&Bur!ey*hrv5{o=SlUQ>0@#@3=}UB;@_px}f*^Fl3e7l_lIWCWcdSG~{l<5L z$TVeu3pqCQT!YQE{+?@&%`X3I*F2lf1i?@@nqoL28zRZqkU(pujj(AD;Yr;{nxRM9 zBHIUEGhBCyb)oVtQkLI+!7%j{N7A_FkzK4w;DTMXEJrb$y`m zb5C?rR!<0|rx;6%%35wy%keEL2tQRpd{IT>FI1-NJ(Vr5as3_-b2Eu5)N>zDPcFQs97`XE8@Baw^P}7sLyi8`uLFIvRv5B^&+dn0cU46lXb##JQo;B8EeQ7Xd{DTftCS>h@Ky&Xp1j>z7|2^L%9(vsOX2Ge20w#84d-QkR+5VaDHg6*p0mwDvy^^Ye)9JN z>r=k4Eh?vP=APR7QD|Vx0d2V%5rj(QlF-0|nJ!Us-cLOyh|P8FRhCp1y8o$9o@UJb zq-T5Um9dPSAbKp5qJGeFbp7y`#K zULXio-=8C`zW=nePg`X!ZbIek2(Xm_SLpb#1-abX-N5`<-vL8vNdC+uRoaW|9Ln{ZO&k|AMy4e$0z(%^}YNX};zV zYymOV^@4Vb*^KGY$YB9Xs>?;}tRlVqV<1anAbg?b;!EmPuOhR=?nd_V+(2f?^FXFQ zGX(A|9}*dHr?$$j$Y%Whm?v|mc8eW|D|TRm73<+^@qem2wN>UT35oKKYVO(D`hs>R z#KO15poFF}Fy)F^_@BO-o+n$4%PR0M66K%k9M0*ROy3ftHlo+A177L9t|)t8{B7-K zd!EsF>TPYgJ>STjqH6Ms%H``sdwx@glMR?l@)}~{kD>?e*Tc)BL-*_9Wzl=?r{i2L zi=m&cPWDnS)@sR$73ZuH_tyA5_k%!PXRz8urm)mm@~XBRc4{l^HT_^l4(gL(-_@(N z9+~C!D4o;{6;QcM!k?|MhP)72ZQD$e?F=; z*L*OHvR#__&X?tzrGr5pximiQl^_o{Nkfu=of?1VYK>p4{LP+I{K~ag9;6^LYMVo^ zJeY&qdj6INmO{*4d*%NCxk+JX&%5=LKK+upX?{h)V_FlP-|Z=Y(p6_8QyZ*2dI><(tECXOw}hS=iRRxN5Q;vBX^`k zJ}AH8tT_3ltVjoCg{hv=JXc>Q^K)GUv9%hvm^Kv?R?{-sg6+5x>)|H-m^xMXn_7TB zRWp0gUOoJ4%8*{v0Tv*+kxAP)-PK~@9m>PiTW8BQZ=TFZOrKMtj6yF9EwT|5WaU&>hmVy& zpt^WleR273eAG`yOLqUS5)j!0uEpgq`B+(updca$CR?@jaM*qX$Z-u>ghH4Bq(nm& zF1P}K6ed!?0w6isXWGRTWqs6qc|;TKxUIiOtF?C~C7nVRYO&(A>qi8m)n~+2@~CRW zmzDl`*;R+M`!-H^zuEY?N3GYkO}}!^2wa~(2V1Z#BT}!R>oZdi z$2obuGhqW$im$K!!O9p|*)w{0R~%%AlkczTK_wgp%Uru2uGE`}J`Y4LSOZ_J`(U`f z8i+&Vf;-^@ZPyAQ3pFn2hYz&RR#4v%kU72dI6l`N3(rtqzrNZX3#Z1wiq7a^XPmOr z;feF=q-8!9cE!LN88r9D!v)9q9?oI(RH1x6zry|ID3io5 z{L3)hdqHI@J|7?|s`%?bZW|hcifEv%-dU8Pp+$^_mVj+M&{j`T-RDiIO~pAFRVz+5 z0HWB&;^d)B4W)4!N(E~$(2|F0%>Ai2Q$sci=UbJq9{?j{H+?d=$P}`Nmt$2 ziT3)S+K>jNU2fpJ+>p*w-zj}*t7k}9$yiWzL-#mUXhCca4L-;$V;T@i>IL85eggdQ zpHL?mhu5_V813!c)LxJFgEj1@@A;dksn)DKy5M27O}VmQ;jH8a91E|F8j7Y2LRm9G zsi^ZMXX?pBV@v18_WA}K50{Ty@uX={aV%WuKA}#j7^nNMJI9w&5>lb+Z-D`gw}b6Q z|9}Q7rV)o>ap1~W#xovz$bD+^bV;rK_q3K{0pA^YCbDnip8B=Vz4Bag_tfsa&b+`q zt;iza|DDVDpBc;8)v0p99N4KbU9s@h$TMRZHM_vN_snL(8uqHR!n#CLitEqR&18jv zK2r=kR7&w3@((u}gINYEj)gx{>KE0ar@YL@7?ha>>Z;Q+l#1^{fmQ(1Z0C6)hC2d(7R3DZNgfpB}w`>I4h`&&Jc&)1RExxsYjB`a~a6kiL8E$R$;_bx2 zTk)Dre;xDWC>1x9Of$s)rlypS2Qo>iiS%S)!Tt%;ir@@Zg4H$FutzUfWfk6lYranp-Me7sYIkVK~=H5AE%$8bu09Q zS^KHx&|__gT-Hu&U?0p^q#GOV2}LF?yH?P{-+Y(O0zG^&0wpz=3+5Ozupa&*0ws1# zQ)j=clLvbE^9WdKFd~5nSg0ZH(};+zc#_BaFH$FcMgOIrC@D*d&@rWaNijOCEL&2| z{OY&L6HD?ko*rtiHwSY~XZ>IWvfr~!d40)zv_bh|$tNq@`r7)TilL4$7+2THU>iTP zL3&oDGHji+OQr3Wgrv8q`8Nls^7?CMs{fDIwz5LN4eG7iteU+(@xxA^QN*O&ue?*2Z_1=h9F5P&tC+UvjZ3Y23Udf4+W zU7~b#gY}|cd{)3~H|2NV)B4e!Q#b8VmN_$$X6{7u{;q1uTBj|;5ufi}fF&8o`h;n` zMtR9O6M2*mo#hH~W)(g}!^{LKJhL#5Gcb@}>eQ>u<9K+BVsRC^_vlGj_P(~&BgDf` z#Ot*(XzN2a9NhYn({QE+$HVL6o5^%Y8Tx@%2J!G+aiXGmJx=xHkEGwWfuQwoCfN{G zDQD>6CwsLX4nMgS-H>!blH*|m!ufHb~(#k9^Fn)++4pYv7^pG(Fh^O-=T&TB~r|&q)U9AbwwP8D6 zB*nu2h*I5VGvT>!shs4fE0X6zD(QK$iyHA-Ck%KZoD~Oa)*w_)89co8?a}v5%EG!S zZh%oP>!4iSN2TfSqMHd1hAz@C;`=cdG$-ZAeD!LLE0}|iIoUr=$KM9bC6saX@PtNN z{5(p}67$CYrP64E_rLS1#KQye|Aa9BxvN*d)Yb#!^_Z!N!*|Gqc#m_czX;p$bra!F zV_;1>6A%01AamAh{%5UYeuuNB4~h3lwr%WC-qRqUIeFWtqNxP7oMipPS%#?KPb<@P?|ba;+<8&_+O|qoc!`Mlv1E2 z_@uf{o{0T}D5c(^;t;jSae!MQ0b z@I)9*7>d|40*;4&89lF_)&%$LQE!2?0)M0lOJm`W$7#`UoC}t+)D?TLv~I0<&#PLk z=YwIRm?rMju>Ch)C|fL9zjIE1q!lbZuP!g;qQ)0$=6*?;-f$%0h3`^tz@rKFr@n(i zjP~haA<6Dl)d#mxKvrDSZ@|%n-u_pw9v+KX0AwW)KFZ_y=XMW%=j{D-GJ} zbFgAa7()gYBdJa>a=y!2D zj)w=v1>DwuK<2%A_}6g(Luowx_wjGk0(?n%Zn^9BnYgcxJG&S|WpMBz>56LGh~A*l z4{KW6>$xIz5Y7Kaec5@`_j@@D4`}=fJ$%c=6z|J*CaMg#{Z->vO!FRo8dV?OriWW6 zVAdHwosGu$=Sulab+(1$vNWaP&%=yC51ZpO9+mW`3Gwg`$636>i}paNK{_P2OL`b7 z`){(OYEiBzWsqWjO!@GpSsB@V=6-6WXqUlTX>Y6VRSY*5mv4?D5d`XlF)kBuEc~M= zBMM%&q~wtjIrEV*ReWSJlsYxRJQ{`^2qM46R`^lSi+UZ;6lNua|90~6t8 z%8#3KlRl1cn5Lg=ZbFBY)6M1iLWHWQsC@xGILb47oX_}<=Yim;1!7YQSG0;55oEb2 z14-3bQG7&v7A+EY(y#%FDjh^yPrCAaN%oS7@KZ4kU+zBOW!z~^)bkY&9~!4IU39CP zgD1idPrU4=ra%_;Uu<(sgn!XbOKG4~TYsB^R??Wu!j*+d_#GNsy--=YvfTYxyvA{N zWLFsN>GGmO6XAC?gateimbEG`gI8(X5}UMIZk3FWPK38>)Uj)yJdo|EmJhD)3xcWI zPqhcI6g6=!H!dB$@BoOHqUi{coiPz3oZaZa6X9-Mz(z|fTo84* zaV$JjdqKO?3}SKl!Sz!I==#_{zRUZ9cBceYfA-&^-MPdjt&>}&kCDlR@8q_%Z19@kXn&joaW&-?eT8d{di62dI zv$yzo83eZWu=Bx_j=I-IQw%qqIOJS;qAHKUP$BsP!;I@!QkwS@`GT~^`P)&(h)<`= zoq4NjQ>8f)FFR-egVca&7xcK7=lVqBgjjf*ZVd9=IdAGH4}-&u*da~z4r*!klTx*O zsLobfEzLcBXw+>m1aq#fsFs@~*LSDII*E?r+crUD$|%chk*Ps(j2gUYR0{ds zxP?-yD2#OugLO&h-nSND+EFwdj4Z$nc&Q4dYm}s0Txg%tbW53=L>;ZvkJcP|?7=jo}NouR7RzV)m_M!z$`CQ*-^5l0$y!5x(9`=n@8kdju0WoMyB7%_Z zYO8PS`FU3so`Q{-JH+k-@{?EzF2~#FBAW~P+fhrV9Vj;3iXPz#8(%#gScF zLr9R{Q;!BKOy&UXV2#EtV*KLBg-8CVg6(%cif|GBp|gSP;(xCm4PIv&NYrzXEjt=Q zo~;MfA0G|gXG#s^gutESYY2h-AJDM%1@&l9PLz5!e_sk)Cp-4YPpU_QZ6?NN4GG^N z16#MNZv;26jBVHHqrr71Aiv+1Le8_RZ4NT9?KJ+4^4@KQcRe+cgn#wL(crx%cj*7T zm4X{W&|tEp29uIa<@}*?l9X)qnJj&mm{cG*`Vx)MC&>(|aQbryV{!&^2xm&8%RQx; z2q~E)%~b2BbkFi}BCBlp!2Iq8DUL%flSQ5 z&Q+(@qW!tvObzAQ%gg=wLC$0wRO-sl91DV}Ap}Zt%e>5Q^I%2}NjBvNs&Up3+TT$0 zp0cu~*uAHo>qLu6WUzf3m{(hbDdwF2duDB~&mp`iEzpg*p_HJ$&~Blah%&83>)(cH zO!N=V*hWUTbYNCVKfI-_C#5}Z(VWZ znTY4A*He4d%tX6WM;OLj!3Jz3BZZda5wi)%o1XMHoV8Q6+)8@|jdiIA9dE24=I?6o zCI@-blSh!r;6LK@T>a1!&Kq-g*Vi5#HKg7h*&S^kI*qBkpv1|+%_A2c=%7Mn^NaqR z5NuBK<#e}nzn8s7rDMwbUt_WoW9rdhi>WxWJBs~p1UIv1x|1uG4J6y@2hLw)$%+{m zW1Nlgdo|+<3V3ZE5Kf7Ud=0&tEB5*UWVv{)!hrQhRZ&>cVI6?Wzm^K+Owz zno$5%!w^$F*e$6`uNs-W5yrG6wC1fbb#m&_y!QIkQ3E^JeZ+Zf@QCwmA6@N~xTStk zo?NpO&eQ;!cNF{UY=gfW<)OFkuRahAwN%cO2T-TYT3d)Wd{vJZsd*u|+Yn?7qMYSx zv20Cn*O#qJ3cSm+;qC8d0DQK_% z@OvbewAWXCWyPjM1TodcGDGla65fTU;{u-;f-TJiB^Tgx*)@16F2Oboq+3s}IEvrL zv{v$2`<%mdMh)3`-z#;Ol1|Xu2HNw=vv<|79C9gtxobv4>J|0vZyc$?Z_E+qziSE4 zji_DU9Dn>bmup+!{supu$Uj$0IPRb7Z!Rx={Oxc4lBj#vDd#d?G?gLYH@>a_2W+n6wL){Xgjiqq=L#9%AH zDd%h(OK?tYBz(QH^6ui4A^m&ZM%j9ILGmx|27bfcz+Y2dx;ww=6iwX?JT>TM_Mknn zuzdpAV_}QNVY3(QkA=DKZcH&4)tY;rab{u^$jLMJ7i>jypz_;*rlN8bprJJS-TB4O zM#1{+Ak&0O^4db`$}}i#$)F)I{BlVG5>pmP`R+S2p!AkBda9#$+71K-w#C`9l<#Mo z^0(3>I*^Bs(UTu-ZSI-6T$E9Dk)K{yH7x3I=AJe+b;@iI*0I;1y2F`q0+AvO$R!=f z^-&<->OhVsqPeRys@BuE=S#gb&=7#(IbhuUs{o~GjUZAB_9{&@TfFp%7C7m%nzMxh z#-{wO)qMwLv5yfDc}trk9+b@e6!8^lP|7q7NM~fImxkidR{xbeQy_({h`^2 z&ugE(vP**%hF`oR19?`ba` zgP@1+(v5qJonX5B%SD_OuBL52e-VhAO-;|p0?u-8gC0)OX>*1> zuW}Zt;aion+|w|oa+b9XL@g+@Vs0LgAM2cj-@_l$!z5l=6$*T%qB08ni#SE#%WZ~E zmar^qbC9#!kl0Khl@Xq%^dxWVKnislraDXKaKo`gz8iq_>eL5$&^dF!&VRo-n`ohS9fmfx#n@h zRnNBb+ON89$8R{Z0)G|s@I#5QJ-n^7&qD9x&MB7jq%y)9%4*+qP76?)@hny;!9N{l zEP5EnjeCskU_E|y%{F5@yPxSm8cIcTK34}dFjJ&Hq*g2P*Z3N@#@Y5b9Yom1%^grF zA#Y4{wqzTW9mY$C=<1+c?s)?ELja|3!sH@uF+(X`l9c12YEj_Pf(3s5#rDRP@_T(R z;8e^DEJ5jO_;-U~O7ia@KX&a1)v!B4tZN4mSX6T*fMze(xJ7R7HIG{j@Q1)+*3cp} zd&fvB%aspyuhK;Oj*)!ZSb&>Hr{}QqlL5}cANo`iy7X`;Mn`RC|MoSFr`QnZ_q?a_ zhv{q=;`IWf=;04zbo^&MbTXLEV?oZuYABTi_)aEK{z;7T%ir7{rjte~-W@P9n{{!kk0@Q!~e}ejL0@Uw3OlL=ugBYaYAnaft`kK=CxkQVf zdw{sJ;@|W0?nD(2yDm}XCo!=8)X%@3B>>^$2FzKK_9PwB!&_tY_^O8=qP0VwEz1+N zH^jhtuU{xxuq?Z5$|wV|aN{^0Gv;pah&1mYZTM#H~YIj~AIIq3XMQhZJq^91EfxH@< ztpD3sOWl&teScVbb!z4#Ur(<5f*A2WUN9v<*9m`!u}rR$+!*bAQ!FE)Ef_i%vLv6) zw*{8#3m*{G$;>z1-_OvD3za3Hr-p`-ZPQEjJon( z88_gXBRR`x^IwhAsGnbJ9Cle~z?Ln-7G(}jy=f!1NkHBoXF4rd#$u><3k?-ylvwzf zwh4p9Dg)^ow`0C*(*Cyno#xONa}75Qs`P(A1t0Z%JpTmn2LMWUJ^{R$@8OmUax837 zru^tuBrEHFUv5iZD zO&fx;OKQaLaB3=bV@-rNDU0NMHw|U08YZqMyV7wM?ZmpmPdoXohB}M4R?R|w+pL^K z7wB~=Ah2dAntEm;?1(|>bdi`v^K0r4uYuCu=rzp{ z<;ORVBqyUz_Kk9!vlYk+t;Jhg$GQjDPIF*?UHX}caCVGdK&CiX%{m!a?}Y141gJlR z-kIT|hPkMdj`W<$;ZId4j|S546}7Er3Qm*v^od*THcMdL)_V(Ba-MCm6$Th=wj9_B zq(JNSGIPyBrPS7Mwk8K?O)ao)>twzBu>dnSsO~7rv3-;HYQiNoMHp7+VqW-Kd0^w3 zmRmHiYJnM2TR&<9!uEpizR4YZDb;2bPo~g^k|%l2Wm02HK^p+*FRXD35O{%wOLNC624pGJxFOOM0G?sRwlm zo-V_z)yk1gvrvU{VbjVV0GX?uR~KyrTfo0&BiR1#M{hW;rmdu>S+JfM>>p3FS9@r< zI}e|z>2E*Mlk|J^`mGw*3crYjpPAr_jDys?iP|SU*z_*iMEK9j^Q{Z24#+~^mrpaq z#IO~Y1KctyN0T(_%b5mWso>lD1ieT#X-&^muC>mecDnEPK|bxr!`$DYJb4god4oWH ztSr4R7fH&R`z)wg`RRT6XsNRQzVf`E|EDgQp`FvXp>xBG$aS^VD?|5TH;13aU~`Zi zo@bodxc+o^WcyX8_fJ6qN+Uq_I$m@*Mo`)dj^>f<1~KiOsP=7fr{n7MZOn~}YS-kw+I=Ld5k6|Jt{q`(A(|flZC&!|#kmmF zt3AZ9?YDIf_f=*aQ?t0%F=BMQI-1VGj6&~c4iG;a2G?wQ>GCP2PyZ)H3My6vKFMz$ z$-cQb@|1>V9Erv!ENSV{g6gFs>{33OHn!WDbo$Ypw4iQhPS8Dk*s~LVly|V(8;z6n zs5!$mf@=9FXb0+&zC(gJ;XY6YS5JF#@T;Rd=NL(I_|)Cb9}WYu<4Hu0 zM0R`&*EI%qJDHQ)op80+vomk)D2tHrEQYE>{tt&?`D^N*f&wc<*l%BSpa?@Kx~Cm> z7n|md#wq2r^yqYoh|3t|gZrJFJHmv%Bi~{VdCo)0_l#$feA~K@Ok$oGAw>D_MhHQD z@s<<2oe!L5Y8KRflIIvP;;rhRgF+e`F@{PaX=4R0A(9qG5#w0%NY>4kNLsMiwTPlH zUL4t}rAKoq3QLote8l}s9TPELg@|#CKfN|5IjGwkPCQeGPrn{yk}b6_kES5szX@1B zg6bj4YrSVdvB54y>9m_`;ChYid7-qtZ1XbNnU5BkWRW;(_uXAwhYggS@CwfPj^o^q&LN(`A z9-mMp{G7TC_o?^dhgCanRNo9TX$xvIRmwM|D){J`B(n#^^yQ!+1r+G~i!Jpu>Rc~C zM~mwYakZ=6`9k92BE5V~jqg8?n!S@!P04AS?rx7%3DNK`A}%2s-WLIpe$+7d-=0`l@WkU+xW1?0c_z(;j6`caa9j05?v@yVT!-jd-RKz8@( zm(u7*loB5d%9B?mO`J+@1PlE{5WlR19CEKJ37HdL#QD!xgXoy(XMX4>e!l;_58u;F zKmsC1nh8qWbOCbDQQGY{(aDmA|54&R3IvX!rkn&U`tcT%^#vNKZ>MKUS5dl+Mp-5g zSiJ7Z;~0>wM}e%3Pzh@8hagCBjVkMBkL^e@1pf1$^$rC^D1H#XOY|QOk@=J zmnJfJ-yLQ56s6*aic)G7XZDFK4Q*~Ic%rYebi1>l4V`W;xU0>PNBTiHrQTjPthSV? z>TP9TsVx4#O6l+oQtiopA~i)?o;SvI&T2eT|x$Q6R-D>K!G z@6@4SW~DOhdp7S^s6+Ristt>2qf$&So_

hqA2S@&>c4*J=x9*-48i7W=IQiZ5)j zTh>$h%|Leo+?e}@)vPI+Z^&Y=S;!uICM#=AK}dCH@ip&>L{o|jjrxs1abolK0Z-9- z|IWhbG&Dcc^G={MhVb$;Iav#>elMD1zsX^TKd|=cEt;xz3|Z`Di#V%-Io6j$q{V|A zXD4z1gd(4rKfmBI%tfH0UKy1}4#FtJw)UU0Vog`mCrT4BxLJQ$&{X&bY zBq(I%hmnvsN}pGvXTlxPwcGxkh+;dWQV>gFB_ZZDfUYkBmDK!Wv~nFs>c<(;Q>^!= z07_%-6er+3ooVvc^vHV6kj3UQNICCMahErn{9q9%4h&Hxjjjj@1i<}+E1JcYvyl4K z+@5XH_vkmmO963RNJsWA1xnVbtcRhCH;CYbgpoAkIULX)M9^p zEFF++Y{4zQ%g$wy=rWbsEA1w+)*ra6g`yT)ew=qBfu3MgZI=yvrQUKna-3*%rR49B zj_d_L;p`V&9FK(mvLC+auAnBFZ$E~pKS)Q0%3JzB_iH0ITjCs-HH%Hy%NSg@UFQxB zR6T*|6I^OMs+Br9n=q&5tBesIv2`pv%kenQC2ioIs7bC;JNG%>sP*qmkL0yecAe*J zV?W+)xrfjsH>Y=s(%cIVc?D55t%;W;R`HsNH@9>exrPar^|2XrTI2Z$}hOIn3Fg z&B2Rzh|jFN^t(psq^y^Og`Ec@l|6fGFJ`%9=_WjoU{_XM+?i#^%ug=W7}K~g2Z6#C zC5nr#_`{sZj}(>0@_fenQ%b5qtXTO@_-3Ff{^3h+1>6bJsJf-B*toX6Bvr0<-K)~$ zBe&|zKu<=gXh`g=?hiY@S(~`=5;<5A7q?UiZT%Y`h$VlbCafGkp9$3GR3IfqQsnV*apaqHTC)VlX^BbMD3Ax%0EFqh@U3 z$YDfZ5CA|VhWr(Y{xp#Bh;ACN{KJC&L0+2W3%4zD^?s0PN{CVIT z_zN+#9|3yk2p|){4o3=U{TR^ayMaD+6lkI=Up{;sXn7&+=>dun8`T$N(}lLC3&1zt z?*sZmFVHvjeED0wKn)!#zC6kJAlN^X;we-)i-Kf2?D)v%S52 zv~w6_0CQ>K>1MuhA5Y>~b}S3vSVqReH;xuB1LTQoI0OEp<7KATP$fHY)~GXYEk@+! zO>PkLn&C3zSLAB{p8T`|HY@@6t5z_KT?B* AwEzGB diff --git a/boards/auterion/fmu-v6x/bootloader.px4board b/boards/auterion/fmu-v6x/bootloader.px4board new file mode 100644 index 0000000000..19b6e662be --- /dev/null +++ b/boards/auterion/fmu-v6x/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/auterion/fmu-v6x/cmake/upload.cmake b/boards/auterion/fmu-v6x/cmake/upload.cmake new file mode 100644 index 0000000000..7319b46df3 --- /dev/null +++ b/boards/auterion/fmu-v6x/cmake/upload.cmake @@ -0,0 +1,49 @@ +############################################################################ +# +# Copyright (c) 2023 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + + +set(PX4_FW_NAME ${PX4_BINARY_DIR}/${PX4_BOARD_VENDOR}_${PX4_BOARD_MODEL}_${PX4_BOARD_LABEL}.px4) + +add_custom_target(upload_skynode_usb + COMMAND ${PX4_SOURCE_DIR}/Tools/auterion/upload_skynode.sh --file=${PX4_FW_NAME} + DEPENDS ${PX4_FW_NAME} + COMMENT "Uploading PX4" + USES_TERMINAL +) + +add_custom_target(upload_skynode_wifi + COMMAND ${PX4_SOURCE_DIR}/Tools/auterion/upload_skynode.sh --file=${PX4_FW_NAME} --wifi + DEPENDS ${PX4_FW_NAME} + COMMENT "Uploading PX4" + USES_TERMINAL +) diff --git a/boards/auterion/fmu-v6x/default.px4board b/boards/auterion/fmu-v6x/default.px4board new file mode 100644 index 0000000000..dc58fb1c88 --- /dev/null +++ b/boards/auterion/fmu-v6x/default.px4board @@ -0,0 +1,101 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ETHERNET=y +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS7" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1" +CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3" +CONFIG_BOARD_SERIAL_RC="/dev/ttyS5" +CONFIG_DRIVERS_ADC_ADS1115=y +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_BMP388=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_AUAV=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GNSS_SEPTENTRIO=y +CONFIG_DRIVERS_GPIO_MCP23009=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_HEATER=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_COMMON_LIGHT=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_DRIVERS_OSD_MSP_OSD=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_POWER_MONITOR_INA228=y +CONFIG_DRIVERS_POWER_MONITOR_INA238=y +CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y +CONFIG_DRIVERS_PWM_INPUT=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_DRIVERS_PX4IO=y +CONFIG_COMMON_RC=y +CONFIG_DRIVERS_SAFETY_BUTTON=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2 +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_HARDFAULT_STREAM=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MAVLINK_DIALECT="development" +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y +CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000 +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BSONDUMP=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_NETMAN=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/auterion/fmu-v6x/extras/auterion_fmu-v6x_bootloader.bin b/boards/auterion/fmu-v6x/extras/auterion_fmu-v6x_bootloader.bin new file mode 100755 index 0000000000000000000000000000000000000000..c48956fc9e34e53237080061365a4f7f60335131 GIT binary patch literal 46892 zcmeFZeRvziwK#lccO|WDC6+$`#deaF)(Nte4-p%12oyy!;|~RF61X=cly2gbt_e4B zLx50HTZuz43HLU{v^T``HW1pv9u0JH;JJb0&HvtGK%DAY}wx5 zGg3lt3w@vW{qOzb=jZWiclON8nKS3ioUhr&d?+;VAil)?-~azhga7~V09^Xh&mG_Q z?H?N6IUhCn=MW*2>pdS$+wrgXKFmc_?tC<>c@D8;nmZSMVcEU+$im^tntJ>Zb@T$+ zI&tLeWKHVrk#m;aZWpU>?(|2+7JoFYr8%0_(ok{G2!&!WuNrK5zE;otzFEG!>b$Bw zp29vL3&(-fPXKvryfa$!jAJ>o}xsUE$Y$u58rh6Cn(WfunKfU-e43NP|Ahro0 z@kuWg^82)vRLJmBA)`-&&b?MBJjg>K02ID(6vP%D3LmWAdE^9zQaR?Ay)l2uaSEm1 z_n}tQ22TD%_NI*&2H2DE0e7UK0=1!K=QY*WN3DhSSi^cd$>cml89?&+pD|j zg2Fxug&y+a%5DnD`@JYJz{;{vV!-QTcl&^qm>nKsj1|_9Bg;L6=P0LCDnFYmeNNpg?3`%JcQ@E zsin~2V50M0ZhA*yA6?C!w|HW(rJJrU?4z}eE*?+Jzp|Uw zUVgTFV*Vwm=hcOFGUV|P_MX8f+spREAUoCG9m(GRdS7)VUF8N zEXg;LuZJ!uWw4A#7;Fz!1R&d~9v_bM(ti3uX%GFNw4e5u_R#*) zEMGqzD$Mcr(4o?PdbYHOo-OUC=Sq9%xzc`0N_!|N?WdoX_RvpD`)RDShsH`Rp%nh$ zhugn*etHBzM>+yaLxq0Mb?kgJYZu6V`}wG)dCRYNMzdO)qm~vX0ay8~Recm387*AQ z|KPR&Drsxa@IM%MF90%o|7rWKXjV&iK#*K-0;zp{Z2&F%Ld$3Y=a;>r&lB@+>89X7 z@>vZQe%5P``M2;sR`QYNdb6P-g%gw6^Uz zLQ5C-(UygtSOeEhTNbjp&U9FU3qL#x$ZB`30?Mf$+hVD;kndquNgv%=sW^#opx8r&_j8 zD9cbX9JwbyIt#>@X3n|vmsu0@m;6zyi9yNlwVIe;{;ekZSkK3`8lt=Ys0km#koYkS znLmah%f~QO_yr7EhG2+|$yUW+EWx!ZPcr#61$?ATURTlv%c+p@j3*IhFte((V0Jf^X0JlI)v0lA@Or3_-|9((q0r*Xs>+b;xIh8&&V(J$tl}jgT@y8A z$bNzr+$57Gua^vYkJEyih|IWW{jZq}`9Fps01)9*7-F;^PXqDyX&~kV{WAK`dMsc) zeyc8ZWG?t{7_Q+yoTYF_ETKHrK7zPBg=#rL_zG_6H^8NP^OSL|p+XF%W^%#8KI*uM z?TcTR&sS}z63BJqwJ(GChfSzh42r#6ae8lFN55U%48%r35<}^mc^_*teRGyly_sq$ zp1HgaTR&>~=zZh+4{h%=_nq2#DtiGK(lc{s&5<3@c{mDw2%=*^1d85-Q0iGIRtACa zGuK6%Xa2y~cXlRW<(L1nC|U*-EqgwKxPNrNaG1<>6q^PEXX)I7XX)JMBM#0{96$XL zefHy;k$o9|Ih#Rlr@}Hf6_(8(3Y@jV!LwGd4F%4Y!NId-P%soYyA2MW-3C_;1n_}W1>Mm9c)a?5H)a=aU&bG)pW+dNte{`;o;a@XSutK8TdnuZ|f0~U) zDE{|BMz70#vESz-0{0v3^7#IrWa%&P8Of0^x09Mjf%`%OaHWIjP6ts8 zA`+iM65|Pw#2^r!vTKPh;M9|ZfovULI82rU$)g4gg+TIY4MF1K9~ftg6GC*ZN9_G4 zS_qDSA!6oN(Lxs=*k6H4g$3usp|fNMYlowtilMndkkCs&=1hR&l}>IyNQNWdrb41D z$l8@KDorD6CK36!$+QLWFf0@XH%OtgWo|@Hy;T-sGNilo_*uQsW~fXf*G~eOL6MEG z44oC-h5Nr~5HV9

uY+34JAhTOtV0KGI4E{gukT-q?MNV&`T;VxvfCqWM=~+vnM|s z2E>!*X+bVgN>t>$-&7%IBJZygGeIom08C{yPdHN2c>DfwWHN zRRVcu`jBd{=WPM|Twk8T%gzQMcZ?gz7qq~a5dbnYo$t#CAo6A+FZpYwhzunV`Sp}Q z-kcERv`SXv-DyLz=2B`*{(8p|d31VGD^b@%y9S*{j8Nz{LE({CLA-Sah%XwUaJvZ# zx0#@@+ysS{CMaBCg2GTfh(DYM;!Shd+6RRK*)?JCxi9{}v%v;W3za}_n3OPE`=E3D z5Qyr_DL8|#CI;)LFTpJT3g*F?AZ~jZ#9ufXf(C5Hc_+_Dvwrk-ji8`Ik5^6Ev1x_q zyV&lf*Sh)9clb5RkD^&EAT@+GlPe&hLFcWRAnr0j;V&Fw(0nqjdL?za)&{uIE^ei| zzryItQ;ohnMGS%6;Jc{hVOEF1Umh!~FEYL28`jEgcglu=lu!X%0!Y&1_fK;eVFw1XZc4(4{ArT)RTebke^o(#TU{F1 zt^UN5u3Ex}I(Bz-4f7>JWF`PPPKAgWfV@Q|%y^q8n?o5m3xBR1SH94=4t`ypGOWde z0?x!hYNjBPZZu$~E1ajcWPfE;z^)Ef^1&372>u8Onbsj0B4!hMsrmb5m?uBc5q1UY z9yt?Wb@cdA{i-2!0E)*>&n!htB+Qd~y$l0+W6IirUSc)2>&${dr@?Wdm&yF=l=blP z6i9#4x>QS`S>5A-a6<*CRMXEHeEF&~V5rVkvpe#hL`(8^F^PjtMgz8w=J+hZJoR`W z+n2At+`;s@zt;uZ$0Zjy(>?$>XIHu}UtQIa(mk1Wf|ljC=j;OKSopk#$eoiB?Q**f zNg8MR%y_oi5CHOvse^&hJv`xg&S~oXPqkS+;Ng2W6Em2G9N4>2R+=}~Dcu`EI;50^ zHWLJiWLvHP-;yt&ekAjLhB@Q2h6+nik6+M*Ifm04JUqE}T2N|;UMgWr=&I_nV6J*T zn)MjilOx%=C8^c!j9OZT0$fXWI}~#*Ttr`z-Ol-qAA&4z0O^Z%rn{DfK$bQbY!a^9 zg~+{$W8-!J$N65j=Sz+CJF2DVW(f*d!g~DoIzM}&*AimbbnC(#V-lM$r;^yXEFq94 zH5$AM&+;*?a<;0+%k<2^#`~8k{edKhe+@%!QC2U%D7P0a$_?LlzfDc|Lg9TI29ugM zkSwaluhu0@LpJrk`(D|kr3XhqYd>b$- zWTWEAmD5rODwP(*!znH)3+dWE!uX;wqi7DPSJ>2ck+EX z0qY|z9x;5PomqS(fns%ya-VuY8Pf7qqWzOEUrhw=tmKJlO6s_yk|+EWI8O9BRj;y9 zZB~-J{WT1Qh=jgq=SjyT>q)pr!gvMF$^?tMV@D(&h{C91X=h5n*#NZ#Yl@ir??wOiS!^6S32 zMoo9Q;*G3{Y8J%MI@2UIn#CIlIXbY>c_=>RHWN`9f z!N%4<&!pUBavH+UZK9J4vy$$F3p0IYGs!UiL8GTPlPip4m-O$;{PEvcfM^MtF_6^> zDPY5lgY1o@ zeA)ZSo+`{dE1xv;%Q52(h783_kmkM6HvwBp-RoW%NLoW!?Q z;WK+&m{CTK!2@TS>+b)yyLlvopY48ZB*XCC4Ltep1Zzo;N2k~>v2*f}ws2TqZoqq` z7JMb1i+PeeA>g3^$Oq{he-U1S`Brlq*P79WTGQL0br}Y7Ej7$Bo@RT|m*WmBuu<%g z@MkKJ?c*1<%_PGR)#e6`&%(ZR{QfX11$h?MDVz}I zmP zC9}rQX&G%*IKA3|;io_jQDM#}gXROvlRNhdRG2fEZ1K0_Oq&XwC67br6?q^o9FErr zcqT^sp26p%S&x66e?OwJgCEhD|1^bKkWNx?p=+yV^28SoC zw?7`uYS~OO;JP8SFiU;C6U{?Qi`=WI?Z_Ju$XpcmQkz?E|4jJobKxp2X<86l(untECIT96{zh z^=%d1knX;P+CkHpZd!XuH)T4i<=D?C+i$*21)m;QJ4=0xVo;RZ*@E|D6NbVo@N#Um zZ*}oxVA72rr%$?h^6n%qxb=+%m@6&A#?f5}k+sx_YesgZfup<^M$^(?iil}Pv2art zg@bO)lf#n&4wNs)sI(UI55w-;myPd!({6&spRr? zoZ0h>`jloQhO_XC6?!~-9JyLN=fg;%8q-~QvUY+d_g+h|dyjzg4OjHv(BW4d0q+lx zlM9!+c=E~wTl?lFckS;duN@O-_IP7Zcc$4AVz%8G3IV?=h73Nd>I(2pyc31HRHjog zyX&vI4UiX;^=(Pb*Ww29aEE}wE(Sks=Y2M8RrUBAI_u4$GkwnzwAus=WQQ&V4ykMF z`K0HH(JG-8x`3Q|qakR-HL-mS9QjZea904x(u84-a9Y9~>CqjyAtXc=z%fN24@@vl zeP;sM!6rn~0p{`K>^ReLG7KYH?=ZI{PeJxITN*0Lg1b}$E)CTE06B$IXj$DBkY84q zjsYY;!LBQl6e*^xZGluLTmG*J*5_{htOn%mH-L1$p`Qa;s1~X`w8Vl+e(9VDPsew@ z#cYz4E#e3Od4+<5KkfF2p(~|H4WtRJEGXd5)P)@kM`j)9@&Ejd1J}}-%g!iz{Dlca z#0+};;DiHnWR*Uw(V%}mT+O^x*G<%I%I^rBrEWd${teqjig8MdV!JZaQ8qZdq9bo@^?JK?7qACG!&Kyju&Q{S4dG1! zbjZzQH0Ia`w!TvS|aZ3_wINEqKs@t=C?IIdWV-?1_gJi6ceR0$$DD8n~;ky6x%*C2TEa z5CQ!aPdx0FIAXm7;Woh4mfNm=K*E+J#6kTRmmo}EL2y@#{|n;B$u?-H-wcI+G(%yJ z8NSk^K)yb>Q$$n6G*RS(O~wp$~OfDw&qXkw-hfdF?e-e%j8F`*ju> zadcQEj{L`z7(g=rpe4j?-OIRJg8UEvk=?-&tA3d`|KHgi9H|RI=jFDUJV9iIfyw>V zdToagxg&XR)5|()h`yv}I7=!E>G6>Mg{H@Uqm$%H0ugHxYNqb!kV=^>rRmm=vJjA8 zjbG68_23f(pl%c&emWtX!PZ)gUP*y?Fb-E$1hAFX*zyx zD)rv4I$RvttAnGz6C@;wA&}FmEx~MB;^s!X(Jqe=uH4q;1%kj5LM0i_NEk`u8gz=U zfmjywtJMLJXH{p@l3H%GTX@Nn8{VKEOWJQ=*Mb}_HWyXNxq!mlA=ci<;j_#xdF-2@ zzi8*ke4W`YZ2nVyE*vJ_AE{7ixwVFHX^!g-;>V7-Fh`2@jp_q|#oN$JV1J*Q_m(lO zvkb{V=8rGM3RJ=B0!AO{SE<3EOMd_IiV9(*%pE1L0@ct2)Z+iks2yrLJ1st3PW|MRNMEBGBcw+fYRQf8{} zP_utd2jhp)slp)_UV=e>N?mJ316k@d9fv&T53jKU1=rA2^`yP}9o~C|>mzrAyskF?y-4z;>B$m@5+S zs%HWgA4vJ?VBnA^Gn{JWxnwJ=1L;*9IW`57qNHTMEM&#`>aZqMGI_j^#4n=dtNLFU zjv#Xw*_cPgiUpFOAltFgh9rTEUApHaft;tz+r(t+n{ncsgk`)l<0Oz#D#)g!2M0)) zUdF&=1JXDV*YtD$Xiws+7{BICv9*KwPT5+=tiY@Aoz-(4kFmUhgUmmAnu>dcQ_LHb zL|jMSdahvlo9J4PY146(c&fH8*mY>#d>_hv+4h{ddD4bMhNXpSCFQfVxaMsy?bj)r;Ei zhT-0~ly^0-r{J%d{-gFelfymCQU&>Mt;G42-;^bEJ8a zJHWU7)DsJ*JXB1VK?k_jls3bxRJH@I#%Lc$o}1*_j5r0?dC6DBXw3YuCZ7SXqSsjX z(H=hkkwFtb!1UM!50`~F^7F|F?afy~H2AnCOK=rkVi7P${&Ny!`C&Fs>>ZFhI=Jc_ z6_w;DOppE4%yiNWmD|2HP_X@JkMYDBwQCrb?Cw~th>B?_U%jAJtGr_G@G5T)10cx~ z@+cOiQem2rMOm#(Xe5f=d@naxoB->u`GKgJKK1Xz>oitXjq_R{T0Fntv z&I&ZUTh}#ISX>htbSkegTakLZqWo0?78k>XLH{P-DtdJ-ECe#(hnQOil4(3T28)6G zm;dOPdohrp|LB;1v6~$AcSXUb$N!)s+c$fWxFR=s-k%$5sOgFF-^%TkO*JG_^mYC+ zBJw4;P?DrJsHKK3ae}8aC-~@s5z*`&G4tNrYeuk{mj@{L`67P89CeKF;^q+^(1bba z9T9n_vaMH$xl4|Y`EP!(_s|%Wos0nQ9ToYtFhI?IRtH8zk-?5CZ$%(8C!Fj(?Q-um zq;O^pk!H5RJ=EY&o8Va={B6|WLJ|F2Z$(h1@1ziO*Bu>$&6T}J$K0DMdJm2H)yw@1 zP%+sHgM<+gyd%KZ5CktPFkvJc)g>o$W6-p?m-nKgjY@X!8G~g&AZFp$kZBVlN6L-F zZ0x6EX~6woZg~XpbGe_|4jqAQ{&{2 z#>;PL@(A$nC)cY_H8!7J?Rxx*PW@b0l+Wg|SUmHjSamzK!|DLCv*D$?MpTGadiW*Y%Yq znC)Qoc=B9=CqGZ{7*C=YaX;|jm6na*1I*eSI?LjVze?&H%*W64swtVpNB4l_jrmuNHkXCG8xMKT^#Zw*GOvsl{v?@;a6wC3AqHjUUH*pnk3de0%c^xV zi&C;NA&evl!bdDJDF(&rE?KNX%UG^KB5X{?=2lMuSwESII#zeGe6jOyz517`Ql`(O zub8I_BuHHW(U+&%1I6F7Cr4Wrl2yZ{v6i`kT$3Ct8zfTt4!DhuAA&E~m^0>JCle+aA zSLUy;voc*rPG~&yj7hWb<Ka;CZ<6r%cnU$+aF{ZWIK=KU^x6p$I{sy9!KX=oSJJJ;Zat( zp?Z%;2#eQ;us?*#Bbt{APUeGU^k-{pSrF#EtqS6j#5`|-z*cvAE&!qHN?L~ z-rP-Fq|M|?PTqWAJ+ZUrKi0~d*CWwevTVOTy4RA< zpp{nYw>+p;dFI93ccK{FUgZ6LvXxf4LwQNH#oXVYALygcDl-GiWB%{Iq}aWEbg!$c zJx^hAA`&_t^%z*L+GkmOTBmV z5yYi;g4{!oNj>z~rT84vDU%fahInD#{nZ_7?!TdRe9p#T*bC9IJwjP^jYbXKu*lR<*MGC7&MtX zIT^{jXrrrH?T-3$c2U2pSsl#WMR&M3GCtlzcL9rp@17pea_~rU|2@VmvrSLa7MO|~ zr@+qcvXU0sRQ&nQvfwS7j8(<>C&~8*bOBpCQuo3XvnI1#Ozv~BXVX5qL(1-887!6% zzp1T0HvqQ%6>$yO_E)fYFE`G1Rt^IlW1J|I@G+>c4)}NrSfF;0myFcs4 z=nq``jX49y=r-voW9C50?q{WWMk6bAATa+{$YKb?`8Zj)1J3}L@Nt|y?oOy zx?N)aK>xfP=0|K!`JPyOsGshweSvP1oT?l<`2fp-btwfH**8{B#eYAM!s5<}6c)EnT*hL>L_ghYap0$^-&L)y_1I%ST*=2^RgTxk zMk_7yWvLl%Hj2H{)AWayR#lD-)iDZqN0!&MDti3Rsnlq_1Xg*;Y(7T;`31Vo#kh1k z8wb<|fZRRaLtlV?x)=O*u!*jzc+*5beG#ljf!sEJSxO5_dgv>FTKnniF0NIQ4Xv4% zB=rb`0k^#fi>@Aetad8?oe3n{u~?O&+iT+>F}a1#%e3L&(o4XA;N!(0HU%@PRLqg9 zD9CBI7T`OnkiRr=Pl2mM#s5mvTpW2fQG!vaxF8Z1jx>bYUIua3Yap_{))Mrn%eUpI zbBkm$mw&R;TqqXiC^yT;w=LghmRj9>H6kVi31nZX9;&s3-b75-=^Ey;m#g9mQI$My zf;eLsoaWA4*(~RHGZafG^;96oH9!J*)zzxMy`h2z1?*O5;D1wj^_1zx{<>{9+dtlB zzIv{cCnlboKo@LPPj`xvSu!Q~oVDul+G4d%J)o>tH>!Qg7M>p{uFol7ujZ^PuCG(q zD8`t(WSyF>+GFk|tY2en==jRlQ8!;H{lrV&Ye=Tc?_qD_uYBrPj(_1WEkZvo^2d4aYBO2+TSS_R;w$iZ0X*1%8kg)2u<+OL$%Fn zM&P)*zk*5Y&5jwp2P2id;N(sYwsZCq+QG;jJm)l=tSRemzo;R*NoF>D4t__2PKM8$ zkkr#FvR1(SteP59AU=oNaoVUcXBUNoc6@N#x3{6|48&v*6Na%zXWgYv#pNjpKYEv? zbbm!IooSwm@0qYH`iy1sJr13$y(c*+Btf&>73Jnh)f>HGYv0`~SZ2ZwnD4*(eAM!z zEx%@Q#UDj2EwgSbD1X+&eZX?6Oha?gmDJSrW&|?lhEZYc&fmAQ?C`q^@_Nm-e1sAP z`;4les6Pz+(YkM2SNkS)!!~ZTpF7e1G+=56RTakkTc9wv_FXFpp^_8HsL5Z)>DiX! zfwjwKsf5KK+f-`>qd~*5TecO<7gjLp854%`Pt_N2!<$O-op)P-opI+X zFRJcaor3plE3om&mQaE#$*;FoKqqUbESQc_y?~1XzIuKg-{D;cvTt2oqtw_P?J`Im zLn>@nqTPJmL+_~)uHLb~qOS3~$>*{V%UJ7D)3HCmtH{_iewmw3G+JG_Y0 zATRN+^2We>=5}x6alcGz_*vfN4{?o17OOzAED6(s%2v1ReVZ1Pk&q3`ctC>;(G4`J z1Bh-C+)J%pxwqAfthnmUyXFa3^&jH1ZuMMhy|S~M_&3aRJH6hKCs$qW>y5wZ3mTDZ ztZsILbb=OGGgt<983{oe>!W0n_2F&Y-7;wW{WfNipaDJpPNyFKai@N6c_Y{Op0Q@c zlf9x-^riWpFy)lzsrDFTS0;79JjL566Os2ml*(O8wwb{)Nt<|*io4j7ahDyby>Ca< z((<@^dBnI~Lk|_o^mv5!P+|4O_GHG8)DU9*H3WT)%on=WWbU`uuj!B* z^D5V(S*w>5SU0P-u5o>ICtvqaLnz!btAj-czdJpuooUIwZOxpla(iPS5sj=wKJVVU zfGBR>>m7O9n_ks=yWF@Ity%3Mf@e)_T_ZbJQTLGC2+q^tjoXd(^-)vK#;yHHp0#9% zZi{TF&RJ*hW!3-Qhz8KIi7+os#{c*h!_Pf~2RD(xP;K;C)@9W{@xLJ6cq>IS22&Q~ z>jgXmdjsCaL8Ea18vRI*f1=Cv`5i1q^S(Z=6(uwMgz1>}k37el$-kga+x7U#RIEd? zgc^e0MgjlDc;f)ycvIC{w08Aup>*JzJ=a|0O0;UV90RYH?DejyT~f_A-i5ePZ;n;< znlN1fy1L(k_Dv+u;ekbT zyMjEz1K$ zZq2`-(Yts8-hD@Z+j7U8((+@8i!t1o<7N3m-jN<{N)TVsK*8uhKd zP|((XboBYmtkbiqk$i%dihJC=_c$#r`;&GqT>Quh)7gRbjqGgV`iIVF&L@`OB2~h( z%Jum7^uNlM-0|pkLsGIH-RgW|PWfoduiKA$7VUWDWL@K3#+Ukk&1jq^x~-SSX02wH zW0$&{S`FS>f6B)$4BUSku@&EM(no5(hv^t+i#LHTAczyKCJ=Z5Hk` zaszr?)rqFZ|7VKjcVs5>YXP3n4L)OaH?=tXC^*@A&`rUaJhKL(+X|w>{BVj(k0V{M z*KKDjL*3R?EcBC3uxDXC{$*!rHAoAGNyP~&lr342@)5E1EIKu$S_8al!-MMnifMVl zZ3}B)UJcRHYe+%bnXU4JX$eE63;&M7LB`p?qwqYsR*w%)?Wd2pjFBEl@;h0G8p-{q&}5Obc0Q3%%)@55rgZSgaRpS5&gonl%Jvchdq#hP|8SI=ZRF!A|zs zW7F%|i9EMm-Yv%(>SQAD@=i{cx9IV*Nw*zrrb<1oCqidQg&u#fGqr9>Sy1TDfy1Iqs@lo;vPlM;^us3Qm~n&1*FD7iW0z&s)5zl! zM%1szdpo&CW93SewR(9Bva)JHTGPl*$gX)PIUi}F`yZ`}MFBmYGkH0ZuEz&-s?nf# zJIkpgyySF~SNt%x@4?LkBWCR{onm)FL;*csGW9gQ>6%~tknQ=$=vB(l4|ma(k}XlOWw_9Hs6px!y9w2l6ThqFo!6ahF&3Z1!6l7POKd=FP?ug^MYu; zn_f+z^TV4#{D~XHFK!0$i%Y+ImVUdfLJvp3LQuv!a)CntQ={Aq+(%+!ckKuBaQHd)PhV1?Ax@hM1mWbe=icJ=)Eu z8*2#1)r>UrD>{`Drcub{YnkrI*F6mKp@)UY>?G#@IxTM>G+jCHG~MQM;D=HxNer^r z)G|7-Ib-A3H6wml(W$s#Y+r*^uE(!WFxst|4r$EozGW(_tR3j|w^R zR-#?KeVeIiZ2Ms-Zi+o}IMsG`7#7_WPPM%BBx^VQYwh+;pU~F6ffn)M3Su!`z4bkf zTO^0yYtMKiE&b4Tv{Wc!XBQFSGiGFF0kW@;^8BH#Yf4^FJ_=+$Wjb#fh%7c=KaNKB7nVouaw!Q`Bl%9&<18#N1o#ZnN7?hS%F; zLw0-Yhg;aW`QOuA3CPd>%LReT6T&SIC9)=?Wh%;ZgRs8R;Js2 zQr*_ho~0eIAp7*bYGm7YD_b2M`10yF8Fx>eRiyy0uC31q6yg09HbeTr6IJgfSIqo+ zc3KQKF=nnjX^4^R_GC2kS3BC1(agY(_A&qBTf*-| z)31Pq%X>efCwCOgHzv}4^k-W7eOT-!Kiu(CdgF7yi9n{CJh0=>)b;&Gx3l%Z;&hXZ zJKPIj#-_+@c(JpFxHINX?1`YK^!P~P7o!=V$4@4HN^iP`vzOufqC5E?(VMP$G`SZ% zx)nY1D|(MbkN<9}K;{!^Eo^mWt1DZZ|H)V20rJQWJ^tn7rQDDopQ2Wk(d^Aj z6t!-x&NqYe=GdykADYmBMa@#yiqeuX?ISAffU92|+xH+bxd+O9H6s;yYbb9yMROf! zgyT<{Q0trlWWUK*O?m0Q?Xb8!%n`yV#W~>tT57xRji1n)Y~PFS}1zA0nizU{0PshA7TtJLFbrbPR^1rS4r2{ledOZS}|D2>{ZLuZ1y6U;)UQv-aKp&A-nN0n9 z{7izusZmq*Zki<>pcYGuF?XQWXCo3iK(nPjDu^7(oXKJjKpMb3GSkvc1#vgESa#EF zX^Dv+5ba(c>oICH4J=LOa9o+N*uRx5a~U%S_%>e$*R~YjP|YyBq4GE_U9HE3gx`K` z5(c%gtl@&|*NUihN4V44OVulrvu`PGiv9exlvc#PLIKWy|2(f!wCQnW zV(&Ou4o0rvkGDXPaj-bBW;?PmZd$YTvCr3R=WJ9vBs7hMUp2FDOB8L6reFGU1r)I_ zNTj|OAUIB|_E^J8PpoU@Y2`PcUDh+$`o!k<+AOATWULrcY?xQ`)%_I)Yz=^XMseV> z(1X%se8o7jvAttIWqM3hgHBej;Zoj?fBxm%6lNnZds&Y=6R8}XnYT(H{4G5V=g#KQ`+x>@`r)ra%evnumSzpH<!yy3Zd#evO)E3HshZYJ)r@Z1lGaUI zGP>!DY2Eb2jBfgFS~q<+qbBB8x~ZkIo90$_)6&XrT9DNJ^!RV69)FQ;+`b{o^BcFa zkzdA{(REKX4W6LpGMT^wUgCe?I5n5C=etm1;IT^g)l=~grgv3N#ZM)#f1Yl>O^-jJ zH~VU0u`Mj74CJ?y{wfahSim);!0e$)zDJq1AK%J72zGOVTV7Cd&xV5UqR2MGQ}hwb za$-UC4dHgQq?z7rSx1_XskoU|TI#p4xNUvIAzIyVCJeIMcDfyvbkV|f1um1bi{>u( zQ_1G1X4^qJGmC`5zM+cE_?Zdjxk_0rH+3p2{IYWEA?1w9?3*(RFD2rfF4uz-4WgUk zVYxo(;ad04zB^ag>ra?2TkbF~5&v@f(8gSrA5e0rZaN;Mvbsd_k}h6W&Zu(IGw=7F zQKsWB(jE%;^iwEfG?!ytt9mGuvFFrxJD|*c0m*gi`LTWcq4iZIJyf`cUB%?poV;3+ z*WBdQdd+nFtUew8v(EgUJ=C&VxAoB6)r+fpXzA)6YAsvn>!Ag!t*TVQPD6uKLqxZi zN@g#$-0h{-f>sX+&+~y@m*!O!FsKEubV6Yb5zD<)TH&RZ1zu`3@9~hZ)t6g&U>)PM zHOgJ}dDS-3wA>ckj%=~*%WXtQ>0Yp{S$9SCfpt6V2bAe}Y+8>W7=MuEthf{LpD`Q2 z&8^OOMFjIJBBZ~T2Et(w8ULSs4a8eKATpj}zKx;FHfe_F9?B5i>61sOrOXWJ7-7DW zod#G*IiHoC#O?g$%OHw5P{{cZwyHpW_d0a`@8|rEzkP1F^h}dEyjNl%Yp5YI7uKmS z&l2ZJEE{S*)6Nb?ET+@>S>=`+dWO+eZfd#vIrTQ>U_?Z2DlRw_5xHBHPZTc|@2;id zjS~JuE%B~WSnedtzNBs-D_=*EOuixb{MhqbS&KEX=eL;4tr%>x@uzwG*z*qo!3iEi zMB-rV;P;=8Sm3}q%Mwe;$#uIu@i03FWTFmi$Jbyz{;T9k1D5v*JE>g?`frHm|MaJK2XX+ zdALm_+L1ATrs)Kq1`=|@$%YE#S}Trg*%JFM3G=qS6wu?p)c3PIzvi#|!Uw3^HrQ@g z-l6X0%p=|qx`PTgz7P=+)9%WtaN`|Ryzvj#TJ^W4oc{M#pBUzhIps$bG4N;gw@S8p z2Nlhh@^UJg*Qgvp9Oqr5}P|^Y?)pwOUs90cC#d521yNU=x z$a}joD|vo-hwi|kWIoE)P8wtxN8gMu*n6pa`Cxk&b=w%euwZEz7GK+IidikTH`IKC~ zZkBTUt;#&*@;F?0jiSe|)$3F-`Gp`x3)XUB@+9p%)rMVo0oLOy^f$F^>3yvL|0$WB zuE&4QBFO=ky8|R=f<=<`b7C+NZ_vd+u1gF-<)miLVL7b4lA-2wh)Si>P~lUp%7m7o z@(SNksfbEL1&>9Xg|pS{K(%_ngTi|J^Uge#Q>;ouMTW}ZJpq59*&~MY)O3YGq=iBD zDGe3Q0Lz?h^-P3;WW3JW0o4)U)I5djSfj9B8!FOOR=P4!8K_owdTI!8#!jD-g^@Z- z;aJ9^%qu?CtE8*hm+-SH2@Pbg!Z6I~VEK;?6)Z2Zp`v#fmMrPWP)a(g6_C4zp`@WA zM~Q1|l(<$F^r~iTP{ry~SACY?uCZd1&s5!Its%fKj{p+L3SClC=Re>N2bSIJ$pp72 z6K3Emaq0^dGbh-|yMq;p_@QZ6pnVK#_!I05HuGkuPIZgHzbzL-db~ovQs&v|ZdY7$ z1Z)Am1*H6TmW%n5Jfg=Hp~YiQ)Ck&wE$#J^6psxGK==pv$gX&*r}K! z)P);DL0ax=Gx7Z{yihgbh=y!zJu*;mjGZ3SjQAY$h^Pkk{Q&2;29G46Zx{gb0=>U} zGVo>nF^?&^g1t%4)o-l-G>@J9cHZ}_XMXs){3Y0iRTYstC%`e|^iL>Go)CJBVwWC& zby`q2cvxRQr=My<`E_}j0a*0e2OI0>myfPH=IQSptzT0xvM!e*XI{fa4GPa{n~5m= zNfU#U@!OMUomkGC9&dR|43!0uUBF-~b?Na%Y>&JaWFb-ppVjpYSCjy`kqVJr&_i2l zfm}z0NH6rz{#te>3do|@S$<8aYcf8cvaA5!}4xaBJX6U%|xRMPsZ((pJO_$$8)E7Rd9~=KIx41 zuJwTPi!hQuQ-+hhA~HNB??%p%iUgOBpn3mcdbNE)FL#4XxwU-ptW$TJ45J2oWoPc(TQucQ=_}H2%c%K?F7O}o@L?o7lliB2P+{2{p0PgfEzuMED4cEY?vPv*D3>`Cjbdvam>^Y^jUi=({%ySqYX>5n@i zkeNLFwmWr_oaN`UljNy7_VAf)Id34ju0h_EzcC}gvION#%))BhxW7V(d!!J&w7j}o}s)1#U;Jwj?JV=NXD_g7K=Yc73su% z>48eTw<2ZHu@Ypf#QW;^R&>xsmJaHY(%Q4zpYoW(?A;aj%?^OQ60;MpwRkcRJ5_L(Zs9DO64K*2h(~C^uY~s$e zcFwS&QUgW#&uKG?#>3e$f0MN{-4@ee!Sf&dMupixj{Ul#>$i_NnC83mn2=ik>&eY7fJL zrr19pPCYlpY7cKFyl`7`e$HwP`hWLRrfnv*!p&?Bg&Q>{FU{(=>kSdB=*Ee7^OP{h zHaNNsoJ+%twxR2;B)akXUbM)?#`*Z)f6v1Ch~B=j!@0?UnH4Y0F`Z^PAZ|RF^!+CD zy*D{cIOe&S``9Wdzura}(Rk+UoaLuzHIcK4v%zf6+FRtAs%<9-N6G zvcUwAt%iT5Ld}zbI`w(gORPN0%{ip_0_Y{FUXNcj$-XVZeIV6O#uF2VJ!ix03pwo6 zM6)^*UxDwg7b0_#qsyH#&8ZlKg*ClGUvps6E16^ zuyjQop^B5zc21Kf^ZPuLqQ3k3{{Q`anz@|&nR9v0bNN0?86?i9+#P80j9^+G7ZMVR zsOaIkYuQq=rXr#`qm}jh1||yW%{Xs6j1}>f`jO4s-MPV1!i6R!45}Z8OG!k{hdOQQd5^=|)4 zWvwB*3oAPZki9?1g#>-xy)tOXOzS*b%_f zl_$lju@t9wnAqdPaty&V6G#*_bw~7^Y|a@7rYKp-Y+#tqpZR0dY*l2yCh!x1)G97s zT=D5eUn;CCuqNT)Od@vuIzMwT&1632)}`T3Mh%&k&V-P5<@d5Vr&rGz2hG->WH*WD z|3K7`*?-bsjE}tDonTl}zq3Bx%L#$sTFIcTk%8y+vlR3h3JE-5EWo%PJ7~zv{68%1 z^u976$J9V&J@o0$y0}H0P>v>lMbVaNC*eE&V_>LvR@70v<$tfEu;zUe5my*~UPaO5 zlbyfR`Rm|Oxm>{sTqwHLqf3WJzf5w~y`5En`_Y3c(*7Vndgrh13&Q<0|L9Y(f% z!i6%7AlIx6Bb$@J-S3CuWFk#n7)I87f|bn?WOWj(Y>bG+PU3r6++O3aZTWjZ2bLq) zs;N_BJF92;fttxcJH0@^463tQL1&dCoK;gN#43lv(@^D5xT6*H8ZOOCaYcGn;=#Z4 zZC-0R`Io+@)*k9<_r2ct)Ea{W^&Ie>`94K?6upS{qy6Yjv=9BI&%O5YfU74V??w0T z00NIi9lJD6rT{G=}S+v-mKD#+Sg3PDRZniz0-aN9o zDeZF|KgZ!g!u?&gr@JCGqQSL!|W zkaD6EHUH=TNcYQVFrM65zob51KAzPkFR9=0bLx?4y^#Jl@PlS53}XtO-7G#Ku1LQ- z#Xo|;ZjGhJ4B58?pntCImEL8$&}0U%Y>>BY zr-U2>Ctvf_fYnUiPS0a9Xl{cx_lxetz+d`m*8UJglfMr*q_dvol339#RaPvQ(d09M zvy#IjRxS5bR&{%p$Z^W%x9eP^VD_+gV{58aQ^!Ort3^Lh9Lv0eYBt?j?f7~8465U4 zyyjkg1R-mh6Dc=ofZvdTkTOq$vyy<2Ql{TcLP#MR7s^D~3S$o`*S5pRGU)4ls?kXz z>hHp0HFg+J;8~&*1eYgU8>Knik`VCuEoo167OT>rL zTj3tK%W>)iQaz|+7rdr@DO*|!t2mOPV8jN@MbEl%5cGJUm$}o4)vSXJq&e6Co)(hL zLXT_`6xrK?vNAE&I&D z+WI{M6D>@*_Tt`1s24{@<)t^*)&b9AL>{{|%^ydf`BNKQf$HbLcFxaAO_DCd6!^A5 z24(4|f|gM_cLpgRYM?F0lc>6^6)Emk+EQB$yU-@Lc;pMDIcyypkxN3#0nJ1t|7+Dg zA*MbMEuq=S+lsH=S-snBIGs;o>TS`L${0l3ZlT#Irrs1)WIXd7x7=};=XEap{><`}djm;0g{Q%J zdaK4|vM22%qPk+aT_;0`F)Jocl0a{EVf&5ldDLzxKfl3@ySWihN#WKHDB5BtcT2cw zJ~azWH#c&D=WglJ{hxky&vk#w{mTv$b=%WDap=yuJMV7u*7Bb{?i^%W?_sZuP{kFAZJ)?RiC}El32eNumcS ze;70p#g8UW=&Y@7={}sCelns?rCjF7&Nb3`3uyZ~$pUI~vfYN!S9^BDjBZES!0ou& z6HyOEfu{l#by(+ssItO_-^;lK!B@1`?Z?`lALZ)P)9RF%HsWCE0;VMDX&Kjq*7{xwPhm`aGqELR{UZ0kcRB0 zlQFe9iX_h77pS*i47l9L{!FJ{#xFtKkxAL%bNO}hU{kpGk=bQvYejNKgUqzm5PM}e5cXe zzhtJGCD>{9Pt6?&rV^aTR71PKwt?x$6)l2}#(pK@&IW+B~bIdZ@wqP#~jYW54S}6YKSc<2DcD*sU&ObGGcwmk+ zoQxo6Wt)F$E)&>R+<&zD1hPU7W^zhS)v-ZYf~pt#Ki>#aWj2=&JS7by$ojRMM#hm( z#>QumVQPR}_gKpF?>c zpJVa>;d};($d-Ma^s0$JUMns3r&pEvJEd9r%9>gNxSjE}6-NDld_~J>l0+8y@f(`z zjKLW`qT*g}CHZTIBoaoKZ{?>nL%esjeW(whtk-;WvQ4|3lP} z$#>$WMrnt?fFPxgI{hn^Bm8cm%P8$z3_0lw)x zzoz1tA(QLexe@2>tkKkr7)aU;@NHT+@~K}_Ls4XpbnY8S0vxf8oyNrDnwk)cqn98> zZ3To@sG#h6^KAS2#|pB>e1X)5pSe8~96)b^tkZP`pSJYSw; z?)>r`cPCO_9^f*^buusAptt{!#$^ucOzTA}KR$rw7Hk$idr+lB-1JVhkoF23imgEv<7y6^7Zqfi< z5Q$tPYA`gNKF5sI)awShOy(rBOH=QN2?VS*hwmHPVt8{t<ziK#QAK!E_o9+AB*A4`A^YnM>YjR9-!{1bTZ9ho)*tCI!qmB zzGs#3T>1p7I1U;07~3UtYkE~;D<_IxO+7aFmQ*S2_H1g^RAmroyW_FH%L(E+nG4C5b8>A43IZ(-=MbpZD|zgp!_^dy?Jn$|K;N3UvR9!)jGzLi%hw{Sne`pun_ zEiB49EG?2W^`mycv(?magv&H{Lf^Iya+xo;-z_z4#CZ)hnwmTa@<~_~=J{QcriQg0 zlBTLdI7Tsb#C}T~$f+A8W2vW~CCk-YpS#F53Vti;-IcG`mi;jW9R9Rpyy zEOSp!7i=iyhA5pspBkGz6$OU3*_d(QNlMVcRkgtc;s_<{0gdH2wxP)Vl4e8wQ z70-=wj-=w8%82$6G#==Owqi} z6gxLlM!*eW_0S+kAUuxA4Bve~Uz_@YvM)^5v8HAP+|q=y?d~fsp|bxMF7X+>Wi>WUTfUFv*%6F(Gl$gvBV^Fu-$r_@@YoGMvH|!*)rVg9{T++rX$GL|V~ZrhKBi?!cEVZ3dYmWLF{1cjM8$*H`n`mdM9PZdgJM0N zCDwr+`lWH@Z5a-{iQhQahtBVD$|@r3?w3`}ONG1nY)^=P&o^fuu>n~(lpKsM&ih&tnau&2EeFii^q zVdGhn0azu!fnscuVAgnPzUz+g1{H7F;m5ne>b@{0K(qfoJli64wTK~a}4^$e{(ls*S!?iV6Sm{Gbkkzg`* z4sc7~91w`n8d3QuJdF=;qqkX*I3Z`}(h(i77C%dU{%!O&51RZ*;OxB)kGNvF=L6Yj zg}PoCgdNgs1R97n{y2oubV-i?<-Ldpx&9R`Bd?z%P4bT@MamrmSl5(EE=9_s0pLDW zk@Ef|@7ol?D0ksMU}gOv&g4#B=QfohrDWhc*;tB{!U2JNEu;3-6qI#vH{$=j8}SKm zA-?o2z{cQ6ajHb-V165(F{r*U&@VG(pt%IvNz8uGO#+#liEJgqh_w}v0BCts z{oDJ~TcfHJD_2nBLU{KK6B^5kN^;_@#l0Obhj=ck8e%t5zW#8rxq~}$E3pzdUF@d$ zWH*Vb>9Mo&O_a;vy7>ga$2dVbXGPjcQ>iq!9ZkHE@}9#cV>i#<*dCWl+Ba#1pHWVTswbmdh);yGe0pF3SOTLH=a`YtdPev` z_Vu~PCcWrRE3$c}oaj$`Ira5;EH@cT~m_Tp=M?|*k!h-Y%h zLNcKKbMRh3J~I2|?WB^tBip1($z256c{Wca)WZqVkQAtg^F2A9XG&qA=PMcVdm;+7 zTvQz%t0l;OZExwjIRx?^PdvTZIbbW5_ddLO%h39i=wZqh76PJ|w*=NCo=o$XW@3AN zJ5VkwmG#J5lDsdah1NmTv)AV)lYOr{g#E~G4q;_W&5 zosrJ=4BMl$fnG~kHnpIw$OgV8z^hAqB?Vi6XMhuteVTgqjH^aDNI`YkIi>*4V;V$B zAb92p(pYltYy-tRwr3m&WhXORdjjaPYsh}GKXh$!X~%((Bl)U;rQ<+INX`!&2#LwF z0tZ65$qR$2y}q@JDK~3QKsTVFwZolP`sOIfRWb`d^1$c zG7i-9C!aYam`i)nLXa~<9(=p;vIC)I$pg(UL#g1l0;h;qB3fB5$81Zp*pjB3AXL_R2ZA$;&_syI1w`ov0^_N%1ajwl(ZYMm zQxraVc^Th6fy^S?NgBoJ1+71&M^oSEDpw|(KbOlDhxu5*%yu$n}aXVZ0Agey~7ZM9!^m#$$a~?%kWH5x>A<} zT|tk8cPh@*%$W7(=O|j>-Ql3 z$+r++`xfF~pxG9IOv}k^hmu6a!fu8uU{XvKrCF!rwZb-L=2ji!T$J$48;Z>#Y~IkG zKON@v)^?}$?xK-2C8M$Amg4!O`($b_x&yv%Qu{J%v9+-Tz8u#%L2pZ^G5z=#A(S}T z8Xo~p>%mY$a>}Xr6E{$&Up0 z_6aL1gD`g-iYf5~>7<-x5#cfitYkDA-pM)-s@Y-1tzr4 zJC9kUeC~t!X%^=bz;xNsZAN#5eH7w+NjV=<-t##WY%VFD5PmA`y13t0)MH^H&57q3 z#*)hh9m)u>QVORjmSm*t_3@#626}SbBxkNm+3CyeJv1j*v6vxsnm+fNeQ63#HU?gF zyDom>yO_py^QMcE3=5F<6|OF)_bU|yq8;Z zT!wF)ZH2KBUy&M19`54B&*c5&YPpb{B=hA$GEYwH^_Alw&O=>HUT5>IazT%gNjuLZ zU)y`ryB8r3YkVzB>^88S%`dw9PQB>=S{5w4JD2(vD;cp6Lez>*=e1wS7NSd0_SaM#**IpX= zXetfPEc${lP24xIyItG++FP){t?hm0t(U&BlVn{(3blilOiC|$D1!huBDG!YMfZ&+ zsqLVtP=5ZKYA3mp*hnE^l)ykj?mjY0kC$-DIsMgQ1I3Ot-8}ol5zvgFwYtVf;EL%X z`IhNF$#D;bpdDtpuw@Q#F-Iw=D5Kqf!Ig-!S}wQ}Ll-RJF~OAzi`nr-3d1F&Ifc(t z|L9IQg|ZKh0}X{+SIu5^^^gY!mg3}}Jp6prhX zU;6Qy<@+vtqQ4t;?Aq&iF*zFx(|%+g5iXb>*>~ZSN1$Y`6NTBqJr_z6mlfezKOGs< z_0o^im(Tb=VjGTMiv3!5k^#@UaAdka`~0_Sa9&!`AKkm!$B@g)*zQl*h9A)*&I_i* zmwue^$i54I)9b)>HecW#!83gqOo^rtmw1NWx8)4IZ^sQkSP~iKnt_!H%WfcOOJ_Rx z7+zfTqI<2n_T4#T0YQxggi%rkoX#5v+L}mlaw91vW*ZV2g&(LPPm%BBxSvN&|NChz zLNg}zEl(;$zOE}CI$Tib@gshhAMuTQ5RZJHy!!ZN7I|Bq*u#-Aps`2dKAZ#+RX2yh zYYX0`shwd1fj6&)?K+P#A9#+WsOp=vZEkz}D1s)LPopXuNiCx4KV#ieZWXeMMctm@ zjlerHwSctPWEmDRVNLzd(23qyhOc5h#xi$Bp~p~GtLufc(-J|ywEgg-i2uW*h_^n5 z_`?#;I}Ez+WvqwQh+{I;lC zPC*k_34rgigfiAsR#oZu(;}y7PD-zDt*MM}Pa&6T;Vogxz^~@yp)#@`gY%<-MAaQ( z>>N~Iih&Qf91>L@)wTB-f{QFIPq|YF8_1}})6pavOii=2UD0ADo2dywt%ik62!p;q z_})Ejo|G5_-Ri|A({a#vi>ea`kR6|l`;h|421v7D2974~)vSg_8&uC~@D@UUt*hNFFQ}T;3MX4him59jT;|s&0R=p&zA^y4Q%pg&2dSX!{R3#y zk(2+HkDoKTveJY}I5=Ud*zulw8nL&}CN}ctZjPtw*U|2(H><>=8AT25?uw)%`$H3w zQ%<;beesxjbp+Y})yWmTntogcTe_&)Mv?u8lYf_Iko}}vr|6V`mAJ|GRlVb=dNA5u zRan$r@trPlaJCMrk6&tu)6!O0b=DtM=MD&WFR9w%P6?c?+D1z(>1hJ_=$y%hY>U$B zXo-Mrz~ceUY#5z44RpzHycz*uk8DlJeVjn!?AC@>2xa`#YI3 zY`Y*&PeobNQb9(_&-Hj1<*yVl4nXo{7($}9v{g#T5ekN7Ar)n1q=F1qQ)O*ONMIMb z7Z&hsYd|0C9hALP(9}+l;&$ShMv4=;$$dfGgapyU>;ZgMZ%e}OU~J}9GY)9i4UxQR z>@WmDI}x~BNZEf7Yzm=HmX;B7MG5DP4=jQ$QXJ40(HDlxJEkZ3r>EreS`DE(bV3ZpNri(iP8?GJN>`VpQs1DCb3FQt3y(RDt&b9BBJ+lX88_5}Z zXx(@(`-e01(^onu?_!iGbh!U>iaclNdt1vD?TXJSKW`&N^RU1uV+JPrPg3MW4y4?* z4hfoCpmAHcCgkYpgz$dKHCbm(aD3l^Uztxu1+~Ah4)J@}A%65a#NSc#%m3B2@%zqN z#Q&iV@rUaW&#p&&?Rvy#uSfiX^@#t^dc?2!uXMl8r+5o`MzW06xa)12>eST##5^+8;)58};!q9S z1l$w0;f$`ysHrc-44H>|_SHa~cl9{$)JU0}9re6f1Ae60#Ni`GA4vM_^phyACVW59FiEqiCEdC zJtYHQ_JD?+F6D+AZpLPLx}d3x^?G<~Mk_4iQtqj7jO(DhWs@8A+*#Ao=Ua<G`@jsV7-B-KU4}{-MHM&=6O_f z)}Bvy^aQz?FgA9(KkMME#$8|1)IFMdJ__x&u*2nia#%*9VV9vnQ@@BJyG!}d2j93Y z3gh5CpP>;e%+KHIAJMPAyA*q$9(%VQ`*l6`Yd%BcI+IIz*~i;a&x<~+@xg8Q|}*&zeU3dGHKv+ygO+&nG4> zB3QXA7LQ*QTUdN;@7#9^dPb(){2l21YHDUw@jsF=EC_SVxQnsI=h)QfQbDK7%Qf}M zHkjw>Y`P;McqKssR<4b~uRHdn`)r^?F6bGV_si@Y8AT%7@XWVysy-tHWo>#3@t1sr zqaQxpn%|OKmOK~P`F79%*%BFco#4UBqv517PLRH7hZZzBU0CUk^~j0U*fBa-2K#=1aqxjhhER;JlYG@kVPgN0 z%OsGFJQ4#9!&L5+F2Oq?14?!SebgD(>R795b$|!3`1{8YYu~1O0|F~!Rx*&`ajOq9 z&;N-JEaak8@Yq`&63FjClNMx&-Zr1Kg+A&`@dL$my472PtUf8KcCK5q>{Wth|iT4kxf24pZ zA&^cfZm9(t%20ET?Diw8k3MRNs*eo-vM?)wZZKdAU%Go9u@XoD7E7rmp!=Rg)`P6? zH?+Isbo8PDka+%6Lt=mP^19u1AV(FY#Z{tTAfV|CmSUjGs}$6M*4Cu?0pN`MRhuq^ z)obW6y3I1p?~v@ejxyLvZUf|DOO9WXG_^s4H#?jY2^Vsj09oZ<)G{K+4;aXrTBm(N zEj3A(zwf>nJVu}YuY8_&{&uao&_4bc-RFI>H7?UWMjI_TKiA+R+UP}MW!=s?ILCk; z#i4-$3FUknh~qEM(cmk_zhI{fK9XoTw97|czN<`fS)cbny^qH}qB{_>KOS(EVcTJk zoj9azw8N4qv0{PZ!+T0TqT7(Ob)_O5#Dv`Y_#Jf26$ek#EAJ@Ek7_u|7qTh)2|#AS{5&(@gNgY2^duTy@Hu_Ed6n<+nO zeA&&#M?F6VxzGogP2CYgQ;Gw4N?8!uxX?!?7`d}_dyua* zL+0$xV|1Gn*%<5do>?T`o-Z^*rnB=HZFEj2(@6Y1jG1=LkeStaj6Od!rq0m0zUMtK zsy?7eKIk`ApKAuPp>-R5+?jMa&U@btsO>)l!2+?4K57|M&uE}^2O|W=@(nQxtBwJ1 zNuiypl;cvi`A#%L z3yAiU?8|W}^*$JF$?v z=0XbR^TnmXWAq8ZBsior&p!H;u-&(f)(hKLJtiogl&v{QL;3PL z9y@aUF~A65;U}Oa@=E3R=nff)i8TTGJi1Ogyx|KU^mS^9K3+@o_5U~YAyDYmgiv`Aw&rWWlRm@a5(XE)=# z_U5MM2KTOZBqE#j=|46nG;eaJ25nD|Y;JHHgJ7$GZ34kpBIT}uF@Avzs!v4!>Q3(f z3$F?-Zp-(I_Nn|=_ctfL+iaoCAw0ce`Q^=+8V`+Y#(Do)-vky!mQ8vYU&?@qIi=

Dyxoqw$V+NkROM% z*{4DX7j!4#GVtcGY8!nDB^IvFl-yE5;dx(*g@8AQ2G2IS&Qf^(gEbAFWAq8jpgMZs zFLEN0^-`brrATKz3na1Ps8m_eAZ?@Tgy!y}YhMc>$JkETmA9Kl90L>{y;e?5RU-xh zo;Y8n>ztbUQw$LG*E^q>Am`@m?B$RT;RLqH@qb-@^7K*ohhwY^wITBz+SwBoav+MEmY3eyXG&;Aa#CPZD_g^b-op{~@hGf(TJ(~?J=igTHhA3G zCxgb5rhXSy;uhyXAJ)Q-iyIJVv#pE!mjh360ov%>PmO{nH^1FuLt8uPKJVJSk4bi* zyEguG(NY(WTL-@AtOu#>(9_KaX_k;2t{)uP3~MrK+Up+Qagf?9@IG#BZU}Z#kASQT z$=2mtO2+sXl0o&U$Q|L00~;@n*l?ls11>e+)+*KVE2_vhv zlpyTY9?;7`SGEk8onmX8 z`=_Z3+P!U{mloF<$+CgW#;^-nBkKNGxx(UT{6@=XWp08;xjgUd5(YM%X8+Z zB5G2EBl)`ayU{_C^}hFgGD`k9{`>s*Ec#H) zoU{IW7S+)woxEtVN(6SC^4>9P>S)c5$|tzK7uVF$4O=QJ-Thsab(Gz5wvOvtwr1y& z5oI5pOP#^>xfayY>UD?deYV5&QTHs8GzTek0M2@Y>hHsGFVQF~qV5U5Bi~j8nrdy- zKz7NfUGXFSEkEM-z}c>4{hsww;v9?h4|J`QBcKI&d;orH28PmvUPV-Gh=I1|Q(?m% zXB(sgx}LK;I)K+TnzfFffJR>rG1kVA_)5k&QtM_y3^S_Jg;(FGZ`zyB8E``$wQ>9-L7 zx3>_FO1&j~Gvcv5CBWDx1f+u|G0|%f%e)J!N>^1XYuQa+R{X;25))UM#Z9YBg16*S zjH6W>R&DY!L!n44TlJHCDXgLDQ*S&qq=Yamo{{0a2PY5kxeNTCCw<7uP0YHiTw!^h zXlh9FiP*~6%9VuSJG^ICp^;(n^;KQoa>bJL`f7tvM^V=juWePuDsgokP3T%K)zQ(1 z$`xbM+0{tgao>0M*U_{?<%%h(>w!9&=@Zvfta)Y4*K4fzRo*AxC*J?^{g*wkgWt_9i8c{ zqnBIi=oN?RXg=CiF?Qc4kW(9TMaM*>`pThI^k6)i~wzcHE&s_zW` z+6LyRZUX~WUKfV!1R`qZ&vpWqHp@O%s*^fRrsKEy#i}xY)BlH^&7~3^`yVCz`!`B> z^H(K+RBTY~9ON<$ogi1rr5qVl`+n9L->@g(M_E|JTktO9wzx$WQ}pFIu4quLi|%ln zI!~Wt+?CRN{{j#Ax?VU6pe&v1f_5cGYM_L&K4*|=ww9}{L*Og%i1_@?Q>bOD}EL>;Dwu2hg~wtuEylu{_3^rjmJ z@vOK+1}qlV?*W7gj^HiGULJt5U#GZfLiOaSIN+E%PA}U|09US<8ZuK(M%1qdP!?cW zJ+Sv$KL-7}NeA3qI~&sSKzf|#v2~%#z6E>ke3Z36(nk#ueqiPKgaq8gzL`T(tC3Pp z7y65e*$%eJ5`3(`wx5ojXEK77L6Ye6nWc zq@0511joe_9=qZ6&C_b!=FT0VTi73Em)&ss@@X}0rgKN=3iewWiK*nQZl7b2rVu>S zS&fvNDYDbxM31)(&p`^iAGObp%aRH<==frX{MjU@dJ@4igMJr5N*V=ZjhyPK1kb!u ze=`E!fZdmODw*QH!ozlr^pBFzq_2Z8elD*I$n5_^4>A^DP3)rr6~k{=&8E~Mn`pH+n%{|rFRe-Gd{T|G%R#I3*s zooxe2&OG1W!OjhRCJ*2DV2kN({Kid`TaNxPs7?=ana0jsGEKMrd*Rg_n^ ziUJudwEZ)`rIq*U$Z?XU_G!pI(8+~TF|1P~DM%L24p|rd5ah0dwZ8%OGHU-? z*BJ-RAB7l+mSt^eWij5fS-$$ zuUg*@@k#fd1oP!oj%8ipatx5gT5GYq<11^$*)4<@8`QKy9-%w zN&JeG8~#^}U&0E16?Q4zg4Q{$C?{Sk&>xN0s{WT+DfVBb0!r`0tuOtUxV+$pv57DJ zn7H_|3&!Q|UHD}A{tKk+)eFUs3|{!#BV#UD(#BrcVutng-HXVF^gre5p=$x)tne=k zC!CHxHz&A_)E760*Y$W#xcwi71olrZA(z8*9q&Kp(k)R7feWz7Z8$N^|M5A50o$uj z-W#qBp&Sz2>t>FwbEBR?*2Ht_K|RPwcqa$QP;@8#|!w)}iX$%Jry z3|sd`)P7TBj8jZ1JdX;8>ow=~nj1q}K69kejd}t;LgKYn71L0yheuHC^YW%iT`W33oI_zu%g<-H z%FmCwZf``1K|i8MX5Mw@S*XXrbH(5lEm5z_@Q`+uPg(DKuGrPH&i77;8D3emvpXT- z)#lcSauG#Ro+~<^P{isz8Ltx?(wx$f*WGuXU}h~XDm*{j^=kT#2=m=O_Zs3S^N*GX zZujr+W|^hk2^<$TskSh_IHB+8@jf0=cpeuTBf~?_{i=sY z9eK_@@&t2DWzpg^avl|2E?-H0{4SL+vQqr^k@ve9_Rj7kBhL4e*JVO}kXh0wyU0=b zU*vHa#z%?FlVLKXpDe?e271`ik{~3^rD|EYTtSt^!bj9MgQ`X0B7v#}x~DrYH;U=bIwOk?kEDZ z^*~6&d`r24JV?1GT&`eGJpVfnK*{})c*xveg^&YCF&->ey2QhjALcDd9@<-6oVTPf zbGQTS{t`N@I?f0nsyu!GDR+ip545zQ5b~ft%M~u;F&;eRsygj=)PB-*+2=I4ddJ5aIG}mogqM=waFIZXw|A z!R&T-X27jKX9NoLXTJT`EO#cpI+2)*8r)-#jHYjTCuOg5kN4sejTyIjU1>@i z$~rDD$~q@6%#!7sv%ZyCf+)V{TRD~dBtw0QSd@iA+C0?vj3q$hJ`J&*2{3jp0J0~h zl&UjZkrkJQ<>EvR6(w>A+cAL{Y`|Lr;n}VDzry(z2u}>~Z3(4R9Ub;57@JBzYld$@ z)nToMQmUHuw@m40&46WoDR00@t-Z)^u$08)a;3{w-iw^xmLqh-)ibUy?DeuA(hXNn zFUy;Al=|}7zO^ZA-{T9KmOuDyUoi&hK_PpC2L|O25 z#=t}(kV(t>)u{v7rAV0*F_5fMz&aMo8r{Q#*^0*4$^a?$$L7q*#tyK>LlbW=e9N8R zK8YjF#_ea(KDCC$pFsy9EoJqt^(w6nB+yJ(wlt$I%QN}v5G^*Ye6$r|T zs?Jzc{dbhg1w9*P;E5lA{~s4xh`K@(U|w8mziE$Y&koG+uVRM3{V{_sr~c+G#H(*1 z9&9le7Q#psl(nvf6);zCV^J29X(%(4j%vqN-pVK(GtR?V`_+H%hcHVQ>H<6zT-vW5 z-;dhi8GJW#rF=`j`gaPsA=~x}z@>mNW+-m^&v6+&?O%tUy)9syhqB&sqfT$z%`^+~ zeyZkEJflzM?c+LNL>GHLkm2z&9+!hHV?Gzkg*1=1}4 zp=MXFPq>|O5tt?3l2iivhR$a21&?^n4(F;QlF|V^oJ!fr31#I9LP_meiiVMO0nK(A z<|G!TEbCVjC{Q@Cvq$8NX2e6kVmlz?GC|NzIiU%pUoDRySvq1GJa$q# zVlo_O=iKUHLK~(RO1FBvB_h77m?7rUTB*U!cCdZElm@rC!&F)$J?l1f;6C4oXWfnM zm*zHVzmG*(9_Z(NNyH_MAZbJ>0`!J{HFG}}kuAxpsiAhD#|)(XV)--1xyz;0DvM%5 z#sIX;O7ZNzAe`g!+gxRHQGSaqKO*z|{pv$eE|b$Ol3&$SH8ld7q#(@;%Mj}=%|I6V z`_((6@sp>f{!OzJRpovaZ%?1^T3El#M^K*+xv-`_tFcu+>61L;?7QDmR5 z*LI_3BFH{32r}CejT5gT&fJR+NXX_QFbRUKn$cMMG~2ns}1zti#j=reps;NOKFF=0bm{8W*x7O}(fw zWtARFn=2J%fet1L@mR3&Enw3hjRH=z;X9}3?hTv_fP)>s;_1754~BS64l-Z1pcuhcY7-Rrf4gD%`hHs9e3Q z;=X0VebTc3m2}wyRh7%G60(0)(t`UdE0?WVbLai{-1CsIdZ<{)=r@uNm0Y#rPPC$8 z1)8^ThI{S<)22+je2Vj~rFly#m)@Dbq~Z!R>6e~x{(M_dczyO#RB%5uYUPTbZv^*T zfn0x+@WAB@r&J^N{r4!2vY;e10wp0ENS};X_DYBOsm`y0Sx8BSvVMfOr#%UwMpBrGR+zP~1!9)_4>f57&5<8IRG%qr!Mp>-UO(z+QI&&GpEJI%Hcd zva%LAI2GBELRO}b&uWqVwaDd^eV(?(u@tg8g{)5@8w%EhTxvpUGRVFR(wIToGyX9( zO~{BAWJdJUnnFcgQoq)z@Eub-a2G9)I4QT9712JHV0~#~WU?=H| zLR=sCT?87t6>-p*oh;Stg033SnCS@;%DbUN`5ZVd@UeqY&P9kQOA%2Qs`nQ$O!XH+ zOxaCP-r zNiA-ZH5+#=^Y;_g&-C{f{m}t0SABZ?R0m`)?ycL^0le8WW|?yT#yOLetC#ow(ysG7 z{N)MDxiimN{$8nYjU%WnX($ajb1i*`d46ZO*l&W>#D} zf5(`%mhQUqFK(JWrw*~f_aztod3jf?#!O{!oH~+*A6>!NkycHl#$^Jac zc=phWd5PPGb}GPLZ^3s;p?3(BT^iV4xSan0(_cJTH%)(Hu>G%i`;g6#zt!A9MEu;* z`ZHTQ6O)QqKz2%ZoOHKVH0aQR2($-02>ow8=Vn}tpZAJ*MJyTCBP-o(Sl?7t?uGTZ zv8)U0$o1A(D{eYjU~gn^lmpB)?+%$y|BLJ9@d5Rt&3v$ zuuk9a_J(!K;_{;+5dabYaKdO681Ni$=2L>7o9l+V(CW;R`}kLa0fl zR_x`&Vz35-Pf=)}NW7rfRz)kjuzd`gE=sjtYP-v&4-nB*)G>*cvm`LH+3e2ub#{Z; zKHt~p_5B0BKO}Qz&ilO2``q65v)1V#EXfD{-O~U6@Bix@@L?d8DIk|?Kf+8T#irUa?UCcd6fa-SS|aO{qINv6xJa@$qn(Q}dJ^Ve_95C83fg1` zA&gD3$&PVpMfN##N9IXb#!FD9jv=`WS2YovA&L?!`^LBUeB?Tom2za?_#rVzV)v1O z8S=~Q@nh&obRGKDUzJ=d<0-N-o?{T|;4&;CUN_w5t^Iku?3o+~|0 z+kr6f1?j?uyyG8h4Tpf_GQWovTJDgM%yXiy!@hv@mZu3N(Y$%CzP5ef#(5vfNTQKxZu&%Uq`&gmJw@V-Z8$3B_?)- zCJIp5LJ(UNvD%C5K=Oc{0Mfmj&H-)zzu?^zW|xda3TO2eMT#*9o%QsO!m~|<@+#xx zamHVqnMbHW9ITB7RuuI&sP>oD>Uv} zas0KFA}M3N8h34uERGMgiUhGaQq<1-OEM6?aaidixfuw4fUcFb26>8TKQ+i>4Ram4 zwbj;7WHcV#;24kIQ|LP*F&&5?w6cxjD)HU4#yVgPpB>BJl3g=h{Z#)nv}G*6`(M8= z3o;!?=rXi=CG*xAJQt` zHv)y$jxNbQzHjAY+8QgWEQ|TZ54Ap~-2rAN6Xl&u%pCNM2Ug~Hyf5W^ zVOkdSkpS8n($zJWaFGBqbLQMjxDHuq+b!#lX#oK8w~1p~xBF0BfG%%t^q96ynB$7B zX5)ylL_qwL)-C)=>vmfQK$ui&!YuBSgXcGI`hJ@gzqI~a(ct;sO~$C_94dU=Ym0V} zVyGDqJKi*Xzpb^yeB3vF$fK*SbRFRhV#oK_fN)k3#}9ct;{lJZ&PmTDyy2VzRaZxM zYHQqkgUHn~9=Inr(lQPkKrHm_)LI3oDvEd<;3)L@h@0(_*4z!`%j8MLhX1LI1b4_R zaWn3!;#lE$;GTkL;W%t6iXf2@w`gnJUGm|vK;agx)eU4kDc$A7x~isMQ?_Vp1d=(0 zzf2ZFRUI!zI_m&Cj8)fV`CNml_mos%@Z6h?x$rSMM(kI447vD zUlT6EE#rZE9UX;oU+8h;bJ}h0lH&)o)z)s~jN<}EBv(V?0qr&+-)N%Wg#sgcT);ry z)scvKUNc3>HQ%IU(d-7W z1KFCOeOptzJ9Kqg%F(e?Yqb`(QT{_uBCIT2FN(65TSB?JAfb{5H^Ji z8VeeL)TgYC`3*pPsp$>6`l2r5yhb3>1XLh#+6~{X5m2J?~@|1v?eb%YIz48uOBzf!( ziP^XV@*KN7K3N>!v_T{+d#lu0U)aT>kV_qkEl z`Y`0#ee$E8i|uC1m7ecO56bg{d%pjs+y^H;?}nbI(ry4E`w$47VVIlKoO>g3fPHrv zkpD`6Vs9^kaGm^;TtN``l2j|(*DRBp)_CQk(lVLtdpI**$GGlY#W_ePvnsdH z*CV+H4h=H}%j9m^Ll6@%nvQ|1IFc*!5sOIcJL~EDbn$|st9M3x@(G#p>r3mz%Hjw@ z79S&>2~oYoIso7foBig75*b7r=9|qoyfJ37Kkj8>CcjN`53rI$Le*8$d1d=oFx2}M z4DJ33hMxEehIW1hLubbffpWs-G10SQ=FN}bb(o0@%-OO0uKB~0Ep7Ojcr)W5CgxWd z$jjQkFD6?kbZ#Ut#&-wC%-xiR&U%16r!{OnZLO)zXGgcNY+UlO=hyghBqRcvlhIqO z5}mzie$JUAv9Xr%Ky{&XUNJZs%7>~o#h57t#4#n$$;LQ8ZTpqdLUi{T1tJw+!H{(b zhHAoeN0c;`G#5%Mr4oNh)1C|5%EKBrzl8)A9oCBGJEX%}+5A$us1a2U0$Muj2+S?; zSK)%j9AUNuMAoaYwUHHowCbWPl1)Az8S;q|$>@i7{Gn!GnZ~(3Q6Lid2Mm>c1w;H- zFa%cM;Zqp8g#+P**}!j}4SZoZAhu!jB8PQ#lU~z*dKebw&HJB-O)ilh_Sq!5`wPSH zHOvqG4aPDBL+7tEY`MXRU2-nY=`X{Tk{j#lnC`}vGLVIOQ9p?DWS1mhy0<9}eAwtO zmFXW{tE`^%vYl-JQm)PW3Wl6t!O#~^0{`ARK8&jPC{tyL+WMOvd^?aO8VLM=rJeQL zq=aH=&zG9oHRU2+hL|)Y0GXq?gQ4@#!X7CIF#)PWQq8rqo)7=)cYXi})@F*VMAu4H zkU;Gm(D*PSA0{ldk9r}lS3`{M<9rSIAN8^tYDvVb1K#p{4J~CfbUnBdvCevMxWm)^ zM~C6&ZC-QituB-~}%edt;3q#}%|_P8A#HSta(ynwIgvO<;b0$zIDa*^M|#Tx}JTBa`*fYTEgLO{3zb*JrRMqEhJ!RAt+~0Pibhc z*Bk|*wa2lpG&DcNXl&rlu7NMKU-ri#&k;R4mjBShWBJ`#$l_S*`YjsThwOvv1l(KC z#R~vPEZw@^h^d4aT-RH#haRFf$Aajo4#L7o1ui?UbPx+1Q|1q=EnTt^AJvKi(=Z>e zFgIZI7?5C^D=!~}ii=dCz9+o4qi4tR9}GAi7|ZWIq16g2)>(ocyuJRb(1TN7JQ&#@ zYujGmfPqBQ0%rFOd_jKss^%14)h@GIL*~$CuRVG~n`cFf_|>l_s;mW}N9pJt&udQM zgvJR4<3pPaQH#?QDa|?prIVJ_>amoXChWG9@tbIu?XV|%zHH!lA)?Lx>znE z9?loLI4hJgJASNvWx1jSMN(Y(6eWa-2JPh$>Bg9u5zN2yep9NdxXXT}y zLf;U5xsdw3cO*tF>iNT(uS=eeSGUc;TzqC`48Kd6%D*)T z^Zii}xp*_PLgQA!{F)dy+Qk%BbE91>7cVydeQg8Yum;G%RBO+HM7dBJLe;zI8jH{N z6ohtpov{YY#VgD}A}P90ew+GaoA^jUs5G?8TO8RSH{h}eOAtHT2jusu*+F`Gbaj_b zXXCf28a(iY)`hA$S0n~v2gx&SSQA(7l?{Y598os3fomi>Te^3Rq5#YvCiPu%0Dr&j zTmC#;D$m3}4PKIbrcopRYMmI%Y9os?XOuhy#F*NQ!8sB$#EUJ(7@e@ zyNHLUD?!gx5Wh1PD5fW}B(@kY9oj3;(opFM6MKAGr6FcB8IENvgw$UYOJyQfNGkH! z=rlY1_EpMaC(1YBEis$Pa?Fcq?LSjoxpmMS*RPH$mdf!=OBA!%&njM=ZGSq&m0vg& ztV2hBJ8I_E_3Z7*&K?)d?gL64r93aSQ=z<_&I81Yc@BHUWa{+`9fEPl5T$sVrZa?uYr0<2my5Q*@1vO*-k0 zeW+#pC!Ij5QztcW50>ut8jnz}xGKXHNpx80AR7$B%GxY_%iiB;z`58Jd|#&irS~O+ z*dtLri;EY7u6{C^Emwf9emGUOg0B935*%E-z?6?`u&(|s^HyZc$5h(AGX*yjboI?i zu-9OQ{9OaP8#CmHCgKd0%UZ?47 zAKr9t)N^h|;Zt59TLaX_rS>j;>kjPlw-Rj z5dNV!9vRwpAW`Km2tla8M!wPZ*`C&^wP!zU?RmDRG&H0<+au94oPk!p0efkm7*Fl# zxuYlB4_f-Ja!1eZ9*R5D$~I2h{31)+62h>2dpFv z&@aaFyI)qk=d3@Z=lwV79%V_eRdz{x-EcxPg3{r2B(%=Z}*p zvr~Ya%9JVq$nhi>p9#pGUAw=&MpwpwSGRF-tI>^ttV@a;k;`}zEfqWI`^IEO)3>*- zw|DlnQAz5OR~fluE#p5~Ln&IF&PczER!4X8pxj%3W@Bl8W>?F-Q&NyZo=(&Md-bD= z7KXVTz5-vGuiuBPu}g1U?9zFZpkFI|3$4mOd7tuXE_H}oxFAY7m?%mY_-d?{a z!&Ol=<(GT93~^*Q5&2!$2Z}Z@e|T)!Tif;}s-|>{tX=_^&6)UxmZ7+*I zD5Y>~nxXP}^W~3Z#?W?s2))o-|BCmE=$UPwtSb#gZ+3;wY@xdaEy?0SSDsL4FD5)4 zZ^yGSkW!5+FBn{gYcP5d$j>yc+&l;ssPEL)!^7O24w9GgQ_6% zK$OWmKZkFXXXEYOf@nFWtMI!CaGFl(YF!d!&Urq%%{dnJcx(ERxL$H?W`{tqZAFW0 zo2lL^FjQ}){LIq8Zbh!#7>Mj}GzdjWx_-4j1D> z4Y{iNp|s46$m5g6{nmjis>Wg$6o?nI=-MI;T~W{v4qN9r<%+6_D61jYxWb32E&7p8 zeV!EGzUP3KI1oUj62DNIiJ6Vv`=F{W`oS<_(eob+v(+CA8>%1C%G^MjHE=FDb$Xb+ z89iNtfn2Gv8w0oo9}Vj20llHWgXD0=UOtG(vPl8+nc2E7*e)L$2A?d|V-CaIPn12G z_uUe;=^od?c_zB#YZ$0-OQ*kvP?Zj1<&M*n!~I=hammJFY{RH}VepDdEoQ~+MzrV( z*F?0lUJJ9b0oyiSQN>3uZ*n#kxe@71x3__7S=1%X^*iM$(_Rb`@^!ci;|! z*tdp(duy2aan+h)tPODSS;$9q@V^ym=!)0lke3&;1h1%?71Px>bavxw!82P~lE<>H zqUdFKj|>$#Lyq7TRZMheo#E&wC!vDkbl{^(t9&^w!|y8${y&KB!~SA9S8fa zLg&2b>Fm5Ca-g4SDwI)mVa5kd*$UR9;T+l2^qKsU1rv*6xi2Nd1 z$%$CI`OAZL>X$6ncX4>;!dZ4xV1cLLe1 zG31p*nLj58M3^k~=LB_iw{FY4-=QP&tpp+$5)64D!HMPu+Tv`|kZCzrGiIK@)DXEn zF{z01DhMeM>Eu8l90)g50WWhP*q#O+3?T3Z5WeINuJ&B8cm4&whzxrw5o1L9uDvgUyT;kp({kr;!=D?2k z=v&~GDA%TZliG4g1tQbt0bgbSq1nlYb5EF?R%mYbsvt9Zh*=@`)*Jmc+32^?ljAV> zFDN!l+few6bkp`c^-oOMpjX;agRXw4{m0Y58~mlRD`;pckPG^4+t4E0mP|AvLfcY3 z#~RM}+vHtAtG`t4>c6Dvg%W}rT;>l!EZk!8m&z;qvpOI3AE2dup~5ZTIv+c$AmUBL zsogh)Z=3^x^OwqEuvp$V5g;COXFa0v4+97_;XHpXo-KCJLDL}9JLF5uQJh}@?gNH_qTBt0d z)o)*l`8;ZywAa)|VM@r_haO;yDa~`EKF@ z-0Ph-Xq68EB57@LlL3Ph$Fi0{ z2g!kJhS2<1BWP}+jF!4QH)-N_G}<+t+DY!%Up4UPq0glEHCUdpr~5wXc~Wy*Th}1M zBGl&~t&GKYA+%>rBmSg|6}WgUbJ>sX`Vo-R2^xVY+m6UgO;;yU0-n`~NY4c4aNMV> zOuAvp*MOEF_sdG5JiT!h6iVR8kxysEFu9FQZUMQmLE z)?s=22+P)KB7Ckug!0azDc(tW=t4i8A*d{hJdAhY0A7w~U_^eL#$|P{&BM%MSE9w0hE#|LpuH~+~s`j8kc)Q z7Q2z#So@TB<`J~`buWo^5F;pxU*lT7t#NaB zj2=Z~LHYrV9v84Bjx1^Q{`AeYA1EETG;X?1BDxp#Zd#*m;X2-7oRp3pM9$KWrP-9dH} z>q4r=KvQM;DCgPAx%fg zrC{z@=ByJXI?ODxNyu^QJ)QM6;VrTOFAlc;1i84AXld&`AnuiF1}GkDW|aN}#e~Rb zDT;?o(wdv}Q5pfY8*okoB4avNo)bfMM4n6wn6V@Bc$(U$H69?zgXlCON7Ef-Ce#ej zm3AY3Ds}GHY57c=#vilih~m`3v+zv65mR}ot7VgU!S?k_rROO2t}KaipeKAw`-UEh$_AUx6bqoCvdhrPxa8!txgejX#@)VLu5SIBV% zk$F?Hkj8ecVfLr1zM+#?8i9QD_32|=M(Pcm%1_`LiGo~Xv8?5K?H^w8g->l3yu6 zI+7%FwjgfJK>bB`_7^XvBmc8r+)v?tJaJCZ)jj%n#+Nw_n>TVe5v+A1vPwfv6TXX5 zJZ0O9n=XWmu7X(QMlRj}h%{+Z&?O7_%$@DBco&F!)&lu-GNUVA_NyWKd`_<1cxiX- zX)6pC-{0-!V@EQ+it1pMe5EJvOb;&-d zUG9=DaR@G6jA(=-d;b6YP5(m!knc_T8Nm6Em{kDs>l8S{Q6#b(PAaGC(HJh+d;Y4x|s77{SCG8ey@M>`HA9ByU@ z7jI_S9rVm?9n0@ldTyWSnwT{X_gSJemXKDrB~c$MF@3FD3{*GxCEE++jWm^K|BQap zvkZI3;hs;rfOMsgX|?;pvVX*2xN|LSdkx+oyMJno=c3+vsy|TtXL^=laU3?B>1ti? z#^3jJjpVSiJr9oL817sPWK%k;FX*b6rdGdmB9!shs=ho-^@%H^Ub)P_%e&|s7Rbli z+U+tvsX+k9OuY(&ooaU9OIYJMc^tkFGR89dt70nZ(Dln8dV!vW-D&E9M7?`Pd1kwJ zTjY=pgsX9P#8V4oOPaR%EW=4YQS^6rEv5FOHGH^-!=;89$FAuQ$j+eeC&GTKLA#hg(flesu{8pab(0zX;sASE{n-QvUuNt8 zD&MT(Kgkql`PZ##U$1cMYS-%^QeB?G$X<*Qc`fC@AR6sRKqQ<3(SeP2MnL416t!a9 zLAJY;L&uQFej~C*_3d*ReLJl_IWeXCXY}n$Cy(7^a2aE0eNINl&k2CYuFZ0GD%mnT zDHHEuHW{kSF~j<*ZnUT%R22ZnvMtP7Ac={rEmboBpoO8r>94%;@G#Um{gObRm;2uy zhFV&>%uoLV`7mj~4MB)Yrg`@|@j_g@1jzSNuXxp%Bmns!$>Cdq%;m*5LR>Ojey>0w z76WNW{l=@tJOYr{GZ1ij{*4g#7%tyHA*_pmT=g}?-YFdBe}lLz1ECFUGl8(v1i}+0 z`1<_(OH8~Gh&AK ztNViJd0pjFRLj!ULzDA^3|^se*Sn;Za=T=_UssP!QZ3q@)qT6F&+ zmp7c$VCYcs$J);hEgL=a!!MK55s0=XhHx4euiz0D@vJ7Qxjw83*k}jRobcd`?@ipP zt+wu2JEyYX1U;X3q`HGUwbc^Le>-}!w)%RP)GD`2hZN%!FZ!HDy^Lp-4#FD0%*e{? zy?H=wt-oCZJiNDSX-#+<=CCKIt7Te6TTxK_*-&i-Nn$bktyh(z{Y>j3ouTwGUcnEm;`%iGJQ z+FAdv@^;I?i#Vu9FBi|my&0agDEjbzsJ!AEaTA|ReK^0LnA3Q-G+lm6%MGB#<^7cB z#FO)e+;|ZN@lknIF*=?vFYMprE&4EDuIw*r{M7cPV#O9rlx~@=&6X9a;H_CF)jB@Bv>8qF%8ye{ec}bdz=h7U~%@E1zveTPI*&m#X;j&#a zx@MOo%7wu`8C-C>bAZw`n9S+|jVf~dq!Ovr5eqP49R$UzN+ z(H@$;Ioee-;A`LG{W1!~r%?-BiG7mEEIFqboB6Q#jT{O@nkPm1#N9v`jrNH!gpmLr z(_8^+5#d{nozOER6$Zu>k2hh?yS4QM-Nq3O<+hj*@&EEr&qVO(ww=j_77%rcrGy+ej4<(@AXbU zdAPj_7h{?!XVh8zNqbf8C#`q1uPD8vwHQ;6Q&M5E1v5ekhH#c@npCx5GU;ETL!(Hu^^A%w+xOo$``gQdgeO_$^F>z~3o%rqH z>EHfgD-c%8czPfZeslH%`)I~cA%<7(@4tF>ztb^d91I<&S@E~BgO zM?CE%cz3*+8EUuI4&Bx40P^$nnf5j9pWK~OTPU@*eR4O=CSJL=g#_+7bN8;b9mL3- zxqH_g#Bt{CTP2#uMbC>h?7f@AIe4Vs)>I%r;I+j{n(cCahL;uBzd2m8@R@isG&=+- zr9Pe(Wj5Z-*d$T5Hr={5;J8(y*mte94lKLtjk}v2oA08~LwBXruJoC^v#@9GHe_IF zuV?P2{tCLU=pJZXmf1W0GMR|KxtnHE-SGzjx89x6%BD^gh)&#km#)5+&bG5)K8!HU z^SMd87}Mx}8u$Yy5Ewtg#WIk$Uxmmw-)Hpy>-*hP?^<{oo=IaAihiCpay z@X7#?+cKJw<^gikt0UUD$M1x2;r=-+#DOLv8*oUej;E{|z&iG5^oc^@Bb)d68 z%UcYX@6N?QW@@?OEk1}_nW|btZF`#-Ea}b<3f%wlDhVv_27&YNeJcYL-%`D`n_EnC3+PWGm98z+G z!%7)`OQD*Ju2LUSagbUaKz=w$brulm9hAa;UTTm!>-}=EG@<0kti<*=NW9cp&te|u z;{v%L*d*`rqL{9J9=u0zrKPa{jbVV! z`dcy-MTcS0qW&DIy1z*R@z5|-ch(n5s&cEODlOwbxo3Ow+*pppBnw%l!RG^kQbTpP z&hT^$_F9>dP5#ejok=ov#s(0DVnb8iC_?mXxTOrYes9;(i+UgB1U&Uf5G_f))4S_a zYWbuyXb-a8Ae4rvhLO$xqgD#_e;H1t)TYUAS}8nU7;GqKoQoqJ^@s@D#d|?x6cp9F~FzFT%#>fq0UY8114Zqjs${ zZ66t+`HK^ZDGZN+BM0YWAe=T8hoHGhEi{_Dbzi}*9UAOD7>7I{zj)wad~Tj4%EnR7 zO<2I943G8J!!ERB7XIhZ4h`*Q<4g{PIU8*uz+3DXzk&PX*XJ!iaWL-6^G1tK9E=Nj zp6J22nCFYW7L(MXYi> z&^BjcYoc*nXnS2b7_Z8+#wgwu8n={*iX&$>1{HAqE>eyu-M4ugNw@iVJ})O$G7g)HBaP$Gb_p}w|4ZdyT+Y-6Ixg12{n>s4Z2{$Ayfcr9 zRE`T%w7~s8Ra%IN|DV~H6O-vSL2qp5X3*C6}hLyi!4MD z>~zI?>uK)RJ9X;OeRaPb<=LGP8wSVWII!Ij5NFhu*IGt-^LusXSY7QtOtUdOq-*n% z+H3GCocNq#uxY5Yw;mRJ8Aab3Q4Yq}=9$NZRyKMt-j?Sf4+Zw07dqC(vUI6mFd~iH zoF0Y(sH_|hth^@{K1w~U;*hf=mE?( zY?S@mY#fZ=l2=KLY+q4wbNj>tlds3kc`Hwtt8O~+@fQrab>Z^m%a;qwmwRbn zR+))&CMHUA4L(w6Z;7ei5N5Ci9|`f1$3jGb$giFT{*kAFw>T=vOtvp{(qPQYCrjrO zA>V>%b}nyG`ZN%}Q)P)kZ%!QL_+*>RJ%%zC{)H5;_=uG~VMND$;{l)5F{qRfYaWXF z#t->g#<_crDs&&rwfEL%xd5}IxBj1>^Nv3&Z{WpBBi@A@ltzpd+jyV_#n3_+Vivv| zYEhP*GqSc3Ht+iJrdP(M_9OdPZ#}yUExD=W-B8dwJ{a`A6oJcrY@@5?h`OitEX9-` zLrdPo@6|a!e16o-zESs11jO03)T3}&4Eko*{_gX4@W+a69Bwa)++yEo7iDG%&6E1{ z>wZ6u+6a?Z6mi)FyKOvhdvRpGU6j$1QRQMkmbiY+2MRqQbbryEB4CGHsO6SzuYdRJ z6U4{$nje1d#O91AlIB$NxL_Q9SQbHc$2i<`AbIXQlbqo*yDr1?u;D{@b;t`ET6*qe z=YTnQRkf;oxB9$7+X?&OG9YytvJ11RZ;s}P(TuUuOo`@+&D8E}pPRA!uF>4MbHKH= z&ty7I^J#(b+La@M(HSw~`SO>F5&u)683)!da?l(!r#q$Y)~J0otD0sViLK&V@y@It z(CJRA*QY@g?;836^jim5`OKZV`ke_ilfNe5w7N(G=ft3OAgyl5_z4fm?QLbYonB|8 z2*W(fX;+&A7uTlLUua+-m8;ss+EFQXGu1pyVdQv3Gg+s_O-NV&p(JGuRqNwGVp>F^U!2tOI2m(IS|4A*N;XZkJh_9kRFI za)af@oR*KZd4aH(jUiFY*y7*TxTUXo&mZ;GjUDN&k1Ma5K&W^Tc=|{0MP!~N_f={i z7t6&#R_>G8U~fJ3Lbw?avTIP3(XW79n4}p5Jf2hs2U2S6buHYrk;6US=~z7SKIksT z36H!LfRITOmV>|97!Y*z*+jiI7drd*Y(&>R={209*`wVF8ey{xeOH?cy1F?*6tpDl zRgV6L^xIAlw1EyX3z7=87bewR5iQK&2REYYOh+VHSJx$|&sX!L)oTViFM9=AKj~j3tRit*QL`E#i?d;&9z@1#e)i3 z%+I4Yrap{ODstk;va+s)07pJ-z&UXS>8fAn%KHZ?u9lJaxRqL!`*5}=H!Wv-p`~mu zv~*f}hGs;HIg$bAVIau~BPKzZKWDIOV|es%Ug@cn`gEEr&l}tzk62e~4lodt0Y(io zu9No4)j=0_7(JVKf%f_jwwE^U>6R^O5mkf4o{KM$syoIOW ziYo?F>JKxx_ik(%QTYEJJ)B4FIX;e%u6~xL`ll18)O#=H+snkdQgaF`H33Y-gp9;w zWJXawj2f*#R%slj(6^Zagr0 zIL~~lUH&99GLD!y80Cug$kqK6)79w?!h>NS84&T^n2TFYi*T|0J(;g&-+awG6RR<+ zBYWR(QJTWr(=_^lw9k~z@GoQo{y)LRZDql=a&B;UJ@tzLDW3rGtzoEsYnZ8~_k0%P zq(Z{eun|AFFR=e1`M&*a`@6lBQJRPN8O<>ntd?QN2Kj?wbQOr~j-_qw!E-YESgGs} z%Jg1IIXx#p&Lsp)>7xV*%hcOvz}s>6KB%mX!eum%lDX@H zVeT&UsPWg2Xk`-6tex_bLFQ?idz#I0nl@NG4jpd|!!Kw~qBZKohR1{wWY^ z@LmbXV+mug989a*b<0pPlaGj8d9kH!rE+z@vA3q5Mv$_Zm-J@Ekdjt^s*fuj#K4`- z#EH%-?#vyZhxP%9CGEHhGtbl8om_eD;OSwe07R}Ab{P6})sp7QnNzfOzAj+XKKH;k z?G0TW)Gyf^(+|uF8>TD~UHxmu9-36&OkJ{vXm*IzLv0g296Y~l(_z^Vv*Pc`lWJFr zaz>ga2lfwyI-ygE9q>Z+6bSigE~DypsdIpHp%^O;DF)X^ zQKRd0%p{(g%CP7R|4H609~*`{`5=&!8kKh^GLgQc8ug(ZNmF}~uCft#W5;W?@}K2r zyaSP?auI$~9*|S&*~GNq?z*Db|7d(*K$;QUyA@UM-JDWQ6I6R;qBLspvIg^D@JCYi zhRhFSwD?m6RTV{OUO=rprf6XUen`$0rsK5wLYl)HgC^-!dA9`Q2O2#gOj44#hPQ?p z4#-+9%j0QGZZQMGVflNqu6`7uxm(8aZaf3e!Ht6j{XkYE447Fk^H}qmgP95 zrjnGS(>ZBK4=E=#$^FydY-u@uSCf{f)CH4wOTW?hz<&jy;yP(6fBKO!HE>L&~-I%S=>%c`&8km@t%cgL}53>OGrNYJ0+oYX%IMX4Fv5bbW#= zw+vEF!c1`G&qUVAJGP?g9h+0?cM?>`ps~kyf+^LN0B3UWKqA-e??1D3(3o>PrPgJn z9la4@c@-_CIe~jNlhbr}rqrwYv-;2Sphwo#34OP$tE!%jh^E!Q572x#>LcrwAt<=B zxs){S!{JhSe?kzT%5vKFGxle@yv8FmN1{?gA_(Gr)&U_C{jh6{CJ z-WSiro2W0pChU_rysDpdpt-DUyHCJeV_My!Q=g}JU(Eo_J)eQKhI3@*XZwR?Kilaw z9=TP%qyNw_ETTS=!l6?6oI>BMQiB9S?ohUTi=-({GE~K5)N4Y0D)i<&34_2~#$KM^ zT+rx{bL7(g9LX<{fdV-c+@V!IJ`T^Y|8ah%G2tBG`&4YW!oa0R+nkdY@)lR(?eqeDYbuq)@Cxv2I#n`PCp&j zmCw*no;A3k^h2tn4os@2wet$&x8SVDnt7G_tEr|Hz(qI@+xzM7Fla4l^}h!S`qS$7 zQ?rJccp>#A=iFKc=l(k|ZBANEOSIf27xY z%aJ{!ki+8Y{#E!|Tru>NH+f_~?kkNABk#>pZt!9GS*h3in^D$)Pg=VBLPu==+P;t_ z;0jo}J(&I)&bq)sjS;fG*%vj&omQihtMI(p$>6DBRA3o3!c9_s@RY_24@*_ub0)eb z@2Gt&^pv+MF#qIlM{|vT2>pJAtNVpwf56vGZ`hUlaDa~PtuB9^iRYqiUdz#6haN9}uJnl&HwMZBeYa9S zZ+qY?g}k1VGCVYzzEP9?zQWr&>SH_Wvriyb{4a=0b@p%6U2M0qzo{Q8vs6(ZUY4r6 zFHuE|-)NQ5%GNb%x-Bp&wJtAa9}5%Zwn{WWO~y2Z9WMa?cY$lyUsM#KXYVv9h^HEu;S-Nd5-pdNa^wN zCt(4QU;ylI4}*cv+=1Lb(G`bEe{8RpIr@MX&h-bj*zO!hw};`z-ziUf z4#x#1MrZ2AU@}eSOgyAbPg?UUCYWfydnuQ&h0+~(Ydxf_jp z4Z8$8jMiDv4whIa#f>1En#9iRttEOV&YjWgZ)QL^WCCH*1j6eknuo?=L~hZUl4WsV znZ`GUL8S8ios4WFExPddK1BQz)G~akA+65U8FEwu#}my@-f*+VE#>S5&ll`qNig}6 zm%-;_z0F;rGY^2sD} zB-L{X18zRI0Fvrg3C~C!ASV~4Fi$~J{YwHa|HTal@vHa+Ousz|N%hSH*nJmzAgK-{ zkbT*Oosd*tO#qoW2?WwWwxob~Qn}9~^2Wa+I=Vw+^hKQ+sL zG2|@`k%bx%Q<~;LA1>u~tQobih8@)7&7pNoJzhTYfVbobB7aJoFs1fkoK$yxP4BO! z=;fo5pVC{haWnm0xz428nP|D7-_yFSFSNruGwMB;cTej!+Md4GpGc}3zs9kF;y|d9 zjV;TJcx9rsyU#TH7$Og+{Wlu$--lt*VViNsno))|WhgVgj+QOL|9ou|sg(i@Hs)8DE3X%vy$(zKi%+lC{E{AVhu zy1%B!H8rN!Vqgy|3z`=At@45!?sbYMTFBbm5_!Iyn?x6KlZNvxOs>5nJM{5BaavPu0)Sp$- z4gB^f3r-#cHxGjFj0xx-7I+ZKco3E|AXM-mR5Z=?TjdhD+nXPy&jPvIYm;)K!VPwR z)kc%Rj(Q8`G_vIAgli*+u1-YWOYIxwS$>D5&(^eNlx5AC+2>Jq<|5-C|NhR03!d-S zIO%}K1P*Ah50UR^Gy3LCbZak%{t%io(UYvgNcdnF?ayhf#vf=9(AC*#M4n6qu;tM| zeooJ!W&$BPbuP81fu}Li$)_{)Of3aw}ue;y(R?5rfSCm)b}pvJQb?N?(iV_KB~98(n-t2bY)ZNSVGk6vB1#a{;0ja_C@5N(L2+q{I8-b_#2FcN zCSlPcV5>NWwk|iNaBtJn{GW4El=(h0-|z2#pQk-J`#JA9=RMndKCgbTZ;amI2d4B^ zcTvau$>wy>k2sa#b&rOMhywdD0{MMH%#DUr~N3U)k z;&QrCj;q1MQQ&kDc^!dVK?4WOTCYyf0LrTm95BD&O?7Eq?ExH%YSg-j);W5zd9VxR z5P2s92h2AwrMiT`7uv94MX7U&+xtl{OuZQ-lqUN=3T{*Z_o3^f zAX1sQCKr(%?IW`#{%-fy23@;E((6K_e`&xs3*QG$xV2LL!pE+gfdSdj`Da(l^(ao6 zmOH-a(4s?!9(efBp+hUGp4h(qsi&TL3KBR{rSu{lh&kQGUh?MygID(Y;%Vi~A z2_xZTWS;9EfhxCz+bAJ96PaqMa?g{Ry;W|Kqsdgu!G^W2lYyW+ck9-M9Ss=Ss75t-qNnmS0`nR^(N`+-ML$LG`Jdm4czO&zM|jSq^z;tq@nfhpgWD-+VERo z?Ne)>13J5SM?;wZYwwPLVg4@-z@;~IMV-E#20Ng`ib>lE0(KJ8M)89{f zTn_{wdt=wk_kXnD*+Rl06yiVYvx$;$%|C(HN&$^|1MaI|Qb1qn@3ScffI9FD0-4x% z@ri9Bo65?XWqM_E%XQ$^#7D1tGt*tBcA^$j=y;VX3 z_eQAnR=8@nIn`_Ke5YczrA6p+rFu`@P#F&kN{FI?+twdqh}U%MN6TzW#4i>;6Tn3= zn${NKu*;MNI=owXrU$3_Xy~v2V%#;M!vZ0Oq#4FO$TrwH$Tq~uI9@k5o&(z8AUh_J z2D{F2HbsYTHJ)t|=5NDkB^LGZ_8xpY|95c*d8LmEBI4@oz zX^QEqK4$Gqgb+Wdk1nCD4o{tXjzn<*uQ22Wja_yLBkj?H!u;kQ)C!EoUgy?yxmFFd zCHv;NOK*i&YdAtx*g2J?yh&_)37*9nM^gS-%iL6qq?u+9@y)jxhsv|OW z(JHMMbWt{mSDcekl5-P>&@Tb-io8uOVk|Lajm##q;#G=FT&3VO3owX#qc?)Ll)pIA zmyG{M_^tinuPz3v=sE(m9O$ZJni9&jaW<`^hhN;Scl7X; z-KAaT89A)p0X0f%0n@{0cLNh$oXle1{BFj9IVfW%>YYsq1z?gCfN7r`Xea>F0XfjK zd!@d}44sU61oL*wxh!Rs%PYd@XgFljvZjyUfx{@dE1D)El+ z#7#s*PWluZlshFI`Dl}Q_$9S~9$#;2m@fpH8*yCX2>EuHzqb$c-(4nZ$vw1Ti(qc+r2koG&%HkgJE|hj8 zvq@|Z|AAm|SU4AHu;aS|@M1b(`pl67JsyvLInbC^V~-`-k{yz~crI3z;*j|U6i15) zFwu6TORyz5&r78j<86bgvppDzAJ$$Y(z&5Z%YmcIP_$(pOHej;W zUU-Xu5P!4B+DSr)5B5NsS{G+av#Td0mu1>h94gxwI>ixdOR~on_wtK{F*u!W#2D=6 z&QucLa$=mzf1U&{t|!hH=ZWjD?(ZX10hqd%V0qD$5(SNM;}FT%5w}2K910qrUtrs8 zfpH+(!cn4an!q?xWW+_x3Dr%Eqms68649qXpdD&X0zp4zlUtMRM6h}KTswntD@n#4 zWz*Vc+jrZ441kv!icHF($aML`6_7O)nJ~^1F!*gvi%{u0D}WIr9cgSDtJba&TS8+; z+<=Sy#eol&j8;5WB8Ems3Z zYZ^5anQ*=^6q!nfV$5C`3Ob-ETdIq~uR;)2L~z<}nN7!P?Xn`ojqQ`#w4zKc=5=@u z!8ns!2%yKm0hF5%<-tp*P2OH_aL<*ExEMuags8}DAYq63N=nB%2#yciiV5zyJ}FDH z1jmJoiV1FWA7U{A(6}(kO%zPGek?HE3RjJ_+bxy4`kos%Y!;KX#=P5mw5RLF{nl5! z8dsd_zLNW=RJb*qnv{6QSv4+8Cq*1}Cz}`eIl?;BlZYBjY8b};iuT+ z9<|OmD9nE$>=*7ef?=XBH?6{r+jYM%Rt*{V`S41x!ewyJlc5VkZON`bUS1>aVIi6& z*cM^;sVi;JznWE?Z|DH3q65i+NwwMvDX+Qk6c@88*_K?C;!d{48{FP_hH(L-bMG-5 zFDVTpd`5vtL3wEckE(Sx;K#K>wQZxdv- z6Fd^#8%1H>Dpa^JDrbf3s9VD&kS5N!=|v&S7|%#*R7bG1%m|XGi9Ld9c3Gp3>?*>P zj0t9wn3e>0UyqB`9^Efw(-m&W1nyNA?(;8MReRKqIQu5E)ElXjIATPK?iWTF_jiw= zD-E({gPY+bBwqO#Tu<4OUBH+-DcQTiDC1H05Yt*83{(4n|Z)W?Y#Q?jwb$`r85=Tiu(AYVM142)W^Rcu5cqAmiMY~0aH@Mxcd0*;W$xl z2AF#Sxc;>bivo>oDOVZ2U&u1r3KK8I*1jl=tk(!~h-XmEM4R$$sEG-VL@`GYH?vzF zL~_tm-boyi{VM1T%>%`}bLw|L6cfxNiJEvOCYX!m(`sUZIVdJLhD6-R5E_H?FXT|v zwE$#K>>B-klQ71JX|EJ>pu_uxJbQ(Ega@~NWF#>G+{;F=6|TVnj8Rk1W@8LW+)w-a zGUgwLjfhXjV{)~4~e@H36Y`xrYu8mlX&vYJWmys`&MEmR9`=#VXL_b&D z$1B6MZfj8=&-D#y1@76tMl_0~Jz3Pp|E;gI3(7VW z_3@|sHWd5YfH`5Nybb2n=j+_FrK>O2x%Ws{UVPN{sFe(=(F{Qn{k+*MNTR#_cyC$f zUNc$K<*L$pm$_F@(Rx3>RaZXE1Tj)Or0AeR4=tIE!8;d+}l_jBh`yt zO_~YLBQMl8%=0t`k&5!?Rp)u?+$mAyMOtSs>f@{Xmbpv2VD&!fjG_@2`*>$xDM!fj zs!1-anAf;l03-gD*Vq^&R65@T>@G<;vD}@&sU=JO*fq&tY@1@u6Nr=~Pp*)lW&|P? z?_+QJVQ5P0CvC9!xd7hF?g{kqv-AWa~YD33DS z^ou2s=G`fQG`jKr>RS!V++#{LoLV)Z8u?+wJwB2Pqj`-OV{}Y6(lJHjoPE5iZ$xnv z-N)b4H=!B~xjs?8*1z^B3>`9sX2)Q@I10EU0+q%44eq@%`9;Q-hRl2VpR&>9!kMFphQ2f^b-Umd^LonYgd;=)l z_waegaXE;F`=|kE;I4%*eN(%Kw#y`F%ufMz zP_3f8K&xA+tT-PPlJFzV3Lh{?m&{_hg!@A2?XoD0+jzePje_hBKjt8j*VBZaWYr%; zH>VD*uuvt}X6Jd#o$9JRW@)qfW8fO_>v*I3V=RH9gHQmx+i<&aUB@x)ars~EFMo{? zCARwWJy{mo=`S>-u@W6{&xg`PM8UBpqyuitM_5LU(94@snc0>oTgq%OD6w1u zVE2gZc_bg_F+xOL2mQdy_(n7hW;aF`CnD5ABoxm<>6H#;!5e1Dd5e$+*w@(<6+*X+ z7L;=%05l&sBM16NT;6`Y4FAbgi+LOm7d2A0tqplXyh-VK!5rmhgm|^OAGv82rvi-G z>yra5)2ojqG%KwL5gnkmtgrH)c7))>FUAM(pPXjp^U9B_6`LWEu zl#|<%-D&MWB)js21X^ujgaiOO@(LGYP(|v1^TTK7Vg5`Q^wC!lBem9;uy+8Ch`5q8<>CO*rM1xL2XpB$bftj!z@3RJlNQm zWgW0}hI^np&qB5Xie{B3a@u8(;6=k>c&;!I@+@>af;3?uXg1}vOG%Y4l`galvCW+` zCkad4o-hBxF{t=xPw)nsP*aYW8D%s(tTmE`WEc#~6$U^gg#nOCKj1F3Q+X9glt%>dCpYKhw&Mnv>$WNuFm2zQ<=uw0ct;%3H zZ@QpRm$uJ{jSWg;rwJoyl0$F`s1OJ{8lE+!wNu1+%Z`S8VFV3nB&`f8mH9#zy%(aF zZZp+3FzrC@GUZun8=}kKy^9w_-nqoEuh$P`LAN}OJbat?cSBZ!x0E9&d`c$G#_|`K zUi0UdOXknF!!UM^El)^P!^k;!^`pe7*oGmO8(M^!-?s=Q+fhxN=i?xyD!FS+K>AxO z`A*uB@}qG}83!Kc6^>|&rrhWF-ho^H4F|IL?Wt)?EtcZx0y>c285gfHX?%z&Bn3(Gf5YF8+p1+%dH9f|1Tz%DYg;MhP6mxUlSU9k7N*f&fUDmPFe z2t`6vZdmI<*@O@6B{JpBWXGrE;J3*FqGL1podC2&n4P5zB4un)9lJo3(mN2i(~mLV z#&UzPY*>`pa5v(SIqWvl6FzbXVTf){Wu!&2V(5rc6YFPKh{wN}{quj;{fd)<6=zqz$XBHn0r^ILjM?FE4JN-w_M!*_(;yb!XA zvAROm&XLf~b0K_k+0FkP!Y8BM{PhsNLF?v!4B=DPZoV~?f9qZ7=C6cGI$wrvzBy#= zR6;j@Aym{E1>L+aRMaVfZvM-VwKD~}`Oic7x00coKNE`Fj&}1IJ@}Tin?Dhu~UKr24q!27-|WD<_W*-{)6Jiaz!@%c8Q z@O?Ao{gYXGF1omvAKZiG_{03C-hC`aoBYH7);T1~_}f`z?d8=cz>Cww>*9gz;Ja2W zzBYogjB$%cZz#f z@wsGRb~NM&L^PIA+3cELJWXI|l$$RwSY}CqWx%FP4)Y1&EQcsvpY@pULL0&CF;m`c z=Bo1;pS_pg6}r$yY^_^zrj0lf?P*=Id(wqA37XoD$nV9_krs+Nuk8S`xC0Sq+K61d zq8b)6sRC{HZv=11I?>Jn@T*2JO&JJ!Ot$Br0HvC>Z3 z3+yCK*$2`ul)LTtwDog4##wil8R&dLd9TLa&Hs8EOX3!Ex}lqYO z6JC>P`^$~bJg&A;Tcg;kZHn~?>|i#`>-vbKui6yr_3T$|)YkkCDT(*QVgC7(0M=V? zr`^$+2SzYOTY-~-#_`FGXoT;DHTJ^JS<|tW7@1XVpJp$)^`$x4j$`%f*`p<`IG)4^ zCR1lPM@nO42+LrM#D~V6Z3t&*d{mlis762w*aj1vYJd^Py)I4$>1M5HqVc8eGbNlq z5O9jPn%ty~Q}(cV)iU-ub{pFy44oQfP&Kz)Cpl6PpTgwK(wn%SU5GY1@y>jfp7aw; zo)gi00GLp~tnX=tG^cI1(`id~l1wnL!nVTN?9^1FJdIPrv;~$HJFL;wKJAWbly|uS zjju8P%^B_d&L72G4pi96N|LI#2nB$0&NduKO>$y1=Hq4)_pU2YjYiJ)5hHAPHU-enDS_Uu0Q&6b zpWlDv?YHlznEXy1;c7>;x(iB6+fAVLPBozku7+D!D~$N|dc~Ay>m@aL)e?3)tA4#n zC^$fFml=jNw_Mk76c}I%tcC-?!3S^}DoV#!$9pP@5Jz_(&N6X3HlcK&?KT~o>RezO ztVeM_tQcfcE94&u_Z-U0=VtJ4s0Gg*wEdaZ`wg>WT#?nF6 zyV>-=Sj99HrY)V#VZiENl37zR7ZQF zm^}e0^J+k4+bk3SzP&Se)Hq!Az#_!06lBcS0A<@O6hf3(i=TXmjVnT2necsJhXUx` z3ZM_Z2^4Pk0|d}D3ZP$A0R4&r=v@k+PrnJ&Pj3PxuLEji9Z)mtfO@hHsJH8Y`nnFN zxwd)5+G;nesGd8yMcC$vssTN4n_W)}1*S~T12!F-Ts^A@aT&r4+fKovPIm7U3XEh2 zV)mM!@FV7V0gU)eRO6Xkgz;#j_F`LnHDs>$Re6ewu#P_LV)0C}O)5&NM&nS2f6a6? z;y~Dg&rzA#M{C?b(`Pj04_Y04;Q2pk5tbn9CHbm10%xD z@T5In@putyX(x1N)nBzi+%y)r<6-PdjEbZ-Tp%W13#8hf7FbiJC%Ib3Vl4ANg$LSp z3M`#cy%E1@HiE(BkJMgM1l+4(k*gba_~MG53Pd=ROxzWbG(Jni?StD3w-s(5bP%Yy z2Z3625GdSkyAA?{+bruKQ2#gx)RPB+!foj}2$b=dWN-|-wSMU3B_gI}e6fS=<`a5| z+NG?e>p&HLGeFb;cQu^tL20F3yI13rz+HVX6w)c%AbXhqC?peC4m2yZ4YJGYjTn<* z6qc>P@+Zd?Kp#*5eOQ6-f@4^Vu9u&1JA=h1N1ud2uk_;6$*>V)+u?oe*7|KMUIB&q zmqIVFWAQ0|?wRC!Y|A@{sALB)k=5sdb1DX}nLcR)WnvoWh{LF6KHJMb5JKsgySE7S z2bv2fT{;m|s|tMg2q_TNaUtqJ=Tal$-t5MFJV(I1^16VyU%O46;We&?ZDze!&3;dP z(vh!`bbLxm*k2l`w~CU~LTc*e21$tQ&2LvC5K>dAw;ZWdfm%rY^3x!N3PLFOyU*db zQc=ODK{ZJ7(7gj#g7=IDWf%kk4~7yz%BGjGMRJO!`c> z!fUphfAMElt1?YovkNh4PE%(%ZXcV>4q(w}UjQ+tTjACFSQz$mV5b15)}(4PC4%&n zsq>JFsa6>he9q!%2g<{`-@c!(%E0pKpj%q>b@EH*T-MZC?>apn<$!<;w*t(Q35I){ zkq(8(8z`ubOEN*mHD4nO!~S9(eMy-H^uspTM)XK?cL>BOtlc2ir>UM>yhA{(^X4<5 z*c&?pvQ^nmDwUzwUQ@dgpjMKL@<;>J{L7EHdI66(OLz_oTquk<=vLN3=Tajh3;;Cd z%K*v!Mh-Q+?f)!rJQ$}+xTGE#?>BY+qsr9zQ||XqlydR%I1Z_>4qi1I#}O*Zt6`O| z8MjnziK(p|4zZQ@%`|F^s1!H6Gx z12ccRG^|=PqCJqy8gL7BhIRYcXnf2=Cbjmf zHe$04zX$J2#C&WsMEKZUWy0mDzqw14&D-V7)sOY&(uD135649`A>%VoJZ?_i_>_q@ zVBM~F zQ|A%wF8Cp!GDP_yll(T!L_6`zGps)syiZI_oCv4N3V=ysqpiv!ja_LK|6F&OE~ORa zB^YRdNWpRdf?vEL@Vb;h8uB#i+4reLfI z*HqvaeH5v)z?X$0GCb3~`L~_}{9E9EX@sHgm=nIOru+Ek`>;Idb0F{~A#C5=hht)U zK?sfN2w;8J*8*dkaNdadJB2tI!l*@?=SQ0pyhy|_h|DQpwIQa-DrIr6J#(kmMm1U^ zvx$m5UgF|ja^ZTKIJXOHG(rl1x~`%)7!M(^mo%)c3iG_n@-ChjHI1R;?|xdtJTrrstxE=G}@j6h6{DN&%ZG?plVy0?gp z2@W7)f{6&feQovZ7ZRt2v$ehqR(3edZwP~axgY7=)?6Xch^0~zjnomc<06S)`J+(O zO^qN)jj@n|WWFqm3KCSUC`&QR54B)$_#d}w+$gWMA=aRAJ=zR(WR?o^u0BkgiCt^n zkFTxrtg+Q}i))n5xJ{a%OQrGxv(h@xe13lXUX2rmF0{1>hc{u$xwp3nFTBwryx_S* zx!nR`+%1rBNr0)Qc9I50k&S8hqA)UA z=FNcEKGaO>%*nX48kdg6bnNS+J(&(FB)Orn80=_NLRP20ra!FBYWqDbrqlKR5Y`ni zSy6g|1JcxN92*rvy{YXI)hr+AAMo8Z{hR5>o8(eD-V%_to*Dt(Yu?pJ2G*@KagREw~- z^?rem;5KwsB zW8Q>$7UoZwXJI~o`3UA=%Ek;94Mn39vR!@{`g8!&cVo#Wy2=kSyd{Q6mad^Uf;qCBG(b*fjZoemeJ0>^)g?Z{W=&$>`enM$6L0YNo@GDaV z$UtA->;2yPK7(mC{$PPmDX&WqV z60~&krpP$h*wygfptR-wt4=g=B3=3JhAf^$N(&4Ubsd_beoTtIEO)$cxD zoJ&9GAn{ENxvYbb=XbhuBa$s`=Ma-wJ;9l0&#@&te+c9{b_&osBXvZv%8+MA0@2!h zDZZ9wp(fKdhfQ&-_lEgrZsYtw|Al|7^K2llHpMg47AMa9?xQ*zqz`uElU`ux;`hwz zOQ<6%^-3FT2&53NF6&Ur$XBnn5!IGL%KMRd$aysS=RlKCVpQ!-FzCGr%u%!6o5yNg zkfxqoW0w0yY#rf=-J=uY?I>40`ewk$h63W8WQ*XNN9J`rAL01~_a)rlF#T|U!}P=F zW6#v@VV`2Ru`0HYuj!4Og7wtUX*n#$I(tJP2Pa;Q-K%FcPSsu=JHXx~6wzO`L3Pv) z^#)0K32RdNHC|}-^8I6Z-=C77#8iLHV6dj! zieTVIzrHQXH;%=!5Ew=Cnd2B~lq*}Jm@$ujg7?Cjx3-j)oOUe085 zShPFLzbE2Q2>g?G;qqY|3a9v9P5lAs*y6Y>lU^+GFiR$QY8?iT`eW^+Rh$wc@)Q(= z0{0wKvgoZuwueWzK`*(S$?C+kTf-Px6QlqA+MkQJKE2gEHC0%?_I;}Uyb6A{9&59}m{uZf4~O{A#88pC=~>+p z;Oqi2lD=yWly}WOwn^Z3_K*&Vfy4Uf;SU_BQ*C69bJDC=BREi4zD0@Kt*30TK^rIP z!%KEz90{xo?^ZyDbw*c{`52u5?ZEo~D(>JLdg}?G{~hh*`dw%z3f9z#;==r?llVRV z05*ml=K(H9AhJn6-qiy)Ovvrmnq1noX?2)Ca`K*I3id@o2DrUqf-=BzHiIy>%N4w* zk7)Q%WQF`k*3XmiB7Rp7uMdGf`0cL&1zXzn-0CpzJ_%{2&cwJdzxgCymt(vDjNkNI zALvhd>(*mQ!n!r;rU+f1uE!WVS^-l&(-Gp6!%_9drkIQfU1dIu5SA#AgUQQx=qkzU z^7RD%pl1YE>&Wgq^i+sA7xKvy8oT*(-E^bgVe*iU6bIR=7jdrUIdtsqNf>_vW5;5w zs|Z$xUX+o+cnj3AQ#bxLW8;JY2E@i*0RzFRFGm+?^N~5qSK8%5N%?UFx^_SmOEtL+ zJ$~TM2vifw0}k@L{Q2CI(}IC;cq5c@VP$H&Z~9ND~kudKa|kfGG$tqrHTrymb2&r*qN{4x?s53E?$? zx(ifje76tpylXg6A#Oh?IVjP3b2unz_Pg2arV{d-36&qmCH*!+>!n!g_jo3*&xGsaoD}(G0_P+b2PUEw zyqh@4H^UH2RdPo=soL0{wtQndvwW$qv^~E3T!*IO6Yn`~zNyHRZ#wRsXHGJ>z0OH$ z4oY!~G`G>D^_t9a9F*pF0n%|B^R?b$Gfruu@68}0@YM`TC%1qx8IqDs9g}L=X{unbXdB{;j=C?IbuS6@#e*0FBpsalBv7)rVZY z?*u7jLx+-pkdk}b3mvDYPB&{UAA5Z!ttHY5o4No=y{;|*l#3=D3zW9!lemsrFRrD| zhf6B);r61u6ziO{tsSXSy?8Gg&uuJ~_)Vbqn#7im55k&zy>JuL5!b@JMiWw7r?w*k zyWy~kR`A}j$BFccU@9zVM@quGg+(mT7Vbj}<*f_4X4KsT^5f78oz(ccj?**Lmr;o5 ztth}f6Zg=MgHTF`h)zof0e5;o5u^zm3j0rOFTuU}j=$J@%@BL8A=p=h%+)~s0IC|gsx zsBGQxwIeF-WCOVXfB?V-00aQ61OO5Mo&f*}0PF&QC;<2z0Hgqrg#cs#Fq;4|(|QSj z8~`X8fC2#Qa)4+6I28||1OQh$Kn%{!1`vzQT>vUkl3VTAi;u+ zZ^$4D+y7316r1W;kf}kG|Dv${l{k>A0qoZXfI!Pcjc;;Wh)lm53^P*TmhMjmai&Xn+f`r>y|Iifcz;y;Xj;KPQST*CQ$#J z0aWpfi2KbMKxOy;R!p5esIOJ4_73)j+>3(MCn79&6u5I}+nD4-x7_YqmF zJT)agaqPq~IYXJuZ0Dm-KDK;W`NE=7Hh<=fxev7ler@aR>Acz8^0oiWr+@!y+pDkb zdExn|o<98kpWgW3=toU|J9YLSm#y2H$7AH%Kp8> z>5LH*?j4;wL>o7Nl*A|=oI2-WTS=jLm7{D?)!HZ4Z++=m*UlZa`#c|dkH7nN-NEiY zp8MAi9Y25a*MEL~_1p6omaJTCU$^G*4bvW2FnhAqQjj!wpgM|(R_cb0)ZaHgZ`71x z)1>LM=FfX%b@j%jD=I7QA7{KLEj`O1MU*OeP=e;Yw+{Td;n>F~c5UDN`g1RC+5Ful z-#4c}`|^vQzQ6uk=yunQ-v@av8<;xdV_S-6# zR7I@*wLlfG18VX*pr)+@YSucS=BxuMe;rVT>%=xSrK$;&*w4nSL|M4;?|f9m506Le zH{y;v{v;7UJa(~P_T7H{V;ZN4{qOwY@r{4u^za|{7t@{%00*!GL5#x2YygDqghVnH z0JO6Kvc}MojB}4^mP%MGT-%ugv)G2^Hke%%7KD`4A5JUrU4o(b?Jbq9rSr zR5|GE?Ef0lGTo9hW?qh%98J^n(yJf(Kf>nzKZTt!YjV+onS~{VlM81~pYy*K)-v7l zKN9`lN-$PTS|n6|aTP#Yrd#N2y3~frHfhyb`jN8bODe_IqNkQsEL*ttf4Ud_;XZwK zgz%L#J+k}(^62gQ8kV1ksLKLX*R0dHJ6-Z&DI0U3J1TqLC3P?FcOawU$!P6ed zqhz3fFdjM(4Pj9Br>`W3Kumx7F;Ws@Axx+MDO6}9sQc4bOH>fopMIPSK|F+!21vPv zmGM%j^pterW!@xpQVe_`s~0Gp0`~oif>GEuO>{nDZyz zH(}g8qjE=PXAWoRRIMgPtn&Z)jqDGx%P4y^t1R}{kEY4@B%N6yd%0_=bM&E#wz{2_ zujRTg#~wU><*~tS7hBzz&b?|V`B2`p!Skdn`*>jcAn&$H^E#ox9* z?O8qK*oV?XKYCx!yKwyan`dR!qq;%$(qZ{7?e5s`PsA+Un0?<0>ec0y+tK`rpSq?k zTUK7SJhj=l@aZW~-ucT;>GH=9p_EU$sHYx0qq_OmOZ5w2>pO1$wklgv@UKB+-hvXv+h;e#T)lU7)YP~0iQ#H>^vP#v<=OOOjt7rE zy^5A!Sk(CXk7fUe?f&lJ-DfXlr0w?Ae{lGlzYVnVzv(aUF8}Bhz4`br zA0GAYRsQfHx%ZrB?YK!7+uwim-2TL2mnEAAT&aqWuDG^kLgg#>FI^FHc<$2m(f^G7 zaer7|GyFYJcwUn|QBb4e&ec)RIy%wdzSGhr4?S4Uf3bL>YxS7rNdf7ym5-!c=xa5c z-#T~wx9TsgR~N5pY3%O)?c__AlYbd_@uhnE^}4UWezL~@#+lR2W2bkvlm-`{@GpMw z<3C-M9-C+z(@^xSA*Q(`Me+VED>=r#UXuUmZ}yg1EsGET_R`9n$4)L`UpQL!Me^oF zA0IfkDt*ikj_EreReniMiayaefJhrTENa%t2_Jo?k8Wz%G4}(5Wa-iQe-3|hI_ICh zW6!^KDQnPs-_5H(U0FMSZD z?-@Lgk4^bdS^Ltt9Wf^_{_8KlUD=>(xg34r-1%qBKU@e3N3S|oZvJ-2R|8INnm4TR z*7uLruX=RSU$j5XrQFV?s_@?@NEgkIMseZS7QVdXy>j7vcv)HDKbH@v{y}lz*K;x7 z%-k%Qa{4Gau58%iKl20ZzR8o86kmRH<^9&B{`aoT{rb|P=oS+M&o#6Rw5XSO!C{!4iI`04g literal 0 HcmV?d00001 diff --git a/boards/auterion/fmu-v6x/firmware.prototype b/boards/auterion/fmu-v6x/firmware.prototype new file mode 100644 index 0000000000..644953a9e1 --- /dev/null +++ b/boards/auterion/fmu-v6x/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 53, + "magic": "AutFWv1", + "description": "Firmware for the AutFMUv6X board", + "image": "", + "build_time": 0, + "summary": "AutFMUv6X", + "version": "0.1", + "image_size": 0, + "image_maxsize": 1966080, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/auterion/fmu-v6x/flash-analysis.px4board b/boards/auterion/fmu-v6x/flash-analysis.px4board new file mode 100644 index 0000000000..30717ad93c --- /dev/null +++ b/boards/auterion/fmu-v6x/flash-analysis.px4board @@ -0,0 +1 @@ +CONFIG_BOARD_LINKER_PREFIX="flash-analysis" diff --git a/boards/auterion/fmu-v6x/init/rc.board_defaults b/boards/auterion/fmu-v6x/init/rc.board_defaults new file mode 100644 index 0000000000..f371bbee78 --- /dev/null +++ b/boards/auterion/fmu-v6x/init/rc.board_defaults @@ -0,0 +1,31 @@ +#!/bin/sh +# +# board specific defaults +#------------------------------------------------------------------------------ + +# By disabling all 3 INA modules, we use the +# i2c_launcher instead. +param set-default SENS_EN_INA238 0 +param set-default SENS_EN_INA228 0 +param set-default SENS_EN_INA226 0 + +# Skynode: use the "custom participant", IP=10.41.10.1 config for uxrce_dds_client +param set-default UXRCE_DDS_PTCFG 2 +param set-default UXRCE_DDS_AG_IP 170461697 +param set-default UXRCE_DDS_CFG 1000 + +# The buzzer draws too much power (0.2A) on the GPS power rail (limit 0.45A). +param set-default CBRK_BUZZER 782097 + +safety_button start + +# GPIO Expander driver on external I2C3 +if ver hwbasecmp 009 010 011 +then + # No USB + mcp23009 start -b 3 -X -D 0xf0 -O 0xf0 -P 0x0f -U 10 +fi +if ver hwbasecmp 00a 008 +then + mcp23009 start -b 3 -X -D 0xf1 -O 0xf0 -P 0x0f -U 10 +fi diff --git a/boards/auterion/fmu-v6x/init/rc.board_mavlink b/boards/auterion/fmu-v6x/init/rc.board_mavlink new file mode 100644 index 0000000000..4952825bc4 --- /dev/null +++ b/boards/auterion/fmu-v6x/init/rc.board_mavlink @@ -0,0 +1,10 @@ +#!/bin/sh +# +# Auterion FMUv6X specific board MAVLink startup script. +#------------------------------------------------------------------------------ + +# start Mavlink on Telem2 +mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z + +# Ensure nothing else starts on TEL2 (ttyS4) +set PRT_TEL2_ 1 diff --git a/boards/auterion/fmu-v6x/init/rc.board_sensors b/boards/auterion/fmu-v6x/init/rc.board_sensors new file mode 100644 index 0000000000..162a0615ae --- /dev/null +++ b/boards/auterion/fmu-v6x/init/rc.board_sensors @@ -0,0 +1,93 @@ +#!/bin/sh +# +# Auterion FMUv6X specific board sensors init +#------------------------------------------------------------------------------ +set HAVE_PM2 yes +set INA_CONFIGURED no + +if mft query -q -k MFT -s MFT_PM2 -v 0 +then + set HAVE_PM2 no +fi +if param compare -s ADC_ADS1115_EN 1 +then + ads1115 start -X + board_adc start -n +else + board_adc start +fi + + +if param compare SENS_EN_INA226 1 +then + # Start Digital power monitors + ina226 -X -b 1 -t 1 -k start + + if [ $HAVE_PM2 = yes ] + then + ina226 -X -b 2 -t 2 -k start + fi + + set INA_CONFIGURED yes +fi + +if param compare SENS_EN_INA228 1 +then + # Start Digital power monitors + ina228 -X -b 1 -t 1 -k start + if [ $HAVE_PM2 = yes ] + then + ina228 -X -b 2 -t 2 -k start + fi + + set INA_CONFIGURED yes +fi + +if param compare SENS_EN_INA238 1 +then + # Start Digital power monitors + ina238 -X -b 1 -t 1 -k start + if [ $HAVE_PM2 = yes ] + then + ina238 -X -b 2 -t 2 -k start + fi + + set INA_CONFIGURED yes +fi + +#Start Auterion Power Module selector for Skynode boards +pm_selector_auterion start + +# Auterion's INA238 uses a shunt value of 0.0003 instead of 0.0005. +param set-default INA238_SHUNT 0.0003 + +# Internal SPI BMI088 +bmi088 -A -R 6 -s start +bmi088 -G -R 6 -s start + +# Internal SPI bus ICM42688p +icm42688p -R 12 -s start + +# Internal SPI bus ICM20602 +icm20602 -R 6 -s start + +# Internal magnetometer on I2C +bmm150 -I -R 0 start + +# External compass on GPS1/I2C1 (the 3rd external bus): standard Holybro Pixhawk 4 or CUAV V5 GPS/compass puck (with lights, safety button, and buzzer) +ist8310 -X -b 1 -R 10 start + +# Possible internal Baro +if param compare SENS_INT_BARO_EN 1 +then + bmp388 -I -a 0x77 start +fi + +#external baro +bmp388 -X start + +# Don't try to start external baro on I2C3 as it can conflict with the MS5525DSO airspeed sensor. +#ms5611 -X start + +unset INA_CONFIGURED +unset HAVE_PM2 diff --git a/boards/auterion/fmu-v6x/multicopter.px4board b/boards/auterion/fmu-v6x/multicopter.px4board new file mode 100644 index 0000000000..147297d55e --- /dev/null +++ b/boards/auterion/fmu-v6x/multicopter.px4board @@ -0,0 +1,13 @@ +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=n +CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=n +CONFIG_MODULES_AIRSPEED_SELECTOR=n +CONFIG_MODULES_FW_ATT_CONTROL=n +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n +CONFIG_MODULES_FW_RATE_CONTROL=n +CONFIG_MODULES_VTOL_ATT_CONTROL=n +CONFIG_COMMON_RC=y +# CONFIG_EKF2_SIDESLIP is not set +CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y +# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set diff --git a/boards/auterion/fmu-v6x/nuttx-config/Kconfig b/boards/auterion/fmu-v6x/nuttx-config/Kconfig new file mode 100644 index 0000000000..bb33d3cfda --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/Kconfig @@ -0,0 +1,17 @@ +# +# For a description of the syntax of this configuration file, +# see misc/tools/kconfig-language.txt. +# +config BOARD_HAS_PROBES + bool "Board provides GPIO or other Hardware for signaling to timing analyze." + default y + ---help--- + This board provides GPIO FMU-CH1-5, CAP1-6 as PROBE_1-11 to provide timing signals from selected drivers. + +config BOARD_USE_PROBES + bool "Enable the use the board provided FMU-CH1-5, CAP1-6 as PROBE_1-11" + default n + depends on BOARD_HAS_PROBES + + ---help--- + Select to use GPIO FMU-CH1-5, CAP1-6 to provide timing signals from selected drivers. diff --git a/boards/auterion/fmu-v6x/nuttx-config/bootloader/defconfig b/boards/auterion/fmu-v6x/nuttx-config/bootloader/defconfig new file mode 100644 index 0000000000..2c0231e294 --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/bootloader/defconfig @@ -0,0 +1,95 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DEV_CONSOLE is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_SPI_EXCHANGE is not set +# CONFIG_STM32H7_SYSCFG is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/auterion/fmu-v6x/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="auterion" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H753II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_INITTHREAD_PRIORITY=254 +CONFIG_BOARD_LATE_INITIALIZE=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0035 +CONFIG_CDCACM_PRODUCTSTR="Auterion BL FMU v6X.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3185 +CONFIG_CDCACM_VENDORSTR="Auterion" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_EXPERIMENTAL=y +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="bootloader_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SPI=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_UART5=y +CONFIG_SYSTEMTICK_HOOK=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_TTY_SIGINT=y +CONFIG_TTY_SIGINT_CHAR=0x03 +CONFIG_TTY_SIGTSTP=y +CONFIG_UART5_RXBUFSIZE=512 +CONFIG_UART5_RXDMA=y +CONFIG_UART5_TXBUFSIZE=512 +CONFIG_UART5_TXDMA=y +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/auterion/fmu-v6x/nuttx-config/include/board.h b/boards/auterion/fmu-v6x/nuttx-config/include/board.h new file mode 100644 index 0000000000..7907eafad1 --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/include/board.h @@ -0,0 +1,566 @@ +/************************************************************************************ + * nuttx-configs/px4_fmu-v6x/include/board.h + * + * Copyright (C) 2016-2019 Gregory Nutt. All rights reserved. + * Authors: David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ +#ifndef __NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include "board_dma_map.h" + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdmmc.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The px4_fmu-v6X board provides the following clock sources: + * + * X1: 16 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 16 MHz RC factory-trimmed + * HSE: 16 MHz crystal for HSE + */ + +#define STM32_BOARD_XTAL 16000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE = 16,000,000 + * + * PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 1 <= PLLM <= 63 + * 4 <= PLLN <= 512 + * 150 MHz <= PLL_VCOL <= 420MHz + * 192 MHz <= PLL_VCOH <= 836MHz + * + * SYSCLK = PLL_VCO / PLLP + * CPUCLK = SYSCLK / D1CPRE + * Subject to + * + * PLLP1 = {2, 4, 6, 8, ..., 128} + * PLLP2,3 = {2, 3, 4, ..., 128} + * CPUCLK <= 480 MHz + */ + +#define STM32_BOARD_USEHSE + +#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE + +/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR + * + * PLL1_VCO = (16,000,000 / 1) * 60 = 960 MHz + * + * PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz + * PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz + * PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz + */ + +#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP1EN | \ + RCC_PLLCFGR_DIVQ1EN | \ + RCC_PLLCFGR_DIVR1EN) +#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1) +#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(60) +#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) +#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) +#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) + +#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 60) +#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) +#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) +#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) + +/* PLL2 */ + +#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP2EN | \ + RCC_PLLCFGR_DIVQ2EN | \ + RCC_PLLCFGR_DIVR2EN) +#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(4) +#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) +#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) +#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) +#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) + +#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) + +/* PLL3 */ + +#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVQ3EN) +#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(4) +#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) +#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) +#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) +#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) + +#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 4) * 48) +#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) +#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) +#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) + +/* SYSCLK = PLL1P = 480MHz + * CPUCLK = SYSCLK / 1 = 480 MHz + */ + +#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) +#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) +#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) + +/* Configure Clock Assignments */ + +/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max) + * HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 + */ + +#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ +#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ +#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ +#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ + +#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ +#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timer clock frequencies */ + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Kernel Clock Configuration + * + * Note: look at Table 54 in ST Manual + */ + +/* I2C123 clock source */ + +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI + +/* I2C4 clock source */ + +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI + +/* SPI123 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 + +/* SPI45 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 + +/* SPI6 clock source */ + +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 + +/* USB 1 and 2 clock source */ + +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 + +/* ADC 1 2 3 clock source */ + +#define STM32_RCC_D3CCIPR_ADCSRC RCC_D3CCIPR_ADCSEL_PLL2 + +/* UART clock selection */ +/* reset to default to overwrite any changes done by any bootloader */ + +#define STM32_RCC_D2CCIP2R_USART234578_SEL RCC_D2CCIP2R_USART234578SEL_RCC +#define STM32_RCC_D2CCIP2R_USART16_SEL RCC_D2CCIP2R_USART16SEL_RCC + +/* FDCAN 1 2 clock source */ + +#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ + +#define STM32_FDCANCLK STM32_HSE_FREQUENCY + +/* FLASH wait states + * + * ------------ ---------- ----------- + * Vcore MAX ACLK WAIT STATES + * ------------ ---------- ----------- + * 1.15-1.26 V 70 MHz 0 + * (VOS1 level) 140 MHz 1 + * 210 MHz 2 + * 1.05-1.15 V 55 MHz 0 + * (VOS2 level) 110 MHz 1 + * 165 MHz 2 + * 220 MHz 3 + * 0.95-1.05 V 45 MHz 0 + * (VOS3 level) 90 MHz 1 + * 135 MHz 2 + * 180 MHz 3 + * 225 MHz 4 + * ------------ ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ + +/* Init 400kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ + +#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* 25 MHz Max for now, 25 mHZ = PLL1Q/(2*div), div = PLL1Q/(2*freq) + * div = 4.8 = 240 / 50, So round up to 5 for default speed 24 MB/s + */ + +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_MMCXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_SDXFR_CLKDIV (5 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + +/* LED definitions ******************************************************************/ +/* The PX4 FMUV6X board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and + * LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +/* LED definitions ******************************************************************/ +/* The px4_fmu-v6x board has three, LED_GREEN a Green LED, LED_BLUE a Blue LED and + * LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_GREEN BOARD_LED2 +#define BOARD_LED_BLUE BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* Alternate function pin selections ************************************************/ + +#define GPIO_USART1_RX GPIO_USART1_RX_3 /* PB7 */ +#define GPIO_USART1_TX GPIO_USART1_TX_3 /* PB6 */ + +#define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3 */ +#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */ +#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */ +#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */ + +#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ + +#define GPIO_UART4_RX GPIO_UART4_RX_6 /* PH14 */ +#define GPIO_UART4_TX GPIO_UART4_TX_6 /* PH13 */ + +#define GPIO_UART5_RX GPIO_UART5_RX_3 /* PD2 */ +#define GPIO_UART5_TX GPIO_UART5_TX_3 /* PC12 */ +// GPIO_UART5_RTS no remap /* PC8 */ +#undef GPIO_UART5_CTS +#define GPIO_UART5_CTS ((GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN9) | GPIO_PULLDOWN) /* PC9 */ + + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_4 /* PF6 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ +#define GPIO_UART7_RTS GPIO_UART7_RTS_2 /* PF8 */ +#define GPIO_UART7_CTS (GPIO_UART7_CTS_1 | GPIO_PULLDOWN) /* PE10 */ + +#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ +#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ + + +/* CAN + * + * CAN1 is routed to transceiver. + * CAN2 is routed to transceiver. + */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */ +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */ +#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */ +#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* PB13 */ + +/* SPI + * SPI1 is sensors1 + * SPI2 is sensors2 + * SPI3 is sensors3 + * SPI4 is Not Used + * SPI5 is FRAM + * SPI6 is EXTERNAL1 + * + */ + +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_3 /* PG9 */ +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_2 /* PB5 */ +#define GPIO_SPI1_SCK ADJ_SLEW_RATE(GPIO_SPI1_SCK_1) /* PA5 */ + +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_4 /* PI3 */ +#define GPIO_SPI2_SCK ADJ_SLEW_RATE(GPIO_SPI2_SCK_6) /* PI1 */ + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 /* PC11 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_3 /* PB2 */ +#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_2) /* PC10 */ + +#define GPIO_SPI5_MISO GPIO_SPI5_MISO_2 /* PH7 */ +#define GPIO_SPI5_MOSI GPIO_SPI5_MOSI_1 /* PF11 */ +#define GPIO_SPI5_SCK ADJ_SLEW_RATE(GPIO_SPI5_SCK_1) /* PF7 */ + +#define GPIO_SPI6_MISO GPIO_SPI6_MISO_2 /* PA6 */ +#define GPIO_SPI6_MOSI GPIO_SPI6_MOSI_1 /* PG14 */ +#define GPIO_SPI6_SCK ADJ_SLEW_RATE(GPIO_SPI6_SCK_3) /* PB3 */ + +/* I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + * + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */ + +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_2 /* PF1 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_2 /* PF0 */ + +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN1) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN0) + +#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1 /* PA8 */ +#define GPIO_I2C3_SDA GPIO_I2C3_SDA_2 /* PH8 */ + +#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTA | GPIO_PIN8) +#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN |GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTH | GPIO_PIN8) + +#define GPIO_I2C4_SCL GPIO_I2C4_SCL_2 /* PF14 */ +#define GPIO_I2C4_SDA GPIO_I2C4_SDA_2 /* PF15 */ + +#define GPIO_I2C4_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN14) +#define GPIO_I2C4_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTF | GPIO_PIN15) + +/* SDMMC2 + * + * VDD 3.3 + * GND + * SDMMC2_CK PD6 + * SDMMC2_CMD PD7 + * SDMMC2_D0 PB14 + * SDMMC2_D1 PB15 + * SDMMC2_D2 PG11 + * SDMMC2_D3 PB4 + */ + +#define GPIO_SDMMC2_CK GPIO_SDMMC2_CK_1 /* PD6 */ +#define GPIO_SDMMC2_CMD GPIO_SDMMC2_CMD_1 /* PD7 */ +// GPIO_SDMMC2_D0 No Remap /* PB14 */ +// GPIO_SDMMC2_D1 No Remap /* PB15 */ +#define GPIO_SDMMC2_D2 GPIO_SDMMC2_D2_1 /* PG11 */ +// GPIO_SDMMC2_D3 No Remap /* PB4 */ + +/* The STM32 H7 connects to a TI DP83848TSQ/NOPB + * using RMII + * + * STM32 H7 BOARD DP83848TSQ/NOPB + * GPIO SIGNAL PIN NAME + * -------- ------------ ------------- + * PA7 ETH_CRS_DV CRS_DV + * PC1 ETH_MDC MDC + * PA2 ETH_MDIO MDIO + * PA1 ETH_REF_CL X1 + * PC4 ETH_RXD0 RX_D0 + * PC5 ETH_RXD1 RX_D1 + * PB11 ETH_TX_EN TX_EN + * PG13 ETH_TXD0 TX_D0 + * PG12 ETH_TXD1 TX_D1 + * + * The PHY address is 1, since COL/PHYAD0 features a pull up. + */ + +#define GPIO_ETH_RMII_TX_EN GPIO_ETH_RMII_TX_EN_1 /* PB11 */ +#define GPIO_ETH_RMII_TXD0 GPIO_ETH_RMII_TXD0_2 /* PG13 */ +#define GPIO_ETH_RMII_TXD1 GPIO_ETH_RMII_TXD1_2 /* PG12 */ + + +/* USB + * + * OTG_FS_DM PA11 + * OTG_FS_DP PA12 + * VBUS PA9 + */ + + +/* Board provides GPIO or other Hardware for signaling to timing analyzer */ + +#if defined(CONFIG_BOARD_USE_PROBES) +# include "stm32_gpio.h" +# define PROBE_N(n) (1<<((n)-1)) +# define PROBE_1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTI|GPIO_PIN0) /* PI0 AUX1 */ +# define PROBE_2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN12) /* PH12 AUX2 */ +# define PROBE_3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN11) /* PH11 AUX3 */ +# define PROBE_4 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN10) /* PH10 AUX4 */ +# define PROBE_5 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13) /* PD13 AUX5 */ +# define PROBE_6 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14) /* PD14 AUX6 */ +# define PROBE_7 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN6) /* PH6 AUX7 */ +# define PROBE_8 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN9) /* PH9 AUX8 */ +# define PROBE_9 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN11) /* PE11 CAP1 */ + +# define PROBE_INIT(mask) \ + do { \ + if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \ + if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \ + if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \ + if ((mask)& PROBE_N(4)) { stm32_configgpio(PROBE_4); } \ + if ((mask)& PROBE_N(5)) { stm32_configgpio(PROBE_5); } \ + if ((mask)& PROBE_N(6)) { stm32_configgpio(PROBE_6); } \ + if ((mask)& PROBE_N(7)) { stm32_configgpio(PROBE_7); } \ + if ((mask)& PROBE_N(8)) { stm32_configgpio(PROBE_8); } \ + if ((mask)& PROBE_N(9)) { stm32_configgpio(PROBE_9); } \ + } while(0) + +# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0) +# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true) +#else +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) +#endif + +#endif /*__NUTTX_CONFIG_PX4_FMU_V6X_INCLUDE_BOARD_H */ diff --git a/boards/auterion/fmu-v6x/nuttx-config/include/board_dma_map.h b/boards/auterion/fmu-v6x/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..1f45efc569 --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/include/board_dma_map.h @@ -0,0 +1,87 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// DMAMUX1 Using at most 8 Channels on DMA1 -------- Assigned +// V + +#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* 1 DMA1:37 ICM-20649 */ +#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* 2 DMA1:38 ICM-20649 */ + +#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* 3 DMA1:39 ICM-42688-P */ +#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* 4 DMA1:40 ICM-42688-P */ + +//#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 GPS1 */ +//#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 GPS1 */ + +//#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_0 /* DMA1:43 Telem3 */ +//#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_0 /* DMA1:44 Telem3 */ + +//#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 DEBUG */ +//#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 DEBUG */ + +//#define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 EXT2 */ +//#define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 EXT2 */ + +#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* 5 DMA1:71 PX4IO */ +#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* 6 DMA1:72 PX4IO */ + +// Assigned in timer_config.cpp + +// Timer 4 /* 7 DMA1:32 TIM4UP */ +// Timer 5 /* 8 DMA1:50 TIM5UP */ + +// DMAMUX2 Using at most 8 Channels on DMA2 -------- Assigned +// V + +#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_1 /* 1 DMA2:61 BMI088 */ +#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_1 /* 2 DMA2:62 BMI088 */ + +#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* 3 DMA2:45 DEBUG */ +#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* 4 DMA2:46 DEBUG */ + +#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 /* 5 DMA2:65 TELEM2 */ +#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 /* 6 DMA2:66 TELEM2 */ + +#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* 7 DMA1:79 TELEM1 */ +#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 /* 8 DMA1:80 TELEM1 */ + +//#define DMAMAP_UART8_RX DMAMAP_DMA12_UART8RX_1 /* DMA1:81 GPS2 */ +//#define DMAMAP_UART8_TX DMAMAP_DMA12_UART8TX_1 /* DMA1:82 GPS2 */ + +// DMAMUX2 Using at most 8 Channels on BDMA -------- Assigned +// V + +#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* 1 BDMA:11 SPI J11 */ +#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* 2 BDMA:12 SPI J11 */ diff --git a/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig b/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..4fbc7a3b94 --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig @@ -0,0 +1,332 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_ARP is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_IFUPDOWN is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_NSLOOKUP is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TELNETD is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/auterion/fmu-v6x/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="auterion" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H753II=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU_EARLY_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95751 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0035 +CONFIG_CDCACM_PRODUCTSTR="Auterion FMU v6X.x" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x3185 +CONFIG_CDCACM_VENDORSTR="Auterion" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_GPIO=y +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_DEV_URANDOM=y +CONFIG_ETH0_PHY_LAN8742A=y +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FSUTILS_IPCFG=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_THROTTLE=0 +CONFIG_IPCFG_BINARY=y +CONFIG_IPCFG_CHARDEV=y +CONFIG_IPCFG_PATH="/fs/mtd_net" +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_REGIONS=4 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_MTD_PROGMEM=y +CONFIG_MTD_RAMTRON=y +CONFIG_NAME_MAX=40 +CONFIG_NET=y +CONFIG_NETDB_DNSCLIENT=y +CONFIG_NETDB_DNSCLIENT_ENTRIES=8 +CONFIG_NETDB_DNSSERVER_NOADDR=y +CONFIG_NETDEV_PHY_IOCTL=y +CONFIG_NETINIT_DHCPC=y +CONFIG_NETINIT_DNS=y +CONFIG_NETINIT_DNSIPADDR=0xA290AFE +CONFIG_NETINIT_DRIPADDR=0xA290AFE +CONFIG_NETINIT_MONITOR=y +CONFIG_NETINIT_THREAD=y +CONFIG_NETINIT_THREAD_PRIORITY=49 +CONFIG_NETUTILS_TELNETD=y +CONFIG_NET_ARP_IPIN=y +CONFIG_NET_ARP_SEND=y +CONFIG_NET_BROADCAST=y +CONFIG_NET_ETH_PKTSIZE=1518 +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_SOCKET=y +CONFIG_NET_NACTIVESOCKETS=16 +CONFIG_NET_SOLINGER=y +CONFIG_NET_TCP=y +CONFIG_NET_TCPBACKLOG=y +CONFIG_NET_TCP_DELAYED_ACK=y +CONFIG_NET_TCP_WRITE_BUFFERS=y +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +CONFIG_NET_UDP_WRITE_BUFFERS=y +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_TELNET=y +CONFIG_NSH_TELNET_LOGIN=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAMTRON_EMULATE_PAGE_SHIFT=5 +CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT=5 +CONFIG_RAMTRON_SETSPEED=y +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SDMMC2_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_ETHMAC=y +CONFIG_STM32H7_FLASH_OVERRIDE_I=y +CONFIG_STM32H7_FLOWCONTROL_BROKEN=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +CONFIG_STM32H7_I2C3=y +CONFIG_STM32H7_I2C4=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PHYSR=31 +CONFIG_STM32H7_PHYSR_100MBPS=0x8 +CONFIG_STM32H7_PHYSR_FULLDUPLEX=0x10 +CONFIG_STM32H7_PHYSR_MODE=0x10 +CONFIG_STM32H7_PHYSR_SPEED=0x8 +CONFIG_STM32H7_PHY_POLLING=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC2=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI1=y +CONFIG_STM32H7_SPI1_DMA=y +CONFIG_STM32H7_SPI1_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI2=y +CONFIG_STM32H7_SPI2_DMA=y +CONFIG_STM32H7_SPI2_DMA_BUFFER=4096 +CONFIG_STM32H7_SPI3=y +CONFIG_STM32H7_SPI3_DMA=y +CONFIG_STM32H7_SPI3_DMA_BUFFER=1024 +CONFIG_STM32H7_SPI5=y +CONFIG_STM32H7_SPI6=y +CONFIG_STM32H7_SPI6_DMA=y +CONFIG_STM32H7_SPI6_DMA_BUFFER=1024 +CONFIG_STM32H7_TIM12=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM5=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART5=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=y +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_DHCPC_RENEW=y +CONFIG_SYSTEM_NSH=y +CONFIG_SYSTEM_PING=y +CONFIG_SYSTEM_SYSTEM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_BAUD=57600 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=1500 +CONFIG_UART5_IFLOWCONTROL=y +CONFIG_UART5_OFLOWCONTROL=y +CONFIG_UART5_RXDMA=y +CONFIG_UART5_TXBUFSIZE=10000 +CONFIG_UART5_TXDMA=y +CONFIG_UART7_BAUD=57600 +CONFIG_UART7_IFLOWCONTROL=y +CONFIG_UART7_OFLOWCONTROL=y +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_RXDMA=y +CONFIG_UART7_TXBUFSIZE=3000 +CONFIG_UART7_TXDMA=y +CONFIG_UART8_BAUD=57600 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=1500 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_RXBUFSIZE=600 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=3000 +CONFIG_USART3_BAUD=57600 +CONFIG_USART3_RXBUFSIZE=180 +CONFIG_USART3_RXDMA=y +CONFIG_USART3_SERIAL_CONSOLE=y +CONFIG_USART3_TXBUFSIZE=1500 +CONFIG_USART3_TXDMA=y +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=1500 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_WATCHDOG=y diff --git a/boards/auterion/fmu-v6x/nuttx-config/scripts/bootloader_script.ld b/boards/auterion/fmu-v6x/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 0000000000..037356efd3 --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,215 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The Auterion FMUV6X uses an STM32H753II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The Auterion FMUV6X has a test point on board, the BOOT0 pin is at ground so by + * default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test + * point is pulled to 3.3V.then the boot will be from 0x1FF0:0000 + * + * The STM32H743II also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The bootloader uses the first sector of the flash, which is 128K in length. + */ + +MEMORY +{ + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 128K + dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K + sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K + sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K + sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K + sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K + bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/auterion/fmu-v6x/nuttx-config/scripts/flash-analysis-script.ld b/boards/auterion/fmu-v6x/nuttx-config/scripts/flash-analysis-script.ld new file mode 100644 index 0000000000..5df2f5180a --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/scripts/flash-analysis-script.ld @@ -0,0 +1,6 @@ +INCLUDE "script.ld" + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 10080K +} diff --git a/boards/auterion/fmu-v6x/nuttx-config/scripts/script.ld b/boards/auterion/fmu-v6x/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..860eb2ddd9 --- /dev/null +++ b/boards/auterion/fmu-v6x/nuttx-config/scripts/script.ld @@ -0,0 +1,229 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The Auterion FMUV6X uses an STM32H753II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The Auterion FMUV6X has a test point on board, the BOOT0 pin is at ground so by + * default, the STM32 will boot to address 0x0800:0000 in FLASH unless the test + * point is pulled to 3.3V.then the boot will be from 0x1FF0:0000 + * + * The STM32H743II also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1920K + + DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) +EXTERN(board_get_manifest) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + + /* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */ + . = ALIGN(16); + FILL(0xffff) + . += 16; + } > AXI_SRAM AT > FLASH = 0xffff + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Emit the the D3 power domain section for locating BDMA data */ + + .sram4_reserve (NOLOAD) : + { + *(.sram4) + . = ALIGN(4); + _sram4_heap_start = ABSOLUTE(.); + } > SRAM4 + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/auterion/fmu-v6x/performance-test.px4board b/boards/auterion/fmu-v6x/performance-test.px4board new file mode 100644 index 0000000000..5e69dd7ae3 --- /dev/null +++ b/boards/auterion/fmu-v6x/performance-test.px4board @@ -0,0 +1,31 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ETHERNET=y +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS7" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1" +CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3" +CONFIG_BOARD_ROMFSROOT="performance-test" +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_MTD=y +CONFIG_SYSTEMCMDS_MFT_CFG=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SD_BENCH=y +CONFIG_SYSTEMCMDS_SD_STRESS=y +CONFIG_SYSTEMCMDS_SERIAL_TEST=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/auterion/fmu-v6x/rover.px4board b/boards/auterion/fmu-v6x/rover.px4board new file mode 100644 index 0000000000..cd49a241b5 --- /dev/null +++ b/boards/auterion/fmu-v6x/rover.px4board @@ -0,0 +1,17 @@ +CONFIG_MODULES_AIRSPEED_SELECTOR=n +CONFIG_MODULES_FLIGHT_MODE_MANAGER=n +CONFIG_MODULES_FW_ATT_CONTROL=n +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n +CONFIG_MODULES_FW_RATE_CONTROL=n +CONFIG_MODULES_MC_ATT_CONTROL=n +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n +CONFIG_MODULES_MC_POS_CONTROL=n +CONFIG_MODULES_MC_RATE_CONTROL=n +CONFIG_MODULES_VTOL_ATT_CONTROL=n +CONFIG_DRIVERS_ROBOCLAW=y +CONFIG_MODULES_ROVER_ACKERMANN=y +CONFIG_MODULES_ROVER_DIFFERENTIAL=y +CONFIG_MODULES_ROVER_MECANUM=y diff --git a/boards/auterion/fmu-v6x/spacecraft.px4board b/boards/auterion/fmu-v6x/spacecraft.px4board new file mode 100644 index 0000000000..997a9054a2 --- /dev/null +++ b/boards/auterion/fmu-v6x/spacecraft.px4board @@ -0,0 +1,21 @@ +CONFIG_BOARD_PWM_FREQ=100000 +CONFIG_MODULES_AIRSPEED_SELECTOR=n +CONFIG_MODULES_FLIGHT_MODE_MANAGER=n +CONFIG_MODULES_FW_ATT_CONTROL=n +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n +CONFIG_MODULES_FW_RATE_CONTROL=n +CONFIG_MODULES_LAND_DETECTOR=n +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n +CONFIG_MODULES_MC_ATT_CONTROL=n +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n +CONFIG_MODULES_MC_POS_CONTROL=n +CONFIG_MODULES_MC_RATE_CONTROL=n +CONFIG_MODULES_VTOL_ATT_CONTROL=n +CONFIG_MODULES_ROVER_ACKERMANN=n +CONFIG_MODULES_ROVER_DIFFERENTIAL=n +CONFIG_MODULES_ROVER_MECANUM=n +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_SPACECRAFT=y diff --git a/boards/auterion/fmu-v6x/src/CMakeLists.txt b/boards/auterion/fmu-v6x/src/CMakeLists.txt new file mode 100644 index 0000000000..39ec808e1e --- /dev/null +++ b/boards/auterion/fmu-v6x/src/CMakeLists.txt @@ -0,0 +1,76 @@ +############################################################################ +# +# Copyright (c) 2016 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_compile_definitions(BOOTLOADER) + add_library(drivers_board + bootloader_main.c + init.cpp + usb.c + timer_config.cpp + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer #gpio + arch_io_pins # iotimer + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + can.c + i2c.cpp + init.cpp + led.c + mtd.cpp + sdio.c + spi.cpp + timer_config.cpp + usb.c + ) + add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + arch_board_hw_info + drivers__led # drv_led_start + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer + platform_gpio_mcp23009 + ) +endif() diff --git a/boards/auterion/fmu-v6x/src/board_config.h b/boards/auterion/fmu-v6x/src/board_config.h new file mode 100644 index 0000000000..c50f0705f2 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/board_config.h @@ -0,0 +1,520 @@ +/**************************************************************************** + * + * Copyright (c) 2016-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * AuterionFMU-v6x internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +#undef TRACE_PINS + +/* PX4IO connection configuration */ + +#define BOARD_USES_PX4IO_VERSION 2 +#define PX4IO_SERIAL_DEVICE "/dev/ttyS5" +#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX +#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX +#define PX4IO_SERIAL_BASE STM32_USART6_BASE +#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6 +#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX +#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX +#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB2ENR +#define PX4IO_SERIAL_RCC_EN RCC_APB2ENR_USART6EN +#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY +#define PX4IO_SERIAL_BITRATE 1500000 /* 1.5Mbps -> max rate for IO */ + +/* Configuration ************************************************************************************/ + +#define BOARD_HAS_LTC44XX_VALIDS 2 // N Bricks +#define BOARD_HAS_USB_VALID 1 // LTC Has USB valid +#define BOARD_HAS_NBAT_V 2d // 2 Digital Voltage +#define BOARD_HAS_NBAT_I 2d // 2 Digital Current + +/* PX4FMU GPIOs ***********************************************************************************/ + +/* Trace Clock and D0-D3 are available on the trace connector + * + * TRACECLK PE2 - Dedicated - Trace Connector Pin 1 + * TRACED0 PE3 - nLED_RED - Trace Connector Pin 3 + * TRACED1 PE4 - nLED_GREEN - Trace Connector Pin 5 + * TRACED2 PE5 - nLED_BLUE - Trace Connector Pin 7 + * TRACED3 PE6 - nARMED - Trace Connector Pin 8 + + */ + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V or used as TRACE0-2 */ + +#if !defined(TRACE_PINS) +# define GPIO_nLED_RED /* PE3 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) +# define GPIO_nLED_GREEN /* PE4 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) +# define GPIO_nLED_BLUE /* PE5 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN5) + +# define BOARD_HAS_CONTROL_STATUS_LEDS 1 +# define BOARD_OVERLOAD_LED LED_RED +# define BOARD_ARMED_STATE_LED LED_BLUE + +#else + +# define GPIO_TRACECLK1 (GPIO_TRACECLK |GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN2) +# define GPIO_TRACED0 (GPIO_TRACED0_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN3) +# define GPIO_TRACED1 (GPIO_TRACED1_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN4) +# define GPIO_TRACED2 (GPIO_TRACED2_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN5) +# define GPIO_TRACED3 (GPIO_TRACED3_2|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL) //(GPIO_ALT|GPIO_AF0|GPIO_PORTE|GPIO_PIN6) +//#define GPIO_TRACESWO //(GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN3) + +# undef BOARD_HAS_CONTROL_STATUS_LEDS +# undef BOARD_OVERLOAD_LED +# undef BOARD_ARMED_STATE_LED + +# define GPIO_nLED_RED GPIO_TRACED0 +# define GPIO_nLED_GREEN GPIO_TRACED1 +# define GPIO_nLED_BLUE GPIO_TRACED2 +# define GPIO_nARMED GPIO_TRACED3 +# define GPIO_nARMED_INIT GPIO_TRACED3 +#endif + + +/* SPI */ + +#define SPI6_nRESET_EXTERNAL1 /* PF10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN10) +#define GPIO_SYNC /* PE9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_100MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN9) + +/* I2C busses */ + +/* Devices on the onboard buses. + * + * Note that these are unshifted addresses. + */ +#define BOARD_MTD_NUM_EEPROM 2 /* MTD: base_eeprom, imu_eeprom*/ + +#define PX4_I2C_OBDEV_SE050 0x48 + +#define GPIO_I2C2_DRDY1_BMP388 /* PG5 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTG|GPIO_PIN5) + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that + * can be used by the Px4 Firmware in the adc driver + */ + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ + +#define ADC1_CH(n) (n) + +/* N.B. there is no offset mapping needed for ADC3 because */ +#define ADC3_CH(n) (n) + +/* We are only use ADC3 for REV/VER. + * ADC3_6V6 and ADC3_3V3 are mapped back to ADC1 + * To do this We are relying on PC2_C, PC3_C being connected to PC2, PC3 + * respectively by the SYSCFG_PMCR default of setting for PC3SO PC2SO PA1SO + * PA0SO of 0. + * + * 0 Analog switch closed (pads are connected through the analog switch) + * + * So ADC3_INP0 is GPIO_ADC123_INP12 + * ADC3_INP1 is GPIO_ADC12_INP13 + */ + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ + +#define PX4_ADC_GPIO \ + /* PA0 */ GPIO_ADC1_INP16, \ + /* PA4 */ GPIO_ADC12_INP18, \ + /* PB0 */ GPIO_ADC12_INP9, \ + /* PB1 */ GPIO_ADC12_INP5, \ + /* PC2 */ GPIO_ADC123_INP12, \ + /* PC3 */ GPIO_ADC12_INP13, \ + /* PF12 */ GPIO_ADC1_INP6, \ + /* PH3 */ GPIO_ADC3_INP14, \ + /* PH4 */ GPIO_ADC3_INP15 + +/* Define Channel numbers must match above GPIO pin IN(n)*/ +#define ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL /* PA0 */ ADC1_CH(16) +#define ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL /* PA4 */ ADC1_CH(18) +#define ADC_SCALED_VDD_3V3_SENSORS3_CHANNEL /* PB0 */ ADC1_CH(9) +#define ADC_SCALED_V5_CHANNEL /* PB1 */ ADC1_CH(5) +#define ADC_ADC3_6V6_CHANNEL /* PC2 */ ADC3_CH(12) +#define ADC_ADC3_3V3_CHANNEL /* PC3 */ ADC3_CH(13) +#define ADC_SCALED_VDD_3V3_SENSORS4_CHANNEL /* PF12 */ ADC1_CH(6) +#define ADC_HW_VER_SENSE_CHANNEL /* PH3 */ ADC3_CH(14) +#define ADC_HW_REV_SENSE_CHANNEL /* PH4 */ ADC3_CH(15) + +#define ADC_CHANNELS \ + ((1 << ADC_SCALED_VDD_3V3_SENSORS1_CHANNEL) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS2_CHANNEL) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS3_CHANNEL) | \ + (1 << ADC_SCALED_V5_CHANNEL) | \ + (1 << ADC_ADC3_6V6_CHANNEL) | \ + (1 << ADC_ADC3_3V3_CHANNEL)) | \ + (1 << ADC_SCALED_VDD_3V3_SENSORS4_CHANNEL) + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ + +#define HW_REV_VER_ADC_BASE STM32_ADC3_BASE + +#define SYSTEM_ADC_BASE STM32_ADC1_BASE + +/* HW has to large of R termination on ADC todo:change when HW value is chosen */ +#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f) + +/* HW Version and Revision drive signals Default to 1 to detect */ +#define BOARD_HAS_HW_SPLIT_VERSIONING + +#define GPIO_HW_VER_REV_DRIVE /* PG0 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN0) +#define GPIO_HW_REV_SENSE /* PH4 */ GPIO_ADC3_INP15 +#define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14 +#define HW_INFO_INIT_PREFIX "V6X" + +#define BOARD_NUM_SPI_CFG_HW_VERSIONS 1 +// Base/FMUM +#define V6X_16 HW_FMUM_ID(0x10) // FMUV6X, Auterion Sensor Set Rev 16 from EEPROM + +#define UAVCAN_NUM_IFACES_RUNTIME 1 + +/* HEATER + * PWM in future + */ +#define GPIO_HEATER_OUTPUT /* PB10 T2CH3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10) +#define HEATER_OUTPUT_EN(on_true) px4_arch_gpiowrite(GPIO_HEATER_OUTPUT, (on_true)) + +/* PE6 is nARMED + * The GPIO will be set as input while not armed HW will have external HW Pull UP. + * While armed it shall be configured at a GPIO OUT set LOW + */ +#if !defined(TRACE_PINS) +#define GPIO_nARMED_INIT /* PE6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN6) +#define GPIO_nARMED /* PE6 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN6) +#define BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE(enabled) px4_arch_configgpio((enabled) ? GPIO_nARMED : GPIO_nARMED_INIT) +#define BOARD_GET_EXTERNAL_LOCKOUT_STATE() px4_arch_gpioread(GPIO_nARMED) +#endif + + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 9 + + +/* Power supply control and monitoring GPIOs */ + +#define GPIO_nPOWER_IN_A /* PG1 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN1) +#define GPIO_nPOWER_IN_B /* PG2 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN2) +#define GPIO_nPOWER_IN_C /* PG3 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN3) + +#define GPIO_nVDD_BRICK1_VALID GPIO_nPOWER_IN_A /* Brick 1 Is Chosen */ +#define GPIO_nVDD_BRICK2_VALID GPIO_nPOWER_IN_B /* Brick 2 Is Chosen */ +#define BOARD_NUMBER_BRICKS 2 +#define BOARD_NUMBER_DIGITAL_BRICKS 2 +#define GPIO_nVDD_USB_VALID GPIO_nPOWER_IN_C /* USB Is Chosen */ + +#define GPIO_VDD_5V_PERIPH_nEN /* PG4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN4) +#define GPIO_VDD_5V_PERIPH_nOC /* PE15 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTE|GPIO_PIN15) +#define GPIO_VDD_5V_HIPOWER_nEN /* PG10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTG|GPIO_PIN10) +#define GPIO_VDD_5V_HIPOWER_nOC /* PF13 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTF|GPIO_PIN13) +#define GPIO_VDD_3V3_SENSORS4_EN /* PG8 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN8) +#define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PH2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN2) +#define GPIO_VDD_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) + +/* MCP23009 GPIO expander */ +#define BOARD_GPIO_VDD_5V_COMP_VALID "/dev/gpio4" +#define BOARD_GPIO_VDD_5V_CAN1_GPS1_VALID "/dev/gpio5" + + +/* Spare GPIO */ + +#define GPIO_PG6 /* PG6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN6) +#define GPIO_PD15 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN15) + +/* ETHERNET GPIO */ + +#define GPIO_ETH_POWER_EN /* PG15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN15) + +/* NFC GPIO */ + +#define GPIO_NFC_GPIO /* PC0 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN0) + + +/* Define True logic Power Control in arch agnostic form */ + +#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_nEN, !(on_true)) +#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, !(on_true)) +#define VDD_3V3_SENSORS4_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS4_EN, (on_true)) +#define VDD_3V3_SPEKTRUM_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SPEKTRUM_POWER_EN, (on_true)) +#define READ_VDD_3V3_SPEKTRUM_POWER_EN() px4_arch_gpioread(GPIO_VDD_3V3_SPEKTRUM_POWER_EN) +#define VDD_3V3_SD_CARD_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SD_CARD_EN, (on_true)) +#define VDD_3V3_ETH_POWER_EN(on_true) px4_arch_gpiowrite(GPIO_ETH_POWER_EN, (on_true)) + + +/* Tone alarm output */ + +#define TONE_ALARM_TIMER 14 /* Timer 14 */ +#define TONE_ALARM_CHANNEL 1 /* PF9 GPIO_TIM14_CH1OUT_2 */ + +#define GPIO_BUZZER_1 /* PF9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTF|GPIO_PIN9) + +#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 +#define GPIO_TONE_ALARM GPIO_TIM14_CH1OUT_2 + +/* USB OTG FS + * + * PA9 OTG_FS_VBUS VBUS sensing + */ +#define GPIO_OTGFS_VBUS /* PA9 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN9) + +/* High-resolution timer */ +#define HRT_TIMER 8 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */ + +#define HRT_PPM_CHANNEL /* T8C1 */ 1 /* use capture/compare channel 1 */ +#define GPIO_PPM_IN /* PI5 T8C1 */ GPIO_TIM8_CH1IN_2 + +/* Some RC protocols are bi-directional, therefore we need a half-duplex UART */ +#define RC_SERIAL_SINGLEWIRE +/* The STM32 UART by default wires half-duplex mode to the TX pin, but our + * signal in routed to the RX pin, so we need to swap the pins */ +#define RC_SERIAL_SWAP_RXTX + +/* Input Capture Channels. */ +#define INPUT_CAP1_TIMER 1 +#define INPUT_CAP1_CHANNEL /* T1C2 */ 2 +#define GPIO_INPUT_CAP1 /* PE11 */ GPIO_TIM1_CH2IN + +/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */ +#define PWMIN_TIMER 4 +#define PWMIN_TIMER_CHANNEL /* T4C2 */ 2 +#define GPIO_PWM_IN /* PD13 */ GPIO_TIM4_CH2IN_2 + +/* Safety Switch is HW version dependent on having an PX4IO + * So we init to a benign state with the _INIT definition + * and provide the the non _INIT one for the driver to make a run time + * decision to use it. + */ +#define GPIO_nSAFETY_SWITCH_LED_OUT_INIT /* PD10 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN10) +#define GPIO_nSAFETY_SWITCH_LED_OUT /* PD10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10) + +/* Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */ +#define GPIO_LED_SAFETY GPIO_nSAFETY_SWITCH_LED_OUT + +#define GPIO_SAFETY_SWITCH_IN /* PF5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTF|GPIO_PIN5) +/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */ +#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */ + +/* Power switch controls ******************************************************/ + +#define SPEKTRUM_POWER(_on_true) VDD_3V3_SPEKTRUM_POWER_EN(_on_true) + +/* + * FMUv6X has a separate RC_IN + * + * GPIO PPM_IN on PI5 T8CH1 + * SPEKTRUM_RX (it's TX or RX in Bind) on UART6 PC7 + * Inversion is possible in the UART and can drive GPIO PPM_IN as an output + */ + +#define GPIO_PPM_IN_AS_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTI|GPIO_PIN5) +#define SPEKTRUM_RX_AS_GPIO_OUTPUT() px4_arch_configgpio(GPIO_PPM_IN_AS_OUT) +#define SPEKTRUM_RX_AS_UART() /* Can be left as uart */ +#define SPEKTRUM_OUT(_one_true) px4_arch_gpiowrite(GPIO_PPM_IN_AS_OUT, (_one_true)) + +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* SD card bringup does not work if performed on the IDLE thread because it + * will cause waiting. Use either: + * + * CONFIG_BOARDCTL=y, OR + * CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y + */ + +#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_BOARDCTL) && \ + !defined(CONFIG_BOARD_INITTHREAD) +# warning SDIO initialization cannot be perfomed on the IDLE thread +#endif + +/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction) + * this board support the ADC system_power interface, and therefore + * provides the true logic GPIO BOARD_ADC_xxxx macros. + */ +#define BOARD_ADC_USB_CONNECTED (px4_arch_gpioread(GPIO_OTGFS_VBUS)) +#define BOARD_ADC_USB_VALID (!px4_arch_gpioread(GPIO_nVDD_USB_VALID)) + +/* FMUv6X never powers off the Servo rail */ + +#define BOARD_ADC_SERVO_VALID (1) + +#if !defined(BOARD_HAS_LTC44XX_VALIDS) || BOARD_HAS_LTC44XX_VALIDS == 0 +# define BOARD_ADC_BRICK1_VALID (1) +# define BOARD_ADC_BRICK2_VALID (0) +#elif BOARD_HAS_LTC44XX_VALIDS == 1 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (0) +#elif BOARD_HAS_LTC44XX_VALIDS == 2 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +#elif BOARD_HAS_LTC44XX_VALIDS == 3 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +# define BOARD_ADC_BRICK3_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK3_VALID)) +#elif BOARD_HAS_LTC44XX_VALIDS == 4 +# define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID)) +# define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID)) +# define BOARD_ADC_BRICK3_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK3_VALID)) +# define BOARD_ADC_BRICK4_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK4_VALID)) +#else +# error Unsupported BOARD_HAS_LTC44XX_VALIDS value +#endif + +#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_nOC)) +#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC)) + + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ + +#define BOARD_HAS_ON_RESET 1 + +#if defined(TRACE_PINS) +#define GPIO_TRACE \ + GPIO_TRACECLK1, \ + GPIO_TRACED0, \ + GPIO_TRACED1, \ + GPIO_TRACED2, \ + GPIO_TRACED3 +#else +#define GPIO_TRACE (GPIO_OUTPUT|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2) +#endif + +#define PX4_GPIO_INIT_LIST { \ + GPIO_TRACE, \ + PX4_ADC_GPIO, \ + GPIO_HW_VER_REV_DRIVE, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN2_TX, \ + GPIO_CAN2_RX, \ + GPIO_HEATER_OUTPUT, \ + GPIO_nPOWER_IN_A, \ + GPIO_nPOWER_IN_B, \ + GPIO_nPOWER_IN_C, \ + GPIO_VDD_5V_PERIPH_nEN, \ + GPIO_VDD_5V_PERIPH_nOC, \ + GPIO_VDD_5V_HIPOWER_nEN, \ + GPIO_VDD_5V_HIPOWER_nOC, \ + GPIO_VDD_3V3_SENSORS4_EN, \ + GPIO_VDD_3V3_SPEKTRUM_POWER_EN, \ + GPIO_VDD_3V3_SD_CARD_EN, \ + GPIO_PD15, \ + GPIO_SYNC, \ + SPI6_nRESET_EXTERNAL1, \ + GPIO_ETH_POWER_EN, \ + GPIO_NFC_GPIO, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_nSAFETY_SWITCH_LED_OUT_INIT, \ + GPIO_SAFETY_SWITCH_IN, \ + GPIO_PG6, \ + GPIO_nARMED_INIT \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +#define PX4_I2C_BUS_MTD 4,5 + + +#define BOARD_NUM_IO_TIMERS 5 + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the PX4FMU board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/auterion/fmu-v6x/src/bootloader_main.c b/boards/auterion/fmu-v6x/src/bootloader_main.c new file mode 100644 index 0000000000..77df9e78bc --- /dev/null +++ b/boards/auterion/fmu-v6x/src/bootloader_main.c @@ -0,0 +1,62 @@ +/**************************************************************************** + * + * Copyright (c) 2019-2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file bootloader_main.c + * + * FMU-specific early startup code for bootloader +*/ + +#include "board_config.h" +#include "bl.h" + +#include +#include +#include +#include +#include +#include "arm_internal.h" +#include + +extern int sercon_main(int c, char **argv); + +void board_late_initialize(void) +{ + sercon_main(0, NULL); +} + +extern void sys_tick_handler(void); +void board_timerhook(void) +{ + sys_tick_handler(); +} diff --git a/boards/auterion/fmu-v6x/src/can.c b/boards/auterion/fmu-v6x/src/can.c new file mode 100644 index 0000000000..cdebe7a3ad --- /dev/null +++ b/boards/auterion/fmu-v6x/src/can.c @@ -0,0 +1,142 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file can.c + * + * Board-specific CAN functions. + */ + +#if !defined(CONFIG_CAN) + +#include + +#include "board_config.h" + + +__EXPORT +uint16_t board_get_can_interfaces(void) +{ + uint16_t enabled_interfaces = 0x3; + + if (!PX4_MFT_HW_SUPPORTED(PX4_MFT_CAN2)) { + enabled_interfaces &= ~(1 << 1); + } + + return enabled_interfaces; +} + +#else + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_internal.h" + +#include "chip.h" +#include "stm32_can.h" +#include "board_config.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) +# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." +# undef CONFIG_STM32_CAN2 +#endif + +#ifdef CONFIG_STM32_CAN1 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int can_devinit(void); + +/************************************************************************************ + * Name: can_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/can. + * + ************************************************************************************/ + +int can_devinit(void) +{ + static bool initialized = false; + struct can_dev_s *can; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) { + /* Call stm32_caninitialize() to get an instance of the CAN interface */ + + can = stm32_caninitialize(CAN_PORT); + + if (can == NULL) { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + + if (ret < 0) { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} +#endif /* CONFIG_CAN */ diff --git a/boards/auterion/fmu-v6x/src/hw_config.h b/boards/auterion/fmu-v6x/src/hw_config.h new file mode 100644 index 0000000000..4ad1049fed --- /dev/null +++ b/boards/auterion/fmu-v6x/src/hw_config.h @@ -0,0 +1,128 @@ +/* + * hw_config.h + * + * Created on: May 17, 2015 + * Author: david_s5 + */ + +#ifndef HW_CONFIG_H_ +#define HW_CONFIG_H_ + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS0,1500000" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 53 +#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) +#define BOARD_FLASH_SECTORS (15) +#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) + +#define OSC_FREQ 16 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +/* + * Uncommenting this allows to force the bootloader through + * a PWM output pin. As this can accidentally initialize + * an ESC prematurely, it is not recommended. This feature + * has not been used and hence defaults now to off. + * + * # define BOARD_FORCE_BL_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN14) + * # define BOARD_FORCE_BL_PIN_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11) + * + * # define BOARD_POWER_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) + * # define BOARD_POWER_ON 1 + * # define BOARD_POWER_OFF 0 + * # undef BOARD_POWER_PIN_RELEASE // Leave pin enabling Power - un comment to release (disable power) + * +*/ + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#endif /* HW_CONFIG_H_ */ diff --git a/boards/auterion/fmu-v6x/src/i2c.cpp b/boards/auterion/fmu-v6x/src/i2c.cpp new file mode 100644 index 0000000000..8a557078e0 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/i2c.cpp @@ -0,0 +1,41 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusExternal(2), + initI2CBusExternal(3), + initI2CBusInternal(4), +}; diff --git a/boards/auterion/fmu-v6x/src/init.cpp b/boards/auterion/fmu-v6x/src/init.cpp new file mode 100644 index 0000000000..88fe88126c --- /dev/null +++ b/boards/auterion/fmu-v6x/src/init.cpp @@ -0,0 +1,299 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.cpp + * + * AuterionFMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialization. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "board_config.h" + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + /* set the peripheral rails off */ + + VDD_5V_PERIPH_EN(false); + board_control_spi_sensors_power(false, 0xffff); + VDD_3V3_SENSORS4_EN(false); + + bool last = READ_VDD_3V3_SPEKTRUM_POWER_EN(); + /* Keep Spektum on to discharge rail*/ + VDD_3V3_SPEKTRUM_POWER_EN(false); + + /* wait for the peripheral rail to reach GND */ + usleep(ms * 1000); + syslog(LOG_DEBUG, "reset done, %d ms\n", ms); + + /* re-enable power */ + + /* switch the peripheral rail back on */ + VDD_3V3_SPEKTRUM_POWER_EN(last); + board_control_spi_sensors_power(true, 0xffff); + VDD_3V3_SENSORS4_EN(true); + VDD_5V_PERIPH_EN(true); + +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(io_timer_channel_get_gpio_output(i)); + } + + /* + * On resets invoked from system (not boot) ensure we establish a low + * output state on PWM pins to disarm the ESC and prevent the reset from potentially + * spinning up the motors. + */ + if (status >= 0) { + up_mdelay(100); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +extern "C" __EXPORT void +stm32_boardinitialize(void) +{ + board_on_reset(-1); /* Reset PWM first thing */ + + /* configure LEDs */ + + board_autoled_initialize(); + + /* configure pins */ + + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + /* configure USB interfaces */ + + stm32_usbinitialize(); + + VDD_3V3_ETH_POWER_EN(true); + +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +__EXPORT int board_app_initialize(uintptr_t arg) +{ +#if !defined(BOOTLOADER) + + /* Power on Interfaces */ + VDD_3V3_SD_CARD_EN(true); + VDD_5V_PERIPH_EN(true); + VDD_5V_HIPOWER_EN(true); + VDD_3V3_SENSORS4_EN(true); + VDD_3V3_SPEKTRUM_POWER_EN(true); + + /* Need hrt running before using the ADC */ + + px4_platform_init(); + + // Use the default HW_VER_REV(0x0,0x0) for Ramtron + + stm32_spiinitialize(); + + /* Configure the HW based on the manifest */ + + px4_platform_configure(); + + if (OK == board_determine_hw_info()) { + syslog(LOG_INFO, "[boot] Rev 0x%1x : Ver 0x%1x %s\n", board_get_hw_revision(), board_get_hw_version(), + board_get_hw_type_name()); + + } else { + syslog(LOG_ERR, "[boot] Failed to read HW revision and version\n"); + } + + /* Configure the Actual SPI interfaces (after we determined the HW version) */ + + stm32_spiinitialize(); + + board_spi_reset(10, 0xffff); + + /* Configure the DMA allocator */ + + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + +# if defined(SERIAL_HAVE_RXDMA) + // set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event. + static struct hrt_call serial_dma_call; + hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)stm32_serial_dma_poll, NULL); +# endif + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_on(LED_GREEN); // Indicate Power. + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_RED); + } + + // Ensure Power is off for > 10 mS + usleep(15 * 1000); + VDD_3V3_SD_CARD_EN(true); + usleep(500 * 1000); + +# ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_RED); + return ret; + } + +# endif /* CONFIG_MMCSD */ + + ret = mcp23009_register_gpios(3, 0x25); + + if (ret != OK) { + led_on(LED_RED); + return ret; + } + +#endif /* !defined(BOOTLOADER) */ + + return OK; +} diff --git a/boards/auterion/fmu-v6x/src/led.c b/boards/auterion/fmu-v6x/src/led.c new file mode 100644 index 0000000000..1e33dd1299 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/led.c @@ -0,0 +1,235 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * PX4FMU LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +#ifdef CONFIG_ARCH_LEDS +static bool nuttx_owns_leds = true; +// B R S G +// 0 1 2 3 +static const uint8_t xlatpx4[] = {1, 2, 4, 0}; +# define xlat(p) xlatpx4[(p)] +static uint32_t g_ledmap[] = { + GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN + GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE + GPIO_nLED_RED, // Indexed by BOARD_LED_RED + GPIO_nSAFETY_SWITCH_LED_OUT, // Indexed by LED_SAFETY by xlatpx4 +}; + +#else + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_BLUE, // Indexed by LED_BLUE + GPIO_nLED_RED, // Indexed by LED_RED, LED_AMBER + 0, // Indexed by LED_SAFETY (defaulted to an input) + GPIO_nLED_GREEN, // Indexed by LED_GREEN +}; + +#endif + +__EXPORT void led_init(void) +{ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} + +#ifdef CONFIG_ARCH_LEDS +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: board_autoled_initialize + ****************************************************************************/ + +void board_autoled_initialize(void) +{ + led_init(); +} + +/**************************************************************************** + * Name: board_autoled_on + ****************************************************************************/ + +void board_autoled_on(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_HEAPALLOCATE: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_IRQSENABLED: + phy_set_led(BOARD_LED_BLUE, false); + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_STACKCREATED: + phy_set_led(BOARD_LED_GREEN, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, true); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, true); + phy_set_led(BOARD_LED_BLUE, true); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, true); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, true); + break; + } +} + +/**************************************************************************** + * Name: board_autoled_off + ****************************************************************************/ + +void board_autoled_off(int led) +{ + if (!nuttx_owns_leds) { + return; + } + + switch (led) { + default: + break; + + case LED_SIGNAL: + phy_set_led(BOARD_LED_GREEN, false); + break; + + case LED_INIRQ: + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_ASSERTION: + phy_set_led(BOARD_LED_RED, false); + phy_set_led(BOARD_LED_BLUE, false); + break; + + case LED_PANIC: + phy_set_led(BOARD_LED_RED, false); + break; + + case LED_IDLE : /* IDLE */ + phy_set_led(BOARD_LED_RED, false); + break; + } +} + +#endif /* CONFIG_ARCH_LEDS */ diff --git a/boards/auterion/fmu-v6x/src/mtd.cpp b/boards/auterion/fmu-v6x/src/mtd.cpp new file mode 100644 index 0000000000..8e57555eac --- /dev/null +++ b/boards/auterion/fmu-v6x/src/mtd.cpp @@ -0,0 +1,136 @@ +/**************************************************************************** + * + * Copyright (C) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include + +#include +#include +// KiB BS nB +static const px4_mft_device_t spi5 = { // FM25V02A on FMUM native: 32K X 8, emulated as (1024 Blocks of 32) + .bus_type = px4_mft_device_t::SPI, + .devid = SPIDEV_FLASH(0) +}; +static const px4_mft_device_t i2c3 = { // 24LC64T on Base 8K 32 X 256 + .bus_type = px4_mft_device_t::I2C, + .devid = PX4_MK_I2C_DEVID(3, 0x51) +}; +static const px4_mft_device_t i2c4 = { // 24LC64T on IMU 8K 32 X 256 + .bus_type = px4_mft_device_t::I2C, + .devid = PX4_MK_I2C_DEVID(4, 0x50) +}; + + +static const px4_mtd_entry_t fmum_fram = { + .device = &spi5, + .npart = 1, + .partd = { + { + .type = MTD_PARAMETERS, + .path = "/fs/mtd_params", + .nblocks = (32768 / (1 << CONFIG_RAMTRON_EMULATE_SECTOR_SHIFT)) + } + }, +}; + +static const px4_mtd_entry_t base_eeprom = { + .device = &i2c3, + .npart = 2, + .partd = { + { + .type = MTD_MFT_VER, + .path = "/fs/mtd_mft_ver", + .nblocks = 248 + }, + { + .type = MTD_NET, + .path = "/fs/mtd_net", + .nblocks = 8 // 256 = 32 * 8 + + } + }, +}; + +static const px4_mtd_entry_t imu_eeprom = { + .device = &i2c4, + .npart = 3, + .partd = { + { + .type = MTD_CALDATA, + .path = "/fs/mtd_caldata", + .nblocks = 240 + }, + { + .type = MTD_MFT_REV, + .path = "/fs/mtd_mft_rev", + .nblocks = 8 + }, + { + .type = MTD_ID, + .path = "/fs/mtd_id", + .nblocks = 8 // 256 = 32 * 8 + } + }, +}; + +static const px4_mtd_manifest_t board_mtd_config = { + .nconfigs = 3, + .entries = { + &fmum_fram, + &base_eeprom, + &imu_eeprom + } +}; + +static const px4_mft_entry_s mtd_mft = { + .type = MTD, + .pmft = (void *) &board_mtd_config, +}; + +static const px4_mft_entry_s mft_mft = { + .type = MFT, + .pmft = (void *) system_query_manifest, +}; + +static const px4_mft_s mft = { + .nmft = 2, + .mfts = { + &mtd_mft, + &mft_mft, + } +}; + +const px4_mft_s *board_get_manifest(void) +{ + return &mft; +} diff --git a/boards/auterion/fmu-v6x/src/sdio.c b/boards/auterion/fmu-v6x/src/sdio.c new file mode 100644 index 0000000000..869d757756 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/sdio.c @@ -0,0 +1,177 @@ +/**************************************************************************** + * + * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "board_config.h" +#include "stm32_gpio.h" +#include "stm32_sdmmc.h" + +#ifdef CONFIG_MMCSD + + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Card detections requires card support and a card detection GPIO */ + +#define HAVE_NCD 1 +#if !defined(GPIO_SDMMC1_NCD) +# undef HAVE_NCD +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static FAR struct sdio_dev_s *sdio_dev; +#ifdef HAVE_NCD +static bool g_sd_inserted = 0xff; /* Impossible value */ +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_ncd_interrupt + * + * Description: + * Card detect interrupt handler. + * + ****************************************************************************/ + +#ifdef HAVE_NCD +static int stm32_ncd_interrupt(int irq, FAR void *context) +{ + bool present; + + present = !stm32_gpioread(GPIO_SDMMC1_NCD); + + if (sdio_dev && present != g_sd_inserted) { + sdio_mediachange(sdio_dev, present); + g_sd_inserted = present; + } + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void) +{ + int ret; + +#ifdef HAVE_NCD + /* Card detect */ + + bool cd_status; + + /* Configure the card detect GPIO */ + + stm32_configgpio(GPIO_SDMMC1_NCD); + + /* Register an interrupt handler for the card detect pin */ + + stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt); +#endif + + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + + finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO); + + sdio_dev = sdio_initialize(SDIO_SLOTNO); + + if (!sdio_dev) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + + finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR); + + ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev); + + if (ret != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + return ret; + } + + finfo("Successfully bound SDIO to the MMC/SD driver\n"); + +#ifdef HAVE_NCD + /* Use SD card detect pin to check if a card is g_sd_inserted */ + + cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD); + finfo("Card detect : %d\n", cd_status); + + sdio_mediachange(sdio_dev, cd_status); +#else + /* Assume that the SD card is inserted. What choice do we have? */ + + sdio_mediachange(sdio_dev, true); +#endif + + return OK; +} + +#endif /* CONFIG_MMCSD */ diff --git a/boards/auterion/fmu-v6x/src/spi.cpp b/boards/auterion/fmu-v6x/src/spi.cpp new file mode 100644 index 0000000000..b1100edacf --- /dev/null +++ b/boards/auterion/fmu-v6x/src/spi.cpp @@ -0,0 +1,62 @@ +/**************************************************************************** + * + * Copyright (C) 2020, 2022 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM20602, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }, {GPIO::PortF, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin8}, SPI::DRDY{GPIO::PortI, GPIO::Pin7}), + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortI, GPIO::Pin4}), + }, {GPIO::PortE, GPIO::Pin7}), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_SENSORS4_EN from board_config.h + // }, {GPIO::PortG, GPIO::Pin8}), + initSPIBus(SPI::Bus::SPI5, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}) + }), + initSPIBusExternal(SPI::Bus::SPI6, { + initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}), + initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/auterion/fmu-v6x/src/timer_config.cpp b/boards/auterion/fmu-v6x/src/timer_config.cpp new file mode 100644 index 0000000000..928f4916f0 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/timer_config.cpp @@ -0,0 +1,80 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +/* Timer allocation + * + * TIM5_CH4 T FMU_CH1 + * TIM5_CH3 T FMU_CH2 + * TIM5_CH2 T FMU_CH3 + * TIM5_CH1 T FMU_CH4 + * + * TIM4_CH2 T FMU_CH5 + * TIM4_CH3 T FMU_CH6 + * + * TIM12_CH1 T FMU_CH7 + * TIM12_CH2 T FMU_CH8 + * + * TIM1_CH2 T FMU_CAP1 < Capture + * TIM1_CH3 T SPI2_DRDY2_ISM330_INT2 < Capture or GPIO INT + * TIM1_CH1 T SPIX_SYNC > Pulse or GPIO strobe + * + * TIM2_CH3 T HEATER > PWM OUT or GPIO + * + * TIM14_CH1 T BUZZER_1 - Driven by other driver + * TIM8_CH1_IN T FMU_PPM_INPUT - Sampled byt HRT by other driver + */ + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer5, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), + initIOTimer(Timer::Timer12), + initIOTimer(Timer::Timer1), + initIOTimer(Timer::Timer2), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel4}, {GPIO::PortI, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel3}, {GPIO::PortH, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel2}, {GPIO::PortH, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer5, Timer::Channel1}, {GPIO::PortH, GPIO::Pin10}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel1}, {GPIO::PortH, GPIO::Pin6}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel2}, {GPIO::PortH, GPIO::Pin9}), + initIOTimerChannelCapture(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/auterion/fmu-v6x/src/usb.c b/boards/auterion/fmu-v6x/src/usb.c new file mode 100644 index 0000000000..70eebc6fe0 --- /dev/null +++ b/boards/auterion/fmu-v6x/src/usb.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * + * Copyright (C) 2016 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file usb.c + * + * Board-specific USB functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include "board_config.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the PX4FMU board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32H7_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} diff --git a/boards/auterion/fmu-v6x/uuv.px4board b/boards/auterion/fmu-v6x/uuv.px4board new file mode 100644 index 0000000000..3a7b00f13d --- /dev/null +++ b/boards/auterion/fmu-v6x/uuv.px4board @@ -0,0 +1,23 @@ +CONFIG_MODULES_AIRSPEED_SELECTOR=n +CONFIG_MODULES_FLIGHT_MODE_MANAGER=n +CONFIG_MODULES_FW_ATT_CONTROL=n +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_FW_POS_CONTROL=n +CONFIG_MODULES_FW_RATE_CONTROL=n +CONFIG_MODULES_FW_MODE_MANAGER=n +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n +CONFIG_MODULES_LAND_DETECTOR=n +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n +CONFIG_MODULES_MC_ATT_CONTROL=n +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n +CONFIG_MODULES_MC_POS_CONTROL=n +CONFIG_MODULES_MC_RATE_CONTROL=n +CONFIG_MODULES_VTOL_ATT_CONTROL=n +CONFIG_MODULES_ROVER_ACKERMANN=n +CONFIG_MODULES_ROVER_DIFFERENTIAL=n +CONFIG_MODULES_ROVER_MECANUM=n +CONFIG_MODULES_SPACECRAFT=n +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_UUV_ATT_CONTROL=y +CONFIG_MODULES_UUV_POS_CONTROL=y diff --git a/boards/auterion/fmu-v6x/zenoh.px4board b/boards/auterion/fmu-v6x/zenoh.px4board new file mode 100644 index 0000000000..cb14fde935 --- /dev/null +++ b/boards/auterion/fmu-v6x/zenoh.px4board @@ -0,0 +1,4 @@ +# CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE is not set +CONFIG_DRIVERS_UAVCAN=n +CONFIG_MODULES_UXRCE_DDS_CLIENT=n +CONFIG_MODULES_ZENOH=y diff --git a/boards/px4/fmu-v6x/default.px4board b/boards/px4/fmu-v6x/default.px4board index 45030adde4..4a20430f10 100644 --- a/boards/px4/fmu-v6x/default.px4board +++ b/boards/px4/fmu-v6x/default.px4board @@ -21,7 +21,6 @@ CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_AUAV=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GNSS_SEPTENTRIO=y -CONFIG_DRIVERS_GPIO_MCP23009=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16470=y @@ -39,7 +38,6 @@ CONFIG_DRIVERS_OSD_MSP_OSD=y CONFIG_DRIVERS_POWER_MONITOR_INA226=y CONFIG_DRIVERS_POWER_MONITOR_INA228=y CONFIG_DRIVERS_POWER_MONITOR_INA238=y -CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y CONFIG_DRIVERS_PWM_INPUT=y CONFIG_DRIVERS_PWM_OUT=y CONFIG_DRIVERS_PX4IO=y diff --git a/boards/px4/fmu-v6x/init/rc.board_defaults b/boards/px4/fmu-v6x/init/rc.board_defaults index 2d9a6ea49a..7dfe7b546a 100644 --- a/boards/px4/fmu-v6x/init/rc.board_defaults +++ b/boards/px4/fmu-v6x/init/rc.board_defaults @@ -9,35 +9,13 @@ param set-default SENS_EN_INA238 0 param set-default SENS_EN_INA228 0 param set-default SENS_EN_INA226 0 -if ver hwbasecmp 009 010 011 -then - # Skynode: use the "custom participant", IP=10.41.10.1 config for uxrce_dds_client - param set-default UXRCE_DDS_PTCFG 2 - param set-default UXRCE_DDS_AG_IP 170461697 - param set-default UXRCE_DDS_CFG 1000 - - # The buzzer draws too much power (0.2A) on the GPS power rail (limit 0.45A). - param set-default CBRK_BUZZER 782097 -else - # Mavlink ethernet (CFG 1000) - param set-default MAV_2_CONFIG 1000 - param set-default MAV_2_BROADCAST 1 - param set-default MAV_2_MODE 0 - param set-default MAV_2_RADIO_CTL 0 - param set-default MAV_2_RATE 100000 - param set-default MAV_2_REMOTE_PRT 14550 - param set-default MAV_2_UDP_PRT 14550 -fi +# Mavlink ethernet (CFG 1000) +param set-default MAV_2_CONFIG 1000 +param set-default MAV_2_BROADCAST 1 +param set-default MAV_2_MODE 0 +param set-default MAV_2_RADIO_CTL 0 +param set-default MAV_2_RATE 100000 +param set-default MAV_2_REMOTE_PRT 14550 +param set-default MAV_2_UDP_PRT 14550 safety_button start - -# GPIO Expander driver on external I2C3 -if ver hwbasecmp 009 -then - # No USB - mcp23009 start -b 3 -X -D 0xf0 -O 0xf0 -P 0x0f -U 10 -fi -if ver hwbasecmp 00a 008 -then - mcp23009 start -b 3 -X -D 0xf1 -O 0xf0 -P 0x0f -U 10 -fi diff --git a/boards/px4/fmu-v6x/init/rc.board_mavlink b/boards/px4/fmu-v6x/init/rc.board_mavlink deleted file mode 100644 index 713d7a41b7..0000000000 --- a/boards/px4/fmu-v6x/init/rc.board_mavlink +++ /dev/null @@ -1,13 +0,0 @@ -#!/bin/sh -# -# PX4 FMUv6X specific board MAVLink startup script. -#------------------------------------------------------------------------------ - -# if skynode base board is detected start Mavlink on Telem2 -if ver hwbasecmp 009 010 011 -then - mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z - - # Ensure nothing else starts on TEL2 (ttyS4) - set PRT_TEL2_ 1 -fi diff --git a/boards/px4/fmu-v6x/init/rc.board_sensors b/boards/px4/fmu-v6x/init/rc.board_sensors index 100c674108..75eaba3d1c 100644 --- a/boards/px4/fmu-v6x/init/rc.board_sensors +++ b/boards/px4/fmu-v6x/init/rc.board_sensors @@ -55,22 +55,13 @@ then set INA_CONFIGURED yes fi -#Start Auterion Power Module selector for Skynode boards -if ver hwbasecmp 009 010 011 +if [ $INA_CONFIGURED = no ] then - pm_selector_auterion start - - # Auterion's INA238 uses a shunt value of 0.0003 instead of 0.0005. - param set-default INA238_SHUNT 0.0003 -else - if [ $INA_CONFIGURED = no ] + # INA226, INA228, INA238 auto-start + i2c_launcher start -b 1 + if [ $HAVE_PM2 = yes ] then - # INA226, INA228, INA238 auto-start - i2c_launcher start -b 1 - if [ $HAVE_PM2 = yes ] - then - i2c_launcher start -b 2 - fi + i2c_launcher start -b 2 fi fi @@ -96,33 +87,22 @@ else icm20649 -s -R 6 start else # Internal SPI BMI088 - if ver hwbasecmp 009 010 011 + if ver hwtypecmp V6X010 then - bmi088 -A -R 6 -s start - bmi088 -G -R 6 -s start + bmi088 -A -R 0 -s start + bmi088 -G -R 0 -s start else - if ver hwtypecmp V6X010 - then - bmi088 -A -R 0 -s start - bmi088 -G -R 0 -s start - else - bmi088 -A -R 4 -s start - bmi088 -G -R 4 -s start - fi + bmi088 -A -R 4 -s start + bmi088 -G -R 4 -s start fi fi # Internal SPI bus ICM42688p - if ver hwbasecmp 009 010 011 + if ver hwtypecmp V6X010 then - icm42688p -R 12 -s start + icm42688p -R 14 -s start else - if ver hwtypecmp V6X010 - then - icm42688p -R 14 -s start - else - icm42688p -R 6 -s start - fi + icm42688p -R 6 -s start fi if ver hwtypecmp V6X003 V6X004 @@ -130,13 +110,8 @@ else # Internal SPI bus ICM-42670-P (hard-mounted) icm42670p -R 10 -s start else - if ver hwbasecmp 009 010 011 - then - icm20602 -R 6 -s start - else - # Internal SPI bus ICM-20649 (hard-mounted) - icm20649 -R 14 -s start - fi + # Internal SPI bus ICM-20649 (hard-mounted) + icm20649 -R 14 -s start fi fi diff --git a/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig b/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig index f0a8d6ae86..ec6b1c7e2b 100644 --- a/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig +++ b/boards/px4/fmu-v6x/nuttx-config/nsh/defconfig @@ -91,7 +91,6 @@ CONFIG_DEBUG_SYMBOLS=y CONFIG_DEBUG_TCBINFO=y CONFIG_DEFAULT_SMALL=y CONFIG_DEV_FIFO_SIZE=0 -CONFIG_DEV_GPIO=y CONFIG_DEV_PIPE_MAXSIZE=1024 CONFIG_DEV_PIPE_SIZE=70 CONFIG_DEV_URANDOM=y diff --git a/boards/px4/fmu-v6x/src/CMakeLists.txt b/boards/px4/fmu-v6x/src/CMakeLists.txt index 39ec808e1e..605cf16ac9 100644 --- a/boards/px4/fmu-v6x/src/CMakeLists.txt +++ b/boards/px4/fmu-v6x/src/CMakeLists.txt @@ -71,6 +71,5 @@ else() nuttx_arch # sdio nuttx_drivers # sdio px4_layer - platform_gpio_mcp23009 ) endif() diff --git a/boards/px4/fmu-v6x/src/board_config.h b/boards/px4/fmu-v6x/src/board_config.h index a57610545c..3259c421d5 100644 --- a/boards/px4/fmu-v6x/src/board_config.h +++ b/boards/px4/fmu-v6x/src/board_config.h @@ -270,11 +270,6 @@ #define GPIO_VDD_3V3_SPEKTRUM_POWER_EN /* PH2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTH|GPIO_PIN2) #define GPIO_VDD_3V3_SD_CARD_EN /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13) -/* MCP23009 GPIO expander */ -#define BOARD_GPIO_VDD_5V_COMP_VALID "/dev/gpio4" -#define BOARD_GPIO_VDD_5V_CAN1_GPS1_VALID "/dev/gpio5" - - /* Spare GPIO */ #define GPIO_PG6 /* PG6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN6) diff --git a/boards/px4/fmu-v6x/src/init.cpp b/boards/px4/fmu-v6x/src/init.cpp index d914b75497..5d2a614206 100644 --- a/boards/px4/fmu-v6x/src/init.cpp +++ b/boards/px4/fmu-v6x/src/init.cpp @@ -74,7 +74,6 @@ #include #include #include -#include /**************************************************************************** * Pre-Processor Definitions @@ -286,13 +285,6 @@ __EXPORT int board_app_initialize(uintptr_t arg) # endif /* CONFIG_MMCSD */ - ret = mcp23009_register_gpios(3, 0x25); - - if (ret != OK) { - led_on(LED_RED); - return ret; - } - #endif /* !defined(BOOTLOADER) */ return OK; diff --git a/boards/px4/fmu-v6xrt/default.px4board b/boards/px4/fmu-v6xrt/default.px4board index 84e76cd888..f64b7801e4 100644 --- a/boards/px4/fmu-v6xrt/default.px4board +++ b/boards/px4/fmu-v6xrt/default.px4board @@ -40,7 +40,6 @@ CONFIG_DRIVERS_OSD_MSP_OSD=y CONFIG_DRIVERS_POWER_MONITOR_INA226=y CONFIG_DRIVERS_POWER_MONITOR_INA228=y CONFIG_DRIVERS_POWER_MONITOR_INA238=y -CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y CONFIG_DRIVERS_PWM_OUT=y CONFIG_DRIVERS_PX4IO=y CONFIG_COMMON_RC=y diff --git a/boards/px4/fmu-v6xrt/init/rc.board_sensors b/boards/px4/fmu-v6xrt/init/rc.board_sensors index ae60e13536..99248dde72 100644 --- a/boards/px4/fmu-v6xrt/init/rc.board_sensors +++ b/boards/px4/fmu-v6xrt/init/rc.board_sensors @@ -69,19 +69,13 @@ then set INA_CONFIGURED yes fi -#Start Auterion Power Module selector for Skynode boards -if ver hwbasecmp 009 010 +if [ $INA_CONFIGURED = no ] then - pm_selector_auterion start -else - if [ $INA_CONFIGURED = no ] + # INA226, INA228, INA238 auto-start + i2c_launcher start -b 1 + if [ $HAVE_PM2 = yes ] then - # INA226, INA228, INA238 auto-start - i2c_launcher start -b 1 - if [ $HAVE_PM2 = yes ] - then - i2c_launcher start -b 2 - fi + i2c_launcher start -b 2 fi fi From ba1e658750ac044b13ba34824f5eeec46952db64 Mon Sep 17 00:00:00 2001 From: Niklas Hauser Date: Fri, 10 Oct 2025 14:16:00 +0200 Subject: [PATCH 179/812] boards: remove USB device from Auterion FMUv6x --- .../extras/auterion_fmu-v6s_bootloader.bin | Bin 32888 -> 35108 bytes boards/auterion/fmu-v6x/default.px4board | 1 - .../extras/auterion_fmu-v6x_bootloader.bin | Bin 46892 -> 35416 bytes .../fmu-v6x/nuttx-config/bootloader/defconfig | 12 -- .../fmu-v6x/nuttx-config/nsh/defconfig | 12 -- boards/auterion/fmu-v6x/src/CMakeLists.txt | 2 - boards/auterion/fmu-v6x/src/board_config.h | 4 + boards/auterion/fmu-v6x/src/bootloader_main.c | 3 - boards/auterion/fmu-v6x/src/hw_config.h | 15 ++- boards/auterion/fmu-v6x/src/init.cpp | 4 - boards/auterion/fmu-v6x/src/usb.c | 105 ------------------ 11 files changed, 11 insertions(+), 147 deletions(-) delete mode 100644 boards/auterion/fmu-v6x/src/usb.c diff --git a/boards/auterion/fmu-v6s/extras/auterion_fmu-v6s_bootloader.bin b/boards/auterion/fmu-v6s/extras/auterion_fmu-v6s_bootloader.bin index 2c79c4b1bab5367e36ca229181ada79f098e7877..233552b39789f86ffa3ef04330d8fcaa538d0de5 100755 GIT binary patch delta 10502 zcmaia3wTu3x#+*v-ZQgFhGg<^7?Ke7Jc5%4VIYX%CBr1FypV*46a{s7s2d_=1RoJ; zXF{+>Nh`8A=SH!XR_c*TE0YkfsSH8kv{qZ2VCVrN9+dWsh`^2s?mh4OtrJ_4wcGU!(f)!M#|!X(HG(oIm3Q{E{fpF6=@cI*f}J`LtjYdJ7v0YtI+F zUznX|kvaUbtD_$*UIo_r1$w(`~7BLM3M;Zu1FOsLm zkq9!cf++NY+@P}GjS0Hv&OP)#eJkD`r$hQO?>)z%|Ev#$d5e*C-rajF{K(_lQcrs? zm_?FM?n!V~ljY7j>r)PLXTzP1r!H$MwAM@QSnf^SQ74kS+*pppDjLusiBv2paARw! z2g#G77cK+B@|6g0t#DUJsC3ZI31>cn~_YU|XXD+bSK{Y&x*nbzm#gfo);|2%`il&!_E07W z8+7!ejPmRax_?Z?nuT6^e4LSrnOeR&Uge`DnPs`N;+P;}Cm^qli3G`?MAzu(rp#IR zKYmAlnYj$dqV&5=F?%ptNkD!tX6i$SDhZbV7NvGWwU%vUmzHidEK5sO!PcaspBP+t zjgDq#O~F5l&^cL~81zP#h*w7Fhgq!*a%ETI3lX{_+n&T_J50vN)$V6UvpPgl84!t0 zx)u}&mQjRW%NFsmFg4_q7hqY}2mP<=!M0Biw#r@&K{hk76D%Eq zo(MghvrdoYmay2jq87`|VVaj~Ps6e~%;tD6NRQ_ljn3Ndy0Kgp{_$v52iVUH8bmBV zuF}@rbv%~Ogy`qFJ2RMkem`NUk#4!o#$&l9ME~`+yUMVJZoGf}F5Qv9SMrOR zE-dd1X$jb`4Scz~j=08P>zD0Vt`6-rF5|I$XNayeig-tYwi-+D$^<=VjN-@g=r1P_ zd@@eIp71!2*xojvJ5QW2sz1fYNr#+UxjGYRGy9H zzl3<=uU<&d%qD{6!y!6v;uIdsJt6w=L~#n1e-ZK#^s-2V5hP&wN1^KKfnbY#ADjuc z$mwu8Slb2y9Vjr-QxnOo&s5~-a9tlnq8en z36`g-$O2}5Bn_Yl$xR8GmtUQ6KF&~+Rrb-hQTk|pp|0sT6X`?rrTiNFUX-5C->YTn zW7E;C1xqq&q99fVpg*Nm^pk?ua%+<-PAL5ezEE?1gA2*qW7Ie4HSs`1Lu&mn;?|Wt zVJD_LrV}KW#NKu(gKiPYFGc8Gg+~3v*kPA4=oFFci%@r=ah?$S)y;;M2v1h|VZ^Dy zw+l;d-zE~nOg4rRWuK^lqk6C%)`RV!{(JGE-Gwvp{uuqLaAwBk=*2!mZQv_|6Ump3 z(SdmrifaGXjpU)|uF_vZWHi_!-v&2=$MkfG#Zs^!VwLj!uSjiDTJvVsVRZgz0g=o!4#PYK@>sZ9HH%1Gr59@b^8Jn0PKB}ibwJzh4>|P{~3*-G-GThxhn$^)C zgnq^jCOMV8dZKI4kmc%h19#;Vm;dyzjynVLWVP(6$^epe;c!rB13}Y(y@uZ9>I?%< zkenR`tMw_iEQSMlMIWxukx)gB+fxJmr}RvD(ThxH{KKe${6nwa? z=aZsO5I)>SU%P!)+Tk|lEU?@dr=Q<$FKc}_u}lX~+f$9xRV+_anbMALFiEC9eM7#K zFKz1sQ6p!Cn1`7Y4+g#xoEjPRF~^^BLQ^lx3$-MZWZiv61s|4sW3vfQ93-LK6(7%r z@MF0@Mt9mv3K)4rS*}uBX(c1s1Eu9?9Q{e@G&~Zg$4m46+xb0PM!zhb z<7KnRy?D#@(JUWWedg<XcFPkYr)!-?*6x3%iD+Uee_?l3$d)wznsocEwHSXx~5SaPUCl6lPe z*dbOIbKJhstPVMFa@3`<%9-54F<6+-=j%(W-Vfqpp}%U(xBjDGx4PZnzj3ie=&zD} z%Rdf6fBbUdI=7`=ebeBn;kJCLb~;{O=c)0251ie2V)TT;Q)B4mw+yKV0p!uhkb2m0 zVnl>?mwsS!>5zIv99YARAe`0@)>GgbA4Uv)%)AxFlDh8gs0?^|HCuQBQ+|BpOtQ;wA`fpkqjoybAqLwk z5MAGl>7`~3)iwP2GB*okU!;PR5WX(e|G9|v2#Z^td=~tq9E6Xxj^14I+!6Dc<&U0j z&Z)LMx_-lX|B%}0fFg8gC^@EPFQTtEW9rqjA@2bB2NCO|7Lr!S(5EhE-cd?GULDaL zaRk_EBTC@=i?M3uc9F_8Vz{TrR%qMVmqWm_}@{u^!Hf`Jy<1eJkb_v}-* zJNEnUD_rhczVJTWIOf~7Pu*e2t8#tamhF-qc&FDrr1}gXI}#xNS1^xU51#k$m9XsK z9Hqv=>@nXqejs}cy!w7@Mb=&Fc1OE(a@3czOWolBd3xfM>H|ATC8-1W&xCz7+6Hltpv5IY9V_1dN5hmjF|q zsUL}kfT4G<`lch7RQL@fp?sY%_>wmB3>)%vgtg{r zwXD^Vuf@sMmm(k<0&J4&1B{;;mb`Ue2P=EQ!f)B7wu;wBv)X(`IV7dT%pEc%9#T7- z4yuofrIK~*?6xY|z?HgL+gp-V_9E^r_s2=Ao>U5hso`Z8H)t?VsEsM(ll#h%tnzp+ z$33L(frRp#$dI}Z63U^-kb1ze+@I2wmElyW4>Qd;=onJFk~k*uwP7YxAjd-t_o|~Z z00!igtMMvF@B8aopF5%<{1zy#8e}_~=uR#}oZIjUTZUy$ZA|$noSM2LoSJ%9cu4Iu z>{E9*?4({=?Xryha2YoS%X6w4*uKQ_hAb)F$rjux?o*$pOQ+>{cgGl%BUQ<;yh@(L z<+#CmP<`CNWU7@d7n=MauL+$}UxgvH6MPmh3yzrbY3ngK(Ac-!gjIeeP zO7;D@R=qW+D&1`eq@V(;5(LD1p-NgM`MNzdYA;Wm(s=SyiIdLh<_)cHU10g5Re$^B zQcl)!IE=nE*X`>UM7^ksa5<}`51LA(_0lWubyBnRse3EOohjLvQ@u{gSzEGky>y>j zJLardE2T-6G3N|6v3Bg@W9uaU4WD=UMyvcDXX>w#b)0wk+O?9tK3&RlrZ-eLSw}Un z;dZbfb4=+Dt(WqpVO`%DB*v8YLukQwgFQjE%gK-vznB<92S)NaZKR5Gb57)y7a$boMqh7g zm(u+oNL@8d`4-s64;&b&<@i#3cDNf`P6rQ+tl)5|=4@l-$?orh$fC1;7z9fW`S&37 zvjrUmU=c-4)?%2F)z~N(2)`iRWZV^P&Mp-WSjd6a`&-d0jjYoM5zUQfCf+N>l+`hj zc%Qk~Fte*BSIyAJl$XMW^1lxTzLKAVem3AP%-pu#dSVn8iS^A@gQic{EN*4`4^w=% zUmrF6cIe8G-#_suJH*@y)7UT`+ z&G`sLG?wvo|04a+|0l0$Z|jNfEz*Wod}Roq?%oGPwSXk?H+);cmfQ59Ne-Zj(?Jl! zx9rr_n$v(~9dh*QZF~e(yezHt?{5X$-4b`@G&kJ+3M^8sPJF|+tzLSy>H26^`#*b3 zunc!&&lVPHI#QB*)YV#G8ezJS8IWpOOAvhxFUa}sRsJlIMm_Do%OH}1jqs#Za~B&f&7Pe zq5oDmzwiHsJxQ2ucl?--DPM#sKYi6KE(~`4u${z|H)3E%!$|x#2y$HIBq$yIObLqQ z>mZBka6`V7-WOL|-t*M#()R3~K7>BLSB)Wj4`sOO!T^$7itqFGDvx@4 z(&#LE!StAhT#~w6+@SRZRAJr84!45VL1N19!qj=Ett=~MeF2qb41$#(5x}~WiOeN; zTzN_byXHJQ10|Hv0GeyvX$VlUvestk#nn7Pv-h|(16e9s04kabrOIG-9+;!bBMFfh z0<^PoCNA4aKd77~3Rz$~@GJ=I1xS^i8Z19`j3vo-#;9qw%^On=BtR4bU~L>5-iqsR zEt2=X3;nis5So1;czSs!cvHGxBwaO^HY2l0RyTLm@FPZuDVsuHZf+xB zUe+vPNKB~> z@r5V8-RA>aqwGsZ`(Jf=PWP#0VxL-KFm#XWZgZIj&Z!OqnlWxoc6VQ>9QLrCSq`aX z;yG0iv&SxaH3MnIy1{JOnQ7`DZ$>jUD#||>9A6w_ftA}=OA-M>*Yk}Eh#O!*g;FPuDF-il@! z<%IT*0aQL64bmeMjO(woCc2yZu57lGe5tF3FVvl929qCFbU&+I*^JC~vVUV&4g0R#^F^>lp1^+|RC+TBjJUNh;-MeUop@hYl!+Vu zOxze#a^t^seLct>kpojNt5xk%2Dy!_*~pLNCD%Gt)fFxphN<-f{D>Qab(zXP2vcVa z@>kmN#0q|-U>tv?om=^EE!nm#uJrhU2F+L_v!aUiLkd;VEF*}6@MOPe(W%&VK3=EBr3&!_Y=vk|8L zhYEW#&NBvIh}s#0pKBc3?m_aL&|K;DE91Bxm-aL>I>Sk$BM)3o54OnLG?#-cV?npy zRqi!JQprI(B$Tw9^;}3Od;~0&gdZ_!vq(aTg~8$=tfq!j{qrE9d>aOHB|-A!2$&rN z$@vj0v6GYm416Uo1o`Peb$jx7LXbJ3)W=_Mo$F_Y+61qAm}!npS2iDGXAYk5=7cgQ zzW!zhBdkw#Q0_lw2zYwGm#a&gdsZ!2hEOMc%h|lDHo@|mCIGoAfz13!0f2m0vStU6 zXD9fPJV0hP5y&(8*(jQ%Z02emB&zsh)>c%iJ%{F6JJZ)yR*CZ=bc;+*7o(>hLfA~H#PfBHC%Y-x2V&#eq8sF zkVRaUcj9u!jFY?byRQa4H48U!ovuewxP5eC^UE&7(X>IX^GL{Iz~T1Mp2)};isV-0 zcXJbWf%U{?L&eGUd43kJB$U4fSm~*u*IdTJF$^{kS-v5c2qcSuyf^7A1rk?&c8pr8 z?A9gm8np;KeQ5sct#7$B7b;0ynHg`9ji3g8pcX+~nMyZTOGs;^#&cZKMN>K*v!5&C7d9Xmo)zo-yzkI=G3cAOrfD;L?#QN^vY znCDxSonY<^{VizdO(-XCCbQ$p8}#Rkrg$*s8l})R<4c3Ayw{}^3BaSL~zCx={TCpwFv>}XWtllIl?lc zIVvhG>4W?NM_f4*HT4++(@I7MzYD^Mi9_^ma=Y>0d?4tvSRR%60wc+B9 z!l;s!V3>V9jdg1g+D-lSRcIr=tgjjjy}0$Su$71F29x- zXR)rR!6dP~E2|5=nuc_LOj)f)l}mA!ri?4C$Dsd05sSMtL{B2hxfr{XqK?MwvWW6& zEUD;aqZiOTJBcdkQCs)d!7|^q;GMmE;do*ko?JZPY(#lGMz=JY1c%C#B=FP5dh{ec z*I10@5apZ7@F_i=(X^r{syvoJ=C34>(^bxDeahO2=2~~L%aYWtz~<@Apf6e`tcfaD z!#ug#eZY^s`UaL-jw`Jpmi1s3Wd?~V!=W#Bvup~7m{o}?k>4?Fi;Te&NF}9BlEcq= zxl%NELh{rkF-bzu!lecHmwj~J((;mvkxJ)-;SL4uIp9ZcMig5d5s^fcPhyk&RZ^+D zU21k~pN=SB$LPMLbEZBVvl2um)H7d|7ZZur98+3V2K^+qPhDdG>*V6sH)Nf4khrpu zMwaGpd_WDd=tL_ATVzgq^=5W`fh!Z7u1u)=0SNHXD|1P- z_FWJ+q>k>DPbLqiFN|^1!J{u z7ZcVgqKsFIlbGL7&5A{69c@@qgzpK_tt;HtbukMmCiqQ|C#ag&&@AQ@T4OwM`w^Kz zv~PkuyXVG=%Lujh{O8KeIIXK41g{T-XM8;?@6F{=7j3@(o_n(f&0l}9RpW4&t7XiG zmC7g-y*H8h&-)&m_t<=QD&#wQ&6z%O%@D@_Q7sGn)!@&sI-fauttQoWp<3qoOTnLC zo!@-)+V7KXxkK~m(g!BcIS=G=)0->k(g$W|6*X{Ie$UaX@QmY{F8$|M3+es`^1Yrt z|EYQoEd9oi4sv>;Mdr8;0(*w@5k>n~SHI@kd7+*xC(yN!fc!<=;aEywZ@P*yyGSib zvw#)kzsB3h3nUnX{zUS*?gf}R~VrzTsYm?HmoeXBip7W@Km5v+nZ} zltc$THMvGg)^72hkwCa2fpE73!vA{YAMXvp#=et|S`2W?HZ-kzTb?1;JwFj^m2qHma9}gs2Da4Nd&)PgLin0W zJ0AK>YsdmyyN_;q*ojuqw;nbxxnJExz-*U54ul*;IFd34+mAJleKAvW_i&JvXM@ns zEdLum5NsUS_WP2-)?!hLDRl|vfvhY=)^Foz-XkTmSQqAZiK%gH`xE0DkGh0GHGnK; zQYpoiy(+Tv186=>y)lSp%0bpA9JFzC`y;c^i`4&!8SSH=K2nET=p<J*J*SmA7L( z-!+?fYzR?bi9=c&YYuIEY5UW6+-nzmKs!wTxBD}PPUU0dsCg_V=>X|-YHM7+ERsJoW(U4tVM(iZ-AyqjLr>nNj zWa9VJZH4&PKKk2j#!XEe*l?kyK~tOCkIaG@%RHXw=FO_I{W!xJF2cp+J#DS3Ja!!V z8O+jwe67%{DpI^rzGwx@D{EOyz;Kw|>DH>s>i_PGlkoE6wEXcrKCEctbn)Z0rVn?4 zQ2Q(hyqzhMp5&ZmdpH`Shab-?QI%iC*kygAoNz>fM|Xh$PFRKPJP~^FAea-%xr9hU z%Cr!bA74=*abR1))_PP=oKhCaBVsiR`&8w30qTCjQm!h27@Buuutm;<%7C+BF;pgR z{WYY?A5v-}d?7!~4oe3UVdcM6dgKXX_RI)hs7W^dAz>$B<+MuAKJg@$!?fv1558Ze zA3V7eKM|(nsgL-Oax_76TR-GgrSCYs*lNOMMjCE?MO$VB+X^Fn<>{5l>ZXbGyQg=i zt((5KV#9_FYiF;cJGVdSWmlO90GO-Q+)}cCbpQacKPfQ0^Cnz*vz)i3Wy{*l58VZc zZ$4o73nB>kX35xLKZA4#Ku&AoMOxwg2yB zAiTV^=iwh_V@=o9gcs2^uZ0dg!)M_S*~NY8!5?OTEs5FV)e7IR`)^1#+(rkzlf5O3 zegIH>v;6+KXaF0ad@ulZe%}V;3bgiH;jBpp=dJL>LgT7iVe@40+zJ1MCt zz^x6l7Z~5Y6~?t-;BQ$#TAkK@E1X?#aNY{%H5gaj3R@O~=T^96g|_2Xc*c@@3q8OsvRt=%Q&#doAW=snFhpq3fPI+K&$X7 z+U6~AJU;`3Llq$0m;pjy1_)PYq~>AI|Ab>R2mmSu+lF@fowpFTwo{|ek`eHMumAv> Mcz}<5l=x=+A0QqH2><{9 delta 8556 zcmaiZd0bOhzWDdt+=NR&Oh7RL;?05$o2Eh)*M^{nB~%cXI@%?I+Gr}I)wYVQK~ZaK z7sq4gIogF8otfIzfSD)lM4ahNJMHVU(As%cyV%;9xO*trd$Zo(=K!6V_x}0u`GoU5 z=lebDcmLia`#8Cc)4VnYENYcM?P>1kqCgIC4&)~1xx74C1r{NYRRhK>Cvi;rY`in8 zCaZdn!}1wWV;JbY5ulsNeAN`&f5m`~jR5^TRw47*pM@G^KBYqDQ$7np&mZ()kpV0K zU}^J#z~HX^DuarXRpc$rOx9e{+(_RR9n%fwB6p!n#NHtE#8h2Zk{l@I?T87dRjWjx zuaW7=#mO-hSiVgL!B5sF`#5bPDwFR6>rv*XOf*=GC{d*jVKzSKNAple* zv;RhgL{c|#C!=KJs3PAl--Vu2tsu;;8OMU7|5xZ0G2f_#M?Ep6lZ1=4go%9d+Z91vxIxT+7zxkLh92@+$(XiG0nPM;K6c$2g~=Z zAS90h0eG;S;la|&gXKjYEFC;pj__dFoDIT^JP^VYK*$Jyg`?}@YN!3jR>vwM?B}b1 z&WwqeJEjXl&u<#)4%+;t=O;- zAg7Zv$*IvA{+UE!EBR=2(U`3X4kK*EKv%{^jOgju8J=i$)3_xkh(p)FZHbUy=*0B8 zNErtDZrsp~j+SALHb%%_b@MdrA~6+7*EeW~L9qOlC(U{XcZMgO`bk`Nn4HtEV?CTM za%W`XPT$0O-=&vvE5alv!#ae^uo?Et*E@F(=y!{_EGS}&`$kB>9QDcMxeSq;DU)Lv zlXDQ=c@lcYXu*=I1xr~#jgiHOt(c=RnM5*7+!dMRjw#|klS%EE##BVFD`NNJDnu_U z#(CjLaJsZa_6F? zY(~xZo2*f+VKvrepX_hdu z?RMPkL!umF;(=&+Tn;fF>jLlX;c>Ql?3tO}ZEmZ-q7@Z#eWf-;_r=MDEIZ?;DSIkw zmS#_$_Fja?r~E)?MAf(J8V=_qI$)1;% zIfQy?NG!b(lA4p7bl@bD>11+yP9--ZLRxe7X_)@J$dmL53)21)2C*y%J;Q26nkT$G z=G4%M6{$zzbJgcoIS`d2M9h6z%nhq?l^^|K%HjP$R|JYMF9e!H5xO;~W-1`+E@*%FTo&5(mdTCiBO zV9C+`BtE2JVktL1N_I~yO?x16p<7oKyri=uy7C<|S(8aFOw@=CksSm2-PUe{i0BSk z@FTP85nYf;;P6sJBZ^!i%v8aOX!Qx``Du%?0FR-+R?QeSDpKFg_b(oTlOklRXh|Im zTf4Yek%p{;Y_YJps@aJ!G1xhU=5bc2kWhAiv>KI-g`ZDF!dmZK|4ljOa0W zAk;#~!mUuLmfSFza)Pqio$Wv9-saZMJLsx#&v%`2AE>+EUltFa4 zh7C(u(15eumqUCNd)*&~R_hOCyOpom6fkob8Fc|38!$&dh=AFIHAWF9~O)AKYQOpt-X~|?u0}u3uLUvd-@j%~K_T`Pq1iDLk%+=)XavgRLxH?1iBGAim zQjllifv#0ZL!Q+K^ht#~q`~Jq+XwW!dqU8|xWOc+ERc$moNByCzFnuf`e#-4=JQFa z&w);qiykWr0^O-ZLbMeGwUhJd0*mCSIvxYvtAN@37&{fi0bSh9)nvF)NruZ?2|cs5 zOm|b<+~X_!IgjsmXh=BE$qjBMc+wYwrl0)VcLiVbK&K_h zp9{;_lO+l#qlKinXbLw&A@>z!{nPpVy^w4#nmLK>q6^GxMuTTJbjYiBe!@u7)px@m-pxeEu zd4fBSBBZ8>AMg6b`f<%01l83_Raf-KfmMYiU!an_K`37#7%4(an)6*tnyvIc%bV-hb;%1v`xVY{s#EI%(_wjm=&jTR+C0qAl^v67Z8Q88R7Br*D$+`2`0D1t zy$`XY4~E)3E1J))JvCt0c`F(G%f^3A_OZ$3{)#Icda9F6pYhXl+JYJjrf!LI#sgN^u?=Pq(ADqqgk4YqCAFE7?* zRXDC}OLtHkx83!t^+1c`AcjI&n1(*}@AJ7iYE#(?$M&TUwr${h(+9zq+QXTVd57F! zYj?jl(3Y`7UTgz8Io`3_iWMoA_-4q^ydTm9c6j#7_dr}~j)RFo`XTcdmj-*v0y{mL z>H_@25dNCNV?*~a{9v5LL*0`>&;`a|Uqka}YY%lE&>WE$*fKspF4yXw(v1F`8TP+~ zkIM^eSsD!+wPkC#q0t>-5Ou)}nl}1oZ<;xy@mff^RuHIH{Oe&sk1I#hi+ zQ+8Ec`X<`ZtVm0v7n&7mQFLYVetEIYifh~}9Hzl18dSbPSd>xWbTu~XoqBhQJ;T-5 zykB0ZBX0BHg(fpas){S+O~j>0+Y*hpbY-`?NT@ zN@t8qJEM)w8E*5?HthW0L@zW4FL~{Xbne}sHu42hs@)iOR)$u^)U2XoGfkW` z+nv&#kotq(%9yHa+VnFh2WUow34(G>2*jlqV}gH-O$b6&EHp2*Ytjq>p;Kha%!#RK zk=wBqcT~ouPoiDRXVxGzi~MHRLe3K>@~p+2Jx&(P#;Hwlutv`7f(dEnyQE{bHRonb zjW4UpyY)jE6G4s=?Fs%>Fe7^wZ?R8Wsx#&tr;RsmO z=a?5)q=6usW!|m}l69$jN$H#_3pWqVP+?twIFfqxGOAO_$O%PKA8|mRF35V}5b2mx z%JGkrzs;E@R;7YvlMe*;0~l_-l^nhGF3a=e7%7@-@g<~lVGxBNnCk}5Kg?BgRfq~F zpeOb?2#Z=l@CJB13O9K~d}!T)O0b4|n>_hg#M$eZL>MZIFH3cQ*~8;wVUz7CT-;el z+fwQ%(xQFnj@KP$dmzvBOnT>Q4sGwnJ;j}k>p;xzX?$O!2N^}YLq;79>-JXi{h1J#UW+z*k}wz>)`@s;<^7S} z@@^K~O!??s3su2qA-HWY)IzmzI>Zjw?ry_r811`fE#Gg|*5kPJbX1+&d>-=HQGMvp zOAgnkho5bHc6?`g=hKedUXurvG~AQjc|1H>_e*vI^WmL`-5G-yeCl3pK~i4^wU0LR zj547+G%_muIy9;v+?O%f<}>tYO@kpQp7G^bS+GH2b?;djbb4w>m3=n{^iSO!&^dY>B5?>-trCcfVQzxKwZ z{3sg%>nrD=SmA7_+0UP$tF~iL6xN2d(o8QKC*Xgrf*;qduLDg29FJAyAM?I zxk=~Pt215el3CzMw=vwIA>0O!>f8#q4Iiky7CN*R85zW=r+fbqYN6x!iy|_(?n`lPLM3gJ$%ExNwu6zR-1+CB zxTcryFXO=6AoKS_@zg&4YCAW&gzwKu=C8J^{?=55H>`|Hfe1NKo~unrHF6b>OTUVc z3+0)7LYgU)NO=yQkP2jy<;coZt`%RVl}u7b<4k<-TDvpb{knfBkGRiaD7qwX!(jcs zPu-t0BtTgaK9`<9D}${X`>_?bQ@h~t{B@wsuwotgwZk+vDe-Ygn;-7WpqA09-cd&8 zx#Hvt#{`rhlEa9v$NAhJ&-v%0Pk(zgnZL59@R{_^?9PJ@zSrYHMk`*ij&U(Ay`bz5 zF%!m42mLt$kJGRn$0dJQojdhBsW)VjwhFaR%lBs{f49dxvWmWUnBPom*h=i`&xe~l zY7E8|>qLB@5{g6ThEsyHIw<}h8TO`~W9u$ftc;US)(y6L5xp+Yav#2$tm<-TK4sE% ze#ijO-pipDxi3l!;61dL@E(a$1av|&U)iI}k!58I>QC0Y)&IGFPUbJ;vbMnzhZIJ{|=pV>|W z9QHD68NXfn`$=7p5%5MunxAMIA;^TLVFKy%le(Zc(C$vdWAQy}n><~Y<~1O+kIcfJ zWw8WHmJI+@N+2WOp94UD7=o+-^m>Bt&jMr|POkoOlC7e~%$|%Hvg!GH9sTbmFu!Q8$BQ1lfI6ett{o5JS45kklBa{ke#xZGbf-H7gxlf{GtJA7gq@*yjQNNFpW6n%;iG1Lkk~|m( zYtp%d^f6JKhvTAb-$D+etRIn$c*G{5Ys%%t&RPfR>AF>GMp{O3?+_I+EqDfPByTTx>drT#JhpbX&=fTdwNRwK z9!l;n)z;&flp0g#s?M=Qd{6Yd&=<0JyVIZJs>dJ7VtHKpJj^hE>w2tiB|`sAzNoK2 zuagN2AK;Q>WYX-q=Is$(>mDkh|d$=i#J+zue0E~-f{?A8TY^mD)s{vw;V@(fQV zFV1ZsQDg?u{FwHFrdq^tX-||hgY{Og%4B-XhZ|nZZIp z?M(5^~@`4*4E&qp3~4PXrUUCN8b{16g(V zjPSS`JB~?TD~Z}uq%ks4FhxTwG|({NR%xz}lu+(;j0U@7 zG#D3>`<7)*xt{nj#5q|I&*F6M1dGy(FUxgFcpn~xjomB{lj{0SoxYS90w`{_M zI%SD0JoDas?OFcQ<=BW>_4{?X48M-!(rWVUvY&Gng>3wpJxisO;kYCx?wx<<;3IFp z+AnbVco~jL^P}YS&t{u@6ALjTSf;dNu--XX^>#jHL{VvcG=B(llN2wXkB*QH%k#ML zF>-LZ%e*db!ugnc73erw{W6-yjPyHk9=rSqPsN&7ftGhoSaBJlwyvam*K=C$6Cga$ z3PMwB*Vg;T@Th~3rX@|8eJxalR1@Y=j!(|Ai60q$;Yj`x^4=ZKeA@DdWmEb0;ZZ zRj8WkDJA8r#*tmCO#0iLs;lp-$aUCayOEUg%Jqq)dsX(RjeEb5H+C$%rb_{uM!sE@ zG1@2j-mbxmFdQhyKra%sdTiR+#5Vji{znLUSS^Q$s|{NFRuFb?1!2<@#Ibr3*Age| zRy(Si?g!zH`$72Q{UE&OMkVjLyp<}a%B6C)yTHtP(DSPiJcz6mpvG|t$B->9&6jzs z^XD_siIKt8wVE}0u&mY-yk?SSu^ue-dh+m^8g7lAoLtku9RZU5z_d(;Sfyu~*;&^) zHx$JByp@af{(tbSCg^gyzd)wpJAj2f)e!*8s{oca04()7uneEQ3$I&-IB%GA zc)rxsr-H@PO13{}N44a=2aOB9k=J1`THQc{VH*~X4V!}Ff2bS$wp4xB`4DT*hM;7|^#xo9ko(r>7@n4qmG4D!p!ilFDy5;i z!PZA2p$;JX)=xuEk`LD#(P?sZef7knag$l)s-s|6U4Xo6p>VI=vAA1zfjP#QbdW4+ zUV>W4(dI>HK8ZI+Ik&zm(y||+Bjovq#vw|6_t4MM_O=d}pP4bfJ<*l+uz}}3juPvm zxoN$TVlgWHccem$N*_hY;z!H4BhdBSqx+EWIQx*=XJgEaKewQ2y?xhRn_aQ zr7{sFWVd-4B!1FG-rBE5w_y2)nVyKn0PmrGRghz=G?4(tspS}wydI# zUNDQ)XJ59GsmI4azTTYa3rkzOKL)VqF2IGMQhiledZZhASRYKt$X5x0u=HSu@wZ-2Lf+pdYXze&a!)+kX6OW&N>Q^+GC*#0^=e%&!(jgX?Pf6a|b%X)MHbuEi`C50c#F$NUQ+2qm% zAJmg{-$BiTda&%*lTP2#A@H>^B&}_`c2!AZ)2cOPjVq^=vDHoodx5OoqgCD{zLW@u$@+r|>( vu8EU20$6500qpXiD2g&d{Leo&UjGF7({5ARZ(2dPlXZE3&Q|in?y3I|y&-Sy diff --git a/boards/auterion/fmu-v6x/default.px4board b/boards/auterion/fmu-v6x/default.px4board index dc58fb1c88..f714280cdb 100644 --- a/boards/auterion/fmu-v6x/default.px4board +++ b/boards/auterion/fmu-v6x/default.px4board @@ -13,7 +13,6 @@ CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_BMP388=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y -CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_AUAV=y CONFIG_COMMON_DISTANCE_SENSOR=y diff --git a/boards/auterion/fmu-v6x/extras/auterion_fmu-v6x_bootloader.bin b/boards/auterion/fmu-v6x/extras/auterion_fmu-v6x_bootloader.bin index c48956fc9e34e53237080061365a4f7f60335131..c619569917b47376eb4de82beb40a24653d88545 100755 GIT binary patch delta 12380 zcmaia3s_Xu+VH#f>=`!q0Splk_gt_+E{=eSS&5(vkPK2ghmP7AMb8;Tg|Z8k9R|Uq z#FNM6`5u&0r_%iFWXXWjC+Uc#)j4(QV@yvfT}-R-lDQCU@44*R|FZ_H^MBv}JpX>4 znRR*Jb$u`Eec!eA|Hz%$!Rb~{0JB!(jC-E@lPHi*t^{o$gIwl3hYrkwE2A=_{9O9G z8HuSzs^NB)wD*G%3_xAM36-h;3zA#`lmvig`hYI?1AT^MYNm>53eX9DpxFxaZ%78S zLj&dw8ZZNZ`HN>k=xx(jH9Q-Sd^$0ie5x}d2N}{`Pxve_t`AH(_H3Jo8{N>~);knY zilR}#h~p|WBG4e29hn>1rUP?i6bNU@W0B2Vv4i{+nTOhXGouPPV{sG+)lnb_E<_7L zNCe8uAPO#^l`{KpP>HZ`TP%-RK_iP8sGV$%scKI2gJpj|*9oGwdzs7!idwD0|+QR=Wc@$_1xX zrq~MXyiF{Br5Wg(q22b3@+Eb@wITWz`R`Z*uc6Hf8Hp8njt;6MB`&@E$xzT+U|#|~ zUg+PZ1G5+b=FS!nPRD}Kt^@PZ2r$<~fY}@YW=jN^b0WYzFC7H!WDwrZ03pc*W{&Pv z$%eQT-L)nVY8+%&T!v1G1HtYfN8=`=Sn^$*NqagTgq0*VeroK>h+n!rO)BCI{5_%d z4zeyjC&?P(Fv1oLbh#p8L_ZBKC2z)0=Q(=z9rAsAHP2BsNbb~UjN|BM!6FRwu#(b; zUN6EN{XR(6=;vzLgxiQqUlqG3IOGkNbYQL~2??cWDS03vljrDP1LO}0tI<+&Ibjmd z(V75>No+z($)>~^JV(C{kYkA!22GqQax^7yt!LA4Lc55I+#)vHfAk8Nqng05SMSn1 zO}Zzga!38-pOdVqk$uqrml!bbhygQWAY?XR3+AXJKwe4`qd2-QfGiRC4<52@Tr&A8 zDQ-MRe;u$nv+W|jxT@Z6`W={duSC>LG~=pbIQp<(>|0#U(Y1c^&^QavQInrMKTb^K z=sf?k!wKzRIqlJl9DQ6SN5-v)=IG}>Qw7_$yGhn=b+Fo+qgGAZO*bmY7RXNN%de`wS zJWkWzcIwVPhuz{VeF|lBos8(hBF;zxJFz`cB0GWs`RLMhWC3=p25n@1t%$kh^ zNq1UC1U||H=QKH;#1c;uksn%b1O>_-Jp;Y6W5?vGA(0jGor5s zw7A>}L$-*V$1FHy`ZSDaj&h(x^4LT~Nr1;S465aBAAjHNkBK;?kYS`L`%5HGv54r# zF^pm@+^)ax_VpsxhcTj**Tyg&{uzV2UHCT)UvPhNiR6*p2V=mzKL*TuV#fHH+{`H8 z5q(i1Ig|4Bh+Ykz@6(sNFX@XB{q6{{B_(G@lz-cU=)Zz(!wKz{z7!ErAs{%BN%NTA z&Ez87A9;P!B%Wz_^3O?m7DPXJ2l{UfROI3@4Be|`Eb*scbss;pIGo=SBu3E~hiFsK z(kB+OJzpOr3&kmDDS1X5pBz$<7?Qdb#utLiVYgTj^#{q{#C(pnkgvo$ctm@HB*ic# z2hnZ8Tj~Y+X$uIsmucyvVfQ@0f(x+6%|88Y$^tq-C?VS04V6%RYE z+?Qx8YsNHAk%*|)&tt2TaTTKGAbH1-&LjGDA30|z=MjA%Kqec@O^D76?6;{so0%FB z-Ir*KW_}h%v@kFn=8Bu%Bjis;LmHxU0w#N!bCDA%X1<}TNGk5 zt&Byq&ClqhcSHX{;xR4a5q-o@Eas*>MCbc;c*}4?``2=N_e0Lep%i4r(;r1N%KwC| z*4}H|Z6CJvc&kN3*UIEmvzbTqnveWswv0zK+Rt_A@L*5ta6)^(7y21Z4wC7ah8c)P z`u*NLEg)zsxn{j7Gz5>%z&=cNOx1#Zvj&A=aRpoq#%a1hv-3U@cC-U46{bSrFP+yRW|6i6&gCHP8qY znOav1^n!eK3y7s7jzw2ni`=F4yGwo;0J@0G%*tNK(Ul>SJ*5FCC$pXrMk2W2Yi1z{ zu88@^Oc51mR*B4~1w7iyXeUsk!WIB@$`NMvT|fHfSE~vcYewChY3FE#Lf*+Trn0Ws z1Q};I>P6?pErUEd4fHdG{FIf)hotK=u}sMq+7xzrx`SlJ6yw;r{@j$W`H-|gCTp^b z7!CGj=OGO_ojo=4YRJ@}89K$K+H~_x4aem+(P1<-{KjT#`1WTjz)7-lX2fg>jWPjs zaqGxee@bpXDR)>W+A}FaT8j7ywv)2Mc2aI{TrX&@mT7teKMk+Uo_Q7(WRAd`C4zw> zbW-l9&a$!pt2Se0bn$liDLu-X<|!RHR=Zt(x;iqK8xV5yJaxTnV^7K*`eQxOHdEk9gzOhWR?lZZ= zx^qQi*{%GUx?{t~^o?bD7r*Y5ya#~Z44jhl_FIn)iO^aSGcYOpl-w;2EY%DlE~+0) zC*=L&33ewVr|@q2G7zV1Ee+-~QnRb$Og_9Tut*7F02BhVbv&zX>^O@7MSYCk^gNNSTe zSb-L(Cu9d$uqwSA`YNnYPk0%9tU*yuR(^X8te-0xY zRC%1zH=4f?WH##@D+s?3{3rh@d6eEMsVV(P)VuYr?eaeBI9%Y=V^zAM>Yd@;37nEU z#Lw!wdXi{d{2uvnD;kJ1C9PoiC*`^h{W$z_U02Vm^5fP)UBqdD#`$yAQKV$km)>Cq4 z7{<7}qS?{*CfQ3VEGnfFHAyxw?U5g~GM;K;D}ZVz&?UYT@?YST z+yM?F7zC>#HTh4;FGET%&;`C*0%R^YA@2c1PRZR?j)*2Li5nB51HMzuat9O}v#?-2 zA@8qNq#8dm8F56#=$5_d1ChzptsT)ERSQ6iAi)Ykvn#s7j)68PV2WIjjvtWuw3*I_ z(yaw{yj700BKoOZfKj24GvwjB8{JzRAgtL4LSvcwgWgqQpVO3NpOi)R=1)ck$tU@r zjNj|4wWrw!Bl=DwQIT9eH2Wt{ulFEv7QCQ6h}gkCudu-Ipd#X@AJi9imW`9+ViakU zU!V7#$9;)zhW>-V{KK7vxA1ePFG2@N%k(tVMqZqrc3T?<=F+BgqlQLk7L}s;pVg$4 zwUJMzkH3#WqA2MBK`)=s>tCQlc^c{uh_+D=06y9^Yj#OI6qm$9EKbIwk&h32 z)361dKL`@!NL)Vo8{+lR=b z_glDW3VG@NWL}XD`N^UC%{d8*>3NhL=K&KxB!FpS6;%r^+CtJ}GFY_dn3__hVKy^EX6V>EMHiFP1CMzcXivmjgYB&LEPDE(FyvEEJiMTOiyHN|mfW5dt3gcb;be{DyH*Xe#8Zcb4%($)HGf--Wd;7z_*R zMZB$S)IRSUg7_2X8mI<7@m5iYWEOf9d`O&&lbS72)mV|RkIy)EV}}FGRn!rUy8cqq zc(PB<5&PsRdVNo1PfLkm;H+%bqx{IFi9LP3JlMvTVtifB5zoqkm^gC2SvwGw72!#w z#qlZqu?AGAl~LMRZ)}#2omkB&{ZWPyFXYVq;vG9osUMhWPoTwUHE}+0n|-NRj(_WK zm$%n#D`O+Fkt2H&d;U~{J!j>m;`Y^1&T_o1jOCG`9RF`TZlHZQp?#MZ86$^M;5nHS z73q}B>cH~CImi+E8>og48y^4O;i$2}YRWM(ux{CAYz~PyOp6y-2me0ka&H5z=1;Qi zs?CMtgvO4Y1IH4FT5|R0gNrQP!=#FHn>ZT8%ylEarMld;y*N643kG#EcIDs@g zsBOO5r1sSJU0rLzY4*-CJ|p5BbE8-v6(JEbXNtkP!mz7rHRqPtEx5Dn2XEKvXeY~E zU5gAB+*Q|E#@gjIe&cPR>9$elmH57{^{ zEtL7+LT{r7l%>9u@G} z?|Z=1K;t9UFK4@RSSiBpOLFUDb}i+#pLy5ULH3P-iMGdPjoq z>~A=k4^P(B=$cKQZ+n<;Sct>hyBX19Uke7yw;t_KdQ>$IO8ZqlgASgN!CHZx*n(SW zv2b+ z4Xo~CCCWg(Vf^N?22q~Wh^SK~n1TPP@EQ8S$RTy+fHx{@B-|8vq72u)C3v)h!wR4A z(>donbaL<2NdC%}?2geLiyXMRmWlr_oWQ2YIM=AW;2rh**lxg3y1?T&T#O@v(%q^y zV+L9F;P__9tfDBAA4-n8u*EdiW%58+t8Dw2tG@4gzT=`GQnWXf_dtSsrksjOpYpTTKsWS49<2&*OgMFiC(TXeQXmLCVI#0S7w zg!!QqT>@4m#Sca+W;xkEik}Lqbi)sZB8=#yKr*p!WKNL;@y|%9H39Szika0 zx)>Q$X?|#T(<~=Dky2oHB z@9mpgn`6(tee?O|V>jM*?7jJX!g_5s+;BR+zNDc~{`tUxSKc7$OHvcb`OY%^(1iFe z2EYPzr(?@`vTe!uDO+o|juJiUi`uQPZcXb+?CDDVsAuDFLVLCi#D?>)ZnbSq>^bPm zBhM|FXfSqM+%k%<`QqXhV@F!gIj^zf{1%2`v_j7};TKA~v&auE?qr27)*}ikDY@5A|&b78y(!6v+^KM(c{i5xv-L(8+FXVnbu-l$( zyJ)Ysnd+|E?95fcU`VzCEmv7wGX;Q_s>r|(r327=!Z`~7ovHFeselZOG(hwF*~V+b z%4?j?ii6St#ngndb!X8mQ==6t(t-epjczbpoUm5JhDN45v+YZC{Hdyur)-D2 zEY9vh(`z>!^yOJcO_&e7?`_eH=??P%>S%s%OJq;!YIbCE9r5Qh{*A+>wa2$`9iyyu zycSHYwVIX3*QTwmcczqS{2Onej*{BQo^GE}T$p<7a$NrLEonX1yp3gZR%<#+)*yfD z@SOUcCHjL=9!*ELŜt;4;6p%D}qSCH1DX#>--%ld-jwW-c!GC#XgmHy>kCi9id z@E2S>i;p=q_Aa}|*;&TSxe*S`AhO8CI4s}<40L^p)xrW8vD@QyPMu9(SBKkLsDU=fhL3O{H_;boc-?POi0|dC)pne-BWTKY2(W|C5K+gd{FR8f__jP|66B4x5En zq_=$JkZm!qNE>}bzx*jaD7_dUe_TG9SEM{2IkY^T4@yk|awc38=_A||WrMv)GBF=@R=R;uUEjI@`EW-oEC1APkL8etU zQ_EFvkRvaxNX=KID`R%IP#lu%N6{=z3-eNf91FNe$tZhDAEc#QL(=IWxw7Jp z6hg5;^%KcF{>uXcA7!+R}^OZKkp;PMqxxT>A2 z50Im)k}W|A`?MLFb0Q8&6@d%hv$8m?(wT0n#{ZDTIYB92Wsn`A-ry=5;p6N_cOQg7re|uf3}-BD?r~Q?%!8(9|lO2-H6^Nx%LHUFL~PjS8l(Lq}Qc# zFZoDO-Gx-6&u)t?|KKvGRi$xZ^N+e?#E@k5k;2s?637FqD-$js(z}^I)oBN3j)XEe) zizc(Y;9|j3MS4&UO5cQ705v2v9fAJH$;@BT;usu|K3Bq*hF{bt-W!lSN>~}@41bC4 zvf!W;88r7?@#Z*w^v-bc8L>Eda8lOzGXd#M1x&nA#C3S94Aom@WZf!rA|gR4Pv$X$ zlRMYU=N|WyXV+K|B?s0_xGgt)wfKFQ7#F?Jul{4#tP|wRH4jV*N)0M9T(Sd=mNh2R z6Q&L{%hbk#A>qZ6``1n^4oX-3JigZRvXg6$sbm55kksU3_Zv)+=HsAr*7wa877fxM zrc8s9?;Qqhpd2*1_q33=)~2GRMfg9F$TN5$gaK?&5Qk~D?+#xTuLGA|w7uROnOzY}x?|O9x#tTbj#+y+(>TRGJ-LNIxj_R5}f->z*98djS3Y>tNi5UDp|aM#RRxRkU-WoBn$uDpWmlQ zjVkGANatcz^0$Um&ZLqL8n$s4LZqg#IQ8975muzPL(AsP9(nA*z9E6j!ZkP`O_NDa z<6Y)IhVI78GACMOK$R8fQgPeJI zifM&n#95fz2XwrweF@#cPSz%c$2KRz`B=9P=*-^CM=m4O)EockS}v-n4TJ*@5Z-X~ zKKpng&jamL$zPsY{9uB|aOImvv{tKOF6DT?WDP>*;R(!i`_035J$$!q)B!vAV{!D* zk9t4%`CKaS*SvqdR{ZqAAInDTzMM;W{-XD<*Y2)A_~QrRx^buOCM{2oC##IT!W{rKSo6V^;!n``02Ff#%*8AjW6H-gFYH)wAw&5nsyA^2GbBh zT}$S^RI>5Q`FIhA&N&$9HzBL_ehk~AWfb3u%W;$uOhEq?YQfKAFXQm=cfA>)aPrOi zm{M?@pYi1JIiL5+%v6mkdDWMPL`_Xe%^bnK-o<0|7G$mzRWjQ# zF;Np9mCa-EVWyrYCzEF#=BbEA$Ur|+fsPLV{Za+`TKJ+lS!Om7yKy~zNbd&V1XV?X zg`9O{8xh?l=bLuh*gYB>-ki+hS!ZnL>@X$hX)GI;OeVKvGy{E9jdOk^gY9ei$o49# z&iF_cs-Kgg8i|N5l_xvT$zX+SpugV;qAD#=`E7g`WZxKM@VjKb%P?zF_N6oE)rGQ& zLcg{SgtR&kp0R`Q;qQO>y;e7xFI^3SvKoZ!dJyXCp+>k`55m@Z5DwRaP_YJt!T-_l z-#hvLC^49Bg4VhspaJC!r6?cN-0}fR0mngKnE{pDJ~Sa&kvJ-+58y)7~1K zg`!!t=`uG0(=(0-0~%((|`?kI9Ec z1LhnJn5`Nx>u&?|En>&^J(+%&hdt)m5_+yuw`~bAw5@9XNzrt%7=E0$2p{)?NxM%= zROxdCEXDLa2V3_)6gJWkhqe=FdFa-v&ncgOe+&Cq82gPdc25}lHHWryV?;51#UWVW z#!C*MfB3njJ3L~s=JfZRs5VQx!VR`MfKL1wWq%mOp*g`&q~{c{Y#7kJK28Lh5Yl4a zpxvh3r%F4OEX)Y-XNEoESpQ}i`w;~!s|G~lofYFVb^8?QN0~Qh_i6vEN-bmf&xG+| z{hz;IDNa$Pxe8bo48Gr!kvsnk8*ZTjmU#nJBLj^t@8X$b@q#`9%)Jf})F0m4zU&$8`|!hi+cPQ~ zU0@OVQ*e8?D!mj;tI%Pfdwg14)SFVldVa}g?FIUh%;Qpn1&5@?eoaQwVB&&0oNa>@ z^g|!lWx#f98acGSlv*_$QKV(^Y77R89jM!9#X|R}4e->Fs*!IBwF?HlEIs3eer9I= z%K?H}1Llt%VZZ)f(XL1pDsx3mVWnaw?`}?-0Cc{LEWGDMIRZ4{w|h)u`n+axZF5?B zNZQVz1L$tZz3D-P)LS+3)MI`x>zCZsnQv937eY*BPQeC@I#uZ_Rnu*CGb8-RF(W)E z?NE4I6;%tvap}gLckw}~K_T5cQ~97|Q^=<~7xF=Axqo~;i^Kto%nK=tk%+&}kUIco` zr>kVVHkfa(DFynP59n#%=pFyzKImt%&w}uu`G6kwF{XIg$KI2$Hvlh??_ODyz1m+z zk!`eQ_Bv3`c26X#lqa>XX5YTy9iS`yVEM_Tcf%0a;3imsUOe0yq4oSy zo=9A;{wFFT%XS-nzye>1)+N5sE1PM-Q8)U;6y0w%jkBQpuU!=A`N6jjoe&``v{LN=F(s@5$|V7m$QK zN%Q>DyP>J&e(7i^uiP&k4k1yNJ`I7GvsRWq3Qei}OG$|b%&hi!XfhUY&MH|t8p~c zPeUP9nibMwut=U99Flg1hP`ucv=^eu?}lj%#ZUw1hbCFbH+v>cIOhO?`5-l=RrI_` zq|L=O%h|zRO(woJzFC&m9j#_+`#hWvzZfc)rBz3vpOwLg41BrZlBJ~~))tJrmNVX9 zFpj-0Dwn0IpK-ZxxooW5=+fa>4CehMFxcq+m23vV>6iErD!l0xEECSeS5#erbVPbz zn^|Jt1cJN?1m41|qZpiYhV9utMUxv@Sw#V2`pr~DU|1w)TD9||OOsZ~(oTh4Z!tj+ zco%OXd3%$2pLDyAlwljnOU|Qum-b#3kC9Y99PS)exyo9b-kp=oo0A(QP6eSZFMI2!eXvw0|#dEC)W#P(%ZS#zI+hQ z7J!gh0K&C=5GEFkPMm%JFBo~H*Q}E{F!OC>@7o#qDa_Xy` P4FJ_VfZsv@7TU*+$U9A$7uB=jQvEA-=ABn=QO1rhC>-AX&LGO^){e33rKEC_;{gGtu zoik@<&YU^t%$aj?ZZ~u2M@C(p3NlozcldVZHGvoRFgCbB>|ru9_p3n$-99|G$jXJ~q zB^G3S{(i^(Wv8#G^3=xOS`NP+m{KC3hnyT1iKrbuY7~oWBb+hMndgG$S>IS(9>C%~ z5%Iy{DX>}m$#6ZV!Z(OmHC*60d@>;JAD-rZDH4+MTuVWV1Uj14Aj7Hw8O{3^oDYb#MqyT2ADA2~?fZudbLD)F1dOpe77QarOn8xC_ zPk@e-@gU<^JjkGI2Q%o%Sv)Etjvpa#EaoC&>4@ynEWQzTdd)5Y^*+7IW&9~HHm!ho zytrdTSv-q1VWI7jVivPu@zMxWEQ{MhwDS{^IB&$LQP$!+EiCQ{z1*Kz4@}*Dt-#{= zpjbF^c^r#>7BZGlYCbG_N8S&g7q5)852tg#H>kgk6dxFs!Le8q5|@v9D2K(Df^Z+} zWcHQUX`0(Flpg3_%?gSPOkS__C_e*IW$pP_wFh0fgsS7?3Yn??5K$0jg z&%4XZ#p2E}6UMQ)J7h(#kOnJ@zYL+YIVW-ulV5<;*Xkg|OU3hJ#wM}&NQgt;!kGx> z&qFM32#I{k_)->&p_f*v3*WMhIs@}(&+7B9!D?_tauBZUQNoSm5qyosH6agzZwQF* zgFK6$3>6moq&0X6=$6*tIB-S^eFS*XlA&WEHi%-1eRR?wwA9;f`k_E1%H%9w8X!`Y zcq1j1WAUMY7@ul|RpOk~ykV3(wXHfmhXAe-cc$tK82pXGp;KOfrv+8%+ywzK__Sg| zmF-+#4mjrI@cICy*XIFf0D7)37Jy6^Umg@MrP{O{E{#_HHb9$gSHyy}bj_Ae=ti6) zK9M$yWAH*n{2*jk8ZLhM)GzYC%H z7X))3{~r)PR}PJ`$$rw_6%R806b~{^$KU0Bar3x5j>UOIJT@*@%itR2Vw<+O{j%1| z;Fmf?r!Xp0Q~W~sT_k#6mh>kJBPvJm3x8- zbnu4(Kj8|tzw81T+Bs#Ii7`#xkG3{j5QDQ7@s2)yE`y;0^Z6-pIamEuLAGDUwX_+P zRs{ls_k}oQ@lwWO@b4l(cy?JqJ7w~qq-`y%5Ku%utq5p{ZW~XE%MHaGgRh0f!-irb zgZ~;n|x(k#T_KZg6IHFzYrEqyJHG3q%6|2-@|WE{nR9Tk%t5}Wm- z#C1l)BMd$k27=Q$By9`Ybtu(!MdFI-QrwE-=#x@i%0FmBU}O-~Yg;*_LmUngU^F1L z9ts@3eYeaA9KK1!%f=PM7@QKO>q?bcm$*1%A;(}oEH-Csn#kabAvN03pIHAbsc(ML z8`GzQ7Bpo8gZGD?cb2=3I-6Ym&K7B&z+g5gK9-rmF}OA)R%e<pLXSLD#HHY|qr+&)~O10qNvNfLA#fx3+a5$<=a*!M_Osqw#q<5LyTDBW+A+vJ2)V zJ1dJo#}DGj@k^Q62gP;c$1~2uNB55Z3uK&!#g(S1vChNP5aMvhp!ge;Dd#uGl?56w z)j_?;k&-wv|)SHWQpolDmi??`o}y4JS=L4&`Ih!Im-z6SsG6VO3fnT~S86+Bao z5>VotZUQ_U&K#VEIAlSJ{7_^VZS3Xnq(O0RmdWw!;77$zv&@fi_{^Zu zrCS3qLnvm5pa5FIx71qWTlvycM!p12w-GKi=vO=9yZ|o>1H3#mWQmn_P}B3~Cm;Qz zB%d;F?CeYzhg*sGP_`k3qN9VPeBoIoczbvBaIl-f&k*s&?1>zMaZo&zoy%_tn-GVy zh{G?vU4WF8RFucNld09ZqG@Hxrcj#_)*UN?ro8w)yA#% z)i?VSJ;316-|W|JS@&^Ge`5WXer^3((kP5{Wnu_b7;=fuv!u>>mNZnZyub9`y6RV39~m^ICB8#uLGB<^`J6Br*qVXFVb zqc-<|XTe$0sEwuIPLX)D8(k%~%mM48Z~)BDvagMz5lM~nLzjNQx^}$xEP2y8+&go? zv-U%$!G4xBT28g3I6eJ|^|<}Bew)gG6PTF;U}h4R6rXKxlb9^N!#3bq{+V=?RBOGr zFRtM`Y}m7)Qvw~4D^Dpm?W=1^v$nFxzM3L?V|iuKz4Ez=Q~js3l||at!qr{m5CB*o z>LSN1r}_j?Ym4`dGk1~Wg70y*4>GYGz<8P*6Hb$37HvBaLK2mvc5(8=(e9LIOWT$_ z`#{@S@*V*APEgxM6<-6nCm$+XXRYQC82@r}cNC&0_`!;9(rAGn(q~g16q{BtqVZXk zsB!%H3Og0x!@)e1jkuB__|~AhnVw9nTq2k?5%6EBEv+NaE6w_D@!6zjlih{OpKV%k z!P`X|Eg%zq*cC;p+6BelRg4%AOFJFxav~sV zSy`-#y!~Gt6|}NQi}tymsIcCG$#2-6U9IwYZ`Zi>zBO0}3fe(-p>H>FR|~)ME=*ry zTQYMYQ#RmPx0`sh$@bl(MzCM4Nw#18Y`q;@*ji^7snaqT27vILl#H%Pxkp78i!F>L zTki*E=0X>FQ~2JSJm6V3+Lt^4-0>ZZ5gO}AwWZe8+3!iNBOXhwt0$q3)L0liICz@W z0TWW(^7cr#l#H%MMei}H0#@%P^&l*(!@xjGiBVM$mf!6tXq~lMU6PGnkJj&1IHYSE zDsy3KHYZvDuWcQHY^!&X8X>8Tp2)QA?CO0LBfLPrr%0Bdeos+d{xnUsQ}7Vx=5pNwqjpPG9I4r9(mCMeZ!5(%PIUB(x@GQ zzN*;Q@-BJN(xcXNYmITs&yYhv>jip6{+n`)ylB~@PVPQNHVLn(6S{{KG<};gQLU!0 zEvafI`ufWV5VY;Ilbb%u6T=ND%dbiWt-w&Yx{g$dA6dq@8|S@8HVI~zap2r~JJzyh zXBTOlchF_TkUi-9Dyk@=8%CSzc*Dl|%LY7&DaBzqDM%-g>@wnEY_hY9>;{VL33ib^ zK#{A0UF1!`dlmWlU>7-HS?C?2(Bpxj-=qNDLWe9}WWPIFNq5WK0A)ykxoG8kmV$OL z4_Gf3GK(y&@P${JRj6<^$SU#EiHvbZha^1Y*gG_&qz8+`@*e_2!+10>G>rLyd&8I= z=pv0;6WUEYmQvSJn_*z{0(Jl_Ot!lnbiTqwN1`jvO6Soi>?WJFqRTjNv7FMtesyNK z=v3rK!$b46W3bSU$Fj*zV0@2kvQW0HqB8;WyZ}Ewc$&Nix=17N7=WI)gk^W2iyQ#D zqX5qxytgki@=lXO0E%7YxZA>rf>9+V+})hb6bM)iS%|lsCdcN5<);GBXh3|)5a|vN z0)cK-&~cAC>?cYdP(kqBB*42{<4RnJ!J`Q<#>`1Wj}k6*n)k^xOP&kuBrz5Se;Ld} zFrUxq^K;FW?fVXLfUi3&w&YHQC&eqde;$2ku-ujE>d~}yLm@1m7=#bs@gJ2=ihs`g zx#}bY87IYM`FVO{SU@i=*5>ai8bOA~hvgjs?Zkij+b`o+K*vb{G8)9z{Cn^vQx?LL z;;*Kp!UnNzN~*ho0U7p9X$BT+*oAgjdUlbnh`zIJO4G9r25T4?Wb#rgbVZl@1+C;}$-g0aeuA#2>gHe1@)U=G}olKw@L~dl)VK!-QamOs|d3vHX&u+h3V~4m5+OcP$eE`^d=i944^B8d%JH|fq zIi?yK`4S*#bNwW(ShO1LpOUl!+^$DP)GdKHH*W=`Ujcx(;?_o@J2hf%+11&jPcF{n zMt3!_iF0gs(HD0VV$X_9tJ!Y9+OY6mXD9xvGf)kU>e5;(5YCV^U7Y>1XjdSH_K_E& zeb}qF*Y~LZunA%o!fr+W+})wbKkrbk&#Y#uzfzZ7wI$8&;2klJZJOl56qjKDBo#-s zW{T5ZZNxlle~x;OKt~j59Q7=@S=@TFKd}zzJ()NAwKeNLrWSoozqbArUARj0s?EdC zLH!%nEbBDytC}(l*_5s~5zNz=)&3t^+|;ZEg7#t-x+%p6*gKPLeZI`AYSj-d;SIDd zP4BQ9yv{sbA#P{J_et#SUF(UYZ9U~}^WN-F+yacAjGO)1+I1gO=-Pg5y`ws&y0af7 z>k6T9hxOB{ID6-Yvr)mNZC9={j^|PUf#cjEq|`E-CsYZjh=^}j$D&^>yzd# zNlz>^RC|N{eG8z&-soNou+z%g?N>jw$Cilmjnzxxl0`Pm*_O;JueM{3Eq~5f4a^t( ztE$w7<^7uERU5h_y3$(uF{(3svX*8 zi51)a1LDLdLo~7uv#_9`m95~=Fl6`It9#VyZcy!kiu}D|tVnGuXjkMvD}z!NqI2LP z0}?&Ko7Ui;!5>-_`CRmLOSM>KtG${-|4={J%~sDSSqhgf8q4K()05aDrg{NfxX3sF z>~`E}UpOzfl&xM2nQQiBoy(&Mb?;boqlGTqj(I|~XHgNVvrC}CPtppuSOsLf%CK~k z(oPlm7tsSMU4`iKrOoLkT!DQ6tpA*F1+<*133eN*V}(&AcUu0t0hM~5ea@tm3-A&R8w3D}6X-Blv&q-Q=B0s9oWp9`04&&+81-zBgpO53Mz-`*n zto{ZV*%B@<*0sk5cLly?nk$QdmbY43Srj)rWo&B78#eH@rQPW2?AK&6gnN)7?BkvN znpvIwnsSCPk23^5n2fGa#??}}qpBWP_A_{GF^hqH*U>NPA4$(IJQln&fU1-2YRszb zS5MpF#L;v44!8Yk;reUyXH|36D$J@@KscdkG4D^B(@pqAH&l;wLuf_^ULZ2v%rGbKaJ;bf$M_OIn9jXiz+QqAjl4 zQZmG!U^(T_r`=I5C+*kjQ`;QXc5G!G&t-4BR=?NApIug6tX6di2EynY z<<-D!z*c7YbIdoF>ff>@eUpy#)oG4Wcy`gPw0$i{uf3a)cwtN_G@c>({0=K?|BU1p z{6)I%&wk;I=5qJ)YFo5*uVmhqi?Up90gWkC9RR(OR77saEbFZd^Zq&XsL7eC)O9VFR7TnZ1J)?(in7B&2%fWOTm&N|2=#|T7wh7 zwWvVarl=h1(oUi^pC!OdH+Uxj=BVffyj2HyCp}|2Es6{k&QM-Ow|e;o>KRew?>m4Y z5h?PI9r>j|m~aIbogrL7?rbA=L-w<%i0Thtbm_dTOOJY7dx|2)oVgRqKxP?MV#{z^ zOz#Hc#+ab0*n)mfz<$c#zbD{bI7N}Kg!hmaEb6|~AjDGjQHGUVpdVS>Npz+%4BbhcB+V3O=p-XdokVLoOMuBR5Lw0@NH^Wx?@GGp>?@`B|U8KWI~ zn<~_i7c9o@)RawCr4F+XSQi?%ly6SP&IFZ@bN7veRPdtU(u?tv#-B^L#m7HR?!%zt zn}-4ax)ty@9tQl4yT3bT0{;Bn&v!EcAD#*LpFceGS!e~kP*tSix|wXoKTZw0$9wNt zR}(I>cpMAOMLxzH?*ryrevpOzr}{y%`&7Rbyz{*EsvS6=A9;})7ix3wxz1~yY^=Hr zGfdglT6T7aGmlyU#=@o4=3~pB2gau7xxTT{q3?_st9mq}x_6UJ7881INPG-{q$Tqx zCFl}S3MjG?xi=g|E{{;-{YeXPxBv9{51v0S(UBkM2H79@=|~y#Xg`?f9$0$>VmDBm z9=`MJkyF=Bf#K@1s~#}B!)XDxcU207ihO^NQg2D5T>@tJz~UotqI=-6BP?3p&m|i- zVClZ9O&a&@sv{uVJ@CSjA>2uRFmZ-|2(x?IIf^*;e-NLIoROBEfD>7N5!Pz%+whgd zOf>qxYKc1$6Wde;r*T;$&V73sVm5AALLz{M<^3$%w1Li0U_X->!ySn=3`m^emZUOZ z$%qr~)>32lnlxSGzMXpnO5eKG?tzI%V(sn$^AY#Nhwqqow_gRxpAk^7sEt7)uwP}2hV6!d%H;;kG0Ar0mMRGvZb|=8y9YE!{&q>IvTEG7 znIk=F_kePExZOPvIt;Vj1A~XZyhJJOzCCdGoZ3Cmci2t4{_!w(mkm_`U~&(PIbzs; zr$y~Zwx)aS1I&8kmITQ@;8`Dtsz|!kWUMF?uHdq*&EJydUFXRN>v^Kn&K$7j+6Jua z4Ayw70bf~e7`SLK3~XL!z>xU^86g1tE6;r_=zGiaQ#QH#Te4x-c{kA&oF{3fWb3{b zC<3z;KTva?=n545>!tfz=(A7*a*{6WDuw!8bEr@>A-a{QObp4^@MV|aWnD`v;=EaC zPmx{~+r6#i%cz`8tzf--ihzD=aY)Vyf3IHLUE>(LQiT&@+WOQ93(lzqa8k={H<$$Q zuWMRvTPFeRt!cUKnKaA)d4KFkFkzMRxwoZniBJRXJ8*l~ zMy#=R7dpzW7Nsm9toA$^VS-oP40~P!#q@4ynBgcTtgx~QOe*v<7&Ff7WPdlw*RMSB zI+>w=rhf~wmCVr7auVjC%CE?Ep_Nt3`ZY-_H^6;+HEcIy$cf^B`%*P=-7Bjo79pGQ zXBI2+k}z+`jMhHKYx{# zP6N7!DDt;U_iQ|>klaA)0o2f=8mY3Z3L3PY9^r~8wpNC92_nxyR{QP@kg+Isbf?s*P97T{izB%CE2&)|gN z)Y}ShC9qx{uI(fozny5c+ewm;t6{r&gWW;9>{n~Lr=fXBkw*o!hKHi>Eb4@AcAuk- z**6V6P)djRK=EfJe~}_{L65;bB?<)h(W}a|`8`0My28V@10565xWLO~X0+}=sv=herf=I*_-n#@-oGT2E{Jk~HrqY$ z_TeF$$V2T0^Di%@6!UsTb_N>VgFw5#ZzTI!J;+k`WP6uXK|N)uB^$P0T2jU6iPXfo zZ~H%rcbp|4YfXPFL(RiZ04M8JP`SW1aB9H?=kNY`&&Z&HimvgL zL~3lr&A#Z=Bi5Db+Eb)LIxjHxI!(x3(7sU!$+HKco+^?(gjzBE66l}}D_c2qvp;dG zXFMPY8zKkmy z@Hjh(wz!jwDDEWr#hoNAYU(NS?}#EFAgkO}EBaY>)do7%yMxT2l-yBDTF;R90wV_N z?bx&aGZJ4wpBKYm_ts+TePQ|QNL_JQJ|F%5TcmcbB5zY_9c2Rp>wsQ|0RAH6DPa(c zI8=ty;%&s4YI8;mpKV|^0z-U|nVFXNNWC$b|%)sib{VA%&jGlYnNd+ z)MVF^Vr|7HJ!WA=WfLi_?DYeqRezxc=A9xL%hD_w^C>c7riTc64~f_BC&Lr59~f4Y z&^7K2P>0jdNo7WdbGFCmoYUm&b=xjs9 z8O^=ZH^>aiKSr8Xji7f`c}?XJxs@1Qxq=;^VvWvTmoe&}^w@iy5%~Z)O~8{~1QbxR z8wXA;JWW6WeYRtkrDf|aXe?jO-rmJFEicJCO}NQ!`omAA-|^9JZS;FY^jkMMB41V_ z^52v)tmK_0+C_@~G#RmIQt4@uzvwj46-;oPCTWXwE+LNwH36Xv^Hw_%;_XEHxSiu;JI)FhDGE34ZRL-FekWq&DLOT&=+lkhlV<)=!9X9OOIYt!kT}Ih$iF0v9N~s>Z zXX*#4pnjlgrXDLW)(-SbmW?dkyR62r*BOxqB8t3saHBv;9F%`W&3-GhDDDss;t%m4 z_HYc~jsTu+tjmW1Kg$Mq%2(8jaq-?+G>*4Eb}^2(#)g`SwjdtFB8b>x8nCs1FbD1zdsH-{_{Dt?Z2NZqtD{psV{Q?qo8SM!0@+t+G;(JUe zBo7aY58kg!q?dqqZi*b;{y-^Y9u0_pn?9Ed$@7V5dT;?3lE)LV z`oY5CA-RMAQ=muN9+HJmMBjs^w3vtr^}6=hSif;Q%rkDG(Hp$lf$;t7y~s z5(zA033PxQ*)Q6FU)xTf1|`uqBcBnDi0X%?y0yt5%dqx(6f#yVTvJ6 zZv!2=X22gj2zV-9haux?0rjlfQv^(dKBIdz^+PRP)qc6sswac8ds;Tit`F+Pmyso)d22&tM(LeeJLO)zY;O7 zRwJO_w~AIj71$ow-k(_CyQ#blO#Jl18q9(}N?<$7i8hcw}eTvqGS zpkWB^I!i`0#`NXH&O<@@$q1J|t%q(lPaNF$rcHh34Z;c_JI@#2wg$VooBfIIt^a!~ ze4aRkGb>}g#i+4pNaxTuP+yF8RWug0k%`(iVi96ml3HG~Y5cTq-q;D_rWo*`HW{vtRr25RqT**G7j|jGhYA zlm8vy{m}v5o6i4#B8-m)jV*UeltgFRpdqF&4QwNf5R_ZOvmjz`@*j?UmY;e4g+5+?T(oJW4w;`!zuPxhOjJUp>n2`K=pcn<^wD9*kjjtA? zq?Xi{y|(m@^)41ecC0-lw+4DQo$$`WI@OSa`In0NBFy8=oqk|kgA+9Cmr+{18z?~S zmr3nLmkM(#p9CiK`z}fAE5K~?P2X7O#%0&(Iu+HrJSYK;LXTGzJ5pUnZ||mq-Zj{* z%Df11(;zV2@pFAbbgR7^Ql+Q#^loCY0(Tsxdthzgig-jnT71=}cB}nE`)CR>(ItAt zSTUNw)N>lPdsvprpQ52YO-0@xz9PkD4f>ODMgr>_7PSw55suYk=^OzTFA`8Kw(`c+ zU-o-+RBTY01N~Ew@#25ti}j~yV!Lcn@A@lYRl2q(hU-(NT^1+XlijqN=fbM=I~TmO z;F%Au#i*7yG&KxSF~;|Qg%j+ z6e?hz{S*VHm^prNs72Wdko(LcD2kx~u70413h3K0}3l>a$eXW8W8&dktQ% z`a%L7Kg3h1sN~VjxWlPJaWBLpv)2)|z#Pj|#<*oek&6Q0`cgEC{M_A0#vGu?m3PZJ zpvWr&z)*m=zBDy;rj`eQ!GdV%$-6M=K#>;(fW81hyfX;gdJBShThNG1Xh=o1U&b>5 z{%w0fGYvlA5Y#L3q)5}I>0YXJ(?C-t)w3aadK--u;1H)*mr@+}^%^l*$Zl{m%34#yxO~Sh+$&C?%ip4HMJ$FWnao4Td06C zJAttAqT$txJCjj--hOkgh1u)oUoCKoUdUU=VGBT=qs za&DGrlnae~dCL~(`}lT^`??=Yxa>2#dY!9W#&OH8xyqNVlE8#-eZ4NT(^#>}Szd9? zxm+4DF`~z+8VuRa%57~ry&{hamv1t9sh)qjG9+h`rcLI5EpSL4ONK^T8C_zaPq6^} zs6r!W(*VHp6sYI=1OTujTFLv;(n$_pw zbYmrbab1btGU|=1#fe3um>ME}3boZq;bW*E>t{87sdFOA5ov?}u4PyTIw zNxr5A0ll*_wZ*Xd505Wc)mYRN75*@f3iYNs@bw3EaLQk#%JvCY`e%N=6WrH4m}}wC zgqGvzo=s+SQ){k*ZtzLI@vj-RCu`5!%PY}+b$iHl- zztm#pXw;>bb?tLS{geXV9%4X7)S_-3fq0aN0RBv&H`zQ2%TKq7FP5aaey3=V%lrN& zj}Vcc3m1`0P}v4&G;KO)Q+-o_BJ$(mHFy*t?LQ%zAR<2+#uA)z*e0EO#`!@d5U8;_ z8r+nqFpbDBb&ysLZQTTCXwEoY5&5Ao7=@Dl8zEaBFz%``~8BBVk=IhKfZ zj`3Vj-WL`RJ4~?=`G#UbL3vA9yyzIk{3R?BM^1b|KBWMY=0Zen35%B5I)-D#(%C5~ zLAmPgDTlX4V5ovoo~L5>xxXOCjSLGc%}r;aK*1o#ojG}4zUl2NF>IoZi<62G5q zW8M#np==DE|}ZEED4Dh=hj=r0EbL%YjB(jOKUJx-H>AX@?+2R}<~x|10rBJc1~^4LKYtD!CEmB-?es1}Q=DkB$DSe%-IDf4JwR_qD5@`r_``zl zQ$8MaIfoU0afMMS@`wnv;BkAr5Rn%V@!~=OYDM^nBQf!~ww<0@_qc#J$5L5TB|h=U z*o8s)sW3DG!T5aaMRkdQg7Qzoj1ib_`&fhFd4nrC8cuvKMz^5V?&8qWHrB-&U}nnm z0^&*{^0`4^G$G^j1??d7wp1nl`H_VS?zP~e=9kXZ9PnUkOl1)iDvM|xbm(04c8!+# zR+S^p88kaEU8 zlF@Qi%JKXt-QUWk4@0AR#$}B@7myzg03&A*PzBmaz`UIVT6PjffMP&C72*)B7cV_p z%Dgow=00YEI&tY^V@5s^pzf?oG%S(pl|YB`hrQE(5Vt+{=(wN^Lr{O&1#lc;jmGDV z4RE@#j$SE7Co6^@8*2^7n-vb-XxZ;&-0=?e;48w?)uqyP-ePlIy)C*tm(X5bDo`)O#{FJ+ARr$LKqR1m{A6IP*X}YqYhA0H>K6j?ivjWaPYT=&zNi=xM59Zo z1^Amm0jc#tnGe&av4P#>aV;>8%W7JYc+P?%@@vH7-Ax{Mf(c*vdVgki8dtA!ek!T; zltX?DN%Tmhrp(W(Z`=({f7q4)thNO3=br%{{BiH}`&*Od`r{;M+DF{vBK9O-Wr1G+=UXGrWoL&!Ap|57-0LLfWDVNhb|dpoHz*h ze;fpS%pt%RAEM#e9GayQHu2s=HsCL4hxsA-SA%yX#zB2S)ZfD#r`{gw8_=LpyU;MC zZ=+GAq%17|{*&Ccu^bht5~N2o^XnifKnGD+PK}63iyN5> zVe!4i)|9qz0Se29!%xh5cwpm^1ARP`g%+Vf`L7`{viQM_m&5ZB1sEQwMZom%K=F|* zM1cn7rchS2=KZkvSLhEI%3IkkboME>a%=c=6FWORqrq$D{W@ z@iQj2p&9V690Gjpp`(YNO5!*M`v%3+<&Tt)@~^=xWXBd_hKotD2!GW5!WQ#2$UHHI z8p2D~KDc&Tv1vinFWT8O}&nTWy3gBHtt1a`#{n6L*G zqgVqlGMFE%LEF(K33MFk2Oe?W)4D>Z7w`wXfZx*$c;NZsz3QDTsBC??nM0$fw*|oi z0Iwke3d=hKStu951B%=eP$Bx}y?_bP;BB$$=@gF0e~pNHpSHO>s{sFc72x%o0pIC@ zd7aM6BG$n=Sx2oC80iz}fSZTvscwdPP!X25wox`6hV&IQA8{su7S`A6f_c5pg7&an zMpzeT#y%n`*JB*4(@|0G^^!u1rZjoL@efV0% zZz_z1`GunG+OqgF$NR=5B%ik-eYBGqL16k@4_EkJYPUphR>E>S0jBF0{v_q2H{ z&>34Q+i9M$mH?C71B|&S3prhNq{ssC(h#(ixv^r=bpYX-WUI*aHb)7~bVGeuek|%- zWwM|j;AJOZ^!L*f)Nlm2HmXhmR!%6_3tAKAaLBwV8HW>M{GVww-2l6Tz{K{%Iv7Jr zC3n%h37VPnbT9?&O`1SAz&C@ybf<@LKtukIQmzhUOxDo^7=E_X$>84-8U#b#YpT0x zM%wmr7clqv1CpQv8EHE4-Jd>?UD+Blm-1TPCdN$1I6s)T37S=Y>gJ(35a8n{==D*q zPW28M+S3^ zO-`EnM0>XAsE7WX^MVUxhy0aAf=+z(nRJf96N%XTjLyyAQG?^X7YMKbGr-Sm0fHjW zRJcZNA28qQfdYf?5N@A-`Z)9DbMV~-#E3!1ueJdG=oY|_+yeNgYX1G1Q9D%bsRjJ& zb%5`z13bGG@U>e3pSczA3%3IPyRCp<|L=D0|3dJe$o_xj)LOuUOh!;-PNAoKb_=_Y z=Jl~=D-PE{V;Kf&O#mL{9{h3kO{-$k4f zMfhoiB0N>Y?xVL@toUuz8KcN=M^x#jZXK(kFh|4*731IuaZZJPI>dibIK8@2eL#`l zi{wlg@c&bSnJ-C;P!@{ogK-caP_|3d#QB{9Eml0ghRfe6`}om%avM9z^zw_jr%W^n4a%6tE!UK^A1B zjRqO_R(x373uzDfO$g#yideUDCA=!$Tsd<3S7BhX;?F#EBJE*1*^?gC9*CKLP2(@& zzh44I)d7{L$j7442cys*h!3wC>4v!AUy$A~C6kryzC^LT8pXEL1M%M@_eioo3gKZ- zMz7stid+x|ra3*Ix1>)fJx2$G!oW1kS2p0Qgt#VB zi^>MhR6<-8xzDk0)-?Zk#~#~M|F>jMGliISH7;&3g7}%p5PU^s(X59DW*?q;D=GQ0 zOVlB!$mwD16&F04Atcaqa+xB((oT6Vl}$Cr_@^NtK>Tooe%m6i*m`~Eq?xyp z@)*7Pz(+)9QRJjBFtXy${~2xl^R#4;vEvZnmFu7FdSbKcb8!8$T?MTPj)d93#CPbB zA~yzyl?YCVs{-*3;MGwTk{joqW7q3k*-mP7i7MI*`#s zjY1vB$YG;Ndb0&rSndo{zmPF18R+}u)`Zzc7ceJW81A4rBXUDjPE(;r|Ck`gAvkre zkbG?r8iw_0px}b|bK-`kAN{`~8gN6RNN6Xt!+VxySmvV0(;bzqL-VL_R^*&uYKa;_ ztP7}6!BJfarBPDAaunj^K@QpVCKQq95;i@#CuvRvGCLuj9$@zAkqa3Ijz_bv7%?RO zKD-ivV!g=)@#KI7@y%3ZhU7Qf$_Bp6SIy~>=@&2KxQ!+{c`+rct zA};$`@)(F8BhbV}C&Who$AZp&P_l?Sf0pVF%MB4|;(Txhm~h(<^D&hN8v_!>%c8P7 z+&UhKHf?LNuk23zI?qy=vk71(@}1;x>0H2#Uy4xggO2+;dImc$(ab-QR9S#IzJp$y zQRAwzhm!e@JI8AM47d=8#pBYULt8DkU z8cCHU*-JI(H*J+gK<{yd<#TNub#+i5o7+crJC9jH@~;BLM|YFWmUj%yeQ*z_>=vrD~^a_Z&B!{}ACSILu7y>y9eAI3BTP0Tr$PbY&vRgaZYj&BU-bR`hwwoqX zX|ud8mm-S_eY4*(9&vpZ4ULZa8__0ad1+pkqL=HGFNn4#e(EQ-et#Ev^Zy`v(-Ive z*LRHXBF8FUX&Z8@c9A{Wtbg@*n(V0r#`3zRI%;atJBU+*GhHC-pT40SvQmYv($EU^ zNXm73?xXYYpm&~exUBj&ophYtk<(;90H$i6)d3BiP7^Y_c9V13bQkM3&cq(rTy&c3 z29~xpIEl+bR;0*ll&3G&IiZ10eK+}9o9<%%1-Sj}bn{J=XEqth3G=ey;Djx(s__ zo%*4fRYfYD1xMA(MwPC2U7(@qJBIG6=`}OGtLFNSLCWc>!QEuD@Kj(&Kg_Kon+2LV z&QF~?>w@3xT3SJQojQ>y|I?fAH8_rYReGZy@PFL}_-VU=o2N-wBN2~MPz3@;fP*2U zD;rgyR2TK6Qv08h70(>v$Khy)t;DCu`y*iDEFYZc@B;(acUnVvb9(ePXP8~>?;>9cyJs;zn7ez{^L}97=%+2uhIf-H zEiGjzK=@dy$*SjA%JV!>UweE%nXAR*584+1Qw z$;*~c2xobZY`45c)RsEZV2Nf~nveQ`u&1b5a_h6w?v6?4ACi@xyCCoSpm0OdXT{$| z%tv!ef%z9cMxYnr0$47s!B2vxBw&oI@sT${iL0~zD-R{Nt|-d1MbQYo`v1Kb1AXts z6r(};tb1@b*=hmig}&XS)&k6Bey;CiY!^8>Z$cZ5QJ~=g^b&Zb%e+nN8of&C?vle z{;e(b9F6u^rVQP9yWds5lzwab;rykYTEd)yxyx2fZGl96YD^2v`)=z#dNZfp5$)v9 z5>02BSkpyLT7bFPXGBctmwGx2nS3aHwTpTNYF&?4SZ~GTyn%;R{GrEt z+vW!N_nx5y@!V*7_~X7cZmd%!TwF6Suly?=YnIQwbBCGFWUk$0-`yF^o&GR zxFVkqLZb@Rky=Zy1Tw#qM4U5fqW;z1oiQz`EpOQPuX}guUrlX^X<3@`X$$?|hSie( z)qn1cp{r<_&{C3mE84{HPD6RaP!oF1`c6Y?%h%F74No^v!10y|Ekl^|mo+rq1*7+@ z%Nm9-!|5H;vWEBn1zeIk5S4YwlD5^ln*R5Ud$G5XY_%k}L8FIkwa^TRdnqg)vQ&KQ_r0XZsh1_YML?r%wycY)M4GAPBYQl@iCS=G z7j!rcU{?=0R_Q*v*=2Iw>`&ZwvtL`c?&Iw=s-do5TMzUnh~d<$Ehk8ZkPv7HCACmF z3ichfjXigQ7_{{LP}G#l-$R@N&@V!}Ry7ul@-9Lld3*4wz_!6{{fYHIw*8857OHiJ ze5WT!hO>v5gsCmNp0GVav78tj?}WKYEx)iGBpJdY_UkeX*n=d)0w=fszc!8qxTz|8 z-pfmS(+`ACwYpGVniL|?Hl+nhL2T3ds4bna6tL^Cnve#PwY0BaKt2ibfC8f+kDWo$ zT~t=kDQ;8jEXD1%0*<a{}(%hS*Av-q-pLO=mym#)s=bU@rC-3Im z^YbMSzXu_lA3j7j^HlO+iuRDrJd=6TlWUvac#!}<-nDNL7+)Uv)K}syuD@rpWCkL5 zT^|*IQ-$cmrO~WZD)4uO@aLmZxhS7Xu2kad4kVfMJu%%&1XuToy)?-jjnUZKX~;|z z#t7$u^w>ZgPdK5#pASeqgdxA@nqV`1!vvGc1}Rd8CLQL+813M8`Ag!EdS zQ=tC}mRk=rOJwU|`wnj856u#3-)Fa*{X=$%sPO4FZzJoU zKSNqF&yY>#`9ewsC?r5PQSMRvbTF3W3Jf9K8GP5bvW%K9dWl*%=7T=P3#h{jsFQA* zy0>?3cP3Y8b-yQW6DK$YP%Z@Md21lfGkgRHmTyyg)9#?U)6`4(sEExOXI%XDDky0x z-Q+2dRz)e?x52G{W70#yHZwcSvJ(f3L8WI+cCo*U7ZZk5dXBFYHF_lO5kD5iUQN|^ zK26mnpQdWacXK6^&k|-5OW3+^>BkH=ebD!}4nQLvfWGbk^ic;OC>Ix@EsstBz7~D!>#ft;R<%uAXIt0clnCEHwoD>A@U3fbNks3l zC`o9I;!c!EmPsO0Jrc`CXC{DN2z9Yx}X!7gAx2igi7Dq?g+ja&y5zsgYg|U zwft+}Q#mE)U}EBhm0rE8(tF4$f4P?DM)BrRIk+~%9m4P2M@>_5jpD&kE<-&?_3qON zCye5eQR==-)!yx$170vNdS)MUEaAWlWRmIJHMZ>BHLh$FOX0)j#KEtxv1Yq-skhn+ z`m@&{Kj9$qhVT`_3#e1u%e^97fAZ0*y%=$NI|C`U;sWpKU1mkgp5991V70wr>?OQF zJpdTMJ{tQ^P16OYJ4WG@_mTwY-qqRYWd!!vZG0w>{7%x#>@jA47&nY+sM_K>jjpD+ za{xM5dP;6e-qaC7-&mo)|l%@KmTnJwZ$Y0ej;X?Ri zK+b8nGI0d~BRN0SD)urJpr}ql--7fL)5ZM^H;QKk<^INrTnN_^`C?B$a?`I%+pXa>iwUj_S`@H9&YvZo0)oqeWjw(p(M&0xg0tje0aa2{cX!my z@t~XvBvevm+n}?i6qKU@Q2rH&IZgNWKp$0gQa%2K04Tiy;6ZsKK=Yqbr|Oq_A~(j; zU>Ac~zTEc2jJlvjVXQIS>Qj`Iht&7Q{=bT9c9YoU$56aMeyt%&@tsf-{Z*~lqGY(7#V>bV2!E)aS>Zi za8?iV3q0zk_~Zf9t0^ZqE$C4gCb9gJE_$5=r}n7J2~G;ipRG5zEw{iVcK?&KKUz># zdP`KDChd>Ts?4wWf_Ms5Bkl>RkuBASSlLRjpX8Ji{B!iI5Qg{T#{$65T+Dne?(P)>dO^_2(BW6ozO5jL~(6|?62f4VZ{wHwAQ z*YE@%52yue&(q#8_J`>x$$`|$aTPNKqwui9kGTM&n@}Fc&xTpu`0_Ab6Xpdlgt6&% z7=IHczLKBX3z(@N&_M5EsDYv3DFyO{4O1q6*8vE30HPidHKi71NY5+o;u;(M!LO84 zpL@{l$KRY>Np+V)Fhm`1m~ub9a1#1x8!{OkSB|><_%lLzA@da*b!(wGHcs1jmzIt4 z{w3ZPyAy;|0Sp~x7!-R~5Cb4D!G(k=81W(FLl?(BVfg_jG4h+w%`=<20QGkP;*4~S zND(Gnq)#B7sIoPc76l-s&!9vY&{dNxle!|gbb`Z=HH0R1q&mcqZ&H_>vGD=Uk1Zj& zaN{y{iwX=@`K65$I6uxfDIeRI$@#I4$e(XaFY@CJVJ?Fkq)MqH5scGAbp4@vm!Pk( zJAykRYN5vK$E(A!bt-~CiWmiqxsc3nYT^7iGb|t6RL^0&Hz+4<_HcfDbX0zE^WQm) zuLR_kTRzSU;;Zj#yVZ-S*oY(Cun{8o=LlPAw`zNf(`mR8i(nWrd?xBHc1CbmUhdwR zKrzmA`I37@w7TV2@u7V?9YuWBeN$Dp+U<_!=GCorbsPAm_`GzaU-I9Z+Eu?A>TUI~q^7{U zxGgUyZ%&SBO>O=vd+qANRkpb>6LM=EZMiKi8>&rrt0hmAR%O*fNh`grhWfh|-n^I> zs+RL@b82$dgSoZtS;)Q1RBf7>H`_$Z-L8_-D*3u+G82)})+2c|@gD;K)a6BeAEa4W z0RU)1P>Q$4+comnTOVAyl?TKE0EMbJOke;UJfK8~LBs&qc|b{VyoQO_R{#g)yG2xqwoO0BtJ-w7C$__X_}Bo(CwfFp8J|@qF0*$7(=t zR^OZBXuRII0?=c>1$1H=ptPD8{`;o@RX!Q3fAS0}Vb&-yROZm -extern int sercon_main(int c, char **argv); - void board_late_initialize(void) { - sercon_main(0, NULL); } extern void sys_tick_handler(void); diff --git a/boards/auterion/fmu-v6x/src/hw_config.h b/boards/auterion/fmu-v6x/src/hw_config.h index 4ad1049fed..949a9284a5 100644 --- a/boards/auterion/fmu-v6x/src/hw_config.h +++ b/boards/auterion/fmu-v6x/src/hw_config.h @@ -57,17 +57,12 @@ */ /* Boot device selection list*/ -#define USB0_DEV 0x01 #define SERIAL0_DEV 0x02 #define SERIAL1_DEV 0x04 #define APP_LOAD_ADDRESS 0x08020000 #define BOOTLOADER_DELAY 5000 -#define INTERFACE_USB 1 -#define INTERFACE_USB_CONFIG "/dev/ttyACM0" -#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) - -//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USB 0 #define INTERFACE_USART 1 #define INTERFACE_USART_CONFIG "/dev/ttyS0,1500000" #define BOOT_DELAY_ADDRESS 0x000001a0 @@ -85,6 +80,10 @@ #define SERIAL_BREAK_DETECT_DISABLED 1 +// Connected to VBUS on the Auterion FMU v6x +#define BOARD_FORCE_BL_PIN (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTA|GPIO_PIN9) +#define BOARD_FORCE_BL_STATE 1 + /* * Uncommenting this allows to force the bootloader through * a PWM output pin. As this can accidentally initialize @@ -118,11 +117,11 @@ #endif #ifndef BOOT_DEVICES_SELECTION -# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +# define BOOT_DEVICES_SELECTION SERIAL0_DEV|SERIAL1_DEV #endif #ifndef BOOT_DEVICES_FILTER_ONUSB -# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +# define BOOT_DEVICES_FILTER_ONUSB SERIAL0_DEV|SERIAL1_DEV #endif #endif /* HW_CONFIG_H_ */ diff --git a/boards/auterion/fmu-v6x/src/init.cpp b/boards/auterion/fmu-v6x/src/init.cpp index 88fe88126c..7e35a407c4 100644 --- a/boards/auterion/fmu-v6x/src/init.cpp +++ b/boards/auterion/fmu-v6x/src/init.cpp @@ -179,10 +179,6 @@ stm32_boardinitialize(void) const uint32_t gpio[] = PX4_GPIO_INIT_LIST; px4_gpio_init(gpio, arraySize(gpio)); - /* configure USB interfaces */ - - stm32_usbinitialize(); - VDD_3V3_ETH_POWER_EN(true); } diff --git a/boards/auterion/fmu-v6x/src/usb.c b/boards/auterion/fmu-v6x/src/usb.c deleted file mode 100644 index 70eebc6fe0..0000000000 --- a/boards/auterion/fmu-v6x/src/usb.c +++ /dev/null @@ -1,105 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2016 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file usb.c - * - * Board-specific USB functions. - */ - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -#include -#include -#include -#include - -#include -#include - -#include -#include -#include -#include -#include "board_config.h" - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: stm32_usbinitialize - * - * Description: - * Called to setup USB-related GPIO pins for the PX4FMU board. - * - ************************************************************************************/ - -__EXPORT void stm32_usbinitialize(void) -{ - /* The OTG FS has an internal soft pull-up */ - - /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ - -#ifdef CONFIG_STM32H7_OTGFS - stm32_configgpio(GPIO_OTGFS_VBUS); -#endif -} - -/************************************************************************************ - * Name: stm32_usbsuspend - * - * Description: - * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is - * used. This function is called whenever the USB enters or leaves suspend mode. - * This is an opportunity for the board logic to shutdown clocks, power, etc. - * while the USB is suspended. - * - ************************************************************************************/ - -__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) -{ - uinfo("resume: %d\n", resume); -} From 9fa4a57c6653160a377fe1afc95c3fa5897527be Mon Sep 17 00:00:00 2001 From: Niklas Hauser Date: Fri, 10 Oct 2025 16:49:09 +0200 Subject: [PATCH 180/812] tools: Ignore known_hosts file for uploading via SSH --- Tools/auterion/remote_update_fmu.sh | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/Tools/auterion/remote_update_fmu.sh b/Tools/auterion/remote_update_fmu.sh index 2eeb66b999..d3777aebaf 100755 --- a/Tools/auterion/remote_update_fmu.sh +++ b/Tools/auterion/remote_update_fmu.sh @@ -7,6 +7,7 @@ fi ssh_port=22 ssh_user=root +ssh_opts="-o UserKnownHostsFile=/dev/null -o StrictHostKeyChecking=no" while getopts ":f:c:d:p:u:r" opt; do case ${opt} in @@ -67,7 +68,7 @@ target_file_name="update-dev.tar" if [ "$revert" == true ]; then # revert to the release version which was originally deployed cmd="cp $target_dir/update.tar $target_dir/$target_file_name" - ssh -t -p $ssh_port $ssh_user@$device "$cmd" + ssh $ssh_opts -t -p $ssh_port $ssh_user@$device "$cmd" else # create custom update-dev.tar tmp_dir="$(mktemp -d)" @@ -105,11 +106,11 @@ else $tar_name -C "$tmp_dir" --sort=name --owner=root:0 --group=root:0 --mtime='2019-01-01 00:00:00' -cvf $target_file_name $firmware_path $config_path # send it to the target to start flashing - scp -P $ssh_port "$target_file_name" $ssh_user@"$device":$target_dir + scp $ssh_opts -P $ssh_port "$target_file_name" $ssh_user@"$device":$target_dir popd &>/dev/null rm -rf "$tmp_dir" fi # grab status output for flashing progress cmd="tail --follow=name $target_dir/update_status 2>/dev/null || true" -ssh -t -p $ssh_port $ssh_user@$device "$cmd" +ssh $ssh_opts -t -p $ssh_port $ssh_user@$device "$cmd" From 0f0fe8f1fa6edfe5007641c51c837b380a3c04eb Mon Sep 17 00:00:00 2001 From: Alexander Lerach Date: Tue, 14 Oct 2025 15:36:09 +0200 Subject: [PATCH 181/812] boards: align auterion v6x with APX4 --- boards/auterion/fmu-v6x/default.px4board | 10 ++++++---- boards/auterion/fmu-v6x/init/rc.board_defaults | 3 +++ boards/auterion/fmu-v6x/init/rc.board_mavlink | 12 ++++++++++-- boards/auterion/fmu-v6x/multicopter.px4board | 1 - boards/auterion/fmu-v6x/nuttx-config/include/board.h | 6 +++++- boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig | 9 +-------- 6 files changed, 25 insertions(+), 16 deletions(-) diff --git a/boards/auterion/fmu-v6x/default.px4board b/boards/auterion/fmu-v6x/default.px4board index f714280cdb..dece24a26f 100644 --- a/boards/auterion/fmu-v6x/default.px4board +++ b/boards/auterion/fmu-v6x/default.px4board @@ -20,13 +20,11 @@ CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GNSS_SEPTENTRIO=y CONFIG_DRIVERS_GPIO_MCP23009=y CONFIG_DRIVERS_GPS=y -CONFIG_DRIVERS_HEATER=y CONFIG_DRIVERS_IMU_BOSCH_BMI088=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_COMMON_LIGHT=y CONFIG_COMMON_MAGNETOMETER=y -CONFIG_DRIVERS_OSD_MSP_OSD=y CONFIG_DRIVERS_POWER_MONITOR_INA226=y CONFIG_DRIVERS_POWER_MONITOR_INA228=y CONFIG_DRIVERS_POWER_MONITOR_INA238=y @@ -34,6 +32,7 @@ CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y CONFIG_DRIVERS_PWM_INPUT=y CONFIG_DRIVERS_PWM_OUT=y CONFIG_DRIVERS_PX4IO=y +CONFIG_DRIVERS_RPM_CAPTURE=y CONFIG_COMMON_RC=y CONFIG_DRIVERS_SAFETY_BUTTON=y CONFIG_DRIVERS_TONE_ALARM=y @@ -53,10 +52,12 @@ CONFIG_MODULES_FW_ATT_CONTROL=y CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_FW_MODE_MANAGER=y CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y +CONFIG_FIGURE_OF_EIGHT=y CONFIG_MODULES_FW_RATE_CONTROL=y CONFIG_MODULES_GIMBAL=y CONFIG_MODULES_GYRO_CALIBRATION=y CONFIG_MODULES_HARDFAULT_STREAM=y +CONFIG_MODULES_INTERNAL_COMBUSTION_ENGINE_CONTROL=y CONFIG_MODULES_LAND_DETECTOR=y CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y CONFIG_MODULES_LOAD_MON=y @@ -64,7 +65,6 @@ CONFIG_MODULES_LOGGER=y CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y CONFIG_MODULES_MANUAL_CONTROL=y CONFIG_MODULES_MAVLINK=y -CONFIG_MAVLINK_DIALECT="development" CONFIG_MODULES_MC_ATT_CONTROL=y CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y @@ -74,8 +74,9 @@ CONFIG_MODULES_NAVIGATOR=y CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000 CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_ROVER_MECANUM=y CONFIG_MODULES_SENSORS=y -CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_UXRCE_DDS_CLIENT=y CONFIG_MODULES_VTOL_ATT_CONTROL=y CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y @@ -92,6 +93,7 @@ CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_SD_BENCH=y CONFIG_SYSTEMCMDS_TOP=y CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y CONFIG_SYSTEMCMDS_TUNE_CONTROL=y diff --git a/boards/auterion/fmu-v6x/init/rc.board_defaults b/boards/auterion/fmu-v6x/init/rc.board_defaults index f371bbee78..1a6fc9673c 100644 --- a/boards/auterion/fmu-v6x/init/rc.board_defaults +++ b/boards/auterion/fmu-v6x/init/rc.board_defaults @@ -17,6 +17,9 @@ param set-default UXRCE_DDS_CFG 1000 # The buzzer draws too much power (0.2A) on the GPS power rail (limit 0.45A). param set-default CBRK_BUZZER 782097 +# Update default IP config if needed +netman update_default -i eth0 + safety_button start # GPIO Expander driver on external I2C3 diff --git a/boards/auterion/fmu-v6x/init/rc.board_mavlink b/boards/auterion/fmu-v6x/init/rc.board_mavlink index 4952825bc4..88cdd87c66 100644 --- a/boards/auterion/fmu-v6x/init/rc.board_mavlink +++ b/boards/auterion/fmu-v6x/init/rc.board_mavlink @@ -3,8 +3,16 @@ # Auterion FMUv6X specific board MAVLink startup script. #------------------------------------------------------------------------------ -# start Mavlink on Telem2 -mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z +if param compare MAV_S_FORWARD 1 +then + set S_FORWARD "-f" +else + set S_FORWARD "" +fi + +mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m p:MAV_S_MODE -x -z $S_FORWARD + +unset S_FORWARD # Ensure nothing else starts on TEL2 (ttyS4) set PRT_TEL2_ 1 diff --git a/boards/auterion/fmu-v6x/multicopter.px4board b/boards/auterion/fmu-v6x/multicopter.px4board index 147297d55e..4f1b9ef033 100644 --- a/boards/auterion/fmu-v6x/multicopter.px4board +++ b/boards/auterion/fmu-v6x/multicopter.px4board @@ -9,5 +9,4 @@ CONFIG_MODULES_FW_RATE_CONTROL=n CONFIG_MODULES_VTOL_ATT_CONTROL=n CONFIG_COMMON_RC=y # CONFIG_EKF2_SIDESLIP is not set -CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y # CONFIG_SENSORS_VEHICLE_AIRSPEED is not set diff --git a/boards/auterion/fmu-v6x/nuttx-config/include/board.h b/boards/auterion/fmu-v6x/nuttx-config/include/board.h index 7907eafad1..964976318a 100644 --- a/boards/auterion/fmu-v6x/nuttx-config/include/board.h +++ b/boards/auterion/fmu-v6x/nuttx-config/include/board.h @@ -377,7 +377,11 @@ #define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */ #define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */ -#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#ifdef PX4_RESTRICTED_BUILD +# define GPIO_USART3_RX 0 /* PD9 */ +#else +# define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#endif /* PX4_RESTRICTED_BUILD */ #define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ #define GPIO_UART4_RX GPIO_UART4_RX_6 /* PH14 */ diff --git a/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig b/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig index 328a033bbf..6070e6696e 100644 --- a/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig +++ b/boards/auterion/fmu-v6x/nuttx-config/nsh/defconfig @@ -139,14 +139,13 @@ CONFIG_NETDB_DNSCLIENT=y CONFIG_NETDB_DNSCLIENT_ENTRIES=8 CONFIG_NETDB_DNSSERVER_NOADDR=y CONFIG_NETDEV_PHY_IOCTL=y -CONFIG_NETINIT_DHCPC=y CONFIG_NETINIT_DNS=y CONFIG_NETINIT_DNSIPADDR=0xA290AFE CONFIG_NETINIT_DRIPADDR=0xA290AFE +CONFIG_NETINIT_IPADDR=0xA290A02 CONFIG_NETINIT_MONITOR=y CONFIG_NETINIT_THREAD=y CONFIG_NETINIT_THREAD_PRIORITY=49 -CONFIG_NETUTILS_TELNETD=y CONFIG_NET_ARP_IPIN=y CONFIG_NET_ARP_SEND=y CONFIG_NET_BROADCAST=y @@ -155,10 +154,6 @@ CONFIG_NET_ICMP=y CONFIG_NET_ICMP_SOCKET=y CONFIG_NET_NACTIVESOCKETS=16 CONFIG_NET_SOLINGER=y -CONFIG_NET_TCP=y -CONFIG_NET_TCPBACKLOG=y -CONFIG_NET_TCP_DELAYED_ACK=y -CONFIG_NET_TCP_WRITE_BUFFERS=y CONFIG_NET_UDP=y CONFIG_NET_UDP_CHECKSUMS=y CONFIG_NET_UDP_WRITE_BUFFERS=y @@ -174,8 +169,6 @@ CONFIG_NSH_QUOTE=y CONFIG_NSH_ROMFSETC=y CONFIG_NSH_ROMFSSECTSIZE=128 CONFIG_NSH_STRERROR=y -CONFIG_NSH_TELNET=y -CONFIG_NSH_TELNET_LOGIN=y CONFIG_NSH_VARS=y CONFIG_OTG_ID_GPIO_DISABLE=y CONFIG_PIPES=y From 376f52f51ddcb0b103b7b6439478357035fe8b2a Mon Sep 17 00:00:00 2001 From: Alexander Lerach Date: Tue, 14 Oct 2025 18:11:55 +0200 Subject: [PATCH 182/812] mavlink: add som/fmu config params --- src/modules/mavlink/module.yaml | 37 +++++++++++++++++++++++++++++++++ 1 file changed, 37 insertions(+) diff --git a/src/modules/mavlink/module.yaml b/src/modules/mavlink/module.yaml index fa2fe38834..a8eee0d093 100644 --- a/src/modules/mavlink/module.yaml +++ b/src/modules/mavlink/module.yaml @@ -201,3 +201,40 @@ parameters: num_instances: *max_num_config_instances default: [0.015, 0.015, 0.015] reboot_required: true + + MAV_S_MODE: + description: + short: MAVLink Mode for SOM to FMU communication channel + long: | + The MAVLink Mode defines the set of streamed messages (for example the + vehicle's attitude) and their sending rates. + + type: enum + values: + 0: Normal + #1: Custom + 2: Onboard + #3: OSD + #4: Magic + 5: Config + #6: Iridium + 7: Minimal + #8: External Vision + #9: External Vision Minimal + #10: Gimbal + 11: Onboard Low Bandwidth + #12: uAvionix + 13: Low Bandwidth + # We shadow the modes that can block the FMU to SOM connection + reboot_required: true + default: 11 + + MAV_S_FORWARD: + description: + short: Enable MAVLink forwarding on TELEM2 + long : | + TELEM2 on Skynode only. + + type: boolean + reboot_required: true + default: false From babe094d0692427195ad857582190b3b86d1a625 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 14 Oct 2025 20:46:29 +0200 Subject: [PATCH 183/812] FailureDetector: use robust timeout checks for motor failure detection (#25757) --- .../commander/failure_detector/FailureDetector.cpp | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/src/modules/commander/failure_detector/FailureDetector.cpp b/src/modules/commander/failure_detector/FailureDetector.cpp index 34eb92089a..2cf3608e5b 100644 --- a/src/modules/commander/failure_detector/FailureDetector.cpp +++ b/src/modules/commander/failure_detector/FailureDetector.cpp @@ -255,10 +255,9 @@ void FailureDetector::updateMotorStatus(const vehicle_status_s &vehicle_status, // First wait for some ESC telemetry that has the required fields. Before that happens, don't check this ESC // Then check - const hrt_abstime time_now = hrt_absolute_time(); - // Only check while armed if (vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED) { + const hrt_abstime now = hrt_absolute_time(); const int limited_esc_count = math::min(esc_status.esc_count, esc_status_s::CONNECTED_ESC_MAX); actuator_motors_s actuator_motors{}; @@ -282,9 +281,7 @@ void FailureDetector::updateMotorStatus(const vehicle_status_s &vehicle_status, } // Check for telemetry timeout - const hrt_abstime telemetry_age = time_now - cur_esc_report.timestamp; - const bool esc_timed_out = telemetry_age > 300_ms; - + const bool esc_timed_out = now > cur_esc_report.timestamp + 300_ms; const bool esc_was_valid = _motor_failure_esc_valid_current_mask & (1 << i_esc); const bool esc_timeout_currently_flagged = _motor_failure_esc_timed_out_mask & (1 << i_esc); @@ -315,7 +312,7 @@ void FailureDetector::updateMotorStatus(const vehicle_status_s &vehicle_status, if (throttle_above_threshold && current_too_low && !esc_timed_out) { if (_motor_failure_undercurrent_start_time[i_esc] == 0) { - _motor_failure_undercurrent_start_time[i_esc] = time_now; + _motor_failure_undercurrent_start_time[i_esc] = now; } } else { @@ -325,7 +322,7 @@ void FailureDetector::updateMotorStatus(const vehicle_status_s &vehicle_status, } if (_motor_failure_undercurrent_start_time[i_esc] != 0 - && (time_now - _motor_failure_undercurrent_start_time[i_esc]) > _param_fd_motor_time_thres.get() * 1_ms + && now > (_motor_failure_undercurrent_start_time[i_esc] + (_param_fd_motor_time_thres.get() * 1_ms)) && (_motor_failure_esc_under_current_mask & (1 << i_esc)) == 0) { // Set flag _motor_failure_esc_under_current_mask |= (1 << i_esc); From a64536802b5a5b6ba8fe6ef1b7dcb6a54a0a99ea Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Tue, 14 Oct 2025 11:45:43 -0800 Subject: [PATCH 184/812] gz: fix gimbal yaw, add dds publisher (#25754) * gz: correct gimbal yaw * uxrce_dds: add publisher /fmu/out/gimbal_device_attitude_status * chore: use explicit ENU_to_NED rotation Signed-off-by: Beniamino Pozzan * format --------- Signed-off-by: Beniamino Pozzan Co-authored-by: Beniamino Pozzan --- msg/GimbalDeviceAttitudeStatus.msg | 3 +++ src/modules/simulation/gz_bridge/GZGimbal.cpp | 10 ++++++---- src/modules/uxrce_dds_client/dds_topics.yaml | 4 ++++ 3 files changed, 13 insertions(+), 4 deletions(-) diff --git a/msg/GimbalDeviceAttitudeStatus.msg b/msg/GimbalDeviceAttitudeStatus.msg index 0007a1c03d..72eca870f3 100644 --- a/msg/GimbalDeviceAttitudeStatus.msg +++ b/msg/GimbalDeviceAttitudeStatus.msg @@ -9,6 +9,9 @@ uint16 DEVICE_FLAGS_NEUTRAL = 2 uint16 DEVICE_FLAGS_ROLL_LOCK = 4 uint16 DEVICE_FLAGS_PITCH_LOCK = 8 uint16 DEVICE_FLAGS_YAW_LOCK = 16 +uint16 DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = 32 +uint16 DEVICE_FLAGS_YAW_IN_EARTH_FRAME = 64 + float32[4] q float32 angular_velocity_x diff --git a/src/modules/simulation/gz_bridge/GZGimbal.cpp b/src/modules/simulation/gz_bridge/GZGimbal.cpp index 451f846563..4fbccc316f 100644 --- a/src/modules/simulation/gz_bridge/GZGimbal.cpp +++ b/src/modules/simulation/gz_bridge/GZGimbal.cpp @@ -100,11 +100,15 @@ void GZGimbal::gimbalIMUCallback(const gz::msgs::IMU &IMU_data) pthread_mutex_lock(&_node_mutex); static const matrix::Quatf q_FLU_to_FRD = matrix::Quatf(0.0f, 1.0f, 0.0f, 0.0f); + static const matrix::Quatf q_ENU_to_NED = matrix::Quatf(0.0f, cosf(M_PI_4_F), cosf(M_PI_4_F), 0.0f); + + // Get the gimbal orientation. Gimbal frame is FLU in Gazebo, reference frame is ENU in Gazebo const matrix::Quatf q_gimbal_FLU = matrix::Quatf(IMU_data.orientation().w(), IMU_data.orientation().x(), IMU_data.orientation().y(), IMU_data.orientation().z()); - _q_gimbal = q_FLU_to_FRD * q_gimbal_FLU * q_FLU_to_FRD.inversed(); + + _q_gimbal = q_ENU_to_NED * q_gimbal_FLU * q_FLU_to_FRD.inversed(); matrix::Vector3f rate = q_FLU_to_FRD.rotateVector(matrix::Vector3f(IMU_data.angular_velocity().x(), IMU_data.angular_velocity().y(), @@ -206,13 +210,11 @@ void GZGimbal::publishDeviceInfo() void GZGimbal::publishDeviceAttitude() { - // TODO handle flags - gimbal_device_attitude_status_s gimbal_att{}; gimbal_att.target_system = 0; // Broadcast gimbal_att.target_component = 0; // Broadcast - gimbal_att.device_flags = 0; + gimbal_att.device_flags = gimbal_device_attitude_status_s::DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME; _q_gimbal.copyTo(gimbal_att.q); gimbal_att.angular_velocity_x = _gimbal_rate[0]; gimbal_att.angular_velocity_y = _gimbal_rate[1]; diff --git a/src/modules/uxrce_dds_client/dds_topics.yaml b/src/modules/uxrce_dds_client/dds_topics.yaml index ef7ba8fc0b..7cc39d199c 100644 --- a/src/modules/uxrce_dds_client/dds_topics.yaml +++ b/src/modules/uxrce_dds_client/dds_topics.yaml @@ -104,6 +104,10 @@ publications: type: px4_msgs::msg::Wind rate_limit: 1. + - topic: /fmu/out/gimbal_device_attitude_status + type: px4_msgs::msg::GimbalDeviceAttitudeStatus + rate_limit: 20. + # Create uORB::Publication subscriptions: - topic: /fmu/in/register_ext_component_request From 2cae8ee7972235506ce34081690cff329baa244c Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 15 Oct 2025 02:05:33 +0200 Subject: [PATCH 185/812] Improve documentation for motor failure injection and detection (#25756) * failure_injection: improve previously vague motor faulure Reading it again I decided adding the sentance in 4d2170c13ea4d42c5b0b464dbbcbb68fb098cbcc is not clear enough. * docs/safety: add a motor failure detection paragraph The functionality is in my eyes pretty basic but so far completely undocumented so I went through the code and added a paragraph based on questions I received. * Subedit * Apply suggestion from @hamishwillee --------- Co-authored-by: Hamish Willee --- docs/en/config/safety.md | 26 +++++++++++++++++++++--- docs/en/debug/failure_injection.md | 32 ++++++++++++++++++++++-------- 2 files changed, 47 insertions(+), 11 deletions(-) diff --git a/docs/en/config/safety.md b/docs/en/config/safety.md index a01a6c6bb7..5640f1dcd7 100644 --- a/docs/en/config/safety.md +++ b/docs/en/config/safety.md @@ -207,7 +207,7 @@ The relevant parameters shown below. ### Position Loss Failsafe Action Multicopters will switch to [Altitude mode](../flight_modes_mc/altitude.md) if a height estimate is available, otherwise [Stabilized mode](../flight_modes_mc/manual_stabilized.md). - + Fixed-wing planes, and VTOLs not configured to land in hover ([NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT)), have a parameter ([FW_GPSF_LT](../advanced_config/parameter_reference.md#FW_GPSF_LT)) that defines how long they will loiter (circle with a constant roll angle ([FW_GPSF_R](../advanced_config/parameter_reference.md#FW_GPSF_R)) at the current altitude) after losing position before attempting to land. If VTOLs have are configured to switch to hover for landing ([NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT)) then they will first transition and then descend. @@ -276,12 +276,12 @@ The relevant parameters are listed in the table below. ## Failure Detector -The failure detector allows a vehicle to take protective action(s) if it unexpectedly flips, or if it is notified by an external failure detection system. +The failure detector allows a vehicle to take protective actions if it unexpectedly flips, detects a motor failure, or if it is notified by an external failure detection system. During **flight**, the failure detector can be used to trigger [flight termination](../advanced_config/flight_termination.md) if failure conditions are met, which may then launch a [parachute](../peripherals/parachute.md) or perform some other action. ::: info -Failure detection during flight is deactivated by default (enable by setting the parameter: [CBRK_FLIGHTTERM=0](#CBRK_FLIGHTTERM)). +Acting on a detected failure during flight is deactivated by default (enable by setting the parameter: [CBRK_FLIGHTTERM=0](#CBRK_FLIGHTTERM)). ::: During **takeoff** the failure detector [attitude trigger](#attitude-trigger) invokes the [disarm action](#act_disarm) if the vehicle flips (disarm kills the motors but, unlike flight termination, will not launch a parachute or perform other failure actions). @@ -303,6 +303,26 @@ The relevant parameters are shown below: | [FD_FAIL_P_TTRI](../advanced_config/parameter_reference.md#FD_FAIL_P_TTRI) | Time to exceed [FD_FAIL_P](#FD_FAIL_P) for failure detection (default 0.3s). | | [FD_FAIL_R_TTRI](../advanced_config/parameter_reference.md#FD_FAIL_R_TTRI) | Time to exceed [FD_FAIL_R](#FD_FAIL_R) for failure detection (default 0.3s). | +### Motor Failure Trigger + +The failure detector can be configured to detect a motor failure while armed (and trigger an associated action) in the following conditions: + +- A 300 ms timeout occurs in telemetry from an ESC that was previously available. +- The input current in the telemetry of an ESC which was previously positive gets too low for more than [`FD_ACT_MOT_TOUT`](FD_ACT_MOT_TOUT) ms. + The "too low" condition is defined by: + + ```text + {esc current} < {parameter FD_ACT_MOT_C2T} * {motor command between 0 and 1} + ``` + +| Parameter | Description | +| -------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [FD_ACT_EN](../advanced_config/parameter_reference.md#FD_ACT_EN) | Enable/disable the motor failure trigger completely. | +| [FD_ACT_MOT_THR](../advanced_config/parameter_reference.md#FD_ACT_MOT_THR) | Minimum normalized [0,1] motor command below which motor under current is ignored. | +| [FD_ACT_MOT_C2T](../advanced_config/parameter_reference.md#FD_ACT_MOT_C2T) | Scale between normalized [0,1] motor command and expected minimally reported currrent when the rotor is healthy. | +| [FD_ACT_MOT_TOUT](../advanced_config/parameter_reference.md#FD_ACT_MOT_TOUT) | Time in miliseconds for which the under current detection condition needs to stay true. | +| [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE) | Configure to not only warn about a motor failure but remove the first motor that detects a failure from the allocation effectiveness which turns off the motor and tries to operate the vehicle without it until disarming the next time. | + ### External Automatic Trigger System (ATS) The [failure detector](#failure-detector), if [enabled](#CBRK_FLIGHTTERM), can also be triggered by an external ATS system. diff --git a/docs/en/debug/failure_injection.md b/docs/en/debug/failure_injection.md index 217a2b7ffb..298e1aad50 100644 --- a/docs/en/debug/failure_injection.md +++ b/docs/en/debug/failure_injection.md @@ -19,7 +19,7 @@ At time of writing (PX4 v1.14): ## Failure System Command -Failures can be injected using the [failure system command](../modules/modules_command.md#failure) from any PX4 console/shell, specifying both the target and type of the failure. +Failures can be injected using the [failure system command](../modules/modules_command.md#failure) from any PX4 [console/shell](../debug/consoles.md) (such as the [QGC MAVLink Console](../debug/mavlink_shell.md#qgroundcontrol-mavlink-console) or SITL _pxh shell_), specifying both the target and type of the failure. ### Syntax @@ -61,12 +61,19 @@ where: - _instance number_ (optional): Instance number of affected sensor. 0 (default) indicates all sensors of specified type. -### Example +## MAVSDK Failure Plugin + +The [MAVSDK failure plugin](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_failure.html) can be used to programmatically inject failures. +It is used in [PX4 Integration Testing](../test_and_ci/integration_testing_mavsdk.md) to simulate failure cases (for example, see [PX4-Autopilot/test/mavsdk_tests/autopilot_tester.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/test/mavsdk_tests/autopilot_tester.cpp)). + +The plugin API is a direct mapping of the failure command shown above, with a few additional error signals related to the connection. + +## Example: RC signal To simulate losing RC signal without having to turn off your RC controller: -1. Enable the parameter [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN). And specifically to turn off motors also [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE). -1. Enter the following commands on the MAVLink console or SITL _pxh shell_: +1. Enable the [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN) parameter. +2. Enter the following commands on the MAVLink console or SITL _pxh shell_: ```sh # Fail RC (turn publishing off) @@ -76,9 +83,18 @@ To simulate losing RC signal without having to turn off your RC controller: failure rc_signal ok ``` -## MAVSDK Failure Plugin +## Example: Motor -The [MAVSDK failure plugin](https://mavsdk.mavlink.io/main/en/cpp/api_reference/classmavsdk_1_1_failure.html) can be used to programmatically inject failures. -It is used in [PX4 Integration Testing](../test_and_ci/integration_testing_mavsdk.md) to simulate failure cases (for example, see [PX4-Autopilot/test/mavsdk_tests/autopilot_tester.cpp](https://github.com/PX4/PX4-Autopilot/blob/main/test/mavsdk_tests/autopilot_tester.cpp)). +To stop a motor mid-flight without the system anticipating it or excluding it from allocation effectiveness: -The plugin API is a direct mapping of the failure command shown above, with a few additional error signals related to the connection. +1. Enable the [SYS_FAILURE_EN](../advanced_config/parameter_reference.md#SYS_FAILURE_EN) parameter. +2. Enable [CA_FAILURE_MODE](../advanced_config/parameter_reference.md#CA_FAILURE_MODE) parameter to allow turning off motors. +3. Enter the following commands on the MAVLink console or SITL _pxh shell_: + + ```sh + # Turn off first motor + failure motor off -i 1 + + # Turn it back on + failure motor ok -i 1 + ``` From e83d18cad2d5e746d4a1882a5dd70ddb2b8eb6aa Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 15 Oct 2025 12:28:33 +1100 Subject: [PATCH 186/812] metadata - _sidebar and only display front page warning on main (#25761) * _sidebar and only display front page warning on main * Update metadata and fix internal flaws --- .../radiolink_pix6/radiolink_pix6_hero.png | Bin 1159928 -> 0 bytes docs/en/SUMMARY.md | 1 + docs/en/_sidebar.md | 6 +- .../en/advanced_config/parameter_reference.md | 895 ++++++++---------- docs/en/airframes/airframe_reference.md | 4 + docs/en/index.md | 14 +- .../modules/modules_driver_distance_sensor.md | 2 +- docs/en/msg_docs/AirspeedValidated.md | 42 +- .../msg_docs/AutotuneAttitudeControlStatus.md | 73 +- docs/en/msg_docs/ControlAllocatorStatus.md | 3 +- docs/en/msg_docs/EstimatorStatusFlags.md | 3 +- docs/en/msg_docs/FailureDetectorStatus.md | 3 +- .../en/msg_docs/GimbalDeviceAttitudeStatus.md | 5 +- docs/en/msg_docs/SensorGnssStatus.md | 19 + docs/en/msg_docs/SensorGps.md | 40 +- docs/en/msg_docs/VehicleOdometry.md | 49 +- docs/en/msg_docs/index.md | 7 +- docs/en/ros2/px4_ros2_waypoint_missions.md | 2 +- docs/ko/_sidebar.md | 13 +- docs/uk/_sidebar.md | 13 +- docs/zh/_sidebar.md | 13 +- 21 files changed, 616 insertions(+), 591 deletions(-) delete mode 100644 docs/assets/flight_controller/radiolink_pix6/radiolink_pix6_hero.png create mode 100644 docs/en/msg_docs/SensorGnssStatus.md diff --git a/docs/assets/flight_controller/radiolink_pix6/radiolink_pix6_hero.png b/docs/assets/flight_controller/radiolink_pix6/radiolink_pix6_hero.png deleted file mode 100644 index 1296d02ed881c3218a1b3f35973916bca49004e2..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1159928 zcmV(jK=!|hP)Px#32;bRa{vGf6951U69E94oEQKA0{~D=R7Lah^S!;j zyu7@+y1Kx?z__@$%gf90@$tL6yS25oxw*N@%E}=jA=cK`zP`Tj@bJ*k(7(UG%*@QU zx3})@?zXnJuCA{0^Ykw-FC!x($;rvh&CNMEIX^!?$jHbbARx}p&pJ9f$H&LBv$H-v zJ}fLO!o$O{v9YqUvOqvU!^6ZkH#e=Vt;NO0#Kgts=H@CYDkLN%@bK~N?d`_K$2K-K zNJvP}&(Nx>sxdJ!!NI|)sj088uRJ_FJ3BiiB_*)1u-x0*>FMdKtgGwm>)P7d;^N}= z_VzV3H69)w*VowD+1cgg*{KsPrz`uh5^v$Od4_(erU z=;-LMu(3l!L*(P+-re1&r>Cr|twcmbudlG(+}r~M1N8Lu&CJgA@#q;D81nP;^YZP< z$H&RY%HPM9_Vw`P(yHLhqLY%6=**bq#*3Jjm-_kh4iOKXoSfU)*RQa!`t|HNIyj`G zqvzJL>CmFJv$a1yK21$c>Ds);#>4aN-^$F$z`(t{y}9JUf9>bnQ&Usl(680f(4e59 zjf{-%=F#%w#_8V0Sy@@x*VNF>%jMtE^4`1e?d7kptU5O`)WDeF*vEr{f%fayh=+#E z$;Vz^UUqeK{3H?OyK#Pfd~k4ZtsOFuPXS4oL>S-mJEkuWaO z&A-w5l6PiM!K8L*FD|U?bNhjQxWTFXS5f}0t^S*vPYTI<;wuXLk zOunw2AA0Y->F$h&It0`?rlEGhXRRBC+WX%5sqPHg#-r2T>)LmJ`%u?iJ%x{{t~!~X z+KztRezo;i>u=phSBJK35voJi*2h~L+N$lUx@~{Zt?RF;)ZpY*MM~h5VS1n7m)v>Fps(o*(Th$(ArK09=9>weVjk-gNR>N?Ku#@0S6>!v!md+?6e9tIPv;Z1sv zjGwr<0ZZOYNP9aBSm0xM?~EUuM}DeJ&x8x6=bMQY>jNGVjC^^%x$*a@@0}S2Jfe45 zZSHsDd?MSMOmMxicQfD@1O5>VKF6T5#%j@?5AIfMy4f48F;=EB@AM>d$%K+-+#AQu z<9Fi2iP2cJ);Mu{bgXFF?CHW>5`rO_Jsda2=QVB33}NELg2aXhaVL(j?+6=0O{RpD`lIXjPDgB63lhl9CjwMrpw>&2!O;A~BOI zHS6RI%WByul8ENB1{a;OVL7zAT*eeZY(^PL4?9@rnvQXrtD;b%$Zq1XQ0!J+#yn@4 zT;=Jg9vA(%U__0%8q*?*V^oWr9TjOl7R4CNtK@WxsK`eV(~q%0JBspnjN|dUD8&5o zLN#olq4BF=a(*zBS!h+=y0wJv4C>7w33?ZLaZkA7AN9yV=X% z8KM1tf8C!L*q;yQ=6t1}H`l`GZm1 z`1O3=y>h>1}=S#U*zrB^)&yve}`?=n3>91cFZ`<;X_V(p%yIyZ;zO3a}ZeL#hwcTz@I@|Tj z8-s5zh`wxpOK_+Q5tQQ9D#KsJv&C-{on9_!_8|6jrXm5U)&gn5lT<>~C36H5E@X*k z|CvsbL=r`kNLXf)J#03oBw;C|l6X8xfaKFBz*L}2+O)!AL)OXMGdUSfNwz zoAV+$gj8#i0EWFo%Lue3h05?mf`kb@DcsoLLJ%UG!QAcO?{{ZH2QZ8$u?ETW2%GwD zNXI1e8Z-n_KgTqK85Rryz=B{%RDX2Pp#FQH)732)3q3q*!HyTMbpqZ=n1z8>0NsH@ zfg-4cn(fEbRnI2KYyWJ2KXR$M-yyAlw>nm0_Q&rZg6AJ1cxz>psk(;WnBaV`kH=$s z{OZ2i+azpfObi}nJ?VDUM^ztb%Xk2(R1e*)t}#;kzM=-;=^!wrLkLw6tOtq%Avh1v z4Y07gSM4p-)Fd-xZwPghybwP?O@TKr0_M(zMi4vQ{MdqEEA;kKy42x5zs4{G)0)9g zyhtNJ4MyHLrUb}PQOY68BRD!4OR2=Cac<&^QaJfupxr&G>}So|3Na_XGtMz&!e1Q2 zCt^c*EQIzHXs*Xzk7H5j^`;M$Y=S&EOF@@_cxX8pfgo;a@J2s#7lXYW#M7Xm)QPy4 zKwBuA+_NWo#gp+p=hL|!v_>E+ewzq3GwT!9l)@A8+Ia#$70Zd>S>T2ePeJ4eUC|K# z7UNXCRGJV`$Ss7;o~14kARL4^so3Iz)&f*O44YGh0BfW=8-=7& zDq}+Mt$VSS2u>r3ahuJUB>_leYgtHH5`%zKXwAfv=fYD#CF_GY_JyFVm6In3d8mj9 zl}HxJlvU$JlSqWw>Y}0xIx2Zc)&EnT;F6Pk?9V4=0c$ZTGEuI7szfM>HTB3@Tj>ih z)0amg{~@HgP!~SJQW#nYW8J>L;-0k^auD*F%m9ows8^5X)!~UM$X=7 zAOl(-7#4~bWJNAH+gCA5fkFO1i5}DdOsH53q38A0I0DoMWkZf0RF!Q2W*srYEI5r~ z5L(EV@)TqWzA4k=3ko-p3pbx%AeD>JOkN?6Fx6By@Aa+U_MLcaI2;aO zbN1S6Gpn@Wp@rsc`_R(!v4W~w)=JRXZmXv!7At7_B%nU>5nXAgX`5HuZCSQuo44RM zs>(9o>U9OQF!EXoy;TlVY0fLJEFa2JByOSVHHXI@+oJ0QjOLyvKu1yOdDnu46(qij zwO(}b7%lfeD{L3;s}DVv^9yU2 zA1gt;h*r-U?lPYXwyWpmoP91Ax;;PBCNK-hjBqD(@h$!@!StC|zA{&3yv|oLWddj- zX|nkfW*+lY!NPKSW=^AwRdWaaCW%2hR$yU@q6nc9bK-%k%->>_B8ox}fdng+IY3Rt zO)SGDd>z(s`#=CY5Ss`h39^$ab{-ThO!$C7JcLv08ui1PGi$D;{Va4_Nd~Qr)4X4@t?d9cV1BJ!kp2bb} z9q?keyZ-cDu+79bDRHeH5c2b_Kf_qIL*f$$6(;HU&OX^EFX$_S&W87_Hy&f&i~?o* zArq<_S@IvwycZd3UCFM_$S*ijuRNmXVj=RH%i67>@0jj{>i)*nuTL<1Cmz>huZ|9;0>+RZX=nynZ93crdbp{0uRDR;z>GMd3r(z~ff7B20M!S6?gTX+ z8^JNqZRu(m9yg-BM$-M|Cd%xBAWZ6YNVex#l_orJi>BOhoQONp2ULN&|jQYHsG59JB~FtvTR?< zyO_$$rOKg%)_3;mu3TL>hj5~_Nj3YyN*WbMrk2q=PRzLb@Gt#85L*&{5mh#Ap-2Bi zjdr(HVh|AKxS*Tirm<_Vv>n399!kS^AD$VAO>y^&qX-|HRRiYOusQ*pv6=Mri#A!R z)Oo*`{)+dw_MS_?!deZ3TI&pV%|_ZMXkI;O!Oy3(MOoFNMj+N^4h478Pcp1;GrGdop6U zoR_&*l~G<^K_zPd+5@nqjQ4+DDb%tEdW$GpmX+uI1hCO{nZwQ^Dp_HG@?jy? zyRe1bE*?~0dMng-$zl$Cmlq_roEM&aH}amL@?1;Ns<@!I#U*-PT|6jC7jN}rbpgF_ zH^OkE)iM&Q)wc44-Q`7otfl#nV)X+G&!2%d3j9rl80Cbz_ol8hxfgB1Nphe0Rcj7{n}yyRVQ_6e6O2N3qp%m$ zEY`U12zZAYREwn&EI`Ue><%QDwWTU8gOI+F=VHZJVol6O_)s>$^v(uJGN|c$DQLgW z1hm?^3wozaRp5RH%EZ1k7=F)c)uK=RSq}Wt17FehC3|~&+dyk5+zZN3_ADZwMN2@4 z&Kk38`LJ5*^Gn~*rp`clqvP-1IR2TgnNSE!vri6RpEfTXv(B*G?97SOC$aJ@1b+r6 zgqZ8tWX);!4t`nS{AK=p7Xm-nu64Pzje_+~UaA7Ts>Ai#s?PFRcCadb6AXMGpmDTf zK0Q?LZ)(z&M%}bQ73#(%HDafA4c%-x28%BP5 z44WkDkP4yWTI6(VC2|K^8R?LW$&DfP2tp}bP@{UPEeBRUfwL-Erz(9UjewclbXVQ^ zZ69*tL=HW(Kxiam3S#8$F54mDu21EUGus#5pTAVvPxMTNTY>E$JnVlx1+~W zeqy@I;77g@-%jsKcvc}?$0E0%+Sn53dwrY{_EXVS0yz!cSdqq`eyRTMOY((bMIy(- zlM2TOrhn(AFC}(jGwfJHin~5Zf_!$t!315^n~!mL1Uzt5AZ9PP_aU50Y*p+P!ov?P zNbp4yKm6{f$8oa-(yD5+>cO3lg-!%TQFf}ratHFoMIZTH96y9p#nGb*)|{!z%<^FH zEIRtrk8WauKCum4G_Z`>&IsnT&^A7b$%692fGgjIjx*tz*KwxuF=HsiC?J-;vl&Vo|E5O_VeQbo!0jv2`=Afe`4RmE z)ejwz?Y0nj26R>sofl@rDmX7M#eIhr0~R3pA1(efUrC%V(ASF7{H=;_`~CjI z{MGqQ{^l$~-SocIn)mj2SGPCmt0dU9WrY=H-BIbTYdL(PDficP?$2=@5`Q(=Be1ET z`c7&Ix}Iv;QaU&?+t9NA&`Njc%zw|qq$_llpNPPOs00>FP*LhQ)gh5dgAa1e~ zlvdq2d(YlJ-(EiZ?-;Itdj5_SfA7E3^<^WRW+uX_JlC6b1G+aVLc@E3d8apadt>yo znek@#{(j;NWWGBU!Lz#G)Ssu*`DV3pY*kr8kEO%nKT0m{?z__k?sO52gnhK9z+7Up z8|&;(ef~d-X0Mw#+J@oJHb%CQtQcepBB2ONwuOQ#q>Q{2mgWRpdOMH{3Yt}lG+$0& zDvD^r32ZUlw5d|ff$e=gZ)Rp^1H69CB*xcs|G-?nKTIC{!@+J`bn)e^*9g~1$P04z z*gR(m)eiSRH+x?stuXlU{mMAI>t~B^ajpb$tPIUg`i|FENz}YL z4|zVEb4w(2h;+0-S;x*7F+;}J!@d>#>$3lmnuKway>5F=JY zs6B-CL4cvIF0rtTg;SBPL~c;cL(5=EjdK*R&SY{F9y9a$p>v(XV1UIo>@IRZ8AJ3mf z{N98xnp=nU+A71()9yDNi`h@8OPS~-SXy0s&>2$7!lPHIt%9+Z_US;_OkaBt(%^_2*hV(w>L@WQ-&bc%mI|O?Y@J+&@iQ?wYO8t3w*C*lk$17f}V= zU4sY~me&n17IaU$X1(Txx8`-fZ`Lqb3&d);`r06TSFh{UPEuInS919E|MNF8;1!a1 z|0-*IM1jdJ6!_q0wLgb$W#4l)I zXe+|b^)k4f>kB{)l^eqou^MCvDEI<%bmb}|5NMl z{(X27c<)?{{4de3AS@PRLEHSul@MYlaakjJ!>>{KYs@u&DX}(4gcP<9aIkO%69OeX zG@LZi8;#4ro{;i_TiYNclCr_u)NJBZEvax4Gs}Oe4sK|9cs1j>(49B7kQX&$nxU{H zS$_$d+^I;a^!df}p!X=HaI$3NjF5O~}$3^YjW;D}5xR!K2>#kiD z=b7n`| z?P^%A_}^n!FU@>DEdP4`hP(Vt*afCpgtczkxTuX)Kl(pSGQkq_1KQPh3>5NIDe z7UD2l2rQx=b^P+z0eAXRBeeB&b-C80(cSa1KK#HbN9BGX%)#!nfx7#JRelios-q6a zQ?E2vEYD0b-vI8Em^F0rb(pkBzh@U9cw3wwY0V^P{3MsJX#IT zl-WQNV;H}Hy3aZVbvAM0VhLzof~fh>Qs*AW<3-0N?JNI zTc3{v^N7I5+0K^cgw}<0{_~K;#^>OZCk>l?ik)el>*FkaNns-bavm1emz8ZFb(&5X zSYBkxH_`$0J)~j@Z}lL@hbElLb!=~nSkOfzqdEhNs6K&cq#Zc77g%mAq)GUW$l-)F zIy+{y<0P@IgfKNPk2)5*S29rq*NrGOt(-#r9!&b50Gi^Lz|FCq(es8RMoo`YsIY{! zs=t{QHYXczSqhXQmEKE)t?c)r>DZ^Z+di&!){j6l^(KO~(22}V)830(5z|Z1z8*rg z=Y>RkCj2EPCagWBmi$H&(HNW;3B$8d!>WjyJto-OZ=u#Pi>J zmeSUA`hxXr`qpvTG%(F9ZRMI+53}jZ3;3NsX!+B8`V*^KzwdvGvoCb4?&k9~*7E#r zItRb^;<6q|4pYe@+qLv}ipUj-QO0ok{ti=ryZ;5@Ez+pk>zePe zmh_>*h6bhNIE>jIle1MDDO6cQ)6K`Xz!F~UX@DE}Hnwx$pzWchNCIw3*2%(b9tH#X z;)wFqonfGxVma}3(9LmSwjZ~4W?5=M{#i-P-efk9dvsp}R_6?eqQF3+@9mV{dU3o8}q z7<{^Ajjj`%BnvOgT$<2tz&*#b$q1}eZ;gd-}$N^GRUlA*Q}<>ms>5*dRlQJIr_o1paV#5M{yby; zG%U2tgdjK1EqF=3vfg|V5d|lPO~Eh5C|U%r(C}5rimcBZ8r#D>u$omEyAq?hx@Kgf zjDxQ#vt_wqkei(>^nK>ZS8(LxS%*f^#E6dchGUWW$`POs2J?~wI{*NK{|Jm*A=7GH zw3>;Cbt>O=F`XQy!-WCuQxXvxZ)QcKm}xhAyc?sTn+V`9;#4;i(UO!o3Nmq3SPOa+ z&)k4gO3R2_-`ZZIWywL5LVPfXfjioJ2+4-~kpn$sH5$0@T}K*{reTyN-VJJE7W1D~ zv#3}>am#|=rJ>0J9=nf&*U*JY{7HH6Q*Njr<0PU_AFg0 zf{WR{Azm!?G$g+zf3_m<=Cqf%9Z%@sa>}PxG z(GtF|A}YAv%=W_ZeohlwtHj{x3$^Ik>#MN4fv>aG{c0t(DmwFM_Bwl7S=V{>9}VZP zn>d?C;lW^J8wmw0Qv?a2SPE8@q>4m@C@kd$DE)0^MB##FM3H8515;6qCfvYRq}w)C zs{QV3&vV|aMl%EWPe=%U-gAEEFuV~lht59_M~LEAiQV;d`ZoVF$DF>Jzv^^iE0(ob zI)s@EjOEw)8n*r+Ty-@f4lUYi>wLOi&qeX&e{^d)T;$_f>dy9NVvR!N@bZDiyGC^K>cBEkne}yo_~4r1jy5 zO^)EzKe1=T$Y2L@e0fH@#$Z#F?V2txw}tNHopg001f{Ew^s~e76fGK9P<`r>zv#A8Gl(sXI^~I ztXU@}5-pk@YZPxMA)=%w>=M=1Llmg06I&4K$8G(&tv(!Q*4n}e zXNg?YaH=oTwQXhn+HMJ@`OK;HFtc%j-z;Q4sT%3$$WON`>tpMmB~2y~a@BCSlVAEj zF1?cBPFsnLl~n6z-C;ljRdILKcCB84w$l=-X-UR0HDI71h7z<(Lz)_iEy27pYg3X= zX-lS=%siDSehpd}+c5&hU1pZS)WQSU*2rXzi-V1}Wgn)n+96H7e2i1`8N}L)Ni*7V z@Q{@tN1MFv%N4=j$@36~F6iK;R?EV0n9JlLiWU5$@3xYS>)e4VOW6S70=>(YBKH`F zV=;^`*>|onrWKen{~;}{^=U%OAPa={J5&#WY~=44-^%Y(vRL5Tdx5vy9&#M&4@t1T zU?xO1=}cf9mwA%Qp$SuAz1yRJ{yr0G3t^gypfn4ZCQHTqmx*%1M)JtXxbKLQ^s;?z zFpDZC=oLKdh+;-0Ws9+mqnp{$wYwcf-!ZXJHX1Xv-LY;k?N}cON%r-6<37XS{)CGh zXB7tdLIkQXld*6w2Z`6icM!{dwl9Z~1J6>n$lD3NvQD4q=pCV`!=!hy3GJv9DPsX} zfMFeB`}UaV>f7F%p$9EB2z2kF%i%H}^vBLg4JMxS;vVmq8P7%qN7sbOtHlXhPWPVM7EO z7QZ8R2mieze07WD-3JZ4*+1?FcZ0ikJ$!cunMK}-bnkwDC!{{!Jy1+~gv$HV#!xTvFE{$$YIc`?I_?UT1byilE1%cCp}!>5|c(QFRq{77CLtEwpi@RT}d84 zEk?tUB<+X_(qc6FeKXSL>D$d{`tKncc=U8V)IQo}`W<^7j)rfq63L8%)iauPIA4z5rqqZ;SYS+8YdR;WB{~j6-RO0BHC$`Y;c_@%OF_?v0<9!2IjgJT zHSY6r4R7b`tMw}>=fCDxuWKE*y!uGw zZ4lBDeZN7pG|iF_nEVQ13`V+a`d(GjN7R8KZ1rUuEe=JAn8C3Y@kNM*q`qgL8RxAZ z`imHG6+X7N2%DL%i*3w2?0T?Mxscf+gIR z;xZX4A*$7l4j6rOh|TSB>o)GJaLg77nw?@s@A6x%yq@dGJ-6*y*Ek2GCyWP1i zk8PL{&(gY`RaVDZtCYERYzuI_YDI9ZZ-{V_N~??XC|O!{Rqzg&2Nyx)u2R1w&YhQS z+UZq0>yR*xKo$SRJ%E=<)Vjs&0u;1{&PhMiaard(CmkV!4Y@dR zorf@1a09d^XG^khUfqE1n7 zGp4l^!9OuR`bVb%pglb2UUV7jc}-{zp^y`IcE^IUtHFB_@^WzLX>v#S>7it?uJ^a^@3$M_mBJB0EXL6L$>Zjo=(FxJ{oMd(_HyBO{B-;9 zBvpKSbN9%7N#R?@zK=JL`-dl~UYNWPYab<;7os*g_xIb|;{pTv@s0k`A4}oi4>uH# z+(UW*wN64i7d;w1++6FAAAAys7e?##jdb$@gLx!*>{OQaVPGtIJ46qM1QzWjF?skp z8oBqoM((qd!%Xz3E{kfjcUH27Voyr={M^IQIR)k(k&C*`t5faZsMDp;@RAAQQ zY+a6A2X?yZYPnu7|GE;EDgCcO;(bADKP{??@~g^5~s+ef8wsFawYx8+g7XZ?3EzZZ3`fr z3UTe055E9^tF2BpBO_hvKGmcdt={_doo0RxC8T>2&p+?EAw5hbc`(C*g(ZfCI7nD#%;AdzRZX~YgK@^?S;VB8L$;&VC`K0qPe7Jp%uajBGW=9 zuFdzSb;aqZ2dNnG?dV%MqT_|pu5R^=x4(iaM(oy5SqeBMgJpM~_V3vNEJv*{@j+}? z7N7nE6Ea!4SEcn?Kkt3*2 zK5^lGuw*O7vhdzidF~foo3u!4^Y2gBXev)}OAuNX%^B8)1bx%Q=hPn#Lt@_cG463G ztaglaJ?<^@kj2--&f}B4%JbHPV?1Gh{Dv2i!hHj7n=E`D29S>(+45@CYg4M~t{G9K zZ){MDR%md23EmfaYT3a?Qev@cL)-C15{p^s{%_=fG<4Rxvxvh-Y+z!;{jcCcGwe+` zF2eTK+Yt)KiR=6RppV>q4Z$hrJtBY3jt9=L3@7>$c#AEJZEc)qIjrr+mqWkDA{*x{ z3oHc6ks~F@UxSxZ*~*O${hf8PJ4c9XKK8;pCUh@$x&VDi?`B_G?ng$ukjzxfHyv&k zLdQB_7X|i9B-7Ik=gX3T#A)L2)B&36a;0sD0P~1pG6HiPGSak=bgpbXPWr+pyG;6F znoMcs_>U2hTM-OeJK8x7 zc(xKpe9@#C41=a*h=h$u-bmk-T7(^%T8#>WVp6;JLXSQ2FreM~Qz4$z5}NL9@Nx{v z9Ub&(VBB^^hv0izX=uTpb0`RcV@&*JE(!*iZK^S99~=n z;+M9Nel2ZJ%~6v0Q=bc=!7WKUQr_O~-=t(fGIU`8Tm7 zk>0VG?vrTp0MC_}E(75?_GWbJ#XuN5*L~u`JrYL^0Gbr=Xfz(_j|lJkOqUBFbTPWa z?qbnv(5vy@6P(t68K_6Sh0t_H4@ZOf?_zNl^VR;qDk)%5U+Omo4FRXnwAVNbct^S> zG!~}zuv<0GJ*4S(p>e$d5D)e5JivYR_%Or^{rF4{c!(YPq28~1uuBk0+u6qLzSF`? zf<AC><9{@P%Bn}}(#@g721iT$N+Z#Wx(tLvR#O8d7!+cXqTy=@3^%o zs}Rc+HVbz3%h86-rNi&hjbrV&5Wl^E!kysY5^~+LJQueva9$mpC*$gbfh{?)-1S=e z6tz&>rrY+$D<>NT@aYi($B-A>siid=ogCP;yh5`LAWt{8bva26!0TIvh~f!Hut(<` zJEs8FOFIkG5$p-na&*GFP_L>*XNqwlOgik-H^Od1I0??}g(cs~#F%S++f(7TaWwXD z*p6ruU-)kr5vOL&5M5DV;c{w0TpMeU=aeZ=8oD`bkBqD)>zJ`HopzEqn6TU_6^A@8 z>{$mh5hfeJUPcS@iB9G#qL}&6Gmoc`W1zQFw*wgigYtG zWsQPn*A%3$|77NyB!(F(Uz0tB8+z$>NE0X2Yv89ACq}Ji%J#iZzB#Wo?XC_&_I|x5 zpyY0@%GKQnW*+d_s!OV>33K6=BSbZRl!_s@)~qI>1&intBVj$J5(znZ5U;J5!F^mI z_S6)pLwcLv&|-c^WSU&l0gWX+RKr=tq#4U}jgT<;U)r`%kC)COU7M|l$?l%_L|lo9 za}C@@Gl%{%Uv3dpsBygAcoy~Rv-vxtU8nNaBk>TD9VR|+m z{aU;uNspfv^TDT^H-OvOU@#jHV`_*uFBb1kBn?K|Zvn5x^Q`}7y~Vs?KNc+c{jnid zto=q#0r!XrGZpUD-~SyD1g_JRH8}U&e$}h%4k&T`Q84{Dc>K3-YxHCN{N9J_LVxST zgoWcnd$XP&`(X4VVIn5LBCLTGQ@_zijHVFFxQo}SfhP+dOmhd5-TE_A;l5|S!{;;Q z8z|5BJ`Qa=y9jIeJp3!u5$6yvQ8*?XE{4zIlI z_O^pN)7jw2r!Iz9S?)1!&TuTc_wn6ZvqT%R_+HDQ^OwiTdJ-f`oh`MI_B{JkQ%-gO z>$c;Q?;(^13cIngYRfH{x8SmANG-X3A$9FiF#R}Wgy`8xi;bs|mwbD`JOo$6ER=6P z@~u-f+fIH$WG4Cw{oAILM1j<|V^D2z{T`^FIKUB0h@=s#WGA5~eOWM2yvtp(LiAI? zZ@Vwk^5ymI6$94W>7{)An<^}X=dSZdC3D}Y9&8W}yT3Y+B>X)w2kw4|BQw!`Ev-v; zv0)WQ0rjL?+W0JBrM$BE(%bKzPN!)%r+wr0v2sDjkxL3F{lia=hs)`e+)@hoGAGv7 zTOj%ebaooC!q7HHR@a4A9pbU##~b^!DD7Asv|b@0TzF{S7M*p=RcDK>t(Y8yf^0aX zc5rQ}A=3tGPgp%2Qo(ZS&xxR~IPt9$-$3b5YG&Bw15VpF^1qXGv-Lcgc|s16_H-A~ zV{4Il5^Q*UlhCD&wIR1gc3fX4OW5(o-|Dx$>}mU=Mnk8+UnX~5I)@5DVLbekWI#*obtjvt{_V$3SxG%kwH7Y!;C4;a; z8^hzB?5)OtBc830N6wsX!mlj6Hz+&wRH-^3?5TE0`?}8x%MxW;(Y|`E8LKT^M~P^n zc1LV(tp!vJb`#pQnw;e*(Q01r-5)L0Nz_5@} zXiR5D_5S+k*-fZ))3IM@Y|8~%%ZgLOtxv%$TPkj_T(|r*nc}0=OlwPszH=A|2b4&>pnrZNO z96Bk5wWEdeN28}6Rg@T_5tkPvfydNdjYhu&sSJqmM-OH_=Efs>DaCgefbc*R*kj$1 zAavBY!!3E>LGSA@1dKKCAlzz_6g4I#d8X53diW=L$w>7$4G(9M!(i169CE5<9h{U5Vm z*KrIHsLy?yqaPm5eNTj+|9P-W`ma!#di9!kAKcH5<|mbVI037q1?j2>wg|`s2eRbK zL0^qSFP`H>;T(WAX5UuZA&1yicmmjs%PQ%R=B%@cCT%wrIHJTE1t(R9tYW^gshXCJ zNuF6dBm=^kFwd}IwK;X?VGf7q#`8PhbQyHpCDCZxlTD|Hw^fC&#kbl&j0O)I%M= zo%|@#M_nzaE_hs(A0fMYIu=61>D$Zn?X~;%@;3;po28K!h%JFuK`PFG)$<>QBd z`}L$J7e6k)^cXy(Ma)79h5FfudQ)P0eT9PuTy z&-vR*b|{sB`vy(9t*>YnX1wikqsrM0LyfOMSymtaP zciLC#-;kuSS6CCrdKlKTv|2IQ3GFrshl_c&mb@J>J#yVNOWq`yBSGlucbtX6v5`3# zu(3#se6wMbxuz;)j}m$^#2Eby$xjV*X8z~u$-thotm(yf=2>e@ZkPZPHZT`^2s&=P0mUWg*}jagq_FemC_P#N_{II)B~7*)@nS7$XA`3RtEHQiQMsC<3ZT ziC79txdBR_4n*OC<|sv)lN(4y5fN@+i*#R`YO9m`I`f;?XSGWBV;hoS&pXdEGtb{9 zi2@jpq99(T7>D0C4FY6b!@?^B)#Ph=P2d<1thw$D1F7NN5~kZUBjwPpI5)_>pb8E^ zp<=cII_Y1D+4XvWj&wrkq>iwo@LQ)ugRlvbYrQK0FG}PMMdav8BlWnWY~Al$_SLxV zoZDeSO4dgcw@-tLb*pK{8i=W|_39=x4dKx z8Z-|Lq|^hVF#A`k&5qLg6j6mo(+n1Nn*E9l>p-oI!>K>@t{q1C+1mV2exCLF2a436 zn~mr%=zE-94|WZ2ptY7^@vJB>CFuJN;M!WPEq~tJ6GkZ*=Id(KIy~r`aCd{!YJGTE zuWpzsD!RsM{s_~!8 z4gTRa5m;@(H(INIA;NM{^aRng`7ab1q!uM^kAEfBDbfMfxupeW7uS8<=d`EMl32P( z>UyvxM2_dNTqAXnI0WTIuB3&$=hP8>l%Tbs58zDeEcUjkwbRbw;fiMO24ysxlVV*J zZ4gfFpUkZ;)g`lJlS~&q@mXE0_BID+Tv;8`3lygzks*yq)F29Lk%zz|Yig^#Ai#4N zV7j_Q@5#g}_i){Pire=rIu$yYi+p>wGnM?|4oMXBLjwz*Z$o&6J*qTW3x5~H5j?T2 zMrYc?FI0j-yV0I(E8A|XXFVjiHjVxA_=Tq>rlY5ki12US|4r4|snE;qNPPE+`&$v% zlNc^mCFAi60apcV_!-TXBPmbC3-DWPX*H9crMDzXOdz!&|Ab`BO6R$!E{t9%H!p&b zSsZx2FTUoX&8wpeK#To;OL@8I1P9g}lDsJN8~d*4it~8>1r;qsd8>+F33lPLEA!g_ zl-1$RkY+807L`NEaso9*6=i-3{hh2@Xl~N9VC_4jO_H?IrIt?jDylEuEF!#wR1SN zu|Fs=qB_YkwUxn6|G2jETS?Weqc?)XuvwF4*3o9rX%qr9F%dQ#DGhjgv(VZV-;2qF zw}zQaNJ?h<22v*oubA9`J6QW!AqAm5TK^2IO^$?G0iAS*A<A3b9Q>f-;$>;wUXPfCLK0xu z27uL}2ZT3AWLOcTb!`y3fvyXuuwx?|$AJyV&awhU6URdil4~nz{n)5`j5dy}a&pE| zz`8@14C!rJGsR=Ljjo8c;MH#W_J1~wfbug0&CO4gS@tab7|79rQKuf*aYU%r!Mf-M z^01BPGhl5(mZc>E8Zb;rjZdNTq0uMis+MSNHlN20Y0$WkM0=@6Q-xmZ-Y0Uad(&GY zp{X^uR%CRDw7R6cW)j2d9z)V*bm$}w8ov`E@c4p28XgN52AFT!j~A5CqQp0siJpCY70zN@dPFHr4|wwDk9hH) zi=#O7?-vm<$#oa(2Mu>lLS9TtH7fSmu&XRMho*$%A-WLhZ`(#ZV*c8=zK5QQ`a54W$tSs8CV!IGTWDg zwYqAj4)*WhNa~(*3YMLHo>plk?om3{A-6UNsTR&(b6!VcVHut~JTVsDBFduLIyx+<*V_Y?5^yKw(^`Tl|d$@7pF^ombU+m~XweSf9`?VFUf1+f3tYcH4c(P@M=iHE*M z4*38q#g&D`dz*%zmxMeoEs{nJZC*>48dWxhLW$2bp(lto!bKI8q>PfGK+pb%^xTrs#|>jM3Pu}BP%LZ`*pi`>d(6jy>-t!q-E z$x)U74$6uYD`Z(h<4%!xE27M@Fu|ci0v0{uu9sm|R z8X`Ju3DWyDL8jCss_Q{1U8hA`f8_>{b-+eH$1}%uDH;V=Gmz@qDulwSVb&VsMoMrS zb$5=U%m~?V`ODp4+EY=Onvi1AjjmDYqYNxu27$)u97g^QMfIP~PxZWx`I-xljg`(Y&7x9DzG**sPxUnAgA#`akn9hEJP;4=pRM*i5&?aX;6G!C=-BqPF<5W+Rbh&q|`%d%roX zTWbtPvjg^{_2yIj79sVToM;evhVSdj-Ai|9J9|5SoZd{ePPXiP1dYtuAdN zwLtq;kKgsgOO3ug)Xp@0DJZvl?TbMAa%sN}>CX;_Q#!-2T+*<5uL9?>!>mZSg3+SP z8n!`I1k{u9X~KiO_bx3*)MMAijAc95r+id4CU0>69~(Ws4hmP z1>N4CPmRbgEeN7Q1goXz@M=l(vfy;RLb(35&hIkq)Ixx5Ki8 z*AA)xlD6L=0Xh%mXSB++Wlvv>OxWhnqQ@f-MSv3**p7i!`u~p@aaUc$?qWJzIL@fwkp1U{9c!-k& zpAkYC(dR|x#18$##k&wm)vqf1E(qChEJ7zAC39yxh zR$8UbgNw_k8xlC&+KsJ&$gH{w2pfkij@lIvVfwXq0PxmHR^ksd2@WF)X#!JvW^R*H zZ=6*X|Lq37lTS@on4rlHz(Qlu)Y+KD^<=|v*8Z3oJEDX0myu{Y$5$OgV>qtIDa2kY z#P?QYy88S-p3Yx4adnI0*ZwdvMzR143L~K?mSPJHR7i}t6i9giN~Qx*P|!pasqzA; zC`J=rV2bHZn<~|v_qzMHHus+5WC9M8On~*Rz1JW8MT*r@V-m9Dqt`CPo>vP_Cj|4v zGB@Rk4g&~H`iTf~*fRO`i8jXK)RVUq4q}f&99GtfC6&%oHx@_1jgbhSx1l9#MxIC_ zCYVgAUck0tgj77-pb2+}5pC)P@egeQ`~Xh(Q^(L;IxWrsfT%t64bO3WWYf!bxR0dT z2ny@t)`~w9ei1-vFnOCx&SaN`_%Ea8{w>dq3=^A`5;_U8izDZ)%%xVie$h$y{VqdQ z3`cP8{G+AB>eNVV-rpjuB9Tig-n^x8bF7@KqqAPJHrV;f`>U<68XmOo1!`lgPR4W% zdq3>*Cm%#>i_Aut2X-K)n()8?njkDBTB}Ijqt=sV&tz53R;~H8Ww84+Lz89D`(z)c zv>qL1KM%8y#p-E}LW?Q&3^A8oF?%eh0Puq9L6p*Sl^y}hhsVWqu4Y0NBdI89)-?vK zA#}G(1p|UBvas+5KX%L6WKqfhY&5$&D}R;-&UU3|Li=hM97c^b=)#GyB|YFfVk^r6 zxn$HlXqT^)FpS$vSgu$y``mGNJSoRSSt;`Qp%u*yUwF~_#Bk+)7Ua2T~tSkrf7tO zqd)6&qk*ph;vUr%x7)|_c|CgHoGuK8344AX{TnmV_vh#DSdum*Z;S-dFNmQH#+B9~ zFYvd``{-q)!L?mLA7TAoT~yAn-n`c;Wx(zN^9U?kd7Bkn_6Tt=Ntty8yHn;eKcVw306tC0kPU?Eq9)YuXj}i`g z{OvnbzzUFt;O-5+?0BYXBS2pALA3{F95B_bFx2yZn4yGDd~XXoPOim0+F5BIK^sMQ^;P6OGSQY~`5i40ck z`ita$F_VtSScwWf1Qx=y6YF$r@ExlSm|%|VOMxAk+mjppTLi%=}wjlGpnGu^$6?SPl%S%oPTMkvzSDP-pOzxaMup#QI335kqBn2dkJcNNpUEZpC6a z2SYK|>PR3tmUg@MBkw2hF*GG70#` ziBUx(vHsG~`bh4^EzOT;skbC&9LL}E*Pj9lDI zJuuEBk|Aj_vTJU19<@>mAzB}~ngZDjdxavlU!p{)fJj&N&qYZCeNqa?-2PA7!i;<8lPR4@i^G(KFmfwE zbpZq~CiDNyXd6`W^CQ|Ud65u8PrCDR@;0A5zLhwPelm+Tirlu_240^84jVSBsG;o2 z1`I>S9X#%qZ^n-eH_OGC5XuRl+x>@BW+1gB`07Em3*hmXkdJ@Je>T`OR^08`U9Ye7 zEcA>TV+6K`dX-n0dZfX4+5QFawvGM{s90G3kZ;&NS*p5_&+Pgoh9o{1HSWQbdnm6I zhqdhe=urnOHP*lES-6eRG^$`E)nMd4mO^o;Y*>QpI8dh^PASKqHb^PFG>L}6i-8rY zAyicytu!IwK2Xbc!L#b|aG-rr!8onyO5ad&mB&p|-DVec?!kapbr6z2)Y1E+t7txp zX16=p{nyjIYY;B9V~otmaf4I`ROW4bk0!S|QIkXn1ZcwYvXktMT#=K6KugeD4L1Na z@k|E0^&V?0;m7QI4WeOm>+@!h6RA1Fi$|K>65v=@`+9?!7Hk?B>Q-yD5i#pkXVKYf zfxj7p{X^KsGh^r%`$!BH^}UA1)Gu(+_tDFX#L!5vRL0;P!XsK4m`D>$`C{M7MJ2%_ z^0(ISHLhYXSxtmSb@#Acbsfosv;jkj)X?hpeRM$<&GF&1mc5GqMr3>3g;=B0MVXZB zlos+kZ?!*R2<~j)$k>hQ&XAQk zS61kwVZ90wMHtO5#!dn%XqG^(+FuLWjqrQ3wr!GAK|EQ3ue+!V8GQLto&|+u@H(G$ zb`W57SR%zTtj!WJVIaDxbn=rOxM*B-P-$$PNR8!bY>A2(kWXDT4p%6-1c1tT_H<}j z>v%?!qE$EvFWkb!%sFGxa^J-$z%^5wm)Zn{-EmPU3$i1%m5!tK+8g>jS(zHz=5W1t z{@NE5UqQtv5ih+UmYoDQJAsED8T;iW4w*Nu@CY&6;?(WPaBghD!DU>rY(lg#FzvF3 zx~29BujwfB2&|wk!Awb%is?}8f{UTk%qQTgT=4m?yuNBE4B;4*484v2GQGZ+9id9j zRJ_33jv_!rrf*(~6a}v#ROXjl#*r~y;dSsKG@d6{N@oEsiWdq&GGCWt9LA*-J{V3L zyk$ot#Z>%8nJOUEU_@oH$_-svMV=LIVWYG5eSJ`d0Ivm&3B4c~D-w1xG$u+q`m2J& zG+!Ae+wCo;-dX;)#p4-uCI&OdTFf39*re|_;44znGsQ+6I3VOJQQiEg{w3zx{n%r& zR_M7%+fwPUQQKn#SSm@YuaGQJV+7EeYYUe1mFkZ`R}Yy+|19y=>duqU792FG16 zeV)xrWLL&v89-0j_s%AE*zPn(<`v}dI6^Vw1l0Lz=(x|W; zNw|mXk~d{i8j{l3(EX?VCQ~rxq_Qo)5hG{fC`*?~kC9|e+Ji?L6}k`I!MOZ29<&$e znqNt}VkK2H&lEC#M)OGQ?@%^mk+-O?Oso7Un#A|%U3D07(64x z64VZa!>=f&)xxj@lzYE_XaubQR$f98&q+ni$V{L5U`V!LDJ|p-yh(ADsnMm7I78}4 zZw}A0uO#s#NdjgQ1$J=t;xy`YA5a@lLnm>ZLWR zkGt2&T^TlOddMgnev{ZcDfJ7(Ajz|mtyBq|Pz0baV&aT3cyDjgpFOVwGpN(C=LvlrBn>EAd8t^qbzL6%28V0min~{CR9wXD`ox3-ke%*6_(ug(NZ|hWm@B-4tn~q2Y-7)M(U1hgjJB{HES}G-`&@jlsjgk$db`nI{ z_upjp8#hM!iC?(d?{@ml8`!Gnl4MC@S`vj&+A~tdB&naTgk6Hc$hKThuQovvo|O{Q z$y{wU9EKCeK^G5ZN^UbmcLm{4r3WOXCc8=_Y!);rt|YmWG1Dz8UW% zldqqbYo57X!K;E3gW4~mB@1;j7@%Q$VBkzPb9SRMfqgTsM2B1Sn7rzfn1Wxer(*X9 zQ8dKLIWClDs~jxIYT;@r;5E1qI~;XV$XVrX)x!oQHd6Xumd;%_bu@~?gD=Q75(-#Q z5DB4JiY)|GNQpQUmhu9WltvUTXpSgoCNFR*iYO;9Fh#m)Q>B{oUbDZokxpj9CFBb0 zUwf|$#SWpuvY^QJwH%El48k31tzdx)JVsrm!$p5U=aFyYG`6v+skcTA-N za98lk1US%M*53jKyjst?zp3+k_c0)KngXNWdaw_bCIpc}tpbHc8neYWJV*e}j}1jyDv|>fKCB)l6FBh_)P9(}J}lJ$Oq;^8E4thz-D+Z#*h5#~Rtx5L@ zRTYg4kY6o<@70quyxgKF?ehB_^XRV12t{FyCHI&*583uU$=FL*FmW4()#PoEOi2jk z?5U@v@9ge@QS>OK|XRdpvPYDrU{^$ zRmGeYceF1u$SulLH-3V)rMrRCFJ_l*1HEY34yQ$#w-w#9#$~l&Z0yzfmbZbrihvGS z?)%WXCV1@!!RQIwT{ytaxSn^&ztdbSTsrpjHspSkWDyJmi`BBZ06O^+_ed z_t-)=@S6h^r&sY@@%Hfq)Ilr@3(HzK`QA;ZVE0^?H@NM)r1iKBA zL1n0HqvXrlJ|?V`j@97%byskUx+@jdW(MG+plb3=F5!{qX}Ho^x+=_X@L%;Dx&8ns zVeW2Wx#M|A_1%l} z0>BQein-J|IQKKKl5ujfJYseAs@PN69J%hZ54}7%QHO$rSsGA>p1tKu*lgs9S#ju} z6P;6#h$9=i9~0@GzHf%4P*41rfR5OORz^m}!QHK^9$Xa{hJ!>ZXY9KlPM$RjrXdM3 zYS0&TJO>vw6SYNBYZ-suA=>I^D6NRLNCq9Kf?;EZhti1w@*}-eaRAU z9bFb}pDzk_gk@yTv#AnH2+->PA&!HEFf5nqB!}A`6{Wd+;Fg?%>}al3nqUn2>fIgX$ft-UIy(Q4~C~A{PHeVf7d&Eo-A-EQ8ni zV}S9OGs6Ll?r#oJv>GU+axPKTYOq1$JdZ?=4YpU&96WwR?Yt2luO2ss!SnyX)&nbH zIf36EH&9?k%BwdLuBZUUP(+2{8v$8s3XvXG#&V7IqJLhiv+#9oP&~0a8pgi8KPYMg zf;*umNxXORfD+nZ`E~N|)Tr+La5^*Yt2OV#aC(6ZgSHCTAlwSKut6-k=?k?Buv~z) zcRxi8J;fz#{MJ6=RhiH|!%9Hd{y%)`-3_0H?>Ky^V4zw-ZG}(7U)|sT^Tb}5x%8}y zewtuP2=L{}D6sKet$b%ppNA50b%ABB^?n8e=D&_a!r0TO?-qa?1l!4T5O)$4cP2jm zqJ3P}K)rnE*&Vvs-^)vH21PnqT<2`h;E}W($w(Ok1HaDdSEd=tEdV)h3wk84sT~sz+c&TxCjE`?!h(G!)PbUYfMbWLkrq z7PM%!O087(Y2(utBCzZawb}cW`3jJ;KGtkTIa(vFYZXz=+}ThcJ2CrPo*q{eS#g$L z!F3@h!iPPyI#zd5h-xcT&ZP8+s?}yJLN&M z=vB6~I*z2OCa{OV=pZ@jSugi)-l02D0aj`sWZs>~*qc!#-jP_kuLnt#@H`;2GV>}3 zmt)AMp@}`hFCYXgpzroUPdlc}xkINTr z)=}A#0U&>rt>^nlJQla_lz-9b?@(uT`k}WJl6+-c`cGfMkhg0MQWJOjCTcj6B3XVZ zMPT$l3@Sr|;lm$nMT&|Z5N}C_v>_#xz=TBZRH{S}%PmnlMt5)`9J>!StrXUKgCjg``FXyhw)unUjwP z-u=A-*yk*UR|kXNNFmX;9q<8@lGg;|@HISM636i$xme3(v<9J#*3Oj|jX)agT`u25 zc30E+(u*3F>-9v=BQ#hF#L{Ya-Frp*Y@q!%eYK0zS28&!ggkdOSw`^OBNm#%L1V^* zUy++NVVrEdcnEpDT)N|2F`$^qDiBE+b)C~?#F3^2b{wlSykFnR5XC79vGRG^(U(o0j&pwuik zgrKRa0Cb`^2qesXeb+L8^aMku-o8o%Ivc}+v@Y6qi}jawc`^{ycV{4as&Uj*M)``A zi0PUUYDHj#T|Z_MS`h3AD?URKTUv3;U(Z|h_qBB97DQFiFLW-8Mco=~<3_5KB3a_u z)s&gk$(O~CGYq#LKSPAaKNlonmGw`eo)L@gm`z_#2s*2&;@8t5GQDATdJaTktb- zE2+5TyY(U#dw+Dxw#+lYD8awaIsf_oK)gv&sbgBlChMla+q((rmI*LcF0vBCcB~BI zOrR;c**Kr=KcbXs5@o}4fmuLmf6!L9@>PX8=4xiUcX%8M7z!%kB#~Q2x#CiRdYZ7lNtVbBIK9oGTm{>hL zwRCws$r{P1;d)mpJsEs&!(lbl_~JzX?f80(G%Oj7@^T)IjiVKPoCzp z_u;$My8js}EqFdu{sKN}vVZ3kyK~07yrkb+&ig`ABDesb83oJpe1*l)5{u)C9wW@i zaKCF>+Z~$z0-~ho?P@<*qhL;Vot;>ZVLZPI)@Snxmu%dZH zncIXr`EvPA=eXa(H+>ng&7`bCXdGnz3dF&j*Vl{&3SZDFa95(s?(YlW4tv)A8hle1 z$Wu!&0oLn-_GZ%?suF^OsLwdx!fD0x=s64;=|piId{#(Bb1|=?+KUrAf247JwOafWa}9c-7nT(|?Qr|cc&kOJeHBv`<%yyadm9}7Vbe9cp1-i)N1 zm{39A31((Ujcl5l-%M<^=4qF1bVI#pQhJKyICU&J&yJguMi%&@s!gTsd{E$cgQLe&%L^D5uVG$LG`r>ppmE8~!Y$|N8 zd$#KKv*(rYN#3hxU;G8PaaODO{JJqUH(6e*{FbBIQyNfd>TPwQHxN5E+z43Jdpnnk zOxlzUa&5){03ZNKL_t(N&rM=S_q4vT>Pr;T$-aa2^k&+8KHWB^(LMRR?K`ej_*1LD zEMkpil?KKk`6ZDMO67i27N4oCSX%TNr|_kZDxQfW1V*Xa*Ix6WKdcbL^*+<)Z@Js0 zw;ema<9HuaR_8|(U!3dA75IT1>0iXC`mxNF`FCUq_;C|?!|sh}y4p_*?WA-rtXSTs z?zAd1;{oj`-EuX)_)8xHMnnwKSim?$L_J6rf3Mn#vpm!_d~g zV$vQ8B%Nmyg_GFtd$KG1*E?31TG4|-bU1HAXlI`tM;@J&iZkcTjmY0jqGYJ;9A!t0 z(_gB*MV^c5p7U4g?>9N06?G(bhnQPvpQ4n6iSlNXGt)Z19yet z#1abtAbjM*Tr49AZC^HjR0VT>ZsHM8^|P&r4swaNOwF3^B92yIQ}W(JS)o-)S71BB zD#9%le8uQ;Tw!n4`mRYjq8@>ztRitW5{9u^)o^A;pg7`8BxzqRW>sk$XjykFmX@4S zGGzhgKvLN;s^fl9R`H}w3L`vL)Q)T!u^8NuYZ}dKSf$$uV0wK;zCTo3oPl;6U}UYT zPzGzo9kSR&pdqqok5^U#-`jtSLRra~C5m(Vj;%TL079i0nvkl>W$jq0!R-&qRhgdK zLPayhRn#!G@kd9jt;USSVOY<2ws418aU5W5W*cc0-tAoU$1y#xph&kT?G;TNvKEBpP@lRvyh5MsU$kKKSCiDEX7@U1dfVCmv2xfXchqhDWomh8bqQto zF5zumn%CB#`7#=en)UIc%Z1wa(z4@))fkv^wuHCB*38V;gtp0Kw+n+~G*WYV^wJ#s z7iShVFc9cw>&2vapcFzojjtt*zJFT@#+q!m!m}#p+Cxe*1$c!Hk<*w*Y@ArDgwBPw zcW@@Sq%c@ubR5}Hm#@r-Romu&0)um3Nung7&9>u%*lLs|vtw@SGhh=&g#mLdEAzda zU3W%lL5bog_kr+#=T}eZ7M`Y68F64F{CZtE9cT*W{QRD~RX9~W( z@D8aJ#$)QD-O*I$q;#L7f&ixYZ`Vb7BN2)Cy|p^fQ#U7JgMKsRvTAe6>XB8qL;^B2 zW*7IF3_xbK&!^3)1c3GEnKbuca6G@Rf4(v8Wr%xvBO6JOs#mLyH*agUdCwp_&KoO{ zpUW25L0jd^b8<&hZEN*--#gi7O?iSm;nV4Jz1edEa1^m){lFZJI;GVh_e zYe7t)OXI;3shK1~A}_}Fa=gmScsCF~u%Xk!Hn|34l^!>H`{9y}k>Ylaxue>nj5{rq zO{siwLJLKS1s?wsuJ}TmY22IXH;G#KX1`RhTneExFgxFvW7tn|rw!mzY!2C{HG3Tk zOj)QmtU|gFcv6kvdU(4NDvMQPb%G?$Vq9rbB8Em<(0it0Wf$Ix-W#G;_#Z`G&Z_Gy z_hO_Gk48AW&@EWZT$Hk%sje0G>I;|Smxn84e=yOAHogqEPa?)LYQ!Nh5CLVKC22R$ ze5%}EUn{Z_8#FhTn>mO)7&w5-p+oL05HZSC1KUy1Ns!4dmG~7xu}XGj2o-pw3RcTK zT5U{dZ_|Pn0J0q@AW1FbOmV+kkv5VVH5tODj~E-H#CW(OHj?=C+ep1|@hI8WEjsq% z$m4<_$B6`;zXUGMXXOcjI^`pe)x z@OA|NDjE8k#B$2;Ks*xq8Gb~auR!5S>^@_uYJ|*~!E9-)+-_9&l}yncCb{iO?2T3v!bf7}0)b2R@g6Equ0$n4^2v9uC) zKA#NP{)KGit!R4|q9w~l{pHi}iYd$F7hs1;wiU=v%kHwJuCyFkPsABrmOvv-lv(`k z+d~uO<^a(hH2>FaDe?$b<&|OYrH{7SAy+K}TP^&e`ncPtU2T7MU&OqE1>K~LOvo?i z6ghe%k-liJw~L;dKHJ{|%H50der0y1c>ezK<42dqv!V!pPzC?ESaIAPeM=(Ws&h6h zmW3iqf_n(zhS87=8Y+V2(XcoAS1gZ3nuuiQK`OD9iW1KT=8?FzEEM6}(kd`m0Ohiz z!Ws}hTUFUR&E#yx;#?{XoxA!}=4X4!vE<-XS->&Lf_5>#@iMy%s_e>YM*vh>Ttx5@S!&ptw@rE%WtcbmdD^;-*CyMD#yGQAbKJ#rXYZ7@#$9hQz zEuvaBQ7SMn*^?;+uIbl#tUO?9S?b?j`OGM4(FC&552lnNCeCg3iZwSmzDBX*n_Kj*c}LW6ikJuXQGnq`#tyA z!Ac+Y#I!s?!N&e{oZhCVUk|Hu*Z89LR{Rp?NIqanBLM0%^{!Q>+~Jt!-iWjUb#=2k z))e*#VuNLEvVcGB$CsM?9&tr648|O%WDWY)@na)zv}Bovw4F+@4SDTyWgg*-c2W!B z348!uwqx&zu+`aiUuM5s%!0GA=;Vs>CFfG;D|=AVicXcQfRtzBB633(JeYVKWxHaR z5s{Q*Z5F#tb}F1x3TlW`dp9UV*jvzrSZ~ae87phg4pOD4Sb1GSyNOX{IOF2nmx^@D zS`a=a1Y~Wtq9V>k_Q*WUgaNU%S%og+A6QoOt2CE&>Z^Dg8mr=Z#?VoSU>S-gsR}vq zt==r!=Ft{y!^Wk+qC}1AMAdcl|7mjMfGicvrmaP&_&^T}4&=(B_`Nd)u4;R8fMX=o zT|^MNMhaYoXRBTVV*jU#H$gTSMg5-kdMDzP!-sY1K0B8_C63X~Nb5%rJ}W)xP{ zJ-jQCLEPxArnglhum!j;g*pfX9Z5}B_iY5p*$yMaURq0ockAS>1YOe^RwO8d?QMeM z{zKE*>n4szQG9FzvW&?Q@Iz!~W?248yuB0H3U$qZVkON57fz-*BB%&rkc%lnJZX!S5g18r}r0qFrx z5r-N?lJiVRGNsA^Ci_Rmejpnx!L`#u%L)Y&oaIB;b15e|{ zC$1XY4UN4*dA0Wa#6#p#X~;10EMl%cPbZOI48XJJ(_n@v$tW@fz=OdJ8PGuT4ZXm( zWI@l=jCA+SUL?esySIQdrt+{vioKG=erT^+|Huf4rljv2STO;dxN%!ZxT!lw>JicX zPOGUj+eE>WeJ=s#Om85ZHmOqZyIYXBG3&j)CVo3@hzX2L-36=$R)s56J2fJuc7s(^ z5m;S%vu|V6IH`+-Tr7I&*f?^d$0dBu&&4@K0%Q+uC|)Q_LusQ;70<|6RMi5gsoK2U zHY{|FE8{$(92eo00iA*yjXG}?oP2E5#5>U}*8uKF%GI_#8tvSmlTu+I;gE=_wm%ly z1TTKQyp}W&E@%RNT^Jg_OzdBly)SAN>;gC@Ork%~KI2bf)=W6ZM8Q~-S5hWb-|)eE zCYuUcOobt$EVwSA&vYRwrwbKUc`OljZIx<$B(|$us9~_#;@FkjSFpTwdov>EN%h4Z zx#@J#Z`y=w0zg=H`HSW7v2FNYLferYVUi6=WR>V^i^ca!Ce+K&N{j3z1c|HS&f^# z2}vFTJxwG_Lh2%9;x!^w6)Mm&v@?M0yBv-^_=;!jAT!mgQ~D0ic|N2XUqw!yyFNqt zBDCU7qj8tY%*Bkrlv_#gh9_`<^;hQ9fzw`mx}(U`d-y8COckdLoFT@BdWy>mIQw(| z3Dx_{Sh^p0f1!e^kcVo1JYpR#OEIZcv7(-@+7x>{W$gJJ@qwB|=Gi{JR_0bGWNb9SH?n5!Q4#%>>bV#n)H6X_m%;`N^u0nnqpQRuZm z8CUTBVf;WQmI3GE3W=7z8IZJr5_+w0s}-wXYJiRX8pTD3W$&kk;YqR3%O^ROFd?z{ zHEz3Kt{;{chSN--S@+tTb9nL8@N_k$fMGe5eb|Vt@mji$3|}t>$I}&<`ZT{VdtOfG zx9_)eq*rs)SB$EGRD;&(`*1+U^EKwf~(@ zwfzNW=RBYqLYzi}>CNC|@O-E6XX+Lly=QmdXM-C?)vS;|Pd7uCSDgl;z$cW^qPcV+ zoeX@5>$p)7Fc5t69rT?&ONw=8RQOw*{!~B=$37akW36=Ay>J9~Z+)z6Si3chSnf!w zn5lD6*GC>%i<%?T+${mh?e)BiBcHKJc#`WnoWYRXNJR@NS`|BvGkESx1%vombHGeV z9l8DvN5<7zk~YR>|J=tNZ|K8{WU5 zzjv{yaQ1?A=&*#nv;%KmkLaxyFF#&itIZF48$SF&_*`FCXLp{$n)am zLrIqg#1sJA)fjyjZArl)#{%f}qWoo_otED>B-h)?+Z&~YAI!72UwnDY;otb??7Olf zgnkhUjr^JK_-Idl^a=*%*M-8a3*xhwD<}HXbz1KFWtaY?6cUm=71VL2wh=row$09t zJ7*k9FyWG>W`@&c`PBva}~qm^;~<@Fn_5net>Q)x2K zoDb)%o>eOb4LOp`f%&{ETzOxljHH3fEIn&QA}>+l$^sR9WU97Ajs?#6G}?ZPSpheG zBvgb)CiY;?)vl4x0DV<)%$Vi5VG#~&&lVy-9J>Z+@DuyC87ai246iKs; zQ3xN!NZVWKOn~M(JTO+av%bSGzT&P67{hNJd0;eOX44+LtBfhZ` zuk61=l+p)nh=UqC6KEW$J4tMr28WSBXw9rSRWq+KWGqY}fXb*^a%7{maSt4pKi7z| z7cQv$7x&WGp!)D<6!c;RV1%K^P6m)yWBi7!V-~I1uKsD47H zwIYk72ND|$@1HbXUcIvtHeCI!%t@oZOs^SBUoI*Dmd|&&oKBZdq&JfU4bi<&Mfe*D zmb6*(`=_a~+xz9vK-my_c<*h5?1!g@$jqSWNy5YXue4Uf`Dk;lGHsW(<*82kVakO6Oa{<>%)U zimTb|`|R}mog7M{uLdV0xI+qqhh2cj-OVRy9Wdb=g+v>Be*Pwv0<)f)7hNcaU+NW{ zQCh13)PM3hBggXfE9P0emlvZNS@1DNx$lEBH6uyYtcEsY9o&*MQ&Ye})=$`b>2ht~ zQuU_Vtq!@2n2RWrUc8@z(&F(BK5_iUGr%d5SbvhONmnn16 z=?$zV8nvq zEnUG}%LC;XAZ$4NOGD@{^v{ZLelxPVolp#1B+S7}?W{$F zH=0woN~OeHg#T(wc2?6ed{6AswksPfzqYN$$rBz|N1=AaU~5InGYj*rbXQ<0byG&l z3uTIV|1a|eX{{8<%^Dyt5y`bxTYaFWYImS*W7oHA7Yeq&sxWM+OmbbtEN#JNf z2HIJH&qS)LA=;le3COOiyrD(71kg zpaxDGM1fVRXjJ7$GYsl$c~T`tBpV6()lJA+L{V5uWX-zbUnRk1ij(Z?y`K4z7Tx(( z2KuD0iM7$>%nqw$ROOz?q1q(9(uiv3RhRyKG7XW{{-^DAhsO3;t`{uAj015Yp^Uq! z;@vUdD&8ZFyV?dZX!)C>E_o}^#LG9lf14b{k-^En=G^e zY+&oOhA-FZYlu^9zHzPYVIE?iOeK zKrkEYqa%S*076PkJvL@ttFHG-IE8dr2F8Y7#$I{C|LmFw%%q(u9Q}#)JfRwh)c;Wb zt!?o%G4;LTFOD>XCRDOM^v1QqI9T(BgmvHqwzGpq+V=7L z!ziftU9dCQNsDpV({OogK--f@I+Vt0EtOTQBn_jy!6@$e#G6w9c)zFocYht@F}e~m zd05vdomIy0KTqeco4C3~@v)7OZ6pL(rU+6r!V*RiP$6Z6Tv*}-TzWc36fWFE6lqRg zU@D4H!V651?zX9JHRrwV{;iMPnR8|mLL4#yFR#7V9~BZ3G9t*GN{glLg~82#WOww` z1Uy)w%Q~#ypALrycD?qo2k`gFfO@bqF8s9H9rg#xk)XcR6z(3jf62+RoBj?cJTeS6 zpx!_%8$tAF&mD{nE9{D} zNh%kX!~N^%ZZ%r&DPp*XF+*dAudhRuAmQjWuzj5k7bIm7P>JtobpOH{nCnkr=T{-Fu zfEE&!6<6bGCKQ~e>Soc}H*@)S%D%HRQQ-17)QzOxgv5=T1AUT`DWR%%iJ!aVdnFUe zJd(tXiwR6`h9g&)+8Ex#mz!2hS2ajk+8R7lIoKNMxwwgQtjq-$qy)*alX6e|Wc+zS zuVX;0Vg?F%a1a|1$7RAW8pW+~H_7HDS5OgBh>~Uc4jY(o2uGAXPa8~ ztasT3!Y6xG9g%uN?wj+ltmgWzWTp74M|ImG$La7$L6%*% z##0)_QCew}9JrikwL2&YTFWgROn*nHoz%=EfAN(ThpQi+)s_t~RY==|8#1#lHu}qenu@{)N*EqwH^Ldr{CR8l*)IPsANE8%@2N=oZJ4{< z{&uMxbS;ob`CHkO_piI~;ZcKc*R+pn?a1(gbX3aK3ivBs(&XOP+#iJ}*amkBOoIvpN`z!;OLXCTT$)kvC2 zKVkqLK;gezntbC`foz^DR?4vxnz%Imk+Lzly|Uc!$~hU7XXk6;oP=MEE6l~Bz=hqZ zxKJk=1poySs4%e$8hL=3BpY|gLxuAhwN)M^;eO#Im4;ND7^(~}art~20OrDE1UI3& zj$-Mz;wH@r;HX;OVN_XUh-uW>&MBQt;g&ORcTvJ2pV~u{k@S*=n5iOL2 z2wfKbS7%Bas`c4ud3h%BS;KRB6U$%KhMjVmpV?>kaO6_lKP$BZ{`}y9+c$n*_i@?c zBB~l{7An;rUl`KcKSjx?xyQt1~N z>bg&UNNYnNrK4O7nMt+Gt6byfOA|L3fzfgqE;bi(qV?mxkV@4y=(qU!#+@=O)2?Y! zJCy1Z8bn=L8nwb?Imxq@%|+9#lSX9?p$xw%sW8p0U^;7yR2_Zc zbn2iubAPc?B`_Lc1^hVm6CPdSe#_|_2+Sg-+<>T|gi=bDwL{j4@^l2so}9fQt=tsaKolqNZpCO?jfAW1?qTn&!uu_i3T$+-2*1LH zmrI<%MuL@%h0y9%QI)UD8I8aOxROI}8A99Vjz-3YUx(^BVjcV+`*Sfws5Ts@MV>7v-3@zR7~ByLkYg3KS82yHAK&6-(v$2&2N?wQ0f zMrnW!y2!JJA!u>QvUNziodL=vm!rk_UG-Ts%wpsD1rz!pRj9l{7aKQqmK##5 z<~Q%{JMHKUo*Qpf6=67Z+yL6&E9rMr|7-xOSAHQOaatKWi4qTKQ8$Y;Sg^M6={njSkFHs1J@qSJc3- zRspFR*5q!|EXo~fGL$u%G3%+0omcVZfr^3yd(sB#TGBOY;`$qS&Co6vk8ebv2cT!i_O-;-Yb|gpDM!7PWF?h{ zJwTNqX!)dLrY^PFX}J8vl`SNACFBqa)h-yh%z!WXvQ}E`OLgXORY%t=JXVc`V#IZz z6iW`sO4hYFC=6HXs&VS8J_5LxoR|^ZSV$X1SJEpYXA?T{Xs?K<#V5vNqtc;RMSbv3 zp@hn4rZMi2d^J^11YLk*%t@ZC!3wxgJf%NncN$GO_8=NxJy*P7T$f-4NQ@4TdJut_qFeHK4xbp$?!KB5jfv@-}5sPPuDUT zPZHAP9pYt$cr@BE<4<)L#rRS1A-_e9b6~l7A zTHV#FZoR6>;iz5rAcWY^RX9xK)v{hLvoF#(P-6kJ>H&V&KzjbJuq#q0WmnSgH>0wv z)hfGRPOup*vv(uKvius&eVe@xXK%w9wj%;JKC=6_A?X`$Z`s>D<7Mb@OeRMh&y3gJ z598szeV!PKqKeKKEGv2=MyF+;e#OK1m2QUkRiPXZVrVQTV3MFSL((DkB0{lT(xl<0 zSTf@1TOv46M)y^kG{xv^FdN%VULm_T(}y7~grG5tUv$ww>;w0|(SOFGZ+-}b4Vk}r zt=3HfTWcWl0Kq6mQ!hcWblnQU{4G1K+%2GUUp5l`0ep_TajRtD=>=*GqrK7$?Oe_CLWoBrG!;rQTn%K zffcY)p$&W04$J#sTM;}-ltXDeh>>Nq1h5MB|sZ>{g(ry2GZ$^U2dlnM$cO+eYaF8D6x{^!j{;qjXh6V6XW4cE~Hoi z=c(#{$$6%e(3mVwpn+YLBckfdZXQAaBR_+tkPNKNp zQ`M33yi24e`dfVEH(VIhw`q2XlL^?B1+n%41S>k zaAXDc6}90&88d=jn+%;?-j&)B2F{>ld@?!HUZ{RRg|-_s(Q{^~?x!jmRlhF}cUIUX zmq{S)l+a4647D5PcIT_1SSl&E76w7pt^oEMD6_%^wCxchbz@-q?P7x#38j|keqowNl%!WHGb`|V_@z@jd zjXF(N{fCUW;joCY?24Lj4P3vSIuh9xGXEi{5-3($WoJ%yR#0~%M|zoCH^`kkHL=hf z2>@Wq2f^&ldagJuLN8bKdSzeL2D(c{PLk5GQXioKurcKo-rpJwo>TM7GWdRdXBQh9 z^Jk;J@2flGz{{`MYPp)LCTY3q&$6%gp$Zyiv(?1t@rvpO)LHgxrJO4;I9uLl@)>1A z#92tMCbM^j(AliNGzL4NGpR3po@H^C(J46TPu`ak15i>63#bB&7t6TW5(O?<~Z(_E^ zh_=-7J9&^Z>EY&8@@KA{>MklGWbu0|5Vo8BgCZI#{7qS{>`%x_5&i8bkW$B74Vc1f zFSlORoR1^l1xNz3N~ldF*6>sINBhM8o95%*kV04Zf(N2i;*T<+lRY3CsvT7o=dv6@ z5kh72xfXRvpjiT^*Mz`anSjXGggviI7S9WY#DP*GGkz|2cZlj}gL%5uM@mZ42f zMGF_BoRCJIlUBgEf^&7#>P{|VgT3X2j6@P9wx4#xw%8nri>B88#qjs#lSaM87VVQ@ zXoIF$Q{ZPgl(d$$>lROpsTm9}ichw#kA}epvQJ}|fHj65e;*U*u`qz8(Rab58bZ8S zl(Z?0)l4XfmRbv+iQ=FFxOj9zt&MPaYoCt`Nx}{VTk1<8sTHQ*%h)*SRs@~(En{<| zxd+3|w%v@?yRa!Ggf5Rj;&%I_yvVJp3QH=G3T=Z~^=b`F@RtE?o9E-o{=|IXlZ|?d zH3IYFg%#>!n4G-7yC#4Ed5sA6e@UTOj$jlshv+paoQUsL!Fro*Q7mA-U%^9e4kkg(^Qy4`(n+znL*ODk5_o6tuQLgf%Qxj~tZkpX)Bw=FPmy40z=Eqt3rO^W z#C?fl=uN(O)EBpZwGTFLC>yi7~zy$#k(DM zXqa-3&h*_IJq_u4I0MvCh{yLTMurUUKx>cu4h2pcS!JONR^xFpTvYr9_{v9|Pc$yL z$*@M}pk-IvUN2H}VmJ8d306ltgUMZIR7Z1?p4XAuj5_PlwPje^tjO=wO4qUr*U=vy zCu$s6+XXcjD%)ceX>1*7S8OQETDhy#XUc_tQbxGe0J;_i<2b5uEm6i$cjxsTqAQY| z4S<*HpDVtmdO-n`2Ck6d8CM&g*7KQBVntQ1>g@i@F8Tsj6$`B_ECg2u)9>@_zQz=6 zD+( zYDBC}TXH$_L}ToMc=1VZ>qe+jHo{7MEd?Xl)LG$K#Tr6H>MjDS_o}M?Kh^KHVscM0*H-diH zu0wt<0A?ZGiw(Q%!yzAUE+t2RBj>U$?z1bLoeyRpZGXRuoxkxbBJYejwk$PFJ4OLa;hQo!>HrMERAm5Rlbqt>E z`jh>sSCoTOF8LJ)0a91&uvDD}r+uh4jdD*MM-SsKJqqmq%Zg5Cd;abD!|rWQF+N=c zSc8*_f2k#OR?G$U1Fs;E}U|pda>&) zxaZ2ZgH+?FP=wh@x@1s5A4#m0ii~_EglIRb&<+`fC>;bCVdP#a=Bw#)&lRl%JCv4* zt4rDij!O&u#h(3ZCP3ioc{{yc$Hi-T;>b$e(hfJ=u_6wCC&862_lUCMJAgul>JZja z*|jlryd552Vxj#rp&DueW*OFC7PjNSnKz)&&7MP?OK7f*|L#Ic0&zhxxl{6FXB2dl zY}u6`DhPh79D!tKAkifFoRG#RZR_*NS;war;8sU1Q4A#db3>PK-ZzHT_sTOhH_tD<25npjrWI zFy7$j2bR6-Gqm@-UQ8CMA|&u?GeH(T{d+#yoF`|5Sd%lnmo>57I8jX2dDEQ_yYq8T zDbEJGXM&y$gBe5jhW3A5S{smZu@8m?8wH+pyRQbqbTKe*Hl!V5Eb8^Uueglvd`Nva zlo7bsGayBPMH-gMk&Gkv@8l`Eb4WFQOwZt5e=^fD7~hdS<4j4D+^0XptJMGgIQv2D z75N(mzr+97w>^8@55Hr7_+>z4X6IHO#`mG>H~Dc5wRw?4&^6D}Im)3Bcpro3?r{Mf zgc^PEp}rN5GNld=PJX3C(R_`KaOl|^nd*FF`HM!LB7_S=3pK9e5z!b=E-D2ak!gTf zMzKW)cuQyiY3I?=8w}ZqPz_?&tnuC$H@ew{y&ZX3#->stlPY!FwN-2wz%p1$-n1?Y zT92x_(O?-pQEG^C;TamIeM={Z5J|;Qo~U8KsI4JwsVlTQZ zl}LH=k@7bR2X`+|o`j`1%BS6vsu=E1<0omUFFy^P>zDhV_=*gMpQQGxUmSQbCGB3= z9Akurv=zTgvGg41etE--VK#4RsJ%K|04mJO=+)lRu-31dO%4%k*w z2&B?Nb9*666I#9zl}IC+I@s@Wyc&gw2|R>KiED3#oaTj+)#A~C>?|qui<>(*MciK~ zA+pfi8RnZ9fX9+p7pl|LCnF3~4?S1=uh$ZyK~9Ssl>5}Th&y%@e6>V0l`=$Tg;Gf5 zm=xOXhW-$qTDs^kyV>d0D){;FR792XtYjemt?X(aZOhUBSrwScNLaY$Lk$a==RwQC zAZW}yL<4dS3s%2_-+>fo#F~YGTiiDmI0yPoc>8aXa2g>xS&FS>f3!zkwG!^Ab1ftD z2c7fpP;t?$fsdg9J_g7R!V^?nOysV`K38hiaj#9UT|)5eMrnTsp)q9Y0S&$}L47Kt zlPij-An=<)mve<6ZK!Q-2w&Ca_;}nKZ}x_WTz+F3dgc4Id;Cd`ik(7frF=-cR6v~k zEQXr{sK~pbK@vfyBb6~IeDbJqas&}q23EqNHz2B6i(kN*R$wALFd?zkJ<`3fmrPr+ zSjTM#_8TR}R`)6cCV+C_y+-+9F`xn>(Qx@{|0xMNLb?4BMaHXz;DGQ}#Yv02qgp~7 z!7?DTc_TFt+T94m8X&VWl4}sW9;_aWC9j_!9=v+c z$S>MyR=~`l`Lg~SrSz0eVEbY)ypjcYzImQckw`Dra|yHFf!ql(8*BRpN3ejF0rO-7 zkRqG**)w4LzM1znoA=E`L+T0AXQRu1tNWMaE1DW6=YOVMdV!~Ry|Z?|D5Zz^kp7{9 zp+~^gWQqcsSu`zz6e@V)GX)8Dj~NoIyV*o=ZP@zCN*HTWcP6lX6y>Gy2u4iD0$!zA zZ`OZ(rM6H3l*30~`RcfF-n$=CUeV6*XiVCWdG`9n_-~B!jaq8(wWCiE>za_5bG49g z0c_tES~cy}jgpMig;acAlNb7=XCBB?INrwDHCD~4;FdEB_6=p`$^cPn)(pDBHDUrN z+5Z-YOx7b-zZgkIo>W8#L-BcvH4K)tHdU;V@gS+6J-e_Z_#bOgX>`aKQ;9wYC37he z5#5DEJ1ikwXlv~>|CSQPF>dVyPk<9ZV;G_#EV5r?!h~<2X{s(2Gh9O-Ln;Gj75vr= zj#aYTo=BfG5ZqPwjUgq(SpTrD9iJ}u;~Uc@1&iJ9lSIyjyx*8V8xYq|K=SUZVX-#F z%iTS3RYsz7`Dn6P-Hcz zuEC3tLhgD+rS72mX~Je;#w534k2@$ex&c0+)hVM}dl|G;_8du3B^vfHc6J<< zG(wbm0>bPV+yV$+bX~k zYyg<$`;Zuq0ZkH!zzh-%OjT6GjM@%dnL-b84aEs%mNJTR!ojhl6>h}u+2g1>VyP;3 zP-X|i;oQKJ>9RyrAmq`3bFlx&SsuHB3vz3JqAhD+97bD=$h;7-(nM4)@@ITb-VN*o znze5yPeiQ=pWFtKItx`nXvft%NL|tvG>!~ow}e4&Kh}n}Mu>AraD>Mwk_O8-umS4o zVYQ;`_rcA;2EiK!%i}UqwxE5{k|oa!vJ>*^b$|GnX(UF zZzh}h^SX!E$i-JGVt7CIRK#FkjQ3Ilyq*}Lou9eE4vE&Hh8})@$GAifAw9qb)7{~G z`n^X>!_csoSu@U}S??2QyULk_K0k8P?1whOL+Ta`aJ#hj-g)1`qdiKz*l2Kf`1tyr zA+y0InH*@J`&fqi04x${LOG&RqT zKd>0__^1+^YS*J$*x09(EH@5ienpHzB!~+aP`aa0>nhbPB$91r;tBMp+12)M^$U^! z7~lE_<;HZ6Iwf1Vgmi-d!(ScF04djnQ} zp}(*uNfP|7e~!5s>a4_OI|ioP{na!9TRs^uH(G4lBM)>SDG;l?ELF}p_Axd5cSM_m zLQX0>RB@%Ex2Kk*&8jnIEh}i?kW>^C(My%P_~{7)?IfeI)(KEqGFXquZn!S6vw@n!_z~0!?2Z zOONd4fKUSJ*qufyZYW$xrEAt3GAocHDZB}o5mTbcG8-BDoGP4ys128U$s`nd4GJH_ zG*)sKW7uEKN_i4m{Tl42u7022Q_fFuXr%o zSE@>yYv?JK<-1fJ5a=iwft+Cg=0qkJUJ@ZooaNHK92h`qv$ z4C*MM=J#d|Vn1uQ7?AFdz&%VDLVdK`_YtiN|6}RgbyG*UD15LnGDbpNWQs&W5tgup zNGha6{1le*0+gPqj3_85=7=KA@B*nQjuKuW-LzDx&UvqYe`{MBWdfMXBoi;Mz1M{| zTT{%?5*`oxyB0~%b_0-}w-iXp0NlRpSRpU;w(C~AjXjFYN>(VnvbHtISw%DXmdyW1)D3NT)1&|+eGt#Q*?888tlEE|nUh+361MZDz1orwtbkN|j!Svfy6~Wkqd-qKa z<$s;KkB?68;Tdbv2W-_)wezM@!4D!gP;Dtj@}XyNI_UM@?h#Gh-;2=VGaB4KkL34# zcG)urdiXOj&jXIJXBy7_{rndqEH=Zqk1z*gPofQJ^!$TW30h}K{Uou#Js(RKz4a)Y zKp|MEyN+1?dMBCA9083-9@ArAE0JNTpFIgnD=|gkh1%q*g0NOX2fH#PRjIQADNAuN zNz0kTeFX*hzr4gz+AAWdTka^0DTTd42LLkhCV#Y>I-Qav|3ya^`Rgvi{>E*Pq9FItniG+5}@u*{!$q20^MV6Si`0cNyDSDb~wOcB}F44*2%X7 zklsTk!rN6vVA51C@Q0_qr9i?dan4lvlCg(OH!XwO6OWs`W-bmQ*_q^FkoMW_N{P~| zytqN2I&K1aK)^n&4w@pXE=^WOd$GRKZ0QnLmTkZ_yvVp6O7u_A)C9I@_-&TK=&T5! zR}rug@NIbQ%N?xQT#^i19^}#R+4bP}?ZdKT4fcJ4Hu=2hulTQ3ZDAmL5d@UHXr{~x z(P-Jrw!z z4kkHc7<(dz!ZqN}#7Pdq zeBOO3`)a}M1>Y`qiv^LCjF-vA+N~D`ysPd9r>>-gGK6FV0`;z9{7CoO5duZ9yw45+%ikiP?vIkI| zD5Q4mY4UNDab+F*fEv(6WaaV}bW)sIv^*Q5U8$1L&T3VvnnGSI(o#;ACTTTXWIAYs1;YJr&*X1UZZ#&qlio~Pq{bGgWH3XO}( zEI*`|{MJPkG^U@hhN3C_u+Z|9uSSi16aRalve6in>{d38y z;zE9OcHq(mffhL(hkT{?%B;Nd$JJhp|U?D36WSExC5} z>PYexS{bWjA(P#=t6Wscp-~k^RmIcBzV$u$vypK*P)gzKCD@54LWgb;;I#rayK)?% zQk11Ai@ZreDV0jbR3Dj_jwM|QlU+?g8>mXR-O%JwSTJRQbgVy2;V_OUsitFH2z(3p zcy_Zuj@`H9L+vEKj+;hbg(!1FJ%kvW8HmAD`;p)o@Repu^h(YbvEq(Y^k~z>9gIiV_N~PV#6a)G*SXH8NCd*zp?z-XD0;1 zp0nM@k~RN@>9>6A6lJzhd z)%HB6sThviG!okJJG57#&`{fb-}?^x_cdVd)?R!;QFsP3cEDyb`+6NvRM`IGaRCe4~a8~g1||5f>s-M5;a zU4^Bg^X%@CjAvuUcdOoG55Q#}eTP*T6z)(p2naKLo&l{0xjuTG>AC4ZS}}Vjl@jUm z{q#;!s~(2lhr7}Ao*NHPTLV$5jz%A&8TO;j^V@w-eF|@H12oPC$6hozBGH-sF;Q3$ zMC~N<$MBX;anFz?2a9oWDETwxTlYlQKlYoKQ`ve*0(@L1zo0vopZF@z?JG{i;SX$8cM7B9O9oZ1yu`1 zwQePz796XUs2h6dZrarRU_LTD7SI%IJlXe_()k*YrTIIu;LS;PU^;*&>{Ur>d@YX} z1j9TpONpTk6@lP)2F4R|G)~KWIeGnQjQ8t>0LqPWpig$^%TlA~d`aTuPYs_9eM^b7 zi~yI%4edu8_b0LaT|%qj!za?A3qifn-va36z%Lnl^ZdO&*5ze0K?P0)1H$c%R@R1> zzSrimVj}I?GS5!0U*#p&NIsW#%5G&xM$_b7Tv*Z?<0lmRQ0eC-U$F9?yZPZJ&~-C) z78|}E6n#}RVmFMwS_GuUxSLlI#w6Ur45RJ9F45g88zd@AV`iS;RbP_*maA@E*}JO9 zK^avdzg-PV>eMJQ@P~j)dx#4fEsSq`W~Q_J|B-Zys2*3B)J?!)bkK^I32&+@LnhnO zU6IVJUJ%KUQwh7q2hd72N~ubE_5X6_orPMsB-~dkr;pYJ+6(CsB||Ie0^p0>zvNb= zplLlECtLL@Va``*N386Nr0E6rIwU#?Bh8zY$0a&U`A}k9FYsPqAh_}DZe61Z@R7A8 zi&7w4vs7CN%45UopdYCa!uj)FUJJnV>OjjYwGxS;TRLPLeFxr#g!D<9=e_38L@+a3 z_MNZ6^;Qd9WkfRe9pW#hrO4i7*bb@x4GpjUuqO`L?o!-GsRQ<&_z#C}`+d|;{+d(> z57|ryS7grivVQkxR%T!wAWgQYLP0rMrv(vh*?-=zVtG*y_!&)Up@xnt>I^grD!-* z42SBD_DX=>V@>LR{-36^*G*jCqWH0mkuj1LW0?XZ6k!P?1gRoTcMgA? z9-2swYGFWZ%yyB`FgP+GY^kRh|T6QD`&@*YR3}6oiu#XcyLDz!)Ve$6H{WE+> zu6)oQz<&7ge-E=a{xl){YVpAI87uH3!|2JBEDjt;E8#Jwqb@fdyBLxtQ)9o>D`?DY z;5#}$o(*!(AaQp*lJ^&>6){+-pa)$8;L&I@J`V==`0)$%f^-pfN!_5^cicy~tY0L{ zVvUP~7oPkvU>kg+z4tF&TuOtn`{<7iWyc=`WWi{02-_`}fn^^b#8C1whQ2t1pOsTd z`o`VB@R_izA9s{7#HvH;*wLBMdK7nD0K1}GnV5Ky23EKIPwaweLpRfsXHeJJs$j|V z&X1+{P{~UWy*$kB~kRdHdMuxN*afO>y}|P(qV(yPn<@V_2;sEm8@9tQFdd?lD5G91N^eyHB?=r zi-z)U{~Gz9tH$iL_EH;zH9qoob@!kzg0&iYO4ZSbC#F# z_8K#uUpDP$LBJNnYWpAf`;#(Z;b@6iE6?WCE)eHz9JHu2sA=8X%rjN~+G|~CManJ; zA7vyR5|t${c-B+$BM8f<$dk+^l+Sv0&DZ90UFl^4XYpnYp1Gc5!rVGlR*zk(D+6Id ztwFV21lBI!To|g$Oh(jTDQ^x{IoQFis4eFl)(pDNV`Jzt2ncqw$TbYoyM!VublS#T z!(s4LiRrx0)XAGm7-c-PQ09h4$BMinFH%WXV$JS)SXE}cNi%0kiq%boJur4})<}`h z6obk~q+m(=>s0{k*1KFBI0;uKerzX*uh`{U1~LGLqR6pv_E4RIScRnJV$95WV`nTm zjuWX%d>4vI>a=50BGpFD6s21!t@?Z`qLGJc5pruMQLz4L70WLcXU2?X-DEg1V>BXe4eU@0qN8kFz(;? zSq+2A)Dj|%?t;qTvT`h`V35$tI4m5vuR`E4ID9`E(<^9X_1BNP{~On3c&()9Fz@-+N;a@l1#f4**pze$qjj}lzFUrJuRBn^b|_fQ(F;rets(U&xQJsDuX+V|n+ z(XH|1`SCPAVP!I)Ubja)QJeO-xjC@x65?18FUbW)aik0BQ;Ms-W&?U$p(yO%5MO*) zEo7HVn_iipKJ!h1|C%lFiI!#Hbl;Pi2w6JAhFslJ+PoW%*LFE%k0?GhmM+`8chu^g zmm{T&(e7SdzfRv?$U6+VB^R1DYG`SW1}{pbaj}yN)_x=cE}l+DHVFpBu0+n`W7Mc_hM3& zMl=}ml?BS}h-*Q27E0l-m`YVKWa7fUs~?11M(Q%;lUJS*#cpk^Y{@|7N192y+HKhh z>;)rU4#4$XL=|^tZj-7?U>+s$)h&2ZBCyCMZ~%Zl?Mme5=vTKacKhDYed+W96qTkE6eaBA53ZIT#Gpt;D$t0#5jJs^rV02|UW)BDEcP?kuO6 zOMo%~hcQ+*L~$hOsR_PF8v#4S113ydmB!7DzXKhU&Nqz=$(78>Z=<|d@0)q@PVy-V zk8ma#G@^A*1l^TSO!bb)s>W`zwdN%o*UHer-NX&g?*tNZ+4HKZk#}mL|{5n0nEtojJJyf%)M9>s59E|%Oq!%-Ii+p*DSLOl4mHv}H{ z@9ymph@+oL!%`abfA7&>KTE&$j{@9wc1XrL?y&pO8Wto0cD*1Wf`fe5%qb_mh-uds zm(U`+zB<8qKrarQ_eiPmEQzof$tZkd4-q-I#QN1TRPOUS)=F5@yi7f-nX6||{2z%2 z+T=-^75;5+gXf}abusxp#R=}Sy6qJ$)vw5AQ1R5tU@CIX@pjUdq~@Z;VX@&tSliNx z#Duy%;@~OD;}McKG``oH_oyBqQ37ku@i;Gzd8@|44ZG2!RJ{gyxNE^dL%E|&IK%Bp z4q&3AwnyW?8!dE~xP^}8*61xv_i1eecn!C;o6Dcep;9@9vMT}A%kBE~dYVfMy)Fre zmIHXWwZC$E+9)2&@cuV-!Q~RQGg>bxxLE!g%07YEOI0Gmg4?~mD0LSTRYfGnToY-@ zuncBJ?AH=?LtE!VRL+XtXyq^hd^f1UNh^Wn8s98kwO}Fs%6i=XJ=rSv=GmsKx$hOj zQVZVlPcrZA)gD|D8)+9qM3Y?@J>wB3mV!V~^mI2>9W}hAI(|dsSa$6Oh#PI5=bu=_ z?RX*!oRBnVFCYmEwhM*5_7_E2U-n41ioH4-l=w_whXSsoz+w;%x+1)`3p>D(L$U6u zbPz$bcD@{^SlI=yc38%HY;$Zy;z9x{`RE*ZRc1NYiz+F)GRM);tN9Nm-CG@ly@v`) zvQ>T*y7@9oT4mhu_#SAfY^z=<_pkUat-ur#!;a(3ZIcymMH`tt)psw(W>nA7o6_Fd zUjlB4r5yDHM74UgXEn4WQOFS9>J%JYyV`~*chlie&(30rFa^fgfI7_0>?^w}Tv9XV zTgRc)BJOo`Wgxk;7euZL$(XOVQ~N^_V*X{-%JiXN~rEue&3(bf`anU;ywv3I)0Mw5pms0k0;&rZ_gU2G7 zcn_kh5_zDM=Ui!;%!=Aq-=OBt2(r=zaa~~K^ zg|OXO)lmG~!4GWA*1)<+57j&PnpP{c&$EAdI(yy3)h-H;Z9v$OPypElNGQS*wj!WH zVnisAas!l{4n*OCCZb4lxB)7PDB%XCm`k8ab>_al{jAM=I?^N%eomsq>s@=VpRd-) zfOiK!HkhTQ!HBS-?S$lw#nAA0G@%n|H)1{f{Ji@x@LYhjg9%SCGHkpUFr6x*V~1#Z zHkf=&XEUSDA1XqcO7d(xcB3Y6k4TI+4$(}H^8?z53V!>zW`yHN$sx;aQ zFE&Jd2Wkg~yuAm*Yg&$INKzJM@8Q%t8MsPz_3+e~pNs=HdJO~W&WR)rL)24WEe#E| z5z1&}RC(SZ4BQpGS7a+5mTG1@8BM5c@6n9=e4S0Z%CyC$hcFb2fAK?5avBIfBz{E2CCuw-DE= zIk;3pa8|krw#Z17NaLeXIn>e^Y%1#JnZh!`hWd%$!fta|@r9@>1H5zP2vgmvl{dPalNrDsS4WBi%Z%Ww*B2zvnTKG#zP=d*6YdNb9{*+!yrR-5Gv;g9Y#-@U zIx@Uo{#>2WUMX$EK7m3PN8{QD(P~EF2czkBbEOS2`fI{9&c)b^fQ5rwdqvj8>R>2V zM~LS!FBoPUI9H0nDsF(UvEm9Rvj=8tiz^}8@`8kGTW0o?5;ZMUFGUjclITjiu~NH2 zNu1?{j%8z&w>(}FzD>a)tar=7NdO+F2i#sr-*PfP;#>)lM4uJZFKlTp0-{qtO`!s~ zr0E9pF!PWNyJ8V!khH5Km~V-(i^GL;v|0wE27ZRZB}cau;qx|8N|yb5BYq?CSX8Zb z?KgZwt)TCAWle%q`vAw_F^d1zDQqGz+mDiF80q`60+SQUckzOnDQB_k`KEBu#UP~*Pbi*|CNwk*^ z))m>If+XP~VO*i`v`fN864CM(c_xq7E=WcxmoIm(BhR07A&5rSO1TK6QU3Npv|yWT zThaMID_rjrX1-0*UT_~h*F!~CP!3GId>9eYVMhSF{1`03wnK@+Lf-&~&}cgd$WI&u zR|%%~i7s3s!%^DOG?}bva;&1D25I0bcHM_pH5l!^c2Mlvi-dz#f^$lpNl9=8!I~-y zBwfp{hc&jv1V|c{Y}RUtFtM$M!=SD12bzl@)c25Q z3^bvmOsKE8h=br+^}yFfd$DfG2Ye;5t8Mg`z${e}eb$Z;!^D8Cv7cIm!)ep9x+oQJnky<1_dmU1{HX;z(09uydXN5zf&035QLlgNt zof$sYrq9o{iNdb_1CV#KDdOk}v*?lW+XX7Do${^*OrDMF&W!9*PWX(_YBFRJJ@hy% zH6QJ!gA)%OYD3)X4fqT@Fo}~?AT?+-Vq#6sq@te*xjJbuZTA@74nKz&e<>ntD8l2! zf_K>aq))-Hm-%$#0p*op>#5W4F_`W=ePUATt5FbS?X%`JUfbXk*1ra*pC_`d9-oBH zJl&o(XZ=e`2VH~6too>$AK&eX{rTtMv4=dX|0rt99vFu()c4U1NcIH-?76Cd`yIS!p+~=o1$U#C+(&Z#U+*VaRf$GYOM396%n4-3#+WE@82~Fl)W0TwLn`H8 zq%}>`Xpe)IVwAId+>EvUmFEb{FPY91u*Kzu^_!YhqeR5mFg8{EkOC#ug>DyNxJxQx zLe@i}m}pc$+uRd+V-|>Y8Ij7ZXL;N!;Zu~%Wd3S-S(cT|MdjIJC|8w%Ji!zNmANb5 z1><+ksxsZ4i~LdT!hji#5`>Qzf&6j!V4cpM**K#KumOahdtSfBvdQ1zAB z^lubcN3}q>Hz+SMvbqp!u`(veLu2vMBe06qnK?O}o#G_>2T|H~TOBe_v0RlK`=*X1 zM-2n;?eE;azjS3kx^h(+(%oop1cGCtukIa<#GEXRA8V~l{*?XrHY-v&V%d<&@-E0K zsQqXtn7o~172aZ+CaM2^X%29?Qgq4RPvnQ@tZRz+f-Qbr?9ETJ_nvFX2w5?b`dX+K!$=q`j@;C&8goJ{yl={w)Rb=0{@zt18Y!GZ zBFnD7i4U{8Qb{NG{K>>SlDru~7YjE?C@V{5BqAs4WK~Hx9nlA@j1P|XU~SN>8;%Py zBhUP41zIADj0PMH0+c7~eU#iwQCkvh8>SkoP4@M5;xFY^AeAo$Dm0=~kQzgHY1747 zn0+Cm?Z4j2z*o8UW_v|d60c!kjxOnMr$Ui!KJC^2p%zkHRofjM;^9vd4`U6REGJ6SePXC}rwIDJfd^d9{y)zyqCw0&&Ahm8QA9v-yr{TB%|Wkxa{DG%Df)F55VR`(h% z8*4@$Z3I}kSMP)O#(XY=aNlDn?el))vqNqNdMoZzS%ZQ3BXFyv=RToWPrZ(I#K5(o z>wK=6^@FiogwDVEO3Lc@9Eimk8%j6Jclm-v0+f@Y4_ft3vazr{+=v8m*6X zNY-hVV{+Kk&Pf_+kFdG7qiL?hpLe7Zw5aPEOfC$uB+zblR4BVo*Sb9;|R- zcfTBR%6LjH--Xg5iZV6uxfL`tRI5~rUOY9i2O=AsEYn<_^w7WR_mTnvd1L8mKq$RD zd;cKh&$#ATzFd_bX*zu_@9ramPM|q^d&|x*KYv1t#~6R##&0WT&>3+X%jFx^U{=E8 z10&_%ui4L|k>B%AIuX%AzY zz`Nlmdf6~zzIenWKh5}}@}w<6CrfF!a^OBM)mUEMgyf!C!v9h6K( zse@J?tT^OH;yw{?dbsq za+GfF0%V-#x`Eu4fh?C-xj{L5ZpmqvV=6vvp2t zr1U%V%HW9hH1(M(S>SH-g{zVq8LEV-iHpeYx_(CnB?_jNvXqEmF1HF&DSE$7|(e}l0Q#B2GcY-r0G>m{s)KF5eG7rXI6t)P2-Un+c zkXq{Ytqhn8S+*k!4NP#XtfFA0H<_6~X~JD~w||Aav5uc){%vnO9Rj z+~Gf>|M!uaUvT$vJb?{kC4NN)Jz7kdIYW$j1hv15k;KmnFxddPH(pRwh+UYuw2{#} z)iI2Ei=H;ZBg{rWxMO5c`5&N`W$+IIIc^b5Qw)rBxknGu`#bVx^&}}8i$bIa*@3?U zxrW{>h40z-YM1=P7Fe1r)K{|n+C8_ur*Enu)QT9V(S7d$zWju8+Av#_Xaz%)#{vI+ z(g%XD$cp}TOE1#XKU@pykH&=$DLW4}cR_n&ZClbn5{}TD!M%4O4jp~tR#|1&>z`S` zwS1Cto zs!LoE)Fx*nJ6lfU1zulp+HTRgkQpeS4Mfi3Re8S9#&vOk6bt zG*xvXA8ocO>PDI&1vA#N8Ua)Yg$k)Y`m`FZK`7j|=!tpCn$Dsb zTVGj!RrhOnOaH>qyOC;xUCE)J*Y$65p&(FRdHC`hEtfq_5Ia1T$E&cFG4t?k zwmKHGVyMJvcOM;Bs}s3cBsL>!u318>wa8fV*}kj{N@mOA__&p;V|iqt%+R?i?V{pJ zy`Vj*zVf3m{<+GTv{!^{l&gf5_<=dTA?xbUsIb9n7Y+%(i!!GtA}M~0_;Lh|8A$V} z2&X(q1g&37*hUtyOVo*abJqHrgJPcXr+;2hz-nyo>_K1U%aI+Ngyl8Z>>cdUwPJ*{UOFm(sE}K zJoMty=ZzYclt_s}(_2+syzEM7`V`%$NRO`_B-nVNp@``Q#B|$)M4DX4U(iO;Xeyc< zkxjYRML|cISB7BfE)rnJ?wS%G_o4>X1gBBonDt**(x>)i2A&&EPho!_h0d4_Kp7g7 z5W*ySFVS%nzLrXV|gqL`eHb%DxSclr>FUBRKtVD3& zB4&nd=ip@!C?vWsRW}1<*_MFjy_$bDQ66ZN9qf=Z+qXP{d=w9%?LEK1VIhF|PFi@V5^E@AoT^l_nqVo0ib$+KD z%DWrn&J-tMD*|uro<(o;YS7A3_{ZqoSnjwt8sEI$p}-m~*bWmt*?Wa7leG<@fpY|0L zM+SQA26|oA%GMC*k1X`TlX?j=<;1#MF%lt8KGBJ?*|on_BeAMMQceeBJ8Y4u#40f- zr?jv?c;FVvvvC1AeBs2#RgLmC@>OO{5zGCH3q_3!jjX{wj5dZtxPFwMHTsj_CaiYR<8{$Pe%sQjJXN1Dt+I}!gjSD9&34)j^0Q}{le;~2rjz< z*dA#loK@QVN@L|Y&LKbLBA_Nw1QW-!da zqH!JcDrXK|kWrPxwX+6bH71vBsA1x?B2f@c zAx9-g>t{5$pJ5*FhNI9okO?;@VrUoc*>LHf8qK#7T8O%gm zVXnF?c8LbLlWE!n$T1YZ5ee752SO=2`1jRTq);7#W9hq>7#dNt-9^B&MABqP%4Vp5 z%2>*dj+RkvabWDD@HFhVlW7l!Y~8*}e`b}%?pTH-Hx{QC+`&F#i#sY+(-prq#rt63 zk7VQ=Dj@ozSb`vq4Bj?W8yIA!SeH0U?E@A61{5-E^kUIoU+DBb*9xt3co9h^DmvJw z7dz@eSs2jTbPz9jT&F*{0CmJg4r1DpNQb5`fyuW*tE8YNdYO{MHaybUs2xlWDaOYN zgx<>@g`YQ&W0%7Tu=Rq*YGdyy+5`g^a}9zE8`l80Fn{A18z96r0kclA-MpQ_6pL-n+1yJ}%K)jmfFRjbxwf7(J_T zVLqBKCR0P*#m}4hXt6L-yg-iySyuP&eDNxoG&nt`8Hr5j(cA!cNktMdSwQam?he!M z2>a3aX3Svt^;J0>W9&%1Tm8@0w@1>XJ%%(6gH+bO5<)-RXr@dK^iA)(=GCzcX|)p_T?2DHE3I?v0kW)zxn$l%@uxR+ zYkZuxXNgd)ZkoBV?9E*b&HkxP$jxQMNW=hgr9?vwirMO5#8&`Us~4!vZB{qYdIs^WmG8^| z`q@yop81XS^UL$|>0}uE)d=qTg^q@op>jBevlp@6bv=B6`kr|HdiFBJQd}aBw%e;U z{^B7JeHspr*WU%B=dFDgZ{%hTVXzA1VuUV_QFT;^M`buVE6eTBa2Lcr*e7M}Cg(T9 z(FT4?(k7N7B;sUOau{;23%<$@n7O-M$Pk#dP0kFlHPtV59fM)GG$!ZssIUYcQ3w)gT`2hl2~kbXZ8y{^Rl!qR4WUpAh2?@+=)5aiyP zgdfj9RC8z-Ns$F@hyF~}bx0ke2Uta|>qxc)-w}sdAgBYQwIx!+Ax8=`ck`kJR@0$E zJF-u?eRHxb6_lfVEjY7li)A^wL~YiN$`JQyoQHeGcBGsnI9EiO{Tq|<$QaAPg# z0&R^2#j)hiaU1s0?I_B5Pu)=*Z~TtV2Ps@CWWeAgUy~xL3>wj&MKlX;Hg;@wwk(r* z4MDKVl0Npb5-)XIVH;SFm_sj>E4fqGuhKf0P8;O!mWIiyBP5%Pui$20_WK{L=nA~W zUWCclNO9+*J7HqI8|+A*WHU?($8tKI8lD=?8W``U-Q|1#`6v)4^r(W3CN4G0?v z1uRn#2_cZMH40QnM1%q&i73*Xyg(|7Xu=Cjk?yussV47r_O~{3XQW92 zHenRP^4fd-7@pF+K#`Fg!$y1;i#03X`HVOY`{W0Q(1&CoynHvd%RCzJT`ZS!A88;> zYzOhs6QZHl@00mxNCogjuA`x$yatVc)OB%`U<@_tG>dp ze%}0Cp@RO~w?J7};F4#<)kEY&6*R2Z?BboRTZ(ydr(qzLPhzx`w2$u+vq*j-jeiPO z!$?xP2#Jvdj>}X^owA5`CvrNHY`+0q^qo^dB0df7Zu5x8M0z1?Wd`>=Vu z*M|50+0fKL_xb+#aJMduHuDu zd`;H?P*1h+H!IalXdrabZ$dNi>^64GcG#(zAy1CmsUoY~lq5Z3(&&08+n&-(}^)7b4iyqS=O*wVCuVHFIW+7 zI*~>vRmrgg82in-v{q?SGYCCHn(J{NJ8OlN^sazv2*gte6}p9lGxZX2V{6hhht(NS ze+pb@;sUI%%5YQ>SY2KI2i((5B5X&!ZgLICb%nNPRccu)TFS)RKStL?W=6}bd@IJz zNw*h~HP!6um?zXqU1_uYk?pGwvbBIqZXl{OV(GX&br?LVOjgD__=p=08`1Z zpYMC;55aPSa7pceJ%sXOHt%Tx+@pSBVni5p-IGJffdo=Qd*_q=T!jpV&db?yu~bv= zZ2xERK6`0m{``S)uO@7Ts@3b$VjYbtc ze5E@0-576Y*+PItVAgN~0e)qWtXVSJE7Cb`C#q^t@loe@iz32t%bS3qvUZL-f=8o{ zBveXn9#LJ?Z>?6`Lr#`9z~f&4^q7Fk7nL6MSHxy1VR8k$BGMYmTclJDmcRWMw#Nq9 zFLoH7qwz`#tlQsqaR26~81X;6(sAKMP4dgR4E61A+vN-P@{JUj$0(X{Q%G@2lZ(}+ zTD{ZAC7Fp^88g4?W|{`>a)BMW)+Ezt&aeMdH$G~qEU~FuF7b4N#BFE_^g*&!nTdAl zH48Z{bD95Dri;czV-6^)E@uxBdZ;Y^=4k-fO z3;VxX!)I(SXr!l1T#wrl)9*=US5}~^OWIx&uk^X$#T|*1EI*}rqWtd&9J($U7CbNl zxj90I?}VB6+xv$HWY3RxMuh*SUs2J(*S-w4$9OcnHm=H&_qcuh{6qsicvJl3@l6ef zOsZkr2H%50UJtN2Z4U>O(Qo$c>f?na@qp(!kU;FhlfHNuk#9ygIsfhOjOU$!SDQP!@_GGwN=fo5kz)XWQf zcerq;-Wiyk3a-!$Wv80{l5tfs4JInfmltXkl*K5Wp0XOAnW+tPDwHM1lu3)TTREKw z(yEP3?{?|cM`Vwp%4(_mjrS7FmPmqijlSYsrL`d+{Qq1!ZJt6k{PF-~LW*soWiGJL z$3o7lPdN4Ptfu!rG@UZ5uUEuZbwr*BnRt**n6U2ECRdIw-BrL<}o3I4I)qq3Uq-(>?fR=aL2 zj2iz~?3c^=52aD=3A-{ZT^qOc5%g^K2i5d^`D)A;Rn=lK0%DE&uII0R7D}H~_3vc% zy8J-`C3EWGd~QhHnT!@A9Sa(d?910>>$THb%>NyAh@2$oYS?-0yrY3OSXCj?q-FTr z85;kko}vFbV!KOOA^K+NqwyrYD53Hdk<~9d0HYFZ3x>I^4p`dvOciU z%18%@u{iF?A5cU*n8_uzx)x57rO@R1S3kXz^J5yR@I0gH6|$h|v`bjixK7zoYD3Ik z*WPHe>FJd5cFUV=T|kH8T_%mJbXA$>cGR&ulI&f7M?B?J=26%hry0ls28VoFBF!qM zq%wMK{Z{l${XUct7>)ddN^Z89s)@=s7ObRg$i;Iv_#}|>C{Q#8i!wPcNY5DLk4G|~ z)i!9bixTT$^Za%%gA%gmN0iaTQ4Y4x16H=&gk<^=H0SS;8y*g7D#UhN+hb`Tt#5z? z3le@f(2ukwi-Q%m1X(ci?ErKwjsubRLUjsEm-Dyjlm@3#ZAkdDinq7?SQ}DrF9iAs60U^wS+LjA zR_Z@;EREJ0q1BY7DH9Vp&`lO8noDOMZbd@YH1+v#yz@>5_80d0EL1s&_XvBi3k)TD zP?`+$?J`e%FilT`@;I_YRN1V4nVLm$_QkoW3#PxqC=;_)gq)O)%DRcN zwu;3ZRlN;~-a@II|9X}L(wIU?hLO2RkQ1RG(*wEkkyhI+J9@6*jA0 z9zcHM=qXIjQPW_qa@q@K@__m*>XI?pR1#%MQ<9nliHHuXsERx{OMmrNB1f>U_U%6a z<0W*NaOMDLMLcDMfVr_9_r!jcMx&;;7$(??x>OWC;UNy>6>jqp+M5Kj1BZ56k19d{ z_X}S!_Mb=&Bb60afvOC{@Piq#k!8@c(sI`)*UGyH(5E7n>S7vdgl#FGZ~`N|Y6M={ zYkw#M4%IHGlBB>BDnl<0MiynnlwGg^Z*>iawEq!{;GpMTBCXRUHYI*Nh!W2uaA7Sz`n>&+Z zN#PN<9glO3oat0J4y1ZM;sdrDU&j9(4~~O_f%g~-Fm9yr!O-(=a8NwffU-i&zjp6~ z+)m>IVk;U3X9My#1h@`TXAeKsg>+AxG%75^T0~bGPeYJ(BhY;R@N@Qur&enZTL6Lu zU4{--f~`PT?-Ki?ZL6wK-z98#&X*8s4=jDAQei1pKp!IARqBp)z2j;aOw=~+--=Sv zt*~X2siSjBQ*sqt`BChIqLAGvaoGle43u50Z6A}#fRikBM>=J5#3@rgR^fUYBBfH+ z4KiCSNhCC!w45vgXGZ0u&z!U>o6h)HS{9t_xkUxHbw#*DM!uu#`zh(Zos>mWe&<&f zz*l0FA-KjlF&wS({a!MuYBwpq*~C^xkBt!*3WG-1oEL9zKi=LDT>UWCTdH8NBn~St zcdvi0faab3C5EFS!h=mPaE_^n&Lm{ZxdFC)k8c9ECOaYW>N?pQ*6szi6+IC4y^SZY z7@ijf>JhiEkZz|Fmv@y>3S8n9E{y>jP<`8l%g+83>P%AG64s zgv-bIEA2K}%qiL{e`xRdmM8I`fm{V#lF$vffl!2-QdGq*+EOwS>XNut*Hk$K1wBPk zhHgPk*j31cn6rpL)05=NB~AJY%pjb@brXj1nW3*QuD#`yHKHcTHK|@a^#dyC!qW!V z)2KS$lCf)FZ58pM6b{gk@1|}96w*>@QA5)X``aPHD{m|E4Q3;@GV*Ir(cAXgU+rj% zX!%0J1jHAkk^N-SE|b%N#u}X#V`XpS1Kx(3;55%pUM1sW$nbDGddJ7K8MTB!kCaMD zhp<++06%?AG7Y1#>KjnsT7reYu-)^LdLvk^GYXRfqNh?}p>$U)hZU98A3oY)hN}9x z`~Byko}srqBaS|6p^NmHSdQLC9%19RDg=fQ6UFh)M)>`GtpX$rzj%U|#7{mdj}r20 zcN!=ol74zxJhJ&+ESB@frLpDd6qk{a;pL|+N`Eg5ir0*ppYEneoj=K#Jd!^NJ3ca3 zHn3eA;xe3O$*c7*A(V!zcgpG*EQ}n_0oA)Tt%KAN4yFf#Yc&*VK@3744NtWrwnvN? zcMtb=rz>0FI0ILdT4O#Kw%)%CUZ&%*vjrRa-Z5AvpJVVMwG{=xGgQ#`j_ls!2u51< za}0FP#(&AMbiiwL|Mf6_kpPQG=)=RmG@$-DRw)wr%LqDTK!o&iNQbAYwdGX6d9EyV zmPN7zQmrX0Nc%x%X&|GGAz1w7lr*G&GHd|W-bRy zW=f`eLR=|PQkBgZVWDDODwQmi%sIkLf(VN`b#3>Wq-b)fvW!d1ew+3 zPs4OFG|K&MV$^xE`k?D!0=(}h6N7x(9*D)l1k5WiApYLd_eN!J%X= zGBRMebOF}}xjru7+7GnEg@Gavv|q~3x7U{XZrdEAP)L*r6KMb>sY0YZ3tQc!KE-Y( z9XMek20IrYX}_ja5COHPM72f?xP5nViXd7Qg9KtZ5j7v}9pI&!L`%};supxiRFR@%Q(qD8o}|U<0agn!4+&kGh6)w@L@f)xbK@olShAd%i1lQB3d2j#Dm0UIaVrxena&8L>}gvCMB61j`XoI)Yp;tM6$r%jTi=PV zww@DNaVK+W>Xu~xb-}r9FCGrJs$#-4Yecw52U6@bReB*#Anl3`nec{i+E|oQ9dMpg zh~Xt7p#wU+B`Rd3jjuntK*2{NB}R_?@OQuM+Y2AID5gejd-Ej0roG_>SFU||zVzDO znXxosS{Ql7p@BtXteAqCD-*i#o7yHu$f02_Xx&$H5}K^`GD66OS82n-c7)0sjo7(m zjqCy1;l|0YM(CaUOS+8g)_2cYe0f#<{@GK@VBhrv^I>D)yII1L4QO2%lGI(xeh=Fb zJK)FBa{UYs?qfFEJokmd2EmV;XFS40b8OCb%!b|X`(pX`^C#2kcjnZF%(#x02EHUe z8xKA&7M}*m3V61|9v7rtEuO$=!`kUH1|otv=CI#6?AIU~M-qx??7+rv?MS=-8E-I! zNFeQe`X58s7G7QsbTb$czCWmY za16L2rxrrL{B=+?);;&RX2OHa#2A79U_in+=pxoDzwfpugS(G)&Mr{{LRDkg?>tWy zU~=b}a(Q-%9%>wx_%3z_;f0oIcGe4=SR|@zO_y~@lyfTLCb~|IC#Q{a{ltff(C_S? zpowEw>>5bLlEOUH*IGjrD2wG}t%fA=UrH7_Iv1i-$0?eVZ=;xC0}9F-njA?Fr*}K^ z%dmRQplf6*rf7|li1y#m3jAIPfy{q{Q9tC-={QBw5KYp&Q7j44x}_hopwK zW23zMz{122T^7YkrsayBC@v-Jf6&KdZJK*jv~Sno-<7-y6<6&#Em9K58X6z3HQAsU8~KdH=csAOyULP=R^h0)b}W2}I6LWz z3O7-7lIpH#o?lo|gNr?-glm|(SS#a(o8cN~_T%Dn>`+2Xj zERHXF*CNJ<)o#RbV!5*M{<6mpbyYBQ^$J=is|@I2=pJl%8R|)fYC3Fr0ev+f4OJs-I7wwMWrrZ|y{$sIPQiQa0^&pPC_c&gv zbfM?HNaLYUdT6{hA0pc7iu(@pmoXZweE36ISaxUF?_;<3Gru3;0lps(^DdiVyuRG> zUhLP97xD9eYQka9aFq%}Cd(Ln4R>Fkm>A<+q8X|8@Pr_`J0SlG5Pl)(YVeaRXyd#; zUw$I70*KK+KWWd)zIWhvvReCkLWQ`oE(Yg_>TfITRpt> ztKDZ1)#(IDbEeE0dMqxRWTd!Dh=nKw6K{<^#Z5@ao4pi0Uyy%7^&Xax6q!a`gs zn9``z^+qRy;Xc}|&B?yZxRigW?YSE8UT;`q$gBjnDmhz8guWH3w?C^J2)cOMxI@^u zXn6*OGv7wf&)dd!q!qFK z`Fx)JC05Mt7ai8(R=AvPWm#r0 zd^wjhAF~Tl4SI10&(te%K{ocr=KFm9{5)@b@0*oxYkp4L!}c4w+D$K-+#7`^)zkhZ z0Qy8bB+p>5NhuPw6^gT@(}D3pVZSbZ1^ zdVdS85V(?3>#RyiHonN8I|kpU3Yb=$l|ibVh}CKlu2bcZ5;I*SMMcjqkSjAAc3&}7 z!lVm(88-?mDlt(*qo$IXt?fBiisR6bIa7|b`+8$_8zvs7QRCa;MAAsJJOPkk6x6C6 zBy$p&rgE^BGdT6>ay!+gm$|bYBn*!!2^r{g9Lwm$ln)7ZC@Tc(z=T{by(&c z7>B+c$w6kgR@0H>eGEcWW?3M3#2z@IN~qJ9;MuDn6gNvcr7^))C+KuMkJh`4)Jn+E znKEIf$ZUVTL7d7_!>&a2eoW2eG-g}u>*+>CrO+!(P)h7Lav%By9gA@Z?~?upu^TcJ zwX{}lhX&D#-D>R&+vosRU@qwek!M=9-GUS-n1hFF$z9ZDooi^%MfA>rLWW4xvO9)N z^&tG1dy_Vm7)RcDJ7FtCdIb&xyKG?ZB(?4v^iS^kOrax6iWmg9Lee^X6AWlKTI|C| ztN*SvDy+i>>;0D2yL~xp54l3ab`E_owL>u~wgLFELyFgFAwa>wc^NazkJrI!{3KcX|j_9lUy2_cEi`+>r%ypFyEXwXmt-VlFt7| zh4tFY5mk-5MuKyVp7Smrd#{uL+v9Z&pN;8`4PpNol8QC{snWsWKQHqCvKEH(qK&4* zxA*eEjbF4LHn1LdsSx(m$p?CY$M-0t@1G3Q2QM&L_%Czkr-!a_;U{%57}OdJ_a0gA?Ms^HvopD7XAAX)EoYGk7vAtf2VR$XCi&j9Jk zB$q)_lk7?1KsgO%rf@DZ&_1~x^prAvtWPNe(3`#M!f-R(G4Wnj)BVO6&4vkTdBur( zy`2npah;wjWf4~hifU<|>AGD57VEPnr$k3db3|h<3aj;{BoXm;8X3A3)oC=k7%Mf# zIKv^!%5;n9=}dz2tiZBMuEuPp0ZqYmA=hwumXK;AZ5#PnWKvQ(MN#mE z`l6e`Z;Ygz#d6gIaTlHnZ9jwk-L3bx6MZ!C_)J@-@N0_?noDFT8kPhDy z)3Q+Dq@yF4r)xJ7g^t}ML4Ymx3y!N-Fi{AlFB()2ssz?!MZ_|=w7k;bI zn`jHIizSt`1KfbE{Uv)tO5g_S4#vJxXsHHC=^;v@B_*Q?^GJRxvP!#NR=CEHjfCDw zKrN2lQus8D3IJT2I7vzg+fjelPt_=->;YFeW7_Sw`!|CAf{Q@*PRY~s1G5DNl>7La zlmN-|?xbGcktVI2N6eJ0&=i2d_eY>cOXKKc^ucaAWL3;Yxh0{~Z_0m3;%IwAgfEAW z!7h?G>)4XY`Pl#PEvkG^cEeB><&dvQgcZoRbc|NPyNEIB=vIq~bfgl8(6_XQ78~L4 zuJt>TVfdipK>*%pGWEU*UuK7^k_FNyBh9=?x#Al8XZvTjx(oUr#C`Mwv1UW#3Ezbg z+dFh+0eDL`M`$e8n6dqcd}7s7ItThIeE`MLUrpH)Pf=x|dVZg1D*bCUL5O9Ti=<9rHJovCU809@6(VEXgyE>%@SdL)wC+GA0$KzrStTI{7CpmwBV3Ilz zLbL15A-juZ&)D;;5nqF1!(XGQ`QL`&%EQXXbPcire$7d{8WYUXeH`~_6*L@W3!L}x z7m*ijfQs_D=U;oE1o#!Xl_4=%(JCB7tYzqn@QRkC2Sd{QUPEkq5XuF++UItkXdire zG0u9gSPeGAL%Tgy3=&#l6t-*kByUI)ZQPf_K|-%^1wS#T9t@tkT@pH!N;&*46*Mnt zd-<`d`Qn9r9CE`{=#m%OyA4qki^Nm~taeS0gv)@1s;VqyWA`!Cc$Z$I@9F>9rH6@+Q5N zT{y)gUS?IciKWTf8+h8o)?{K8oPovbqF!sCkkwUvt+T6rG>)4Y36~SN@`@`Q#3!#m zQvQ`dx7JXbs5P|8ID_H6hM{Sl*jZf6csgO6k|OuQ1PsB<{^h&q17kH5x;04J!7M54 z(zPSuG%tAtuXYdJCJBS5}~Q)euHh0f_$3{-OtG z$O0c6cbq5d*i*QAOAh;5fNVI6si__L-bYOijE&P~)tm}X$+@Bd(AlkQNs=#@x2=MqGaa+ry>}A=@fi zTJhwe8W0eWiOv$Tq0#pLXgYu0#L*~dV0W4*ie;Q zWHvVP8wti$1B{-U)JuKzF&KPoTao)#J{V=s=qWUao$pn>V81a38zj3Vtl4%u`-T_e zPjW)6)qXykueP)K+Ad~Tj^=xUDA$BglEAShXp%In<$U(Nciq1$rCY7ORe)sh3*wHa zKWQUetqpdUD}tRdEJ1D8hShImaZreaCwTgAf3>Cr$=GcFI_;_mX$&Vu6x~%Tp{VZT z^{hyZ{?s6Nyv7VnED>fbJlVI#9=X3_n#-SbL4(o^@* zfViuIL5-e`AR8s_GHsqHqY|Kg)|48i`|BC4)nxMH`hW$=xUCW6>$79NbN~;zcz#kK zhjJ+&{;~UX70U4!DdiZuk@D*qQyX#RB^`O zs!Ba)N9sBGX6y=Hh@IrAU+Gl{eT&ZZ*gISzz8oYHo?z}YA^;?Z^f4qCd!-`YiW~EQ zL8E5Oe$L_#jZG$tC%T+8_3iaKXYVJXMBD>~Npb;a8B@zIx?%$bL!|YkQbj{jD<|tx z5P|3tjkOeQ8V0;TmI9#2!iw3g-bRg_w6`K(7@8HVWOEfC6z}M>s5&TL7N;B4MW=;U z!Z?VI(lKvFu;9(>=H>6rX0v#q4|sEWeObJ|lp6vn4T8y`EXv!<#`x}+@}h5>;-!4e z7Uhl2^I~*7E>v!)h>z2)IKJB-Uv|wVXZ*}cw<(HSuCVCi@yN(JAK4*cg!_nSkVbwf zvNIcFxArJa8Nj2n{K#nC4isqti=~MnD}$y~i_$Sr%oXRAqP$=MM*fx^YxOd`r)5>5 zj84-F&L9NQHU1;$rlDw^<>WzrT^hKsnj9`cnBmvXv#O>Q16>vWg|R|DKw;$5D%uF- zR;ppeRbU|M)o7>GD@iaVqU$^tj^_$NGlp7|4=od$>uU(Y3-acG(xVusx}maHDd|OM z8?!r!J;h+zHx;Yp!#U_A8zekcoq<3MXU7>w=Ye*pd9!S`Nqir5Y4O}sje>oD2)kTIxZ!nAi{YL`Sh5{yN*20M z%1^INPBXe?X7O-idqLrmn5m%~4)p>eqD&VAor9!oIAIlTUXM^l-^F0r*FfJDGG5+A zsww)Epen>MtHfrz*in!OdO}A-AW6$yuOo*s+hH#fWoH=OYkx)%TD1%UsfO>2o7HtIxJrx= z9n=QVX}NAfe!fZqb{DLpX0Y{pDpm@7b{^jS5t%J z>6_Y)-ny>YSCJdt=~W)!J~Y_il`h~unUlcoxO-Oam4U4B;-Twb=n9CRyD;8~q3y%D ze}3veob4{?u%7MuAyHUQV6R~(h9dU5XM=1~pr2^@MM6C!!}94od?ulT_>HSZ&}suV z2tK3JQZSaw#6ks4ohE0dLtA1iHou6SY5%h0upL*!NRX?QPK*uFWdIXE?7!Q%6k4sE zG%ibYv{vSZBJ_BRwc--`Uf5(w@SN!N%JrOkMg=?t2l|1ur-Ay+t3-kML;*J1!PO*I z%1g?n(i0je3cZB2B+nW5%ecv2ajVpTRt>bS`8P`t5E!xWO+^TWGP?S7MAw`1OwR#d%yZbSAP|SseCu%0!>-!fsfQRB5M$QGRU5hDKi||F5x6rrL(D zBRO|9k1kTf;CDrnKM4tl42 z>8G2EK`B}+l>jqsPHHXho7(<=RjW|YfK+_}kueom^8S*x@|DFLq>`_^wud0m%6^Q> zROu@;GT6CGbx1NUF*&J}OcjWcDpiei(?;(FeqGtUz6f?slA1KD)I&8*#;Ga^!@JX$ zcBI6M`8hLatzu`V3lv_Zngq|2vWw+Ps2;GSk`Rjr*1apzufXAZ?qiRH=-*)NPQt3t zsiY;h^6$;R#6|P$(^YBwC&R||C1`_-1Z$^}ulsz@t%=Ysx7B}`5DbYh$_wM)in7u` z*}ld0?p}5T*Yyd-^IMpbumu6yZ8D(&=R^Z(U&+xu^(yo{9Yxe!%5Y4)HEjDX!$WuU zrF{18!!r!Qaw>)HzFHJ3RGKOD&hM!Q$-d7+k7A}?i{$1W0Ukh`Ge#Z^yD>`kwAeME z9H=`6lM=IOn626X*^|0{!I11KuJA+;dxKrOb$2A~)E+o+6@t5+0Tyag@~*g*EG$W; zROFyY4j!`Aa%3giQO9ub2Ay4`7%MdxsyS&Vf@{>3$SHaWqu*ld*o+5?j#e}VsNO*+ zjoPXeeUNqKb++QcJYq{W-#Jzy`_fzSWV`bg&v7SmeF`nPhNHn@zx@Q2CAGr!yS2w7 zZn`tr9}XRNcl)&MjGl=3KqKf6qubjRbLc(qA&uS>KsmFI=AEs65qf3d+?maB080mL zFuvX|SL?m9ppEyK8CC!QAOJ~3K~xH_G@xFtDPfo{XBd*Eo%MWcfcvJ}!I^6$B$X2J z)p}_x+Adda-OF_PvA>)`d&lH&P{M#H3v+N+^+;o~t*+YY8rnXtCw9%4g|KngwNpX^ zx>rNp;TRXu7%+Z%>?*CpAouM027fV+9(EsxS8$lXN^VEkOfTvRj(9S;vzd*=uB!IOuf>jO4i z{_$6vW1E6*B;pSlA`NupwI^HT$)_$qKPOiy7yTIVqSIK&gwM1}Gi07fS_v~3Q|8V+ z$44Q!y-G)as#_AA5x6c?&??cX2#S(5jDzU&lDetnz6=xuh#X4>&on^r`ei6kLofxmYD6$_Gb}tdqg$DtTt6T;8=z*R)5(CB6fE+fUl+&1 zK0Fl$yK)Ch%e)wE%0>1!c*_-lr(xuXF9!Q9Z?6z)H6OiDeQ4bH_L_mOEPM0Y;@(48 zx>Eox4GHhrcXh%&BuO;lv7>@DNUtn())?iZue_*L=6fs~{l(F16?viL$v_TZ&KtOv zl3N+GH&-!Z?gFy|Y8eop1^APQ1cmG}xkmY%jOa2d6UBFDcF{CJ$yuqvtzBjWo23TI zF`HvPS!yecWT=}-x~fR3RHlkDzNOA%AdJ$PHzHkhLc_hL49Xy{II9`cj;Zl5!fHn` zP%KCko9ZiUEsbkmTox^q9<*oVvN7%}j+*(6OK_`Q)SLS;MZjP`iy@uX>ThU-n7$Ma zih3gi-Pz%lzv{zvAg-$5~ah+Nv{0epCz!?IHAf(?3opWJ>$H;dwO)& z7A#{RVCYK_1^QugQpkrrCEFB}8TUq)9Lwm-yO@-E?hntcj8RM}KRQ%|Gmok{m_1t0 zyXRN-T%e^hAYwHlLtY#k)K*oRg5;Hm#RGWSx<-nxJa{{rUVPT9iVl(6=}+cfTRp#e zQyhoVHQSnfvzq->6O2(rPXze0_o-r}mdooiq8R^A)A{Qrj%Z{4MJA3i|D;a|PHG^Wpt;&n?|TV?-X+T1 zVAO2a8TJUDxpdpg$P~PWbQH4M)dF{CTvZAyjJ`x|=vkpSq1a8JqS!W z_&xMSthJM2SOaRsP*RM$3~oo_Dgs>vm-eYXeQ5}45Mf7^YQo-`!Dc2 zCYWP7-#!lQtnky#LbHvdqCiEI4Zgd`v>%JK=g~h1za4k8O4$y2w5Z0-8$NCq}t4Z@}m1wVwA0y8~0R7PE+&|qKoMRV)&h}2=HIr*CfBzv7 zt7jznpXz8Oswgf-CBJZ! z8j6o}n%-|nYCu)nwgv$$QC5g&DaNY|TX4#vm^FaLpG48G9bO!;D>W{YR?~egfc^H{ z@IR6&r~woJR#Xdti488<{=$$Fn)&jzSiRK5TN$1j`ab_D!Bt-|ltzY+2Fa5JIan*Q zIF8RA@=ST5@}4KgkC&5UEf?^_h0ioBVGp)rET<>N(dmuA$i!H>?jMfCY;Yx@4kO8$ zrPhMZ9*&1Y{bq<~$g7W6rD8Vf$}Th5bXRW%wasF$AZVONDq&nOP{uPoV#WOSCbEkx z3p2HHpbclGchmA$l4mB(#DTVUk+f8P^uE@m&r+n>J}%i+!}p974E66C5ZkjP^INuT zsu}i3sl0&0?x9>7cJ0~f$GDLSY-ZxV8}Z$$s)^Frcuc7p0__$Tc`ak>&4@_ojpOKs zRR`h&PuxfqTuJOlDjgvU;zA>7t`93o0}F2-yi9je_Z7*mlsb-bU-q&_A%)vL!$Fry ztE`^}*ziUQh*r}hHm&g{ae0(qv_@rg$?lM^J`(#CDibux7AO`BE0J^IJR`B{OVSe3a?6;@{PigbyfDbAx9)bFJQujp{KJv!D5M z=3kVkw?$tSI<9i!2m`Ly*O6ftA7ahRLfaTL4TkmsWm)PJvOT@uji85JaWuWZDk$^QroehSSIK!|Y#r7iQz>`{T@T*l_moopfkA3?J@h z5=^7Y`tMA5%B_dH>3a`YCKq~Yl-F>XSS-aqs~Ol}_;uR3yPgh+rUacIC;$d_4P85f zlM!dAFd11`g$-1JV{rDeUgNCd|gC){3c582L2MnG& zy@$c|>2z%*_~xX@Nz~50&h-t=zqAmZ2vVrQ5s(E>#`60CGya?CjeB(z zlF7mJS+nV<`@h79|Ilnk<<+6CSR+aKamNStW2VrzSTB8L)v2db9)m)Nt8`gA!9W)n zKy#A}T2Wl7sqE8X3S8<(I-R6;RW7MjbwOM$-|%xt)S@2rLeW=cx*5q~O%VsSX^4SX8|>Pk6Z@K+qd z$M3X0DsSZL;Eln?@ej^!HD@*|OxLfm=Aln2>mk@pYELd@!z ztXMcOi`PuqlSy((bdD9ek*KE7;g_cr{KP>biB*{V5Mzl@D$drDfgr^yj7G~?lzEQr z+G%rX=alfQ+p_jv8V+^7xkNnwQUHh!L>?_o`~}DvB{KcOPjTmJ8ynL(ybEwkk>W>3 zA-JzVYubHWUY)A7*Ixp%3=aP73)E+5E+TNq$ zN)oA^f4bp$w+71zlBT{P(X4s54l-k($yH8n7Bgce#<_FiPZcKQ2KS%8!a3DUT}h;_ zzTSL)t_g~h-?JH~76nrUsRXOR0kz#OJugj%nZCNP$^`y`^0{$E37DhFY_H}KgW&ZMUvxf?h4 z#6=sQy*}M&T+KR{*|J&+mCNzegWdKN5{)g`l~-(w4X%5Cxe@91{_m%on?LgIS_S}2 zzai0ed~fBnXYrC3Zu|>%sjRv3+Urr2gQGDNCjU|q99i~L$e3TO{p!5%B4GK8lssQ# zKPd(eox55i2dJ_*XKj>VUx`g@?5yVTLS>7#24=gF$h4IP1|mcO4hevxve__qCR?c~ z=-XjRZAZQ+SYV^7T69Rux`CoCFaV2$ z`C_-NwQx1$p495JHx`HrtFN*@O{4pLG0jEIW|uA_!>;3T@ikejjxWpApU*D_tEM(VR8p1kx|Z+s3lgZ({NjcS_B@Z!)PO}_fI48%O8 zCGnGedxjc^OO924QLTt6nBA`d^72cy!pnZ;Sy<@-VRwBT{jQk+J)Pb1Pl3QJ^|a^F zfuS?ns(roxuJ-+}mi76bnnBjPi`4TtkYovb(Igk{-=Yw>PVMR_JutQyF~U%UvjOg= z+ViCw(c9FQuT8Ba4Du&Sy%xadvZei~^gL3j_za92@=W!)F#)8?#Nrd|~5Of=*6u4ZRXd6l@azVcHB)1FCpAu zOCp!jZM#6V=c9Xpl4j77OGjRPR4QXqIh3K(T*FY*!;(~>oYD?D^8zNWeT&R9u3~o^ zd2>VI2wdpi6bQS~cvllB0V+JX9nb~mIFzVIpEd3Y-l5Cqrv&miE`#~ z&{2VWIShZ84JX05D^8A4h{wvMGeer3>4ar(&)IsNDTvx&`WHOd;PeNBke%Yl!a6Gn z`u{wgyKdro7sWr{kZmM1U_k*Aied>{2&j+}`A{I`1t>kIvPI#7W|V^F#q(GEva}yI1+@_I0~r1zaN7;v)acF0`X->oIYTCF&XqWWPf74-O!;>}7*C zmWmpO5HS2D-s*=(+6M=+`3@@A=YVH84DC-<`G-(WC8pHGZ;+d%Bo72vpfk~v{=3ke z$VryKu92a2(`nj}!oflf4sB>?yKJj>gXZdeWAH1N5~){sf8oWD;B~uLvhY-A=cgIT6t> z+6KQsd)L$Z`5O@&TjRfT5n&`(nmv z1mEE`I#2ud#ktoz_s{OH{`vQ;H&c9N&wx|fteMeM7u5lWM(k|Bd_L0?+@JlHQRxBq zlE%xu^NcU=XdOKN{Gkq{*@%JjOj0X!&i25@l%>HkevFKo9)}q_;DKsE;8Mstf_;AFbVJvZ{x>2+5({e`^*zp3hwaeNa zE9f3Q^ljtIVWiXaF;iT^r>Ylp+n`nn!X_W8XFYKOt(RrD@D2VjWpcW#l=!$T z9%~6~@Oe%D-(Z*+Ue%c|1FUodm6HQOEK^zts*!Y+Yp@&nn07Y z40(-RSAquXF%x5o5()f(e;gpuAvJ^~P#drQLVM)}2FS>zm0(4^Z+P{z;6)ua9KIiq zih&NVL)97EXCv4KkNjpzeEvFq9lfE%&eRVgqheDF{<;hex(QXIa1`4$L~LE$Mr$9Q zDi{XbOqbWan*{foZq z6E)daR&D$4$CeYA<800x;G*>`b-G)`AjbZx-CP=SA59_Os9T(+3dN?Q(xS7`C4&I6Silo+-of%nI0`_a~o6f4f5A zhdZ3XE}0TOeD}Yjr|K?W9s-|YLQL%petZRF@rJ(@bI0zSSf$(XA5M4^#?HWQB1eGp? zJeFj_vAfI;liClXX0DS6LJX>w@_6PK(vT94?nTmFJ~a<*^2;8ZupRijuIZd1HMx}o zsRpS~7ZO1dgg+?|3nEya@(;R(jP+7@P{?lEeC((nDt9MHFOnvMqLmBOSdqE>^i&!M zKTUq&MOy9X9fbX22mWg{K@t7yaRnYfKRy)>i~;3h@+hmY!TgHCB}_~cS3;=Pq!pC= z^!!Q>!!x~0#*g=}n1`i~#xqokoWqnM^oX*++MTN@Vk_(-t~%-)m_yqy-Q-;NYH-`w z4?QuWHiAo)BPo=Vj))V^S9ZquCx)F_pw(=nOWX32YcPD#{+LqVadKj^+|?0dY5Bm>a&-x#X677ucS$}khOkVQ z)v;wa-#3J_0KKHVKvTQ4X_Bm_m)NoD$Z52Axz;iuD#e zW!DHU1-+TdlfJ9QgsY0y5Rq0FLo8hw4kSsK0|_$ZF>*=`^&P=#wIYrqMNO*2$ZnXW zo;!mkItzT{B)|=%)psP?OK9|WX`yUSD4hZvM3GWy@eHxEvbXdf=U|L))xe6@Q>|LY zseR-sg#)GS8QKn1ODIvbeLmvOV`777%FtKIvOwaNwta@Q!By>wHHD!yV}5csK*+rg3xRIVTJK1 zCUpv0e3Vj3t%Z_I;rvBwCHkw1L`K}SDpbR3RmoBm`mW@N>2hVa)pzZH(qQAlL%(`g zX+x-*h~uyl6Arzla$T?0jF^#T z0l{xC_<f@qRD?s}u&K<-Gk zqnVO8&ZwO4`Ua(E16XeNFjCGHtw*!pKWPa5`wm^S;qJc>vc|zdI)}r(_BGZvc z-@7gsW#^7BV|k5W5MyOmW>S&5pnPbA+KzInZi+gk&v&d4tfbcA+NquG`1lzy?quxP z6rY)(gkE-BNi};(17xFY+8`QQlntY5D%RO_lJle(ry^nI3{)8gpPEVcvC7Mxk-ptT zb@lLJqmcWZVaduMt2tdxgkl*+Qv9MjB$a}XYCZaZ$*xGRqF({Z-0hT^WzV=fJ)ia;6PbH) zOcl?khIDD3U$W!YAa9{HFnO8mgzbXdpj$y-&%5qabgZ=1Q-}__R5nMExIW~@8I3wc zc^HoF>||!&H5jwTvXx9 zW&?7|#P|~etW~aob4`xgxTX>_%C+F&?lrEZ`jWa@V5zC;5$+;a_G`GyE4o&PF#QWm zwI!XpvDPT9Z#9OQQYy!8J}f~Z);#;MzTF_#_7~bs!;ziIs&FKYosb#lajaHsMANE$ z(4sitS0Tkh4EQ$C4isw@f4|+RC4&$Ll656o?`F=Rixk?hEhCpIiw3Emxp(u;){sUA zIdx;F&T>Vh#C&K(YTKzmpmH137hx!+`b9;;d?0jyI zoV6!ok~cI@e%2nC#=-3$gKad>LfY+CFlS>IvEqxYE_kj^Rr9ua?Kw+}|}*})IP+V_rR zTX&tGo!R3Vq4S6`2KcYKjmYJ=W7JGxp<(XhfFbpRlU@xwLj&rQdV_~QHDey4*P;&T z9ysRv2m1=Aue`yA-uBfJ-|q=GvEi^d@{%dD3!Su^ptDWO z_up85pcK^m)=3~eRiN-^!#mdxZ@NgIh)M!wznmD;`53h=<9rdKP12 z$b+J3Ksn4LN~!Mvw~k`8d1bV8{P1m zJ+Q1%JVFa$fV}$5kA*hYa`YN*t{QvYT49%;hTc`iAV6blXB<|Y!_oe)xKb%Tqu)?- z--rMJAOJ~3K~#CUFSO(3N~K#0LYYU4*;aYbM7XFaL_*Ij+muu~xL~MrgivLD2uQo6%t*cJN&mmO)vLN=srX)ptU1W4CLOvq;Nk>9r(Pj>*x& zOe~S4!Kqfpxk9t}+!+?xhb+8xCtwGZz1STq7JL(`qpp-&_s$sD0;{aLZxu)=(&=cjzZ>c5QztWFY+7 z3Hn7oF|-Bl6F@L=QG8zZn__>LR|+QDmh%i!hJ3v+;Og z40y67cVj!4tLFF5X#Qt1G1yhi)rfqnxjevz#iL)Wc(MJS=LnxW#*i1paEu6TJ|n;y zDROebX82t?XVNv!*nc0+KMY?7cY{6*xN~OeY)^PN8!`Sq==>tAQpR9ov3Gp~*nwep z|4h0S$2hs3B>IjV*kTvHqkKUvM@*eheXWLv5B;CRB^AK%U}Vfg0GeIzX}P?^(yLS~ z)X_gqo%^9Zk{VzH(Tt>r>SiFM^3-Q={X#-CimdzP%eO>|c2{5RE8AQjsjh3>rVr^$ zm#gaL^kwb`itP%QE9jdP(;iT(^(^e(|u=^Ogzo^bYUT^SAJUD9JDIVD`XRw5!OTN1m0EpzS_`;-39-vc@i1+>+kFjsy;t0|l{? z%s{|iEZlV-1JW#e0ZSJCV7;~wLR>1c>}^%5akxurvqr@rWgY~s;6u`@K>Ob=F&exr z8B||Lyb8J(5;mkzwx5L^2-Zym8+fQ}7~{dpg0@RY7<5#}BEPrZKv|UBrlpo!PH*Z+ z)eF)lGpCNazWV^EfLB@2?ruf2GT5fq#8)RFQIdI}SE3}>Q1+o%YOIKHZP))NkmB}G z;gq$Pffq{Wy08?C_VCBu&0yt)a8{au`3%Xad$kn87hquN@2AuYXtL zTCgV62!~zQ|0{QJsA>m4aIJ&nO>;5ce4F*OBny(s}wtYrV+x$YqVsya4o(F zs#9fXv0mmGyT88R*!Pr=1(DT(`7WTyZAY0Ktw#zLV)aX(pu&di0j>1fwx`qjXNO^L zt1YcPDpeJ50@=j|6(&Inc_m{iB^|J>+Cq}KLKPl`5>vO7`(ZF0LQg%mzNws?spq%T z#KAi5Bu}-2yT6{yP%h3Y0RfH4s;&s9F;=Ctttb!UtlKMz(5}PC4q}kFHNf5w)`4qC zfmm#fLH#Y<8?9H1*5l`-{g(-}Fqr435<8156A5kqs*kPlUZ&mY2R~xlmUgaBVst_ zw=j-(gIXe>7YiDIM}Hm%vjxqBY=9q;T@B7N*1XE!aJXxrd%k--|G1SUy;FB&z^d41 zrCssY9mw5rb7c52SI1jmtb=YxxjvA^N8i>I%lxJv26tjQ=EexV3`*NRS$U5SP@i!LywEGWsG zq%bz$cRAUrFe!4fSp(awu}6^a+++uBe6tI^c6Kf%tiLI%y}>~vUhIk&^4chD;YtXL zA|knwItFA(jbfmiLy5U&TIhi*34@#JK-)rLG9Z*zH^`$|r-MFXVft7R# z#XZ7~0o}qKitcQh8B3>9gT=bIFlw(L-qe#d`x|W37AjKxXCT zqKM|prKx#Le)&zoFWDS*p%ARHw(lvtq9Rf&;~M(POq%qmnxtp@4M$BwpGK7-7~rjg zb`KqM9t$^7(8H8*7qJ({CtL?g_z>jTHQhxVxDJ|<(G9RnO-R=bpvyp#>EIHn06_|_ zi+Hat1~bAVxvG>D8T}Q3l!oIBs9lAKn+m(CurA41nTi2pnnfZFr*Ed+Ja&-GGt}dU z%P(UEtZ1ul76v!;BS~88SmlT)PZAe#`~{coI$M#e^NkTw1E?+(8U>a!`RYJKx-<3i zG$7Y>i_Qa-%i8}!js=#nqBKw@%cdlfs^CenTxDUn=qr^G5?iUWK`4ERFD*5AZ5Q}) zlESZ5-r(!`db-41Y;T!kZ@%0nccY)xlGcmMe~*|x+)NrMw_Eseg~1*xX`cmaOxTnG z`E>`W#&SeB2E%Dzg$>*Q!fx6mZ*A;F?Ht?^5^a1JJ(u)Z9$Q)ee@vZEPa10*#$Q0D z!w^vzhXo|WFbNPMG&v>FOj%%UyU=%mUDVNZ;e-WANsZwotoQ=1T$suiaN$QdtFBJJ z*L(l2hja3RBFv!D%FOlL_kI1rWeXFke6?Dj*c4q^T4KdGP{ls)YY*0Iv9An=+wJy~$M#WUXi(dNt<@$9m~t4iN($XI zX~GSMzKw>wCJm0Q-X#VY+EuyPEVl&6hO&)Xa|Hks_G>Vo%e0wm#4EVi1t`tU!)wiR?FTpao5xL;zd(Uob9sa~LAwnM ze+_qxt3*V49Mc<#1`96#2n}!;<<*Dg z$VM1haVC4R&ec(`q&L|?`+kY|V9tv0O{VFsonz)!Bm4?5pu~453R8S1OHy%gstn?S zB56W#XG+czK}c&QEVjQrxHKjCXmJ9kX0c6xtkfuYD8;v7$_c#`TDkfthf2I5Vk?Bl z;`WO4B8kQq%PHaPMmXu!bTM%7FnQPS6y6y%+R*J6v>Hs?9z32>-2xe z3!oIdqe9&lx?{vekgUcSV4Xai*#mh^lG6azA_}gbEl?aGBDPxBpmRB2D*kA4B!$uh zPiM+hrnz$buw9GEazO?Y&KqOwr!_3L*Swg|>koD8Bk{zF2?dUw@pZ5F&>OQPiQzjF zy$HqGb)@H$676MVM6XcJdJm7z`D%i!2*-{R$w!YOKi}$~P0A6g5TyZ&|3-i$-G_(* z8JB1K&%Y(HkS{$lC`(EiW`+O(oj;+=u!_=oFM#80f6jESXe9JY2)%nSp+m#@XdV-8 zhU@j2wIOhbIV?^Ga@$RhRgulPhCFLubNYZ)w z(MiHD&dm(IHU72VHp3qp`)1M;4SbU=rCHpos{ABvKi*pY)JpLzCp^yVRqR01LLE#= zt(*oyF54tR!W}EgcJj}1;h;NR$z;xf8eXNeWS ziNPmb)8UedR0gE5q78!5cqL0p57hP8_#&KrF|3vXsR{ZXbKTbz*q(9xAKtC@hSd9a zs-BRoJ*yQhEi0PCFc;p;2u%uTIfaTo;`sE#yc$g#CQZeBw4D&;o$jb7H>*IcJ=bQF zja8uG)@|StVvq}gr%Z?$sfDm@1h*s|DauW;sy)O>kAa$vR>;_C`caBcE0l_|Aw=O) z-pgMI>;EOg%L{=`v3cx|X7DJa$r;@qz-F zos&7RHF;&|X|NVkLG};@qvA23vu8y1x$Hs0LYO;Q%qR6__n|)S9@Vj)5{21{-;;Yo z+4uJ+$|5{ExhDYW4F3(f&W7Yi_qO{CDe>8uZ*j>;%ety&L;W-Hn(NXV*NHk(AmJ+m z;3WpsG{Gls?7ZN$9`%Cq^~K%A>FMeD#rehV`R@7o?w2oD*I%w~uCBg(yZLr}eDw{= zz_G}A5CY5ltO~ugtut$lwpYfj)z-O58;dzR)c(c`hedGTP6tG(*|}jhO<1VsP?YN| zRLm7~h6KM1Y3zhw)%m|z*h*EcV3ltpe_tj4DOk_m3NBaxa$OkzmC9z4#6cNir~(xw zo(IZ{R)RF?521ubSTx%zjES#i95Ab_*eu45tW4V&QEwKX<=$5Zx}gSDtgY!L=s9G1VysHi4``ek#i_rE1+p*xqwz>_b(}ledji* z2qoEhsMl<$I3?hy=)9W6k!EvV`kz2{l#1>x6spe9gKlvs64h+ui;t~JSSlkI)8gd3 z&dEaxV&{_OozKPTa@1m1WoAXJ?a45}w90v!bHr(@b)S_UOheh~o;n+wDs#pW8HWzCvKNEx`*4t)WLqCBkV_rz1HKQH5xOR2leb*tzntYdabLhN_RC zKy$_nyS+!dZzs9A?TM@$>fKraliJVyCs{U(F&yU61Z5H?Su#qLDPr91rnhpE(EPWK z4W&~hQSB}0juL4*iA#$T&QKJCuU7BQ7n1Y5F0oZ!xT$FusH-1!Ut_CuRUlKPE}c8{ z(Q>??gM2c+KYRb)5cuf*2{rHQ{fSWdWP;ljrLL8oXRlaN8rajbw(Vy`Aj#qb64t$o zXLt|^Y$+`6j*n16*(+R*Q7NC*^XARo-k#mxJJ9uyy@LZD zAM9z1U37DB@NWC5Tkd>3c(=WL)D4$+?&ibCe=i^Y@ACb__wR2%*!At(?{<&N58eFu z@!zjMxPJb@&F8OQKVM#cy}Z1}0UlDxjT`L=&^y>HiMjgbo}ot{e&tHIE)L$}r%dT1RuqERM}I<^`| zUfJKFuht<*rsHB_Iu#L9gX#3ypV}&}r+0xZ)>!$)Ft828Q+ubSU1byFU`--5O=*Y> zB0xi`j^q`|I#Rvu@G*4dE&(JEi$zB?AdQ^kvjA8YS)oD-RZ(kNoJR7&kb1a;;+L9Q zcFZsw3uK-YQ2R!}A*c<@D{$@}iaauK4(T*Im<;LoI-5#nvPh9Jiq01zCI9M`xe&r_ zx69uq{tDJv2mFt&v-wGD-NJbJ5c!Cd4axu$LLdP`_(&>=4P}6!9kdM47_}!INEnb{ zP-7D&hlz?&XPze8u0jOM}dKVw1BY& zEoh9Ob>_I-o$1Z_!U3RmM29;bl@AtK67jGgJM01zDiXl1ZGDl3W!u0Lsno3)l4d`P^~CDq3_GnC@u>XLZ6W9P$yyc3JIx%&Z^S)DQh28olsrLpHxaGOB~M_j z8XbtU7)~9??v{(gigO!Csqj^JDluzT@G=CZ@R9HQ*d_YfdkTSw8r3UTnz`9U$F=xU zc3oR2lx4+{DzCtCrF=O!>>v+uc}Fr@z|tQwtkuhiK%G1Pl{_5iDx(yRh^s>fR*a!T z__vr=(y}aH9ct)VIwK+%CY7^vQp&(t$At}~OC$}9+ehP)JSa=;LR%7Ht9Q>RKg%W8 z=2idMr4V({8hvf2t3)52zA==2-FtmP$Y5H6BN7OE?cS+@YVWlASK7I8XxMAjF|uJa zNvG8_+gEbsuEB4oeF!U>*|F^|_4v{7 z*B-H1e7f6p4;Odsfo|@}?&1sXpLXh@p6U&5FWVQpyH96vhdiHb_xbehPjKIhuk^D0 zC@;C^;j&vFJnw(`idBP_1nwtae)X>v!oMG_{oby*?b`D5YJoMv8ta6$Uu%Z0Zr!fd z3!4*elS!9Vf~^zWQla0NaQ8M5_<7sDI6uF*u1KT!BXUORZwL)kw)zn6&RLWx{6mRJvEv!NPm_UwFhUPH@K&(?}Dh%xixFgDEo zQ?F(7w?&b9hLwDl^2cvgji-ySF5JQ4ZP3>;P{G5g7zqAk66)PWiM*40JoTDJx`vpH zHN(zgIp{;Hqdv5j_%7`Tm8}S$P(K6SQ*shrHsnN%k%xZ&&mS5S6Dq6@ouBa+c}hXM zK;gw4_z@1v(h{RAC@TIDIY-f7m95`dTKdJ>@{z0BLig*FsyM6y*{a{Di*q3F7jZ4q z;kZjr^2Y~OcEd)+9oichz>dI3|6M#Blxt<2neD)@;9XD?Xb-j=30gUa!1|qtRSG7e zcnzZ@@&ll^Op1eKBzX>U?Kd)rYmDpHX`MBe(tUq=;(o!t62KaQ(sh#im3=VupFOH% z_{@q*;x{BSX|F}Na7$j5@S9tZv9NxQ*ZrC*+hI}V28@0*K9ZHJOJHyulYuke2`dF{A?}2~Tnp?R zEZ|p=7e(w^5>WRJdjyd_VX+*Lh%N#sMA3-)&dyy3XvS;k5M!*AlZ;?62?N!TdMqi^ z*os@btl6PRiNtnY`7g3fr&6+WDT%NgLF~f3(BSz<6|A?2eOC1+1XpO-k8of+rK7*E@NaR+n@cg*6|8eJ!{hg)vR+w6Gdc5&zkgz}E-nko z9d7HvtLN3k?(;tFdGWks@%Pbgq45O!Y~9^UtqPX+ilvQ4;$AqbZ@0a_cepFqy%+Ry zcgffN{mDrc!oOO}(TF&RPI4r&v%RFe5~mK1Xn$bA#gyQf6^&5E!f-weqzb2>&mX>h zvyad2ZNr1}hx2nDo!jPuJ6j*v=A1PGk1sw~68lU2Zo_`-%ai`*=Cs?lWyWT=Kk4^3 z8=H-_NrPYcWYV{F%5<{UolNY>beSc|w7cA}m-uidbT8~Pu|>(IeQ@11x7*HOpI)E6 z{Y^XA-rSw^yOTB6EDhe*pLXpdx6@C$)5c`4@%HV+KKzOOWv~a+x7%;Gx2Mxj+k1`U zP#nK5ZR;`LcBUWov2U{m#4X{r$h+ZS61ZCm#Pu z*x$GhANF^4c5;dQA2AVMR&N;L!Jy6F*OYp-R^@gWuY)YZqLqNiYLV;=F=QP0?vMy6bvNF+rQ&5+Oeu?J zMvE1P=)`fQ*x0HhFtB1aJO~ppEXyvs*g@GlhwsFqa=d2(2@wX5?goavqo8-^ljc{c z32~9PKjxTiap(|HDcJ3U#GOByh0if(zAzZdL572m!j@@~DDatvY4z z&=8hVINz)|2*&NXnIASOhYfG(Fk{ToEM~8z2j-*7Gas%Ev8JTyoXLi=P_^=z8oaCP zOmm(|=9~1KNkqyv=Xp`Fnv8@EXlr2bJVQERJ~PjJ56x80LeX*-l!OG!S27DjYpz0< zcZODPzSC6BB~c`W80K1G8=EC(IcU?l+-e2`ED4lit2cC-*X0LoIBFF%s$s^#Onq}Y zoXVKZdeQ(nlzY^RB0m$N5o}@5w11=@EclO}q#rg<~`W!GZN?JnC7YJBo%= zGHSbmOxh4wwI`%4efYhC}*) zd|m5Lnpqx3KoAXz+?uFk5Dc)^YBFBR;#-4Ki?N0gV?jr2Wym6UDdL7E-7%Y(G;z$D z7(%Lvna&5d$@;;#HnE#p&3xMZwExupp68%rXLk3BIG2Z+6pnu0Nd0kk_jvsl9O0H0AqUUoQvM=yA5ckEMhKY-rTgE+vCp8 zUQm?|p$32@zjREyl+qVu5M2y{GwE6pY_ReeE@v3AE(Chzogdo1I6p3z)r);puD;gT zAFCJqb~{!LuldJ~zb!gFuS|2Pg@x2Y$~M+N@{&itQ7EMpBBZ-Nz zk+CPK$v-AXp31B6^5xU@^~Cy1^*Z!UCLd3(AX1PJ_?(pG)5?0^$|zg~Ng%em znYmXg#bPr#8OY&Gmy5;ZBp1tOb2)6eoQz6CFP6>8NGw~5>9UwB$yG57W-%cr^K!Y4 zccN1&;r3-&Dozz1U9Hg_4jSgQoxUt<>-Dbpb3FrvsP+~q$= zKQPk7mHDo8zsz@0{PzKo_kn;lB^Lmsa`b|%BP}*_zu<2VgpFVcLyDnaz_$fj3>8!< zA=2yZ_f}9H3_>iySpahj$SL8BZuj;yP_3{*`VAn0Zs@O2@z-njs`6mz+2NN~Rlxnw zU|{jlR!hrUBtkcswiFFzi`VpbM0>#xO|e0cM0+551hQxu2MMK(jL`sT!DO45y#m6f zw|3=kZt$Rz7{Ojlqa+wMZEGv+VL3;H7Y1*G%>)(>I|YwC=M;CchdW9n210BZ7NEJM{Y6d0(~$GUo@H>g*tX9xl@Xe^^Y zt7;06b66Zxij5wOdN6q%6iRil>VZr^hT2)sLc8i+K?KMwwLSdIfB4aaCSsyL0*Xr9F!-)HV!Ny5WMdTECn?IU&N286K?^5 zF({Xi4J~kvNU&T1>LnQry5WKLeF}n2F;E+bSTR=>MNX8;?rMO#2df&gn^8Tx zNsar})#xUxeLz>~-dv4rx}nR9yyH#ePn|@xq0p{CZ3uw65e*GRx=|Ah9;^VOyQl<4 zwGqmcs5K~7Ee+&olzCO4>DUCpC3CDaM1!NzU5)m11jLb0k%(xdqYlynwy$iL@4)OA z!24hNznzN5<2MuWI~T-%eMf!}7pjXf80Wn_+>YMf9OoSGiRW*hIzE_>bE zz^A}5k1O+o`7eJ>87+UYeo(zK*9r=^%2gCoxK+h3L9HuUEntOk4(R$UtA$HhCR~2L zyt=x){QU95X=rXD*gxO9b9TyhcE%lA^;k7cm30dHwA$X_{Y)NJ3q^|z%sV7|2DQPU zM$AMhemJO9SXFxfkrvV@^!2WHr$=j@kA@$y4R>_D81C$R)FG#G93CES>lp6n7?$2w zk2>Y>;>C-$&f%|)x7(Yt30GiM{{I$t#Mg~QCDgl+ciyd5ZV@-sMTQVjamzbD7}YjE z$$NQO+YAIY@p;*p_3bWemgW8Zlc2oC<>Nr2oFy$#>k0(*0n~LHe30m_JwS-a0KF&X zL)R>$ju(cV!T&G6e4!ZY{+TuyySfa<45V|!DBbe%8aelhwfEJ~%XVPP6W7r&D0tS(*XL-_w}^!1J=p5!ADQ zZ~$|5etteXzlfcjE-o%&%P#)^w(hSX6LgJWE4ZNH4z6oFfSWyItTVv9t*ESwpv9VM zWQ=!8U@&7y1B-#KdZSDLltEQpgUqZnT-CIUDZG#ghi@c)l}Ljg+6=e^`O#rW6E>%( zSU3!zZ$6}^Ffyewd|R}eYO_%AuH#PaR;x5#meVo5zf-+rhq^b6hsQ3apd zQNbkLhDrregeFuLd0_%05vzg>s|WNiBfYA{4lb-MfzvGzLj!x?%9DW%+9Wovss^Um z5jBq(;B6(%6;htTY$-sfg@q02|zV|>62?jEBhCMp4 z$LJ3aDGAnSaMbAuqa=r}q5dV(vJOdx!?>_OYomch{02p$L%Afd+SO4&hAQFo71R9& z1qTZ+WTm9RrDv^$AZ)#2;3bVEA=st#+GZUN!B8;^f?!XOZ?0t|p}HJPDE*|~0!TQ> z^6cX?SQJqbYlIyU7M}>p)~d1=)Egl?27HFpdIjUglAv)A#EC)6r-0H~*eBT{6Rtpt zY!TCHIkFELMkYY}BHEHK*o}f5>i2 z!Lb3=!Hpqm08?@hp65`sTML1dGU`5I#Sdmqry{0+V>yGZ=Wc&sIe}%MP%nrtXgTwy=t_SbH?Jr~T zyWk!FV(=Dg^SmdI2SHb$wF=Zcp@*^^m3)-cOaX={1;QD>I-8aRxZ)B|aIU3%px2J!)zP`BTc5!`i z!R@x4@~3(@y=iZPR81hFTBw**rF~-~-SjLowwQheHXEi~gEgIbTn>Y8=d$>yt>gav zwm-aR8~CnmyltRuVBo%NX!pm*$De=qd>rlh!1(y@$Da+1KYR9<^KFNJYswcX6!!iN zzxW>f<9mBMa38!wz(Ly3-n&9Hv=<8P70@q88^Sge>fYPi2o<^u(Ly0KG!%6gqywgM z$ac9SfsGAhENIaJ5*cJMsMJPeK^XN3ipyuEu2Gq(U%;cso<&MkOs3qN{N({na!%K9{s z1O&Ijd_m?DyfHxA#*C3V49zSU&Ik@?klRP;1wd-JF%!=Ghpp@TNh{BzT9Fk0|Pqs0N%n`WzT zO8vm0WPmbQtZ$A+!F1E~Jqm~bvlhWi)vTmq%&90qnmtJYH6|q`678j)Rfzf;q_|GN zuQSaO=s@5@6C+JFEd^dXRd>b8E9Yxq_^!9<-DR!wu1pC9&LFQp34DVg<%5BMOTc4fNOTrJ;GhPQT|b0*Yrrrc!rf&cB7i5*qoY< zKw{;->XPM*+Z_`!yTfeN#01O))deMH|B-vkB`IGU%b#PS!l2N$IHd$_70Mog)!K5@ zJFK`EcEvSIx8SO#5*Z&mbcw6~3Wq=YObEV>L)gM!dY zn?5RX;KQU~05=xjFHqbf&o-eNFE7R#i;X&L+P=7Za}q?K&5$XIpp7GH~>2(aO& zpAlLEs8usiy(Pod;w{jcX`|z+NOiF|8a6m>=&(U<1HEQkNQ?72K^G?iVL+*Xe8-?K z{~3fO$QnF0*h{E2$g8uG87h_PrJeT6jg~!ndU>I*A^#0^8+{RzFGs*UyaVR5vjZ#* zr;IhQ`j(jf-B1XKk>?4@oRbmTB;-mDFdk}@Hrja9LBI6Cx90P$uKCs;_Nie{reTKraGT9=P%T>1eT!3CPRBu6we4P-1p^e0`m9Viq?ul?#9b0B^H|8mO$$F(Dj)e#oo$ zRK>+ev4tPhv`fe`Pdq-)KH+;{+7{MegCidTNy(nKEy8sC1V@-r9=Bx2vzF;7&6b4B zvxhW4V$;$z3$xgT1af>>p0&)+XH$n|(%)=K+26xt3RIW&gMii%9R}`3iOWfF1b5`gJq_H)0Eqw%tk1{`sa5vB*dg>AmvRZ17@5(!j7~f8FD09W8#olB`ty} zx$(}y(kcd}19= zy6g=YSq?ME?fsn9`X1~S6XqOFC4(JI{?c~=ESa`}z)L=vV-7Gp$0FxB1EvIEIy7W5 zYzyYGWF|2I#5be3bkM3HPMw)~rXX}PGsDhc88I}a5IrVw)hRX4Z<{{(k@b;%;)pOS zGs2&z49%UC12^S$XzU5j%vPjHN#)V(2p=C*kDpZYgH2tB45iV8fjM4ToO5|kGJ~{=R~8F4>D{wx%g$i5OIm@Gtn~zo*sz1`;(4y(R3B2_cY}VwLZ8$Ff%umF)dk*tNH4kgQ=R0jo2JOvYFlM*>_0|)s+fnE&qLdsF| zYK3siLgvOYEs(AXD#0S@Ezp!O=NUOOU{7&rU@)eNbmY0QRGU+Bl~a!zerwdNuF;ff zAK!967W-~;X@r%(7Gdr^dcL`71%fs<4{-W!tY2Ju^XDEfT}L0Ef5Ol^G##kmycWd*}dT%{QeSw?|^tXBF6@X_bM*KZCxsFa4E`+x5Jdn^a6v+ zjYKvmjS)6l(X?~08Tahm*-~UJ@;2g+yj{h?YGjpB=e3A$;Q@HD&*xkC4^a6b?tMUH z05f*J_T{3@6EEyt7fYpx-(T`aBK}p}BKY$A6aL7W-_QHRTRbi9vBpSzqj~;Fy@dO3 z{5VgPN{Q8ke+>`eCA=hwQUVXcBkOgI`SI)=EG6oRV#&`VY*@0Cc)!CvcGVr8;k)cq z{Z;eY;=iL^suy<>^`#xIj&Qz|s544YZI`res`I~p=XROL)fyhLRBgA5RsCTURiV&s zkN#3jZd_-#wFu^r3G;5J-MuSNQ1(IT@*e;Cuyt|Y>GrNUblt@QrK^I4Yh@s?AQ@b9 zWzruE`Z(Y+1uK$^i@`;oi<7|sYZI=@2E&uB-#vd4VmqfGcYE82d(ch^xT+ymSuuV* zHN75P2k>R-G{`XWJdu*{n*}9b7w}rLm_-4rBV~Lg%msKRLaU-`TFp&(TElZKY9!7Q z!LzKIRt1(^23ayz&RPyFN7-q^how#_Q$n!Y`D~Q6(PG3bd@h^bUsIKq%_`eVE$HaH zB}pu2drSoUMn4uSc~<+$v`!ADAfhbc3@1)uoubd4YK%(Rt$0_3_1y)Gy~2A zRZxY&_fDDzV;)E_)4}vdnwbm!#4g`wGGNG1A38|sEHYgds&b#PGT$r4n~?`$@EK+q zy#;K|F$u>|Tt-GDD&SKip4tJ}!e^@a**i!Zk_r2$Hd<~A(==F-Qk`8N854F%|L_xq zj!4qSbx-_kWbP)6bOGzC*fpf`EeahdCp?ndB?7xCq99eln9E(ES|F}%O&aHhIIEgv zp^jB41^pR)j@u@f+9inEsK{iKe{9?a#GRzN6~H#XK{XEB)&}kO!tRPZ7%EpkvR2EM zr*@+1v~VavC}};p=(NBf^J!&^`ixuoJmb;vty~QUiZjO=O7JdvPQ!9KV5bqTf`77L z>J)40Tznt63+%-u5ZA?(!YfududH}pD z9HZDIo`4BF2C_Y5)GG9fG0jYb$4L#)A7Aw38(}UA;%$kDo12f{6pOt-e*5Byqch^Mqv*1UG#A^Ur(cf!=F2aJXODmT_=|sEw##9X z=#JyNuOB@+XrDMfVp{KL&wS)wEO!OAd?cZEM^6cOZ5t34>b6DG`rT^xqBrRE>iC`i z%h&n+q#t@22AeauH01qiPIWx4O*x2df%>rf@JGR{gL{g-sT6dy1$D1Z5 zrb&}Y7HdMXUU+uV3$tm`CR2O4^M9Ss>;1*E^<+8N3Oqi)pqAJ3{(e87_gfI|SNJft zd$HI)&*5*qKd2y=HST<+g3-PWr+|Hy8%GSv?>G1M$4ejn;`YvcABx}q8Jj-YbeRrG zVmj@&zY~c#v#g{mfF4hdy8C9>ttFc&<(dQn;XrEdbj$dd^*v*oaS=uuKz)ch?|Zr( z9Ps_#{QN!d^UvY)*8Bb1-QwLh14E*1nH`dM-nMKz@V4Qw2TeWu>w``n+0wS}`wd&! z_ic4s+|IJbLBsR4e%6R>%MQfh20P@O46ybC1G258t=vv+cbu&~wY?gw+n%SLvedTi z@pIp6H+VtqMz*JO_3b>_5hvx@Tc7pZF1apXDQD^q>~lblstW>+%1w_rw*zgL)w{>p z>dK*E$Mc6L+?e;>soBfZ8Twp5*bnSV!|&MzNRPLgSLo}7>0f~h4o~Ni)d9J-;2_za zZPVZT*Y!B2&})-43Rg$R)^O#*#)IZvYM=>M8dDsSiB%X#I$?0l)jzLIVBtY2^NK0w ziJ-J0L3vgNP3FEX(ZCdQ zDZn%WPs$Ffq_74idxI`6n4m(!7mUC8--DBQU}0iu%C}17Z%OQ>37E<(!)r-tNVaG? zKlgh+N3)R$<$Rf$T@nfND#5a+FqRA?8D_~F%f9k0MIx1rva*EEsm2*5n|^h1gt;_# zboqv+cTFsZ)XA^8V(xbT8KNi2$V_n-_Xgp^=&npR(iCMScB5n+p>C;xR)dkOIIzOX z+(_eHWmTSzB5TBpj4SnIEUD>T#S@MX15qRD(+? ztJsPNo+3~-M6Vhwe~`CAtyp|pEOrdF3wR1I6q-$A=7NE_Pz%>ovPIU>TU&9aHp5D_ zrv)_yEiAlzTIeXXfO_NapB5#97YGVwvY4=7&El#rm-*X8=li@#>k;f-v?YrSKI3?G zXK|CrBRYbo7T?xx3e!((*mOL9s^~(+6+Smf{gNaFJBktw3wIVM_`?5+CF(ye=n;iq zg|+*q|7SM$bbG_#WaKSe`hmetW69sruD0vzr?3R%#m?kFI^YasKM@ z7f+r%dpCG;-y}}=^t1JmPp<|0!AG06(*EN(D-TN7)=#>_?dn58+^r1B>*jQA!HZ8v zMz*hC`*{$>H{`3+i;Y(RcM!Yv^~T2R;Fs@C47mMdvEMUA_RGVsOXoc&h|$LGzVQc$ z-C#7DuDieg;_m$yf5_iIk3Ro-ZupNc-F^yl;W?v;n8-wG+}YUZ|A549Wax(;8KxMG z%cDvSN&&n4JgL~{dt=LY>T;+tvqBA!m#{S;n@aXP|KiP0uQqFY1Eed2^F=`+ zH`~6VkK#KMx(7$?P>39>0O;r7M!&`y_y5zQPAU6aj5`mMbm806aKjrYKVe%e!Z;e_TfP| zu04V5x=P5pHwR@dq2G|q*R@2WEldyT$!WlI?W*ky$q7LK03ZNKL_t*RYC`XB7HvO- zIu|~^fXmx4+?0Jna$Zf3A9IS`v!m%iby79R}+cXCV!)c_+w2=9OLVZO=U>1O(f*g zf$U9CH66NfC=EPKgKvhWUktJiLmA?IGnpvk&+#3~uAugzu{o2b9$Ly73ux1{x8)Q~ zfmKLNN+d00NKuMsO!CHeXw@`*Ef?s_L-K)*=MNZn&S>NrA1q3*AB+Sh?RSDws~9~< zq>eD{JE2l%1&IZ4i;avDdNRIpgi%&XU=CpI9+9tLM8JDDe>1ByKVXM$e2prx3qQ$y#czOe~u^{;e=W2%e^bJA~p< zVl`!eHgm!*|P@+h?YLmp(O${gQ)9Pf9xF0Oxh+}-NE zd-mk3?a%1jop*zptb>1D4N*Kle&TR%QN?)Mx8`6&L7bw!j z2Tp(6`!laYHl$=BrPs4}%gMahiX47?6&nUl68W)tz-Lc zEC0kk^He{j#3PV8Dc_DY8i0+pE5S9DG`}`tjwwAb7AvjMsMJ!&@0cP4G1E}cplmzF zWO)@Vtr@(Jz%Ct0%J!w03)7BjP*z#3*o3rjklZ7sFHF2v&vH!OmI^TpPEuG+D1+%; zBXux1i^E2+mB$=Q-d8~)4_h!bSVi^PZIhjhcdZzW*U;FLp!)m zGVRNE(i)h{Jq%HLnKDSqFXxKR}8pj{13_5;$WQ7S|`-KSv7J&> zNE;kyd^y=vU1-x7yV?n>3o^WlmoDi=O=tPrp%A)bcuh(brzn>E4_{aJlSbY~1(XV8 zt%9(LC{Z8`Qk09jgHbTF_>sJ8X0&Ns`;inQTScIV&6;dpZ%j;#(WIR;)MOI5V0+<( zAw!}`1uu91ulG664{W;^Z!Iz(zZqg`Ih^Nt&N-NW&bSFn*Aa^pP7rK=rCV`49c(sG zsYW8)2Y7I7xibmG(uO7E-GS~R+?UWc!D&92WG2|Y3=2*TGXh|X>%6`v?K|<4&E+w!ftVW6WGLVPZ!^1^tctl4fDeA%0Xxal4%5*xh8|^qj z&$1WRt_MQj>C`STIuA`!8W^3*gZb`ySdIj-5@!fv7#hRXIF=whMj0B0ml9OL(Mx0z zMz=tUrxPjPkS_mQi1y%qk33-xS+|k z!6%w^=>|759zS`a%g$94qUD>n9!0)>dpNsP{a(S;9;uQ$vLmJSaDo8!Y`YF%1p}tz z&8`R+$3r_sL#eIqRCwS@zo12;1Wl+bGwPPbAT;w~F@Z&weR^mBIRaVgr<_;ykG5V@%XB10S%LT&|KI$&D zI#WzS-7NN6_kWr{>|y_kJ`^$uUU%77;2cArUD*NJ#qrocTiRKt&z-IncgGK!W0mMX zOXjEsYMR8~@wsFWLL^alro+j(IiX7mj?osr#*$;fxuAYkJuC(43*`GuR0F93acymfSAp ziu6F=IjucsVC};w7Y|wiNjdNc8AdGeg<1)k-v|sXH&+m_Kmg3fT6C|?5H8__S+>qH z!A25s!rcR+J4{gfSp*-=Y;YqvLeB)O=>86DM7miLOrRXW#MQ=U$bdIy2z4Vo6itK} zQ&|%mA+TU!fEAgHY#@TcN6gkgIm3871^+8VA;FF#6!Al)#Nwj~Eb*~Rz8=t^@hd@)=9@>HE z1}ArXt^3{zAutH6b;vtv9omN~*y(jR;_&9c7!@rVwPN(y;jB0--Y?Jr!##4S(vKoC zPeT*j##v+pjQ-;ER$%4f<(@APnV`5bx)1an-3QO*2`r}&9HAX7hN0tV7c($(Pq+)y z&I52dhd-+c!JOO2A*vh3p#X=};6wnKI?z|H zyCfpVY{2h!h3We67GbU{lgR`i>&;{kf@I@BLDvTx>^j133DI*BC;M#W!;t#g!t3qg zG_Y9;g91zWuq}Z|2IMy&ej&A&0=lt1G%T|61g*%S-$GEmM+Ef-FrrMP6BAk|&{pno z%{iTjrY>2t8zqEA(-**--rL(>-8x1!GFw zM56t#Cno~l^Td$R|K&Mp_)^oygDse4=A$PbjzUUArO_GfU)(o$Pev8FZ@VUrzmC;n zaZT~Y_Ldr@?HfK_e|6Mes(hQ8?y%U}p9H}2v!~j{+vRK8G6uc#Ms4TybA#60Y^N3Z zc)L3Ap!K}~xHI8=Kl9xBGeie=x2u?k)^`>F&CRY!UOluJyUtzDulhvC`0S4=6X0CC z+RWRRCAM&2;Ri&1x#<{BEV6qI+@h=6n`9Ew-np^U;nUN(xv@tWg+3h~qpx4ENsmX5 z9t{r<|MENbXtP$Y9(iVO2^Nwg?RxCTanTD#*O)dyJk_iIr!UT(3z^zTw()Y%ZxDaY zJa|%7M{a+6(L~ExKVImHRm(*206RhEm`wM$EsAz3_O;%@`PlO6OjA``*5$?bvA^nt z>RR!NRySY9F656RS^dBB^E*RrjG|GBV+1|0qrARb6mbyTaG<` zy0dm^^e!*PibYfHcFL`R>^9m+iGiE&8p3+Q2<3YF5DLe zgE9ZiBV6%k#!D~3{pOFN%{-pXa&7uHW#?oCHoY?c!|GmmLKAUC@PetkZ*zs|@QejI zT{8zYfUe>V)%2O6*WCBnJYedL5b&bhjESmlLR^?@LNA1LCANj`?hVo2#sI672H2r% zvm1oB`}04rhh|qS6U@D4fX?(PeXtsZ__uGy%v^Vq6-XN#hP2VmHk6#PFc6wx?Geh) zOoBtS5kZ+b6xo=Z41FTF#q{$GoS;L9XqXfL><^*T45N-oAMx8se*`sUpAXWcsSr`w z3BT_XYRZ1VFP#UUMJNMWzmWg>5xYRF7vdufMq?rif?uoOSDC8#{RhZ0q7_c0F!-JR z1E<3`bb#E2A*aYeLi!OKZ1^f(!sCjURsvg5xQ3?4;cb_at-wYHn?lnw*1|O!>Rs;_ zBmj@{Ko%m9yx#bb6;wCQwvtE^ggvFx8Ygm1IBKO+aC_zihEWh;9*G`}@57@FF~I$C zmNAJDto|3onBz{S!gO^P;-h=b_;uj0Ph@-?a7T%0^6^k&TM~}B1!hk_(@&R)lvW&PC7g`x4-nVYo+3Xu+lc zp$v$#ft@aoI}=UjxH#KZxChiWo9M;VrxS zgUu${0^tupV5o&{aJ*t&5%OoHFe33#Von88Hh52R-VuaG=nc~X=oG+zQ_|%nEhB=P z;gM*M1pCKCDvB0xVv7J2A|X}_Ary%dfb(h3E(?LDJ+PuImCy%H%%ZhB>w!24`Gg5@ zTy%D$DOMt-Pdw2)>eZfn;sjyAQI_~J{{>K=>`AG7O1NI40*y&6Dau}5iD>?WFgPCi ze>&dEc1sLn%{z4ePECHccJtga&4X03Qh$5+{RQ_bT``39c!8kC_uSA%UoE+GSsye% zt~TZ^UAJJs+m>cM_OSJzdA)7M(FXo|;gPsYa|vL3yj{AxYbnP3f<`A=&-a@~P0=Qb zYc6HBxaJUdI9j?=xCz{m{WA5vpLj0k+Qn(_d{fD3i)%6%^6djRPUx{!9nV{_;+bMB zyna_}D}wJHAGQ0upuwHOvnn)61u@CXL|8t4|IB?HoO?rj6SGcZW2dw=Je*9@)7+!E zQ|6=)3(@yr^37QCBhl03wVSgR-2db2YJSq%({K@`2$3E>v4_IQ}aIW&vqu0nXyF< zhYw9-eR$sY`QVw5XeBh+_5EDFiv}n?N*d^=7xAg+K{CP7qUQmT$^Pa_iBC+#VL2Mf zj7((WBW(A5_wFz84D7#jHbu8bQgr7;D#do-zqaZZQ}zqR3mKBYU4l@;r_D{VGL|va zjyArQowv%}NnJTB9dFD_mtMcx<{0Z&{LQtlCL~*lqw~43BY!k13+CsSqs&z?tbQ25 z66~nK*yu%IrW{d|C#%xYkN#l2ay&NnnZ8Cn?Z_7BX^r(UOSW@2y`Ru5t6h61F3$~1 zvUzk&fLYok@DgL>l2Q*&u0CCr`Ysw9j@|X8ms5?)`ALFq?`FL?x3s$?)z!8~8x3z# z{rltf2EK_qYw=Y$A%@LKzW`oZ4C|OML(!#l7K@Lc&c!~~>*XhNvDj{19bLTl zde6Mq?kCS;&*pnH70tC0|w=>r@Sr9974j-# z!R_p0f~yIP7W>~^j$fP*I7lQIHwMFl9@GyKDi6YxG#o@x(lBPugK#RLoFO*|@iWpm z5O@`|4(A33$IYX|!=s!&IUGb57SUtE+VSDhFX%uDdJcmqMHvTVe?lW6V0Rp%tx>lB z9&!<(6PsaHNB1H4ijepdOi77D)vA$PVq?c<`{X&*;@V7^R99Qh9X+u;gA+#ISB zNbYc!w&(fOY+wq~W-cU*z@ao7ARNU~c$UY_ z^pps}b)*Va7aatufgN@U2e1MbjY&wq@xTr0a{fTU*;!r7^d}0DQ2u@HpL2a>e!y)%AMWAPDoxLj9*1 z>8AjT7r(!Zz!jK%6N%Ah*Oh{nE*{r^Xo;pnuMp5`tGhpLo2s%uw=t>S&zs9FLRUiX z%8{d9c(5TQOKcJTWeH~T3uI=iP32_fqi)ALL4X*4HxUQ#oJbKo5)4kf8zEfG&;=k! zXET{l1`mp7MsD(O;Ng8|H*;X2Qlz(;Ed6IWgowQ|b!72BfU62wp=j^c=P%U~VflxV z5Al(ScqT<36RA)t6sH5a84C4=LZMV|D3zh>P=?O;hN8_Woz7S<@o1FARE!z$8~M*R z!CG1IbierV3J_E9%4)}&yKAo^EB5lL>(<*`lkSpdvbUn%cFosWa}<>;%z0%YTozkT z0(F8rH8-|bQBPJs-e~r+Pw}cvwNPIzTN}wzb+D!Vwxv9OJ z3)7qSAKLk&nkM_N7oW{mys~oA6~2(l#}%1hK~4&R7OOSIXgMSh|CMFytjQ!My1S}^Whz)RGj!+ryqrNX#3=_JVJI_5^!3AK}lKz+S&}5NVEOO#WQSa1Jh}j^vEI#uq{k@^?Kn*GIISi zw-Rz6sEM6OZLGc0cOw=HP>afMq(K{5KVs@eB!`}UpLCnva9N>=TU|Ri@`q(t9o=@$ zm^2Y7&37YyQV%yU+kx#UL8o6-`61Kk5O>6&%oSMN$wAMY+{{ReNpxqwk0>mj1pa_c zT1OULaRY7f(}<~@_MPHUJ^52Cetn(a z(bJHPz?uX#7GbF`@5@&skt|D%`%$q=_w-;_+?kDVjbW7@P3Tzd*`a#_Rmh{Jv(?!E zQn9!!VW-Lg&JkFEvC0hqdI@p&;X=X$nyv|(vF7E4FCN3oV$7I*NQaI@zR%8r>$2Sl z?*Nc-IbFq4*yr2l5P?X~&UYS8<1GMMAbNVFu=*d7&xwD-(SN+X;^X7r4i>h5J65Hl zdbMDDddpPz`0erkqRt6Ld$LQf_u2u9dsE)7w;ZP6i{H(A2M}R3x5`Uzjf(O*rt!k} zSDw|wr-UH0V8ALC(KY)@UD0AoFaoz;#cVIbnle7Ww|tx4OS?q+)yei%;UR}Z5dm2O zd>`m=g}uS_$u-v^%A4LgSa8%6&BvX%Un_4rp2RK-fueo>djExGSray3<^A$qr6gdt zkSvJ90*7z>bRn@0tK?UXcV~u7enQ-dP$mURnu*5=Z$A+DrT7S!5P@$hp2~d42pG=X z!26Ck8BTmd`xgXRT+6^70sPc?B8}2(f3Ds9iN*@XRQ^~t|#+oNMf6tLdm0#wUv7}KGl6t}JMK4UFiA+??TBuNd9CXDyBUG(_HHx2yXh`-%?pD4 zM!4^)JQaVCs~-hvT?3W8YNgWl^xIFYvoIc^tpOPv>|Ih#zo^Pa7oxs$%(5b*Q-xDv zM~mzXeTDT6L`y3|EHQG{?TF<7a1)uCga!Uva;`X?L){n;oefC__?Ui=p!k>V!0c(j zY#ItI9c@X@l?Zq=pF>Bmr2*B0m@p@GCulC~73>&LJB9no2@|g5>m*FUoHrvuTD~WM zoK7(MSw}>No)o?-Tvos~jeL%DTE$=`1Ciw0NTLLJRTAmY0>WA{ovtVA2#WRwy`>}= zZ4il+!E_zQ;8#hkfH8+o&?20Ga4X;yR-5p;gd2N-(wa)(cq_!$C2Tl|O2R`5AoTmsTHD4;QN#v-s}4>qdG^GKlgH}tmkFGt;wIkS9$$r_7jL`OR?dlnXL z&|u+#Zm6DB^Li9lvcPCf=rofwFk(jXn%(T(9~F1wt~ zI`q%Tm_NCTZhvx9jyyPU)4HAuWTqz?&%EAC001BWNkld#^ej ziroj+3c`Ln|FtmCM~aFHHT~QCBO$$V_nDxtaN)1#>A?7?4+P}%zcN0S35UNB|%b9Tee7bN;C(>ErX)Eu)pFdp~YJk+v z=+oo9Gx`1El&eK)bbL?Hlx`x9p#?1S5LJgU)?V$t<1XUI{moM9Ebp)EtvfULx;a?A zkT(!+K3%xLpt>0xukPk&MyCo}+g(L_^Z>J8Atj>SVq;I}9OY79?bUA}DZ=)w!|)P1Y>Kqk9kr z4e6DWr4Ee3a{k`KAvG4fI^kKRO*(l6It_6!i_WH!P+lDt;UU4&Ar++6qm)`nv?1xo z^Z+L~duC3D-j!rQh!sH)rTmpkkGr9hLnTbC0mDNjJt1^BGL%O2RV0nQFaJsCb;Lsl zl5_(H(>gMq({GuSMW?U8X%cH-EvS+=5(L!=d~3rbpQ%;|8!{EKWXP3W$`DXWjL z3$6+3)`a7ZXiL7D25c3EEZ54JJTYg>s3aUb@;QzKSkVkTSYx-Zk5n0{(Ewwixx$Zy z+`^jVQi+t@1JjG-C_1nOR>ojK@H?}HStE+94J+u!wwerfqO9G71us*t1enbx)LmOu zF*j-%m`F)uFfB<`boTNyyp`%_6Ju}}sfT7UD%QE+!nQ>dmC0-q#J1PQv9nFh<6ual z4Va|CZAObxD2CN8G*+=JQzvc6$O`2sj$Wf;3u3Gow9!$RlCUoJ z#Jh)J3U`Ty?ryr=? zTFLhzSkX>b>4?fWQyG``{@@T0f~xTG8cxte zj7SdzY%u@}oem7R>M?S&3&XL>gYGsKBK1<&0mn2IGkqfhYAnbLkJ2%NDxHGUg8A6> za_@^?!U(>KaMz1+;N%b_S;<7{c&JAZIZ+x)asezSh{1{o5ssA7i9`wJ;RH0&5%e-7 zBWd&nCtwPeTgsr*jHrB-4j}QW?hU9024F6;HW&x3q4)?+qi#%=1}joPLmdNKl7t8! zA%#QE$Z+MZ3o5KYT~k#@z-AhN1#UIruK{084t+=bHqs^qg*qAgEZhKi?cw+p6t+V?{ zE6>BYs8A0?7O>C+SHgnj90@O*kvX+UH&olP!3L$V7H9ebLswKp3k}|kHzp*;#6(Yw znw(TF$X@iKv6$#)6f;--!}j}pf7rA$+o~K7FQ#eaInVdy^Kc)y543qMQX@%ipc@mO z^mcoB$Sg*n>1C=2LmDGf zJ5~ZsdJ;JcV=klsyF!yCQe;wV7cU~wz10#^vFHL|l6R3^uHUQttt;V;{K>>>-_?^F zi=*yGOZ6!i9ZORe{S%tnt}S8+tC{%xdZDiU|KOu^TED$^*%+O>)SgA!+U`>QYR;+7 zKhno*XewVXhSbYj4z)e{P*3ai*4HWO&d0JUQjJ=*FLZM<#mGy2Weq>AJr}?uHS3BN znab;BhiDq_);@{+h7MygeY1en`RHr|Yu?dzC9Ok%>BL3X00yVEa!LnxQdw#HrZX4E z^DUI1E9Vm)O#nESnNhj=Ee@;mfl@TR7pJ!#zIV;eyn4bO_|=b3V07v8SGqw5_&!&p z5ry#NJ{ja!0?+*F%+FkB($zgQf_cpdSDUCfW7f)uFcZu@^VKQN8ha#|W*B7od}jE; z8xmkr{pYN?&&l($2LBUs%PzQ6e1;vS`>#;^~%uD zr!`w^`Siu;gsq`f>Y1=7e^oT)*Q(3({O0sTxELsxPcElZSG75w#4%C?qaL&E-GLU5wPOGuNfk<&I19L1f z)`klrUC=sf-~?c-5?POh4r9+K&Jjs=yO_4JGWe<&bZV?3*&~qO00M#`!Vv?x;iEjj zl=(kTD+v$B$^m_78pyn z7naxK@RB5x(i%u^?olQ2eCXA(ChZl3y^f-hp*bYfSZKjPu z4o9+Z3udq@GlVbh!hbhibPE=AHx6boSp^IS>FaEt zk&JNq#^6cLS-^NSkAmj1pbsz&S7I=b znS+8Mwx}|LWC`*H=P$4t4>&oB5DaK~|3bmp@5Ib=7G@cfD`aQo9B(E8TWQSg`SA?D z0=h<$4wHyuP)ekk(5KL*FPX9bELfxX>@(F3JkFf1Fa~@Vi9q{ zjEN>^sfZ!zA|O{Hl2ES7Mb}5bH_(1n5`05)8S*Df36!Zr@WIH8aqYO6p&8@`Emi3FWQy_udnCRdsI%nQGhGEYCF;>({U6T7M2r zx>-une)wf^u~t`A%i^Q?rImK`cDH&;p0{>EUh{gXsA>zhu2l2Vi<7n5R{CpD;c_RO zP{a|oZXM9K>x(C6*Jn-b(fq~5WwTw2wAy5Lddph9Yg;c{`H}kWR6}D7bSH8lT@e$} z%nTNdU=*R%7&+jI_TPC_sw)`6BBj;KDK1ef(N_J|<7PhEBzwEuTqvI}-wZr62TQC0 za|#m5&Yh`fKHhrxuFj;}%kqn8qUV1CRp=pCkMB%O%w@*)_FC#f@G}I(O8~3hemx??N`hHgk1ESU`^{9>)1RImwTBwf zmpTmh)}yY8==`px+u!e`b{j9{$2MK;Fx8_y>J1W0tQT`{Tac^-A9JWPW<8>NqNjAK zetT{rnyIhqw#*so1kF@!G@7w%&B3+ah0FQ}Wqx-?pgB})W@}ZHuX(3fz`#cKSBG%< zg7Wt8uwZy_v3^M3-2*uiTu8KQt>j^Nuo+vx_U>8xF%MoL36NUJHV1wFlxsI|iQdatKH|Dlqs8ihX1k zkmz{8K>A#W$4Ruw`a+|vq_%-L@Bi8ZM*u&^BfUYx5qa+bBd|!P^TBw&mqQnN^T9wc z5;$N;M}S2*5+hB9Ee^-Y27?403&wZ=nm+Qdxe;GH{KZ42ICemH#XQjB%?L7q;b(mq z#iElj_ogovIq+<<`-SnfFq9I2EJQXyYcaNEAzSNPkUVf;I`n$IVlPtT!RJ5Jl+! zEPP-X7B2?VZC5vB*Dy=cTj*oZhQUlq3>H?Qnr%oVgu=_)ES2625^=Ul=KIHDqcNu`Ul7x_+e)UI1Q!IUl5F|;+~R~@nX_m&WR+m97hD_NNoqm?Q#rZ5<5t! zAnzGvXfYOx{JG+uq+pT@tz-q^3yPGaXYo`tvI$ENUy?f6{}J`(Vp4+6`dt#&qscXc z5}jm)q=#2!WcY?$RfUJ5LQHGsy&>|r39zsxL*wtp#>SCCNDmx$jU~olo4F{B9VJwx zQLlD|N;{;lFv19H;8$?5zlPK*)ewHr4tzTO2!Dd3k6^f~GK(F@FdzZry{+^|V!nwoAZx4WjVRn6Dn$!Qz* zfG^7pRXv|*sCsN^aVn^#zfWMgfpMf;fAi4s2~t>V34LX;c8ApW&eH$LI@_MK@-&PO z3N8<$1r*|qqci+pn_sb^niUvr7~xa8Mic;<_Jx*B_dijB?m7%WIXA{~s74 zJ9^^(Q#LGLMk8IN4Eg?($fQE zf9W1P0#~P}-zP=0SI7BAj9x|a1{G&5esy%UDDa?lL%&cKCwjt|UZmfdT76^WIQ3@) zF7#o%85+#h=YbAUi0)7{7Z$jeuJ)oK3;|w#Y84U+aLNgqq_;JT3k^tQfaO(TCJP}* zZ?Sm9DGXZVBdW9}Rk%jv4r1sTJ4AFrhrQ)>Arq_fLySAq9gO-=@2Q}q^bfa*1C9X2 z;_`I^40gDo)2$N6ib-b(Hj)>@4G8x|1K6|>#_|!5L7UuaOjvaSM9D1ZPIAWGq{(VG zT_anVoy)G2fqI4n$XVI8R_>;T}I)W!6IB{T|Vj0i| zCdZB4C1zw9=R)SMwA#0rf<|yO7%hvi!1{*_<3M|Nv9VT5e=}+{DmdU8LB9fn1I$`1 zB|&mIhmg%Krv&o?5(5V;NlZuUcnV8PH(T_A4xPjjLCV1SXrF& zSU}Q{+g+m1B<~nOaOX83T#*DP0i)COF7f%H}k7TAG{7<@*Dz&&uT+<-Wf1^&78WU%bA3ahpDJ zUqt$Hk@)gSOBGBnOJY7t;;C>*RG8XRet^UmVYc;^+YRD;Us8UML~M&anqA2qb4Srz@qr9bc5qp3@rFz zPDd)NkFIIZ10F!7nP;u0xeh%oHiY`PB0cb&w0MBGgrL;ZRgCzfzKmBln9zDOQn&=o zL>f+J(7*-j^~x}`9;*Qe($)+e$6H%pydVQC7LK5`1I@k7is~wD;4g%@x1%|>o$$|j zPhnfJgCqb`Dd+}NGi4W;=iJskLunYj-T3y*cl6tz$nK~0*+QoJ-CPJIXvksZ$-R9a z;u41K;;9(nEC`H@(I6p~U#=E?_Mk3m4WddN-(GD$EhIe0wx8<`#}jLSSD#MJ93Rb2 z9{4H_5_Ffcx&sy@J;^Yu8Aw&be3Q=?8}xUPD3_khyyx=qVbmz$LHmB21Sp7X8$CAF z{qXzoWVIAb+cCuZqWDO%M_Q@aypptmFBW1cqdSr z%vNPdikFN}4~)(qOj~fk_%4H}yCB8jb=tnphdXCSF-8W0?;B9-MMO%K%z z3xbxlz<>|(xSepYh(!{HSk0(tF_p!gUQU1ro3!D@27~}}YOuHo1?jMglJ>O!`5(HZ{9utAT(Of!6M z3y2yaQs8#m23cAqt%1b11p&Yq!@`(!9ikOTMj^2zxZq^f{em7aDQ?KTVdg?JUD^QI zXb&0bVRa#_9syyAajQ^h*37v`AudLTaBL`q9x!GFw1_3ta|s&dXpTK%5H#6c6UQ@P z6S!8}$QQLr+5-LEP;p;a!=4wNU~CXEOiwQe1f<;z!QH{N;gD@<5>-@)h3 zd%VCwW8j!XcL`_npiz>KwhH#M2i6tYNGp+l=HI~+lV^TM;;U#Uk2I6~qU3BHAB67q z4-R5T3n>j z^Vo)(ryqxu+llF{A+tlel3z*LLyC3$NT>40&+(5RKYsrF5vNb(PoF+re7Y!4moLg4 z=jHQ9AI^KrA0Ct+oKKwp?Zd>6H{$|H^*>x^1*su0l~=dNVqXRb$6{B9(3RG&N4~lF z$BBuXbb2uI=)t2A(hdw54GcVc)=EC^Mr*2kf4cPo^TvI*U*9kHP46H-K{@6)0#u|#zRS8pPkHxO8eb1M7C&? zGP&5+Sks-Rrgk|lR5yL)dWHVRFS#6WfSL4Gc52Y#>f_00^n0J9%uE`Kwl5Ty&e z>DfftnHP{cl-93UKH}jkR^VQk;Ev$njNdp^NnNhQ?$}{BcLes)HypPM2|2D`#g1=D zKI^_$pm$1pGi#D%rjU^v??xRJ&Ls4m{XNQ4%XSe!!~qN#M&i;g*;c4tDKJ)uyH1~G z3ppvBBDu`2pB59Iv!3N&j*9oTF=~8zH*p-)L>nd9vYM1~46-1hOd+Vjg{KDIBJL9j zi1bYk-La<0Oiw0`pq%#o=&VGK^le6WnIc{48Lh4*)(79;ZIk&8hOe-!$%&CL*AAyD zq%vaY`@b<1ydn%mmfhrlF}GF2_~+8xY878ZUeBJwjQ@wMtNm#zPovZJ+PMYo(stW0 zt(K+~N;{OYnc70>4rN%~0kwbx28kqe%M2=2i({I8Ad{HzGGU2Y42i@~u1+%X|Jdg|ze|?v)B@$+3;01f_dL&eDctKUHk=up$)jxr(Z!;(gwkT4QP9a1+? z6156tk}5%0i$yJKs$ff!=cH~}anX|`A)%k(SH;;^D%N9h7Nw;3BH_v)yha-REL)eb z=|xeYJ^>{)hfQ+bt@)W*001BWNklXp;pc{wciXJFm5E82ftc3#%tUy^`1ABpa(CkI-6%VDMxeEB6Lh4L3*d9O& z(k)1_0vvv2zXiYzfDk(;eDs=-xEws0kk%Psr*D9e7^uzFgap?UzJL`CNOrLT)=r=v z7@lDxbkJA~TSX@Wdy(h}rqYCq*aoK|oGz~b?fr>>Sev$CbE{1QcrkTG@-wtqMu(RE zgov}IZE0+O(dv*+Bk~y&W*etO!;A!Gh zq-I1WA}m9E1(fCF$pQMMQ&z2EPa}}m#Cd#W1ELibR6y2oI2N-5Y>1)PG7Zzg0W5y$ zSJ41w(!;R*a*G4L-zdGux1gig{OZucU>-#s19rj0Zdc8iJR>4{l`t1x;b=AS;5taK z%T*pE$w6N(FH=}D3sC!%}9VA zgC{A1n}d`RUTO3Fz6dy0(~-HF+5YXpojZ5_b?45%@$N1?@7}-r{rC5Oynp|}g9lsq zv-R87)~&6r7cX8sfByVsY=50$EVeHoYkyI&(&D=(n~wdzd^&b?Ba_KYPhX|SW@V|l zL||X}X0fzcDiM%0W;Xv+wb9u7$uwQHfyd^lj?6~m!A!^I!HrA@eJQ;Wfv?I`D&bd{ zJ|E5CmICKGHmVMOa`0elZ&hz^D*=3KV{>b3%}`C{P+#wwP((LZ_1lOtdM?Q4j<@b^+y zzXEP~1KeEGSEJ~#_IPk*u)g1a*1f)0*f8SZLO;|Np})`r*aVK|=1y846^ibb{8y*f zMqJ7HemN)iT&j)e6}e0ZI5#^ zmsgU(ndA1teE(`rcR|Wt?`a>WFJAfa+qJHx6Q>_`&G$HpUE}LZoM6QcAz`6Sa?=x+ z{f&%t-SpSf9n{L%o`;Z$9a%o9&CCTTY0pCQq8i`5pmx z7XLubbke2tBq@!H9Nxw7p40X(B|Tj;{sTckbK!Jbv5W4oR@&Oua9>eye6>D$yz|Lq z|7BkIKCbA@@AW;o6z!M?;n4`H#7mb5;NsM2PW;HVmNX-=t3gYB@hlvd&r9VU?1eo1irPkPKMxH0i;gy3OHQr(%`sh^Z{FmAK%8d zm$39FI)Em@a_#L9T@}*W(6s;}tL1et(yk!B!tj|uI30rOIn7mubR~U;c<3|};oDkx zi7Omuuq{Sap(4quNMi|X{78kHGBJT>@fEzkYUaXhOOlxy&*7H?hR&SCfmJY(T{ZT< zGFDco3Wk;wi!D>x&&aFPUC?h--&A%puU7;Td z#$W#RMDR@Ti=lJfFjmKPyhApd>PD-1RZMIc$ zx~fA1FME;PkuecJHO8@&QOt*N0;t&z2yKa`A}viVmU?=#L{gSi1VU_#3#L`6rg zG^N0Hxs_0`Uzn3Df)ay6(@Q9{=#ndtOGhmhbQwmj(9OUYJD}(Uet5f^wb*p0;0R}b z=R!JPS*n`OY~TOqcT-d6&V6%k|Kl4x=_ozV(b*|JI5jo(*YCFX*C7c-6}EUhq*bgt z=Yz4X7|V$<86H2MR2;j(eK;IDOdy)sn9fXJoqoNuv%S6j?AddAKBp%?p3!6b*~04f z0-f5%V`pb)a%X#YcXubhv$M4OdUy9VJw7N&(82N8_|Wv##b00k`ts!~dVBlf)rVKF z-oJnU>V2;8_H8ixpKLbvE+~k8?9H3S#l?4vrFW&i#Zt}UW@D+6u)leuvSV|zHPdmF z^RT*-vHjh^p5SC#+hx<|LoBvp$1egozEmCz!p*!4<{dEMa3vd&9-7Upa>l=ONF8+a z-vwzjLVX3pug=VeO=h)DjH)p%!i}xD%(C?7!=EC865!j%^5_4(V+$~2E|{;P!)mPY z)L-;hSk{U3D&0lQ%sc{!IS(2-;iPBj&=;M?6PNUpZBB$^EFTN4$=^;UJ%xrp{ICYS zRx5NhbG?T?3~!Tw`2$@TO}>y6YIe_d?;QfhozpAV)k z-GD7=<=VA}ZT1}8LAl44i{bUGm;^H&MQ4O-WUq^X+oM=I z1{}>9{lN7Ze|Mpf%Xtbv^gqdFv*#aoURulMa@pMA+1#>!FgMwA0|1=U_v^B;@gu_0 zB^*s%E~SuxOD+^wl^D>2Cg(06keT1=^X6vme9Ts7tHu+yjC0s5<&y*C1iHmYvCzsuyWL-=paPT zk<;q4q6@ge&RQ&-E(h_o!==Po8&24boUE`y1QtxeMgm}%lIW#_&JggzAY5TZ`>(cw z{YP2>%5<%f#n4bZ16sB45FsDy9wyTcE$309``3#3bBOB~&^d^Gu??wLxE>8k*zU5b zDwJlZMfI;kjHMBQRl)mS*o=7a93t*ZXdYtWm8eNV76+$u7(*YG=@CDvDl=&0IgKWv zk&uH0g@6WigenZ7abFH3X4fx4?*TPuV`*4;#pzcAye3wR!CVLoe?=KbRI(%KzieIq zPg8jol|tFJEL}={jRUqKuku=?RAVirv|1_7j!Ft*RF;vXST}qrjKYv9A*2aOkw_p2 z0){3sV>7HIvW_G&B1{&^tT?RxU^4!=*-YX;viIE21I_HdzCK>x7pNq1dhR{<9QreZ zKvXSH1;ad&P*+@o2tw>gdTn!a)WHHQhYTT=Hi{`>0@!Ffnq~ym#B%8&>n90mwUZKR z#nC8SvZ9hiVBC%lvEraziO8)Yf#RC=iXNVk7*4|MkzR|UGeVVMn}q^0QO39wmlQ>m zqaAV_5y1qq(qsUgg#3RgjgI*7$AyV!{bU89z#MQnjT9bS_y4y=vXMOa7~&; zSpaJKw18$XJ95y^j0ccK2z%-fF?V`PC9dBSV8X$Z+gk&-UlRZWaX&5{yBl#7P`rDT zK>3YubKWZ@dn0!Tz&d$3g!P=tPR||xY~c8z&yJrywsr2%=}T62fbLX(c<13mhqg9} z%?|W$y(7@w`T6nU{Cxc*UJ?mx2kAMZK53Jn=M3*ZnxB8D9;!GG=bdvCAE zA?)oI(k!krWnpvUMSYWwi{w=fQDc&;5#bjtCw< zW$AG@h1Zz?+qn`ev_noc#_+Bk4jN8tbyRN5Y!KoT9TAgYrE*io&I4_uhXiC%7)zwonI%SQd&bxbhJ}=sEj<$?D_H*1)j2$^*S&(3vax|~_@|-p!#{wH!f`yv2scp_rE9{`#Z~?JdBR$$YWq!uy zHdu9VG7=GBG=)87Y>n0C|0m*sT}Wwg`B8^P5@DIA$aSw0Nei@lPgr!o5v!Eb7%D3{ zfDqms#D)oBi!iI?DJ}BYfVx8>l#s)apolJIGVCEx2E-28?hWxkFhtNepNq43KX~ZH zEEHELHrp_1RAdAGf&wFF!G?3WXyd~9Dwp_d$!sAZZ?S0h7Uq_)D7x6jI7tkfE6cfD zd`7BoA$wiHHJYVY2t*;ou1p+O?=qeajiut4h zPG~47-q#popq1!DnkEL@G-AJ6wtd#9){`-$F>nYWQDsB6iMzm%acU4hs58X4Lu}w= zaZLQepb~RP**XcWk z=x;kaY$%G%$-s_K9EOw4?F!+l5|`nErSJgLnj^#}9Tq}n1O*c%ULza^!-e$~k`SVh zK2<;h9bmoml9(E@$niXr9`K_q&LE3Dw)C9ue@X{?h97dy<1<>3Q zUh)NM!hH(yWuLVNDc zBdy!#`UhUmCq@L)!i#xCu-^^_+)t2KgY7X@cBVuOa5s-5sTA1RnfmH%SRVx0Z@qq*5%{C>>XXfp zT^1}T@PQ){-<6&w`Du_HH@N8R z)4{_*@5&1+f)3LQso~Moa++=l1`i&#+wm27h~RzfFin7Gb*|pB+#Fu_5U`%3+R zb*FtJ^@4k|tMu*BUmZ@Roz~3gaN60qoPD*#0o}3cL}}*@$FcZPA>V8au~@+rGD z?JKBiX}RjitjF^63$B%~u9oGW&A(8*kWSr9BVr<>jC$`n8@%J^zrJ#&X|(eOr~ckJ zMcmgejJ5VE(7<{t{YHXLyH}eFPQP%mw$9ykCY8ym?W(Okn@W35)Sl>ao7Xit8S7MU zL#k=PdBdKL?f+9k2StAVxN*zq0Vc?8O-t7CFFbGJ++%PC{8C)%~0<@uLZUaEa z*rbC^uyVkifzk9rljDzpV8fBpc;84Q7}af%T?nD)&^0E8n+3TQMuClB$80t|XM**l zAIXGms2(HUqo?N2Mr3fOV6S<(j@SDv0fyGtC zkn>9OY#8qy8bZ0*h7PhT7p9b`J0mTr5UEIc5JnRz9zwBs2mwj9+@e|J3&Mzl>(Hn^ z6W-dsK|vXVMTN7oKw#9PkvN!_S4?}vYxAlK3yXlqfZM_TmnW3K2(_VZB`Jq zAR~c6Pn_5x5k|_B1kVJ)Yfx&*vcnt#(1w{L(BVKkQP02{pq6k>3EUx=j>jE=XuyZm1=_y@G*&9Y zeavmKgabnBjF3TJ7<0gV1iuzK<^%SE5r=(o4p-nD!f;4%X5mUnuzN>=y%kre@eD1+ zVFVrM!)P$h^PRGonu=SLK1V22ob!KNuv)h_i2(zERfL_No}QSPn125J`OAryFQ+G_ zCtgnc?Yr+DKK%C4mtU$7ytXU9+ViJu80deuN1;Dfu^I7_jCTZTi_fNZo5m4VK_A@O z-rhcbdULb?7yuS>PY&FEm*9f>Zuz{UV-Jtjcl629@hMPu2wYYndS^-)V!;8rdsmL->|FTzLO?!+ z@-i2o336N6kmJ8xUH?zh`5j&hHib3~(6qsFptiIHj&?Nxw57F8%r17Bhg;J{kif4h}UP`g(*$nC%rXAMcRvl{42p!Qa(K!LIkM0}tCy!JT z8bc#02_H|1()6^E&$Y)lV&`O&mun7(y{rMrdaEk;;^yd(!(V+52RDX3yL<6_5q*9MuAnOm(NS1+~Zj1sG_Pgqx?4Q zRqF0g_(W$K_4U|=3#C$Np!t2Ab*V4iTpBAaEj=6!^_9}$P&)j$G(a!xf%TU!*I$h3 zCSm*!!x};Ji5Taclo+cWc@^?Y3$MR8B)_Q6jn$3Swbi~uFE-Xz@2@Vs_s37Juid}? zhuHJyzmTH`OB*HGH@$QH=C6Nub9Df}U@wNupm0|uheO0%wt$D(!)7_XT^MkO@f1tL zHkfgkYt4dw=0-K`Yq)1*I0JZbjky-1NQOq06>J8q${jdTGR-h+h}<(ErNMw`LwIoj zljT`3TsbNOZfuMgX|Q3Wy15aRZJdLaRzOxceHZS7hQmF&mb4cUgA4=CWY87Hp>W{H z*nB8f(|wX~>uZdF1N(v*5@D2{GZ+O93X6sHh7bF6$@9X115jci_9zgXb;+JRfnY{x zFhCfzm!6bN1P*e%H`w+Y7a|$3=yr9%5G$ibirf~HkYX4+qdct)H(;&NW`b`PLXsG_ z&}O0+Gz8Fdm^N}LAeJQ)JHJHTHd8}h7%)sZT4bk*78*#SQ`{mbikkGCLRHkb|d*;B@P4g%NI7zn!cU&F71 zxeI2y0dExsS+vj7mILe;EZ9ubTjs6R;lsY24p}Ol5brM@w!Jv83ruxT^Gsn1T%PT9 z9^5!MMI?K%69{Zz5t~A2913R+fGbCS$GdZC4yij49qMpGE#{;k zTcAG?-E>A1M`}y&aCdJU_d;()EA9dCSs?84%r$&nnVx>N@JhC4&z`-SzVd2edTJR2 z8M~bSYw5op(h7oG%a`8Z1UQFmKi|8fj?nKfR+rxCwg}zFG)>#DrILk96$0>AUo8p) z{&;a^^6vKJ%FOn*T<&gfZ?CMZJdn$S6@JNOd3jl`i%*^`KLHH}00Y(G13f4|$z`JH zc?GOj)pq$RdG2SI)zW7-Zt%(n_3CEQn- zY47{JVdN9h^_k$CR^!2G1{NWtp?7PuPI;^nfE{+aU+r^13IQXVdMYROq3)xU6m}($ z<{>qS4Po5p&JFI>pTjhKR`geipfPzA4k-d0;!>&qgO7fac&O%pIXTo$LWtI7YkO}z zRKcdDa4Dp$mFCoAts=hom(0r`_C7c{H25Z5Z! za$HNLWI;=6p=2_-fBymbnUb1TIFQ6zvQV&=4-^iB;?~25t^1SZRPwM_)~rcufl@r# z%Ef~BSo;{~knpmsy=5Ml$Y_QE|ZA5J4Kna*OP&WnAdM|>WF4bAYZd9Wq zs5Qgc8PiQRLy);g2BZi3Y&JuLJ{|}#Y&1tA7(n9ak}rZ0VIP~qOe(a2%0{3GBQ|#h ziNu*;R~O<7eO*vT%cDR9##ah}gR<5G1orvdT*wH)MM3#5UDRYv2*zfDZGy+pJkKJS z&>ff!&{VQ#!rc}K1YEO$9#;>7f-T5PGAYqB{h%=vY*Eh8Zoy(op)H63o|`bScr8?T z!s2FUxXI;i!8|X~*J3iYQIF+9>YzYx(;U(jgwY~y5Hm@6rZwabq7&R=LKKn^+kA@} zSYpu{nA^nSGYKu~$LtE5gbNFPS{fRjLWKoRD->Bk8+=x<7JcD^Z1*ArsUd#^aBYHR z7F{?XoIa92LkA9}nT8dm5v>VGn&mqJfzjir?C%8&zwi9m$x9n;d&20{X3A+=BP&;5?f-j4{bMu5p)!tsk3F@osIc@(_&qTB#iojG)Sk9Rx! zX}=){!691qV(LQT;y5%|>=$<@a`5!%hT>`*K9ig>c1CkheEFSpqeeNL?$nS`I}`qc zzW*sfs|VqVwO9rKv-~VDDFA%!+LbHQSAM^+AP_7!0>BG`$5UStO$osNuciL5GYJ4D zmn86=zo9tjFK_5duJh;5p8Zqx-|y@<*g2MWTY0aK6M+8)0RD3E`=5V&d3j1+ZF+iP zdg0kKxnPs~yvQ~s+xFD9j>``OS}*^(qzpZROOf*ySgx?v473DUpt*S z@P7m28frMQCwFTc4!WqzXV=6QO5TIC!3rzb-Rt`{tLO#23a!&(Y<)*R_|cjEb%=tG zDVs;SPzYTGSiat^u2t{fN2}nCy7>fO)i-adYjS-VL{AZ5Jvv33O~|~s_sBmJfLhsVtqTitGiWn zE#9JeQQcjG%5DuS@}Rn<7ONY$>}+slgFTMjDh}9r`}+0E@4oxTKQ(+xfH0w4@Wwjz z;a&Op#&*;Rs(2M#aiZO=ja^;PSKZamCeNxLq`E6FT7A94KFTVd!|w9ZTW=p0FBQU= zooc7BYgDhNGhE`~QHSl6FxYHX-bXp0i&}CGRZ_5^G(vC#-7_lGc&{~p^%`pDZA?Y7 zWsRs2!^J~TF>9#J2(8T`9oPn;Gn>N7I*Yv7*qDtlsIZm}8`(xeGd!P-(*-gS8Z23AWav)td=KU;zy)4tPSt zGArnt?Gly?stW`L1#W{hD=7F3M3y~zaIYtbS~C)jf=clWFDz7~13`Fh;32|$<(>te z&$AYe0aN}A$urz3;fxh9VK8`h!ZP7-YWF&Ns(avo_#kd7b`af))?@v_u6~<+TAzY!X zfJ_ijlo4itfoih+7#wigc>`?(Hyc~jkR8H?(b}~@4P%Ug!F8*2m4c{@Y%)8t*P)r1 zw$Z>QwIXZck6mAwx-a^s=?njnp3nJSsN41qT<*-hbK$~-XP$GO^E}K0Lu7^4mb4X= zsM)h-32Lw}%(eh&7Cw?#b+mn@JQv%^-4vkPG$g4F(biF<(FSd0IV#UMrZwp{?GztX zOy1(=&yE>ZQNCMn*j-HK5muDKg#~*}-XNA%LWW&#;|T3i11zT)?Q#4mvA6Z8G7D%{ z0On@g^*m*khrB}emco1cOVygv7x19ELa1V?N0zaL)?r>PPZJDmQJA&@vM=tN(O@L( zDt(sD_xjZ5$~Qx4xnJ(j$iKU|e?~Yk`3wQv^NkC?6ucIYixG%K41)h^L=CS{KEsmbNj$|Hj$+Xa z{Wazo?cs2HJV+;ZtUcO3;yuu=IY-!1MuO2XFR)2XIXI$-%tVpE@rcF%YZG}aqF7Fi zIY=O(+zVV)GY-a&0t_EVnNWiFMuGu3;Hq3rRM@h=vT1fh0QJr!kYT{*1SbtmRR(-P z5Lno+;IHuC2M;dkvf?n=e>6Uet532=$U%hy#8Z0W%DS=o;U|AkK*g#;tE2u08e0}Qrb;aK&_XL2a z&t+#FTddyJ(MDmwiOZYs050DLu+7OHnA_j=Gz;dUz;jN<+3wv-ZM=nGxzVcb&!ffy zOKlxw^W>+efA+a&50lBv8{u{Z3^VMj=?f5Eok%*OGr>m;PYyj~=pFYrm123+kcLt- zMjK_=(a4)qcfV?`v}mNU!5)`NvOHstIY581PNv_!P_erLbtQkUEv6INu?x#|+Wy>Qg zvR+C47UkNN?9&(D3a%BF?=iMo8jfT_=&AB{HCA=EH14Tt+|$z7(p}Z^`^N67swzIa z23o3GS{grU>1?d38mMaQZjlE&O-jVa4ngg!fA}K%G`sXP`^C~ymXEBRUAnSlU$L)T zv1L;}uY6&rm+U1wZOdVDfE;1lX<4VUZ{NN|Ise_OS8w{jUIy6Cu9tTy0XL4*-@aUu zOOxxdQ(U-S+e%WeF_|(0c&Fuevchk}945P0l0QkZ#eE(!Vm{k`_3X@AsMAnhnD5SC z_ZhowR9*)>x%uuP{PZ>RFW(I$l5r!P^{~pBUE1a?cEf93FjZhWSJ*K;SWqz^s$A5O z0}ZADJS3zU->Y0whKq7LhKhzDx&%2;aYkO%QFL2SRdyg^&ed_?{5o35gUYURRH&7k zldDEq9UXNjw3sA@4U;Q~?NxDuAULtVgdue_qq@4GcVWWK4FasWxy^{4>jbA!V_`yB z*EEPZ2bJlD=H?E}Cxsl>)YPa!WlhtdDOd~16}%1gV?PV=Gx8Xj_0GmXPEUip;`}nIFm% zK3pJ(y_=Y$it%w;y+ExBqD$JaysFGY7)@svoGxh7{kvhsm6gs!k_lzlhC2r{!=Q7C zK7^AMqAY-xf-@n8Krz~89Xl$3JTr*|dP9rVTuUR7j_z(7-&Q%UW#}#XLXek(OHC+U zL-L{-67+qHG#cHN+vu-KbrbY8wpWjH+@2hdB5=OP5|{>dUFx{uR{Q72Ob~lw+SckP zb`aT#{L69sw(;hJ~?0+Ko4sV+B@F#e??f&&Kd^nh_F&q27fOZ_A4KNAC%bM zz+c0FTmLit+uB;+^O*qf+_lBYYmVezUkZxw<;{Gz|t%3@6{r_P!g5 z)Y`aC)sqtR`fFOiS$kzZlb99&zO=A`zYYWgnG1#jgPAbdd!Xi*)6)~efKQGZ7wFNG z-Df|0J-sITsWY)Is~kmtC0DEK5IaekXi=HvB!GE+t7Z3j{3{Cs^}l0OGT(m zUa~qeFRQqv?^O*m_UL#Xwj6;+A0e&|>9VPJ4%IsJ*SK)(+i-z4Ks-Al3^;hl=}_*} z>D79w(Dn6u>hHctW)gJS6WUzot9H{9thTc`eeOL+{3d%c+s)p@_CzLQzkRcQ=Is8^ zp1nJb@Mtf&z&d{WasA%zp0%EXJ9-X%SbgwNPxb!l!s>(j*9zCx3U?Il*wM42df)#2 zg=>X9JvzkQ6Y4T8Q=?*HI{AAh(tnl7%>UFV-<@TCbM?-~JRfW)=jZ2>^SpDgpROtf zzy7DH^4H|2DHH~*hFBEG`ySevbKAMF_YxCEPheJZn>N3S3Dq9xj_pQxFzqN0rW0mo zLXS@*=3hKJQ`pj}zL&6G<9k`pySDoJyPuZ|%~jcRKK0~$SMDuBkBADSCY_Ik)sRpg z)L63Db@+BM4jojI1*vm%d>Fwr!$~BnvGPfwPv;6Xs8nsTr=1pM>N!EKCnPA6=(b>DMRlPYK+24r-0w5C9H0fgb)fP zZX)nVtIWc5sZ&>+SMNzV1`+g)8sj#pV@VZiOey@ik{RHVKf!p(MyklGk&P0~BrK@d ztp=1g^HiQyQX$VDCvdO=omQUm-CYQ@)Tk25d$XX@;3@7Jc@+#OA=4@`!@guB9iu8; zG7cY>6}HaQk#8d6YTJgdrO;tPTp`11u7Mv1Jz)lz7&=n*)%Z=N#;SbY=6uLmj>-4g zQtaC5F3NG|c;LLeSu1k8RN74ZFZF2m*2ltxJ)Xlzv>?3TF*R!=hAyIb&3ktRXIH5X zA<6$3{okUayp}Urv6aMA29y*@G5e7%@EFg@8DO^GvOL-%CK9!j(y|5e_6s*A4=JFM zQj}E?V4rq-ah9|KabF}p!5x2g1uy5`ftr@v5^`6zNqsc#8R8&Js2@l&awh zdzT&Yl|QVmmHw~*{8&JqK}K+7%)3nGd@LYzcr1KXh%~+9lBWL-VGtrZQ2Pu9JbmIs zCY{b^jt?iVUlhD@2=L#8{|aeT;Jc7KethCwCNnWS{QQSe4#GYA*3Nu4d^vq>aaHhF zZWjfBFD`yFc~Q3KR?~BKI(=?9`TeY!12)Ct-d+LV^)-5nXa4va2D~H;cs`LxPJxVy zznc`;)SnlAKw6)e67=-MS9cVAHIcB&l%O~DSJ3IH3kw@`S|NSGIT<(3<(%x^z59+( zOP80VH)!iug;+)f-PilO4}SEUSXU$EX4<}?a+5&V-Po;j!67QeaNzQgVaP|63;)I1 z2tgui)8a)(ZRgIT#2Ti|H7 zl3nXSS zIex@=iQ$+16?;8i@7D9~1N6)1^J$@_`8+?**X#LuK34>PKQySD7ni5N9#9C0+u5I` z3@WD#LIX~^n*#8|!83=-Ki`s<{!-blu14K;@Zjy+uV2rtug|UD`F>+#Ks5wBOfkBjcV=Owe6VO&ba1W3xDt)m!?mHI$?EE=d(oS!qYs-YEd*+Jj}2GSrh zQ^F=+&_gYHT<~7QkDM50fw-nVU91^Mg5&g$iv_Qvnggth1|F#;v@OyeRfkGpxzS)W z9F3?+RzqD7!wrH7BUnvh5*?1V3ocWbj`|}}G8nL(jNrfF4=NF^6Lc2d8x|;q1FHzD zu7Q#>7FgjYqkgv$VMU;~qdI*=455R~6|6Z2+|{e&xV;Lrc*P$4x-E zs;3Gmv}1?Y4S6L_c!#$~{Ueb^qkGnoB0+Dmf3;Z*A>LtbRe{DhZzwmeQpBy?{KK+i z$0zE?v3Zkag0gaPEBdPmtvo+<78J8h05ShUy9>2oRHsJ>2#c-Bm8%&7 zZjKA|Vj~^mp`m!FG!zj0b=8Lg&E)>Z6CuJG@PnrB+orCQV08(wOv4w4=rX2}1e2Q= zHHf$6GIr24WCJ6B(%gi4_2W?ZTx@AB>mrF^ciC>Cwe>AKsXy=BnP^cVbQh{D*`bR^ zfzSfCU5nib)lP%vA!e2q%WBkB8s3}ej^}{BNj;*K47Y&y-OXi}FQeR+7aDRzuKY9t zsqw`AXAcbkcc#xjek>T9QT^2=?f>3Y1f~Id>F*c%(tqmAOi!;ab#}J=*n1Kc^wz2s|>XDLCy{NL*8($dv?L$k@V z8N+@J{7x!nYW4Z9QdZLh&R30R`cui|@|Pzx54iEfDHUNQ^F+2&0C-sWbnXca2{s*N z<-ziF!}*3X0Q`d_IyK&C3^-2dC=%AkfH6JblZo2>xiMdjWFRHb_--66*Nj4-*z|sn zYU_6Y(QnaLm6(hXKF$ocmjsxaM>2s(ks3AP3X0J&J@aG`sl-_rE3NC99*O?5njMO%j2 zZ~i-z(JgORF#A071H15FtH)X#wF(C&qG1BfvJ-LExaK3ZS|&{YR&X~;J_D1!9;=XF^v*i? z>(K!usBvrYIP6vka7V`k7%k5r8%-dCCrSVV>4Y5`%A`VPPqfu$u|z%Nw3?&A2^*70 zHrzc(WUzUH9xKrg%7TUG7K60GU_0|i?X+`)bx*=_BS_?Luntcw%&@{w!k9oa`zsgG z@F=cVJ}f9BJ`x%H?acUwnL`pT92Af?ew6-EvW|Lv0>wTbM$qntiiU_!1* zcJ~6tSY!d3rC586Xi5XB=r%N4-&R{`C{%k`SG)Fd#TSnLjUm#Oedex(3& zeIk*7C(F~Q?N%bRD9=JqxT&n7{mM_hC=WDle|88F*4csM>GRWlUkd;a=ZnvG^MG}K zvhTid;&i6~@ap3w!+;Ou#mrhvuKo4tm&b(xpBLyI68ycu^0;sMB4DflOb>YNRnEFY zbATHU+?M0xvux3!GpDmJR#rymXZt26hm-y3i@AdFJ1t<))4=A%cL8`N)89WoeE*g4 zp_H#r4?jHpLSD`BWO{yPX6*RD6b)d5z@`E{`Bu?2nX5qy0uN~g8V0OKWmQA3UQyvy z&W+mO{Vnzj3e4&|c@#Ocx^SrJV%l`E~!4BnGfY$LBkod5nzWIS9)k0H< z)>ww}EA@Z)?8weL)yCRlOKmQtK=1FJTV0^|+^_5}nYl$dKfeqQ4KskonyW+d4$sa^ zjY0gBFA4)rzxggZcxK;GO3*4SuKq$tVg-Wt9IJix-J1ov0x5RyS6bbl(t9ZbduNlX zNFO-6@Xf=)ZF_2SnGPnHVN2~-^HWe+{cqeFGJn?a@S|bv`}40d%cZ`H`TyO;N9WH! zx_WO`U>gQ(0Qlvr(}QOo78PZGp8fdnUU}`Gs!7Jd+OMWyyJktHGAQuS)uYElQ=rR` z>hFimFXl&1B5w`N-nu$7lS$=YioCM1=eq{8@9!~bNa}J~t+@|Mw&zaT(O(JtT7{Nc z1zHIf)M|7`tI*eRTL)5TqilBCoX};PQ!|4F6v0wqtx-);@TjB;0}Z5FNUAkr!B|Wd zw_BpxO7_^C*jHI>##0Lkv)pcX+N?qOz3N#>*%>8t)Mg1sX&rllD#DVp0gXpecMgvM zUz@E?a6BmYf)Si3gNy*%K;ZT|Y_X_06UZR&9A+k1)-?F2R13xmTnkDoAo~p53UgM< z+Yk-nb`@@DCk+_jjrjTYw^v|-6>&ERZaW~sj$Xf}9W@9C?!^nM;ame5Nbp)WCFlxd z(!zBGo5Qk)tmp-8h55pDeGd0Eudf27vxD_szr#3TF>2&feH9?;r5=sws?yP0+2ieT zdo_8mk}CCPhaxtG<{r%&R0~QvzLkz1O+b>}HdBgL)wA2^ue?<^p}zzzI8@JtcDhGc zZl#u<;mSLd3mZpEf*Y#TNV;nCCY#0cl+mMBkJV}sCTlCeOwEevMr*6nq#xlzi4~T! zgCaD;Njk4s_`q3OVE4pSze)NaHEB7B7!@ZHDyEWz*xGS$w%gxlBEFR7Q zRZEvbTkRw=v@x0#i;rk|nYJ-I5kM%A8rP^`R*wkP{U$)}!vER2qMxSnG&(JX(Bd{N zwSY-d@V3^!(2Eo$nlBu?d!?VP=)W z%y1Vual$I3c4-No(pIk<+&3+x*%!4^d-b=(63neq!fR#2n*hO0B?NlW45m4UH;y`V zB9cycTfB+%k|1p&CeRj1b*0fBMzc8L&0rQOnh9hCb5q_l$8`mUp|}#fT~Hx`&`3qt z1wI{_A^Xi-f(VNSlLHk1@W9MKEJI+%sBmS5>4k8igv}KT*&x6JkxXDFx)5X5!T^Gi z=$CZ~b!tQ@$+wfGLZu6}Z&t3OM|!{N|8XGU(8vigV1cY{fz3^*piyoHJP8dZ4nJb8 zRsi@{lgq0I1_1Zhjsf>iU<`=>tdak26^bCgtEJy83K$=(YU_o`$p>%V*4Rh)PYn$| z+smK*bU&ZJy!Z0E7w0~z2zNKSQ9{8Gmqns2?y|+9V6fIB)|2s@ z^;AjAUlH6^;bFtX5o_S#$5da1lnmM+!lMT28eL&Fg!NAFSAh!`I!^z|Nbm(ROvtB+ zGfcyMQC1EoU~{?BT(vxpll=s1KRw9UcxV-Y@b$)*D#K&h8(C99b zP&@-or(QqF6$*R!WMWZ?i7rE{%pSW7$O2uw4I>)RrmDkO|b8^>ViOi zHB}Lvu^^PEh$m@0Oa2PwNtRa>00V*91O9OTEJ`frj?o#Tn~}!%*6>3Yh@%B8Jsuk% zuY`Z{lBjv@;Z*1^J6Qlc-YqQ~;El7v67;clm3^p63o2d_E0X({Y$m6f*39Ehg#3=9 z+-yeDksTh<&bp^Cu@bO64`)iV%0@EVZ*dG5JXBB<;e<|PDq+yq%(Aq{>4e7ytv!@e zN249nM*{L;713aFs(B;mtCF&>K3{~RCb=m`g{m6bFdBC_Ew==SpW6LNI7d7E@W#T3 za1vHog0Zl{a-u4o^!PFToAf08VL#f%9*f^{(~oclw29$D8SM1Hg;I9z?DY_X;n&d# zm*`%B-XL#*1(t`t(Ve~Q1ot3(0e~uS+ap-o!z84em^$ihp!~V1sk5yoD9}r54&lqe zBZAQ2y`4Qr5Q}t_i3|eH7z9T80&FKyux>!^LbFik2DE?S!|_MiluuduZUAh-e38(g z)X)uC7)iEe+b~;%R0ax|84ui?ZEkZkp-b!lLC!X#0G*{VbO*&uM z4@TX%FTwlu2&6b>c~dZehVwJhk)l>#6cuS<#X^ZAaHRAR&mgywyM2)~)M(F{JOBV7 z07*naR9O*KgBHrU5KW^u3_D8Z5mmgPx|x}l1zKW6eU&u$X%y2&6#>Lp09MfQF^~?# zW-x0Miw$@OsIQ74^;fx1!Vrr!WteY(LPyaG&IBrO;%H$+A$!eGN6$oJ-Whh1mC67$HpdCgaPwmx{>A7 zPxtrt_V!Mm&0ju20N$9p0{~u`)8GE?01B#TVDxTlFq10iwH*QAAtMO5FF*ehV@OxD zYX^_k3WYTmpm%EVoC}Jo68c9f=(2Y8+i$6cey2*%K;S7ghlGDq*DwC$w0CgivsUK* zV*EGM_iHd;&|nIm;YEpXLUe$siI$DOcsY6$N1TW&;UXH_Xp9wa#GpI+H!7=>V|lJR zv~Ey3a?4*r`k^52XlqFC|As3H`U!*fH9 z{Py*q%ZsSy{(ObPsAblVp^(~^|EkI@7gV)h?$5Ulb}Q_rgjyaxeQy)hZ~~(a!U}&4 z4IS49HBV8sC1!7E8_PMNz?;7Z04oue@LwSC$Ptm$srPY>TeU5_#{qYp3}ByXk`b%Xcn2lYfquleCij?&{)v}ns_UhY=@&c>&OCYnM4Q-1}>j!15-v} z+VO$>^3RV$?+iVaoeq?O#R9r`AvM}Klw_-eEfzY$kT~1W2}URqYS4|sj_a9TNO_h( zuI|M_=&Wbe8Ri0*Is*GeI-8aANr)KaK6NhTLFuz$+6Wd|C@Bjwz;H11(kURaub#bQ z)!r2xhku_Jb?SsXIN?t4N*qH;OV$)J6|CN<)oV>eQE2W;d%G5_2my8{d@0p9cBKSo z(f*BMhRB8baw3%h6t_e$+>4YXw|9x|lTkUM94%8xAPPzLPsv^oKu0R63Q;+li2$Gj zExr~+A$TET_OkoSP^3T<{I)`O=g5puR!kUWkPkdC0PJny3^4dCfLMrcgr3kbOeo821&#k1pUI@a?p$00QVfM_XVP4Iy^|>^H!EbyMg6$pijo|CtWJE82ko@YtCA z8{-#lz*K`*`E^-aeR0~72%@(y%VX+7#-rXhuzttT$ zl#TSzF{+>ig)i@YPX_$x(ayEp?^cSO+tnUxs_sb9l~H@-HcEr<0r<{;{yn6dK~H^t zE`Rw8VZeo4@!C}~V7`0r)Ls<$8lq}dgVv8$C@gDN<#Dj$c+o#B$U99ZN&+#{kcO{c z{NxY5Jfzlp5|>3!gj^b6tlQvk5{!Uf0a`xAsk z0OiD&s6HQuD^&Z}H_Mb85lM1eRdB1aOXEDD+MsQ%uz1Y6D*<@#^3V2124S)#;5)23 z%QSmzKl4@?@Z$Ey#`;!it5npA+HMKTcugx7SBs_HQn9pgcVlB?b9wPfWiS7csy=rs z!)D;to6YiX0l=Iw+ad+Np#$)HUixb1l@5+~ba1>jyIy7qdh^LUg8>Wtp4~t6;fc^0 z%EeT6;G2sEDaX&V{l4yeL*e{Rb@omFE?m0l04z(993QQpisz&A`+af-AbX}zZ9*uxsPN;!_+ zEyAtz+c8$SA4c2X#_oO)?(ewQJYTQpmw1Fy1|(OcLH8{6 z;xUSMgqE}hI1&lzxULV`v8;z=g_6{332B5jqDFDq5c(_qLzy3z|kkdOvw>aS( z@=SssiHan6E-Y95NnQ)y|j#^&f!DfgpWY-@}Lo!aKRoyHQowbbaY9S!JH?WYkR0fR)X(7G28OT~u z6+L@mS^+Ff*dt7r_(_sD1jV9cWW^Tn_jb#FiOnRfM?ov5(a`9uh@`w5435N@Mkhc) z;lZ(BR6sD1yPJc93J}tk6zo2lqqs=WwQnpnMkNx`=fqKJfm1|X$zcK3u~aT-ijSy1 z>P~1_M|Z+(hVcvsg-XlUG}d1^b)=8YuzrPPZbWU%#D3W8;hb>u@Y1!PWl^3#``tV2 zfagl3`^92$?OZ*|>a`d9=DGXT)u$W3uQT9nKHa4vtlNdEs;>&g=U4eaz_=<;yzBa$ zo7W_)^T+EETABq-_R}us0}am=?sq{4tk-9{M_2j zA5m7T3=135#UCc~rP9Qmnacq1#M*89#q9dz33u_1?tHJZ?o-?~^!K(IK??wXT{Zx0 zmmulx*H%G~Uij>{Z+zY-0DKk;5;)s0xT{X2586m5G}>p(!MKpx&K}apj&GeBN2C2- zPAvuV>nKQQZ(~3ZS-{q^09{=Q6d%f^gFU$u9H78F^Qz z7Dzc=Twh-n25fe~b_bF+8FY31$sR$Qe-mZE^JW5VCc`i4O#OkGLYqPPOtH2DHcQ|i z{(Xh;swZ#B>&f>hjTqJJkHME^Th|N+p15zmj*Y-_xv_0Mf3cGQ^EIaBQsk=qqSy*) z`QBB&|L)>jXOG#_XS2gLs&M%(|Kn(2H<25{bP1Rg_TtkiG)rAJdqYib_mCX-In=f5 z_POa79CGmCFlYH1*x|x{(JNDC2r3Uaa0#;r7Q`LU=;%)Pu%L8CrPBKcga_~5FSnUx zbEdn=Cx9(ze!V82rg9L{3sb&MG}eGBuwcN1TxERMNxb3~MkIt-13gUx`-T28eQxR$ za9-+Z>V*$yAikX)y#ty;+1nI}4+s&?WCVQU`+FmC`F!d_>W#;*Q;-zz(csBUM{f@k zW{|o=!CBEb6j`ExVM+*a52+oLG(@JB*!T+g#+fy@ate(M@LqzUBj9gDLp!vY(8Upz zSGBGXxuL0(aAIm1@Exsy!@_OHTV0{QgoP<1n#OY!g4MbNWShBD9w)HrYG&apgt{HJ zE2MWtix|*C>#De&1u;yQ`{`I17fLJlthBqvS6nUQk%HaUzEkr`g zeSWtIg_iTwER6J-`Lef`Lg|bFxPGTjhpB_X`HQm33b6eWw%bS?mK8X~0$B&m{&dVA z6$sVGSQ^KXjHMAcdkhzrhstxCK&+W}YQiFRJlcdqpRUtWuI z&aXZE@h6&)bP9dpD?5r32K@E?dXr-9LG_24{7Ey5v_H^1%F1eSnh`WRV8z{f6Cpy{ zuE7hRee%Yqx%ZeelLjr2%Y?bV4JmYgn_Uxp(%6ws(vu{(e6s)0-!yE4O^X-qt5=(( zo|A&E7nb}2s8&(E!R&w4u;g?HJl^DA57?{UeQosyhT1z50bTb5LxR-@9DM)7Gu^iY z9m#*z7T{3=BAEB?y(J8I(&&2UV8Ed5iyh-#13v%{6!`J7oP;i#z45QGAzi$5qJQrm zJ9To<&UsWn(XCfolXLe;VYySdTAVKy=VuBet4&XXzy&VIxN}{8zV5zrrJo)oLxIW3 z_^7Mvvfen{;Kr8(4ihcu(B-U9U$+l%bU22fyF+9^Vof5b3bfA9 z#lUI94lM(2(0#7Y*U;HOvU9_A!DNTvC6QaZH7H99fEA>D1Ne!c-}EuaVR9#ZolOer zopLm@dv}HrH<2F5urdnK`oN}v-Bb+{v(bqrE0gIQ@b&UeAhrWvQd7p)`A>!03~S(c zhS7Aqm)mTM<2sKfB1`?g!gPB(_rsEVLp?p6%_L@ZEa@$+`;BYtBu#~QkMQ<3_qa^z zb7YFeFD~FnE9o4eIBCz#9rA}6bMrW7#G9v@RbB<@r8=1SXmrmVE3H#5>KMjBW*92E z=Vnz#j|-FiGOS);f!B~JJQBQhg@madQ6F%)edP#1$^@F-Ey2=qJfz$;+}hHtI;{5A z6#}tH-#8r(e`!{}WK*8j(5xd$c-sY%!$(@q@L5iiMTt+z%%j`ecTxE(KOwx43$jLm z++j_h^s^Ig@XF5z5gd(vbpew-Ni)(7&5ajw>u?f;CFEF;(5+a^QE*sC)o$H>VR1Yq zPdaj)A5+DZ-*0*GW2oknlw7A$f&fi~3cQx;QUU^{X6?&;F~T)i_)TiU|_IYxdJmGjeryn!^n-^7A2Tz@o>^uUml0;$1dEQ=`GAJqU#Pu5DO zlVn>Zg$h$IxETf2DEFhIK^X9Y#eVfJo8VYtHrw6J2wK=RnUJ$WR>x*jQ4%TTO)i-t zHpt2ymP?G0zJci%obCgZ`_N&b*oyWA%@(*;OPE4XC0|6_kdRk__KDnV zGB+DcMN_$4!XvCZ$9Z6HH*~z4@pEo=BylAEa|V2vB&($D} zv#qW2a&>LF`fTgon;VOjH91hJRM#u_oW^1o0qq0zF{+i{^cW;K|eA{SX5_b6WG{nNNQqg50Mi8}u>Zw2 zOR|dFc=+FIS_rIL;Io%%09>4zzF(>}8`s()w%^)sN~Illl@MVSr=OyRE^VDRE+k_D z))=e{qh04e|KxX{rry>7j+1IY`oN@Nsq(6y#jlCPGVKi9*@g|t@_2Pu;-O!Gt47m} z6mTvCOq4nHBYyg^302fW6=%9?yz?`%U`eGAM6-u8XXFIFb=%M6d#Kd|@ro&zCTlwjj? zAWq`=InVn(AL?s5Z)tv8@ZiW_QOoOp>`h%O+|B6#x+wJ7Og2rYv*|3a1~V(IyitGw zUp;c{xG7)Kp5l&?<2T>@D_za&2>P+9kIFt){5^;zHJRz#A+$WITi{ZDt@Kb(-lzxw zKlt72xw)S``qdVD;GVM@hkaZNjQ(Db7f#+-$jP7l`qb*gq^gE{59l%YO}eMc0iF~vdz9+Z+|LS zNGafemLLJg0=qeUl$w%!DGUK{;L zX3KBAnH4QCyrOF9UiqCd32QThmIMR$L}jTcnmY-=SnpDklt6uL6K+djbWml|a^D$Y z<{S}VCF(g5IT5W72A}lCXiEwzO6vex&{uGmpeuA%!N`eNBK9Q0=vj!caNB4bBkNe3 zx{Xq-dzT`biAC2@L}$y9+5ijQK(sB|ma2_VxghAA0-otW!qyuL)ZkTOiOW(~ptdaq zR<{a^r7oD<=UVo`&8_ALnz9D0On;bcXb@D^e5|9SUkSzv@~U}>Z7>VMyz&ZKp{|fdBroj@n10=g&_4uL?MjPsAhZk!Q z2X9qEC|&LB&cgl&p2fytKm3)i85OEK8YV4zQ9f~bhKD^ua0e+G25spc^oJU0A`JV< z$a01J;kevw40#~AD#P+Gs26;lfSwNPkGs_e$sKrvCA68X44<)H&YW z-H$@LpV%r5iSB3V+i8YhHJM42akT;WD;)C;J3GzvD|xhE71uN*jp;5JBT~EIeOy&p zed~Sk8=Vc2{|8_*igKM1bb(RfcBWFQR!TcNdpm0zxdKRBDH$8sD|h6x`}cQV-v8p# zi?`5g;c&-QRY6<+qhfYuCL?H${<&BMfrSBU5|-s2w&u_u2>!nR>=#>)RD`ty1Ah2W z-|lW3xlGQ;q_gFjg>qG>Q#m)YVaWTpVa$}}wz`^=+g$GPU1P?`{P(q>@5F>M>rb!# zcGuhiXVSA}yq)T8{YXfUVmBE^X5a#|$a&S}Y9WIK>v;&9?touRAcCGS0a#bTSb`@A z;s~A8g)dTQjllYHU;RuH$B~N{)E4}y786pwBS-$k#Mw>-r$Dfq@=cQmqs$_Q)vRjp zBZO|mJ>Wu#)z~;VDF1i-eLr42a>VKZ{>RPv_PCRfSE;B!ZB?Zn1(GJI;*!^Y!k|wdsN(L|1+Y_`-h)B7*`81kV(81Z`CE(^K7#uJ)Wg zud`vxj3iI<&8vIG!dl_L6qS8^5F{$k=hXo6f`v%g_tdRHS4lTfl#XQ-S1X#+QLjx5bREHV zlXjcKCXCma#3}4FGp*{?g_Q6mopzhboO_*MHuGs6G%M@14aiq$wwA)MO(k0_h))Qo zHe)A~NUsRtP-3hVO#;b6gAqDAdlS)wGZFFi2A6|Rv;i3EiwBrs4(%IMBAmb*j034x z$ZfCYU`2T-x`a+z8FDZZOPru|!5mQ|%hCoU#?B;kd>e>G)Ggc=jXh~=iv^Vbk~;~( z6>Jt-EU=tPwGt7n5tXr85LR1&VZ}9?dqquQZ6MWNX0b>QFGV`ZaT(SrxYm>@u+yaMdbd!k$rV(HLBZD63f$JOq7( z@YYN=FlVmQa7q%RYgF|tFsnIQI&dZin)^q!4~a!`GcY_!WHiSSVY!nIpMWf?05{cy zg0?=l0}GN|YB79vYYQQjgkHDZTAv~6>N_tI^V)4Yusz zm_W0~>v0HddfWAVCd?if3(}z171oSCm!=hHNs{p2!9fr3tf5#qeKGgSZy9z82M#ZK zcn4#?tiDP)KG-hwmC6PLRpCJj3h@Gu4g;%$CggIEN+h}UD8`0HLk~tFx~zvE#0AGS z{#nQ^Ig_Jf44UO@hIOh--t%w>0Ti<1kT726&T)b4zR^$!7qEaSNEo_t?565I)7qtw!LNzKOsi^rR~$3jS~N&OfD zgtbbT>9)|}P`|F8Lrsdr%*ECJ)EDoojUCcpS%pXfz@J%3SfyfSW??(CeZO231b(@< zQQ9y{%7rV%()~T*!iA0MT6M2->5}KxL7=4OX?;QxmH=>NVIiBzW-~tskZ00RALy_- zb2P4hvAJu8QGaDdaeVUCNv+>Oge464#ZJYTrGp9c)4hxkSR()pK=QvcJ3CWNXN>Lb z*<3YU6hO`xM!L9@+5VwiP3NlemYyp*IrE<3cIV6%c~`!ggJTIo5F{uU!G&^4EIHZHK9hN^QfRd z|9$A>1)AxE1Yi7;0IUm$qBZ}Dy|393tgQ@YC4(UI-#n^9loz#QP_IC>g@o=A9`?9& ze}jJ>C6>#}SV*10*a$qGKYnbIUvmcC({pGBeae(WYrEiw2S%h*J-5~`Ump7A4m}BK z)or<{-3a>m@&D|7#N=5RV>y4ofKAwaXS{35kBq`R1sQVk+LSQhm%Hi%J`1aE`C4lS zp_e0?OnD0c&aVpbT@cbcv$`smVgkJBw6SVkoaLB^tmdcIzL}frIinUS`7Sp*)J@y* z=HK^{eNIK18Lmzq4CN*|zO|V%a z>;&V3KK1;{-DPJY3YktMNT%#HgEs_&DIVt2V31k{VZa!W5`<7j$jD;G9E>g_dG1XF zV@R<;+Y^x`@;M@OAVrx$CxBbw#K9#EqeP}v8^vj)MGQ-|0IcAyqHt}XH5N!kg#@c2 zdP$8(kld(HTNpA?lt{3?ZCy$UTsJhc5T+6-5J=I0M6yOe_-?}_@syen-P#Hc;{?W{ zL?%{^3a#X%<{ISDXtF?C)B9V4L|TpqYE=M@5^J)dd9u!GW$4ng*#i%0_(sxvpkNfOx1zMObx1UGHHu65LH^&LzPzfHswR4{R906cFymyLmESJ zjjzoO1n#-#`JESVV|tV94wv6f4>0x-mL-@2DC=i;k{`U%=XAK8!H~E@I7Sko{Y;oGIUALDCY}$rU2l5vTx+}nQFA3Pw(fj{WJyKD&&6?MOhVLJ=*x` z{rO}vnMp^}N=KCvMm|!? zm&%buE@EV4o7OXla>U4|Bl%pJ4@Po1(Dh6L+jLo@2y6ZOQ2}1AJu5R3vpCL-0)Ri> zJKHw`c1ww~=&wdZhNW^hKzUV4mI7d|R8LIweJO5untaWT4Xo;HZDcb8sIXEd;u4Zq zt1g0W9T%Qeg&2OJTI($CuO<}UN*9u{1P{KP0#_hc!l7jbOeTE#6X)f>HrpQp8dWFY z*qJdE-ps0ihc9;NK045%**~wpWWcYQY-I*qS$s{TR#ydpvjV^rVLf_x@R<@Gk-bU~ zG@}^LECYbU>r=6KRKs^(%g)RcaaE^j2YPHKiR&j_H*^CKoK41d_qYU2!gx_QqiDLu zetr7CNOCvBS}ZL%?bcXYwrZPLUo=(Kd{mS-OO4Yb^9KiHu4(uQ-x~9-A&miUvPmmSxRQQ$?vYL~yQ=1ZXigk@{A9 zlyE43@my{9obn8tx`(QKmqiS*^B`nv|S`?f3B%re6(Q zlTyNV)vh4sVcY@aTCX(^+_y3ZtMgjtU9ky^+?l3eATdes0If(8&(Ya_x4E8H;N~~z zHfpjk1blp4#=%YFtRN&OHjQ%^C%`oQ;<~)%8^A0c2WKWNR&7YsXtmM>%t&bPWJdZ( zPa*iMiRdeZY_qZ-L|2jvT-0aHVk1RJT*2m0_#2$H z0H{HmWA*``?*iJ=y6XTQJ0Ad#IRXw&f*H@^E^a~ke`on5#&h@_*f1iROW1a&D|nOh z-i1ZJ`$dy(9#0$2@%r4leCg$v}HE<6q(cf0o%{qD^r zJ{AapoCam}m;md(vgF-7e;&LyAdy&sfG}MzSCj2aOGH=#HI-Jp6C%C!+i!Ad8b@Q= z2br`OemM%pfkFY6AhHJ{z}@UtVzBgP$Qg2NVn=)1YXU6(89aTsqS}yB46rKWmd=-= ziQJPHKNNDhktY=Im!bu1pA_=xbRji0wfCDYLIL2Fs~?GgItCaQ{Z%?$CIqJifOqGo z<{89sTLEyt2&P6yKRW{8AAgV_4po!D65?$=zV_INtVK(aH6tC@%J{?y9jEX_B#tfk za5PF_*74ZE?S%#M>gE3BvA&fJX+xq2i)YOP0D3gX1#MglppXnS^gf~|u<-aa~wDxs4j;KEV~ zjN5U%4GJsn`iUg|? zyfIi6M4ujf#fWsg;s-u{+kg3T^Oet~3iy_qOcIBNasSrE&$o83haYpWnV^h3POuXz zth~qdxZ3g#@G_AKUnge8bGxxHgE$TWz|(I@?6EWwa=@zMkS{&|xo~}bDjbhBMJ4Xx!AwrNDznABR8WUO@1t5YoeE15*5Srqp8cuPt;j6S zN-h|$Ngn!btXZ&FgteLkacd-?szo9v>FialM`WX0O{RNNx?o~;15nX?L5xV^TH0!& zF1ktD0x!&&<^)G;Ylfukm#*G%6N?p^B$%U?cBHL)%;}(?nC(f-mgJEE;p0uUbxfM% zYPCm8QFejA9=k#7 z5eP7_xwn@(Dv@A$+NAXtPbXB9AG7j^O@$()673ZeI6!f45LJQ8R7c}}CsDZVE*lEz z`aNc4=Wo50OV1QMTd#o=Gxm!9-e!(%fw*G##p{^)EY!GD)iZ#Etuu={tIlSzh?$W| z9k`~SLGazy238L;Alg4EfgOuJN#SU4w)$BD43upJ zI0L@Pf*lSgv5eZOS$dJ&4QvEv(3TI#?RLyM893>5?%91oa8KOx`TQ&-`7dZOzIL4Xu`Mbak^pcu33^QFp!+|1`*$Co z?;GqBf%62TpqX|xsQQqU`-mItIWFofNx~ZWl0Vdqtm))%*Fk@;g^CADLtUe})i%lB z9A1|;&;MNrS6P(5zwr19tuG@_Sc4A@UAO zX5__ND!Q3c=;trOvG5MQ*;+0fTMZ|Z$s#i{sxcYKadKdWgM$GBfR8hmi|Vca zlXbPfY29ZufQ`7YT^X1y7Zyf+UBJ}PN+q>T=xT{Cj?~81rc7ks7|fB=4rg+r3R?~Y z%dTD78YFVTDM6dVR)=Vo)lExFrY*~hyR4D=VXFFVoA$xd{(=4jd(Qdcq}u$(+f4;B z^||MH&I`dDPw%ULe9@@C(qbSq_xII$r+(pQEk-rBUTUeV>K3lb-Hfeny(HgF0C2nc zz929Fc=7&2p5OJ$D?SH&m$QV6!ho*`1D1Ez7A(CBbh#mugb5q$o}fD#+JL8#m9)b# zR8wwMEAm#v2zsIVx5w*mzSvP%vkD27PLs?Q8T!+3H^t6WGH=UYR$CXFfB~JH4GT=_ zHl3m>A)}zfQ$kk3g>_nm(QqULSkKCTM%b>t4S%q63Z+M2)cBWi7ApwHb*e%_lg>0r zxz8;4jGeBo3wnYTZ+D@7P&c!C!5q+eCq&U*+3WF+byzMDi4_looftDavst-}2cmH* znvpmOcol|>-a#}P3aUB-7)c|MLvT3$DY_Tr;DKnIk}A1^uR=CPiX4cb`v|NU02?93 zA{^Qmi$xrW;1EoP;tG)+k=Q^!62n5c;PG9KDBqFKS*$9LR)@c?+r=sQ~=7 zdXz7?hB>qY2Y67lfa$b@QP2(oF%UNowe&}w?XJr|;_`7bEM(Y=vO$lq-5$)OiM=kU zt43J7Adn6fH3By%)ygwwgOaR#54}nV-VjvIk8t-Zcgb<^8@W^&us`3!z3|x{mt3_X zivuYh^1!hf{kjDnaf>ir=0eZt7UW^sOm?BOQ)XmvK!7C=&mefi!aXo{z!sbQJuzb; zjA~$XF(8eDQ)jm_9$^xV{v*3x>lXBcyP_L`1oGEN38vu25bQ)>Arhcr%wVY?lB@(f z4Yxhhi#i$2uw&h;vMbRDEU=lu09rGy8hii)XiMm7Dx9oN z)PtxZ9M7EBi1AF@$b@o1P0-UFM1w(28#gG2hV)7v6uKES==nY07sTK?n1ghyFVh#q zTw2ig_Ib>JL6)(EMNwn=Fjew88fgSL|+U$P04DE8Iv74T5Gf6+4-f5H$8wa1H(|b?a2Tu;C(`!%KMOQ%(f$3^)kKmATb|ffW2N1em$_9g$|cx2ZdV$6a(hqCK(@AuLc5@zzVg{=WkO;F z12oV8in)uw{Q37rli#JjiW2CtGiu#Cp(f8`6a8un3|$taQ&;`eDUK9Y{ zUEm1%&O7Uik59aIZs;0=j|T^#Z@NbO9sKv5y`{~atu5qk2sxEs6MhTwYgmEs30B}n zxm3P|)w2LFGBS=U@~qOTj(_#Vy+)li2(8vD6u`3rK|ZO6$Hk`VO_T$co*sZ()#g2n zpqqz}gaJ>k-@pIx)G0vl8En4g*�D+Pf`Ir|*S|l3p)-q-CnsN1U4--@{V@~*h0WS5aRlt^c3l_nG_yGYp^#4V zln`K410wv2wMHE@h9sJsUgS#xDLG~amLtjoDa|u>6U!Bx`V`l^C?|Btk8Z0`%#p^Ruos^Q8XdN!tnuQaR|BwJPKuF_$UY;j>fX6B8)`` z9Be8KID7XLOU?W%xqxr=dEY~mY+2bf;e!D3+iV-Nv)L=<`M3O zT}Y!8eq6JDD4^*QDhreaP76O~1himpjbYD7ugstIds)rUQ)5k1$N!6F2EkxMGR(8fcl&|QP>;f$tb3_DY?GRC+@W^9Bq$hHcGP!nwAf|>K2 zGl#~t+|`Vh2qF_&AUL$4A%UY8*AoU3C&v@F<*KmdaqNqO#%-a(;rNTI=fhffNej-E^=(Fly-XNsCfFD1DXo<|H8 zWLU#=DA5kA#LpXK#t3(o9~~t8V zRQeS?Nl2h{qeq+TUkgXn7KTDo7Y!%<=*KU9ZRI;Q*8eR3dF*Kw;j=6(PN8pPE?lsV z-WVhTA3v^ElS6}ZumKRBpumgUy3nSX@&JMooojxSF&iW%hpuW_H+#z4P&1Q3}d{0ib%6o@@ z#RytX5)i{7Z?Lgz9jg=e-|tp&HX-keO0&*3;VQ{AE>%$Gf~th7gIL!)vw%9XG^;FW zs#kB~MeKh|7;*LU@2tQ6ZJa{LD;PwWHES7_BJ1NI!Z*yOnHdwToio=3{jlpbIcHGi z3w8^yF9G%yt!_m0FXCNjl_;MgR5RJv6P(i;RiGcw} zKLrDZAqi_>Pb3@=f{Q(H%ooAf+2=z#md6(mc=mD93_c7yZw%E))&cB*2Ur^H!j_k6 z=z^z!-XoMTfbR;`^|^eGk30;a>c@$ zOW>B;tPw9_E4c#3!WgtT4-s_FF}zmMK02HtCjW5UiAFT*I^e?clGxbKu38!uIe1i7b$LuQCj5JjJ2ErZ6iNXl7+GTXI|wn{q9{D0>(}lY;0zp8{hs2=izFq*@#Iv9gfWz#!I!WPV_; zm_e^F&{;Fu+yAc(=~QD0n$xywI#Fe(FFizinf&YLz+`*7R4U=Llgn-8c5**ETW7#; zW_rx*Zv4DH16D;yR6(bhy#Nr*g8>7b&*%R2pwXbDJ`V454VpgSXUYc*zDv3!)7$%n zvrn0$WX+!EDz;UaJ)2JAx5FhjCwQ4sK>XPzN5B+9pSXH>b)&9=&hRattI&X8pmsS4 zNC1jkjOW5-F^OY~G*v>p%Qt3MWO$vOy#bcC)tCW`|Cb#2s3O2J1Agxp`cI^Y@SIA0 zo|g6nMq&|ykFmB_Cc@Ka#sq<}Vft}IRLySwXMKs6LI*y_-4Uk?&w3}H`?S#W72@SV zZi}jA;Hydh!2TKmoD{O{sZy%?cRFK)RKTP*xH|I zLn_~2H{6kWEfk4oMQq3xY+zlvY?pF5yR=g&KgFYxF9NKyIrahXp4xw# zzFJw+R&78yd#m^A*RQ~Ub0EN!Tjdj61d&ldDwQ<%_<(SFi$8q!diKTc>KUmb6l-$5 z*x{Rhe^$%y)sl=uF~yk9rx5LJ)x2qD^3`NAoda&8};i0e|ny{f$${RFM+}X*0c7d+T9XOGiI{~ z(Pc6AD$FVGX|V%!IZiVdn%%&sL3~B56`t?vxYsowZtmc^wd1ZRy26B2$DCS}7E_Z9 zm6`ZF-z?^$FmE3)JLe!Q%PMy`%t9vSUb(n0fEQ3b$8j;R9zTDWlx}eecTZ^V}%tuxPSIMux+~!<1-I^E|}JXJGD7`1oje0HAxDvtDrG z0TSiWA#h|CApw>L)Z3<&N}VU!;Xn;mKXuRK!<|%Ri75Iz^!);2B@rAD?3(B52zYP@@s|melV^_ zv5%OMqKlgLBn~JQd6ur<(qc3L(+ce4u$7kEpibQuK8xv7i(H}h0ir|Wh6GqjInp@e zGiW;UF>S+lh2_7D%>W-rwK2_T|pXh4YoPm9APJ3o;Pdo35kRw- zaO|84$T}lKVtoBOJW-u8kP+RXSbpUIR9+1pDP3S8cAFRoD4E8QtVC0`w0N)l<*@1@ z{I>XLq8(PX&$7%3o6iK=IA$HeN{`=?wk2_ zo|&~z@JY?gC)Yp8r?@3~-%OY_Y);n9bcV}9&42&^AOJ~3K~zSny>)C+-AEj2m+iU; zYqeoRn#OO)0XSiJ>1FQ253gtO%^9ljY#V556|B5n%H-e3MYxN?*d}0SM>8Wjh`LQ-m!rwi zMT^jBl3zeF7&b{QQ?*1ME$}=K*d3Z@u%z-6H-)7LiR0UjF3?_(;4mYw)R(dhJv1a? zSm6;O^^jz8j5L1{o(p%40CWMqJo^HqmfGk!;PDWU6?}JYV1zoYVX$9-HjPNbbH{<% zfL5YzpM-CWj7rWGKz9`2+~>yyHjaSk`j3k)nt@o1f%dP7=!z;Uwie#@cMr(mm-JQ= zpxc=oJwWL6OF?kEKyNE&!ixF!b+_MXT?2ZzviY~2h9bao_nN<_eXU0Z!=JVa3gb4| zdZfyL!H2v1`~CiYN#3}_P%P5o<^I-(%goW}WLPCvo|z&I{))Yq=|& zuUAl*2m1k~!Q%UkC*pR4P&q=EUygOd8J#R41y$7nh- z0s)Ryfy5%qGW46Y|LQToo_LXhp(lcQblx&=%82W6@%?CV?DB}7T;^_Qv=JGk$2UXq zsklLkIyE^yH3|F$0UlSgV5P;HR8C(&wH^vx5zaixZY0A89M@x7oJ-bJM29r0pkpM# zV7?)-{Q`?0ks7nL0bs7j4b{>RWI~tTKJehbz`NNP1ON8>`>VU00pG}3+gyVt1;!gE zAXpZUp96unKi>WrBp4KU2ORhZXC;cVk%gr$dUvn=UNK-Qsfl|e86Yuy|4rtzvIJdv z^{oS$i^dnH1%9~%{ap#-u=qZ`p2`RXR^lBBaZ`z>39BsehD89bT_{!xm29PwtMK2} zRxa^CBv>NCViFc-z*|*tEim9Dt7Ji$GNx*+v#=@gv|0e#@b)Szz;)c>*7b`0)Ut|| z3)ytKtW?nNEY+3Ik_Ih_95XW~{_&$9|4KhLp$5GZLV;xpJUu<}fs#LeP&XtUIwx@* zvIhOwE1BnHbN=N;@Wap7#ViJ328zmfhB0tWL1Z{;ZBR%vY$`;DEqN!sLj@4e@qQ>~Tr`9fJN5||1IrYnWlS}N$L7vFyG(GxCyp?~;% zzis%OW=X66YgNE=8+F)Qv|Q*?-VFh$f>i_SPell>U07QE@R`MgPHIx6U;*;rpF6c%=x%?3yLMzg>j;aJaszm4^E#9mau?|=SJ z;((pT{_t^~`n0V~^`C!kYfboB#mTT2~vs$Yb>Ti^rgy}VhdRu}Z4Fvu?GvIGF%_t7(pKR&E;A8MW5u0fnV_Mtzg+k-wFIJ|88AhAL* zh0r-jLU3CU5wsVbGlt9_V{Wj`(trI#Cj>FRg5ANCE&1Xh?aN|MDURw9lSPw=r1$W9 zknT_gcX#JWncbc-H&;L)^5gpGD<%>#g=c1eIsYL zp}VS+qeT7ksE{0sz~TfgY1PIFn*r-E6-!1FsI-#!UM1g+Bvyo7+fLF=ESV(v2p~rw zabn)eUZFXmYBmvwJ2vYLW|5Ud_Z%1qAkUiTSrMw;zyQ*#6%065=0gBGj^--Vk+k^W zf!XlDESpG>^;$TBlZGnZ09|Pm)qSEgM$ZAPu&xc5vowLhBJUCU(|UgRWfMX7nIYvM z{*>sn%)N3@P-O%>Xpd6jhD<>vlB$~4LxKIF*};Gt@FLd=pphPQWwFk7iiP1m+Z49< zV!H`tv_%o}>#krfhY1H>&s@BDVQvsNjy6&Vz1d)v1tV`Rry4is?ebU$+MJ>3Ihze- z4^^^WarG`zw-H5X-dJuQ7^_=z;q!NS546#K?sA43<~Zpj(7Ih_zgKnfvL!DNiYol} zEDOHNot>tHR&_ku*)sy0t=<)IC)3j=!s_f1iB%krOk#aCJ!w`O2Zn@N+&HF%R7&P{ z(e=R4jr8P@Ed-A~m8M5MGAW3YurRbdeS_uS(a{<4StnN=d|=`RJ?J4SV0M6=J=Vy? z^S$YrG#C`RxADRndwz5q<*1F3StlQ)dj`wE9k8yKO#c&3*E37Cj zc7df|^Vpa;r#czY^!S9;vf}y-TTPi6Rl3{spU2E@@~L!&Hg`Jhwv$j`jbt+V5PEGV znZ)97_@)2TVBLS^Azj6PWJVmA1lH^IX1RW=LZVSqRq%gq?(Y7+Dh68*`YixFcjit2 zx0=a^9(?+fB_d$An$7%9ai@{jPf`8E-9c7WDsG&4;>;Ps7#w?B23k-4?7fy3^y0ox z{(kFbZI^asDPOU~Uo=!UI2425!BEFELqW3Vi4ea%A-(y)-rmvCy$#?W8g!5DO@sHw!h5N}2VWVz@0X!t zuUO8X%gaLvEe0Pyd$RwJH&H<^td|PnOu1HG&_&YaHwu+q-4$Piq)M&I0HIo|SE{uF zY%5jDwbeOmLEpW&?;#=%u(lXB^Cy#14WI2l`;E(BC#h+9t}mydaw|Hm)~lr|8alqg32`%Vx8|cJaDSsF%j4pMKja zfJ-;s8q$@g7ax3RpPK=z%sy=m_>=u-pWT|fc=2knQDQBvS{Gbv_04*%TB_((0d>3z z;HutQ$cw$@Vzr7=PhX{KwPf*7t;MV*){p@3?}#C^Ok|{P#~HVq4(l&7?S5}6m&V-$x7&A#>_VQV zl9|*&GpQDOyMLfxMN<>4RzRq11fhrW(UYCG=u2D zLDrV66>SLa>kEsRv)3@m;&^}9Z5{PdyAHk%h{a*r$XH>ah=#got*D5RI}e)oBop5d z9$2v4`C##;!P(Xx(%}9hr%v6q=E>Uh!Rz=}vZp+aDV-|4HnxCOchI zjx{75ldd3ePxm0SGH*(VOW`|7$viaF)!Ad+=1FWf+EG}chZe67EMv&Q!Y^3Iw{mFm z2D9PO(dp62=^m`FP-RUIO^@`LCTj$FGaJ1_;+P)pCHI#%O_N7Bn%*`c*2Lsc@1zAI z;rWa-xs!ch8}x3AhUWg5W+QiWf?z-#DANQe5DG{nl12TR_(}*qb}X}WJQbAX%<+`mR6*g}bH*YnIC|P&whF|#mhA8#cmH_Ki4 zqWp)opsP(9#wEZ@5MJIYS6fVd$MKieGh3SiXRH3b`XklC#jni;%XX0t-vQu)?JJd# zV$lLE8j>pp^RjDW+nH83Ai43Eb)2o$4FG&m06q_PVJ{u%`^^*U{^uU~>2qTzFr74) zD|h>VivvE$JlMq12O+WBPWn0NNPp5rVHaqn5&amKqd2s-lkwF~#x)A*F1Ft78^x{8 z^9{t1r}NyKkHTGRJ0ESiVci+Wu-AyD`@CmQ$qcyTSFhlHB}7_upgC5d#5(k^*SAyw zH^i7SFQuK508=j3b*Qh>W$|X0k!!Jhxh(vY7p{vu`j>p|0$$L!{`R)ucICuy%Ldxr zoHZ+}7r*)J=G<>C=wJKQvR&-B%D3d$+q9sL8qvUWb6X!SKJ)mA)8C(C7^&OI?}SlZ zx{0O>`Ns8~JVob1<2tYvd-IK*B2H;}O3?-*-@Kl;e%%$o4O@4zFow^sEH1u%w-ec` z%y#{E#?8-eEiEmrR&<$>UntZ|`ORvfRIG0n1>~|mUmfuIR>}pH>6Z)nO1Y?mvS?gJ z7-*SDo11J#Uz}Sq0N-P0<^{vcVY`wzIee)9P4a*V8T4oM3-Q$@>pN%ts(Zyq)xcO` ziHrI<>&tnvz?bwv%3YR~jM4-jdAjkR>xiy?F* z9$CRwLltj=Sm1$VyaS8M$ozZ+3I~W!2**i6>JW~Tl(bk`iL?l!JLYk`0>!FfBY~Ch zuj3s9FNY1nL<9@H;du*Vph0cYXb~B;bb#6N>^0~du*3%Dz~TA90rr8}6%MJ~Rf+p@ zC=d{d`&_gjL*u?9N5TTFO5#})ShXJN3+S$ROuxAU@fE=f78s0ztFP|}lV5x$T^Iwq zz@b63SSY<9Go9#Dmc|e|vi~kW8mw$k7in$G3cPLEtQXSaoQ5XL)0LzDOc_jSlBeww ze$SS*fb9lxz{DSQ{gK!&hD|uV;lWFafEDzCe6O;#qzP zVX9z4s#vIEi*uqByjD5rY*`WdK!dy`9HZ*NgIKVppNFy+2vb)1Y**M7F1P(&T3uDq z+ky2#55btCU79=UjvP87KN!nBSG3dLwAC!3_yx+8JQPFqT5BeXJ*p3FG2h=lW<_* z;4q!A#>Z0xFy2Nbs@Yo35WuV-LQmgU`FYA%Fyw??GYmUJ{kuAIT|HpVT@73^iG->~ zv%`1vqj!IGr4y9>xpIHy#i2pyV~k@s$s0x#vK`EgU?vhm9Uu8r`3o)ukd#>3GGd*X zr6GFLxYU<9?JX0Ey=Fh2PFQrK^!omOPV7A(Kj;HHVz*Fqep7WWtO^?f-?rZQ?faqI zGKFY-Tgyk}g3+qaUhSqAbYhf_CJTJBAqeT~nMjTSFPS@d!l{byrgczG$fKj_l_79* zaqH#q#HmN0{6flAoz?w?YBV_ipY6LT?eWYo5Sl}9V+ulwL&iSj_|n1@eU!&^An3^`*pa z9UcdD`+*3`*@as)>Q-M_0=5E8FHs8cc$jU>U`N*YGj?_=a3 z=c?M6XXxHny~|x$O^FNgmIAG;LQ~FGDzM>W#v|33vNH?My9R5tZ`6k4@6m#zhInO8 z(!P&>15~%E0!=V;RY_Y)ZEf`H*!32BzNb4Vc4<{g-wg-UZUtMya^28aJv+h0eMMyo z8&ntrQ^bouloeJv1CzKJY?xfG1Yo?|lye`c+^Y#Jy~7lXxvH~K^12{)DT3+!%<`Pe zlIAtr8J6Ykp@3C^+E2>k_aVi(x*M<)GimTj#yQ)1gO8_GChO$H}} zG24n*!Dgm5fVFfM z0E53*xtA1bzuL@Vbcj7+QaB(#EMS@$hkR^cEfBMP(RQllAZM;P3eB-ApZvGhz+E4% ze35_}*1&Oy=LpeY^~kNCI!JO2Nk$w)7cb7Qrx|6$Hzj=Dd8qdyyfHxmFG~ThtjynA zytlI2-~VOT4<1-MVGP3{Fc^GI0DkoH<@WZ!o+TuuO9INs2(T{%p-bd}n z&uQ)Vz zP#H|iOJm^na{?Fyo>^z@V$77ElNtxmiCsFqc-=hUtBHwo#}$xh!W_D}O8egzuah%F zqjULh@-Om>sinLCyhI0Pb~SJ(PP3N$^4S@BoPGZJR4Qu*u%L^jfQ=XQv1`K{r^Md} z=l09!QeG;xPgifGQaQY;@|o1xrT8dbAK7u-VY52h-@lX~cbCrgXA?Mii|5Ywr*Zn1 z%;e7BNJ0S1%PXxC^f;c1rw=Ahoa}BKP=Q|y*KB8Z>#NV~GDpX0m6|CC?-f}D;yoO9!KA41uJB`+Tc{wpkk6p;9gEWJLRF}oTb!tau*o7mRBZ`kU@habPMm$ zjiU*`ZJBkpHbMIKHZ{z)C~^T;|Lld-RTL693>-6auosHA7fhuJ#-aLNs@&<;)|Muc zmu+A5hH>OjbzKAa+B5vQ6tAsT(AP!PhpormooIm6=w}pqmP|rqnDW zk;TxlrGxH4u=dYf7p4-f8)Q+shPzB{(7{Y&pcYo-kts^=;{;X>jV1>R-CrgrLF2li zcr}D&!UtJ$)=Cm5qxbljc^Dn%x-TFuUx?xeYISc&0`h~uVT?4AI$||A1F%qXUmS* z!PsP!nMjObfXb9f20N}1`>M@BsK8pRITqlqZos~(^&kZS%U{yx3w3hLIn=HX&P#E+ z8Had>>}`*+_{;_{NFIuj*fGv#iOpbdDAsH%z_8f>m|oK~f`&%+MFW#T%4T1TR@7__ z$GE7ZJmCK;L4We-guI}~FV3g6@e#js|NPLxtA)+Y&E4nM?>t<1wYiA{3lFyzHdoHx z+uT|y^nib?f@#E2xLhNGH@^G+`+q-s2?js^=JDevPqwzUrtt%}wtrYdf(kx*(9EfF z4e7Z6OzdhEcrLkfVF4L}g>p8X&1RRDmUj?bP{6p1eP?_)1`1Qq^nxB@9(*RFB%Wm4 zNb4~Ubg`*S6GJHAW$oSMa`Q7rNf#t_E|)5-AsPG%G+Y6u5696zy!-wiuN;TuJtEFR z?H)OHZjZ@B;s^9D%h1Loi#L1N9R4eJkT~kh(lbqjH)H3(|RR0ow8Dknm=MdJ=3ca9* ze|hHZ3ylA1WcFS+AUr_S?{5TvuQOJ8d?t^DiJf2|;P${7-~hG6Nh)=LYCd7>%JJ?6q7ufx~|7MB?iTwB#0*)_V z_kF!wJ!8mpU-QcC|9t;s`AT{Rz0=d#`E>3vnbLFfn8P5!OX(}}43($FdivU-&ZW!g z+>@u^uNugwr}tlc`^~FYKl~^F{7gmA?{=Qire0RzS8xAq>(2br`m8+sVOqY7@MtV* zJLt1#H8_*<#IhU|@^Z;~I$bIVNH5Q)uPrlw=KTrc`SPSP;O7fR=ekcB^u5}*0{H5b z;c8#s*QpV=y}yd!Ncw)0RY^w4_&Tf92CR-GO`Bvh?5J|r*sClPEvaRMH8uSfB?*?2 zSWU&MGI^D9-}`PnzBRfmwrWO_+HW{Q^2U7wvo@Vt+uUSa*{CZtr3@rK8-X;Ko3YH2 znY@in%t(UKju!c%R!h=CVb!P=44NmI1fMew9aguHKpDwo+S)J&$K#F!S(F09g2mds zz%05==gpBgVEeLBE)!~umq<{TfUHDfjW%E*x!gf5NK-Epk*NqgIH7sZ!eiIMQ>=Cq z8aqh^aDo-EOKujQ3WfpTFxk+=TLlGu1*<7Uf*VIPZ^K7OC2l14z7!$}&!r8?<sxCy(7N#D=rUKR`nlb-B-OrS2X|3U*=;t9>`8Z3wOu%^O+eRjLV6*! z_I}+63q2+pn&^%DYMLNn-mkl10-(`c`Q5^IF(h$p)X>$&E3D=Ud>GEbfbPMdwQ{3D z?FmK|I!q2O#e@NS7D6mo+?4eU2JUKzmGD=877`q#97z)_oir@OC}fCbxlv4T^kDcP z7R9|A)wy#_x5I*-!zyb|If;sR;)unVNiW9g?#cr^>Y@OtOR%*I zQ!r`JBw4~MyM$uO#W9V%00Bo5sOMw=03ZNKL_t*X9HmmNivpjli64>P!6I15Xz$o4 z9Sf{;h4kY1?YK~Pp`+tgZ;FD3j?vcMTXn6s6r_6vhS6*-%Bjkny9Awkv&2T5I>J^> zf@a1nM7v{DqodJG9|#1S9te3`5M^O3mogbo`6@|R_udY2KHqu51aVw1v-irAoRQ99 z)y(hT!85!4Vt-Y5028_W$@K2O3F3J5f1~V6KW+X{_^+U^8A0o*oEKC+@$CJdKi}Is z+S}Xf`*FntU=hZlC-oUdsoX;2Yc##ed%ZH%wYH4S+ zkVg+)E|wmc^xnt!Ds8~RfrlzllsUPzkm(skbUu|%%LNeX!nQJCvrdKsgTbKhmadl9 zL6AEKmzY2^h9-`q*|akBUHal|D#GeS{%n#ePhb3< z2jxS6{}TbNAk;atQeCI+d#eM2w7mIrQo2bljfPk?<09*lZ>}lsf z&zZkWZ*On!@8s?P(d%y(CI(>U^yeZF1Av?V{$wtnn_txm!{zn)VxG59%jKn=nQe6J zMLFP2;&d^`w=Jl9SYG}7iB@RIKjQJs@d$coVd8}GAw3_^xUEwrh4b}$OH1>+LThIa zmzLzwF*3Gg`%RZgNQg_}Riw z>b2@oCkygZ=v!(2wVA5_DH=dfBWUT?Vn9LOe)ovZoHbk0!Uc@V72$G~?XTLFfSlQ4 zV{5ZJEL(EK(!eS{NuBJ+^jouOp^w&P1tO*4)4BjoTARSI5n5MmT1J9pDeet2!>6zo?!OV$}%O-K51(=&Y4Y#^Wstzb%POvhih$V=YP2b385x z%=oz_gXoGH2h_}MQ`!v7Mp(|olTS z;|;nZez-xyg0I~rtkyM7Ds+3La`0g#0~$u$a9KF87B};PR7vMJqXd&i8QSY8b%qY z#zZ04*^eb#PSc2_WWbNQiuMH@!R&#_qtvvGL8t;34hqcDm*nvWgxjLRYJ%_%4hDuj zcLT#IkKnW?3p*A_j&W}IuDs0oqmKx@3S_e>5IWjKV5M9cg%W!NQ*j=lb{>w7dWO3W z1ge2&f#6{QObAvq+l9O;<%y=Cz}ak5Dw}FL7#-GH!qlRm;XzhV zZ%l|P(U2Dw1%^jsV|C~w!tx-WpiPddX3=YtzEsby2X@fWT+$l3YB#oIxd}vM{x&ZVv_GN5_yaH z9`Atne)fFg)0$_V!C$C+3^_Bt2Ormd` z>F(+7`Niq(`qTCGJw4|>JH2;)@BGEiy>o)R1ABs0M@MImI{PkNdJDQ~L*ga!Ljm9) zUcdTgbz9pApPCAqC)dhKIEung^2^(WGVmZYOineLp`0$^ESizi@BhjCS*Or9hAKPY zlk$E-xze<}Oh271&$3RQJuK$YW91KvlnECEe~Ts4Ls;Iy;>2uQAbql8L((it+6Xm} zqZuLejo*CS@Wss@E%_bNL9~J5fq`Gj-(TSZR)MtX2kyMcP+Fk)59Cdfe-%(GaMa@; ztVZ(h(ej1rL0zRd-Rjdb+A9TWr=8%Av9B(6o~=Ny(L(>v4_v8U=rm;bteHt`5?1v` ze++fp(~xEzk2W92LCK%*UdV5?NZU|xeje0C^;TRWJ&f`pIV=-8A+UK^o-Z+m$n&G$ z5!glrEx)f1hI+bjG@-sCgHr2u1wrrW4j2ZUpEcM8_OiBp{CHZozzV?f4BLG(0RWpM zWfMes=G2XU6iOv6LnuAq9nynRakW$^A;2pXmf@m6<}^ELI+8v&ZNR);t8nd^{Rhf` z_ZBAJ{lJ*q_Eco8=@_SOzupz(%r!Xf=E@vGD$9bV*daM=MO^yE)T$>Z_PjjYh(DN2;)vP{H63s2sTu%>gx` zxfTmqZ7*^wE(6Ln$fhkfb-*Z;E$cq8>b7hMwJ0>yRA^$g92uKxuSVQ7D+#Cq=QWND zJ6_G2#Ct>_v}rREBmF<7mqM(Sgss*vDmHENi>|;*HA0yEC}mU zpv8ey+itQr%r02l8SnuMukG(A6MV#m8MtP|PI{XA&uo6-yP862t4N~3YN5J*JKkXB zxkx*0*pWCeCJJ@?4!UiAiW(HAnMNbQLS5ov#7xShAB?4fkeVYEJP!)n#c{-%*Uy+a z8}kz_iKsd1AJzcM?4U+t#bWs)`@zOOJ|n~RJyAuhGWARsmqYzUA};bM$wJTYxV znsBBn6%_^HIpQKBg&>5HMFJzj6ILOu>m-n9GE@PQP*1AVEWDwFWlfegsv<2f_F~gs zMC#wM^EuxiG>KxUZGLubi@H31&Ur3Z(fmaBy*XJT+L%1&+J3IYEjT*tRc4I!*T*V&IMhq~pqV`rZWS8#3Bvh;!e)b*g5la@ixeoGA;B^0+owu&g}{|n5saA!yV%tUGA<6{*EBKTuj0KaiS;3;lNCp zyZjJbItk^lkKuJN==U}>=t!F|k1qEj^qVJlBl-fM7bjE!4H!?z9VSAsVqkg#+tiW# z&wAb%K)3eXJ@xbH#FLFJ0pKBXBDIA6;^t=`m zZSmcM@Qp(sFy8{eKil8?)!y{vo&fNZmrs>1U4b#JT$#^qqQ;s}B~xglZ*BIa(812F z^=+ydb8R3+yzp#xAob%-;J5W6=3=W4*t8+7m=z*KFU#(3Gc%Bd{H|p*_)0h(`5W?A zb$wxh)Q;t)>_|$eUz$%N*GG;2H*C%=EwnJ;k3Z=+t~r$I^VJJ0`xz^eHZXK|muUzk z)97wwSYPx0XR%wFGpuj_L6;7j6@guOy?GAEaDo0G<8raWk=s2^6*#)a@3*%b1F!|V zmJa&ZK^qb%Y%IYCfs|!mcuxFws^bfl2br8H(;C3Gw(^HZ@pvq|rXzhYXMOYG(()4Z zyURMP7Z#`;y!dWdq03>`=9!Z*1>i(tdcUR9;7+B=u=HBErn2)tFSg^Ckzu80FKH5} z!td@qzVF?mYs>6_1)-lMrpr3dS&yNM)$=AP zO+Tyc@*;Q509wV?FyJRf1-)l-Ub;Kao2*OW>aG5?e8`Mt-+Ibq<%3v?Ct7+qt7V8L z$68k*msAh9Oq*gVwVsY8H}EL|AL_w@QG)O@gR! z2}R`!*}m{yIp8>BSI%m~2wbdL84Q>OGdV^UM}XzAx`Q=I@;X3`3s{}Ng24xqT=oOoQDQY85vEKRlCWJ^Z=(QhW8;z9@)^NgVxea=nnPHzpzV>WsVb0KOOMzT3rD_I zMg1=+Sn|afdB#*Q`F*W_XeZM}vqSks@&vHa$j|FXKg?b?)ZW{MeTL1Ij;b-@g* zNxCwXz(|=%pwx9QT@BSA$!&)J0@6kDa005;Q#2t}lo(0$6m#dc3dP+vBw8OC?{8b1 z<^N?)T|`sEJB2w>n_d2c6Aexb7RqOg!Fl9!2*%oS9NK{7aNaT44Nmi^pKv};L2nL$8$L~vB>h>w zynu8;>98CY>MMttNecmHo9odOjsm>Itqi{Lt2mo29Heyt!=RU(B)MhvJSva zMptvmTcRlY_fID#pKWX<1%XG*X+a=%M2)+0#?_%d&W6lEIa_#gxB%{Xh0h*}t2FKE zwKee}{+hdwTCKo$_xDciPwxo>KK(UOUcK=Hq;YGuMPbdBy*Cec2w64~8_2EzoPx1U(-`X6z$jyNmL0Pj)0}IPs zrWOV;oXpK8g;&qd5k>hs;{(?Dvzb0?Y;o&f{!sMEg_eF31q}*o)&`A78hh2=-=g5# ztrBS?#cFRq`X$q3xGxqvHo-XJO(>j}ev$t?=-$n~g#E*v-5X9~ND>sSC-8xxaZ$MDhwXSgnY9QYC&4!X9ple>wM8UJz%H;!17VyL5gf?%~qMe zqP1BoS1bTtF`_+&)5{OG{|Nv;o=ljSQvqOR@aGtp*MxhXZ^aJ)IQ=I6W=t31!xU}+ z${CFyaAm~;;7iN_Ai$|qI(9i8|NZxSi4WedkxviW2MqAa8|0#juIs+?<&ddBB1Rxu zcqUI+t^7?@3onb@LVFZtbQGDhCjLfkN|*(WZQ7ks7`SeyP}ruxn;Rt*+D@VdrlLTx z9jFdyQnW)eIs&%hGl4=|u0X5}h`mACuU(!X*OWTgpuM(l*(>WwWzm3dZlpLu3}voh zu%L2Ngi&*?91}o|FtBcF%54;O8zCB6aJgRVkUo#lf<$9*Q?4L#lePjkHwh;eEUt>E zLs+1;R!A-NgQkl?5Eo^1RaLDfbZ8W1M1i?MBodWw{_%9ZoVybL1`Iw5$8b zo?|Pd1S!fIxD?TqHH3EBoOqKQ3b4lUo1@oD^S*KF*cnNd%gox;lH~LdrQy;PKDjrd zXDvZuJnix@n=AEEJLu|VZAQ-^qN-l(Lqa3u;wl*J5>Q4QT@VsDbzRkrEP+yh+tV8= z5MC?%SdI)9gnBjGQsCC(4Td~wND@qvyLd}OSB2sZ`+Q?^s})X3?XL&3kx#9`io#xx zps!nlC-EumjNJ(aeLHUQuR?;s#A8iBgNa_&a4fY3`}}u2V-s{GP_>}hR>lUbi(Y?M zM~4cY89I}0W(V3{n8vgzr`$$vk6w4GV~+vgOo^aGUHfnA-PGimf^mJnKgD;<>n0~qaYZ5WA z1pOv$Dsf0ZwCZk7o{XKO5=UO3T%#R_+MJVHTc5K79yM7Uzp%2PFDH|+xc&KFW z>SxodF#+?;D(dOXhJ0sYX>$D6*V3`|)VBO(%_i4{+uaz}g6`wB|fJ;155( z;6G{_kl?y4XZw$r2?wT+p{&3A?D2Lb!R`I+e>{6ufV#g$m~hKq(e;;VAre8W@_|y` z_D(i2c@%s(*|8L8Hf4@>0F#oH2mT5hcKPp9Ec~9yo;+Lj>giC6WjT^ag;od#fNx*8 z2}Y_5xJLa*Dmt#|{O(ypzG>J zf5c;!)o)~WYX_*f$qbqoNRo%a#a+Um4NX^v?xia@o>BntvlnFoz^9NH>^<)9w1n0m z@H5(wVsGcaJk>fg=+u(=AYughyOuJL3G_S^IJHEFlswAwMB>=dny?b!b752I6o$;p zGu;mojN!16hUE~3dc)?h1)>gzkXpzv{vjo_4#v_tI>tr>^F^K|e`swA-*zK!#)DMM zoEkGxRCsHlU4G7uD&f^7adD(L8c?bmh|o2R_zQy)B)gC)_W#K`|DUGsJdTgjHndF$ zv}t3CBG+O+6)B4e$`|XcIqnDf;lO3_QkN`gQ!kakoj{gK7}G^hE}(=RD4yOI!@eMn z+m=i2PA{9X)2ZkYLV}Sc6E!jTciijodVl!h{3sRrDaByr`FXxx&o8BL;FzB?7lbIn8yy;WA= zmujOJVyj49Jtp9YAniEm(4=Y@*v-bmHQzIP7A`Cgi`Zf-lCL6(#CRo+qy&cGf$<2z zR|CFr9^i}kd|K1Lsg%$=x2W?ts0g)9~V`Zn_xB1sO&QN_+EK2a}193jNJzg05(QI$-&fyvNJ%I2v?~j>3=Q1W0@0 zu3$WHBa_Yumc}!lv^>8R%mhFF!giEQcGqeQRtQ5;OVY@nVbQg{ zs-I4FhlcENwqQPXC%Neq&=-nco6;iUkX!>01rjI0vNNQAmEMrm8&3T3H45C*glMYo z+S8})Pgho-J$bS!$HMc~C38GleDt@)#rgU9|J|3H`}Z5~&)uK9JGZon&9=RsuC;d^ zg4c)8eAuyZ&Nc&Yo$Z_LYwa5xe7|oA&(f_2cZC1G4FR_MVDxgD_5vqkudvS7O`i$6p{qkUJindJM%}y(i2RP0&C-PQ)ehlSitmR4th%wA!}sx)QZcfuS#PA z!%h=OS&Fi%lud8B9lGHxY9=geg5E)#zw&GeOh`_cZgUJ>79GL@s&!71DV>QJJU9_^ zVnAZ>oJ};>e;>=5&<*0DYwAdTj;P%z5+mM0=@`V0aS)jSPlgchs=*XGiEa2H+D0{c8p-|8$NbBWpa7CCYzjH5)2zAlHur6q*L-h;*70E6iO6u3ASP=ivim@Tje zH5ScB{PZD~l6p1#NR*HZ;F4Wg0^c1Cs*cJlFr3zbwET*yS4o$|!eeo5WHbsZ5I5bv zqZ&QQBzZJo<=G2+qA6F9M2@t8EjiQjP%^MmalAzYO2@Sa$;ynf{1rMZ033{yx?xRQ zo)oU6eB2@jS|B*7^+$rdIFfpazUuAF(>s`+aUs*;e`0Cy*$I=4$9$-(c(D;NV-cvjlAn_Wc)kW&0}%to2~4wsq>eL5(|p0?8Z8 zV|>7~>K?|rw7Re)SP#h0;aYm};)VW{))t7#&p-Wq=2MNMCXVZO1ae){|^iIFZ`Tma=-`FIW4I zpTF`Y0wm-}LNLFZQqcM6)H?30GhpP**l)(JoIg$w$3uC6+-o{3&vs;+(pNKv26#T1 ze<1&2lSHS@%v_(jK62;Jw{PEGUViz*56|UTU0HedWc3+Wde2tw_0fhze21w5ruDJ? z$4UJ=fx?Q1EE^^#r;tXSlq-aj+HYku^qXj~%pm%-Qee!+BQtYf*Z|yWXF>n0eLwo- zZAaRxyXLR^dXp6a50feeY~l zEjX7D)kaB%A6i~6-&#RONlxgkNoy9Q%?hZ-1R0qu#4LYWT|eE2iiaRq8BO^GgiR#m7nG0}wvu(koBi%Ymn1=09`nL3wI(tsw*DWFX-UN6vH5>)fA_At0`2YJcHV(J#qJid4uUvJ#w@ut)G zdbJW)EXrz+9RY_m~=kxiOUy;=i*?Z zWH1w*jx&b#P+jQK+QF#Gv7#E9j14Kuq8FuAGM~3BojV(!aEPfiz?)YOQg5nr+KTq} zT1l-V5-ep@wy0W z^Z2+;6CBrEJRMy^BfA90y1MM{0XB3Ww?E$b@&4+^a{T<-*TA>U_1|Y+ zCBP?siog09C+0fLH^H7kbF)(z@E?Bt?!IHY4*Z|3^Z#i&zvH+qrJkvlh)%+9$BHIe;E{H-f&W z%TEX~8CDY$v%vPv$8W~R??33=4fvJ>tUyZ6Py)vT*H$@cx^dfFmTxaF|M&5~9zJ~W zhxN6!CvP`ir#RWV&q07j?VghLvm^ILt}j1&_;7XYf$;%@z=s39R@#<44FLSvsZGiA-0aq8v|ixv#HGo} zrOBl+6%SldoHtwGD`%}!k6u>kk#f2_i<@L`o){}9X&N-Mk; z*RRf%?QD0gL}y~KW`x(!mz1T&NVd#;yF>6+&B4rz<#jm0Lf6hzI4d{Zn4j*^nRRYs z4^_dsUv{)R>^h=$I1o*x9fWA1cqWrlaJ~^WG~`#{8hUKYP0(4WQY_ZLd#D9&gze_< zO$$sTa;B0{h^-?(y+;98v!L@$N(b(u8bCOq^jGkg{VqJ0-rq3wz=G3)t-^~-N!m&)w zIFp7ew0Dr~jp0%a-yk2$iABjxPw*G;WmdotUUIRDoLG!-|GGU9x7vK&9w#+|Y<%@A zq0ZQT-N3EWv?Gz#A*A*TlAR+FVZCzQqm6=*i1}FT%p*EW9y)JGV0j3TMTu3MXLQb> zxD%j_Sl?2P=oznYIZCdtjw*L9-q8;HDhZY!xV>GlcP6(zSNo8tBea<;Ea-4H3DMa$ z3JNpX4VxG&VZ%0GW`=8qQltz+d$p;M)v%`A(tkt~gI9%Enzl#U4`Vhzl?`#Co#obG z(8!|&NBx<|r2TRBx_E>$L#mVZ5&jJH#(jQQw|7dwS67&0e=%77V0)6@VKV?CmyFd2%%YvnxNx2dn!u-+7S5ur?+Y7=3a15F5>4;`pSfrZ?;y1u`F z+eqgq&^AH>qN~*me1KdH0oiC@KPi^NhR>m=R`^9SJqYfe3x?P`-=cbq5@&C+jV+#cJu-`&ccjBTqT+*ItFMLadcqKYAq0dil<>5Nw4B^0{u_{Qc~&W@&o5y7*hu z!9IP8;r7G*m1;mTSy+}6i86+x7fv*Hbt$r1DU_Xxz{-CCU}RSqlR(F=!-aL7Bw@L{ zT4AlHp;!arxPj3)iy-f9x$=1V+v|ddFP^Wj{q*F`+qW^zX)%s* zeyW{THnq0-p<+7zA7R>pw|If%$`ZgkLH&VpQks;`jGY}**|XUJvjx7363dE${(4jZ zcy)EHMF3dv7bSFEvvCO__tFvc`Dr|8^Ye4^1oAZCE(`F9OLOz1@&u!k*XLD%b@uG! z(vn#MPcCgn!<-ozyFN;s=IPT{$%5Wx3|?)FxwX$pQ$H&MKg5N^*c|N`j`B6zN(hb3 z)+3;+2uo2?PnLm6o8qnpOVYGp@6nw*xAHkn<8Bv>} zVKSceScfA+D;OHngnf|wtYhcgbXp^?NX*i9B+Y(SGZKzq?PI_hOy^*gEzP)D2(CjI zautogrX)$=*7PM&@Qd_W=x(}dPeQY;5`1b5S5@t8tf>l9yg&nzb|qC*g-L;~si~rr zp(0$Qd6Tpc?qv;JRSE~jrF6NX2ssurX129J^RUoihRj73PItv{7%Z*$RPJzA&<*S+ ziNk5SfQt!@g!_6JI1hX75WGkUk@T3U^&Jl*XK+|xb_h}TGo+4+&8KDx`^OZ`bIZP8awEkC@y%Zvmw4sTU1W^)?rSdB@SFC=q zDLG9iFozav9LEm%X=SkjX0R-1%PK+WFDG%iGfbN^3F2TNO-DlpMM?GOa(9-=sJ!#J65)Z$H*x1kMbd520|@ z4y9_1(-7!ZA5yhE%OP+*8dUFaJ=v5TBaaYNn-tWWU2tDtv>@51=K%iX@TLkn7W)|n zTa`xdFLAerO~zvHtD4{Y&Yyo3+xB?-e}TfW?T={!B#nLF|HjLWjc4D#eEH`4H)~JG z(Og?we>N~+Nw5YKg|Q;Fu>+3$xu6cc^I@GZgT30rP}s0l&(L+a0T~u|3QLu{|02KS znSNx5deX`7zWfQmekm^zAoiO;I3db}MC-0bPFL-)=FCHX!^*U^<~10*J(99;)Bamn zYh_`5nep+jk6yTlOEpl^YgEty_4^1CX%NTkCHy@CzDvg9L-DfmUp3k4e)S%#&qSFJ zMLA0yp)%msTFMwov|&g zi+(6;Xs$d?M`DTA6$={2e!6>QbovHk<||juEG~{|+SQraMXTX*ae88G3>>^My)-s* z27}qGAn;x7Lek6iWuExS%1NTh)rr)_{JpK0*y`TE32j4SgFH_p^oXGA+~iC`e zWZJYxEPk>mfG^B{`Zu!x|JdaD&zH1|;huVpM<-^_3yxoXK0aQ%yIIqpE88phnPQH3pO56y%LijxGN1xqpcHYRcfb!!|60a+ox|Ar(B*#(%Z*bUdz==2%aZ+NdZ z9)%N-+{=24f^1kt(2Z08UpCTbY`=SJN~ubcH-Tqojj&reT(DXwEgG$&uzVu#s?=Gb z)8`r|Oqc>BxB7i6G~*co7Lk)=a}4RG*KPWfK6P^#Q)Jj}DTNE*F*+$vDXL~{!b9by z!cmLln}#qVITesS;nM`ZmbHpP!|ApJBS}fQyQfGwK)GUDE5o02VsIfBaGq!BI?Vre@+XYJP zUg5nQk)ehpEk{Bl4fuKqniPtgmCXVxJIizc>nn_)tsLMpji}kY-hi;)3|KEtjJVb` znBJqfAKZ;=M133vjJ7K2iYJBP#(lzUfm^}fZh=}q*;pZ8h>5bc9g*|wLt*6#`MUjr zy>fduJKzx8+^F0fjmv?4Ki(vkzXGCk79xA@4$6^He>52i7SP<#C+ORhycI3@A6?h~ z({z4^uPtpT5Mm*1rOL=4m}|Ork&+8F29!W_5p9Kv zY>XJ_MZqsuv&6e~OU4vA&pU5f{K4FBx*smPe_;Q>UeEJxIdl%SpSGVC41qpM(9@MF&yssbaBMczW z=Py2Lv-u^l3a+IJIxmCHA>wk!`$bg$1GEPNq~Eb0b>!_wxnub4PqROC-Y3BMENDux za_7~ySRGYiQW(zO{0KYTp=RYBepUR-1Lo$jKr9x<7v%%x<{5ZF=q{}ZM7_}^hqoqh zRY2U^TVFqLwYvJ)z%c-&P*qg?ebYGH+B!7U+IMnjw@*G!R1B3=dl%IU% zzAFq`jbq&U;&%fbN#zKn5iT4gP8$u~Um=HMfA`zf)u?R1x#k5$ep{KwK>-%-{8Q0K zzo@$Q$ADwW%PnhwQlTZXK9XWN z!@@><0cA)(sY$c|@ORJu@%_seB`gOa2hMSI?!TA6-@b7E!p4G7W`WyT#z$|AWEfbz zlNre*)s;^-5!*F8yYgvj;l6-wGJa_ucH;#WGR)2=GGxFnPh6%NoQ)U!7T|qO465_M zmo9lNEwU7V$p~@9Oc>l0ej|^Cx@HxHrDv&Y#rJJw;#wOU}w4i;^f@TJfbJgi=LXPFQvjEM6&CM<2NZmj^18b4m+s9Q?0~(Of zNGM?Zbqn0UH-N^1y-q>eW{jenT58*8oKECgVaZ!5H=A$NVnxjKt6Bt7Ru;E6G~7UJ z7HW+epwz-v7}IAYP6{s1)E3XoP?J?zJcG0jJaVR%1Lw*zYM(3NJpznU0$nL5xX{HZ zb{x?MtWu$Gn*>eErpu<0*<6Jbtg<=;P)=6~4l_kdF3N6JL66m047>%aHId9hxy4N` zq|kK)UW7c~t~*r*g%vi&hfYs-b|MSQ)Hz+%d73+57?$LTa56C#tL_7R;qMF4TUn^n zJ(D+L#?k_V{DA1N|3$_m0J+F&pcopCU;|2m4dt){!;^%(Xr*{Af-A|O=Xkn^>n-F^ z!ki>bR&9g1`3)N7eZN(+q7f!&9z*&ha?|<){`hCxS@BRLRnOFWi-OZ1%53Y&fAIfi!=_T_29NxjrwDJwhjcA8D z%Oq)D3&;2b9Mle52i*wr8^PJYew*a{nf#s=f@uZAgu&Vg_jMbBNi;d57>4a>3h zaJ~(x>+_lBtmjC2JhQfETwD7~(#;wD<&xPl7C4Ba0X38Gm(OC}0wy z$O}797B6l6K{=A<=F(~h{BHp802r`?bquNih+ZGZa9hbx+t7)VZM%JKeM3VPeQj-h zyF-G%eHFWHAD)!6B_$^+D%wt#l=Str4fh`C(v_<*^Z_T=(mN_WE0Y$IyK{eMF1_)T zusfUHm{aHWHs_SR_-Q(4a)QxV&OH?Xe);mn zxvyF|yZCNo3AvnbBw+_^Mi-K9qQD@4SP1{Ff>ynubZ}zO<6-ZhUO=>zZeEXW!ZSFC z%`Wnp0lg?rqTWiF>>!gk_yqYB0_XT_LWZI5Dj=~&NF_>=bi`u|?}X*ovRaB<$%2Vh zXtFH0DsKc<3!F^qD3v2PFgP#lNIJGN2pB^dJuVOolM=kXPE`JmH(6Rxmeh=x4yQue z7D%Fj+H$%D6~N<+plq*oHn)TSHno!iHwpD^q9>^Z9$?suPjsXeD;s9oXOM=4l&l%XPL^R*T`9<0TU>Ti0JpO8hAKwFvKL(p&|#U7Q3>i>)c~+H zH3-(40M({x(p%Io)RF0S0+Wkz%XFv?(&yUgPC;!!*5ayZ6W76T{oWMrD{L4UT99QO zg5y^J8m?b#iIv}%nO9)L*z=lT2{s|UvhI}JeH*)CRuaONB$T^u8kt#wzJl5a5hm2uO>H2E1@!Jk9x{b)#yJ%dP#0uCog`qem(mu|pH6PL_<<=Fq#!QfYSfwBf!+)!Ndinp7+Kz+kVgI{) z_ic!ND~9qdVRN|SXSLPaqwAda*MA@eYhN*)e@c!b=M-Cj(QxjJYA^KfYsGNc0chU8 z#WvvmILa{jag1l9DxZVE8&eQWOb!!+3B_{ZSEFVH$T$&*u?JXD;J|(q$B`rcTOXgg zb@u2mSH2WHs~(1doF9oBVGN-2YhYE(@DTE5A-_TVTG)d)!UT_@bI^|Wr|1c@YFGrL zvCtYc5U=qI^>^#pzpBWMuAKVnfbHmTR~~+I^Jq$`1zGIrl~0bVho?84vM2VI7*4!LUuO|~*E8Fp3 zVg&u!x!qAO>J0^NI=J^#8mFkkTVGvWU4QI{V@K=j>yb-ZUEO=N*IR$@hoiXNiC~zLTcL3k8{bkbB+U zdyr01FTa<~ewST;`utnq@2h|A%A169=XM_p3m)|X5FJF|<>vt43-Oih6`IRe;@k0+ z^Xgihcfkb@19@Ei&AHHXUiA3>4Z+{|+QZA2cY7&oPn^ zEMGt_a{=bdIyFbu!}iO#%F<`(U%*T6Gp0>Wcr0iq^b88(>R0tpWTDIm#6td+#Uj+!GrnqJ zO!T;*DdH)cxes=tq>#t|@^yZ%ZQW-WuXQXTOT$=kEsQi9Pg1QPm9&nkv12Pm%uqbo z?DQfd88gV0!3cRxB7$1HP}q$Zn}8EiI~cMBR+|L8EZap*2Bl>kR8B<`<;3k&Dd8KFQXxjucSG-v-5a_VDq%{(%^Q_RX$<*u$1vIOG8*EXB)+4lIC5wd;AO}h z0(eh#q63iJ=)frh-K5$I>0}70514GqEdn)8A*P}d7?G86TipivMgBZ6<|>eq1BS~c+`*?h&&3RA8{sg&EWLqq=feHWnePM|;b5a5 z>yac_Drvw09PsYYgcR(Fcq&99iUUmcf<#n0!W$-9Pq|oBHK3FB;IzcgM?BWQ1Y&s+ zL(-uO^~YL)rRnbt4r*i^RAr0;D~ARNfF{BqEntnL>uK@;4M6h0qK(*IP&$<%IHsbs z`hC;run;ZVVGd@zOfqzzVQ#uQWRy7jIM+v- zu=9-kNRuuPL)YjXaMh|dXp&dZ( zG}#+9yKQyaMK@AH|0i>A!*Ks zT_e9uAC`5a1K}0HtUy?M=ar{;3*@Q=$*rR2=dY0QgbMl!SaJHsYXj5Mz^!aYvuECz zb#5dO+3x~oIsD4`;o$`(V*$gnf3jb-Az$UJuo}6Nq<QnJ_-ZMmF2a#lZ|2V$C;se_Vav|F zoqPANT<_@U9_HPhhq~qtAG)J=>8f~W_wVf7fBF8-9wX?VeEbSi<4iu|@)tp!4F59z zCUj*b?*Q6PSXs*4R2!hq)56!zTXEgQ6!@Va9zi?2a{9M&njIYM9UScJ9qhQHJ-lZ2 z&$-T|m$OfH@VcF2XAz(F=HB)F_jW%u{`=3*zx?uFZ?E|bcyZZyHQt_LzC0!Ql`(0I@LtF>rBgw-Zuf5=mHr z{z!kAZVu00jd=~v{;PdamKQ$9$l0!Vk)B|W7iqBdMUtiDNlKC$s$@X>jEIZac|!D1 zMtfR%d7{K{U;CS4AWBbgM1O+xSIFqEGJwc^hW!Sy81>mj9aS?AFoex*_Su7s+h*&8 zLTBs2zCmNYX1x=`p9P;!g;{fMyW8x-ZFeW!Z2B3NCkU{Qy{Fx3w|VR`?mpfjs?1CR zTYq$|ILg!Fw+x-JQ#k}a=D&^#JC-Z%t6{XR+sB+!Ty>Ec+N&}o!{00Nm;l3BZRvOuq}WP6N#rcz9O1&kL#qK0iF`M$cy!hWYe^-&1}xxQ%lDA9oE-c|Q>R8u}jGvx7Gc zbq#Ip29jF9;_G0qUD4%%JmT-|tBMfW*Vk`fH3a?%a`_+4W^QKuR|O*@kMFa+bq=*v zvfgyqy)ek-32qBsNMyUe_vPB!&wLd$5hr>@VXsN>0grsp_5zwD z8~DO*NzRX*Qx)M9frCY#jU{o?HTP{?lQUr}J1pstC4^MC)=H0Q^Xdd(B2E?}~f&t0%!XFw# z?m_G<`Bg;PXxERVLL@f70j-1wi5v(-20v7)tv3|DK=xJ8P24hynTZwKNG-lGIir*I@a8G?TJsAf}1|v9#5uy zdfP?nuAf-dg>&7z-1gVs4s%!2UkA@Q!rL7}pBOl^0d9)#Hdp3^#{jdI!glwHyYQiR z9&i@$YA<|c-WOmAiTTK{-1vECdiwj)Trq=2Xmv(89Lj#y;CVsqNX`#T8rB=efG-T$ z?{*zg6}~%rAsTTp=B$7Tgk~hea~P!W zG3Y+r^G(gXAK8z=+tJY{UtL}MFJI^X()OLl@oB!0s05Q>s9L|AX-)Jr>mXNaOlKf4 znjaPg>9BBxIECQpt+gB?oWBf?LAik^r3&M^gWU?2jd2Iv(XoLDMTQ+xi1a602Z#U1 zy&li^Cu(Bih_JPrq>B?>hth}R%B zs=VJ&G^FV$+Pe_Z2K=xLZ85Y8%@SrbOZJiR*2Y{!0l<-v@!CmO#KxddL(%q}g!mea zZo-BQ>o++o&P_u&7X{Xt-)c0>-J~|{{vUqb0z{?46D71@DGD4kcP#B@g&XE}; zNCvkUaQLys>SyXXi{+I8aweyj8yUa6o@a9X6rbtx4nM_=14&ZWBfy#NdoW&GpgF95 z$$hctK;26agF)~xd4$0XcFwCcx*TW)K`SHr(7f z;*`J~M<8sJ7V9ejHZ~Fqeu*E)a!j@xh?JPw8VSm$5`T_ZtBXOpPXH27z1#{P=1q)g zd0*)a$2w)yaRX>)kgNCiBb{%dIGPPbCmZ$fH6Z zmRSe&X^PIwMOTdU8iapQM{*6%jY@@7!t`34 zK%|1P-a-|h$^`-)5*o+CivuI*blzxh7@2RJ3#X(zN~aUHX04FG!17LNVPPvTo9H}2 z!3%6q3)_2T1${SxQPoxfl3a8^452M3!q*Na#>Vi%x^ml4cT5R`DN4--w@PCm6PT1F zgIqgPRQ7L*;pPMtXXDU`F#}@sO^A&aC^n~M1ASLYr<7z!#RBO}b~H^yVczaF`g+&T zwsn66XfrL3p0Fz%pYh_jd|GloaiVtboA>NH9HlLLMP-lvy2`Ux zjP{_`8?|CF9+U>9;=@bxr?b&zuLTVJ%A#_*f z8^T(GxJ_KX^}&q?w~+iA2|jmCv(MK)WB^(&9Lhk_-px@)pq(ao^xEgXF#c8nh%h1~ z1K4T)Eck1XA`fdBdDFyY%pr}u`oy7d+t|0)>XKgvz+Nu!s7qiVCis%-(ibnCBm;ln z^!9tf2kT;&9{g!{09)w8jfc=l%DMLCBTCJbquKe-!;h%_K9oNC;hD!j|Nf7MUp@Tl zzd!zTWbAT#^fw;0RrwjrnY%FHa)G)|6ge(!&`oJcEIV2l7b$cdfQptNl>>cJGJ1z5Tu8+TpQn_xF#E zULL)C`Ep=af@8%}x8GC}p@yKl=8w6~!8gxs>kM6Vy~n!TUTx3Y?(Od%|NQgb@$r7G zhBxcs{-JG;4?jCPJo@73&>r@UK6|nAr%y`fuPSEAYLq&L^m4{ z=jIH86`VjFT7~COMDx*6tQH~-ATZX?(gcxD*r@Cy94g_xsEZnNjj&x=U}1^H#%Q*` zpUSfQqH`oaXtdd&obS5fg(eB~?X%p7u90e3FWufqKfG9G&jz&-mkex#*FT#RJ(f_| zu-2c6Y6vT9oOgzqtc-s!hdVThgSp}1r-KHnnQSiCKbU=*q1~I2>s3zq!1!($%Ays< z7g|;v85rB6<~KD>q8=jgk*Ph&)B@QHx8n?%875`raC8tL_vz9cjRmz8t0EXNHjq4C>L?U`f;Lt~V{ z3`t{()%sSXiHyowW4@H1#e(f0Rp(6(;RMY@mciR! z)hAU5bGndTOI7nsG;fhW$c$AgnNP|aE1lXh_%niRC$%IME>y#5`79^YEyj$)Kv*`- z#&?-dHk!=vQ~@t4%Fq;u4M~UcSFYR|G6*gv#%#wZ?U)QW3{i`>i-x&?^44v;kkMyZ zKuh6EB(Nd2VXR8o2FqK@W?6=63T|STPO?%*MB*DReobp zx%~g~q_ZmFH&mtH$&n4Tny`P>xW#^Ng6{EL3+uQPL!A-ohva;PWOeWjFON zyQRH-WqW0(y=A3TDvg)MTS`4Fm}=SHZYkON@$>HfW^Q2dZ%DGbF1*W+F|qV@ATT-W zGX|4W=pdt4eifh%6@8&-qjA!Zf5R8`H%|I#21hZCMy)#;if+icqk$l!1_^aJq2{si zUOKp_gd&>_z^fX6ehvod}r07(H#(HT3hspqJ_-=EV$hN`2APRbD;EGTZs$?nQl z&Ny$5nGHDb3^Jt*DD3Yae2Po73@Qf)2mR6PjM4}*nZB7EAq<1Ldj`lZn6Mw8Xq3RY zzTuhd49(zfL)uJs@ZLRA2ea9kKIe#qG&sY=v@KZe&ZrPQJS_K(j%HqT8{*oTj^Hpk zgNBxB5gUun((wh7`&<;EHy2G_aBvk%j$nr(30I8~cMEE<(Vzw$?4>K*u}m}A$Z#ue zmG?pG4y7WY<-Ol+YnNMF6+vjcIEbt_rZO~+SR*$i-Bqi%7t?6U&c=mZL7H@=8w_K` zoVKV_Hk7<=vd9baJsM>X& z0K9jN@2;g2Pw-n#k%o}3N&>uaC$+{j)SU%duTFN9kOC>4D9VnxfV#JUbycxAHdZX& z$`^0r#i53<%%af-58YAHf<4C)TgHm>Ll}A#^NE6CZ!zIKwTd#rvL*ISt|X87g#nBE((m=Y zj$S{{2-ZyrgRgy_q~eoASQn3{`Ex+?YY-cro^Er$^>M|L$SK_r+2t_U?Peg^bmhCz zy6L1L?`Ylj*^3_ZETK^VU-D+5ZPgdEe}Dm#eZ&-$6si+*19M`V@4k5X=*6p7uUM93?w)p^-Q9)mLfyODJGrwg7<7BrLRYMDk^;a(+f>gBxUus!47TIYO9z!-yWP#r?s9jtwYj;u+-+?>T^8_e$w9flDR-9JYQ)mO>0z>2 zto}5sdxBXO1<#7x@}q5I7i+hx?VIiPNwr-pwr`55_UCGO8qdhtpTA}g1`PNWLmX?Kx|nqb!ALRFneB_g88I{iK{+sz$l;# zg<3gXAOZ{Rm9XLTlsb_xB4wx{T*~zOf}b@Ff(BTTL}v)z$Y=&fL5OgrOa#X~i5=+* zBCJXUP?npydAT7OdR{2(Qu+c*66Pbe!f65}D|9XZtaLj7y>kM#zN3G!`<;u=2?O@c z9|?s``-CNv7ELlG>Z&xwzXGl3q@NJ^e5njsuE8y==~v@1BWF38o?z~*3UCW5PmZw$ z6SqN(^R#vZ3#Q`VmFp-H^a<7i&7?dtu%<6~dUDkl*S6pHa9eQKM*~tEyU`-tSwo`1 zXB@zbucu#+-%l?7692*N@*t!md?hSsD>tu9;uX;xI%FPvbiLA*aL}dU&+f2}q1pR- zz*}gs->YqeZWTRywXK)6u19+b-MaFPdQ2o1suWDXT8N5GX)6Lud!s$?R=~UEkFqBd zq6zGRnJ7ug=>VW%#g-M_C4nOvlmoN`_X0huN0Xt|Q*UrC8;JBi1l0R0WHz#I)hREe z9VxpTfahklnea46RutLK*3%6Jxobt7oq%{ma#J*T}ZAnlG6{5Y5^b zuTOTguT_PDd>`r>UB#BRWTBvf{jO`_pbD#IW)2QYZ%1;&E|?|;p!fNjU@2t`^dSkr z9%wi4i*-5nf|^4$BMH`yjHbH8U>TLxj5Z)?A%ylQQMgDqqA3EFqjHkm8I3BF=ieDQ zpMM)z^`*e~e(t>YSd#S>O5dxR|5xtSw{q#neGGcdgXn5+?~4UVq1sVi0jPUUfv}li zJ0~7Kb|8VYhuVjv=3r;$eCRBV4}sg^%Li+)`FHr}V{drxKibn_vr^!EN4LMgNPgJ4 z*F^vL>(Ar0w^faz#0I?Wq;V+u)gVf3BW%w)MGR^PezyHbK-q6lUiwijK!O5Og5=aL zd{iBl{Kfh{eSz}_xv1CwCx=# zYfWdo%|f>Mw7c->b|bV9`xLreSP_JaeOg$F-L_&Yu?2b13bjJFE4MM2XG&9C0cey*OD`2OAo-RVCj^5cfYd66#XZEy+Y6>#i4J=O0X0mC^ z(Po1`4S66>HIlld?UP6DX2+du0Q2(jpQk~fRfo!&EQ#!S${qgGCI6Y$-0ubx?*?=i z)xsM8OQ57csXrX{;59-arIkmht)~3Qump*9Q%kYnfQ+gMT64mKaJZne=)O9Er^tqe z=4vE|E`wcUP3jDs5NP8OCT7EhFsl~shjkgO^$WojItn+3QOiBIVq+;;m`_*4oU$2fa zBcXzZ{rbaRxfLQzmDVf2-{n!MGfHSrP`R()6LGs4HiOECTTEdTvm;HjD zS`ZBXb@T2%LSXckAM;T_4ZxHhp*2DB8HDvBJBh0OSLe(Ek?62anNV+8NLK>7DT_u= zt>_kqvW%xq3n4;h%WG{3zu3wt_Uewfr@XgkvES|WtkVxXF9(Uo67bEMsdIgoGDGq; z5KH&uspA=;(xogb)b*^8U*Wfc$*fg#SwOeGo?Q>@?`N-t5i8!UUuTc&qkXotR!OzW zEMrGA*QJt1Ljr_?r-H<5Z?y*);!E}<>60Z5=9s}HT+))lYn;P4g{cufHX1C}#F~sX zGlEJJNLfej+#^hSo#+l#OA|{;`lNhiD_bgE=jxF0tbX9(%a;x& zt4sKPWvo!F_-wYnCXd4*zm6s8kZthLp~1s@N%Wyf;OLkx!aPL`V6Xu2++cwzZrAW%RSzZHM?mv~*Hk{hgeRh(>VmO85Gs5fASqc{K;4YHrter9qE{M^An$ z{8;0?k<US0m`B_gNe&x4O@xqzzaVS;hn`AWRb08e`GhUMflpsk~r2Z)|2 zl0q|+JI*%QNnl3e4T9TeI?h%^A9j+C`^hM^I}O_)zFq?dmn+Y9hR%;g*X2XJRJQq^ zRlU9A?7BPD9I2bjjNJ2De8ktx>mdHnq@3tbAUXU!>-8g4{u46eR-3O&%|#yd8wCdg z7aRvA^s9ju9}NcK!Gzl-!0HD((J3MtR8J!j2=3 zreA>376f>O2=@z1IF?X63-c|M%Z0SuXC1u6Vpz_ma3Nij=U~GZ7nO2>y)e?N3Rs*z zBA-(D?FI203de%KnMzvYpVLBd=l?EXU0x!aQXqFup4WLZ6d1(41dK_Co=d0W6&N&O zl4Bw`;>2M=XhBXLInVp%1zHK4RD-V^kpomJm=x&w_>;Lsl|KuGr9EjpO*aw^g^=h= zpKmNUJEmbU&Zbwebxe8((UUYT_{Jdf;^cUY{AzM_(x;IeldG5VXso8+RqZ4s(h?!H z98}}5aSLl?bbRs$$~vZkF6w|igMr^O1tZp2N*66h?r_i}uNRHwkcXr{gS=jP2r(P6 z2#)Fy+6!U_$*cr+38aMC3OxJKKdV<*!}gG%MDb+6gS{T6$r_3qjcx@wW(nuDBL3cP zbaxAiZ1v!|z0*j<%25-Xi&%`9qo}g7c$Qf03KG{Xsv3xz)QY2=rDNzoqz>!~y&fdZc8GeQSVFYt!$E$zH5gRtvLLZoF6EIs_-g?hiJA7sWe zG}Il$6K8{g!7KZkv=c^9n4NIV420KEmu>&o4C<;Q+?X1FH#R)zF5Ue0B@9arlZoT_ zCj8cebpzm_?{LNN44ZDS1=xXT&OVdlSYLC~bCoq1-YBvoFuZgm6;upzTLP%bzBb|9 z3xs%m$(VuQzOQq^iN7e^ zLL?2wQpP~62H{%sEP*jGB_pB8ZYTn-lQTUZ3DpdJKZ6;U>>w3K_7)7JOOaYjzeBCd zmP!{Ox~--iDQN_~8>!VG#Vu4=#%ya$lp77ZZNG3GHHY^@5m=LZgXK$p|p;dNB+7=1-YU7aAALqM^3U*@mHMzEQwsG}lm_(W-IWi@E&V z?1k3B+0#=hf=^H93{GbY|Cl{pp3TE#VatWtRDlY@IlDWD8Y`>1qkR4(k1J`J3Wt=P z%~YCUH2Yt&oeADpNYP{{HxdKpl~i^mzmi=>E4{u>&k^y@pr{=KOP5LBz~7r%0KzE= zUT~Hp97rkGiv-RZbtayYc{E{IDct~)7apbFAO>rm_$&4iVb^`6Rd7fP;IO99kXos% zP)UdFVsQy0#;EiIW?!`|U{Cr1k%=TFD6wF|z%N?pm;(2JUZ&0J1(pnYkPgR1dsPuL z7~nm!E6`a2nrkr1!nar)Kwjx#7z_-I(}u8DmC>jZPuoQe?=RLQBhJQk2WQ5SwfG$o z@+>WMN2NyPa{8E7hS3o1bG$PySM0fHncL&eS*J5BpVdbO?Pd6J#ZdR9{p+}JyJC2H zl_|^WJH8rqu>MjAXj~JSRmM)ByKvZkiuE^BAJt!Gj)7G}Vi>Ribba&isC#JWd$`#> z+%*2XsVojSFq_{a+7{>|?80!{9Rjir$%#I$Gkj)O+^yT^Iks~%U8BdaYKGKTUY?bq zozPySY%h1r;JSRA8CQnrlQTA>fzy}VH*F33R>#@t_Jfj@TOj7dEgfaPRZlN;tc@wn_u7@Q4Q5-b-4ZFszP_} z?dlemB*WTys4Pm^e@W)JzvI%doI>l@Bw@t|#b_}qD==CJRQ@w^9+7w@Nkma1XrvIR zCJ5|^VVv(?-{0^f=MDd3W9mLyx}7{jiGSy`&<4OwWkHj>f%152wgm;KV5Pl~FcbSzA8C~U*7=d$s|!wf^NEK`G3cP` zokD_feYMyRf{Fhg;5fS{#1l5@PDB04zR&ygwTjiP z{)?B1S2M|QY#Z7d*=BpYrwlBkudyWQlacWD9-Cn>GeXiNTU`!>VX5e~luLPu`YJ@V z0t4ulo%Aa78Gk(}Xv)GAfJaWm-R1Vrr zl`k0MRUI&)lf*o)tSbadb|QP4ay1NjF%2&p%ATkk*kCs$3_c;GV|`&=j-p3)A}Luy zXe3w0o#|viceQXrcn8%-%U>#_1I?Bi4hh1tzi)(Ndo#&cXxq51iU}_hAhIqcMrD$b6=LK{de~ip|8MG%_rP3G!r^b6`Z*2=H(ar-*?CZak5$ET+p*wEq&V zab`?*SRPjFqBp8UJ1;wUg^Ou>m~Ai_l*K`%_;OSk$46~6(8D4AB;&;+Sh1n)cq|_< z{q}=$x}%UunRUG0?ZnfL0vUq;rY47B(7X=bd#CFIu{ zc8d)|nkj#v3Aju+rG3EFJ4sjvKbt)ptX;qP_^o$;`CV@<{XSHA_3_thYcJju7QgrS z@q_PQ7r-&iki7on3%m90*I!*f)1hbo{pfp-xX-_PezX7WO(k4+ip zcD=9Oh_K#SK0N#_@+(o``#U@LRSay1{5AvV9aj>(L?rameOZAwHr{>#|5dd4VtPi) zUK#P!RHA+ci~);;acDFYCzuAO0N+^`53hG59P$(B-)v0VkMv{1OR#(ugZ^1s`lj{P zgV|4?xs)j_Kl_1O(X!2SoeXG|&;8~$sGd(}xdBt$K*-{1=0Vtr+wu0dB&&A5U9nT( zZ66P?ffk_G7jU`~;yc4;zxVAcxKYgz6TNFLaFYeYyathRvR0IM%88}!A`HU|tNpuACjOOk-Y6ApRb4{1pFg`77A8;63#$HQgT7Cz_M$QV z`_V$d=gfJg4CsrU6HQWm@?w~XDdagxoegTK7>$F>luN$42yX1e&0uY^reQKdLq+_+hOpoVxLD+eLaf|3@(BE|*sUTS6 zXpw1+w_BmlP-aDvP5KF2rTLPqy@t7VW{DbLoJizvl$ta!)LN=2Y&9dh;4k@CtHz6! zMY&ok)k>=RHGaGrDKzrvuzoBw37ce)tUWJ5(2Wv4B_qMRMu1ndv=Z7+gJ#2G#?!NT zgJA$Que7YJrqX$AMtSl#KEXAzn_=^kBDPx~}1fGm&T6 z&(l-XQ_CwDf)%{6qJ=N1mG(EQ^k?+}6OFZiKH5#6Pfk(}PpM_Vu>=?!M&kwsPYI)B zri{=TTs0V1Z$s)tlWW+tk>N*=m_IKsD;dk4uYAfk@Pr!(6S;vBdM2Ed@G2I*1d{EM zSTwvH+ul{TR}u4fGMun-9V$7RwoB!?aYp{SfuPPL8n(*3I)uVL^}yL<1D zSgXuYU7)=Q`|TR(?J%A0j?2VA8?+luE)!s>WXmprl#~yHukE^hAcoJ~Oy+63qp`HH z@^ak15)4(^P|vPETYFvqg6F5pAAbD&KeNVk|M=(M8}BW=|EIOJkKetvN49_QdE&#x z*OekoXVIm{pRe_v{q6CGfBzDo{^Box{U2Y~_R?mahRv5lb6_$iF`*!9o`i3?N7b{R-EVbV4!ojBC1+zb@Df}laP5NI!?7hZ^CVTIZ$do^>l|J1(E z^ZufpVOd(5!{?`|r{{a#_c{E1>IG18c=p5k5C2-~q6T8`tauUmD)`~?SO~3&8gl;d z1RW8h(P(JYR>RRy)1b#0Sl2ZSrmdm>cx(`UtcziN5(P?{{aiIAhYHO-^4!OWoHR_B ztKgnWu+#vocj!Z^_VfWlusD3~;V(g>|9IhPX>V@>ag)?PFK)023GKkQIfm9kh6nTs z(}RRf@WvZET6eNuvmU88vh66_p=xPnrg*V1b%9D2mKT)=$uotLtKlsDMq# zi|o;`%NZ+xm<322(qhlr&aWKQYHBW0G*enxV<=86N5z(46||`te@hr9+4Fo zdO+Si4&+KhNChw^){kqC^Xzrhxqy~W=!-LhXZb91Sgp3N-nqXeV7o~@v(>VgdgXw} zvt_xwK|j~R&XxnXX}KI)dE~G#WG(z^Ti6 zMNlob9OTK!ghsxWK<_41(M=W|K?jECj$v&IIhu%wJ}$eCX;TU|Gs2pYi4{WfGn207 zGMQr+GB^Z-1&n8BW-xIk51v6hmN4I@kY)ki8MGi}nk*t@8YNP&=Hx~IwaG+E)CQ+m zi$o0;X)a=;2ZsW>@i+h(HeehT+zrfO1T9EANDbigl{cG9&c+8R4_GiZz=1*1!%9MV zKf+#7pOlIZg!l$LDdukgXrZ>kOgae)8^-20z;dH-{3pWk4&D*E7X%$SUnX5f%2fi* zgb3S696@#^cq{Z3Z4L5g$K#pA;#Po}9$_Rq$K}ou_0T))8Z0F|9&UR9)!Yut(*n0U z7)#SaJjwWIV75ZC0Q$sc3*u*Q$Z~GJa>_RdFje*OK--`*=(U^0)!oCAar|G z0*w_GLOLkEisAqYf&KLUB5JbkALmi32hwfpZMa4WHe3kCH-k7-lt~1MqD_ zrIoXDom?cFTi&f>5Dl>v$_)gVv%8(_Zo}@vw6xsq(u=g*!LS(|7z{X9iFF}$N8eJpz_e0zJh zg3a)DNM_>-CP@ae>7 z!gcT6^F4g@)u=k0{cdt^>#rwrJ z7L^B^r~217W-CnJud1KrUQHP=CDG)*+6RmzN_HWE1=niTXIn>mFE$o8P`H5o?}Lp$ zEsm{7i>k?j?3rZ^*c7v);g4^yPVw1{zl!2|(;xY_A09kjfz~nlVN3^RJ@|2OD@8^C zjZFspi2_SySl1Td+sxlE1Q@$uYOyXHcei$4vk!PWzoHo#3Xy5bqozq^(>h`Wxal&J z$ON;J76_@l$OKuMId3}8K`h>Q+7MwNt;(R&ERq_hZ?ugIc|8Bt*|pwihmfAnIrFqx z*`~+Dl~+8tfPfzBfJ^x4PhO0IyPj?Sdu{rm@Dg<5JZ%=aZ(#oIP`ElXmLCsWJaEHv?&HMouMsA;hpK33k&s>_AVFg;Xp(V$neCqMnO2g)Ib3{tAS3(Z3XGmR*4FkPzNuz_2R> zylrL>jTMsnF7_@U`ngPZl0b2W+uzyQ=FB_`f#q=uQ5$6}d*|oM$r-`eW-^sLLh*me0y*63HvW<*1O=A`TZKUHLuV!ETtV?+4hhnyxopRNZ)c+wfNxGqf3uzKijd+QW0bR5m1cFj zUAYxz3uV(Tg0Nx&&oJL+G4&PF*A5 zdBy5OT#Y-rceRMpBVGO){(GCk=Nr~L9zuVCRzi6+D&O78yd2ex5-Oc0PgNE=U2C(N z!BiCz4_TvZL|2BfA}0eQ)iw(hIAbMV^$zIjRSs<$=n3(~G1Fcd&ytbGLF{T{V9bw) z3PXB=^DC;N%IlaJFQiAgm{}C}RIRLIXD(R<+3+30A9X z;WjteY1TfFE}N~gUJhJOrpb%j#<2uhm7L$l^aCWmpKsTC?cVr8A`exVUQ8I7xj}Yw zZP0%s0PF>UwaQiyoYsL~o=Cky)YYcfLL7#x1(s`ht(M>(KsnSh1->A#2-yI}X3DN# zbxe(Nq!v@0k1=Ytgv@R-@KW2394#TigmUC-5XV~z<}6}5Rv|SQts__#_%1i$j3RIc zXO7FqF2+K;Tp0#lHC?V57?KcrB`mrucs%1m`iAQl;BRwgma$mP5ENSAzW8T0gNBCL zxx-W@gEC-&Qs}Y-mgiFg;lOi;a$oMvr{;J06BmVyw)3$^?6om|69fYAhBqU`hNIk}Gx!3cE$QAvMiV zW5E-=b4N3?P_p0=nD$KG(LJv)-4aLB4Ujh9Anq2?vr!t)KucMOf^M4q*rE z@LQJuRm%xjW*ZVHv3idD+6~MpGt9qUMA~}2H2u06740_rE~==$QH1|QXn*vE&ruF$jUp3Djn7+pc5ajIlL#!AQrF zUvxG)3cEstJNwyAL&&f&z;Nfk6{o2c{ILaaSxq}X1jGbcz?0k7xNbY+fk?{7S zyrGMJLICZ5*}A%yw(>M=OpHmytT9ctL=xO2&4-)lfKIA0g;d>XVV0bqv zU#-oeH|vd15JAwxQiVXh$dwmEsZgQSGFP3e{ipVQp7(dA?aUU(>NzKgBcacE-uL-{ zcDlOH3`${@xo9hghTrI+@Z(J*cq&wcG#5|>c*x*Lfnz{ml(MSmf;uHW=dBx?hX(Y^BrGxJV z3kP>Wb-#rKdWsUPyIMg=XYgH(h-Nq8LkhLH0|xcQ`#%Lt4ZC|FJ;Zp&@538A;1`O_ zJ5cJhxRvqCo82vs_+|Qopt}(~Pm$j`g6Qi8bisn@L{d4{H#ep_p0W9zgW4_2ffO~@ z#0|>?iM^%tR=^2EWhJhFDFGr4vBHd2P?#8MIhJ3lkaXl5zh$L$W6MRXMRl~UY4g~o zQn$5Erl{&EqZ&@D>X}*4@_VJvM_$WPuDPzU%4!?7ke$`E^c7T@tm-Z>d5ehZIEYol z)jTq5T}v}K&5kzDDTw0;&}al3zH%L@mBMKSi5o!% zWq6?3!UxL+1tf(Ux!jODdyrn~VJ8DvuJGlupzKKy+uh?JvL=~2*#ObiR1RQrh>#vU z23cM@<^UEz>A&h2F9X+8hHZt%8G+Z3;Avy27z)AK3k{YB3t+@-c(C_{>36hT_6X1- zJqyO)5vZOSL@8LBF>H8bbR;tp%LpSDkVOgy5H*&}Bu6!a5`9P$J28!mP89z$kx3R6 zafJXUu=K_9H^Een;zS?D)k(lK0-}>Z-&h~0FxJ3>6NsIRX_gg=7ofoEdxdXf453VT zhj5lTS2#F02%m5ap;%t;uvf!45)^1{_iZCqqmRNYp|8SXUkMyz*~`*j6er>9A@mNS zXb>%j2znmI)EZbkq=gH@Zb_8~u`c$~_dE0i$lV9~FDBPOU4(aFUA#?T9v=FkE7WNC zPN00I-U`hfs9FfRIGl0+g(Qj777?}8P>ZEU)UG%1$?v~xfjrcq^TSfI|FkA z#AYAymw8z7um!#Q7w(H2{zwi%SKJDRY2-EO(8#*-FJtN)hzJgc1!)iEpCvg6R7UgB zp)lkytiX%l$qS&rkwujH`g6I(uyEl>)t_3<3h2UzR81`&=GcHFjJ6`DP=6$tnyM~V zvnlLymFfzcOjXx-89w=|%V${dW-G1PGmNft%!8Ec1d6kVmHjp5WMo@t3XVo|g|(;# zVHB#6G()%?WgQZS$A!Y?iP$=&{>XYzM#gEh~5O7hESgo!VU|TM*8A;B1hwLvP_xDsb@{dcUxKB3P z17o)B?LGbJZ2I!5bjNpouEymznE9-o(o-(PJH&9x0ux90*Sd0gk(K&|w{ zM*Ftc{xUI|d6M#RI`@9&s@C54&aSF2Gjtq1+@um-j? z8q35%s{vTsfL|C42KhD2SU%eVzy}9^xqJQTL#-NoI0YFNOusBfy8e*EX*M*_3e1$s zZ%+|4gQ#a?saGVYbpnI z?)*88W6BXlJIH($TAla4wy8CWJ2u-qiUBc1Hb@dDvqYjK+&h#eVfY+xn&Kj^IgjFw zn#l}u)!u`zRm_z(PfkmclHxR+K_;n#N@m@mrj5VHto)+PR2B z@wl>Zc0A;rQU}XyVULdTanrX8z$QeeEe&5b8JFv-o{Fyge(Y*7NFoa%SpI zn6*4z^MxWP%ae3Tu7hV4ZXGrA&coEdWqi*d!;IKGvYPzWQuDQ&tNT2^ux7y>a>JpE zNpuk1MD<|(m>McMyW~ScM~DMzwg!8U<*cPg1W|BcUxVKYNc*6l3ZBR_9phTz!!FF2 zX+{bK>vb12&OVHn8=+qzcg8|k=r!4Ox6oL~vKpQdMm?jEkdYrAtc8VVAA3fFY#apL zT{=b(v?n-PW(fnf!=%5o_`(QWMlc69yd#<8r6Q)vSO#+ojEQye6Izc@e1v5%s*Q@; z#E{HP^vUOu32g&TAd@migRcNCtAQs_aD-xDL{9bVQ^uP;q#o--QdHgW5s}WfKt7QG}1%8*;pobPZoMYZb3f;ki!ze<^(z#TH!8V$$>{o?9 z3)Bg=L#Gv8%T@|%Jt_zr&H@u#mFy;(5}=pHq83yZ@Vh@*VW{&omcN3*s1@84JQngR zfQ(3v*0iwZX*u3v9TJOwA$JDxZE?gLRhd==e4NF=cycr~$k8=GeXFuIS;eLr7>zhe zz%lUn4@p>G*>-&ZVEMvc9k_Jgxhy4nJFES>Kc4GFr$7Do|2|e1$@7mp^Ip3%ch9cb zJG~$7-D?|wemgVid-T$_`^W6|jJLDu`nY>;t2fx_n?Zv8V{iU+TCz7b&$biz1|p{h6qcL7Bu)N z`v<4~sXc^*-iOd*sR3AUlUnJ&p8CV`mX2_~6JVB1IHIX=5#D?H$%1ivN^5{)2kv1n z!}H6hH%t_zV?Z*ZEcyJ+jq6{mf|U&efHPzBgL@^6Re>@`&Gb6NyJ=3LAw?2?3ZXH9 z2CGiB)>>(^o8>`+FkA_z^S3Nbv`}@F;v*5uAZ^-eQnr+~jJjBni-m+R8Lu0+k=ztm z#-D68<=zI`Ce+z;sEiqR-igVu3>mg8rJ;NkdW}e7H3`$o8~?6_J#JiuSSq@13VmPa zkGZZZ+|MM{QeTtGzw(+TX|hA`TZmKR1%Gkgk(jOX{|8z$BTe_?TSevOcPwA*uFgre#?eZFe1uX3+0oaEZb!gkuTg)o?5d z!8m<}qbY+J4q&dp?8uTQ0~ZpKIQUU6kD&Uf%&G-MaePAaU=j2eok)VVAjK0IdXtI_ zdQOfeh5k;Ad=fG&-zJd7kz^Q_oFnl?9wpc<6R_lRGywlQ=}lx9L^;v7gOf=CW9);` zh$M#-Z2N`B7o|vo#z>;{4$8HF;TU_81a>C`QxniX@4yBuz?wuSLu^|xb{nZ2a0f$Y z<=w{W_f>K*Hq7j+L7?yd*t*)6w(>OUyNS|lG`ZP9Q6zD4W7lX|GgoUOgeJ2sogvXh zMW;JUG7)1;oM@oJFn$pVLqV`Xrb58^Ap5}&#mPVmRm*(Z`M>r#=lMn3-4&W9_vTGn za&n&Myg)?-W3U&*cbGwyjD_xDh$IcX!=T7u%U+?)0@HFI1YixqE)1a+9KnF-eUM^> z;xU|?CGYjF56`YM8VfsM1dF<8`W;v-u<#cWdc<-NW(8E++tqs1fsL@$*G{M zjNAx?tVkcb1_f{hfh~q>2(t}^)~uXmhswx*mV4!jA=DCvLbiP3K_ZPxq=<#SB0B;% za3oR`lrGxGxk$N~ONNdwY-T}6+zC5jAD1J^BB0vV88!C5b|{du6FJlz*ptF>SwDzA zV7ZZ~A)MJRN5F8I#S!367#&5)msk!X(<(BVjHhfi1J9-A6l*8x`$Z`dLOGZSjhg`G zcwFljc9HZ<2NT08VE_gaPbOXhfm5lXoKM0n4F7VVhVH@(LFptK5ffm(^1kdEBPr#9 zp91j5b7WkeZN4SuT|IlY`Rt#+I8!s{iMIHbGT{2^O!HIe^v6Fp=|JP)QKK>QrQCS^ z_-cEnZqlu;+rHj@wDprS`KO!f-gqOuKGW+z)NtrK30C9j*iHHrIxo3dUA_t|U$qQK z!hzp?J?dQc{*<}ut>VDZ@>@NzXH37Ee#P|3j2S;?GCGM?WUgfD!_&=7sqWowUN0Y0 zDgEZpM~+inuI{0TfvmS=3X!ywFk2~Qvn55{ib;jmpGqdaGgLhih@}fjZAUC#fc*L4 zcO<+IpD+)ab|e5a+K?b3#Gu(n1hz47hUD4mTZ81Et|K%6TP*X0IvTkgXalAQYvr@M z?%$O=HP+{MQs@V!pAZXR0Q60Mdv)~8nHbsAlthkW35?w6s(qK3vq9dPRY}u`!69yB zK`xnnffX*Tz%7Zf;tx%~3qmI=W?a01=`db|X;jGMPzYAZ5}|I~7<*fuU^6A=>>A+z z%A{YYe9F*ryw!>>e(yLj=`CKu=*P4iQS(5^ipLGkDksg3>kd1cWnflCx%|j2y*E#* zuTmNL=xvP1w*+~EYNfuFbCWl3n8>ZHnxZR;?G#~!I;p`L=)i2*BUs!8E!84=89bi* zGz%@dprjg5p4(ZN2iCGap&;zGqks&{Ke|we^qQ5wP&fmL=jAb{g0Y+j5^T9BnndCTn5{v~;q9{2U!gyJA z&p{5GqcP@TK{OpZK-M$qE-p@jf}^pMA7jz}QIrP{ffNtLMn}V#C!_LrCe#ihkaPAv<(*D3Qj1aUE4h7fuYQ)&iN@_OlWCM7!>B$27hZ!Fn%Ylzj}V0Awp?r7%%&s-Mh_}tC#@VWL)1L` ze8>1uD$3_p$dY44`77xbq8kYnEsUN+If2`xrgd1v*%0d&LJ~!QP8n zIr377aiC_`*wj`2Iwp>8q_TZ_Za&>z8eB51)UyY4e}GnO>^5R<}k7eV$I#pWbsCJ4+2GbN2Xc zbmm-TRiMzp^!B?R!IoKbm% zyp3R>YfQ3vyG}7l554ITIr2e-(gk_Ncj4&(NZptsI^!jRR`P~6Y4%T zV(3;oA_mnaPegyk@$9YPn9YJhZ!0aU(fEX>d8lNJM4!C-)yC~8;3GZTMCGtsfY;@5 zp*rh=eZb7bLdzi5z0s&(ax4fu1q((3777~>zX7(4dW5LJZ#38w zJK)+E*gA-F!eC?lXkHl8G-$e$AaG{y@8HivWBvQ6KN{>GJ{VQ;mO!cia1cf;z20x+8Vtc$2zz_R+FUUHc67;iH5Z+~LVjP%KezyGCtEy_ zfyJIe7c|iQmvu;J7lajIC$pz*Jq)t0a4M&;#dg zm2pOB%*BP&?#}H({R|fp`Lf&-u^ynz@_74V5~)~;Vi_A}Xs{EtR2f6*aw3`H7Xt)k z;)D%{^JJnt_1_HmlVXHMFDAgv`ru#B>y4eA#%Q|X4EvWq07|dY+vgwQZzl6;XRvE? z`;q_IS;PNTJyUng)PNrRMi-({G&mSKri6cbXaJ{?_vs4pJr^CAy9}j*J)BDJc*;&|+ow zNQ)t|x=MG$9{k4tqV8=QXlC{*Z+cUuQhj}?u7OzC`7(@>yI!>b^VWzVz7_3dz;Wkj zwLgCL7s#wYbyvP10R|C%!sU5 zcIlLe5jDIg%Eh2sw5r#i38ZV>q-kW}5c+`@FMNI*5N*;qaQ%9IdTIE`;g)y8Bpp{& z3&mr=4UDH3jEB~g4VaDr-DR@ecH|YqDzoZ9QghPAh6YYBqJqr0mCMX~(J!l>q>1s0 z_9C$(i%OUlX}(X zJn#E_AbYZ<09HV{Bg7a`4Oj62WYMhvl~$B$3C$HehT^J|U~eaF zF9fv%c^61`0^Iu+i&`+3CNd*~qgc#Ui?AhWMOc$c#RGv|PNYkPj`9HGhn6lCa!A9{ z-zb1aDy0zEToH(hR1P)(gVH7eu>~Y^=-3krp6(S<$FLWNWjHQaT$I1h(81u>^}RRH zNCRX`v?A&L8R5NXIubsN@Q!2&s^g zry?pqPM82Jf7~2EbM~w@#4|QWHGmDU2f3nlyVDV9(RakUU%_S{3kih@ z``&siDHg=fVUNoZk)O~)Lty1$)U(Is6I2G|qV6cnA_f6wUpvBk{IG)_-!MjUZPuUq zkO0J7EEjWtoY{zAt1p7kt9F)&eL`ei?QBG@TI;$5dXZ3xhTzZLb~l5f2Cp}hil7`A zVH@&cIBV=1sWk>f?|ZYysa^z)N12FVuV8o=6xQpFt_k*bQ{H_83*Z{!u-M6vF<1-S zLox?mWxRO=aikEioMGxRK0py~6mJE7dj@Q{h<(myP?%7E#e%@7GU&>63m7Ta7hyZf zqls`aTH9WXLJ?g@$`$2QdCr@6YCA9^ffVBtP}}@MwAUA4rVSXHtbFtpEJ!RX>@(;i z8tvEVd#cr={Ve%6M&$kDOs%H_fQRKjdK6dJPT${su_ZKiSh5|JE*~`xA3cH=dH9dz zkH1?QY#N9EcK2v}aj7~61HQODJ#;DQmSEy|NtpAtK>FRmk5l9ER#3>a?UU7~VAd=} zS2rGQY`hl$9&eWSZC{K_=Vnxg!0_p(pSLc`uBD5=PY)ZL=P#$0PReEwG!b`GZGJ5q zQrQ$gH%!kjRazfy2Hu_77B^3}9^E=DKlx~j?(UY8k54yM3YMA1p~lcn^}K2Mk#@2C zwOmNe^3KiB_PalW^2Q#la0C2+tw$?&V%HV!USCm;;Mg5{kdOtvatQq)vNj-j;HZb; zGcJZevz`REn5w1FMX!7WAdOK_*!9af%NV|~2(Zd$f2_3V|Ng(o^HNeF} zcU?)9RY3Grl_YI0ekTkR9ZhOjY!(MoFg0uCFB6Dy!uq7tn7d&i-DUs>ZA{Qv3jl+3 zo53IE_!z>eNm8`Jbu$ZkRz+Kzo+5rv>~G~}VfM+dBW81G-n3T6s<`Pd>f1e;!xWpU zEQVPtyjEXbe#hqXh|l3*1XU1gSr6b7od}x416Qv{1IU8X29Xi{R)a{(;gGZJ2SS2i zA%c?1BWzh?gRg_291OgLQU?+))*abVc0?i#H!#8}9n8OKso+XbXGT-nvF;V3jS)0v z(K*eb9R!5xKKxIhqp{==T(^U8X!)>u03lY@j)`b zI@c-4LG}Qr-*h0vDi!r2`hwrc%T6I#OzTLVOc&z?NRy(iF=8J%^3`~ zkPwdW4QBwBqku!Xf1zo1!V}zTwUGPlbog3!^bUHQNJ%rRlHfN|2Zi!_*n@-(Fmac+ z_C6-gV>F!tJgdlCp}YTrCOV91vv6A~MBz}1Aio~PNNe7GFkkOJ_PLlBchL*H){Q`F zC0L#6dfVA9H@w{Q3fzW~AMK6ohr3>cTL~B5Pj&Y**)Hg81iuG)lzr49ea1Dyll#~S zXAQa7@UHPkSJ2joM5A8AE0^_AMkvfTh5fH^;9j)XH4uQ+tD$KDg@8hlU*Q_0LDm+~ z4UA+;c##kt$t^CDsvx-9;VyU^Dy&6}pBEs0uAz~z7G01J*-2=|OF|xvF>{^AD0t4( z_R9%#t#*um5mRotN2s#{0`f0Fw$S*xA>X2Aj}W%&Q97S6Z+`E=vy$KP~xAzos`PMqm{attx}fAWAihR*ei+E#cXf6ckw>FD*7UzYK0)de=Cy{UV>`mM+Zv z$*ZKjoJCV>Wi=zIY6hej(vpNR=5S%lz4&hB&QB}!`3lb7h~2sVfbD~%zjxR-yYk?A z%nX8#2?k$3L=-FTIK$Li;VzSLt6qBZu$A$-loOZFOdA%)R%v_+{7!gV!0-c?Py zD)myGLQI>pX3SJ!t8Mab^Qt)!pPdlrzc%TMQi^YAubNh{748Mh^{jOt(KNd#%s1wC zS1HkepDMkJKn!f%<^0;Z)tKndUMrZ!cUm{)TPj9tT>!W(|A_)pF&4&j+3pDhRgJHZ zo0hQMfCsxgr$Y-mVgJ;S?i^r52Q<(@M=&ku={R`k(9lT;EItT0;Ut1S3+d4htJMHy zRaF>{v0g?OA+x8kK8Bwuz(){;git+e*z9)D1`PJxVeJt(F!DS!@M3!amLmwTa6!6* zwqTStU`Cxz=TssG@}jZ+)dX>K>0~L*ItJ7)bPE3#z)b^yA<}{*OGhN7;4)^=N$RqS z$cHYLSU?Dcb5id>kmXL26eA3qyq9L{mHU*EEZIwU-bY+^w3ey!OdJcghyU~U;GZ?U- zP>}qdoGwooJ5S%IKe%!ar-W>fIHRY-VSgKN&uQP>F`CnGu9J{T@IZ%Z+R016WtBcZ?I^clXRFeYFiX$12u&VG;Pt(KFd?6i}=PF&^mjl}qdOJ{?Ru zs7PYXVHCC|IDB`&c=N}#I#3(I8$!1;0R3n`!+@-4Hec%>Ljxv9F+Ud|KF${J4S%

AIo}_;GY{LDv9!fbW2}dB@426IkL3)Y zRlY%1`W5bgJ?c|hA<#u&u|Hwvkb4&vV_VfHFoA5kXnQm3P!I1#<=`2E~%82@{5dYF?xla`nccdUQ#>g z@TaScm1tz$2v@PIsHWHJOX{UUE#0h!)gKrINd7`yPcyb`Y_$pRz?9m*M2o)UPlI1w zyGmulbE{T|B@Q<9i}NO3aL86Sz-APzom z++@`X)$NdYQKXnLQ9d#uBZalE%W0oS`4O^MX7dmW7@(2nd5iPN0BrzTX<`9`iLhv3 zvgEySPs|EnMSB)AOtprMwzKhwMlVWOqW}OP07*naRF;D4EMxRcVzj}%V!a_M8AOy} znzMvL!{LHUiR`n;Z?+;h@NH!%NT=cD`CetS)BIDb1ZqVc-n+%S@IHkSx$SY@cm`1}c<>176Wy zbR6O6*K7L;h)N&&7`#~Lirc0C4G@GSk~hS?qC9E{Mc) zz?UIY%jQW`X4mkk)MrI564%85i_!NP1WN}d(F<8*%Y-Jwo zXBSK`N6#j)z7%3Rnu3w9qVzfe;E=BrLk@tl%=RI$v8-mhM+6uD$%}c0qCw!Wj$(k# zUU7D@;S$56R=(iQqqNXLOU!~o&fUbJS`oRz&{@7V4Ixtnn54tAzaJA3emlB9igLmj zE0Ri{eXBTFG0!n9g5O3F%?gR~?z0s*nv0^>0rCtemiXFSY&RDx#iD>-MWfM^5F9c` z&W_kGoIEq4g-4;2>E&1mB@4NjXxSPK#4$ipc1Mtq?*80;@$A{13Lc;R{KK<%JRI&9|Mld?4)9u_N?*(rgSQjsou7nirQ{}70Z0LRc)>nXZrc}xt?x5-b^FoJfLx; zuPO;?d|63oR1ek%*vZcOr#KDXyVc`(I&|ao^3I2ROG`OJIbV73vY>Nx(M>xJT04eH}TarJ8)imqc&U6vk@0rY5${e!qz!D@N7^l99*7 z#6l?+#wQWgaIM{}iC?Yu`~6Pd2p_k5+g+Wj*t;ETDx`JYFE*W z#Hz*?K9Tj*=; zib$ngGl3n%XBZK$tIaU3fYtI^F|X>U+UA<;QuI3CdR=_#xu|tqFJHPp_G<>SQlUg1 z`3nZ1(|?`Y@*AW0no6Ph4gU3becOto60@^{^P+jXIV)d1P4gHc+u6uqs<_0%4k7l6 zb*~+&OQF4q3SZ)_U|=DyCRc=KNDyAsI#{yuYz(GxSY)bHDrKB3fgm|=IWoiEvU|{p zob(|dQ-)nfBB(@KS+W%(Iz)EO7NDO+gK-;tXmK5u%OOialEXhK*7>@hIF7I`;3LJ`^SbjTrDLw*z4A?4ffjb7T<7vgyIEg zW5c@@^orJMUJ^1;%rN{J<7h7w8ZE(Y9|F*BpBP{phsYw#aJNWlVO{KF5yNNDq=!Fe zz|{z#wQ$QP63v4o;5kq{3}gF+&A##^5;s&W1MiM9;(2)*?DH+!zKp1E85M!fV27Mp z4BP;%8+{CBr~QcWX8<@vcCAojvL}Bl4%1{)!HZr$xvLKxpQqnRT9CM^gja zf!Be2o;6hX{>IoW${1q!KTOYViapKLV;E-R(TcKt?AhGRR~KT zcv(?E|6d-3xeqHC&3sj(eb+b@GLX;tKUn7c|MH~sXU`_k0U!eWwtxA zfJgfLDD=4XU9?|o_jn4&%Jl6`}ptA-rZQ0pFX{Fdt~l!A4LwfzWIIZ$rE{x z*FP*Y>pSoFF81yorSt0OmnvLWVQ3wAvuE`tY94Mpco?_xJq`T|G0Z+Fo64Tk+Ys*ub z+aJ&6slESnIg>tL&OG;Y^L+I|%{H!e{DUB|vXxZIWjE(G ztrti)hda^D;@W)A>CqqgYu(gG{oGodd-{uxZR(PNd8U4fxSx%@Je7}ptGM!@7~DyV zqi((}uFQNJ@5mF1kC# z$ep=CmWJks#Q|H*hfcebJ%lJB1UV9`+6r6O%>YIsfn_dNoZwN}okvbHItaM}L@dh% zsg?JQpi$6;gCjAqENT$xt)K{rv@B6nl>fTS=vSbvMPsllYd0U^h&b-D*v%X>J1N;> zek0fjV^M4&`H}%F0I$%7ghO9TIdNEyl%0pJBv4qcY%*)%b{B_5i7YCCv!cO~BpxL# zL{P>P=x)&B7F+^Hk_U-0GR=u(JeU$cEMkp>6?j-kK#NRk$wVrm5jh#eFj|X)g_Xk9 z(l84aa0u*GC56MtUwKnrFC^R7fbe=7;*}e2n-)BP0^@*KT(3J|OL;ZT%K@}_T5U^% z?Zv@xaLXp17}AVRK_sTpsSp4KtAPPC$_ABf&3I{GaqYWh`w8-kF|+8oFEAWvpzqhs z%`d@|&{jw|s8}`-v3!cMu?1DlECR=Y^wsyQOTrEqyew5f2w`^f7MP1+Tru4c%ZsLt zo2-i#9hTQ;cC+&)@TKx1ZOB;>e{1&4+mW}b*hPQE3ICU^tNm#zPoq*=rZ0lDr45Ug zK|p$2XwltLu&r9{h&W?fP$6K(1h#CN))pu#kln__gq1}|q;aU3X6Piu$v|XDNnj&r zBxEwinV5-*6F-S=vhn}e=RCh#X3TCe(B6An^$X{o=Q%IvKr(U}gABoH^fX}Ztj6^0 z8RpLfvQS+W^SwVd#G;J>zF-)DxfK|GBj~dbjir)IrpHD}OK_{@q8JqnNp%oKn;^up z_S4lwd5PN^HSG4)uoSuI0_mzVNh0VZ;>cTFNU%39p-U!+sKF)8IxG-HU$DBzP1sr`yDoqAbZm53vhfT z7QRHHr$MI!%ze4i0nbF~62hPTW;wo6!g|=shU6tH{r!G_8*)N?lJo!hfV=P9xN&3R z4u9?JOiUcx-k#Vw|LLitmo6Q^J^EScf86}zxt>k82!fVBK{$UAsU>;}IpKLP4_eeTu(fHm&4!;umXD-acVADODaGIxDu2w>L#YMnZipBol?n)5i zs~m#GMS_h4z~H)oR*mKvkXMZ^28@HyPpB~&)$(1ds4Ub9=*7BNOANR}jGqfJSbIOX zA&H6cQSoeV6rFD%20Y~s&CM0~AJbn^KrggSOpVv75`=Pn>miGKvghn1{U`gt z;~pw0WMw!D^)shQ(|Z?y;1?aGu%faIg7BGFd4lJM5{Br%LRNFai2n1nbH5Kf6$3w z2ZbjbR)#Tc)(;T24`eWaCLkW*y>Ev3u9JAK0!v{;ZFtH+d&{seMgfu&(r2z@P}=D& zcD=)?bl5$_fgPwos^v&Z@y+4TJMViO!j;=%iT^or&TI3d;|DGdL_i68kJfCH-=i2V3H0* zh%cCWRcL0Y>(x9q5k=KPb)`Z}gCtD95uk9Lh}oc{b^QqLAmlV@xNDI3uXK&$DW%6& zb{R?R5tcM`$|OfqO8)*j$e_6dc*#1AV;UbUNdEqa50P0Cv{zuj1a}d$Z^>_MlA3%G zEQ)=jz9tDd91?Ob%%c&oVn5QNQEkLubYKaMN8YC45dvO3ptTwyA`A;sn|Tyz(3~pC zo?to&`%;_F$6djJYn&$C1j7-+wGc;n4g2Rds};&E@L}e?P(7m^7`CV-R4Af4*y?Ng zI0>s@243FYzH{T>uU@`<`RWz@dG#wjUcY|*^Dj?+`S9WG+xNSRZ=$=)@7}#xezSc1 z$n)nrJKH<^;{`3WKw!%RKhB^3^b!I0(IY&6g))iIsb%@lOv|B}!*5Q^)gwrds6tXU z0W*xoS+NXf5&LV)DCZT7lNtYPpN;{|Q$5(m` zPb{|0&(E%B4Lutcn>%aCHS5x$%`X!xLfS1ybJdH;u(^7nzdrdpk+j7oS3AiRYDKsIb8dMnhR9Fft^qp#Ke~HvSDEkpnR-Pi!*sDYgA?DG?zh~ikRCDcu+bFpOT`J*S>)5Fhc~2a?O> zA`VP!wt;9Zrqgy#cqWc4ItUT8fgBE`QexvPJCUjgj|qUQQ!XLDLMc+JHieFcYG%r* z6dHf&P&Efrf+p)yV_?2IrnvL;-oI7B?Mu*FTg&~wCEO2;fM^4UXBblR216C3&bSC> zr7BLxfS_t3(Sp~KlT2VY`7&EkrW$zdgC}m?3Lazh?<})SpV;mk`4)+nEH}<+Z z=(xsMk%b`3gCh0{dMmo94@C|D_|{f=7R}haPZ7q@Sy9}nS96E7B8&;NTFreO!jS}4 z%oe0#qQOYlP-!`KL&edPkZOV4D%4soStwSUijlX6@*~Ki@q35GS90VALa}-wd*)<5 zBN11Gb8u#^k!ybIOwd=+FQ&Q(&KiwUT`wai!7#{g#3b5}q3&Y9Bq|IEHHOWEsaPP>XQF2?V&zU?|1`+(DAvZr zDUn_YlkF&?I?#jUCk{;jNJLn&E)g{Pr>95F5l)~IT4g`yHU}_JCM0eP_`Kc#QlOCq zjaN`p1)r9Y8BSjUc7ei4W9&F^MEynX*Z9@^anWWQS` zQ0P8&?D@{o?ep6c6MvW>tlv*REroXn-O0b42XOB{b?Op81L4V)E!{009gU5LI%W>d zG#);2_~glx+)M-UPMjC9vN;Io9sF(iTaaJTp?DIiXcYSjwN^5#N}Mq~CAypI`sBdp zo6(KfCl!hQ#X<=KCs2ms9|dxRxQh_eXE5O8f7!bJpC<1-e*H$;BBWo|#w%+lZS5DJ z1#_i^7PQFb`Lz#dWZt4ldu^zNA{5PH3^6eQz1v8%F>2O?Uee82ayM7xBFEijbCUhP7VJ=P&8eavbG;9!40#q~GlbF@5@G$znh72L zF%dw=)_Z$*nvhrq{hu-1J7Isym$9{+rg30LXllXei2i}BU$*8@@xUdJUU;# zI8Y8t>njz%w067cXsBY(JRJDw*lZ!+cW5$4tiMuQmx{@WSOTtJsh;F07v0N=SZwcE zaejU@Q1R!+#}viHM$_tod*#^0rGj57g`t0*9Y~d=j1<;RSo6|y)3J@ork=3>17R{< z9b_Qo$`i+R&>Pp9ztA)03;UN%owJFBi2&B{c|=*$55xXkdSYSaqM;&{LL)WIt!o!e zCHqclv~1Vq>f(AHhirF}tw~59=qeR#^F-TV2Syf0K-2=ac^Gwr0jQusa)ZGcLg$o|h^;3SigE;2Flh4t zq*-GX;(;@)zeuQb+Cnon90vim1u=~dIU8|;gX@!s#}Vv+1wyw(0N#xaT-*yr9BJ6oXu1R5 z%LyGw-DqJWFx1XKV{qLFR>pfcIGT?9$t16U8G*&jc@G581l&xP4fUQRLxh7kG_0|s zt13=?MlB)1E>T~ove=J=@ifYj^ct0!x5M05$blS4q2zufjah|gTlj(X7(81dwRGp8< z%V_dt`%;!blYW5$D`|;a2zq_!Ln7{b(@WqAB*#RV(Anji&RXIKu>^O;a|p2GJaz6P zEFVYD5&e$&B^Lp^xDpA_OXvH>T~>l<#$DsWr^{!RVYr- zibXJwp{)Q;!qG{Ho_k_Fv8mW(&(z=)os4>dMvEGgj5MQ(aV>mrXFEEAW zGQus#A;ThE_QtJ*uN_c6dohp(=31-bL~qCRG<^kL%*^||Xlj56E1dYi$;%{oack@H z^;h>FT%9|A{`@F^jE>?_+(!A>`O&$#x$|_NoBJbuTzU3EiU-~N1h1FgZvXxM>iut4 z|M3lh^(x@{Z%>{)dH4O@?Vot-n@QOVfe*tIGi{Q>^`!1ZgKJJ-bI3{ zQ|I<>ZTD8y7ydO_WCAv%)s{6*4Fm@ zt^M||-EOwe@Ec~KQlWQL0@g}xg?Mk`@eeD@31R#dNgO$O5M9XcG!o)dzg&sLyI>xa zhWjQQJ@bF&;v?q2=mb8@O$?%qp_e1EU`9H;n=>jgq;4;>`3S~3jSItN`l*Hw7&1d# zlxjI9ovAVXnVx$|fWKVLV4h#E*AU8>``=|qLW@;z1l}v;S!>RN!_L_-#>M@z;nkmU zi*kBdu1sXEq&=iB`niBeT59^v(6T1kS596SNLQquLp=qz&@@YZoyss?qF*?2{h5py zX0!4+V@C!?zWi`hqJGGVOT(*!F z*;maebT24`t{MAU1sabOtjXdsVFlk1NQn}{sQMm3V;a(FH8CS~lukjDAuLAp8h4F! z6eYk2w`!&nhET_VU=Ah9j?!sn!^oS)_SnePhd3E~UZT9lC<3lLm^&j9y3KSBzg%XUBRFf3Iv`a4my}}5by>9 zDVy`DC&0CXGY&X~k;}no%wZj&#@mR-Vk~aF?Fa^(ju{6IghCD&kV1&zm}#^H33~ye zgs-gFYG{~oK-=tKMfCS3X9J-zmkMIIOeYgBwuuU0jfeIg`L%+a6#vv0|8j z8!&k`HFEOCok&Zh@K({bv&y3v$ z1BXx2QNtHPfMw!MuqY^G6#gC0HK58HBGgSQ71}flp%n^jb(Jaw3Xibj9ZKurPg25m zq@ag;AijF~DIxIHYBfr|5}8<_#}Gbico~e}Xo(4H^*ZDZz~sw*V2l0?L92!>MY!h2 zd=BInnSDs2)L9-SRTdXo34Jy$6e#`EI>8xeN-jp`&X~83S&|{iIeHs<9%6O7E|Xz zFZTg+q%<#7`>OB}6V&<`7Oj0*6a{-xg~0mfj%f^}2dC+|aPoFcjU$87DqO(vSd7qi z60qBYv9pNhzy=q2&{aBbdT3-OlM7AgLZ`zW#4b>RAC0l=d>w+}uY{qQIuG4Ob#yj3m2Y2Nxq9^q-5xx6m5`elh^Dr0UcPkc{j=xq2&{=C>@uU@@*g^Bp<*DwF|^5w7ZEAM};EEB>0=i9~K-o8Ek%c471A4JO! z`Q6vA^G+Mkz4^)Ju3aZ~Z64TnVAqLLdrzI{f<(9r{E_gpySw|`Vmoo|kK4O%weJ6z zsCMhEU;5qdTes|No#mTN>sSB)AOJ~3K~(9paJ3Y83XM3*uyrC7yTK#p`tBFHXNaM> zf)Fs=eOgSPITHF@Z#Mz(H8b~sSvYh90jw^S3RVE-y&OSv&zAPEa_E_QOV z`P*5$f4wQP=V&b#JJeAWaOMvWjwExUC^*mG7$$_=BA5Yj#q>2%{cJ&Vwp=Lmbq?hS z!bS|s*@gyv|uR$fcES3dh=U8vO|lP(EL8yy3VQdl)HpLjT|DN6Yt%4d%*(RD=T79iH0=P*i{ z4#WQBw%3_4$481HBlZUqmYarG@bxc^8N(aLKDxNDY?o@sofSV_Cfp9!yAN5_C1oV> zY$nke7Jwr^OmsuJMevA(UPpUkR;MyHYt@=&c9SSMh_YGxlad<u71~@lnpjQ_mKRO!Q3JqZxuI z&@EsXK`?&Vh!Z*x19#I*AwWiOBya~vZfD%>7$Ihfm-`8~ON{@=y`Haki{7DPp|wOH zJU`FZ`}ul2c@3EUkhr4jh$NL189l(B>JS4r!e~VDg1o^L4sJ$rc>04T(aR9-M+t+2 zZL-HfcRO(S3+rnF3=3Vq9I}#-wQ?b4<>~JS658RqgJHDf0@_*fn8L8VlF91mLG^-% zw|mJ8TZIQEsU~w9L|2lF*^_R>xuiQ1_*hoZvG_p}>E|PcbGWfy#0e}nM$?jHL17{J zVaT|f_mieU??4qHS2Q4i)y(`3XHQQLsdMB`PsBt*4RU3KcabbT5zMb~Ky0y0TOixq z3ru%d_Rv=x%^Vs%eYvzP^fkspuU=mc5_C#~z%wFNS|du4K!VnSdPR3)C&`#%1Qtm# z*9R!B8_?m z0|_aqHKx!$`XNPHnwA->;agQIpu31!fvzFb>(vt?ge z#u2XyRHZMcRFLw1W^c`*fI&v}f=W&qi7eDEpnKs0S_YAPM)zPK0SuO14UkB4RT3Ff zyR3@tK^4oo3H$~Ll35x!vn54jSKAc_1FJIt8HVuAi4azfiIiAELih^f=O{<8x&j=M z=96SH)VRy;iw49~qHU0@aH0#-W;k7JJ6%xd>L7uRBxI%OKZzsiL}=FmzkX>u^832W zH?|?bEV5@mybhJ@8|WKg4JG3{a31b=SCk>ctNH&4VP(HRdHLh~UnhHquNPlnmm$^X z&x<$C@7^;ouw9H~k$ArM>nArpe*Sc(x36zl2=zeU@Gz-0CgOd4y}f<2y|WmG&yF9T zq?hr@`!n}vzMh%EIQ-?y&7Hz=aDfd?w@H9sY;9~j+uHiiv#rO^c6O$APW()2{nNka z=jZpGnxFr+uI?mVG5iw7`o#A;&xW`r zdeL+1<~dX`9AV0aFuf$RwMYI~%Zo^&qVUv_x45H$Yl7by!bu9&02Ewy%3Ov-qKof( z`i@8Z0ka|O>CuHMmtw;Oiv^{MTk8ezb8QjDv0H{DR+Ea^XOX|+TkHMpm&UH;i#@*R z*sBy-r(_b#!C6+jwWAN0IHO#ZeV{oubnCFayK3R+qt%Zp@*_?0?kX|9opLo@Lw)XO zVS|>7d>LjrDo|HgR`MKO`0^u#3~T#HThhPue%VU6=_bgNkg#lCDvP-fmwlQ4#(Hog zKXUBmx}`DL+|)S4Y3UAzEAud$K0;n+SzI_+n(v4o^0oPs3r+5oGbF%V6~Q#fduM*z zG(;b%LGJEsxYbelO=y4n968tDu+DafD++OqkbJ$V%w)+9c<3yESJ|vs9DaQC(h>&K z3+=Id&ArIG?}nHB3;W0N*~*QJ)+vF^EM6b*>uiCzG3u`@7BN;8+_A`5or5%HHB(IGbkK5{w)E7QYTc` ztD~pza*!HIiyDXWP$-tc9xyyG^p`v^ijOiOx{Z-CX|K-f4eNABYJC?*@Yx%x4wBf0 z_(<4GVv2{s2#37YAa9I0f-!G+jP%xor6Wf;=yjkCDIE6nD>~S4Vv80+8$0+S+QLtA@}UIG)tyCZV4N`nXnn6%biH& zWPejBx|-9cfW8v#NLoG#F4aPWjiUJoQ)m)n^dzB=0q&VYSNQpY5SG#QH}<)<3Z$*H z5M$J@8OY{}W;XoT!O}*W)R!UAB*sRC9-+u-a=K)W$@``&MAO0uw3y8Bh>Ru$Lz>YY zs9|Wefxkfl+nPpNi^STuisZARuAWv^a5@0aYE>YgGAXl#p1dlpF=3q{pP9^$9hA z-lKRlUf&gucjoNzDC!8i>|N+OiX$2wx5w?#9P4ZXMM(j1dW`2LWd_NE#2REvIPILB zkAqdjo<&VCKKcdvS89DiK?IvF0TQ_Y33ALb^~Mo!A)Gv4`-BAeejgj)vmc&4JAUQ% z;GYJs4i4TP9K3q_>eZ{aZ(q6c`R9NC;;VsOE4=yUQSynJFdM%77O)tlIhvy-Hl*T z#n9b-?(&TvC&$GJ_M!3d*~!05-v9Le%*>}V4`=@T^~;wpfB0c@VsmqI`=9acAGfzT zb@s2t=gZHxww}G(+1YvZ>gN~vpI(q;A1HJo;fFTou^_?8ny!nP_)SzXkgh_4&x!D} zh(rU8Mbi8h|HXJpbOMt)-(%7_cYWCq!(#OLD&tvCpEiKt3L^|kD{L`$F`%r$#=j84 zI#pW;TK#_+(!SRx!TWX>l=juGXWB2hu5~kW3Wu~=5zqA>s48F<0lDg4ZYW!4c(cE1 z?GKi<#bdFl%B9Ah#m2@BThm;3WjCWU7Ctz9Zo4<19;H3rU#l;gz(HmI#pzM&-?7DPxDQ|4LHs$(YdFgPwN6{a5uD#i7$lMM8 zV@qUZt*mUV&AwmT?I#^{FP}NQ(jl4{$b}|{Ovm5XPx&_*Jdbq`S4jM$$C}E9+5{+r zL)kF9SPV`kvj=vUfVnJK@Ir)Q^2eNNZosF&zqmhC<8NDUz4(jN)WUw#iP7Y8Lv_t4 zpXzp0@~4r{(lL2YRuzKLeEOT^_;zuKohZI zkjaHHEiq~}Em{uTz~LIXmI0uwe~7rVj>T4loykK3)z5HCO?kCO8~`&a8t_V#*^!3p zyeUMXk(ky99tSz`mU0v`a8W}n)>5>-A@;$bR!-;uy&{`yX3jHiO>oa4>2oGC!9|2# zZe++*$6`TL0S9#%Y$s*J3KF)0QD_vN0H=eDt_QoqW30fWzTX95g-NNAuL_|DIPAe* zl9&8*I1}u5IOv|>C!Qb{kbv?93Bon zdt9WJF7m-vht=c4AleEzhttFbz%KH@lH-vCZACWA$(2Z^Ph4POIo;EwkuI(vWa<^^ zsU#>JPNyl-V=+Ofp~aGD9^}+BZw5P=+X0w##A-n&u*DGpj*{IiDYBd0G`bj|w{Gky zP4iB$1#@UYf_A$1;Mz;mVotSaOSEQfd6BzV-qQAkH!P_ogi;u zDHs}x_M=WfIp_f}%}nF~d!q|Lj{2Nv309+aABUm^7W%)0o&QhM`5njCFOXt)tWet+ zupOhleiK?VSrMpNE9eZ8mTnP|(}bpsN@>AzL@u1=t}RGt5G;oWHUT-dDVg9f$RYwa zm#McO{K?(#`{8o`$6n9Z`%^s6OIA?0wv=9iJo^*Aj+73K9ui4QKbXtScBHF_2o(>k}S^vd^b(n|GxCu-?MbxB^;~nRx z`-8r1|6q&NZMSdxd^?utvYlIl=sT>Iw^s`!$7X+XDksUrW(*Rh=2bOuwgLOG$> z86wQByIhr;sB77Otwl#St)DeMyF9RG7RD){)4lnqa$qvBsk!*LvVNBkxw^d+EZ-Df zXM@O!G?)d>5kSo^BMj0OR-vJZZOin!BxmvML0G3;I;;x2$Acg5rJ|vn-JWXG=J+wB zLI&=1D0D(`5wRFh^IV*>y<*}M`oC~bYUL`i6{IK?HdZW{C{<-j1W>}i99Fe+HG`@Q z`@E&43#zg(y~*2&it?Ap&cH8W`Z5&~I^+N)ZwG_83mh{^e8*uhj9cMQ87FsyLb4DN zu&_ZCRuZ&j7S6u{pc^s4Zsc@oybwSvhg49=U_~xvndQqyIY!T1KG^6W@G5afhlTVn zDhHj7mRep_BD%h?IFL^XSYsJDL(CI43ue!#04Dq*>WZDx4&xUVto>Hg z?Z!GzzEYzosRDT&C<-WsMp`Y5KZiE+ix&%x=N(kj#{(DHVfK4T~ zMq>r32;40aTfqw?i*>ArF-cQk_ZM5ga#W$Bw}CMHHGc1Oih&%Do$2=xPv(jcya6gl zo|+IeNmp9wO*^Ya3}r;CwRLveIwOd<;*vofOwcxOgaomdly$_`t$TWiOM^)?n{0;& z(6h5P9F-!C62|9lTQ`x~)bE9Oj?`d`Y_f9FRX-Y$yb&Hy*AUdE(8W+g$R#yw0?MY~ zj`9){y>mU zJYxr1oYnVF!+q?4%=kMiR5tPX8@4}l9u~rfrA;LFU`I76;0p~6e}unT5oYPDpFBGbeepH6^1N&8jC}Ln%?^L@6D#nQjF)6S~u)!>*raVJFWw1Z?wQh6&kKKRr zMASF%i})k^y02?@{r6o;-yqwG0xY)_1LC=%t>9xB5ZVrU9qD1zE}VW;|E_(217Q z(Uud_3GeBmK0o@;ca9=R5B_M9m`DO#VzQ#43t&>|NL zC&;|DOjz#WBj+CRxG@7><+#UnD#S#}WgNhvl)WUpf~{pRH_JJVvR$0}5=3R#z{RmI z3|Wm~NL!-v0x3`u!-%ZHIj`s>EEUA%Gh+;x+wnKr8DyerL52_y8Dg=(YWl`F)x{kx z+`0rpE0s88wuD32NFp*5VM{|{2lp9rJT%c&W(mn14kB+zOrW`cq0Skqts4x#Ky1F(Z~nGXdOgFA*WkG2E%8CGGV5xh1gpAsk6?hMk-}3VkW`d;#y3s zjl6qAEUm3$&1+N>im|6uZLC$-p=i*E52RP2c6lbP=Ip8p44vuj<=k>aoUKGE2Y{%HiV&b{YusH(SFEvhia&ur zs)p@QO?odZQ&UaETs@R;6IiUTX&OX87S|F&2RCzTgB2OkXa?5vhEk1CzIq%hHxF?& zl4nR{MeD6YHB)pS)Gi==i>}c3b325$W(wBpsVOU-O2p&1_!CXQM_)k!-(>(ZfeFCr z&y&f&CNsb<6LfK(_?t-qha zgZcKzdY>pilH{-3pEySfSe##rQ|K&-UHmyXf*zYV7;zVfe0Ac-bk4HZTl6A{<6o#? z1K~I~*ybEu64tARD@QPBZa^ppxLa5~I)X4PSfG!vK88apg(ak~MG>%+bXC&H)+;Vz z&~Yp@J0m*zp9ADD!I<+n6a?T4AHHn^ey0pc2wsW0;_Wz+u(m6rLG_>?kl@`NGyq8$ zF^iS~0A;r;zHaEjO7Nz!B_5BTK5a|v`KoqTo#&mcg9)b1YH6@LZ!T2u8aO_g`{_BG zLM+pg!i{&8zc>>$<({^+_XX_NqK?&TZI*mM)HN7#q4R{$)PUB#d+DO8buyMWYIXvB zgJ-AlO#%pXCSA>2LwRS=lUmlFJ(O#THu(ej8?Nb`wI$-_2#r8bU(Ap&7#;;HR}&`( zst1<(0&aQ$_ZP0^m~cz+J6=`9%sqwNNU3>PWNHLBFoPGPPti5waizP*uybbMaqd~3 zUSTz!U0#mL{jt5)GkXU1X>+-RIVOhW=G%c&QhcV}E>^rmf1)|Y4{rvDd;H^ClCv;e z$%wovImce9Fos5;6|Bny!?0`tjw|jaM7&j5Sn)r$&h@9w`-gjAP(v#csg#VyG)vW#IB9N3Nu#JuqAjCD0SR)M z(y7%Z?cKKb{a1EA=l6tG(`+!okNr3ZiLbxsd@pT+kCTvF2cK>;c`nf7i>vt9q#)|# z4I#qU+vFsuq1ha}P4FbTX`lOs8h{TL=4^^(L9==2&#(ZWK2NipK9o(NCih|u0Z zUh_HRSY9W}?1%&2_66Yho4_}qtfqH-C!|;&-=5c?XSoSj4Hwr~)P;OCGL`3|#0Ae$Bx^!$HdeMV2sL-!WYQ8$#^+tDtY2 z%i(PCILMwPWm1j?Z{YEDxq?0-prN`!&4zA)52L&aaY*gIpsgySbyQ9GPtX-IWvEJf z6P^$?4Sp46>B!DwB}>F~SeB<`m4g=XlQkGAYJ#p`e>sHPx11;? zSA`=B;)W>rEn5n)mcOXLoUp1@c?97b#j@P^x08uvd7D{umG!Sx6WFd6i?j$QyXJxB zu7?87MN?IX^(QIRvW^E>Ko84L7n@`n7pNj6EsGXli%{qyJ%u%0&Vr6)@~E3&j)A%@yh2z#+$EomW== za_Q2gmzVCpe0l%M%lmSQs; zaB8|aIO86?&7v3NJ!xDUnuz=M{pV9>DKkXC-N=|%A%SX`1f zl-Q3v#GZR7EOF@yn2m5L81hj^_~y^q8~a}I-dFWVb{WI|*KPTgA;DX*sj=AdoaRny zJ&@7sUN*@RY77=YyVo;SpBoiy*}K{LcH_=^{it{C`GLsB+;Z#TBeyljqB-zk`;HxS z43>hZr(vP**|I2|8$Ujr-&$)fkM(Snr>>6feHNX$FtR>&_%TffO`)i#(?`CToBLum zdAd1y;O*Au-A#Y%^7QGJ0}VSTLj}-tyvo**){Rj)Ve2#3!QuY?3p1@dspYZpt?tpM zoA>0U?mfCUI(nzCGLl+9aANFEYUI)L{?yZVW*?8v?Y0`}dRAp!wi;S@*{>2cy6qxC zl{W9)Xq~yRw&9wJHFt8p=WCBn%x>M8THI{B)8}iBnv>aW#CuJKmMLqr<0yCA3)zP2 zYw2tDH{_3@lkHsx>s)9qs^!Tx*D=B|1S9eKDnn(@H;E2{7RsOf{c zP8yc04GkLZOo)bZUNw#Ccp7BYNr<|i;z>{y2|v~8|aB(ObQc< zl|ir7qr{k6V1~-EXpC?UuVC`xqBrJ+3kM>BNJJ4T&N9$@0UkdID8J0sUH^hV^nNT)E`YeY>F z)uA-5$B+O3AOJ~3K~$-f@MAeRq0yCs&fcg=!jkJd?VS_tCW<3Ulx2H#0w1vaGJUQe zo!Ua^(vkBq`Uvd^EZt~$Tp9@N(uyPqF)`7q#bO4nUBC`u$3)As`wg-wCbt8}qYkG{ z@DK0%EsvAcFby!iRSkTG`y$KoyFk_?sw^Z_p4F0|aVb=vJzIBbZ3Zf6~k|`R^u#W zM9(L*r$O;MSsRk8K(rjKch!(RllTnWGIvgB8Z?{UAr)dN1Pdr$6ilwu#$X1-@&(rs zBItTui;mLFr3cYfp|2VqGQpH`^1403M%jfaNoUboS2%Cbd7fc)g1xYS@el%P`N@h8 zi%PgT1L&LXqLM-0BNXS0h4JS9&|kUycK`Qh4FEs5bnXw|3ILz`@>5;@3h;uyPvpu7 z`uyJnfR`TZ*|X>U_y6(BN~MwhZbr~QDUG#vz*iKqp|4MXV8P!f4-5dG0)UMR3F*`u z``KCkdX?tWhkUs~q@7Xih zRQE{NOjJO!xw+GrE!>+8^QeiU zR2({ed)A>TmWLmE4tbtFb{u_oC$$mnvz|4ddm3wkT#v@%ThB5_8l(M#eFp;qq04{F zZmf^LyEUy?X!0?1!`e9E>rbWD+E1*94rLm?1ASdWgELc$j~;nC8*{1DoqWss^7xEU z-<>1BAK#hYs7!pYoSlkp@bgX2Y13iKbV2Y7)4&na>qHjxWmQ2NJu|EEz1;%weUZq~ z@y+RHfum#j*}igf`Ou!3gEN&KA<N6u|*zv^r0pqkK8nAB=ud`JcDA`}$IsD#VNq1hYC ze|urTl}fyz)ktiV3%&6U(7BR{GneiqiG$5AiO`vj0>y>QoGUra)yPr;{Bf4%!3-{> zY`ixY>lG-@aJVNI&YIGrOhyeznIDis3oM7jSvi=~&IVz*S94cm$f3hDH|Qjq)L8yZs{g_}+}Vjpni2(XFsUlgkoid4>1O((}cf_!1p&^52AlFH?fX5EEYg>7-fJtQ)AZc z@Ki1gi0G?yolcZB}(n+UhA76j40=l)Z2_^`J54f(oSH9qfcDd0D{woR! zFn%=}yjaX4!O5_H(h+>PH7H*!?t4newO7-X+WM5Yag_80L^LI6a-{DLVN_1umFhoq{Db#~&&~P`@zmMl<@VFZd|7(sTwU)Gb??W! z1|qNTs@CbswmueX7FqqyvNGEh0#NYhKG+0=Agtnc+}w-Dc`5x zVyk>)#BsbXPaxggy_{`yj`kiu=J@UE8H41xl8TAN&RRrSiRNJp-{b700!VXmhKTp> z8g{5x6M-}PrV+=vYxm;2NcBqXv0N=I3{s8pLOrq9V1#pvJBKq~seOqD^l<^gM8pl* zJEbAQ%nI52h}@v>#SDn(Mj|3y%(XX!eMK-AA?-+3K_9lEuR<6tbL<9OzabFZP!W__ z9@vOEGYj>;p|YD5H_JpUR+%RVXa}q1#juRiHZcBXftJYi@F2zmv{<$bC@#WMxFTfY z>ZD@XS04C}0L&(OG7}d!AcfKdkT!8cgT-Q64$9EMKo>hUz}WW6pkhW#gZ;WG2p_PC zn+Rb$qC48J!-+&t3>-$vh6#Bb=x8`%Vft(1Dh3FznsLp>sgrhOQ1Xl!NtKvP>zmd3 zx@Jy-J|b+uToNp|)v4tlPs)k!BAkPJlH`caQo~IIyV4OrDzRWFs?_SqamHr3G>yhA zS)(u4&;wv0A|Qn_%LSKjHN3rup_JF?(KlGFVQW&&xSB|;n(Ki%_i7x)3Q%M5PS}N| zaCLe4-&`)Nd0mL2Byh#3xmp5f?qDeA8##xAm&2!O{=fpR@&h4}9gcTEG3;v`WvZaJ zhXSr6sI1V0#LO6^muawyl~*Bd5Qp?x#lByKxS>P~hj58XME!8wJjX(dg>NY=!1ef0 z;z)W>U&yiOs2SY~LtQ)wBaL}y70f?^{9dq(4bB3KbwJ21C9K zP>T>UTZ#Q9I|+Lm)-ip?Aln?PY-j-1LJ1wCFJC)TQ?OSIrhPGAWvnx4O^Q0gHc(!o zzGEl_Zu6OwZd3qU&DM1{M$}-yV^-g~53XM;S12Xj9E(K{zfADm2{TgV*cdTzD?+pA zMa=wKNe+sRS&{t#{d6+ffPTVc3^j$Z&gIiTQ$gd3_vJhD^Z&VZJ{sM)czX%}OvnWA zg@B6qFG1*!0IaD?GZS>hZ4mDy2F$zT6~UiZfWL1|po!0> z*M!X&aQ!`ZAUPAFoPiKHeqw(9)r4e+!peDVYD$7%f#_hsD}qtKe#++s4t(o1{Lal? zdF2mCO~4`wi$7}P*)fzcaPzN#S%|D)`fb5aoI!bl)zLjwgueqENm+HGWfo~~gQePf z2>o$UF%jlbw30(O`Z@GU%js8O$o+_Lg;}^?i4n9Udv1NJknn_L3Fh%L*D;7~Fb=ow zsE5zh&H59JM8w*RqIcdavcWJY4P%q*pY0m%8|gi`AnRI12Vvybi~A={c|&;Tpkvmb zF~k@8{(Q8%yIZqEC=-sO#sNvv;ec@QNEL#Oxd!#7*J$*Qmal%(+da~yPGt$-vUlEd z4EHYYuxe?4vahdh({BjmL*>wPCFsCe*$&4#8eiv1(f=zI+X{z`i7o5HN5wa6s?{8i zb+?KRx|Catq>m#tn&d8ijmK?|AWUD?T6B+`;^B>=3_%1-Cq(C9yujPxLxLt8(rw7`@KNo4aQ+-atNo&u^r=89Qo?-r65JYHMq~UN3@Cn_3Pxd26rM zUhUyaQ=yD0+b*t0s`Ofc2W1 z>BgYNQxUW@+rfQp0Azcxx!L2<+nPOgo5^AV4nuf_skFteMo6X21U(ke)@IV%?AJMR zQmvo7jx{fDc)5`fT=s}<(l&|2$w|N|{K4o1W^~mv{G$CAoxVhcZ%oQLUs5y9<79+X zjuSpt>nG8@pqK0QlSsNE#*0NUY`xqrs0IbbK3EL|hG|FxqmhfA)1lj!pKr9S%{|&y>2{BC-yrc}Hu@&rXjK?nUkVRDdy%VX;wD_pdou+=O7N^*H}9<6r;D0?l2|>;Cv4zkd+=2D=kV)v zau)Qrch5(MmM%`eAON1Y|H<=D(&_1oOdNs6gua;I&RqC#Xz9sqV!%URJAYCRYy^w` z-;<>ab5}l{p8ER)M$iI&34Nda$oRYc;KRAK=@(OLL&(vBdx@KjzQD_W_b(#POSh*9 zy8*!IH)tv0B`<+jBodrXuSKKhH#Tl95d;3-=`YkFu?yHw0Q}Ln1^;kVFyI+J9k|5f zaDKv>OK&a=z-d8%i2)bf%JleGuk$wotbZ16BqU*t-htbw6-9)EzTC#pDiFDc1EB|c zi2PPb@z4VpLbs%p^u|_#19K7Ylx(&08S5#nS>MiY-7ghPdKx=c!D64 zb=G_Lh&N|4UV_P7E*|daFgA7=JG>dM_lHC_P}^~}wj)C@dAO;mrQ`4)2_?NEaZ++0 zA-Ss2c(`StX`l%$8ZE7?QKxexoYwrGt?T_s`_AJ9z7PRJ6aqo)P@sU~k6=!%BEmQE zi9TTKg*0bx=?=?9d$YS!)1a|xf85%}-mT8L($;3_nru$9>$MLqm+r|NYliL3Tuf%} zne>wVBlmi}KhW;Mp@3fnRNDCB^?tv83`*IQj1%H`2IJv)Jd??0!|7}$oetxpY&zak z&$s%P-KMdY-TE`VfxFc?}MyGSp zX)CiRr3NX=WUP=>BH?a1eJ;cbh1DravOG~{XVL9TD~~?SZXuz)+j>%GGt%_5M{X9? zhuGrF4CpD3XNG!Y@>l{iT||IM0BBPAk_LtVu|p#Rb7BKd4sfL8vHySTVAzc@en-Xu`+#g~(ld(|Av zYNXX$nn#8Udfql47@yhV^;up@zLir9}56i_rJBD z=r#XUGw9pbWDES==UZD3U$21id+)It>4K^OmP-kx>>v8TKXX%1mYSm`6qs$h<~oxkK!~Z0f`5{3BLcw-VbNnYu48b)gs*Xstt*9qTlnkntl3@zdh}r z-CUR3@p`kLj@JwQa_4t8-`>PO^DH$@lpCF(ni|(Bb`P}6UX^U}f;0?K%_YX!;neW& zKp#moL72fE1F2y^6~IvvKLde|<9)aYbc}*grep;yGB2D1fpZ;wc=G!CM$f7;i&6EY z3d`rOmKlso6nG{a&&0i1ioUb)YzF6aPg6@zPsBAbf#k2gPa)iL3jQB@8jVE0>gFc|6@DTltxw%2^# zXftv?EqGdF8M{$wl?~!eYLw1GPM`%unG9`|={3!}27?wMpVlOYgK8{8URoONCW^A} zHENDJ20n8L9V7S_hNEgxsldg)u;373yi5T9s?pTb= zUp5XFBhoPlvfQnT8Mp?PMg;&fuDT;JjRk};=2CW1=)3{u%NcYq;%7ExSB&%KSTEo= z=|sA`dxBo3Sz zdIk1;iP4kbx*R4`rDbQv6;QOmWpQ(%nP25Pcfoxsfn)(sY<;(@BGX7&MdRxKR3`AowZ z=1Dsx6&ml%hdy>!mIy`0vrsA^J;3TCW)Rrq9Bw=%D`7rJbh>TM!?E=?V=Oyy$JL}~Rrky>Wy-V7tt+@M z=f}*c)G3MbNKmCNS&*Jwzuf<>D*#R}-1zaIV8D;BJox@g!0&tSs`Hzx*Vh2xmoEXp#r`*~4!CINV{AVE z6oB~2gXQJL$;tWqV5s*WK72?+@7C5QTOVyL5`e$QcR0V#@w3uz&7LilsDl3V*2-6x zuK|E3S3VN*T!l*c=$^>Ah?)0f2P_Qu@|ER3&tJdwcU3<4hiVw*Y|RIJ{`{}#rFyJ( z!1t;%?dmH6LGmi9U#pFv!GFI41HOI>KlOb<@I9#to>f6uH4faq9{pfq`|3GKpd`#n z;1%UpgyD0XLaSzAW>=jB4Q4Q<*L(b`o8l_744cXrK2y9>In4hknZ=L?!cKkGw<0{mAAfA zO?kv=lrJ`@JyVkGa3%v9nGJ_C@p3p@#?O_F^B|t}W=ep&bUkpeWnm$Eyy~!3dg9aR zp0OtI&Jw#!5};Qn_b04Y17YliH$~WeXciFN)7}X5MQ${u|IP$9crcoLhG=pZ6qzyv?P+cdhT?(r3msmE*(t9LG z-N<%frbcT91=yT58}mO%QirC#K#NkH2(~m1tsTk^jH3yoA)*x{Dulzq(jzG(Ohg(f zie~i@Zb})JgVhQ&9*g+^vmuq6XNU`kF#h`4$JU5F87#}|=IG-?j z(qd@<^>seMJ(fR&adM zDN|+!ShhA4&YT4G{X+J_xN`xVx#72XjAM=TA4#&6fkDtjStD66{`J9n@0v~-3^oHk zVn>5iAQ{cJI@>8D*TD1w^F_U}PQ+I>vs;oWfw?MCo|#uH0zQS;{6<@d>=-C3P7LW| za|`p8A|x{_7R0oHKTl-D4CJtmyT_lofQ{hA$u)K>a4*b>G;ld*b%p3T8n@Cu9JN~Y zsWp(|wW&2p%*ut5qGV=8gS0S!A4esP!`kMF0=(HL7|rR{=riVCwMpUcYTNcS*Thl1 zE$aCnSJ(T~RGLPorDY3D$WVqxaX^M5Em#n<$#zM+yA%+qL z0TJs$77=NNRA;wh?39KuyI&SJyR)-Mqkxi$2@^lbFbSD2`&aC9&U*`HFQt9&?GKCM zJw4BJo^z~<=FZ5A1Q@g{M;%_z|^?99MRG!g$MT8NYnEO$Ara2aAu-7sf z3NiH8=X5%+18{vIpC^Pk!Ul&|*e+5CiK{|cLyHz4OgcgyD7>J6h81)OMQprUu%SUY zb|}!N{+iSmm1u`&62@Hu>Rth1Pr&Q&B0-|^;z1nYeg_vKtjN~N(4B77fEV@$csS3i z*zhG;Mtb|3=!h_2LClZ4N8*Ckqto|Rh3RSoNi2nrkE3u*xE%jh-s~s~)4JC~@Fz?%`7R?d8cfSv8$}-qzOi{KAJ#hff}EJ9_wg6uk`q z03ZNKL_t*Kherhg+hCY|{(K}NsOb{QdgXo8h5~LLuMnG|%n|jojTyMFc5Nej?-))Ew}8rDFHV_uv2W>ecr4tL>k@ z6O^P^=wIG&V`%l30OZypuGhDSk^kKQN^0ASjg9p;yAgShF1lg0XrgU34*YOyX(7Qa zo>++;e8r;CWlp3;lhGtL-pbx@liGw@I6O4OOPCj=ihQ+mW6d1n6X5ME5s?tA$LJF_6jK3(pTysd)5hEX0OIJrh9uW-z^rezn=V*>KRUxeUOz^b{B);8 zR3SRPs7==kY}Xq6bAW5ON!Hgun^iBId03fIA{e*^#b#l;H7Gonel=WPiWww<-*Ol~ z7c>1A-C;9)q2*#O&CW)v*le!H3@{qP%HRqVS-9$O9!HFd&85TT*|g}$gDqugo^tCb zEgi_lfG`*`oj8hx9G97yRfvcqL1F5(fUn@b2ns%9HWQ5H0#7X2KQh1!!!yL1W629CaxLI`BIwN-l zpsLEb3jCj~2%%M`SWrOwLQrP;eCPo?$$8N)w)D#?ib>zN+Oq zDD>XP;qLg@=$aB?HEVIg&7ZV^0e=&nx&uyob4csJUWI~rMCB;Ssc&Q|9F~(|7>-!c zXo`-c;VJBe8P_H2DLA)`@EGpLC3DN8_zsUG(*nTlpH^w?y;s$uIq_9d zHG4OQZCoL%emSF}t*a-aHT_Uv(8Gm87_fobXnIH*OpGJcDZfb!C4twrG7bq{TnJwc zC{OD!z%-AJvb)QmYX$!W9P8-nj5S-s5JfX>5Zz&&s#)h#aV^)a3{cX$X#!0m?B=sH z^GSE54zyP#AE7f`?ypthNP@V6x6nO<2@ASbBlx$r)?F&277V6IRc?kVwZMwV|epv#jb942jd29`1UqS{Wr{TcgEZi zYt7k^Sbc=#BQs4ovXO#x1~uq`0hFg14g8ctNdn6QAE3#A-wXpIv|95~fi^J%NhzOO zWy8?#JTMhWNphWUlKXRMN{MMUSsC*|fZ;qjFO;_xRs&f~J2fhQTZ|jgfq;QXw8p}x zeU-xiKMpwX6(L#haz~C;sBMRETh1iO2~6-8Lg^XM-@-tkD3HUWMKgf_s4uu}j?G?F z#0g);b8YGi&!>8><(k*cTrfST{&afxUk!mr3N{sz-X$z)o z1#N9PNaOYS>=w@?IVjN9VPi6aBNSvdLchv1vRD>FmWI%E!CZ?lV1O^}CqwX~^fZ7a zUv~=V3P4*dbjyMfhf_`e+EA#5D~Bpe<3-``(eL#I@xuU*C%rJI1mq%10)|-qbfiQg zqP(GC?eAv~au_lt=(DNkk-^t-_JAL)JsMkEdz^T-^7z@_-cmfBh%cqn=~&`fJh7DC zl)Z&`dT*)w>I=pZ z%9DHE)*%fECFt-pO3?exVfZ1(M)H?{$K;67-SJuH{W=mQRrUHX;NGGc+wN6{oi+ zgipQ}KDp%tP+ngrp(LN&he=diAMMTU$qnnSn`s0*Z*IK#`9@^$aQhX+4wa~2UvK3r|gDR+&S2919{&6T61=l9rkH5`L^{6O8r;>-7(?@ORWOA^r=Fy9jAXuw8EokT(H2M&5X z2@^+2ol;;+h_g$9JLvFGSE$7da$5?P5-P$H!tLQWPb3`ppF#VXXhF&a)bDFtz(6al zz^-BptR_FJ23in$B&JtU(x0;erBQ!od0G8Pe!2#s#95`l z{&!-2KBC%!B%h&}rcDmM!=ccKkX&Ln6nnvC|HvrgW(O`<>b(LolvVC=_OQG0n%GY1lKU=l3}|8zJN!)zO)UR*k=;5wDCyy zRTL-r+(v;#0*88h-Kya<0hI`#2ZkA_@e+gn%Ioy<#^3v?J8Y2xl;o&zT!OGrV}ZzF z1IPqn%^|mPy2;+a2`uP~^EWSt-K=%z=m9QUagwnt@0{GFWN;xruXE<){LGv%VbEFW z??Td2u(e3om@*p27QLXjhJNGKkq zytPoy3o0)ynGLWdlyyHF>BETwW-p9Ize&p5lluFGA3}Z*85~-j+>Utq!B_jk` zW`2DCTUEdZBCNG*Phr5#x`5iVCo8p{0B%=aal4(}-Xpo)dDPu)fy9q`9OzxTWTGe! z>GbUW7oT0d4+Gw)*KXaat=!t~w!7Wk)pny*-)(hw+k4%I^=_-tu088q5(cbIgmCC9 z-=#`eZAksi+O3t&%gt|!2{)j?2ek^ucJ!{DCw;juKWpvfcdLIe_9GNng2HkEfQ13; zkowk2^H9`$`7n!8Uweh~kbWgs!l|2tVv#xhu=?(eR;{-3u>s&Kvvv{(Y5p2lEcEbB z+upEE8bxG|ojW4aMOelr~RCDpaAI~SAw#&5RIbR!YM zp^238Wm09)NEb0HIn56E`=^cuVI4`r`X-msb_BnsM&Q4Oe)-#xn{SVg+aBN(b|lnE zxj*~wXT6>24c7Gzvp$(ZWPFQ zupxPZ2W<*xJtZemSV3Vq8e1h$>=R&(u$HrHUO2x!o7Qi_dBv)9mz%J1oIYHCnU659YaGEBhM2vOuazcY9 zqY1Xd0?Zhagx{)2I*TWGg6ONPoTd`2Og84v2*phcU@~ydCZZ#EW3f<7jlcfo?8qRE zgfS`?XbX;226af;F%k5l<<|`+?RJqGFa$qB+LKDua`ni=`xa zv~oVAE8~!Sg9Zi~lh_%9%?6)GE0eS&y@cd>z$tIk?gfGZx%cEPoYN3tc|RqvD`eQ| zLTRPhS1f=%&|8nTBRPHMm`|G;7(k=y^l4e4>PtMI!gf(c69eRN(?{+$dGt=R1V;QE zck851x4vjaX@|)RM0-JEuQ$A)ifB23?5pIwoH~;XC#`v$NJ)@7DKBxi=`Caj3>wQ< z!}D^sK&&Mv;XJx6WOqRxGmobzZ<&v{cLBqZm0vI8J4#whmi2gMDM{MZ!c07$5~`Vh zoG&jxb@S!?%zBcDDWW%+QJ2eQ*scl7C=kbyN1)7_HiEV}RaneV={HhfFGP1nZWgCu zyo(^~6c^Gtv@=)$xIpWXN}s{fDZMwX?ZRY0r`Bi6nmjG!I8v}QrUMljsgpD70@UUF z6i~dRf-oy$6>Sytouf{qb843hX8CZa^E;Jd&-EgV8ENT6`_!|?RvYjBaFJ+Z8v(m?Y7)o?e^+z9YHGr z#*6gEnfDQ4eGLFt+vHWrW4qg{jZUM!+ilbzbQ+CDr~9DO>vcQAteUM(>tP>a)oMRk zd9rbN<1fTtov|AU$;A52xwSR31Fk>$odEFBF2u`6E(bXs2az6!-ATfLKVD%3z47JS z8oi-?gov>)l#Y+zNxhoMzo!mhMcC7)v9YLF_Z&qG7wAF~ZjAd^!B;oK@84vy;~Vzs z+tP4c3m8yByXWF8gw>f8cgrukbC@;;p~ms>+(6jt9*}Ro_sOYmC1Kf%;B$w3_ox_4 z8-Y(9`&;GBUuADzxyT~)qK0Q&RH4vGf#5S=|54D@02sB)8`t4|5WwpM2CWv;35oLm^N>lK*r|vLs~39;j^z8LBFoq z*R!)154)De$3OYd{J)t?b9?*2_V#vzzOK(7e7;#%;lZX#4s4y??~U|+wYIss`k>LN z+7A{0uU20?Uwi8nm5ymb=Lzgy<90>xeQZb!nMuDwF%^XR;`nvw_}LNsG#C(m!|N^E zU$U|sri?*ovfjlU9CWb=c1;khL6&6>r-~yOJgZMgx3CVV17~SDQrnV2dayr7fQK9s zz~6%LCQ1V?9_`TR=VGuZu_BqveTo zaiVDQHxk(dOqucpQn4mRGOzd$!62J>~dxzru_FV+hKB^F$8DGcuxN# zi`Qs5niZ6lgLDEL*;OVx0^?;mjs7Z%V>ss5JPyLJ1a@QT5r1r1o&~itGiqvq1*HAR zt_Il*VV7$HuixUf;I7($uxn_+@4qC(U4|$Ac?L_ zvLmL9!69&~4OsGzB>(&f<{eH4WrPDBUwFXhAf7|V&;bzFr^lVhwG7m9M1uZ7NBkyH6 zZOzP+Fqup)*G3{iWn!lB;!so`Jp;MkOmU zWtEo-GX=u16msouLE*d5+NtTqnMI+%IE@N$;i>7=k}iKg66}^DLk3k) zE+mdaLcPlN8Uv{nEmGB7wyG@yjfN?js2xBIOQv&KLEu8x+|8H=JM!o)P+vTD^kRG4KlTPN5gSM)WE{49^a11z0>Jogw_*2!Yf`zygd>0}UtD;4 zT~5$r^Z^gbb)@Y}Y=DI$Uwhg)P|q^Lmmv2z7R%cIvK@(QV0kz2S?M3%YrQebH7%=; zxUW@RL8Ah|vDw!xU|r(ib?GIx8RJG22NdI+BS5R6@R|JPk5e-<^=;i;t_r;0v3hVn z7Y2MZ6b5PvMsBR7o@A_fG)K}F4`vVKv%-tVQ?Hz=c+5_vrtUlPN4yRIR`4q)rLweV zZ?7k|6A;U(4Z#NDF5v5NFuM545Foc(5ny%`TA`F5epJ%$ zKm;UHjXY704Gv$2CM=Z^lGx@J@ePtVG;K9%honklL?s8(aQXs4L)iBs5eo^HG$(-+ zdx{)UEr8ZRJIWQWCsJyzetD1nKka3GL#D{ zSXLR(LCB-sC?OPp6?A@ISTWp4?n(jOno^waK1ppf1kW{sySQ6QZjbNLl*o*`L8=q+z`5k$+r|0|{7i z#b)#LyMV+{I=hO?@ji+HG>p9tL0V)`+7!Urpo)eG*hVc@2^U`FGzcRoy8KIA{(D`F zn}l<(GKNEFFETYCboP%luJ}i4Q8b8fs}&){$juUVDq98CqQ8@4DhrzV&4Qp|#aYAf z7d4~&7i|n(=v?UPLLPK)bH^B`(;dER!fb`{BBLXWph{uOK0b;e9GFqd2_3cM#?4Si zk73)~+vW33c7!K4A%ga!3ZjRX1;XQdoX~7HBa(6~^1Gk#0iVbC7%J#@H%!w=0NC=w z!-a!_Stz_S982#X6bjGeKzdiG@WSw{nSS=p)#on{v8^oV9|~(6LF>A3=(wIt>Sh7d zH<#4c3+er|nK8G80%xvX{n{eV`1$zKp4tH~q|)ddMhjvxmo{=l-W{-KGbf0fPv}M= zxtvcXcFeqK=5uL%UjTUNJFb4Y0>%jX`sn!3%+w~5ur?ClF!8wj5(r<8yHe__xIfUVj#^NtO_&(S9G5LlNZTv^3Ct91@A3!c?U6ihNRFoDF06e(Nu`H zs)eDJcLJGV;k*45;M;i!zV-jV09Hqiv!E}$hMn-=O5YR!ZdY{yO?Bg{25G#Gg@oVa zUnjb9qDpNWdnp7eIb`4$1yk2d3M4ZXvl!#-+{Wx${_FOsnN#(ryOnTRnQyT6{P*q# zFi@>)Q$Wj`M}{u|m@Yt>i2)=@j%S4df3qiKy7O18E<&-rFxK|x8`i{Gt_s$+m$#Sa zEiQTliJu-pBMBOxzcvRvWW`_!Dc>hppHp#s5kODTdo5qNp~ z2!L;XdhCNc{5*11DFAF_t*^uao22*K7vCDFqtv=dRTHxPa9obm-Mw9+6(hm7$klIS z9#*lCS=1oW&I>1zBg#dr@YjC=d_9~f+nMJ~5VqUNmI2fPosMDzWx4EF?8?h=2<(>~ z3_^4Px*E(*5y4*Ek8g0dcAwva_5>#Bi$N@yq!2^_C# zLW@0uvy6ZaL^S(qAYcz*Jsi;*S|TB)Oh%}6ZV^@-p#=%`MlCfFAZ$=>BeWwBXsxM% z@u)?R_#{dRgRP*!SOTL33HJplf)1W+ZIDy%5p)G{?*W1>%~k7(KeGQ<&O|pu5Jq7) z$SxwC-9e12fz!}n36j>7F^YqsS*-kh-!0IK&O($k2;2(CExliPg6b(jLjgnK$AC=K zA0bx@%4(ItQ93;>2kw_m%Lir3-%IDNJPHXNXK6vgj<~dX`VqQ~a6;Lu)oz4dmHn0| zOK5ge=Uj$8FisZgi|$|{zYK;3uf|rmvJyLBM^RBfWOl_59JXkGKXwWZ`pGd}W-F2$ z7a)#8Y=wodEh?-RxmTD&BPEMx*|09Qm6sGd{U|ieSIM%b}?|~cXG89DXr_v@tt@)o7I;K2Jq8}Cktj`zmQu_ zo9VT87q*mui@$%pcg_Of4MUI53vz!Ek0%Q9S`F+r^qe3G^LUs503ZNKL_t)ou;^_e z(&_D-Ag|zPGM6v}nDw1sTwVJ9qVgYc0?jb2wwak1sAWpY^Wg>ci-!;OtRQ+)*Ntp? zKA+stg`4Zbqj!uvK7r8wtTCU@Ez2ib*OS?VTtILK{6ZKnQ=prgu8$MQ#t}u?^>$$M zhH%?9OrQstbtT*v?=4CUNwo4Ku^tK897CsXILmQK>1sr>8-$7F-W5!NyzCnx2X?VG zTTP>_7`YO#<`UOOPZiZ2uwtK&Iq>1l!$6KBK(6>~`px%RZuH%OIJc@>Nrk!(9lPH@ z!zP@qk>)^vg6o|!zt!83s0?b+Q+MlrlzBF{Y>aZK(N>kNc=LTor&>Js3QPk98 zrbnRoEz`wmD0_%xmTdyNC7Oz<5%jtGp*Iebu=-RObk&tBfB%>~nIO7gF<^@V&mSg+ zKYUp+&o~(NfFu%$^-PSt(M0gs*zSK8Pn~~*KI6Wox<0Epi8AQEzub1&s9pAG4h@Ns z%zQ@r21qK*o+t~3c1E*1idd}x%@!(=(7OQrw7l**&>#rf8x`OcWTk`)u7lhEEQv!7k8&YtRw548nn;>A-!5_gbQIoSC%!jhU7MKu_A(|*Z>O@w?v@F`X5_Y`_tBaM(Y=lU%Civ z*^12KIhb-U)UZfRf`Qx4ioZ~4OQuDUoJFz7T*YK&O+b-B7I3dfKuT1H)`61bRs*&g zr$VTzs>PkwMZu`)(58Jzt9@FP57GXQJ?H#PUZf@@#`ev{AjrArdCrR*h!TcwrcW~S zxi>0YSe}Rq64Uo9a4hf1eH91YhYV;$a`erhp#fkHcfpm!CM1u82n_C< zYw^(hi&#pR>l+_j!7a#%ZaRXI$bq{-7aM|ooVvM!avOZeAZYGy9*R%o`b7#xtxN0syFY(7k< zz``|c67|7fP09s8SReYykJJ(V2kezeSj+W_aNym#KycZvH}>qkI_~W5ZaomLvQ@1< zcu-rYJ*d_$UVQjG3z}J2U5|e;ef5WD!hqoe1_ayIqinWr)pyJG-Rw=%-jFlZvTK%I zuU$kL1A{05!N+!fHhuN$trMk%8louW|9tF_*UQ(e3OI0OzATplPAw=7o;B=8C*vWQ`1ggr?k*S+xBg+iVXVAA^_DLznzuWI`$# zT~PUhKMg7Y)(fQ-yB7}b1M-pP4)_RTIM@gLg&%E56Fpt5@9kn*2E#K1I48cZPN{({ zkZAkXOW4Nh$R|zY5qddmnU93`acqmdFb2F&gPU{Y0KstZa-d~<3_81QF{)2Gk;R24O;Vx^BBE~_E6yv;3dz5vE+&tIiFVY8)U zmRAV?;1YjNP5r*Q_us|ocORd5n=#WYGE#QnuAYByy#V0m2>Q`W40!&|{s>xq5uPZV z2ho!Ih!L*&i5n6BYyS1p8i`q%BNxgiHIbch{F_?2UyZ#!hw zy(*)UQCY&aKhB}^*Wq$}vsLHA&6rlaT=YK)CAnvNjd z^0S;lo{G_J1Y8#Qj0C`g8O8ydQB25iET*!pIs`^zY-teYIsir13Wm%WMI((8h>HA4 zbOA%)94MYe^fN1wI${H7u_MOT82XoX_RV9bgZk(}`LS z_=1sV+9J1T8Km*Z;R4{2^g7W33}3J>i09bLAgJn8<7UCwcreJ(o6ARj8)OFqgRwA| z6Hbe}N`^HWS_;BZq=&qt*z{_82Gi$!JSZ3|v^bL&fX?gQC4@U0LXqR~{HVNv1CK(M z6))%+)HGE`gDAl}sQA3nUdz zB=~>@XmN}jWsnxDQicT5DG_%?_fZ(-g=wyM(L@*~slLJxOGDs3VN7c20_4*|fFXMp z2%Zd28VK-$WV-)HcEHCEKQCht04`VRTfpEw8^5fEUEkUT^wO63fL7q;T1jO=D;qFq z=gC7mzk&}~XlzN)O&FwUT9s_JJa5Tamb2$ft6`e8eCHO1={Po0y>OmS; zjYzB`9KJa=w(yq8jWV*Vug#Y2Spi|o5*}O;PHnGmV4vKu!Ol12GnK~$<;}+ChFMvw zH!O&^=KeJ?(JW#ZXB#kSUeCS6A9{`JgTG_l@0s%>2Qg*lyR;mkkB|vjgCnR*XpW-? z4`26YGCm0SvHYbQiOd(@?f9;S1+T@2{y_?)TXs;x_hoy~=rX zP{kL&a3RTir{6gLmyQ$f_y6&@LR^64hpMUvTA}gptAbR7)P=dy-A8v`8t*E=1jLc~ z3GA4h8>`*tT&Y(5_UYB>oyYGq)1`2Fvh1F}eM$j4LH*|TwU_bt2~LJFE=I*dA-Qv& z`XvE)=ip(2m|X4vzK;KcKCDBJdnm#8@Kmv{Epvlu}`)vP4g!hrv`xVUrV z7_K_H#u-kfswf12tF-;X4JB6<+t2a$k=iZ4%Co*da(jko=!O2qom=Iw znoUM@3Ljv~B(z$qR5&A0S}<2At_NdkLGoNqiLvCNZZcs92h6I<0hVC!Xn7g|Td=;QA0Aw*Ah_gWhh6h>f#L3alHQI*SqU9gbm6}g>(UdtavK$bt|pDDIN9F4%M2znKS z0duh%fj0@s%$-F)`+^~urUDDG&Vd2MO9uk}VgLlVRZuk`7`f810s|7e81NU}NX6C; zPMRUELOW7h2g4?d6gvmt8fN51;Ov0vY#3>69(LP}s(Hw*>47y`?q@c$yKgYi>3OBpogUl~S17lI06n&!Q9I(hjr zxbJY9ejM?XQHfuJ7jxWo7yJ4GC za*MN1WzPZRP5H09h<)Tf3D8%r_KA0;x)z=jwOWc88N$1VuKBi zu{zBe#38BG>|&E5;06h;3bI8slBH@0Ll{}cj}wPTc(pSe19808xGOj*vZg9(U1?*X zOPjRQlnW;9YT8Y;|6}KTe-AHNLhu8|4|#F?dCvFcoR>K$;9Op{l(Wm9WgjkUm29P$ zfq>SsT2sSq9z@PpNM#ba34L7Lt^5tby1F#fk# z0OF4xoja!|5cVG?9`)-VDZzVKdR7_1_>#%b?Z5e8=;P~y3;-Iu+O0-`dB{JCC}1_| zoKBYtha*P^dUTb-o0N@7x2=RAQ@X%EDs8`9Te$b^#g#rfKuL{PIU#qydj3;RPKgdp zH?mJ(m%s{@YK$0|OhBrZpL3=7>vI>y)KXEbd+ocDnttZWPl;qaVdj1G8$EccqBVGp zu#D%*7EW2+s#eQ&0q~!BiSVRvTq2JK53M+XN-E%VVh2~6)w-0Rb^Uv&vy~6|>j+lj zn*@f?PM5ULGEzy;)xZDG!Y|KU;OO(A#kPbbzt3;>=tHN`D6gi531I2I$>*(-J(bwY$be|?5hNDM4G@*K{MjkYy+ol0C>wL&>m3+R~&g}F_~Uj zGx1jCUfIgI=a$V@R<*zN(I=~gR@AMccH1Kx8`AcbIjs#FWN;vEi}*q|MlcxSA@2Xi zdssiVGQPn)%(<&|W*#v?*z8W}L(kki0t#sq z&Gldg5kdybqRd^1?ClUk%1=2I{YE>-_T-Xn(?F>U=o*zBB@54zNoX<{ZIHHYf90Z) zu^r@fw2Kc17m!ZT{#oJ)PqhJ`5XH`xDVctfgO>4Dn@O`)b>uWD{{_@?~{vT5T zm)Qf>G#o%lsr!Dj3)rPiQDK;y`s+P?ZE6qv`L@wf+6f=7nTsKsj+Fqeq zN$6IT(gCIlmef75*Ptq6n{aP3m1>rUcWGvg_hq>A6ff zEHSSbOwx1`m!h+>6l^hZ0f}3`Z8E3DCX5$)c#8j1OeW{ePbQTU^wFa4aqm|G82XRG zfoYIMB47F3{O$*lyR1G-lzg|I7q4oucU1{G$5G&1sc?chs=s=0JbWZ{BQ&{%n@$36 z+yj2A>$LQ3`_zgt2Y>rs?LvkoO65`=XDz>8f!E+o&fKTg_&%*2v`=`-P({tK-S2gM+7sWpbU28YF2VpIy$>2;eGvz(46atFAhj zzeJ;t@$L&($6x)C0N#JNoGF&lD-ET7*#JK3G#{Ce>wgP+16ypvwQ6pql;6t~wmEd2 z_~F*Qw|;j~IgwmdreIu0l8XPM^CrHALh~Bs1r!RH;H7!S4C{n1YWSAj=5`;Wh&N=~ zDuNGN7=>hzjxr~#;v$OU8?7X6oPN(XmbLNWhOL!eSP_U^rHkVMzQau%pk?V9OvZ7m zFBE57a3DmRjW~pEDB>Anjhe8f4W%a({)Pu(Vi#-;$UK&cS_nZ6_sAp`JHyN^1bE3= zj$W}49hOFM55Vhz=;i7!Rj|lox(*XqT}ocu(EaC*@?+zWmWTj`U()hE(6O7 zlT@RJWmKz!JHl@mW+eOwQg;GRi3yHC1FZ%%Er2J6(P)^Mz(M;d!={PB3oT+CZG;x4 zJqK@$Z4QIc$zTSD@}lHK762^y=6_q@@&a>z8`-jal#x zbPIOQa>d6F2^y55^=jvcv}0)vO+PHqFZxxda(E_1p@HWw30&v6_sgTXk+~q3f0-0~ z^D!ZPiAIw_rZBLqEmi3#hoEuC4f0s_jYeh1h|bTnryK#Q=Y#%ve#78nCO`z~BGMV0 z=M@CSa6peE96OW)6(zl(p@8#E`~ZYFzWjXwILbG7YkvTIYujJax}p5@vH)0L z0ak{RV}qQe{;v#S6}5fJUoIellsbSRT6e+TT5-F$%^t8gM+$$hpZWTQ>;Wg!iM$ZF znXeQw6eJ)p7|X}zi#xUAPH}g;+Nf?<@m4RDnDbChuO$EZGc|=JhFG!){EMZfmue5V zaAz4Oxl;g!3)9nJdZyW&o^E6^_)}ivZIfa;2mPCGR^Q9k{w?0q!jhbiRVeN=1~3{63ZYf!d(~cI^{VoS)1bgW^u%fyy%o6 zECw=A_F#_$)t@BTJ)dyKQn zeQG-Bs!C@91>k{EHkT3A|o`)nU=uj!64KK?K9@*W)j z`!>{hVt-Euu+HB*Cq}T27LX29K|p;EmC048Ce!u8az+Dyb2;{apFQbQX%un^fnOXI zU{>;@4=uK~78-0odV-}BHhOBb&qNq9N8#EwLz`bF6tTlgL#qg=y2-LKaoKJZhe zczpD}3V*}=g*f8}8L|)xar#PxGVbN@GLBsm!T=3B#GFA^q^;mI1S=p6#mlO6in^Hc zHs!$^6>y3hzh>G}QU`m)L_;DOSc`V2Qb0Ml>2XPSml+KySFejNq4|wcsk5nW&}pirj2Th{Bqxnxa*jdQqttx!Yf{=lT9j5;T&4 z-*FOjKIi$qJdZ5-0$&7+c8I;Xb9UX$k#ctnVF*%WQuh#gD^17n8E0>|rPd z(;C|1;*SoK7fhBY>lIYBt-5SDd(;sC~r&n)PQ+JG;#^!7?-Omt0oagBBcId^TzL z(vAblSdKjP61cz~m`Cz|*%zZFA2clM%s5B^xgarvkfdeommCJVO)?pH)aMVzxO60r zlajOG@G)o*JdW!!a|KQ8-`SBVt(Z@bbDP*$HG)Y!BE!y*$#GpbB8Cq#*Pqmbaa~J- z-$tCdLM%2z-1P!x1XlXyX$FP;>} zCYX*C&~&0!GeBE@TYTWmBAL`!E>DJn2`v!_2CcsU4M6h0`}{~6u;BAV$A#;%2Mhq` z0APw&()R^>!26|FdpT&}&r}mwSqi>O0H1$bMW3XZ$Il#P27pVf5<@^|vedx&>>_Ug zL&4wOLV33`ElyaR!oruUbi!Kx@v~DYDAp2w355mSI3i{CBa#p4f%}{!8KF#8$4bS1w#|+;P-@)M1O@MAK1^D?ST>TTf3o4=p&D5GDcIf?%d3Iq=)< z`{FBlaD)$iC*N3Jsa2%YO|Q+cYFoe^P2q1EKKP{V%d0>eS8R_@Nf%fgBS54Z8{kwK z|0@rHp}D+@s5r#Vn=vejt5|%p&8qEUwp1vtPyqwLkDqq@wOvMw#o+Py49z&8fKyP@ z^NYFS%EH!>3iQ8gA&~j)6qG9Pw^yZD-hFwn{P?5riR03!o{`9i&2K9!MM%{7(ne~b z`gUXX{?T)UL;lKqbrt6k8R*(F-r^qxz)ugtXJxdDZdhyhPlP^gKlz;~;QY-+0GNEo z`JyU8;~PCWv?e_?DOG#Md5MeWqY7mJc#Z%r(`ux${vQIkR#(7T$l44A@Dzpc)aDfn z=aOk7iNmPXjDuxVqzoek>7l{-=tdlDqbgd#B-R_xaa%p`34P2ltf;`#%C#i>ps3|Z zmt+a!299Cz;ZZ)sE?wSew3FdSjU%pm*2Z-yVh^s1$|jX3O`X=my0+OhDGt!4PO4$< z2Gi^VI=I_9$rdozfSJ%h?TbrR1`^U7T6ThIz%fY*cXbYSuCGHQ(-)d43|+DXe5VUM zZlecuTQ~9C)^n$uyzR!Vj5?C}=-$pwE++NL1T;5*dwTEO=>=b96IjeRXr7gZ29|y= zoi@1p>-ByLnzlLHz*3+%?R56GamlwOjr-GW>De|F2HfIIx79h1dFy097(7h_rY#a! zC{xkmhINdFk{oarXG%I}&9*+c>lE^Wz^!}=hokG5{!4dBC6Di_h2R#BP1iA)VGN{g z7<(WqNiBV2O7Hf`j;|y%@Dm%(5Wh5rZlLic=b^=j1F9LsW;yyDSM(lFt0e9Ul2%1A zxJ-6gKf*ODL@*gD&Q~~2m?V?|;+8|w7Rx^f=`h4O001BWNklieb~}zMvUg;m>41&fN*1>SuZageHGzYUR&I`j$|@2I&!c|OSBJv&sNrW& zH{ytpzpF85-54kvaroT+hzD1hIT+WOjO6e;;>`T@fRoh35rex%x-X`Ce5>?}4*DW7 zyow_>s>cHUxZ#16rI1a6Tt2P`CxPrFuIrK}I2wjBlTxdz5{Rel4{e?zvY*KZ(2V5c=F53oXDkFQ~U9=!)wE9bk4xv;w6M&G5`0) zELkZ%;MZN?*E3ksV5PjwP_`CsQns$ly{nwCE?nT`6v-6)*sttFBN1zdX41_!k`~hLxMN)EGX0F*gT{-<*F^O)XUqcZpRET4<|+qVLzT zGz6CU+*WF(n3>N4z);~2zx~&>NIyLUfY0Rcm!bkLZpq5?mY9Ty z&(=n9gLxma7tJ)J;u(5ziEXL)Q!g#dU`NN=GWwh~2!-xFm{O)*A;+BQkEq*=Cp6bhuPIIBJr1 zt&8L}iyJia>KdOn^5vQAFc^)FkjZTJ4yybGcAc&AoaZLtG)Ji$#cG;wh+9WileLE& zh6H8;5*<9aTx>FNsEUesaMEREIl8NRP@)-da}SHw^rGw*`;EaaPFis%n1ff8wmm&W zYFDrIP7ha%dH`QMPA+hrmqXD+GtDNufoVXPURh4S*-H}+Z}+E82?cKUaz@MBtjsx@ zo!)dhO^1!C92bxFg0R0lIy7Fyt@Sf7#5fYjrXwnC0eUvVTNt z$yw#%fjfy?W;k#ixS_9=3~wE4?W=2HJj2-RvDt=(x)wDb&Em7#NdkbuRnt8&^fuGK zj94|}hlDk0+KIdB#nQ@7^*dsBD{Tz*YqyNB{%oQB2FufS@Rp!v&lm?22dA@SB#R|z zs^3wDp3=0EonH!JGfw^M#hB0Si%4v_jV_e3t>kd)4)LfIMa&j3ZLn5x6JQ*3=!U~* z_*Q|`xL=GnIH466Y3$I!Y!BtIPmirawE9OG0?f2R|EfbG7!0oe`o#WOj{(liEtIA* z;O7te^?(k+%j&Zcp)xi!M<^J<1-}?y;VA(z#RBiNIF+dp58l?KKCH%+{RycROVR?U zstwWTs(*+OrtS^Ul7l|b+K{+z0He1#e}%jGDFo51X^*%H94BfyrbXvVF_k8MhvJ4T zDFL^vH-`v)>SNZZfoUy7Bg(j#b{NL(&fjky`bVlPBbkDx6_vyhR`)1<_krDsxo59l zJ=+5;cVA>mub%CuHgNqJE>s|g#R=;O#McP%pLUBlJQemRVmSs4istv{A!GL;sXZwoXkFl&xM;rxsLzx7URC$ z?ucZ4iPr{;%Un6KNlDtl1%Zgo&T0>r^Q1a$rv~w7V= zxzG1G=Q+f_NSiULey!W&LkG{6BB5#Vd`d+=ptWdqa!>8QT zx9j91sp3lC4!C%4X`uAA>fQR zCw7slP#~YsZYNwL)0K}E6mW+M#0)#tAPWv1^Lg_Hr-=X-2$mlf zGs(aCjXVPB*oG7JRm_)3`BaM)OCikyj$;{LJ{ED3gp|yul2GEFR63uJ$Q~!Cy1@`q zk7f;~fokmuYkX3QAfyN+IGv8Q2)t?}12_!uBEL$8(vjZ?QBKCvEyM*U;k(UALFNvO zHs+W=BA!98v^f+q2GA6sBW4~+@HGNhKO}G~g<5N>CD6 zz?e?9ggQT^D=Y`$&OtC?r}E=gO4I(1Fm_kSsQh7V=Z2f*Va-Zg!&I+Z*GJeP1iDW_ zxKDLnom7^?og;o>xY$=}8gOfP9pRNV0ZbcsrWN=WV%+&Xnif9wm2`M*xVSKPC|fG(T!X-F)>lhMQQXZ zG?Ujr+c!IrZ7cT1$s9BiD{}62`uBQP@VQr&(7F8_s;D^rR5`^#Ms=t5g%bA?CJ5a< zgMbQ`D}%fJ{a4Ni@}kI6firrlGxUVd^&2LPpR{(1$&W{JO#3XSz+`}#YS%ZpApB;KF~Sf?b8Clf__zm!>gl< zcaP`q9v)Uk>o1-iK6>>I?1b_gYW$G%jsL7=yFXlu6n!xhvj6# zhlEki1Hkg}V5ecmkN`|oL4)0&JdlfF16W)IF{@@8$pEHosjWN!f@`3qx*M7zbV&es z`4g-1EEs%A3Gm>+)uq1+evYrL96`lR8GKmiB?}-;zw?apQ*- zaLCfKNXaKbAxLN9&D))boEYo^-!=|2S z{HD59>B%m2-@09@9LzI1wxz?uL_3tM0ESXYO)RYxBOQ!dtXL_5i;bhQko7eTKA!$d z0GKZIpt@9bDKAy2*jEqau#zxf>gkJSBzV!9v8ot{4IH>;Nx%eSjVpEObZMz)L$)tb4mi>M;pJiEG=+krpy9s4Kk4&gE9nw$lhN<& z!i4d7Mui0e7M=gk>B%HfjIDi{;upex`HWgqKju6P1?Qb~nVrtOH}A{aGG2%;@xvKk%;`%(eSHK5 zXL^#12B&c0=%HQg%UiA-^1%FUHQ;~}-_9gsJ+Z$gW4Ki2i9HgSO{F3sITAOkSaS^j zXH?IaPr`Lmp^kJ%golKb8MBk1B=xuwn4O~+%wUnw-bgysk?crD=GH^PgoV(CA~PM$ zb0L*ng<9zPhWvPP_*+`$NNX$mv=V8MEUWg>xF1=js|ZS<{ETsGua@YLTo)2dMo;TilV1z-IF z&EY=!!K!}7#d4%|1~cif4gu2>CJ)%V$&2bOu(skgm$y)peEWs5d`57ETb9NTGHK*- zp~BK^LN?hwb~vxVu-s9Hcz_2gL3kaMwfRKY|`9_Osu@M~>ZtGTpo6uk+@&@B$0l54JMQV`%@$j@-Tveb7MtKJ&G6O`%yt&xNkJRAJ57W#a=Yg0?apXsGOKkf2^$B z)n2T+aa@_oX(*8Z;)LuFTDspG7v6gA$~nPcp~zRLMw>|_gjVD-2m}i>GYZ^xSvAfS zq&1Ha(%c5|ZRllB+J1#_c)RYYe7)v&I3s7gsJ>PiR)5Aodh75pnhH$n{Q5 zv^jrr>woIcsGv_h(K%pELpm;(kIU8aLH+pnxO)G%HokIK4LN=>jwGSb zbHJ}RfxF}!)Bgs5XKQy?Re7~go1!LsPau#_i!iHB@R}O1CdxGBEyIY2_3Irbz1Y22L{+uj^Nizd%(vW_5 zRT;3H4^6e!pS7Wk%@+7806c$)u*)#u13BH=R^w$3yGfXB5WH0Rda!%a($r9d?m}tQ z-Sy$QA7tDgVSm-GM$ZF3SLY3l14i?VBHDnjPAQpy;PyA(M@Z+l z8*qCtpD_zg6=<0*usX8_5n(C*nuhP|daGAp+}{3r7$IXwpZERvSFw*K2fHtJ-R!z} zv8#*V1R@!*Z~pdAv$F?ER<}x(Qho1erG}&O9+(N=B%(l2Q&uST`tCMq&3l5YwS(Ep ztOD@T*?|v!BxhF1ujO*l{mmm~z<;R%o#aqf=#-k-T+45IS(ZknBYAcAUIOs+m+yT1 zrUhWA-MVhQIKAAMm#0>vqGB=AibY8wsms61F_BT1QA_XjP|5MuWq| z2MYt1S9jA@pzJYZ*9e9ol|_?E=pwmt$m8-lHf2pGsOz=6HU)p}4vj~03=KI7R)5$t zL@*(-3;1CLnp6VqFpaGyYxoH9C#=^KK%@m3b`J+Mav=~b2BLB;B51+w4vZ0a6!Z`S z>}pSJEZj2Gh|Y&I)~VO3C27AQ8zA*sTIW1z9> zT|~PWk+w)wS&$5$|UNE~ZBKIv?;GNfHZa&H(R+mfd0MWt1{ zn!1Z=|Ht0X`!$e@nqd4pQLy}+=Y5|aIDsiwh%^De3Dj6Vx(FY@Wr??<3n`)EEIDtM z3!$)Y5Yclaoam4j5ERGPn+p4;!_$$_bYfaidpd!6mY$?^RI7o*Y+u7#S%?6cpsY`) z8ScW4lbC>zMWvJ6Ni!kENYT)AG?`3m4dG03MtE(K+>Mw5a11UysMBWV%}GtBj3owU z2%rS8fn!o6qcd6!tVvljNu6oOs4t9a%fePVt$aI{2$@vOL|7w0ggpy2pTrvlEe{WR zfAjRHK;bZm<5%o}i}TAYT;!zo3FT|JKU7bI1^STpLHgdzj;)ZfC&iy zY=3WM<)4Dxi{%$qmcU?mb4Fi52#t!N^H#~Ol!Q$cIWXO|g6FwvY38-6-{I-a`En)h9;TF^WW@}L1JK&eB=T)nydFsM8~^_5@_Q}dfxbv`hXv5 z(ODn8h-vPF}_G0kvE{0#D_c%782Di>u}J;5LBy?c6eNg@Y6SE zSJ%;LSq?Jo@&r}@8syJ>YzwH#|)xv5Yi5cb)d?(r<6mwx)e;y<=7zv%eLN7L!nLNJ;7MS=@(6FRR(HD0r-T2{X9Ri!HDmEH&^kbclDFQg8(ihVWKwQk++-~6(Gp>GGIcS% zrg$N!V`}7Ik84Pl_I4qQW*f}Jo7P~|&#aU;1Dd`e_^S+8KseqTA4A$Kv{(&CT>{g+ zz40DK(86zfyjSCb#=Y^b%^rM8M03b}YWHpLB6CAvT6prQ94x3mzD)vkMD(wt8UgFOWSCZt0USUZwPs04Bw8U>mG zYhtmq?DtN?o%Y7YcCw#ajoXMR^9dS}W)VRH#H@l%G)JROjD-fzZm9ZdmUf0#<3}>q zqgjF3e(<@`xPgyzyKq*P$PnAs4YXYJFbHO=^2$^Jw<-?T5kq-G=`W{`8)wmAL3{g! zAve;H)PLf5oj~(D2=oGDo*?nhp0UT?dTN0KL7Zvz1e;O-TuT_V$B*XOgHDeq@IU+55AeSppxkQUfhiL^W;Jeckfq~3~9Fc_ZRLY6h1_%xCT=~6gC1_sP_Fp(yV zLo+cV0?s&x!pSt!Dc~4dOsKPv*H~0Tq6ycC8R!)JrIc`BCN?-QGaw{5iF{eGS1GMV zRYHH$gGuc~N+!3GQRUj{nChPi(bBKb;7n4`K4wPKBvB^uKnXt%kytGpJ(@^QZeaDmx`7&D?oy#tKk;T312#wA$f<`f=;C=0<`?~zfVGPdAMoA^WeihumbIn|Xv|3Rs!R9oEg{N6 zkA>X2HylLJ|CrS z0K24MT@gymVwmsyjBzy9s#c{85kH5Qn0^Ii9~|>(EtpSLSboh)M-HuS0pGC>!+?$E zS=)Z!Ze%#v1fMamT#e;W74+s^Gk7-JNlm&KhHYMxBd*1qVZf`^z2^Z`n#;>3uS)4A ztJ1Rk2G(?LtSac0SLc4$*=b7nswB9xO#oPTz-yTuflkCrWv$s|u8`BJ3jxqv!O1Kv zt=YMGjiNlivbTTf!_Hx}VQrnAo!t+gy{SsMvbI~KG^1jY;g}fO0L(f~0GCp}Kf|O%60z zyvcQPvNVKJPMg6V5+>oj@tSy0xNeu~pX264^i?nQz-)2B(}YE?XB%~?b?adxKY=mZcECb|Tj9O4BvrPm1xcQwu^j#V z$KR=ygDoIf<^!h!=e{$LGJSGbZqeijpg)qc;h8qzqpl_ad%Cg#%~qM-32 zQOHp50e@9FP0t`%9E_p;>Qd4#t!VHI43C&Wv`^#t=#3dM+7uzX9V2FSrd}ijS%h8* z7>9jiJvW6XS@NbPBl0-kgJ$8v5kXiQ2nB@6#Og?-h_@1&i)({$?`N9GSM3e z1kb>4BqaAvCP;r)Yf^YpqcOzVQGs0OArAUX{)%WH2% zQGEf?p)eZgkfvS9%?Q9|gz$zETS;t5;l$P;jm3kZt{?xv2>QMA`zykL%Zu8UJ5fd9 z%ld~4m#bIJb-g+@_0^-d!k|gQ`qAxM|N9$*NBByP`Z-5FsS8Edbqk9-E{bEznJQ%R zncS3SL91?AzTey5uLAIT9+=z}^nOwr-4Q5$d2eU5z$`j5FMurcCNno$(ADtjs5U07 z2>?I8X+ofXY4*U^j)FLTV&w^=Tw1vIgd`5r$+Msii5C1)J5rd+tix{pJzoJwDCj z@SEz96nR(}rmjGp(ZY zg4sq^$TXJX?Qi#P?Y+A4;rMt}#MCza@ZWFbRTO~bH88xu|7Yv`f11wkIDWJrNWUZvZBxRvN*Lv6ve_L8 z3}N>S1V>te#bD9ZVre51D_>$YG}{@;w0yW#)M!cpS`x3cm%$SZ47n7JivpW;7!H|z zGi%=#*0@C@nr4E{0|YJCxKL#Rv4)Hpct~S9pu|FUX#%!{>-GnkJdY1)=mtOx_^Jvk zg(Or@RA>}4X2_C)8=kx>KEh*XpTv;0c32wM-w<0N23 z*zYQDX!RBZkiFs2ctII6S(8LiuFG}V39rCwa)P0<+4V4)ABKg~(Pa9V5^9ASmUDsxD`TeA*8gNd zpZ~`BH$VUU((IoeZ0@c#m7cHE)}Pb2m(+ODuwuDfdG<;f(mVKoPhXn-;ET<9{o!-x zR^BOf0-e)1WxKLfk`n=Y z*=a04R7H5XgobZter;uK{`vjYKiu!-^y8q$Pv+$@^2o{L(LNn?yNaG-(GrFlK*-9% z*5wm$v_?ES9}X%NzU^VKjOgmN3%QjFwgfsgtiz%cNkckX)F0YHNxK#y$<-=yE*6VG zE8AVR#a5tY$dY@rjOSE5`>cSfufX0uayBe&H6(IFex{!f=%I!6 zrmdm$EseVpSXSCQE(F&ShMOjeQhNydaQ+IDQQ64oKE-jnT;^Z z-W31n1n$>;uTbGs7nvMAW*Z!Z0H;ZQ9?;gL0jAP@T~r|Xqd+u4&{&nC8+0XY2ty80 ztrR1dgIrj$^C zb{+Gt;A~Pi!@^}5O~(;LhZB+EbrUhU?wuHodqnUo06Ir3iNx6A8d0kNWy5O;pSu|LJxKna3Q}hyM?~&dy zmFxhJwRDJ?FQ7OmKuGoAVQPMdRSXRS&eA$K!{m87_g)S^5(s-jBcTyu5y6q0&Z!tn z5O`Xvky!RlcT5lFPIOF9v;RFTH|b#3EmvGWtk=V_iP)MZ9!uxdIW0m;V1we!;2w75 z>za|-_y5|Eez3YaJNx&4{N?KYSNr>Wd(WRefAPr|FO2OMRm$eBsj}CS^m(m9y|T9V z$^uwm)Qq47fUh*+8x7OB$^YQ*D~LWx5JxjXOCa;WQ)R%LFB@l@n?h>u%$xG*pDH?5 ztDCh-z2P|Z?Z(!Yke7v(`Cq=QLAv;kPN21n;T~Dg3k_w|q#HfFQ+{{ecCZw`yJDiX z&aDXA%bi`Bbe^Em-loZz!SsApUUr=YP8jwz`}xqtycWHxja1$~ocNIyxoYyQ49Je5 ze(uB=+-XG5>Og}0c7n;eC_eDMNq{z~SL+iT+$t^9d`c8on3G1CLi@sI&7!BLJ_Y2T zDFZ&bK{%Ui9IWHjR z*i~vO@MZBXNZWXzV_$wDje1p}w6ZMNQzD#uVU03|zs+8H`{@A{VC8jtt0E_29QC8t(iava>sa8vn1Zfg?OvwvP%ef`K7lH}f#MkCg1 z3ZeeIvmnSRz+1Xja>|0T_LF6Kprvv{4i~2(@Y-;c<(8bsoIq>|tT#&6?8ove5dJGy zLF+3!Yubh+0Q{z^x6hI~o$o!X2aJ4v;q31R!zNjO#1(W~!dB@5Rv9#yI;52fE&)PU zafH-nY`~U!cabf7gzrLw2}KHc7#^!Vg`KgGZh4SV?qj0IgBW4h*SOR2AX5sjvzBvCH%We8DL&nE*Rzu!NA*@$os;lDi;B1ISZ_F{~#U!pol zj1FDauEE7n+hyEE?0wt1V>A!?yEQS(9~F>QbyhcIIYd|`sgzLz)=@!JaJ73*SIF&} zFWKGJjVm~&-NUNcY9rQaj(Ic{gY1R+SA)#kMjT1uNU>So5yM(r#ob0d$~{L1Z%t;G>7Aanq#L9iO2-)3{YUS&=UoMH4sa-Fw8S3^>+8cjxsmy9Rk z9r1~THYZKNZikbFnPi8uWudgme{psGKTY3x9A7OXg%V=nXgCoLDQ627#wBt>Ez*o1 zjwL(r7ZP?C2pk6VN^Z~*N(diY%fW5E^rOR~LpH_SiQ+=cC7YPL5Weh&ZZn1i<4=BB zV)lRB>+$*&WLFj14_F!{Jm1gP>-nX~8y1!u0bYB&nk*Ue_P~;Z)E)T!cS1BCM1me+ zzkV-S7w)j|(g;#1lCiv~p@acP{242frfsN@3cIh||4{n}@g5<6ZWt2i1$+J2lPopX zP{_?#TA&)jtd&PCA^#`tlYEVq;2rX@B10IJ!X$24X<2H8qWxD(fXSY0&+j5RiWOU}w)rtZJ&#-;9loym<8at@OLm@n4MZLg`e7Qop%bO!)Ec_E>JM%^3hr zDtJ$2=ZEy| zp|<>p?vJAFipToTqM6;CnG!O+X~tH@yBCDzrDAj4X>-%alrdz6&er_diiB>*2Yev+ zLMt#!=5v=uP9lcZTxb@;y8Ts+w92v+ijVx2+M`@6juI&5n;zAbRS4$MVlX|Qs_!T# zmrXFq=(;EdfE8t}CGYQdy+`{>fOoqIGijA|9sl~^-H);^w4;J1FA|7oC#`r;@Z#L| z99TJ-NC}JyiJXipRK{-Jpl_ zfxdg-?dvbclXIs0W3R{=W+7!H7$V2OPeTto^C@{I2(lpMjHQBpiVdj)b22Yc2e{8) z3jq)FG+rKMkM6s5ej&k~D^3Blg@YU~CnUn$dAOfMMn6bW-7x&WFRiS(3w zSH$9m8SP(GWkVuvC9|<@8NdCgak{y6FJxN-u?8)*btNJ!LDN1>o6Nt;PgB|k^A7|V zFy>#)6{-`U4A^CJI9vy8R}eze?we)H1$*%**)^h)J+DIr%i3?GTVscdK3-FOnPo3| zmA$nS7V-)U{x8m8yh#|1Dh|~iVkumUCzzZ`VY4;Dgazr2I|X^m3d&S{PDnr0qx}u@0#|%i^+( zqen|-vuCpp9x8Vha2Xphi{X;86KI`JK#qy)P{S|?tQMq_?1T7-k$jcFdY1Y7Zq(|+X06}%-H+DpfdQ(7&;RNtpcq=jo!1W7XV)bpK|K&l%F^~dibY& zun?_tC#o!8VUZAIs$_(|!hdrhxrM@*Jp)uNT=WU9c2YYS@`TZX>{B_`gHR|!W^_12um%ZPK}6Ah!R+vZkXPl-lr?xm0$|>t_l}@#Siz0`uh8B* zenil!KMuMhUMOe_>gb@Cp|RT?32P%Di0y9>)C`iZ(J(Y*6(NDcCr=6#Gi!Fchv2#` z8a9dLcPPYKHxdjA6bt(mlqI85o}bpE7Jrz8=ny{Ph&D2{_%t1wFAD)yHXIDmRUDSD zFAUx7A8-e=c12ii`_{niO-+?eO^54G)z{az)^~LjFEws$)NM5XvN!Px4axpTUUqaCaJ@slMnr6=30NNdsjH(E7zTP_zPbdq+``3;t*8FhiTT}Qr+Bl-qu=d>ofGsX zT$nr7>esHBly7&+IkdBo@iUv@FRm&56~0@yPl2V@qvE>8;^LphL0hxv4q?C_)m~_? z%7jc|8Nw(7BQ71>z8^iGP6!E@Sy%8LZc7uBz;QIyR~ zr`q>|#$dpDHZaV|)pbfa=GWuKOnN!BIX}N?tVffJLQgl1nW?jjaj-F#>|bEHpCEBf zD107!g*bx{uCSvkQ%kZ2$gNk}#{u)z22X`-xmj80qf*8I$8#wEK_p9A?~{ z>OQ;3=`GdYJ*8`r#qRE9g!DMmg(9!eigbQF`t8e+W{sk3A}X!4$&#aKC0`^~pGt`birNG&KV5Zy

2b|`-xcs`iQ^;1eHURl=Y2mO!qJ;Ag^H>@GaO z!iXItueh{{flOz6Zl9h1SelX!kinrhhxLHbGj3oMSL99R=1_#h=Uio%MG%%;Wa3;T zZ^@#!>xrKyiwP&)b--!%i*ePuU-kA z{`Zq7JFnU@eZVka!QYXe9zXo<^*59r&fU6yYc4(aXDev~UyOjLMlPJUauTq&WRi)v zczZ{aD2KINk3k znvUcUiZy`aBtz#yEB8$mStPUObP53fx^cJfXm8b<(Piz$Lf7pT1+x=ACII}Gtm{<* zxRt7r(pDs0v{qGC2?I{fr4sY;RdZcXEN-p~VCuqC04A15%-mRy&kJ{*pG@6YV2*EU zCa5Z>{_(gC06u(%_Ibwh^2C^Ys;n&NNi&{UjjijZHzv=&FmDKbX38s+Qvi5VSmgW) zdM*Lr$6M1I8(kC%ozX(S!OC`Fzyjlwca6^y0*#yygo$={FBtMNjT?f5go@skJINS5 z8(<@P0T%nL5~8#rJ$f}gomYHJskxjvw4+Ez7^PofLmK}dTj&4NbbiP2^$ShEn8ud1 z!6IDOk5VKBF+;1RdUgHf%x*|xOmGH5!$qQyiNsW*a5y?Nb`d>9@k^rBoE2lxTec-; z(*qOZJkRq>H2!qk{owEW8}@p<-o?|~ffm|+_&@^b^YeVYo?jLV=L_=!w-hi;2=1Po zLQ+udnOu|~d1AcSQ#>i(cw$PxeNiqKCd$QPxuBM~@kJ)kS1%mG5e);rxw%rayrgj3 zZl?WT?XR*s+0!}$ZctZ%&#m+2KBwL3*KjL8(a_{drnJbn4|W@HqSfjP2q2?@?xY!s z&}b*bSI(9q`WXQgqeOe}7N68@ip&ZbpWx*5~w&V!B zYM^_8Jgl4`F69mKSX1+v247p7u--^p8!(DPSdOa~z$GKPt$DP*B}M}<+A2Y1O`(h^ zGAjj+L3Sgqm=a$CE6)b;4-4z{1!G4jR{)58wJv!&h!(nDh;H6D8jRH=W)^HcB5ayC z=-?e!9y1bdULnQ4v$_k`vLsiYSjtEqRdh7!A_Xh>rAw$Q0_PwJR+=IGr64r08N5>q z2q!gG(j~_v1*tV(=~I7{qCCrt}B=&y~tG!&A8RfVL=q)@6u3Gb3t0eia~Xs-yu z>T+O03c0Iw6{aI-^Mb=mj}=mV73QKUZ*LbSCED495;K+dS{|>K#t7_M@oL7)R=n4Y zn?3Qn9-+Q>`+GgU?371@{Kos!R)09&3#E;RtrJ$LU%0PO-He6gc|efYL#rT3 z9cd6)*z`aeQ5Kn3arDmW1m=_jfO963poB0HrtF>~qDR6*&8PWXom=+)E=dTYN!!ahc)LC942ZqGtBn{ zaMh(u9%dpvHylZ%O*e$9L_&@4QEqr%b8Qc2mrb z+U3obU;X)waOs<@Mc22k{$1;%M~~JmtXSA4+*vVtLHP6D3Ip!wJ_dPSw&T(2n{PVy zZusKj58po%CVlVTtJi;fefh;7pMJal+qt=~A3y%)%r|e}zJ*TTx_;rpRyM;oKApM# z1m;_5VlY7*JC7a2hV*V5y~Lv5G3WP~^p7m+Bb=pX>erPk;kxX1AVd?Vu@oPJE%Zmo9wROp9WJqwOl)+?SDGclXO@CSbo2|LqioA7NS*s@1 zI$9Gxt9yY6YkcfzVWKoifCXIg(#)P2LPReeoha?ueP!yXMw-p{^psh!q8w*#Oda8W z4gd{6^1m*8T(iYg;0~Uy#A|KWqJx=}=+4WNlZ#q}H8xe;eP~K^MGK{#-R1L~N{u`- zhl_{S-g^D$;K+lTm8(|O4H}vGXF7tuu?Xl3H=RUCcYjR4a{7{-W30SqQi$)-!kB!A z^3+seY+|ukq(p(AkLhsf*N1<(4*(u{@M!&J^LGh9?qd(uYa`T}&2=UY z3^kUL?SF);oX);Zc`*$TE@>CS>UQ?|y@Hg0Dbwea!%ld!U)ih;$uz7Mk(3`@l?@Pf z%F#~ZGG_7Xs-DU}3(#_$W<@iJ4rtJ1Kohe9IW-ikvP(r>fd(X2DzqYyL(RfYGpoh~ zj8dx!G-mOe6F%#t1*xS)o@@3u<<1EQXYU(ma?(uL)CS{iYYCu+PBr9&_BP@973ypv zp=l{Z2+f^TtYH)}Rhyt{Gm(=mP+m%qS{icH4vxl9NXN9LuwJlO&^gi;i?pG925$v! zg$qX_qm%^8BQC8_8m&JPYxbeXQid!a1%O?&CBc1z#+Fon#}^YCtYOemKvytU*TS?G z0=fA+!h<8hdICCXg)b)sbA4Ele9=g)22skHv;&x==p-~*h;=fUmqXMroKNo3dIlxC zQN+wiP+C6S6(s688C;Ge3lfaeH<{1Vyr7*7QJliGC24M!AhY1_u4wWX4mvv=3{Lvw z`bsX_oI-}FerEq~>$KaTx$bIPmHe@IJGCgOiYREWrexW@4#S6W{W7I?&`Kx=R9CsF z2&SgN5uygw8`8a(yu1hx5b_J6stF^c@4D#?so<(heH%0(dAj0O$P@R3;-1E;yVY=8 z%jy;8+oeg)Rwxsq842T2Z>Ikgv*@lkyI=sAiF8+-{y`?uK(6rG^a)EFkTQ*T2Z(EI zL`)U7bQZ5c7+U54}kL2gV&Ag7Ojy zcf8M)D-^gxOBp^uaAmg}HXPW{VN}wUu*gB)2}Rs%2GE>m@56Hs>_uV*jL+8)MrH%CGlRvYSURo{x%<#MT zR4u>)zdF3sI|Olr_ockIA-9_}_)5jln`+iq+(tC`l-&v*v z7}u{Oq^UGrTzq=bWmR%&xE6&QV@L8-9lutw0W*R&A(Zb`5`I_`+-l57-S?vVw&pJD zSa*%8gjNX)+-q9n2cQ0-c=&?gS7CgzXV0QmHWtdedx}J7PZX4B5+WwVQuv_&+?4J< zuihvMyj_3#=HSSRohxe+K;4f?<{OgxyLm{yfjZt$&G)l762yTWc%q=r`6_V0xuZ{{Iju|j$c9_`y5VN zpL#cqv6m_YKZ9i*B+`OJ8*iW6@1SDP@6VBBfUOf?PT8m)B>XBRoYx+ZJA_iE zQi|2WS&>P%Gz5gho@;Uftx9o)`8Jcx@laq`waswhmWG&o?L$zPxpPZXs#*DO4heL# zlm0=q8)5WqA?J$l4fz;hB`gR`RF>c|Gv+qMU}7nS|3(-(yXxD{2mz*jVKn9&b)EG= zhl!s=g+<;Z3DJVVJ`;6C8B(7643dFq9K$$|Mp0Rf`XaUJ0+uu6Beimqr!QFR2g#{) z;WaXr-(X%<%OpJC5iBMet5z6uGGA+=t)i}^>YfFSlfWzmg?W;lQCii4wA__jS2V9_ zSyAIjit5oIv~Gt{N-Hw61LoH~OA5HVlTmb^U3;^H{bB-kXa=Q?)KagV{sqV}ebZjI z{cE?w?$#AA2uy2(T-hVZnzds+Vmb}*R%sTr7uTa^aG?3n7 z2|^=)77*_BpmA=z3-#^yc={1M_fw5zg&O;qYixUvu3T%O zrG-lIeyB=6w9t+H09n?O7!qAVMpH7jwVa)!{X{o?yU9N!0C9ayjZ05F#kH@#oyklx4Ry^7(zqvd-6qxH3~Dk5Z$lBzJu z<0jHq!Do`7JOY-yuj|^|uU>t9^myOV-uUqbf!~f(r%t_ivAOwT^S>`9x&@pCtGm6# zUJT3C5IUcafAY!Nn{S^#f4=+0?yKFGFLy5O?EL4^)2G|dpKzga9^1V;szyaU!Jh*n%*FA1() z2IpKa3MeD}>0zM=@6f%~oi(AY@j6|5l!3ljka!@8uHD5Frn+}$XW1k8`0@1mc#%T% z$2UvscjsA4g>DW2@Vymbz%v_98j=IpAtx6wAkSPA20RW-)J@uOhzT~zrBD)nI*)vC zgqvNS21{0X)yVti1iAnf^gRM_ckfYea)B;rs-XG5_3Pb_FHHV%c5!|Ga`0#Tm7?G; zO09JSzRZk|^Vk5-&(j19Q~Nsg1y9#z8tP~P4zg_78%#2BOnAKa@2z~pv?CV-yi{-z zY}7(WaBkUz2Ed%%0-;q--b@X4li6rM+XB|Ng1*Z+v$==7Rz8<0sgjRngFS1+=aNw` z0yf%nnmyz&GKB*x-X2ZpHP*ivY&+oh1x3~zJq|dV5IiZzmzDsy<{ZEnk7CZMMqmwq z9EmPz4y0}A74lAoc&n#%HX`DW5kU2wsm1O`&NUqAYmY5c@p&_^)G&mNG zg<62Gg27nsqLM){8-^p_^=K$+gVU%5D(DylS0KGu`(799oqAATUw=I&&^cv;OUY&< z;bkPH@LMRQ>#^L0RLg^AhDt!O$B7NG)8?zMM2eQ6>X;8TgdoR=*6^_($>!$*83jo2 z6(M!QKP8wuhCpa1+(xwso%8@yF_uPVhsTLT=fjAv6#Vo6V{gcfa01uD5Db5>uwegZ zwP^hnC_jAC$*nK)HfquS>-V2I$*w{qQBu!U2`SdE{Ag@&zGpFOg19ETfNRcVF`(@T z|0Doeivi+i%Cd3>43;Y>!?N@sAInq?1F(`^Ss0B~t<=vh+K?)YrYe`k3PF~&N^tXd*tk~k8N28XZ{PTU8- zWjZC4OQY}^rO>~Ctuh)2!{GqhhJ+In)?hq><2O7+I-CIDp-327Xx!G?DY%zts|j~< zx(qBm*D56VtZ?0PZEelXt&m`W`+^<&2G|II#(EeoVRRwUoRsKntziYy zxi*yy-OOUbnxPs#A+$FzDq5WqjM6BDr<01jf9oC6n|@~}ybqu0?@F~!D9V~Xh|_x{ zIlTw7>4Pw>ptg+F%K4j5r_+0*>^vB9*%ORxth|oM2zG|D3fx)HS=}rL$f5IW2yALv zXnLLWF6bGQjN%{&5BFl$-92##R2u5B?j!Q$CvvT0BJOU$sQc@YkrQv~pKa@*j@qXQhIM{1B&^)d5bN`K?MVeybRYC0LAx zVEBMl7<9vdC`yIF<)gYP`lB*N!-n*6==LzC&qK-T`ve%+AV%3*&cI1#Rvs z)M0Z1NTz&Dvl>?qFOe&h7hi;EZ3R2>KRpElj@LoBTrL3u1=VQn91} z46vp8d~cpdt00&v++K5q6=g%}5G?O)Z=zf(NVfhQJK%TdDKn|%IhI)0p{Oa55hn@q zpz<7rnqDk$2do2dNBqMeii(09kCO`v&)%g9`XK18uaB4imRweWz;mU!l6oB&>voeb z#q{3ELt#~3hzpa#fZa14UBLw`*D11AWrUb@dx!sVR`|)XP#6pBL3r=1lK0A-CFjTq zzM7UGO+9vKcn9$wgg8~G^FX2_)A7$AquM{Th9b&VZ!J^Y7qcNNnw2~GDYok%ojmj zuutVuM(gWCzItYBKyn59kuQobKw-|HeN)lcl+T7#N{>&tu0XaAp&q;nzY&DamDklq z*yD*|?du^Td;IJH#uvs@V)X1IMP>vCcD#O+Bzb58Ms;AN-|rESg(X;dgb|HZ2{$id zqQ?&3@O#Dps{S#cs{p6m_Y6WNE1gW1l*2%6KLW4-(tiJEB)cbT73sycSdJox5{4y& zU#WcPlV=2i&oCMKJvn_+;a8kF+k2pK&RHx*g9ZOf2$)3F6`jEBWw1aQjqx)wpQ})! zWTF9>MMwZ-i;?NjKwP|;VAZA4eoTlYz`amQC}^#lGSL5m_a~Tth10s2$pJDf=0I3@?juwk1*oxN^wl7)3QvXG_ff#wm>3lF zg}ONKHEf8Qq-TU(7hmasG&%2TB5E!8|p<{F?Rnsh2 zwfArRz|!}}nDDh9zb(Cw)H=52(+8+8_$^6pUY|6padf(Ty*z==>xfJyO!Vb}6KbfO zCNz(*b1AL7Mk?=F5oZE!INs*};t1#66Ehn#8yinHx({{4H{$UpYiny?XRf`?2qkYCW(G93h#9Veg#lYq zm%89OLN*4Fwzp4(P?m$R=uy%Su^h?mPF}I%oYHz4;s?0$uzNu`Wd(;oFalSxy~G-} zsynca6Jo=vY8`;x^a1Y!@LutPav#xv1f?_=#l2sg`T0+^+nApRlR>ytRnWx%RKZO< zD}o<7>jSwl3#MhJAHs&3Idl3g})Rj!om)C;#6Nd8;qI+-TC4ScoziRX2<1$ z3Yg%|ahk0j2R7ZCm-YHyLAJTMhea~rE!dDYd+U-&q8vtV;6Uch)(5jXB(Cf+Q$b*q zL!2>!N0Xu z10oG36EZZ6J-MZvNs!Z&LrpLG36!!1^qK4C?VAnPK@!hCVaO=i$sL(YN2RL>`SCef)NW$N14eX&ad*1 z$8rj+P63*2z9}Ka5B#{*`Foqk=d6rjyj&~X*N;L%(B~UAA+G|X@_V(FzA0a&?S`|G zK4AX?D6nqW;07M^39&tFV+1r)Ddh*uik%OD#U2}G%zl`EQ9~#csb(O!ZkLst?P3lRisoJ**>a>Pb+p7@ z6%b7cYo#)ZAe62F%2vwMAE4207gLAYX#}-m)pj$f)2=4%f`4Ss=X~GS0TzYu=Jk)J z7V&w{dCqf=KK99nm4f@eOw|JHHir#s!!03=95T+E6URoxHcpIWz3-697!*}H5X7`c zdKw)Z3BD!*L(-cE5?3%{1%knZf;S9*uPCK*kTI}!f$iagVT0%($6=O@?7gNz95fLf zQl{-aCQ7?PSc)`W(6nk%+4@bBc*Q#u4ZsGy>4tn+v6En|Z&$7-1-8%VK&!LUJT#{jAnOP8A+L+DzMYQkn&2+St1 zvE9-#AZ&=WY-G37$&}C4ZlO%qZXrP%A4YFpM+{zv>-O}(j@v(~Ne<3Pl{O;kc9aY? zdkTo0n#-)=xuWsNu=9BX=QR=5=Zzw-38`5*vQxG7wJEpb+snv7z5cxTFXm{@dyPnQ zc)WVIFhx(DvkQPDir>P2MIqCa;z2sb*$s*3%l$Q^Cp634 zc7jRe==SYd^;PD>6b7@Xw1U=cpDPpHQ6sj7PA^`1@x}AcK6Cz=+Xq-90>g%n?H_0E z>$`*KWKf31`**(|ZGNCNqvMMQw0gAY8W&W{pvB)|?9qqig+A;ygh$VA<9Zm}4l92~ zHQ2#z`#p%+?}c4&+Al$DFb&-eyF7GVr^cKyV(9EUhrKB1SvTYL39na>H0(!V&GuF4 z<9A+uN}D z?Nit213r2G@cB#3JCR$*N5%fezatC!hSP8blLAVIzE_=;i;;;w$jdhczz_dr*FFyp zyr7Omw@^F!pRYmrKKpe9SkQRc6;^ItWGrhxnTRPV-?VI;(SDFI;8R{-({m3FFr6Kp za8EnlRSMXhYb=m|cH^@rK7e1n5EMdP*hPYdSog0S-Xu&MHNakp>$sp#+YkBev6J@? zTv}L_5TJw;z0RaVuYQ>c392&Sdb&@ymkAVhBxX&u6DL(Vqw9B^!0(bND}+qkdb#4TXESPfLK z2#~7`o?ZTxLtkUT)Eyb&4XF$XOIFBjAK9s5D?wLMtFmLXw`gc=IQ-3wYX+XN$LFU* z#hvL2)eH83Y0^CM(~~okc{&PPGx>^PcAoev!`fnAM-X23ktK{HOYVjd<4C+xNzu1p zC+vne2%LWxN0wHE<3?qT=n9VG*?feC22Rt1H1?WWkv0u=k)Gq2pzY47k?h8p;b%6r zxyk+BgXmHQY}7WM+Q1+E2eO_cBVa8F(IaGYY%t!qH99HP}a;c9Zj_r=* z#zx$I?6D4hjR)g;j%-9o?!aM{0)j^rJ*l=N!(t@o5yR$}Q~T_$T0_d^o=V6eKqquG ziDxeuO%5{lHO6~15e9T+iXJp%4im{i+fmeIW6@KH)tSG70egoDT)`b}Y&gv7l31}4 zCx<*IblMfJsS^nTT(BD&jhHrs(+bB;YX_;JcGOsdb)=!@c6zAMD3lxF!m_=0DT5CJebOQ_28z4@s^xfV;$8!*>O z%l37CzI+b3xm2SW$%r%t=}typ447{j*X&5|HGWxA{-gcr5X&*8>bhST+#w%n00Lq;@!~( z(vgykUntdz!Qv;etAzrw)+HAY(&;5V0DjVVReyrmK4F!9cHI-N0Z^dR&52j~=b7vZ(WPSxjk^wo{R-gvN?&;fSwUHs$l-tT zQFotpEmYYTcbg75gQnfpgYC@0RaF2l_!SH~Tu@8igjb2Q`hMe;VB>S)^rHB#Hh!@_ zJ4>`izVs0K(UckzUpgC$k^P3Utct;~3c<*K(-wSVkRyh|j9pX%97~gt6-x)x>9fBR z-g<3>v%Ubmm%rg3&w5kfS)wRk`o-kuOG`_xpLRkPXm(ZYxC;Y5;cL7f-oSbU?m+#v zR97L2$>h_pSQ0ex6QJg)Pe1+#0DS!4;qoJ@x4qU;p#|t3P>ek+3R-X)#m&<3oP58@~E1_KODn$xTgwh3qb2^y(f1e*KLz z*ROB=*?|2A{DiUpzWUY=hi_{{Zd=Rv*}{CM%T|QCHKGlVGpith%ELO};48 z`AQ`};|duzsX#J@9G3`P$rj^d?@DY&Z8oq(ZpNl%aBZwr!gLlJR)mct<#EXV%$hGq zY=A6_6{#DWh|f7=zj5QQ*&IE=#)L;`4JK~m5IaY90}0R(W6AsMR}*+9;1m};|~?=G10UNfy0f#baUvhc24dSW5L@oN{$6xd3@JDw_;<;o(-=Z0*r`laD0#k`FM@Dl` zb%cz6dvmftvs<)2MGN7ax&_I-T30#;Fzgbb;l)RIIBQEsM4*pkddiSislz%F^i-$T z^Jc%zIkuhb#@b!R(zG`jC%5laA~6M}*A)PFNZiHPgc2HqhYzPOX z3z3Ai=x-TmJ8^Tai)x+mIG;H8^6KKBO&p^Xz>knEVS0~1o z#`OYU>W+Sy849(rK?mCdZ51p8f^6Xis?-FxX++@7_Nd|}14k8G$wtzS%7e+cV(x3i znZOLJ%!Fel34T@pRxw0bA@rC=hIXPm9TF8#Q zOLFvBh4Mkhyd?O1VR;~s{tN-zJ z_CIaiXB02kAluPUz`}~sf>PZ28rLC_MtE^d>xur*ZIVHnDp8?yW=6GKTMeKJstN{5 zRH7gSQsxDgN)_2!N?+(EwOX>NZs@iy(zG8Yt=dnU_OI;uobRsNiS!LbTMDGamUQOiBQ2BY^;iKb zxCP;JpaatD;5T55w|lbn^GIuFv9+y;2}wxI?EwtHksSpIoS( z8x^)!6=T8O(P$vrDluq83oj}PAqR*+`J!&)!|^QySKZMqW5y*!RlsbC{c$+lmh9fz zibttih*!dKuM{qYy?Cia^i`pt;d4&XD`Uh{N$*|~RkJq0$%27xC9Yf!ItVFg$a$4; zR!s}JdtN0*n~ZzFD^ z^+T@Up?m|5hkOk6XV>|rYpGlwYOIIz`R0V#;cMBAq}?dn$6U7*X29H72G2JDTO2pv zh{JNwoA+%`^ZMvdo~yoyi}yUdSIFzbuN+dc{Fc=@*Z^YjV2r>GC075$ZSP#5^!6q7 z06WFi^LT*KWIe|Kdeo_)L1qo23939b`qOJ_`fAg)Wn77Gg(!O!g|gB<7$>1dvVFuJ zga7~_07*naR71j`vBgh?LlSAV1+Km6dIy~isiAdl22q}O>tVkySTgBTKQjjWgW%g$ zjYSm?0m${w+QHZ?Bj}B#8tURh2XJ@x?;dT#fBns^k>6clZbjI(sl~0K=F-oXUjFd! zmw>mY{qlKr0jcc%ZwA0Mdn6QCt8M^&jK7XWs+$=&zjGW#`IGmbwx@N|MRxU%{TdZC ziYu-O_V#^XJknyB=Yb2U?jE+jtA<`ph}U?Qt9S3bXY~2q2mgL`{r;(^dS+)u{d=4y zfGzDuh_Gtg_AmyvOv%@-*f-jI%YNe3y~BOouz7fR!!ARN`Y$ap5V*2(v~lS8HXN8Z z%3mSndilW@>tFn9%>5lmU~U*(rJBKx{}^urH-)6Ms&^`H5`B%lyM$79V({GQB<;B) z*pdktY)-aj>d~9$+@PshQMZDwQxUoD%=VZInp$L5vfe^(9h+{2R|vUjnQh7#uud6c{h?AeqsK zqX+RKoyCEqUGU)PzFvcCXHx1_2=w3yBfZPZ%$Jwt5Jm;9*sNX%Zyy*;1m%fd9reO$ z=?W&T0U#wHGZz<79z)He(Bgf}It@ z$p}=}Ue1!q=#~**2GCocXCxN$k(Z-~Fd3ghoK>)MVY63?#gR1IhXqgkHwy;mj8J>I zO0tx+50z{znN4H(#bL}4w^Xr5T1aOrUT$H*8}~e!YYh{z5tEFS9oKUBASM^EhkbX% zsBtVdXOuN<=i^G2ym&dCzRVIA1y<}bNtEO2T3{t?uq`|ui5(bA9?8y)Gp~*{Iv5OT z(-k7Ir0&wFJEzVE$*1kPqz}doa}VerOkcNKw2=0&M0sv?olE@acK*99NJC%S`R0!+ z2OomhuQA~K@l<)}Yn1ol`<5G0>3s7bU-oavJE^ol*RfwYl*$bq*1VR^j^&m$k3Oc# zWq&~o<;@=>ug;sf9OAp>37-^K1;}NMs~?&|H_w1t;qJWO1zgqKd16A9NUCIbGyZbX z``94&g5dR%Y8Ou7Lb~J!Vm7LS9$9|i`Tw+EeQyK>ebSVYH z3QS6e3bTo<%`dmVU_5Q1`{c!Yg!le-W8g@EI z(r52F=tM)j=BC&yyPDvBVsE<*HSs2SQg^rlFa~_z81U$06F2<+4@U`PA6W zCtNfJ{C`4^|MBl%r-<=teWmusp8aU{LvFmdx3+c#%ks1x*rOj!Pw(@6>wD8Lt*&si zH@$K76Mg{3&?Jda9`ZT>{LEwh1boiAG9-Un!MNlPmm{zllAoDBqhanu$V#D6QK^*7 zlRH9M{^IAQ1-PTA3@pRcTZW@JkJugu!Cz%U)2I+qv^42iOs3V1)Y+0jhGmFuKu$@p z{XxZLEcX^lXoF+`JEN#eG*))p>QbUfz6xd%ps!@qL7fa_25u!>6EKr$pQ!*)O z0zDH)kg`^)5b@L*rxFDPtq zk&}H&m;{Hl2=47&?rR^Ex{9hn#c}j;v!O21=HKUNrJ_fn2Y|w5!Lkt%2Sc_dMFw*vy3Sg(s>S|wXC+O-?e>x4~wi9xts$j%Z zi)ZL{FkXz3vQescIEIhG2_ z8h(UIjt<$p?b?m@g`!=;X$V8pg9#MC(? zxK&KFabbkb5vI(}gk*P|V)r%0X4vj%V4PHC470enLa@lswZj5ASYdc_Nm{I^7Y@e_ zJ-fq3atr9GDh2dZUiX&q-%`9(2x|jM9CYEJ@h?8KA#EkZWo+85n;_GQ}*od%ES$OWk#q7u&%ip={+ADiTm9rNOZ!2l) zfbF}b$4R?%Yhsr_O$l%;yO2#9JXgkH>UJGq@5xy9Al=vjHw4c4H@_2$za{gkF}ThT zJv>crLUi-%B!zA&of|y4FPi_L z^UXJx41K%=!!t8h5t}~|; z`Nlj*mieh@xUImQ;!XuUI_h**=g&79fqnYh490rcrF7}jA3yub;79p>H4&<;M+gj8 z?Wz6)5tfnFZ8vwlu`PMi(Tz>*J{4?1iN!9cralX`5RkyQbdC}9YtKCSR8RlSC&p$c z9L2WBul^GTyszv=5#SZ4yE53Se^TGA@A`UZbk%R|zXt>U^H=xR@1Hj;$4*=oLiYcT zGKNhfx4Tz1ruVrHs9)Wf-dkD0$aMH(ZEdA){~W%!VMN%NFxa@uESj=}KN$coy;uA2 z!GG6Zd*-hf#`@j%x7s6wtlD$^3hr9tIUT-4R>;Z+YfEn!@m;B}Y}PhzkPZF8YORKb zdu{W^(jn2%YpdIbdy3k+OO3=fCMptAYnSh@pMTt~*PQ`r*6##Hgf$*T9~F$WbnJwR z#nv6w3NmI6O+t)=ouNp}jGYzzh6N+Ot)MFmxiz$t3EJzh5nksXYRMF-_3fC{c2{fS z&KaD=A(YQ#M61{rC`WZgNY;!>2)QYfNQ6{bXgJ+jEZ(A;K|5qzO&ON~ZD4$hLv&k- zflguXOzJGnzZq2lr=YblK)PlYFX#9e=S7LX{yxw5#l%32 zOvxuu+a~v%Z*ZMs z6B3O{DM-~|42x1sfO`F0unFqRWIC54p^^@zCX$}larJ8P!adf#^-V#4eeNFhf^rKg z$F0WzEYEuH9L8cEpJQ5`Q}S#!#lhis<=gNn3M&W4v=7+ha=M&@njnrPSZ;$J!Cj9} zAbP{6dtZ--xN)JmPZ&m{#qxQ~hwxq1Npn<#{JB8|(5l2z0$d9udsv{%GFlNC*y61&`4cE_Y)h0kY{{R-#RO>w{chVQ3mXSF7H z_WrD(b(oZ{^kin1KMO11blsbGzCB9LzK{dI*sqj5egb8;$IXN%bEK$gX26^I{ z0P7?fwqaMt)K$5&jl=xROx9LoY2t=y{AFL|56dZhz&@2_?B% zgR=~w2aGPu1WuY6wA|MU83v(S&D2>Dxavl_5&GbX^#y`wMOTf%QrOkvK?A*t!0%}t zQllA3zwt|UxF=jS%{?hxht9ljSl*UXO4|X zjb<)==D42F&f*}Zr?S0b;+~ea zDm#njuuv)OEG|MY7j}x3!hy<{mwt84n0JK%e|6Nu;?}6JPMgiL0C0Y;yaIV%sZ?wM z@$IeR7LgeOsE6`Qx3$#1P@oMdzxzm&u>RK5r({}p)y)Hc`dR>ZVQ=sDL818m;%$)o zKrr$^p5tI)OK9r>lCHI)90;vmSghU5D$IBV|vO z0dy=*c0_b4w3oizEU0Ph23XqZI((P`Wi`3@;+_!@O=uX#YOXnzX+!h!e z4Y+OvI$LgzcG8K|$w0bIm~M+uTsdOV3kC~(cM3)B5(3b2zaxtSi;^50pHkE<@T}h6E;hb+ zedpJCaKxXB%=1XXu$rPd1zX|13fN6lGPrZ=04lR*`JmW0rrdX(G>#_Z&Iqssd?P|` zHE1$;E(nCijO4j#JxAd}E?A$-#oYCpjRi**E}g>;j5-UmkwCAyhjrUKOevwi35E<# zt5X;a^l+@{RNa_kFrW>To`AgBGVQ;PI-e$FZPe6IEe!?U@Oc~?wN9syTe2zTabrNO zMo-EY4`i5_4mou)ny#&b91Az5prN*w&IPZAR_avR%bR{po+K$KCJcOit(q*p^t0C#?O%q+l(N%-|4C z3jilfJupuv=iVe@=W%|-TD7cp^#dy{&WvX!?=Pn{sxqA(pTxLCLi8k+gUFCs^-c;x zG7!#$XSE8DR1BQB{q1V(m784cl{3nK`+K#IL3lAo)0#$!1sGv;m?j3fixNYYyCxM2 zEXHU={03>0`ketc8|H9kHfe`lYDTo+zm;S{tx1&f`{E-bcpR>K&W7}VA@>FNY)_Ua zs^J{px|TI+X!f^8x!j#S7B**3>bvA*rV7Fn)nWz(;41$;!GKTDU>k&WHa*ilak2(U zsjsr+8C!yth44<9jwD?hPwD8{2%d2w&6puH0Icg^jhh^pGD#mMdQvm6OdFC(b!@)V z@QQEzAvqftROYO;g95;36p$OWgOEUIAe!|rkGas(`sq-ud2cDW%RlZRM$WZ@$3EQ* z>$I6=i<*Ny{9C8JVMtY2L!W*Ij+?o&O@JF4Pb6d62g;81dgIyGfB()~ACBIgvQ0S6 zrm|?N`SfX_Y2Dv^NOK^(vGRUJ7_R{2LE)2&<$_LJ57sV14>g3b{NrLlL32q^v#g8T zZ~pzWw~x;DX}@l3t8n1c#sT~12ZHK_z1w>Shd=q`Pf7Ic@8!OM)~V)Jb?UZ$`StExWpP0uwXn9fxUe8^50)NpUt83=LBY$% ztdI|{tvyDQg*Qsj)Uf#N?X~T4>9yU;14huVo_$%Pzl=j@s`Zk-je59A_eNf0O7pMD zcR4QR=jMteq0JRP&dbppU$y>&6I!}x*5c=gO4BQ3r+shp=~q`@rE;m-jI3IDLQmwE z{6o@*7uPwamLctMWurIf2+#v80669WL$Ub+kS@f|&auECLMhsCAi^{dI(2L75Q2Nl zpEOGf7OXJs`_bV!Wzg?m(nuefHn}eI6BOC!CDu+zw{ubx;k1$1!UuGT`3() zcm73C749n#9O-NUO_5_o@hZiM++Y=~DIA!S{Bp_Nrv9X89Po{DpJ1*#g3~C@yqRIN z8`YH{>U?~j;st?g0-~8TM|1vpm1X&f#0r9^n!G{1kzjGqFNi8%=h^eJ>5aN?3J%8N zem8*XkJDpBD?>eVXYFo?#)#y=ilhxkK{I`h`Ex-5QP#SQkz;NxY+xEKST3l$ZYZ={ z9zR?kd$*|`ml4zGVZUZz48K29kOgdH_R^N-As;jAUd7OhTPk?NVL5FZ!g2Mq~ zkAUbC&!BcOpm%m|jL{tIsoALU(UQ~v+pQId*5R{{kZ6;%p;1^hgm5sOh9L90qpvv) zyunv~OfscBsk|OlGwB7Dtx&DTY@i#35bH{qU9i_0vbX~d%W&Gl6^syi#2OMJEAZ=0 zjtH`j2;7bczfD+~5jMFa!ei6$UCRoy;T71;AnM`{d2A-6v*?j<+S0`?I8A^>W@IwC zoFuY?ioeVx!)IJRI`d73b<8{+4o`y9?aSfiunMBuGxR73Nkv~Z3$g;ma9{ZhU+#zO z(g)nHw%=)i*IpFUc!7Jv=X=%3E7$EYHC!0iZ+c(re|7td=-N!V88{2^#U3oA*t$bUut2201zSvz=A*sPgN+bdwy%~0K}O?hVqy3H)wuwPr8b$ml@ zHKP|4j9YEl)qqN*Ih`^oSj2ivL4gPE_&)Hg-nDa|doF1GQICOL!->^-Wb|0N6J`nA zGw_RqS7TNMeOGxOO2!6Qn@BWR+Q}L6daRI%V8w#O@Q2(Q5~M>{ZrDrTp0ic`)rl^K zGuqN{=0q=&d|Y_=&RcIf?oRco!noNGGu>2PI(@wrA8@H4babIio8QmLYA#fYJDU4+ zaIjKRvbraShm|e1!OUtGAF~6lJov|NRD{)coxhq(;G2N4;JPqi=(0TPVX?G?WO(7X z3zhs1nbLB*Rw)-&aO|!uU0Yn+&F}6$`p>_vUOhSz1}yB6Q8p0#<*#?=O69HXt@7t( zWu%`|B&nQqbGIZ1%0%-*MyZ*kz{)=TFJEW(+thu=ar`RV=`6>_QRXae@B!ONZ7+y4 zacwhs%Pz8A#Mve!GYQR^Ct1c;leiI}z_e+aK+w?ufv}*hkU>hNbf8@fQB4|^7^CT; zsS@07H&OqOJ)h@y@&elCrm>HGILQV0>+kb?Uxb-{Q(LrF){Fm|e{%TH`+7}X9JF-? zEe9{x76f2HQxZoP?2;{muRyGVtzD7DQ=EHALrMvs6xz$TON5LI)82ez{_xwTj*)m1 zG;TuSujp9d)6`9eo0b}f(|J?1H1dubgaZfaYDt3C1RZsUkR8WVP>U9bx1zW~0NV)^ zyMykjXVf9Nl@|&85|V{OIQT57V`(_7fN8zXovwGgXJ%nF!oa8f7I?j*^Sg2KtdvK$J{Wgab01q(uGr?c7RA)&=XOsI!& z0cUgBq^5O@3^A+DB@-qiE1QdH3n7-^WOBN&bZ$Dkv?QntTNVn;OX>*DY9w@Ah;L#^ z!?7qw;xL|##c=rwpVi*rrLJ&Huy>@7Wm`sl0k+6d+UeWaWP zf_$LT@g7?E|o{q!64vD43sk#JZqr4AQsYdbz(u+iG2oOiDwA|xEYD8-qmE}o$ zJXWLONm-9m)l@B#Vhzk@xCPTKryGrwCD__%lmw-*`8NEqvgb0#C? zx2QRj`I+%?+k;f3tZ-bjDCMY=*VQmn>^wu~Jh0kR)F5aOSnzgS1zF>zJR0d@IZq^J z1`D$MV17~RN26w$0C^3ZwAuF08ovhh6qG_9@S(b@2hE8J0a1-y{3{-A^Il|zW?3#f)6UjA*2KtjS#UJmCERERu)eGk!kS04}GKGh^C15&`7NIi?t&Q z*FU;;?au1z%G#YfYqwXi5ox`nKA1gZB6G9&eQ2MioEH2Qjy`(+{P%|6=W_i@(EIJC-U@qa zy;0MFnOCo4p0IxoS2JyxB!vU**9G|R6CS>D``wjCYwxaodu?@neSPb}nfW)~mX9I2 z2RFq_gQlag(*LJcM8M7|jD~pqI^$#jH`whHnnN8DD2&|7#e1y0zY+@F?Q}ae*4aHo z5+zz^@+t8%`AF#S$rVYw5(JfNIek!E%Ihe4sMnVZK@?cJ{#EuW=L_%(o(qFj-!PGv zG!J&0*|qwP1c-AEchYU_z|%xT2aPxY4M6h0E2*W1Id=j5m6jz92@uQIa&D|Xd zJT_voqZ8<;5^RDKn!Aw*Ct~rK@Z1C@q=dkxGG8Jo;{v&IuO8rVJaO(um+F|k+WQ;x zqLgOyE9b|E*?0&y_9h0fB&iFDmtrh@NzVw=1&m@E`4wo}1#QJVBs7@DBw@bZSYH@X zG)7(lUzJPCnW0lgW2NDf0~n7m3oG+gYp@qJ7Ru<5%A=V>hm0jS)Hk;8rlan{1FYd! zLWLD_NuP90IqMjbw2Fan$texxaGFM7m&>;P>h@RA6_*hYBQ96e(BS~d^7xHFT!1$s zJiy1=i@eFIl4br>mG>hZzG-%SRn8NjXFwk=i7AUaqrPPV-W#oPJz38{l-Ut7<*0zQY zcK`G1CzeoN8$^!sBuaVC?i<98XbwR4SPOjZ%g>gft<|<60bu zYnS9_EkK$fgd?w|N3+CG3Mdz;3Z4-zP5CAS} zTW3o7k8M%3=5Couw5foQ4-kUDogS(RaVQ%GJo$eo&9Bhe*A2jvyJWVxv*1-UMML%4 z1@z@PyRUH6#6mZ>bzz?QU157DXusqj(IRFG46>-DGXfS(*XK+Q0c zBfUNt_wufwnn2d2>pK9t0G6G;Z%|Fa?Y@nbK;_*H0GK}D!Gp@u2d^Bge7XeyA6d`= zvBILk#?wdk^Awi_h>zGm;{NVUm@riN(fXEf^z%>t{ucY+qk~7~w`eHNCChUH{$sy{GG2v|Vm(Y;7!UY;1ha?fLW1XP$39-`xDi=9l;1PVxW%AOJ~3 zK~$T>g};0$UoZ6b#aI9Q%UA!NpMNreaO_Iu;NX@1pADLsyjFAmx#V(A3AGL0bQY$% zeQt-#spUux+(3ey1X?+?%7~)hWyNL|!p>O^uUyBRbK(iRvy6M040 z#*h%;f`b4`H_e07w)2=Md!wKAVc4S+G1sKPd$lwUW ziUnW2@$9*W0I&e-$kIb$$6@xs^aGOv%@{e{m!P0QSZ^043~|*y6Z6b@r@Y}Ci9Uj_ zC=NC)z+DejDlJqvgf^OsUGDv&4-*0zN{HT(jur|3;$Lkuw%GCYRDYC!u5 z!^pEjL{^55hgI_2caNYC8VtumKQ^wVv9W#fL5w~uS{V4WhI8Dd!O#c@d|G`J2ta>L z610!+io<^m1nMr$o^(YF04pW-_#zRe(}K-W)6Ecw${9WvE)1PKTc|y&ej+&pg{!Wp zhC?%fMh@-Q7$AQ@`+OrcAyjske5oQ8ZBd$gcIDD3Pk0LrLXurQwzxTI2WCSNQHp`D?LVV3zb zCM1own$74Wo1AF11hYQ=I8)@I5@=d~h5D+b8sg2CxySBo$SBBmgvcWv>q+TnfF9}# zRjl19>1lg|I3{1Ey_5eXe)5&_g>4Gl+!;0RZgaP7NV}uwJ?9u;-f3(wlVuZVsi(*j zl@r5Xf0N>bH+u)0b0%1N+hZi(uNt3{dVdvo=T!V`j`%)0*WAN`4HdSf(9LbERafxb zw*5$Lz@{Ei*TDkHgSG@~&Q8Em|L>qiR?ab)wo3;p{eK9Y?5=&nSlMu0Q^vsdxA&)* zj!Y}z3Hb0K69^3lZli)G5}m*28hYhljF>Kl8uS-?fXW`A#Qd93hn}SZ=}6?)w@^Xr z$k~XX|3lZczOV;Ec?NTD%lxriD&LMaOQzkzpAc#F<(z6hY}Hs|(UE^H=QqyuV}Y%+AI{b2(~g zgHN9KeJ-`<0a!u?eU8l+w<{B?fBMTm3~OC1(iKsWRr$ok;RkaVp+aZ${WMQ+r{{>~ zO;6v4!07(;b%B}Fi+R8t6?71^b?fM4JR7Se>c>l9%;?)H2;aMQSMF;kK~nF3%0Fhb zjzM&Bw2l$8Zm|xSj95Qw$9Fy&v&*6JKt;rHunz>iKCBiRud`?;0ZE29RU88ovt4o zt*sG`t{?6aj=ua4db8-$@rUDQ$H$G2POEOefB*jE-N|y_^78A-mY&+m&1<>W*-P0? z`ns9T<*vr)O+z+EmvQ=tC3paU8HtGc&_ronKTH%5Z|z2|k<^XVFK>0tC`Gd9B_Oj* zkA;ywsS6`~LBvnuD6?om03jBz7f}uo&%x2!+1P{v-7I z@^IR%STi?aNJ7pA7YYK1nI)H8E@3k-fiW>$$g(as-LkU#$PLR88GK?DfRdxgOQsFseE1|CvX6NjRkrn1=$}W zuul)0h7loHc5mA2wLgR|nh0+%at(Yoq;J@X)7p&f-a)(1k622?Z1j7HE4Tamu^Pry zc@ULJoUnoRUq2!8gb$NuKNvCHThpIL$OeJ!;0UJ9X~zhnEz^$nC8ox{8t9uZX1lpfA{V2{5{%oS1{Y#zcCW$y}us?Q8IgN zt1XV9!DyUL*}h>xl^`kEBAw6g5auK8PNuq=`ih6oLW30-4`B?=nrJM0^FnD6 zODW)2`zl<&!urbrS#+-At?v-he#QKmKIUzoNxf@DTK59+TR?76kx)YyaScPC5I?g3 zOJH+L+qZb(du``lUz5?sfzNtSVCW7_+=0zLB%_H1he*pJyrws?y9*!pyFQNzklN444OsK!zS=RBvL+Dw+9 zvyNeNZsF_*J7D(TRB*sF#?bgRKdsCOCd#ywWy1nUah}@%?c7+Hd-`W4p5GC6&h8(N z-y4s$M9bJdTfu1-j}Erq{QBnAo9!jS((NCafPT5ZcW`j<;NWQW=*g3#qt(O1^~0CD zZx0DPKODdP*N4+*$Mf^2?@v!oPu|7j%kOgc=oIUmM8+jb4uuRWO3$|MS`L-dmx^PX z*=(%1I7ZiV^y<5kja|KZ<;s=f;-1)MPwlmy%FV0vj)w3T?&_9G@ju(wnW#>5_Ek6Z zbv7jWs{2Z-8_Mau*`!E15e!(2`m273$Y@jNE_GC?TNqwB1vfRk&p!?6cm6C+^ zP*_={FfyU>162b++5o8)=T##88N=u#DhDOifEJ_xn}kCl0Co}w%!XAugBr8ODr^V^ zRG=xMp98{&6hPmCs=}e9hFmHR03SxwBw_LtfvC#pTh9TOAiSP>SJ2~BIFypWHCX5Y z`NjU%qj-WLWeQzN;Ivo)2RR3et|4NBj<9m{75D!lSHq*cK=FbH*&0eAdxbf=gD_VC zy3#EtvEodj%QM51YAXiKZXvQF?pmnKG-Z&*p(t+N9KR^J$r)Jm2|lDkw}M#c!Wp+a z0~ZmLSlH&GL#c^FIA%bc;rlINXHtn4bp=Sq?WRH^yti%={k>IknJ6*~ux{SuF*N+a z&k2CL&Dcwzj=`eSOQvqKY{3#(XMyoo*6TRkiij`lHYqr2Sx z(C-Hg=5|7_AF^k{U1U%~AnipQ^uvCl#Jv%SqPY$U)?PFs`Pzlow;zdE?Sq4a%ReI9 zD#DMn4=(v^#B=>MULQfKgZqEe6HES)bbAf^dWn+~*tYv3M2p*bI}ET!BSQxfV60j} zK1Z1M0s_VMHUgh6v0x6+fi%Mq0k-Z3vh|CMF~utPYeYJ4^DC_9#r!Ih3oM3(411VXcjxul;ZD0 zS~}LS)=PL>GaAK3{PTI_||GM-v2coyD8s~=_t0uqhdN;XTyS&`f zQ~UaL%jWCNSndkHQ3C@d4w@a$;d6{Wa^lrPH)2`7ftOQpB8m>iGTtE&wDY>Uysx$s z(V#_%hR#GoLt?qSfk3pgG+N!+*0%h0`D9xgUCN_v(I{OiqLcJBieBLgxK)miqBz(@SUdX|>tVvw$Cznz8xnzW%A)I5xpg6xVp$a- zE7-7(r_GQ}hb>_BGtZp412_zcl}ew&gvH4KtiJ@%su|H6Q%HbLhLhZR z6gI0WE1(0R0LIk>#-1=tNN@rZAc)uQ&4ANG96SrAxxd=kTHVMf4ZF3Li87o)hkHn@Qf*AV98FAyuoRe zF4v5L>R%@s7YZ}5BsrZW$fLxr7hD)Y9y2b5qoARQF0mq5gCi&r*Z~sUEZf;k=keO9iZUqEc?1C|!2Jg-AG8iVN3jf=l7{;}xPo!>oJxH>6z0m6iUBH+u+vqKs-U1bU0a0PS=@*IKzoig6Nh}v@V&q-P zdNXG}W7Z6hFz<#0l{9*1;T?I1KrDj z+)wuss{WU)t9@xJPoooKBr$Gi5^~WP(=l&1(L^d3t$EQf?m*n7i6DWpP>8D#G6}TF z4y7=D96A&~tVL=eFuPD@pfaVq3o}r*FcR9j>`bRGRQ%-B55xW+`<(N;H(FY0W4yU) zLpA4~=Q%He%L2RAxM~LWc_F3>hc8!!{yH3uF#C@RKDn(5D#H|9ts;6-uPTXiK@Re~ z0#dFtA;d)4ImBFM~O9s34Tnt9l{XfcZD4YmJ=3ZzM4b#^!|bqUIpC)X?K? zv;`+G3MMZB|IpC8L~)kTUj#r4`U-w7UA>sSmWBR#Y3bU1tbwyoVkt4Sh8Ez98hV0r zTo7MG3zEF&Vi$YeHYl~GC-t_*dSQGYCO|Lo!FD@oG!{}HeNih2va>WX$%JV4A3GoL z9+lq56`1!Pv;Z*BvqVMdPoi9h!_0vEs^?0kYI5ILa#0fMg@cwditkkP0 zBSwNj)iOAme)y-~ ze;RvOPB5rh@l+rX9V-#fn7>HPEd$*-kf-zH9O*N+lM zdwY8?BSNG zDT%HMBNb|T;S#Sh<{ADqoMt0Nu{d0rlQEshBJq814${kamf@LR=||wy1;+ zSeBFl7?Nl=Y)B{?#8LSMsA_NtV@8Ul8{%jS2Gka4t%OvW8Z5?lVC(BzgG38;gXndj z>IzQaHC083+M^iqvE)7Xy{IIdKtvWICo@w*k6BR&t+U)+V?4($QlVpO@@F^You-5BAT5f;-^1oHq+>qmB@^ zUwD&tFspV7@twi^IrxR#3<#y&L>lFFXV3%Wg(?dxUqM`Wf1L)lj)pL5Mg+$w#9Bd? z4x;b~%UoEHu<5rjU(n33Q)8aR;`G^;uM;pxIW5484yhiaMhuTVruf56vnGot?JclLW;wVL3#0l z`L__Sh8?xGBV2IQ!jEbUdd>+xgZdU8#r4`PM@?rFL!(is72p+)a}Hh83vJySt`_vR zUQ6asL0Gt-s|v0PZ*1sVybwpCBVst($=WSQj@vmcp44u&?+ehj<88=|+c-#p9m3xn!num>o$51+JgfUUAEdVRI{gXa~M5VSK-gX$(lwBFxJCZ z@^PCucDwLN*!O_hR~0q^BMNJtw6_wi5P9b-X|pVeWLOwi>nks}xi%|xSYfCPA^Lat zs!X3`In1)$`}ifBy3D)#0m$hlg(tAAYaYML)fG^TXrg;}!JPI`Xm#xH1D#$flxklgN%Ow0fA zes}f!(Bk6I%jv~S^0v4tH>(#`S1%0*7)05WYXm{Gh=6GN%6Kuow z3}h`El@;c=9{TYz#s{1#^9hzCDrSRvz}lB%1EL|Fb<9{X2r5Cdi_g7xk0 zL2y+&Itk@f)$Lkgss>b6*!a0DckS+#b@+Mh0?f|8DUPt0{KRVifcU`*zqU6jOw~Hmg7-TZ&*@bXu!Ey95>>@|QZA5Pft|FBq=As7)mL+(Q zEXdh#^=GEw30_0;o5~;zdSU`8Scu6& z9_5rAVDQG2fN2V9D+G9iKzUO;N}7eR=TvMUh+t@e*c6ONA$X2ruqN#Y(9U4wycuFD zwERK*#*D|$#-uxdVWG)E;OreB^Nw@VgN({iKZMS}TxhO5{t)XJ{9g<>HxUPoxpZ*g zjsWOC{D_)_E(>Q0&vnktK_m@yCK8{+U>aPR<|7>8>4L*p245%Lg{=rfXPgH)^v5db z*+Zw%$KL>z7EI$zfrWQBr z2m6EoTZ9HP2dhu*eC423B|zH|!2uC8)Sa9=gXGfgi$`ii0mZ zFo#9~A)4C;5ekh~La##@akXYc{FUP}5f~&QPKHpE4}r1rp^n-k;l5$?E;t$}+2mE^Ju5bhTxjC3 zFl9J~k+p$6uuk07t(Ns9&vtWFJy+}1Aq5MIJa8BnCnxP$ttyIP+T`;@NiY7!< zul%9&UYo)hJUz>G-+x~+PAi=Wd+sGqnj);y>9D%zRjQkNV`bu1o8gwhmLpMNH>*N* zsKI*q`t@t!Mz2A8>u1Ezy~^KSDs*q`Tvs8{M)Y&3WoAIP4A7lz8H~7T_lU=0O7JgtquRZ8!$8i=>ASq6Y_i(eCQO(7{l*JF-6_c-h@o zdlJ`SFFxg{_6a`1n?SVPP_m7dVZ`Juu%0QyjOc#L5c;RmLg&qq)T00GbLnEvraL zfGUzTcv@mCVcMM4t{zVm!(n`0#DGR}SK}eNp@p_a%866-O_-B{2+Yk!J8^l86%J}Y z&2>7|ECOE7DP}At$oI9LCcC=Xba}Z?mnexzU%7CSnMmL z!ESl&jjULn2{Zub;SN3a5854`4DWAo9j zJPL;Eo`{hE%iXp9naoq_pkq^R9Eq`gA%)mUIE;3tSU!jebSRaXiG?OY0>c8e2*nZv z-3d7%$0D%}LItffRuE>*Y^I(DY5q<5H-k>U2T{;L#$P#u1DhVf+K|%|0@)1>Y|i|j zu5)>9>%hWz^+b=-*>JQcRF=~ZAn*_k|_G_ch2`X zotZl~##$#0IyqNIh=u!i;?(%7G2i5Ac9tCI>^H`8We(2Lku)oO#;mkKBy?7U*dr<@ z!bmG)xCpaUXEcjJSYvDHo;?^^`sFM+l#)r$`(T+qBmg*@WNIzLk)iDb4Z#vd8)s&d zJU;)9rqkGz#wT9M?WgROk;1IDkKxzNYN^As!mn*N{F7@(mr1{r!XoJleMfW zV4*GWJB8?pEiGA8kJ?O}FF|CvfQ`i(No{X$HaAJ3bo&v%-%u?BRCgKP%MHw%5kxB^ z3oPD5Nv#bqjGC4t9>aSIFBvvZRUV%ij2( z{qo|)&p*HT<=L~sdS{fzF|z)4#Dj+y1hgKAX~@a%DqkLZA(pd(Nh04Jp%Uz0(m^!Bq4i!~tFr|fW+dF_!HXk&ZS=;rMs!ILZMs{&0O|`cVJyQA5 z5U|~RTxlL(@&gozUZ1 zrhHIlBT9l9O0(p}`n$;~?5-{2Lil3Rcuc7_2QouOX3HhuTz z-L*USU%PSb-_L(B`2EQ~UOay`R6hH%*TGmB(Ve4V4z!HD!v@0e%Ft@$aO*SZ!5|z; z`v_Vq;I6VMl?EL~Z`6DRd^8AiDBXxu8*YKU@m25GgTkkY_fz@L-xKCO2#bHi%&Xf9 z!}8rQVl2N_W~AT~jd}<+Cy_E^FY_3wtoC9*F!ZhBhu4h)V+CNTEle4e`Hw!Gc7gNs zX#IQD{VNj^j95)cYofqAU%&dNzg+y&&>^6LFf<^wC2_-uP>F;1)1R=_xylnUvg3gjg_s!1ayt(eb=!$|{}r*>UGX9&7ZQM(5DkmDy#G;2OG zmJo_HFHjsf8|{V!y{p56p^lxugPI`RABB}~w^az`;x*wXPp)4Jvn4rzpf4T(FO%BWBr2W&h{K#>BSTJwvvF>?vJTo0ql*a;6}OnhMNRVMk9dn{@A^!A#Ma!Gt!$M zK+=7fP~3G{_NHsltTl2Z;)>~r`hnro_e6Q)InXdbUG!X%jy z_C@N4IE!KXp}n!35nmdQ8oeCeUof|kyI92cOV!auxv^sCT4o!(*gFsF7~-qFI271^ zEtb{CU_h-{=rTSfRL}%-^m>NBE9Wb7_3}#j`^6Qt64n)Sb*`KZsIf8I^Ev=b^c7!> zBG)-YqiABFeP3LJ5TDi=I8(E5I>8rue~U`o$V!Hl6fPU67L&y}kTf}?mIXu6bFFy^ zx|*dQ33*m>PJ7^qzbO}MHamNgJvqV8bROUMf`SHv zRRdx}UHd$btH>js?J%^{vnR=SRJUM&{SLHvd?HI>FgH2&LVqFHcE?w8oLn&+*(bX+ z`jpp7>Z##vPA?@xUi&A2hBdr?HPN7b5zsmy|c;up1mubVe>`*jQe-Dx|>&LuaVw- zVy}9z$C$aa*M#_z^jtkWtTsu`GDP01RPCDdV#88Do zMU@MbAWglox%|jD?+4qP>SFjn-AI%YzQJl(1LEq|;M-PV?(y9*j$#a5PlWFQ3$^^ z#`Ib0{lw(gK6&=?U*Gl)SHjZ|eDo|W)-(%XrqK^SQM0udAhACw?IOO4B~(K~^cyeu z#BRw83+=w1R)^9#*L~5nw+-+jxOkg!hYgWZ8W8a=k^Eg`|gI=JQ&WhnL~GV-q5OvlLNVS zrqXxt)(pBo__m!fu#DkDiez$8`9=u43gerZ5bu-z%$w_&7Jt!bF4l|Y?m=5+GK%d( zi;Xg05ZytqLWJZEkLO@K{S?sEPI#Y8=P{0mG$LbEC&eR;3&dMJ*3c38jvCCguQHc5a=c1P z2M!~;8H%fMMLrw;!kdj1uPm;p{KyFL+)B^zwK!8>DNB_#S1094@mO=GE5PpRT=8_K zPC|#|R}>D;6|<*=T73vcCqd_#?kVarEiz^1J60W4^ts{|w zV|z3*Rq9P>8Oxi1yD(U_L3k{hu@~CZn?g2*f*porAka;jg%%;9Fbgk2q2R2$$~WjD zbW!Lx==nY8e{H8tJz&{a*S72^dhT=1^O8mZZ3Ngbc(r1mRSkbXvoBeN0GG(hB7d^v zA(VC(09;A0Nt(5WrRg&P?1jY^Fk%)t)kuVJmV*m!MH|<}JG-%m`iJM%pL(AR*Y@E5Y=JRJ)alMm4Yqyt@PJsXN z%s&?Pm^|~uSwv1CNqvIlFs>x_zO(`xA7zugAsJCH8&(Rc%IaTa9*Rswew;t8lD=^+PwZwdcMZU<#hQM|7W4V@=Rg0u@D~97&fdQNSNOrc06vSmko;3uTzOoU zcP<11%-H$F(e~tC4ISDS&O-O^nFLyn!c$cehFx!HL-G&~MQ}_*A4Aaa@DhC79(|F0 zQ7F9qNJYR5m=6v5TkllQ{B}hqYhh zLN!xB6#Yn}>8yN7$tcOTCi>*lyOr-f0e&1zz^;qFHwe2->wN>@55`}$+oFb&{2u!} zUBS?zk?cT?v()-N8@c@D-)N+wLp0k#?6vq)dl>%?rq09Ej=drx_qX7To0EX zK9=XPesj18+078^oXXp)=^ip@qc*@RN&8HJ4OM9r1XZENEN6pjNVDiX=h6r3;T#Dp z!1NdzAY)fi{)W83DS40jsGd<}NqCh{y+#>*q`suYnBt??G&8(Ld9~EA^H>n~?ex?h ze&JM}x&`C93mr-cd&Y%(OG^g7#(r-NlDkH6yB)i~-|gqSY=McrT9-NLwj+q`7{?{4 zLnhxw!yt7$?xxlo3Zv{ObMm%V9UJC$4V0@LLa+$FdR3L&stV7&sGydv$cnUzA$UEl z0wh8yE9jWX;mEBUEU#V|LK*&MNI z$S!L3Ol?fEKnzxvX|qvb+JMzSXveOy6U8~#YON^SY#E^AHNu}Xne1N`Zdmo+u>Lhx zJZue5YgcTCho{*aR>0@c@NhzK#ULU@gEXsRQ--6W7Q`r`ht1~Y;ox*YAjjN}3>A0P z@-z6|K1JX_Y7|QFCfPmlP4Q-A<}*H#%?G)+Ss_uc8-f6-=^W#_rJSg01X^_=;ZW4FtldS zhRy_0j$Hp7i?UACe&i)cXCVmMp*OgXrosg$abGOHh+1Dhl>+O)$IMTkzOTp)&xIxr zTJ-l_MR7cRYPXaz*p+1ViaAh}M6f{0)#4;Vs%Xp@+q-*#xh}0yW5WL)G6iRAfB2Ll z2Ky0O_&$E<0}du&(c;HJq{aJ#FMs{Z-{s%J&rme6x)g6b4yfuiK?05GH3McJovOW0 z1Lpu@fXwum{i|UjXBbNPC;%Sq9NM+ObB{e-?an zyX;%sx(3&dW_5266y4VFfnBXc$@Oxayj(x#D`3X_BHLN$d3&Lh!#jjQ!-CDqbadlX15kK#C91|REzg+G#OwCdq+(DveszYGdg z9VOZK+AXCEhM7#H@s%trEZPT03rF8FS$>^Ak}a5bua5v;LL)tma)Hc_M5>>#cdrd! zzg4;55hcNtDD5qX`VzW9tfe7n!lORe8*TuOZO#lPL1=u#<N%7- zJ88Aj5m&Ane5z~VViiXbJlOC#XAD+U7aXppX*8ZIRjHB|#m&vqrO(_7oco%B z!j)3U$Px-Ox29sy4$RW@0;A7bULmK_PUfA1%1QUOS z3&~rxP&+Fp>rozT%_uT@F@yFQ%uQtM)g%*okjS+ysIUQujeIE0GPnRMUi8E4!+60d zcs;6KjIOd-m@jtWW>h#d0=$37aJm&m6ABxeMrnt&*42>a-&XT5svS;hi_NS3NR)TN z8A4kV& z8+ViFkcD*?OQz#4h7*NG`P_77w7m^S6KeJ035GXy`K)1)l{J25UFs zcn;^lK@071&^qV~-e3U^lB|;uJbC8wXWYK`eZXhVeb3?*u!hlK?r2($b2v!Cie5y8 zxA5K%6?jGG!fy{WiuUXc%77)x((Qp~Mo<4(uqU&;MfQX)Tq%r_m}g2El7B_`U{7r% z&;{?|#4{h+wQ831tWP$GqVzVxc;@`xg9_ls0d?x909eD)rM-nE zUXF>_z$$ELnn)$Ygq_+ZmQo8wukBlYOVNTI+@oFCU>#MLVQZ%Uc`5T|E>B}a4szapEGXpL1Py)+C8W)UzRPb`N;7SRy$@;A02x)) zOo}Sng4cju+`RN8k^8(xhULsa*S^&<3>o_{??7h{p(G0$vGi|bR$6}NXkq*xzRsq# zvHJ?+(VNi=h>?WMAXmcpYJ6pnG|j?zY>gb0xQmcb%bS2x7?6;_I5v#!f;Z!3As7nd zVmyW{vgpc-DMO%(S(L7lkI*mCML$E&?>YZ#J83A)$X8dgtigkx`<(NMsj1ceD-_XJk*Z1GlF#pDdXpgzE z!EbIqjtld~dD#O)eBTT;M3yWo2DkV3#|Gf2lL*%^0vwUfF^=}f%Ih$S9G`X(ZVkwQ zj=S-^!7+@oOCV&&Antgecn%qk;*LSw@o-*UM)AdM*A8f6AUR|ERMkk^7lcD^yn6Lw z8y^xkOrwc|G-cVqn^%$C>nz{$?~$z4LFYq3HBLuhA6 zhRwp_1E;_tcG4x!cT;J>@QD*&S_y@@-T@4zcsPd`Q}es@Z*$SR&CP`H8pnMS;x{%Q zYyG>aUL^JRN+^vE`rzA~&^A*3b6ty=y&O^o?C!ZSXFIfD*NS^IlNcDQgCvuS>bdcs z{-R!`d*ji^cQ#<3Iw#2d@$Uu3_<-Mi@w+d}?~df(S-}nqBV^CJBFt<`HgxF*S89Vm z#3My@XvW+2WpTi&QCN;%I&lm|_rmH+$E(@MZ9IYWdI6&RNiJ;G$b03|6Q7-XH$zL{ zrQ3H_Tps4CthP5`9685q%IahgzI7RlM!b|Zzq675Vm$8}ioNA%>|omtt7?&2G3}8D zg7MP$j+=qwt^{wANWGJLpMT5}Kh#J(T@dflTFSh-gZm@tzeYx>DXD1w5ECughtC+R z*~LAQ%}=K{q+gZGHx*ev4JfB+sBdLD(VV$b$@C3Wr+t})`1@13a$}(T6ARsZIe35V z%d!V%5#8_RBBQf!6&kGsN~Bq3oJD8Gs7tbp+W_ns}UPKbh@5HM+{uX@V{$PAt78SFh%U+@}b zNfQcwpDCbY?R-h*q?WRw$(=Ns+q+`7YZzRj59t{sxOKjyv<{?OOV{UXuR-R9fw93a zL0C)G^9CE@^EEO#3{jCqqs@A)I$$Qw=jR5c#)TIod~TdIm`N{6cSS$L^2EWUuR0qz-YqXk+BQBW_CyuoT%6xcABf$|)RXoxN8(ZoB?k*o0>+%7#b2u9^> z_p6+HL>=MR3krq4HqJ{{2RT?@Kl+3E3Ku^@sF%K(Dh_%|Mp|Z95zs{}zr{R4zH&+- zSsFQ~b6%B{pNjYz64wlCsSBnQ7%Vk*TSFFIlQ${PKv}|0F79*M3mZ}wihIU>-xNbC zZhfyn@FXx?i2iA;7uH-LDJWOy)b?2pM-er_H7GK&=t3OT3^r?Vp(BOWcpSxhQ5?l% z#8tE_?42HhyO7>t{DFt!n1Y7Gj`;d73-mP?>Ke_WTo6_gV8gaI_K6(1& z7X;WS@PF2W+sI1`yMy?7u&w za5kb_kH&WWxhFNWEC9sAczroo$BBLJh*hbxnKb8mnO1^$G6mNJxrpNLL1S#?{g;fI$|!`ytOvMVW8NVQt- zD;Ap9EB6^=3x`vJ^(SDN zH2SL6BDG12n1QdW3!b1MgkB^DOBhYC2L(uWm&A=T*I6--ey-GL&*IPnvM})iR5W}< zh*`Rv;Wy7!($s#X8RjE29~CnS#>x{jxto)wo_az$3eyI(Y3+T}_Gz)36Tf9eY@Z`} z5E#>vw9ksf@8Am)^ zh~7YRqx#-Bs?m95=vs&2UUWK9r^Cj0s7S1MIELBAAMDu%!SjSiUfjk7HUECNphL)5 z;xIlO42K1KUNne1w_QPS=XOXz;VF)zi|$Y{7znYt`-8)Qs&^^BgrSsJbK z@vqnVCWhjJ2TtIf;QI|CrGgVodEFPoC1qMA0+u2irPrRCU-*eWH?kH zW#|D8y@YN_BJ0^tON5oEp}n5awa_Q~|F|Fk03ZNKL_t)F;27y389ob*fm`k>{Yqs> z0$_uhzgE7f8w38_eMnzDdFgiFO`kz;Cb7_)NjAqzrqz$vzeQ4*iO@FGBjdF){?-(@ zs_bXdW{M1b62Bgoo^^FJL?MXdu6!^wFFf|<-_T9?@jW9Zrt#_bUw-z-$~*R!Gi5IN z_7VoFQ92{#O95=VdAAdme%W2LjGAXY0&crfsjXG9*0@dg6FI|lmGX)M*z8hcXJ0sb zf`vmio7P$TPL4IA9gu4qT))8?tiIx-AOQ^$J5jkI8Y?3Z zHpoPaCBAB`HT`2*u!(=Sj4LTk$)KXHC=AY~lM1A)lw0L=-;lRL_h3o^meXuyf{07B zy04e4^!s^c(-UeJ3}}I4#L?x+q`Zm^7*JkDAiX?!+b8=9LG)ym&9JfLKGBoQ^b)RS zCkU-pmzP(wy=5Yv-3Qz&(M)K()*i8Q2Dhs%qr&~ACCV3;uCA8QVBtVAj7D|UJ71H- zx7Fk3yd@j(ob=J91`p{w&U*&GuS*;?Xi8dJQnDoZ&#w)vOLHxx&46`7AlrBju)Z(7 zr)7ZY4hGC?Y&VzvY`^>J}E5GS59C zivy@dho#OzDj3el-XMwc5y8-yl*pw-CJh5tSs~V==ZeCbJLC2Y2xok~_z|;>R9Q=2 z`(I(#T={&ZoL3Y_7UEl$?m4gIXXT8$4hxE#FQynnr;F({qN-e46X%TN&CH_hF5H*$ z1&qPPTwSRgcIgi^*ObJOE3zUh*6UHdF3WJC)`>Eta}b9`9ib4nP>&65_oMy87+$=u zvy{AfNg);@EJq)P1tYXXV-d_T>_lG1&@pO@c{tvGL;caA!S3)7Ef$HB#*9Dg|Cg@w zd2RbX<9MxKSQ3~>LL$i62uafq&k{MfcH$^St5ygd(>IraJ1EG=LueAz)*&Zf3WJeu z5RYKzv>iqdIi!a{4>^>bmOr3>!2W?93O($;=khSWyf@n_eK&4mAZIdo zevx4r-+la>I1gH!*bdu`-9Hol%t>Ygc|&$mI!aS|H0eyzSp}e%DFRdeY8l<4WD@Cr z(v4Iue?AT|&<{KfD{dpa7jJ!keG8fW;N!pj;+Ma=`X*jgZUt`G49i~vewwIfq55`-6jb+K+qqg*P4vM?HR{DOpxi zUN2uRhn;Zb=~msXcmdy(rwA*uQ1-+%RGugq!l;&8v39JfwYE+TpsqUoP#RVUwbIHv zURk@^YAcTI*wS3!Q3wx-B+x!_=TzXqE(}`+pH$ZqKm4r2Q#l`XUoUcrq!F4F+UGSI zeGL!S6Vt+zg7ToR6vLreWAOI^s`hS6(nezX7CSE+-Q-&8t#mn|t6`d;+yS#uf^LO` zTtx|@DGf(SfmS4RD)ExstdvnH?SBi$8|&h`8*9f>N~cgi7d(VRVyw4^@&Kps0vnMn zq;?QRw+wmRja2CO4R(8dqBo9vklj}QaHkKm#g%kSKX7Zuz_!;*_4an?Nz$yjB~7zE zvIQ{r_O=b1kL!K93cVVszSpwPI_BSMy;aZeRkttq47Xmd7Wb6=e2(9jl`^a0s%jVVnY!lC>H-ElYb15#)d%b~gsg<^%c@~(?J|=& zHvm46Rao^5Pct><&_$$FY7ABllHu~^Qz$O!Sv5q^nM=9}rEeDM2EH3(>%pcXII7Nj zH$MTb?GCjsKRGxkN)62cd*b&9Bwe%fFY1q;tn2q@x+cl9fvgeSH3rT(JF!bAlgVjP zdMv|UMAA>Z@+jf^V9+61^e>BOKjSAacJA>zjx9wR2(@?fOEGwu( zEeq{gdu3ppU8oFrHPK8OCDtqZ3PIMJAq3c9`ORQOX0+XXuoyYQ4HmQ2f@F?YuR0au z%}B9mLK^O_p4k@$&cG$H8b&^!4R%ilTIBi$n7Uu=z4RfC=mp+=Xk^$;NZv!ZD;Kav z&(t7|j318_gtdEWNIg<1Fd5NCXorMlt^~s}``VKm`gZKj;QnB-E4MN)P<6nZDU620 zjUNVajDI5W>K3&A-(aly_?@oc+sk1|q38S8p5Fk*F__QeOiKIrI%Vol|Nidw1o|tV zLHoqn`+wt1=pcD^-W!)5dHvumA8?4{SkB`D24HtS55ZVxOQ*ed2VnLr0Iq+YdGKVo zLB1r7B%>IDyV2hhzc1%rf2tAlV|OF5t_=<$>7?bJ33F%P(t>Gz#Tju3u4wxHw;Kmx2=Vj{ zE*yqVxqo8yWi2Byq~YG!Uic? zhlg}6K!?#^VNFV1ZLsE5!!JM#8@2;2(mjx8fxU*fhvCmL>gU2S?MNv-q?hXVWfX?= z>Jpi=5n-aPK-}J*QC|6y>gTi(8YjkNl<(s-s`gqC-xuhb;k(>>&$Z7ico|2N)RBKt z-_Bq)q9ci|?hEx2ZW>6VcRn{-OOLQ|UJ0i%Qe6@344pM-CafppFYjD3kKR0BAgu%}L|FM+@v@d-8N7+N2x<(+ zE!Mu&Xu9UD3s3Jz{(Og7x7&c#(m?oCt)>=+Pl~c3)!swsoG3`$OyVjgOx~bFr3aMa?>Y_oPpc)21>1UhS2MZ<1kzWaPc?-*6`YNf*f2lDLF+v zBlm>lHo#rsY}PAbz}sx2G-)u1Ho%=Qp_|Y^*vXQ2RX*xKeoNFUG&e!T zE8Cf+ZUrUuLPbbygrU78M2|+QJsRzfh86a~u66cSU@j#>k(|0daLeEnC%cm6It9*?i%Cg-;{zw_HANnsSd z^bn!t*3V(U|A_(k3n2I_17Oy_o~JPmi{H4D!KcmM)iAyeqFjnCQ^0WMgg0(Q^7->k z7)KP%wF3_IM`z1x`|nxY3atJGeJsPkHgbj0k~XCK<$rv7*9XliLt^oZk#zF3V7+58ZskAP0u{jSOjz{$gW&&g|9XW z>Bo@|oDI1yx+)R6mO_WzslYo!J42WtEBQlc7KXmE;5IKVPC`P5kA7XXENc+2F(icm z;ZY=$aqv(@7mA=%;+9Sn6o93;j>uy|JWIq+IGA2IM*F!!AgJAd{fgm|?UXEM2QrZ?8Y9Del zQ5^QTM9Le3rMFh5Wy+xbP!CV78Mg9509ce;J-gOIc4c_oCk*SVP}re;aOd!9XXh$K z#}O2Fr&Ulchus@k2Aj7LU-f&bRx0%`9suD5gRvj=RRs(iHc|}PeX;#w55;urMZX1e z-rhDUt)Pt_(&z2|o?@>upfRo`Lu|X5E@8ycMsA_DBDVQG0vBexiJdgg zyOGpXdR-~dNzI|@V_+4G^_K~B$=*}c25j#-FUh&emDD><1YcT?V9daTbCj~r)2c1E z%cD-IT_&6o3Y=}U8B-rUXXu776aSC4`lY0^w+UoCG|{+jcoN&62=(MV>W zX-`H+N(Y(-6(cl=7~z|ophlTeUhUYK{id>@A5VdI({F8Fvmtp2!*U3P{%m#m!*A|C zxS#&cbwy6sBm_P>ayhiCj}6ycjfIg%D_Vc3CdPZ-3p6qOwETJW5Bj25+fSy#kVEev z;6)>Kvf|F!maCFnYULiva|@y+sd_`WjkZc_6?(a^M%5 z+9}2MUhoG8g_q&-xE18d9wF_xT-zQ~Jh&%mG?~#dRLPq)cG1<9hg!A52E5|x@bD{m z#-=#)p8wse9Z54?+jDg^{~T_m&=N8JWrG8ZP>!qn_%fzNJpAq^I_1Lc$?-LPpEHy2TAH27&UXa5T&=$iD+1m%{S>Q z<3fUZBUrEsfH`(ZFK_{;u-zCkpT>X0^&;S268Ei7f%)@Iho#xgFugu7_Ll~vV?g$sCd zw)!G#On8Zwh3Z9ijpU6bvEdnsvTnYZ^OE0SN}5@^FeHZ18nWM1FJTtMb(?TjaT|+J zWMZIi5{iYvX#Mqi)&P0kSnz9dE7<^N4ViBsz`CgxLgh;;5*lr^(m1kMl}L~_?0&r{ z*p>L1Z7`8o>mTr6L@6u@r9vD2B8wiTJd{IHz9?_BH<2N9gXuCU97bVvC(`FsKL65= zW`KnRgxDe^gKyYe$^RYYA37P*b^<#?m{p>y3>qALou6 z#v+b$r8pL6j^nsb9`r#`xmpMNrC9w6ar4>1WfMd`jt|6q4;V!w#WJuZ9IJQUjz@}s z?onpcY{cbeuHPJ$NBy!oe;blPH+q+smyI__v-;r~oeg`cCdoZojnGML7;K)RxiWhD1t#E)yQffKuLy2yDZE3AA#Njz7JS~kL9mvr zNjrCU+N1K_5oHX_p-8F(#>m!9`h`UY`V(yf>L%-oA5P1RWswr)ldip&Gh< zb{0tS?j#LsJSieP2@xFb@0A=nlmmyfN!LW5P183fGU%~_p^6!Y6y3BM(7b!M=mnn7P*weDP%HxFcgowCvEi6 z753YjN_OoPysA|uZ9!ycR07loa$I9X+^S9V#F&C_-QJx41Hak)=IwiuNl!yHr7F|F zSZ5OoqVnl<0OyM4%>3MA`$_+^#}A^3_mQW2gq|bObT>ea^;9=sg)hOlF_x5J-0sJjAEFLb)-rmFR-+JQTGj4ljt z$*4pmt?(^&s~thfnT_4e0Jg6h3pGRu+&&E zTr5Z^uU<$By|AbS?-PVtPq5`?iFP)cOr4R-rsh-Z2{DC6TD3VM@iJ->f z6wc1728oxrgY7VBk`e3RJdu-zzZ4D{%S{+LW|12y^$Ig^r1De6Za6d(Jjt_5`Ajm! zwac<(wP5qBy7HXANtH^+#ba#0eC7_0kJ*Nm>`Kl_N(tjqbN~DO1G_Vhi{JMNH0U>S zxxPL2*?Iq<*^m*5GD3TBqa+l@6x?q#&yO4ZH?%X95j`8U8-|Wp;u>`G00C@+cEQU= z<9q}KE;o)xk`uR$3pX2>k~X||7lAUB2?s!CHB~1Y#reDz`_YQSX$K zfZk4@B+a&+BG~uumoIr>^Sso(_>|^`ke}B$^MS*|1Gi^f(jSQ1SECMGd;aGO(SPu*2*LTEY z-~BrH>T+6*Bt=&698KK7fKFKYhEa5@B`{VEp+=TxE!koC>Q(YVG4mbJ8>Y{4AE|}U zl~^o*9}0!N4OsK&@s~O5?9x1!N^u6&1E-)x#i8SVr;{_2i&LHqXD5^qJtReHup585 zvphd_8BLIQUinup!b-yb{=ujDA6fxo936$m4kn&#OlU;yo@2479n)L+ zT0_ngVOCNV1ttuYl^UxOx(mYmT3CD(8iLeA1P;}_B`}0pwZd-Jiw7$L#Y!Nc0H$x- z#k98{&wupM$AA3zSHJn~>gwjhr!^*cwsx&7HO)tGI~1zFndZo7ueXUr8>t%dRl52aN0h@HUbm!u$S z{B?|yCY8*Shh+eoVkoRwtO68vsNk!F_ajBbL#J^Qy`81q7g1JWK=}gFDF(+w*^Y)= zOqB_*Oh-eocgRc`Ve}TUSzB=G(9NK}-*j@zuCNion4!;PU$R5S5lozxk|?qKlE-oQ zcQQE)S`BFnbpv7wkkU-0>0Dr3T{qyZ(|km81Ibs_dYT;Qjy+?gW3>0jmBW?p^Xj2N zFpL-jaF;#?N{ra(8VGlYon$}UsV*5eHb{M5y`X5J%WXu?#&{V!uh9-XL-T?Gt6eP^ z_g$J>P)pKGbq0ovrHG^s${5s|gua>3tObMZIh7R}_-5zU44a=Yqt^VIItEn*6MvOu zf^3%;LfIFK+&5<+jlg+v!SMIO0DIA`M~0G%uNQAhxizOS4wW{*a)I=l1V+!@m~qYX zll3Q_^gLsL%yRg~`V+4SR`!O0@8|2vie4lI>vIOtA0!88@(M2_JM|h+|R zC5-hBiJ44AslhOne~BI|qV_kTG9)E*Xyu!a5^&!X4kUUAA-@?k&r0XW?B|sTO$;_w5R>6#b$*-bS1B$+A*6B!1S_&Z%;s?S?U9 zihzOI)A9yI4R*Y&xw0U;*LJ`~T2=1RYglfdU&<5QHY&W+ciVA~G4~rI;wt}zKA)=? zScMQQsA0nW!Y8i;yuYly+WndG%3<^5&hF3X@b0u=!P6#BrbS4*lM9De*IS+JzN>6d zkHTaZ%*EN>tq*VAyY=+xtw+k?m}s#6=2t(tW$A2ENjS9~1wEDmu+CuD0^41$UZDTz zB;f8zfZP)St)y6IlSmFh@3jBO-Zfnitr7-jz;Xji6+ITYyPA~eyh{K2AoZ_Dj~+f+ z*2LL!pnU?(miDol2sMfJ4Y2;!@BuU2Nzo=!YO3#u#_I#zd8iGU1Qp{@89eDJOy$rc z5=A*be?9qXezFe^X5eMt5wEU(wi>)iPYrT}J{5<(%Kz9ppVzkXD~gXKTS(R* z>=+yWs6C0L=!YYlEENBgVt3raq!2wr2)GM_jSR+(AhrffV6+)1EiQ!!OcIzy7p04= z5(=~MqD(1dmZ8k1yY6N&tN9yxKj(g*?a9=!W$EcfvJ)pq=ic)}oqOs;0%fcJk%}tP zo;HfSUS3GstcEa-zL+1`Sxk1Dz6ACWFiu$1$Dw1e=>u$^OUJw5xRmHV&(~DUlyWy5 zI$7X~#D*x#VsPm;Z{41J_UsSOo;~IuGjT+9zZiEcXd&Bg zM&29|yM$)cillG(pzq(F?9qn42Q!yOWzY9;k{bn6mP^w@t)WPC-{Y^8-GvWWPGKEv zMs617sjAVN!y&kABBM^%1eqFbB|9tdS&}Sh?lwEW{5D~g1D=0Hw1z_~eqVWv$cY}< z&M;6WI6Cn%p~uQQjx(^NW{}M3_N#$Z-hr3|YCjEfJ3?rh> zN~1ZVIE)?F?cAw_IZ@(SWp|vvBZq^i4TIfM-AHg9V77zQ4o*!0r*pljTu&%mKc7opGm03ZNKL_t){5IDPYXoNS5_KIQ!Itl^fa%E?%Qm8yHJVz{T zWVZn8eNHD~WsEiOVY%?yDDYuL2wbpp88TP!9i8oMb_)dvZ@2N}@XV;?6Y3bK)Gasc zfha_(p?2OxH{GCK3F-6Z7C;9k*Ia>2B6JzeF?WoQ!*C4*UpE@B1-+2hEym4H1;Mo~ zuLIsvLxYjvr|Y%#aoUpXByjim7|+sigUGD$bt(>5NTyux+Sx{v?WwoQMs*t?e&cM5 zT`!T)wej*VLg( zaH)0KKG?eI2M#cN;^MB({X6&W?d}?oefN_bjz5V3|JZ7I$FDZQCt>Iu*1vJlk#k;$ zUeDWbi?1WFGiBcb$8u-|Q4)@2kXwz52i^PY9Spj;q>XUD>PZgXg;Nb(KVP*!9UFYJ zyXx}iiF=N*6Co6ORYPgbqj!~tC0u?y(fRYxU?GKy0fCjhJT+uB&YN|XJ2qO$($6p& zdPqEwvY`AL`*&3NeQPz8AH@>ri8y^j=!*^MuGb|64c6UTU;g@6zf67YepPYCYO}9u z1)&yLcH+TPc5g>`V&HLb5PYp6>d})mB9G^A8&JP`8LdHHW8|u3HxqXPCI-Q=Qlx-9 z&4V=_4zi{=)mipmd6Q|3fGmUO_ijIU#@mBWKAxQ1c=TxF_U*@agsqpoMyy&7A~!@e zo4)3C5i}1XbCQBCL1*{+7ONqEQaN5Bc)I9&Yc)B9eRt>5`^5UYrouogYO72p?@)|53T0FR?A4?>qe3HU<=P{H-(;%Iy4YAN z_(`-CDOg68*QhaksXk#cBgLCX<`Yt5$##?gN)s7m(MYZ27$(LoBP(;(Tdt?cHL1zf><7 zu{Bt>w>g%=7=MihqtH4Bn->v6mjLMnV7Qb6Z5Pj#&0)wqi&ZH%C&Ta5;_TG<;%rFB zT0mj7(5uf8H96}g!G_HX?gH*nUv%0d<9RAQhX9Mkut@Oi)GTXWx_=?ecJK=nSG`_t znFy?D2r}zonS%{L4QSs^E2xrtc|V;dUE|cyn7KCf4a@Q%ani71^Gzjb8A_7`eN%=d zt$SZ6Z88nbWnIjad3iX!EDn4_J%vc3F$yzzUPifP7_7vskJ>5KY_#*rV!`ywYcd3U zBv2Z>ZhH#lb}~aaR`Q!nisUN=Q4&E(@$?WMgRtWvE{)h|^@wF*kBGMQJ# za=V;k;9J9QWY}w@)E?4q*ABY^xUxHR9ggWWq8916L9Z|CSRj>>!F9QfYFL457=H~= z*GYw5M`XnqdVIysk{D}6CgPQ@>IRuX;|tcF8FBNm!T(nGxLZaXjUt*PN`f-G$7LN* z3|FBxe%vJ~vyr(Dz^$LRBDFr~MQXK*KId`B1XwGp%-@b^Dbg5>25CvhtD(aBZN^HQheGwD*KBupAIG%|K7Cdj zq32&o6RpctuVsjy;`7bA?x9eo^ee0Fi+<2O0vgD*SEMKphX{q!hM0Wly)Tzm?_SxD z0tvpFN3#KT9klYG^@$Pm=c&I}A$gj-O1XTXO(sy(7vC-VD!1s$V!2!aUzC5v_FIUDAEx3psG&$ICL^-$eSXuGeJ5W0FN5rzS<3>CEx_it0RFQA338vOV&qTh*7NxdlKbQ&5V_!@6qwsW8 zI5p+sm65lp1_`|snTd^22as2OvFnWktx2zT>@M05hnt~-pGscOh4vv5sv9}Z&A!Nmc&uKpmrhU5 zP7j~byD&{+pSW#w=Wy}<69bLWz{?`c{-U~->dET?m) z0B9PXE7Ov6R&0Jxodp{{-<)0^zClp5N|e&mgg@VuTH4?kYp{L#D50)rbXT~?2a~h{ z1GK4jvTYYeff+TYUMbt^Wgd4h)L7%_Ar#W7%yvFC#K2n0D;{CcI5AO_Y=2408XQcf zAiCKd3SWj0gGz2S#86J|$5BGD3eU4tkyBni3j0-2jG-;&B>S&yXRIJSX=N{4CNFv~ z2(q&HeI==?RQ3u+hBxhUvwUboc#kZsO0BTj$i7DBT&Z-+g^NnrNMqq}^Kh@r_<4^N zG4R`PnbldtewSUlC~MqYYaAN(RVtW}RLWq?c4eFmFhky&i>SJW%1~AnC9nrJ@HCv= zq6BzLYG<_1PiZ+agnbGC!**+$O%sr%nqTRr8!KC9c$ADxGuVEzX~2x3*j@{4(L20C z>_=nsnCLC4kIG8vYS?c)8>a#3!oJKW#(-;GOi9}xGT_z+@~i9BN7utCuktnGn2qah z;iDLhkCv_~3B5qD6(?dX#S$%@rhV{H=f1Gy;l@LfuzvXA$_H!=`1}8=g-}(%AZqJc z?~#;O-o?;~l~yMqk@Do|D9(M3rCA->frY=9tw>SlDuPnUl(7if*)T{fi?XLc$0}X{ z$zRugH<OgdTIA`Y`POv2`}DZQpksuO95_p@_(uj3Z;uvuyul&-NTptxT3W zwMuC(lU+=TddRSls4HZa*kighmqMYK6>MYTKwx7vIpi=l3N3`K^wx99VaMHe=qb?r z1^c|--|tUJAL7K8em}`i5qj(W`Me*T$Je=jPx(oD7?}`j;j;qO>pf>wVhy|;3dlyQ)># zq4kJ)bjERCk}G4N=uS5ptr8fmduH!vfKekw2&ghKMNi@ori2iqvC-K~C%O~KRIL~I8E6g2)(uh;;whrXVnXwo;O5YM^!}} zmSM8t_xalVIP7=6P(HWQg$cC zjzXi#D4Rc^1h_!SQK2wxL>T8Uw1ovp8r5a93mvxms&@g1 zwL1-m#-gV+yhe64UO}cs5XX3$!LwZ;ud)IPPgK;|K>6U6N?HTyN@e=pIR$5F94&?P z70`J6%1ietfbQBWvuw9ZVj4MEnZ!=j{?Aj1ome(w;2DXgzJ?9k3%8WofbA_N6?7u? zRWuJFhX0Bi)0vcz_&Ju)=sA&RIE^xd8DbPhOoV2wUCYmw`P8vawqivyd zQlcVhQk6)h8YhnjMstlG*9?YN?_lx`?7*Pm{Jw+6k-=FFGAz#7I12969+3gL+CcX- z*#x>9&7*;u5GGl|9@l6C-kL;Mb-O7E)|Mgb(RE$E!w7myVU(*>CMg#S%`|IagKpY_ zC)L8h+jT-c)K};dI7GG^O_%(^rg*R_$Tn8r_WVb z&V=;ox0`P9+X`bSN8yu)qYO%?b5PC zZcK&cz`y+Pof~gtKJ$8KBf_V>g^(F)*;#kJwjNTHWg*U24-GgA;UxBS!4W|h+|l!< zAC(ojn2Q<7uUwFFUG;=co8sMN8;M6Q>@sQ4JPBu_@voiu`6A9UGJYd+ z3aeikqDHE66Lq^0A}6DXY&NQbB!gE_T=ci<+JOn^Fv1(D0<cl$+zlOHi>dMNJE+fn`pd}EigFC70mcnFWt=nDEK^uOql*=nn z+cmq2A!!{LHl|EjgHhjEhRm>C1LQQ`Ut`ByQxxUhd5xsg<@6eTgR|o-gJ&lgRF89? z^Vz$0c%CQ@;MO?qJe7o$A(23d{+U*!G{{TP^LS-?4j}%gDhfXUn66l`|dt-!O33g+0T#TiX37%p^g=uOaCOWUU$`mRU zjh)$jwR6c-F{Nj!HmT2swfK-qXtV4V?J>jJy;6`rX}3$peGQKr^b)p{dqKNlw+!s; zqtfI3QgMHu3Z&9wJW36<9g(kr;;L8+jtokJV$JZFv2;)x3|1S*2DoYfK00bVLcvsm z76)3h;tD1ji#W>3=AdC9O&r#w!FLIJu8%%Pb_!?PO{HL0B#)fXCU zS(@-Js}yN)6#L`lk0;Qr%^#K${-7M`d(o56MOCd(ZFQOX`I~Ql+1mVgxODyR4_f`R zF9(15w{Ca##TRFxJ4xDT0rKX^qcpQ<&#u3H`P$X1fBs$+)_?w{K0-~KT@{0?AaoEc zah0Dkx1PI=d_u=TKimKxhT!X>u(l6d)Ep@e+MAB-nwT#wNQXjQt%ZfVhxlS8v~}G9 zvI8rT;z8o|V)AoVz%FFtrYk*ilV^_7KzLL0=bK2fexrimgHMwAF-Y)BrSxbuQHg^2k^~}jpqb7{80b!?HjK}Ki7EH zvA*Snu$X??4|{vA4NzRSCp2>z(2gRzO)ucvtGjRs&1qdBuZ!YfoO|HxWQ0_1gTklI z?yGPMxs{9~pZadz-m>ctJe~30T7JKLS&>MYfnPQFefr(AXWu@1_MKty?(Xi!t{R}G zUU4zb+q#QBS|v!7VM)|CWXhUM6HfSI0%%g=~nqOL7C1W=R5W>UOp#h!x(TGGCQ9ZBpb0^N~iCxEzRC7gP_D%%~D2~PNQvBD%R}X+4OX} zTv)>oY)9-PjSK1twoB-0y9|K1xnWHn5ED7_Yel?KfBs6v`kFEEjl zL&^&!#xm@knDa`kiW@;Ix+NATv_%`>NGyZ)iYl!gN*5v#(yp)otAN1;bAZIrXiCA* z44V@`t<+el`{YvM2hQOZrkaqz0g|xBa!!hsR0Ll>l`}+cqm{<@Yb-&gq+-dQo%W0z zkav~O?-hA=;xH%dls!|O6!UvVVT+BnVQeY6r&hwEag4o_VrfvS<=FujS^XNdEgc7w zcCr!dKMEQ}l+XsokAl5MO=9Lin&@Evxb`@(n;YW|nvh@&Js50hJgN!fN``zWuMDS~ zhPq8@l8w4*1gsulj79eE5v+EL3`%8PF>&5ny)DzPuR*e}y9FoSlE_M(M_@O6my=C( z1YZ~1RoaHJ;(=18sUdDEaI48*gLx{0nS?hd?`S?QkJMoG2!?F<8%(C&xZM0vw&V-E z*EcJ?c%ttuOQG3l)AtNMpID!*z4uP#XTN@M_U`ZB|I?dGm#vRqdhh+$KZ6-}UV3xl zvNf7o_k93In55NTUcC15)oXh5Gw865;nV;9chr02sIvoDzv*o$XhT69Byc!yu#mZb z7{)&LeF}$5!h+%UM;{Gw`v-mq?WWJle0I}kO)y1=9pd^7XqQE4PsNvs8)Ny;r^59v zIU8>&?pZ=C{w@N|ei(hz9a}v7M82bTia`(7BZ|PNWN=|vDQ3_K0j@pVNuh~RhMh~m zlE;cJ3wktjX3XqUDSZjURM=8DszX}-=npqu%VI<7F-}z;vgWtG$-pl^0k7U@W2z~t z)W*xs8SL1hGun9QcHp^i;OEnLe|+1~cHQ+iND!@DkLRJ4_>*Q_v5`}0sTf#E((IjQ zBoRXZee0Vi-#xR3!ngJZ2)5T~yKJ`YSN*G3PfusUu0t0h;=EJRkIi@?)oFdk(N=kN z7hVl-?U?F;_dZMhJmd4IXFTZ#M(g2(nxD8w`I4JO|DUY$d2RbX<9H=mnk9p<>_~Wa zEj-DSzEWk^Syb7vr9_F-xeOv}D;`Q9Ak7BFl~&6d_%dGtff6X#sYwEc<`8noz+@O2 z=A~t)?hoi;$K8C$X@|n@dtT4;{n|?kiGN74q9nH7dOx4{^LkHP6hNb0WYN?I@2}d> z-W_#MyFE#ytdB<7%@sSk_zz#56TK(vPta38G3Lcs0C1!~8lWUtjH}#m00@J~vro~K zz&9|nb=6;TTqLS|gKQ|Z27Fu`Wz$#BatU9dzdqU*L|FY=st}8{)(6N{`%q!lljMZ} z*NFj+MzxD@@v-7LGH|40(Y)w1r?&$ly1Kbgtw98AQ;J2e+yA-WQUgEouP3NQqt4P<-q?U-XxzzMOh6-t-(?bqokqv&~34^ zw?Jf&|ehLQp9f;_7nGGdf0+tVa7+*dxz5t-Tpic}h zh)Rl3^%4fpJQX!Y-F?VFgM>;`2^?`1XOf|GAjS8@AUJd+!J3RaPQ2M}$D2V%>_oeu zJgm4A2WOv6pUAs7wph$^T6}Lf&A!n|x{8#R+b0dIZdQ}fam8STk!4nZ8ybIZr>ifr zg{<>}adWk^+$=jM9kzcTlnX31iS5-aR+XI}*pt;|6GYZ;L2-yF)wNx1BjmcW@+d_k zmljAt(}c9Olvvp6Ef+vxv39hy)bF9RJ+_w?mMKBf(_p!Sg=JQomJ3=+xpaKgTKVGHXV+ie|ICqVvKLyjE9o=vh7mbR9ubS;q&3mrix+<` z&#_((+C1=Ar$1t8ONXUR7ss*fwIZ41dc{cY^w}63dhDyJs|l;F?H{>k!(y6O6_9n- zI%q9O7~E|)1a0$Xv%Fnx2iSID$vJ}n>+|*D;EizO8xdVgJda&=*M0AJitH9KAiHcS zSv-3C>u@?K-{Fwks2o9K9DN=SRRpOBz`pH%6r@1;*q=QJ9bXp zFx9oe^xWCUbHBL%r|Z`O$9k-qTiv)KmbKD#tMoRylO(+Njc6s#PM2WGUU49*v`r(Hk^&3GY_`jmSb2opf0=#zTqxW4h*R+*E7%9Z1OY_*KH>_;YR*7tT2n99G z)%3F)eKsGwZ|hk(MR4R?#`Oj-F)A+3!@3w;ikKPT+-gNf)T@;)5HMbK=sz9)+6M2u zx|n>LmFLocf89T@Ua$M2foMR}H2@7j^1nR28a9KKqJSbQ{i?B0D+g705##7%ak?aO z#27=DG&hX>WwIQlJ(zpZ0JSEx$Zm=4WvOV9NjD>BpRNr9!6HXZq&i0CdVo`DbUU_~ z7yp~jfXMPGV-mIoo5L}7k7hHom|ybGtrp>E-4Ld>aCRWi8nE^NXTVhEX=o6CTomDL zrHZ1yGY2#BnK)(|2q|Tl`JU{RRRqt7BTfS3AQfG-{oi8oQHsOgj5uVHTB+2dWa=PQ zY^BEOMaob&SVW-3?}FkGr>c;wq0od_VlvRE>kxK%B9)wg0Zn*0nVcYw#k?7M)($+Z zR0?5+!1346(3G9h6p@3hmIupmYwZ7pCM7)Qu%vFU7!9cv=(| z_X|>k_27xATRXamBwuoiCL}^xQ?~&^>ol5~^@Oe;4G)J#Xl)STelNx;{<>eeEyM*l z`qlqu5mz6j(i}eEjHBz2pEY3xg_7Cypm<-pe}daT{RAUl-O5mz9GJlDvr z<4~ZH<~aKpqm;0TibjGBrBw1n71nxk4uu^Sk2LJuB=anC+zju9o1E*?%8+iR9m;>@ zBbby62Pw#i5^F_@S5Rp z(D=Imk8-(ZC%}Cac8fgpLQf&lxM$5^B??PQiC*X}f#P5Y{UF=xC;IwDJr1Ec2<{=x z)x<)7iB6_MwY=bHaWTVkG3|vHlo?jVHYXgPJA!_9zFazwF#m)~c|MP>)!y0}cBxmT z$jY(a=;5^+ho#rQI{5oawpRM~P%b;VS33OduOAvi!w^}n5bKtb=xODu=f z=gaoSfE)~;$2@^9ZKdP!@SYa_#?zXAc5uW^GKWFN)7eHN93KqZ67Xo+&jHM+{tE8h z+Z0W`dUFwVKLl6vu3hPUvr*K)}WL!r*ivU{I^joa@M`H3NFg( z9X50WI$nYX001BWNkl&wjbV-gGX4EPUUEs*1fww9fwoz>S$*$EQ zx_=iv1a{No+Ng}D@4CB9PlJACMy?Z`(lqO0y&j7~fQGaYdqPiege71WlLlf>IQbK^ zs`)H2tUL?<(+A~h5g3R6@n9>a&&yFwNJlWWPjm@53R@DK7HYf>bdnMze(4G@^J~Rm zX<4wAENB#3%aURP8S7ILRn8B@^12Y*iXq0@M@acXG$TG3{KiZsh9t+d7g(%qes*!- zKx8>DvWrE=@3w$O7xSr^Vus!$F{nT&;X!9akD*b{pun2C!UD^kAkoQjdKkp?%GG}! zFQ$^(*r17MDvna)%7KISrY)Gryfm-{T1a^vr1dT&~S($vMw9VYgl@Sb)zBcHyTzs=H0~3 z{IHFuX>(w(j7wHNhwTc>b)xekyrKD>d2k-=3Tq1ztw_Ve%7)evwCFGYTmE`98t~U~ zzwC{R`3(eofhb8Ue^hzU!Dv7^S@I%|C1G?ozzrhGf9BM;9@K3kc9Do%MIyG-$bzsY zqS51^yzqy(H;SezgHqYIO^0=*Mk5`D7$l})w3!CTHyRgv3~i z_nLgp>Tg@~Rvj_J4M(Aq;cB(*bev{3Ey~z;l*Hj+dWl6>b-AdM?Q|$hQjSHx)9!(c%TA))sg~1;tU6pnZV*-mV})8jkWWPP5^ypKMbo{fa&-ZdDX4pg(dk)q`6n_>4tDYaada1D`MMMPp#bxkU6v& zIMJ88cp&dz6vXQmls#hjEwbAN?2^Z}{#FXQR;$(CAwj>Rz;9h#d#eq})!)rp>BB#| zSKPjESUS9P?bS-t1#s|X2RELXbd!m8(^qH347JsE)&OZv5=S*R?P1-o1NiE5qJp$R>E z3&3;M(clrV=H||JlqTa!u zv8~stcuu?2E7HFE8cEh7U&S$6?;p1@u!dIg>d2d}1|wjuB&@(GEbxC z>z%a0PScufNhYNxF<+Z>3TBg9 zVZ10_cu`md1!pSW&Gpcm{R{TOD`AAa-{+j?m%5I-mD(n65@RXvdC&8lj{z_$Xv5MI zIyw2}4X(mYDX?&0{5I@ z=2Xd8N#8ac$VqbcJ>~8yLDNNeNuR_(Qjle2YT@!Fx?)DoydE(>U>yZK8bVl+e8RzL zA7Q)AqTTyYi0ER=UT|`zYzGs5XrrkJ=^R3Ae`?v)Ck)IK*2~~$8y3bGHB;F9px_3q zBV_~FjgfT$$yWskoV`q*9BCQFm9x-ddyW6X>6>A ziX`$`D=;OfOxP6$Etm>jbRKdo%QH%i^jLljq0kK72##%|`B#8+j9(Oh8G1Fgjk*N^ zSNVEV#m_>WncM;H%e8MXFNfsjO(aL>&)6^_aeLif%tyHLZ`oKn=mqV?1)IRI!{KzZ zFj)VP124h{jB z0nG{XaUo7=B0CGMNJ9~y3tdR?|04P-(ul7jXd}{Wlp{lkgBH%)96}dTBo5Ef24v5| zdm(Q|cqAaWn4nxbg5F;oEF+jQv9VP~AyRxb4RaE}Dqe;#i^gC9T#ATcJMwP`Hm?fe zmQiz9-UYCgL0D1!SHXkRLV+vj2i{0?oSYWq^b0ixmxWq+t~1x^z>4H&(O`OZ6N%9p z%`wXWN{pigy*snB7(AytTbpFio15va3OX5Pi@SJXvlC`87RJo87)F;#zp1E>Pklb4f9+yFcX%~_cTcdamf z_RM6iQ~ka7*5`*9P1`T7eP@(cni1WtY16`iz2}{Kmh0Aj*g1Oj>W9PbX$EE6^bodn z!K?e>y6Fe*4!~Eb?_dwi(=E5Z%;3;bXZ@gXtLb`fN(hkweTl_LH{F4cbC>NpdXm48C<5y#p>!#k}o!M;gSiY zoFEA{U_5c!$}lrC7)W3E;?CtOmxTeB6sGD%^9f~0{DuJ zX;(IOtlMq&Rtpi8>=CrHB7w<+IBIKoM}{$@mRsIMfzuXY5`~5+8bog82wECYKxl70 zunU|DemZg33C|EJhUK`M17{>(wF+K)4Bk?#iV?VhG|K|xH}4>%~|)+zZI9z@*@<+zp=*niYf^3-Y3Np$F^@v#9}N zW&vA4V^2`{ue`**+@jX1=Rxij*sf6FNk()aq@!mA(0{}YFdB^}=|9>J&`X3CBZOuJ zp@04dGbqP6M)p{UqO`E`werZk680_NEKsQ_96^RtYN!^V*fYv{V4^WnD}xr3pWy+% z8MH~ux!H=P`_sXk;6SSj7(@d+!hGuU<#$rrJdt0dMws+LsXC@G{a&#D~gFfoPbE z62+HW@r~6){AHQGBtcfeQnU~X`Q3;l{PA5Ox`M}B0GnKZzrR60sa* zfiJ+V0Bl0lP3Rxw%C$(1G9||Xj*vwci<|MSbY<%a9KztftR3`Y2;Bh&r$Kuwb43&b z!<94(&o8FQTNQR8X$dfZ8wzLi7y`%zsN;gq7_3;pSl&b>v1zo> zeiR08lqto6ODgRjzjp9Z{n2|8{66vdgMz_<@u>D|50c{Z@%3P?pBULa&Yivb<8i!t zH+QF6jT{bMX5kP0oUs$-PS?N4!eUhPdV50P*O*#Q%oO^~ySFD_)M`7`jy&KnxBjSl zwBFC3d-2E557&SE?m)0MxB1mtr=}qsimkdNZg-DAxqbcb=jL)bt6Hu8=61Tq?%zQd z5^cX-?Hx?Apn>CQLT|FG0UTyD&EDAhNnnfUj5TsRblI3OC=iQkq+yaAx082a&4;Ig<+i-IA8IVb zNVXo1IFM$A>`8PBw_;of3otvpa2I>QneA?@ilLWg2DR75EwEe)c+vgK%xHL)1X5EY zG$(nN8Mz@(aH0swi99SMa$woJ?0m4CEjVMbRLUuA7M3I@3`f%s3e(wGAv65|cBE{k zAOv^$J^)!LFS?Inh{sYaqhv;9FNQph6w)fQ7&BA-?8#<&^1a;E z6Cj4l3ihJ_VmLgLS&zk`G-9&?2!Vz+I&dGgNJ@PvgZ6j?lC?R(Vy6+9FfyKnAAdWB z!UoucE$E(+%^`r?^RSU{%-RRR#k01N#*zQl@>qF+dA0$AyCVDx;MG-9OF7(Ell%9I@o`cW^9HeMz|&sLBDS;Vpxs%J!40xIWd;$_OD zdVtfF4qU!K*$Qe1kq8YPbQ(}R#})BhrM!iP27&D&GM&qeipJ{{0q0uNAT*gaBbt(k z^ZxW46w>kdE(X*L=D_59HZAW({s+ah>u(1i&6;Z;XH(W{ANr4KzZyfI&aOdm56^{j z$5+?Bxzk_x^X*U9zIs|a*tz=6*{3>jKECeI^vRqy8+CIgU88H%&?R-4V01hGGawk} z+n-P55veQ38v6YG?W6Ac_tm3om-`C2g22zKcQ|%lH+hr>WNR-zDZF@o_TsblQQ1GV zuyz;hSTML|cy8TnhqZ-49lve!nZ#FZWncz$()f|BdlBpKUmF7v6@nrSLaxArDuASJDr{a`u9g{pthEp1_keI7lYaK&$Gv62r zrBH~Bi4B3~BJ9E!BW+-XrVD{VdL8y(>?+XzVDIPo9x2||xvs5qe4;q1tLHrL`~0}} zB5&i$Yd2gt)-~l}xhXUtd}CT}rScc@88L<4QVXF<7f6Agk_IA@NYH}KC38x}qA5vw zEJAAzm(Rsdjw7&q5|(4OI*uBN>chIIT+t;+GNmp$Mb*f>EB;#c zrAtNEl{tyj3N)aEmx=O{uY(4?e{A=Bp>qB zcJcFn`A#&S12cqv-mDLa@op~nTku#pmgO4CyWiWzMz$0)U6v?HO~u8!HpO+f*Dbnq z%zQULE@A3A{@NvyT5*z!`m)pY?kIrLg>Wk2(#K&1hPY=_5=nU|wKqe9V%{Gz*q^L- zcpK(oWHz~J$QmGIBh;BB0y>BmIY9_khYmtR!&nTWYe@WkKoR_>hRPk91>1JCiX~}N z`stI7p|VmslBa02k{wpLt89A7%IbuT@e-58c6Sw}G?Q%V2T6j4@U8~r0QPu>w%<>f zWB?69lRg<1lZNCb(OiYu3loPGAOXu;ARfB9u(05HWMvs9dnZd+l`5V}kSf*o67g7u z)KxEwNr`Z1W4a4oWv0!nc}X1Dt334}!0m&=($l9NLTDqx?J7~$CVAsP6~TtN zL|tW%3rkVHnw=nygT}#$?4J#dQ&EFv`Fag~3poSe)DoI!2y*>ghp`@ zUxktwesLlJyqokdggOSq5dauDR)~H=?7zV&Ji=N4hth#5N|9(~h^4jtl@|#cFE29! zTRYEdk-amE3lYPC3Uo@GSQn)cU>WM7vWjnQ%^CNN??mFaOB|*#CB@_O>D$C^81*&q zH5NRN1{&lo36>l2Z|xx~Uz&oq;~dm#XSMxOV|RD%w$Vl^8fyCu7e#5;oZ%66R^beN z4hFNk8A$X#Fy7dg@ogw;4*&hw=4NAM<^M>Zp zml>#o!29;i1mC^;BNc=HlSujB^XcY)4x?YhL38=tKfS%Y{N25GK3o3y!5FoOC<NpTBW+==P_2q?i%hk~n*6V&2*04Mr3EM`qUVlT| z&5Hn!-+Tc6;d$$(E3{lLj~W2`uJxhl7%$&Le-!Se<#XQ8q-0W!r5DhruA#+$Py1zk z*9wIotnR8E+)laZw+;^F6L$T;;C5XiEC$%E;jmv`AG*Ooy}a&Xv&;S*++}0g`^|fi z1k2lCz^SSfa5b4sBr$m=V=&s_WCAK0(3>ntR3gz^bgD8sHpHhvqr9QeW`I$$i=K?N zPrObLZI$phXvm7qHz{1^6u}-H4m;uCCTWxbR*HtxCzIjWiJFtb;Wne_)ddeJw8v=L zK6&4J_mhypZ4HDuGuO9nMregH=@qAJ0@#U(Fmdou&h+YRGv!aZn{H%XslbC3Q?- zmd4i@la>r(qXw-EnhE2$GZWQ$1LIr)t@8oG=O}GSg+VHn9oVUqrqHt!ScwNIW7HzV z2B!zvK^6}aInc(LwN$pxvoL6kz$}07*i#I0;>^xYl$&K4jFL)AVHhyIMyRjAcy$h< zY*yW`xN~l05Eb+q;^uM}|3YlEg0OHP+2z-%BSaVQq=Q;M86@@jGz{Rz0z4+yiqb(j zkUGIc@YK#m&`GoVrGbG92*5(=j5~=^LMfsXY<(GFr}<>(26w9#f8`Y2?itjgm24;Jb8|*{dy{ zfypdajVP1PyqNhMw42|pl{R*vy0Y(PRF%N`wqb~ee0edmN9nIqG+)L7e0go{lTY}> z(pPq*HIg$}@PfLZ>@k2|yPVlzLrl(wA@shB;@G1oxR%-5Tdd&|-ZgYyJX>tcFYaf~ z43BG?hcDLbc3@*4%FZOZR#G??W~A8LcYkyT?1O9b1pz*v#nEe?YhD;5aB~#O@$ySw zH=EyG_)=H{c9CYO5; zE__M~)`M4edj1ZWL3C?`zs=UD_^9QZjzoBMkXQV3-vwY1Q0U_RTk0b8H>URkS2K}^ zH%6kXD{o$LQ)q>8i0)n+2UKeMEE)9j8pb*U-gF}pw;y1XRtT`B;t4vi4Rm+rB6DD` zw!^m-SQ(Eb<_xvdrNgp6Xr3MqoL?Kcj@}qAfHk9*NZQW5`sp98zMXj3?G9ZHp`R?- zb?F(1fMINPZ9W}yt2<1VP%6Kk7nL1#7mk{gl$;?_tk_8=u zNnIAQimk5a{jsw97nWTts)fSM${jP;EtYIhXs1DDIj5bJ%kC%WJCaqao_Cwzyeo=w zg0HStz%AF+Xn%+Nvfg1Dv2)U1IFre6r$ewLOh!5)?gA- zF!@+8pO}$k;wlN8R8U8UdGu*Ab{Y&PpV;g3_h_*&6o(aRNj+iEl?E$L8WC0?>?wXS zFezPhI2>frOCd1F_S;W-o@xxktcckGPrB7E9NBBrc+{>K@>Z(h)oO(*hOj}bS2gG* zgkynrh7*#Zy#g0wNs<(+UC{=3Nef?XhM7eh6+W)cEUik`T!rMa5-t=xM$r|bHVVhb z$Jq*{NClKw(Iq8Lsym6Ur0h&ZOWtUOu7;V319Gsk2iT3WUllZRo+0AWP_=NN_zln( zA`Hgnve`RXM9tCEos{cKV(A-YC2ao;2Dt&b&qQhDa#>l02TZ1CbL@ZZ3Luxp1){BH z0oIg;%PT2`V2S1Clo*{Nfg`1jFv2VXC|9nphymxoUqU!$qZ2E$QG@CCuV1jcvp|R5 zjZGZkK||tLB8WAZEK_{I!Qg2897+TOn~_-XNhowW6-4+<2!|>M6X>2*2n=pVKwSG0 ztqhI}M?z212~`xb<(-leG_LtvBC(_KTpA`!HQQ8r9(rrc*a+|T?F3014vOR3b6aWS zxFrR2*n=tiV5GNUSE@+?_mK#2ys;w&T$244;N6}tWsqYrcqR^O_wyPZM{~7#m~Lr@ z#V?7_86N4av_ZrL!Y)HvfXS@Dvm?_!TZXvBnY$N%)s{Du#GO& z?7ORJflX31w-|Oqkbdj_Im^-i37s5IoX^!WX!YA$K5rl%e?0u~v*qSD@7z0j_oKV6 zE!gljaqAH{eEpTj3WWYQTh|iXRC-3^r~H^^{205zAyp6@%4b<^xy9yR-xwdM#c_ROEJeSZ4%nKNgvOrQGbqc2XKN`v=4 zI`@n6qu-8gEwvwC|9$P7Euqx^9J?_%V*bX)v$6Xcg0<0B`!5~9>;3P)t{px~-Fz(v z%8{GjDf((ShsI6z-_W&e05PvMIH6fo-zf1sgRmeKH_~hne|S>IY-@)ih`z zFjJqe5rHSBjVSt>`hu|_UcbY)G@3`U!fl~;VD%SUk5D}b@+$<6wknQRK+kCy^A!C{IWrCJq*ZiGe#^(eHKUXoIdOBkUgZp0 z2qi!nh@O7?uMYw6+n;l|Tf_hGNud#5E-)VHQ|t{ilm(>92t za-9PkLiyHiU*3r!b~oI`(0QB!=`amO@;%)`gE6Qc$G?Fri}_b!8imosfLv(S2s0In z<7EJFcsWBqQV}ZX8VpH-r*e6w;9llLx|m;1=8Hm)vFt@aC6vvjJToej?A0a+001BW zNkl%{ma9XNC8*OEh#X@O!yI_@;OU&X}wqX3V3W=idTw?8RG9f^{ z3(9OIAbhq^jwHvvMI%zMh}J<&mn{p?9O!EJHjy|MPK(8G0={5iu$NX#LSsJNAhLc%jN~-I0I{i0b`7u(5gYAv|#jAFL*7t$-wH+Afe-9x$+nQ z9b%?dD8x1-)FkbF>J3329h$6!5ZY0JXILJiSPA~4Z{#r$8O|knIyUZb9&quC0d%+9 zb!z(63d*v$^L08M2Yg=%q#}yL#X1I`a%3kRz)sAeL5^bx%L+sfqR8opA{+|~VSgYB zkd88JfN2|4V<8h-$8jiSU=qDQnnmN0d|*K>jl6nFps^iG3EJ8!dG;@6+16mMVFMh) z+}R(a${F2*@B?EXTyJJmfX^k`kK(p1#4sCQW5H2<=|PjV!2-uH@YI)@+0A(NRekdo zn+-5shP9{3X9(ZmHn?T8o41ZY$vPy+m;)n^s?LmN2&54nY0t=sxjL-80=Wv-C9wipRbJdv#P+s8zOseD5Yk?hODBY`rDmTfeTg`eE)+2%9rb+nNL^cO>Up-`k z)HhMV(6n#Gs|f9iH=8X6ZStkh1TG$Zc=9}=v+reWyqEtx(mbz^X2~c2q+LF``Sp|U z9^bfEzP)gW(5e^K>+++)0%Ta#tvi~eQSNh{s}&7>T?ellM!eo%{nJ_b&^!Iv`RT7t zeeu`dO_3oVUjB8teK$O|-G2OsOIr*3g1qGyf4On_kbMi!wjQ?Gfy6Y*_68==fZ&(E z{N&>8k3D69*&h~SrigIVgJk-DJ6gYR(tZRiX7F<-2N3Re%oEyybNbjgf~kc*8edop zyg2_k=gWj#76EhTYevpIhPq%poF-M?xU&X%mB*KjEh_NBZ$uwJl#AYI$`$pXbi_k5 zo&~k)mO*)*++M3amFcY23()p@+ z_o2v1h)j=yy*L_|0~@N3W-NyQI&T|t_^CT)|KH&hU3FXOjtS$KLe1ion$svn)1qV@ z_RGQc-B=(@I2DfT>+aK4f=DZ7?8Cn~z5>j23B<1OBUZo~*K`qk zkYaWdqEQ&TT@R8p!YehQL2i^YP-hhu8tg`l7Go;qDV11Z^#j*54;u6r?ZIKhXfX&H zXF!5alCdyX#!*h2YmD6}AR`Ns=>6pkhSb7u_lwIIMDGJxGj7x`$k%*L5Ea23s3$Ds zA;uC$Tv*O0q10Mt2uBIz7+_lnYW`#)nFz{3Z>eO_epK2PXiX-V(;>f+wo$ZDx*&hH ztz99uUeH^C+UtaF zQz(}w_aedL;N)(EDl2ayqO}ZysFpx4x{t8S1r`sygGhw}s|pGg@E5erl}d0R*c%zp znuKoPNz^i+sE`%H!g%+D_(me3t8!w1L=Jg|;EoE$(VR$+(Xi$~6R_N?jXQsII$bL( z2M%X|*_4<}yX2+|GG}^%k^PLC1z(^WU=%c!(SpK0CjvO+l*cEx@xCZZ7_bUv69aWv z@)Ea$Q``m$`{ zm7v#C%9!GedTv23EufYX*vlec87gBIAI+#789Uk@M#D3#PcRL>=rXFeAiSCpnmdEx zbDV)3cXaEk%B-Gn;9GOJVord)S0#HkLTEMy&#`0)jwVKXXj_BO@M;eNY09-8fbMP* zs&Nw_uk2|L8t5i0Qz(yUId30+c=!7OE7GX+xBXu0?}@*c@sx_x?eg=FuWwzSe^dVB z{1MJQ-#Ygye<>p8o^So;-jipC>upvUnQ8_FUxVX)CB+-^X?WrE*(fGN5Cp`pD)=e#8%>eub4yH}9ka}h{ z+k+$E20C_u`2YUt0}S}TZ-0iZ2@#_G3y?wUIGZ;`tC*pi`eN>_83_VOb#ADWZvKo$ zwXGDj(;2dCff8>F1cnUE%1x==Op69NRbFj$jItZqTjbJ=7Evd$++wIUfbcE6885&j zdZf!wVjhR0t*?fF-|-cfqb39g1LzfCF(gz>Yz`x$((QJliqJK#D`U=-h3V`=1ud-h zz<}mBR>Z2Eg4gJPy}!^eyInXbAKUvJJg+b#iM|V=0C2mWoAI4+5V{g1TBzNb@gNy25ue z$z9eiBs0)d2`L8fVqc8xjbu^&l$a!0MDYToR#qXCOjwx&iwcuWqb#BcSoknZMREng zHK2mF(D@rIAf7`&H6hr$od_njy@Jqi2nU(Z;ngAZG38oZ@KPh4v?58kd@TXlPw4^{ zIxM)n2d10gco}~sf+%A^B-ZgBRap^lX>zbPSphZ!yw%Z*CgD&Jqh{oIR0Mm4>SA~u zN+3>}L+C*W@XCQSBv_O1BWWoEdVx8Ko~#Ts3mT3z3ZGq$0OGL1T>x(YU0N>Ra&vUIFNmryIZ#W*62`lV1PWrHMyq%declz!-k?JNfxXuHGtbk5H> ze__92_jTRRW7@z6qXjw|!%&j7h^o{D@qikM?9>h@i zh3iL8)^GGJoipu6)H=wIykTVF5%3p1MizR+=)u{ZfVuV^kpM4POWy@M1RD2m+Ad&u z@a4^sFyLQ0E=XlZswQIhFQE}#d+Z|0H5kf_P~$dVZR$h6JLz<7w#Y5B14#fbut+J^GHD2gSf;?M;FS#~ew0f8t^TZ96K5PC+ zPN&UOleM*UkXr8@&dwJ#QVfn?VsZnMd{gr*F}$xn^S?ySq&w^jb{rJ7`oc9sGp^(W z8WwWXVc(!Yug}4)E!qg3s00pfqx}~M9Cm*T&#w{m2?=&PYjQLkO4?~CkSjci(kv&4 zvBQ~1B?Fx-%$k$~J6J(uB;5%MF@|6o6K%+>6v$8A;K!IX=T!kMFF@qntD%uF3>$C_ zsgq&YeF3}(-~jF}V=7&SBC95di_FPZ=3!;=W%PZxJjw+ZQx06k!VPqn$w@H`+(EbFqNUa6emYc83&DAzuR=w}3K+7X`)E zcoAagLg9U35*MC)fI@{X2GgLy&G_55h+4)rl^SUdq~oQc#!bboP^wassTXx7W4+i! zol$cr01WVDGKN4atABUb;_@5#yDLz<%f+yOFcnwSLeriEr_rV$_yn(yS4;J`$n#h$ zk^N%zyV^uF=&-ULj1^V6Vz1D}HcsR`d=l=77Eq|s03v+29yB9z52>HGD+oP)I z&V?08IbiRIuyZ<@#?d3wF7vheeRXF{L~X0j*zP$*TnBcHHqPTzYs>-Mig^g4w`OnZhdMb8se&8FN_Ja>pG+oszY=Mg38j zrNF2Xbas#(U85)~_|iqJ#p)20*Fj@Z81+kNXb>Xo>~Ta5>MgHOj4k}RMgvpLQKR-s z5VjW1WB1ERH14_c?j=+g3K7Pv8RbZ2Xt9=hy;=p`3}N;XE-&@U&}AjcctMnCu1pjWF+O z3eT`Nt&-^w1zD&c45d$yd4=f7WE%44^psUe2!~EauAwMeIPNxN+nedkL9b~OZZ z7;<&y>U89}pvysM6{ZVev%`Q7$%W=56fPJ(J|_F6=ou#%A6T!PTU;viq#M}pip6}< zJ`opgNEZu%k+tE6m>LedapW>yQ>B7Lq*+1>EH{dWf7W%BA9)lkukD?u3{L9W-({1cj-DZbI;k zG%O8(9t$x>G-Z4j0_U|&2)8iBMj{rHHW1Jer>l4*jw6e}(CAoczZ_fAm2)cEdzF{wbKlS_$tU?BR{H&Nen6qE&h`BS^3cMn=&dYx_ z`nhFs-b)u!i^NwmDm5CbYRRLuf>54Yz57MwH;;F#ulC>Jp!1(U_~zXISFqvg(bN5B z0B|d7k|`UML|Ga( z!N8yh$b1gX^V5wr*VnghJ%kg9h9w-%6&rCVVOjw#e??Z*5r40;OkgNsl% ze>R$hdoI?EZh`muyDTN~1B&4QCiKR(=pF8#wH6laItJSZeEDd>ZYHD~$tq;XJ->J7 z*Pe@pnpf2^3&9cdt9C5w3=O&zE}6`V(kcZFsj&NQ?cfR>TWfr@0O5!=2G#(UtI(W1 z{%vT~R6}>mBTZe#qr=bM2YNSuf5V zTZG-V$^%S265mYgtmtH&jRP|1ZI=_m=O6+oot+wC7@5vtl+Phq!{>0gI$?)aEI4Z0 z?rk58yn>;pPGoEZJ5J4^q-E))-f;`9g~$u~EJ0|ZeHd>S6mUcy2NuI}n?GfBl4d`n zED7xlW#m6=f+au~zm|I8GLZK)$oeC9xp(Ro^mT`qYRt}Z2a)ugXF;J*-tQ`)#l58^ zp~mH28Nz3{i`>f)VhKB5s^l?ePHABhyuD?iy25w!!i#&$*a9Cf%RRRLGC~WJXkoq; z$7sC&XfM{I}M?&cbZ2wIrXCW^~)u7QKW?`iTt{Gk#5}usKsyO|-DPp1J ztFAFWCFt8`wIpj8VToU7mlE>rQLXmj-)X@&}LYQ|BtS#eQoPLqtWa1 z5=10L#+4&amSjs-EVW%^%atXgL@rsz=9?|7)ymAQS3LB~Qqwd?+Z!1fpHIp_H)$wuqgj(sKDiX-m1=XuV{g)+Eo zjc(wXivV9#CzVI4I8-I(%G(J1M&+9F^ch?{l)E$CdG;*I%S^TEy0rIvv+w_8Pd+EZ zGLz-6sb5&0n|*0=barL-_(Xqku`+GSgF1?Ss76qTZ4GTlEi-1;4hFLTHc1>U9Zb)m zL&20asMb|$k6MG;_kVdRd$)CY=^noIoc;8-PMv;z0GNIC{4ZW~?=5#s>hmyYvfa6L zC^#5=cr-Wg9sOvoqb4M!znVO$aNN=*uVtLS(@e%vv6aP4N)oEJ(Fqy9s@C?%8Te*! zsS5!9@yhJ5X#sJQpv05f#qi3{)rG`1U~`}L1y`h=gw_fi7}le3lA9K293V9e)65Rj zop;;k^18e}h@oAMdfgSNzSlO>=V21`FoFYv=TWMjl^Nr1KftVd(z^b`rB_{d6fsOt z(=>O$R?K8Fs@|wcMhW>+DrRI#-0-TPiK$mK#F|Yjz_hO#=_Y2-jFx7qWs?Pd5NmNt z&Fn}^s|=dP>144R0c^L4L9_{*qM8~$peO&Q!J-Na04z^7c~ng+H6hQs3f8+Sm69LQ z)>4E@-_oiiNU?~X961Ztrcl{nac>-h<%yYQ78)uvT}7`2*n-Uec+LZw8e4+H6@lR< zDvVQ4L#QiFW_eDhbecV_v*}n<8;9wGTD}~Xv*lT#p=%Dnt~2OyI(A{xMc5GokA&*( zf~Ha_<$%!D7QAl*8wReTI~ZPFtb5Py3W5q{hD5dmuP^4ts01zr*(=E6Lpf7pD9suq zwkyHfq#7*bUkRahma?|sH5*bnN!P$8mRP3(?Q=B|SmjaS&X{t%{+d8#bgkeMND1uLm=* zAZ%!?*bCi=7tz#!6pmhqS(0&LFxI?9jiiJyI;21ycVi7)gjpCfYf|Fkkz$c8gxCXz z2*3eopyj`64IR=#gV#K3ySTbS5GBH}0?5M(_|{ncYv&f&We*GV+Fc&)26lK*?ThU% zP9DB6EJzL)@Y$tiVDuk(5HJtZQP`vAqcBSvT*;)1V>cfraWo%AP&9p~S+%w>G~qUt6Fpsdf=#X->MU z-T4`99mV9&unfUeEZa*84G(opItPtON}pSEH*eh?2oTG=5kX=a=^97k>M($$D<98>wS_M^7iw z%)cTO8$%K(Z*v%V)nqFnI|PWxCPVmU@KiZ`YjV^qfPutdyOVq++npRnL60gS21}lM zHzF66T(lt3t9y^4s$C_TVCP8xv^MFsK%~?(pH}%;jaBH*?%Ps`{(Rp$N+q zB%Pal>JCO6$Kd*}mrlAq<}y^!#8O4DRtz9LqQc-Snr*n*)G;feEmo;$NR-vKhJ#|} zD^44bqoymR1iklV@?;8X%V1~@~Oh0eioc~>Yz6VOo=7y<2uBX|mFmBN2>DE7S} zTvyn$@M1S&vZC(ZcxZ<%UkIef{aa&+EksV@)97#fZk7^`lkbKEc|))w2_u%9Lp}MZ zC-;bw`HuGzA$`HRSC}u>zLY+XAsB0nF_lP;?g<|Ifv8YlvFo>3WL+@)OK3;B8iG(7 zl}ONEp{3!7AEGOKZ(+Rx-gxO1-v}KkzF++5Az08Ll1Cb}Tvho3@{IAVF%;UTxz9FX zxa>v3OvMAXDTK}WJ065FjDt<9U#GBUHV3N z-boAi()}1lTtNhh1#E>O7tY8R0fPmF!x%`1SJU;nAZs|2)B@m0GQFLyBitE59A0mA z1cEDMZ%_*j7)q@weh^jFECogcCQM3lSbvl-mEQ^BFxm6dmn zAD=k3m|ASZ2+VP>W>_hdg8sG`t6^GxHNA3~LMu3#1_Q&7_kJ&b2FvZ%a1lH#M%w$) z`SY(8KWu+=^z`Y|Z@m?2(Qu>R}?KwF_@#Lv?jS*RKPrijqES2g)} zFK}u;b59k|09sOAZ6`Fjlsv+g21uuPe01(zJfFSbzsX24xf&+th5rt-XBIW64hv6q z24neLk!@U_MgYK;Zhtk3V`xGe=22=s)^HMS+(@zOuPvR7+%d^f70qB&5wkWe5><>R zSHP;NJej7}zB+?6=E|&yr@0la0Oq)OO{sTB^PG*p$D})^QreMVQD+Q-+NYXWA3L@v7j_fJC&)HwBC^Q6wOT1<3J|9sw>fF9m}Ufd z(EYw9ZN-Kpo#fck*lLTJ8%+wsQu^??>Q^!yGeyTuHXmtp81u9%`fIVw%$f6OL4R7l zV!XcSyd7ptug7WkX|FE^#gJJ6Qv=$*AovQcjgw+&Ms3&~fn7Eo**!vagAOcqQVt-y65i*|Z2$#k;qDChwh4x)g`>1GanqIAEyx#R{J(=8IPuACy$!aFDo`w`_H6joU zl}mbioe>-I7Wpq*SNq!5eMYAj3rQZrlCVf+TXQ5?FOKYeabj7%*EZ1x4qJ0wOu$_* zv(R0g%%X9;;+WJJ26aZ7501%VlR`5n3w0?h86+d=MuSO{CTyu@*vGYBLca#KzhKWf z&rhBMQ7lWkQeDS5I`=%!c|k06W^Q9b;8>7%zOazUB<7GVnMYR=g0WB+oL`_GTA(*m zO3YdL0;q0&UYPL0f@Lk_1!$M79Zq#EMpZ6a3n0S4VrY>`fD?-okQolL z+A0$?%8QHVjE;9TZXk0B|^DL0Olt)^K;Qd4yoefoPf#(v@cRzVu^v20o7Qp|%V|Kc&B`=Zr z@WV?_*Up?-U&nQQ{lkkFFI>3r>)-$Q#*G`dZhijf#fxW8zkd3Ua|WEh`TpPE;_}`3 zC*!-jyDQTt9{%vs%83(4VgG$o?yS6lF2cU%Y;$CCvitDiZhMR=30ef`nBnr-Ml15l zQDkmt^rX4P^!vOne9v!wbZ7HeqjBus-J3T*_}!nK^R1|7Vz4$3>Jdke6nSkFl?tmA z8k6USPF-mObxgs4HUQkI9WP8hAlaQ%8`7aelbkl|uz8jOXdG5-9y!&gWel_$v0ams z=1kj$e8gwuY%|jtnrAd9txo^}Ri5gCbGNZW0#Qk4{|$|&m?8xiKYu5HG(F7r4{7DkWy zgo$(*;Af58xku63E!wu39B7KA&YP8C3a_+X?dvU4qU8vebpHF=AdZ)N@}r(Sdi2PV zBa>rBzl9yHx{R=@)g0y?U>{e^O6T`OKkTfgQ)cab6*SJK8np0Y{_MgG%(N9|X}OwB ziKt2W0cntktBzuI7E_yNlT%|I%!Cpw*Rx8^i%>y#3L8P50(usZmtXhRgLSxl1rt4< zI?^b;EKcw#ISxj{7(04V*nmd%FC)U9>qxZ{hFkH$b@Uhm$_RRY>qOmJ6cHVDPo>Tb zs|c3Af~nf=TZz!!v=ymrdD(+RAchy2vung)3D0F6lbC|fM{iL8S+85g8RzBaRMp~}R?J;4y0>?<&5FEz*8bMd+FiKG& z9f)Ci43G{8L@sMFFc4UP^p8TE<+)`*s33N4`)$NbcD&uoFTo_}-eFCG?xkTEg6P;V zayU8yNau(R{{ma#;Vv$XyE=X#sEOYd?^LuNuA>qd;sKnT$#K6IXJ^4FhC^fAEMyou zKY*||>}&hdvmLApw0cp*Ab9Kdsq;t>xf3QNZoW_q?1kY7`B)6iLeDRBo^WG?3CZz! zdCBKZH&P5x|*T00tQ6ayJpsk|-TQJ`px{wx2un{d)d8`b$t(Gl;Vqozo z{JyLY2Gt!!>!2kFJvyqbM-~9P1j8}<8LIq-s+T$EF7q3cZ*4JA$_xCK3OFA?nS_x4 z@NYhOUH5R|8M;F(+1!TPypvhw1c?MB&ai73(Pz`z5_HiI4Tp%&d8*(bmTiCfy| z{S`3oWj}uF_)pvJx!TT$S-N9JtBx`G7Bx3QI|7xY#af}{7=0Ip22^7?J*wtnpq5SmiuSP&GDveqt-1#;;K$xb9j&fW zym5Lp1A6r4j;|(H5rNg7N(borO{QW2 zU~h`Rn~bHB46sVKQ+b6(Llz`~<*GnBKyDo9XpgmDUma#KLlU}YDy;%t$-wPi8jk{W z_yVD?3r_~wbe~+pq=)mY2JR(XJ5df=UZ}V;FxsVjT#`8pfVCfW(a$ zdkY15mrYdku%NO$k0h*m6p3e#@r!|6N-ljdERkon<(FbR>YG9XaMbGwd)nYf3WD86 zgYkMe%&;s}ZN;Itiu-(>K1`c2fQ}=GFAROOu7g7e;|R5J7wnx87=}U=)ObS<&d?ai zCZx7dxHGf?(1kiBT$mTGfFO>}0--rH2mO`6Y-S>Zmu0vFo(pYk0GjXTLxr{i-Mp6< z@)P$98wE>vFCwvkvGN~Tv@0zkS|bleoWHC+NE243kSHYP^45~PMDT29X#z{$r4m$J zrBYt7c85@0ov1D%I@)4y?*i1$6f9%0Yk@PPiJ@dIqW7pYTCOgZbpyNz8!)4wt27|( z@F7c)8)D=&7VIKY<`BB_TL4Z@BZuV-@f?fuXjHB_Pfo!z0dac_L}mc zm*;vj-c)R6{M6Aag1yD=BV%J@whg6D(M7t3DLpdmSHm_M%(>F#FGbJhhPz+WgVZom zBUjBxPAmQ2L?GfVTNrRTcu&z5HH5kd=Au`qZ=dO9z|+u11A^sMhc?To734N06vEI3 zgjmpaW+px#(nvU7wF(UXI_T09iX0Embl%MN?Yn=C?0H1*ju<7h(LS3|^qYNs#gE_p z$dw!bNofXUFu6!C~rEPpg5# z>~=ND1EB314-?O0xQ=$SdJsRA&EIw+cM|K}DHhlS8I!?EBspFYDE0(B!g{yiN%BUb zeiR*HSh8^43KX)CTnVrBA+pj_LsUl% z>MRc-nT1LIDL)s=!jjP+3~g6*s}^Mt)>Z@oloe0SAIU|z48}*T;z#HPA}NLO3O^RK z1qB`u==CFn5?CxR5kMZmDuWSrAt^DV<5l>%Hy0x50+t z5k>;#Fbb5QtwM|kL{~zLdxrtR9seWiT6>#3%xLYzkuQ}6ShjMRO=>5;q)tfGkc(pz zZ$|A>sW?@X$z4?~5f;XarCin}5kd_Fk}h0%=2{G?^&-0uMrpT}xRb!UjdLD%gt>D8#YY`a@d(x)r zN(!-BL6$dwPRmDCz0q2Y2oCf&Y@lBlM7VmxbBGXCD;j>TR>4>Zq2={a;w-_Lmx+WI zI4YOFnyl(Pl6x#ByO9HpP6lLQ;g-w35wm9GU-4lVGNDV{7CyCvt_xU?m{jQoOxsvI zXvx@^O8^TJ3J5W?bGxqLu*JhyAmn!Eassnqw=LxA>q91`JU5v+A_Vsc6Db4kK=PU` z6tY2ZWeZ`ld?XnT&4k0(1cO5X_7f&;AqcK=1E9RZeQ^acITMbCa`Bue6rG`W80j6r zIn)lyEfC!})~wMaF?NU&WRwxMan+h)`H=@jf`Y>g%NS}~3W4=vsN6yP9Yn$vbkI@S zeh1-G@~{dRZAj$1todyt!DSf|s*$t^xQ(_WY<-b=*(NLU{2m_unuoqA}20WEFV5@@duH6OzD-`Q3 zgCHBYJoWK>zGb*}`s)k)xG8-2E5PP=4(%BOZ~ky$L1)^J&mX;e`|h=l!F%@(?!R*5 zqZ=#tuUFd4u|nvH68GOFf=huUEr{(~)ACK;mj_`w{`Tz5VBmxl*LnV2<)) z4=`9UZYm(xmbd&~@Yb!;XA8CcVdcSgmrV;e0lwVB0Eab>RnAFm0sOx>?PbDry9Q4- z7J;~See0_s9kuF0LM=n&)XUpn4X@0l*KE3Tb2ZwLn@|(1H?r1{0B3B3;waz;y6qEi z>R?@)21O1hoa;0vZ$3hE;<19=}xz6r_& zIU9It3H-eh;Q#&bptG~H=e0)pxt71E=3{>DtV*&8?s~@L9p*Bc(`oIH#NVd!bt7X0 zUv@T97;Y(eRSjL^%^GP|8hCB|%Rqbu)mTl|XidZ?qY~QqrWF4p3h)VSx`6mB!o{#K zU>lsc0Mb&fU5}g4iC`6UEP*!{M_3c~vj9*~WnnvJYd;=Bk%AS6VtS774D=kCjw6l| zh-#%ai}xYWQeamIt~~EH8<0$RI&!nP4Q9=QnVM+yF)hY~_Tm`t>}UR@U@3RMPGoSz zkTuz`F;?2mYC@oR12kCu!8*oZ)h`BvvAX6ue@rkr26&DI`-SZWkxVI=TNeyA_t(|q z`9hLOc~;9|mH~VHmA<_Qe)a)VePxw&0{a}t{P6gWmL2o^vCQ@Pg@9I4 z3ti>VYNRrjFktn23?N;Njc*z12&>S`0Fn!;jCC+T7La>>6#iiO@YYcww}R2fD0>Dl z!`TaqFJh!ys~j6t0xfr8!mJfY=mExLdJ~(G%0P($)<~mlJuiS<{ha*tZX`P55rFfM3nPpYrr;rLe&cZMVo4muE*C4{ zjF`P;quLLt#L zKK=I1hmZbq^5Mhu!+++Nm)pN?ukE?j)YWxs{MOCCH;s37J->N#W3M5@f;w9WalY7x zWB_qwIPKNxGsCbV-a^_~QAUb|>~eg*UjMVGc?EOl-nV+!hR+mVu?QF&;a;6is|pLh z%UcH7Edsd};8$MQsKT~b`oemz76G%0#0KcK7#-M1qI89kgvBkePM@iIu3b;$;2n5- z&8SzdRR;W1*XIRFp>)4nqZ?p;Q*8Y)s4C;3=d>;uLCsk@eE?LN-kkQTs##g2_8xG~ zT&O8VJrlpUW>qVbL7R2D9Vyh1Xlgo^hEmQ^6{cl|2nAu_)V8PU2uXndD+Kr-JxvuA zO--FWJ>|bLs(sZtgukb-V}3`0-3$npo=28**6=YC5~+2LMCS4rWb)eivX zV7k7UBWAxKx3K1huY&cs-S8EHHY%IZM%Ykac~sbKy}vTpi~@#cta$4QtUd%;!sCn0 zaHS91VW6#C`O3Hk_I>O}jAU7}1JLTP@|8h)B?!E?%EwR+A7s$g4!;ml)*hi42^hQy ze>hlMSjBh_wEQ}bf$BnJwZY+l8+eqdl=9$cHCmK_vyM@ORB{PC3O3xz#AgSVz-6rv zWg#CLoeWS}jkbee@)yc%Ur^e+)r$xa3gr(4mEg!bX*Fz0~OPF^GCMNC6( zoB4{tE5l?h!C4!63FTsU0&ML9!tz?;VA*WOzSj(L%Loo8b7WvZDzQNMT!OeOWMkpj zVr4c5pc(Afs3?aY$zl()05t=1Bs3)ymVN6vO6=MDsr%Ha<6$veV% zb4car3%kO7eQxAu3?zjLhmHg^{TW$TeOwO9RX{*Dl#}<}Sn!7NlsGC3;+`cqfaB0+ zp>$yc)96q%8PZB5H2%VBglLNqWIU#r$-(LG0G{CC&D2oG2vk#Tf~0LrC@5sNZ%2Hv zZE!G!aLKk*YEXU&-Hmq)MhDOVjBG4~Z6F(qRwIyMc^HFcT7Xm3R7cVFFp|Rhc*KLW zO9-H6JWCw|%*Yyo+bBB26lpl9)W3wUYXF02*Kf`}J7so?BwLW1GxO*ivwRA`166u$;sJ$lM}NO6BCCIU%dFffb!WhXU5j& z)Vm(bXD>8PFMp=I`N@g(t~E&BwVQ+M-3BTXnWspVarKI^Yd&=1em?K*yfyyz@;8q! z{qE9*4=(-bgS%fo7HGb6?Hjp#`|Wq%eR}`?zaRbU(W5*Tz?!%bQRk5{jgF*^NREh6 z0;@7%Y=L!wIhUBrW>r^vE`~Zn6+B}IE;P6oA(R|Dv!9_{<0*xP8geY`fICncB4>

t+8zv8FNQ>=v$|ge66>zlYxua*OyDYbb^WXH$!XmZzqd|-zh9d`Kd5+qbA=#q zMN?02e&x!Q>n+}F%O{_nzVXRP`Cd-$w>S@8B_++Cym9KZA&=s4Ji#1j%Cl?!Qu*sG zufHDqyk78eVzpthxIxb+RPwCSE0S*RInu@RGGpV60!D3| z!nsSjrsbf;>HI%e*Y?xqeTHjee=>IF*-%@N5f-uuK9obEA#lt`<^kKZrNLyAkh?09 zEu%Ti5WuU9#LS^4$pmT*h5&&~IaFapMeC?Eq$W!`x{c;~_q*K1w2NKrFWCD$zt3qJ zbMV?x{@ zvY^dwlRIm6?l|EqvM@I*o3+Rbx~YT(b0wTxYJ+IZqAdv1a#G{$#tIq_Ii*U=w7rcx zE!)D3F@es299!Z@es*UvZlbkZb)I4oOyF&ELX2gJA^^*hVGJb&(69uvY9Wf?=nlbF z3$mdxh>oI-uq_Zki(vq8o59q%vpZ0Na~LA5XtX052(Tv!Sz4gENQ@4^o`g$KL8FBM zwZL#4saPyQ-%>!qu;%x5m*lJ)8mvGG?%)#2kB}tU;QNh+O)y~9AJ8@(MPEr1(A@Gd zdD18Jwx}_V5)DY3m_Q3`3y5y94!DWf?9(WJ7Etwbx!Z((Bdyrdu(j2|4KR9t9b2v@ zZA(zKmwmn(X3e0vTp@GB>|#f-(Ml*#t--{E)GHMT-J%3sEiI2>3Kj;e`Zsn^LuujW z7cQf^tlNehEOcwt!GdHSvDwsG1Ibr*lQpZTZXJivax=;X?GTdKJ&m;fk^$`N9H-EUJc#c~4!&R=RY<~(^E%{N`Fvh4guS^$K8KPd{RvjV zi5vne+u=@9#eN~mpYzz~3i?AA+r>aAj&*o=W{R3JRy0XDM)+h~=3+9b@QayS%Wf zCoDjZ4XqY*+ulN6#|sx|j?#^pdAshsVXbQe?*ITG07*naR50M`8{oRv^J>nl5}RL( z-Y{fXDmBs=L94~D{GMH`RQ|eDUYeJa0Pyniix;1k=a-iRgO@6T&G$|!8ymmh*nhOY zf1qHS*m_tUpGls({gp6awKtaA=7ier-Z{84JG(06c~wa7!osaLPl_KKbXncdbu>QS z`ZWOfxeS7slPV$=a%DWGCAMF39N}02f!$ByH)Y3$f$yx^zXVR(w z7dWCAAdM*e^gU`DnzkNaGz3`Jl=$kJ(S(FzhKn`OrEuunSt_H)V?pkB!xTX?bpzK^ zDUX^oH_~Spv_kY?Rb@$Gdm2<&j#Ae?i@X9~1;k2sb-ot;eBMxFT_Fdi4> zpBZfd^vi&~K`T|OW0+8yDdbL!sXQn{-3&ESL|KVwC!%gDsiGE*8V1t8WX%Z+#ZuC+ z94pY3J7y*@!d*v_a?f5*B-uYkLlDC)`nhd3*3)Qe8lxVp6%_biWWTQw;4>G_@cY7* zYTtLdCNJNtMvi~>Zr9`wtj{CW{N%vUui{4_!+TSs-?dc7c=SXS^E#|h{rxDRXns05 zq-mFjI`<|%jBiIv-y8jm2M%gx+}x@ZTkB(RUty!m-Glrilg+iiR)iT@$yRk77U2q9 zS)lv-*}2@>Y#=stf;~4q&{VPM$cACDX~zwk3Mni7z|J~|p?5Gz2E>{yrmT=38hqJ# zWQjXZ-C3x#*r)*XG&$8y*(P|p13wW97Z9=Gjtl-~5lCsXSZu2H7mDXN5;yQ)_0`U^J?NS%D;XLi%j60D58d73__6 zbi^~T6>&2x0Gy$p7t?6L;taYMkZ~304EWnrAV+{+Bq*XgHajtBcKDGK%`(Ccf19%U z0%nm84Lug)H~d0@nF8(OiWkx=L1~BF0;EMtQiBirXfzN)8?7}N$&y|dp@?DYwG^_6;sCO0Wta6rRgx+q*&9xGr=V=z-Fi;!4B{LI<%7D|p>kA?JV zLSnVv$LRWXH56MMs2W7Cp?o=9MUvqnqBmShlJ!^~BXHhZ8%E=0S`cdK(pui43keN` zNJWDeEsF|EJLP=xRuMJ}+6!Ptz%zYrcBF^baTn|a{k45*RW{&8#f9tb47w%y%Gr+9 zu3{)XSP@%;Kxb4D((WkmYgQ#N3@l(U5OCItz6H5Scy3zoH{}WCkZ3P>ob#-K{{{s! z*94tm_ss>FyiuP|B!I%XLO7@g(ToHma4uX3>mb4MU>%|>J(1HxIo1aYIri2%3Bz7J z#866|psVMEMur7&^D8K1fcXc8;Si%JIc{zT>?vz*A0n!}gXlpRtl5#KW5igDlVSFS z*9dwn%Chhj$g#YG=mrK3_YGnitwTqJn&9bJ0+0?skM+SNJk8#P&|m?ZVM4yn2oFr8 zvBWMERuT$(l@j~OpyKeJ8%M*#-_l?Wf5Ur+$7^|5J+I55l?rRP$B2}CN9};$H+H}R zz)OO`Wx?OOK;Rd5KbvLUqlb?UxCH*?`+(cORmX<~fY0yO z=&sy4`>{M@zEZ{)PL;~y$q8rL4VzS_YOdu$tI*$8!(tOT z>KM?oPuZ|Q$un$6h7|f5x4=xO1Y^DUO;Xm`>J;K*Qg~0xTiTko6L;|*Pub;N4nFLW z!_go!I8yfdlpwFN38xwx!}l4)@hW*kq44=vaU4bmgQCB1CtW#rF8SN51DEYj*(0c8 zp)iJKe3OzXDGM*DB1&?({+t+7N;3mvkThjTdm}vfP~+of<(O64Y0hM4_CCM=v`79- zd&hFx8x};bJ|9dgX4*RbC$}$sJVS|Bn_;Va79LEQK9H^?u%Ou^+ zP$^@)Er$lrCx80q>hTXppC@PJEq!zJbdP_Dq#9DI*iHG5M8^8Z#^kp3m}8#WaN29svmj;Y3*)qa*;eKAEKv7BfU^xABdD{`vVbY_2y&y%anuaD5y#=&F{4<)3Bo&Kvh5&j5=Svd=_z(h=+Ez zWsrasRfP=n1;_tRwN(a^=*>)LH>0t-JEBP1K<%LVO(+)Vl}83TyGvAD$vF}yOVLgw zb_lISHitm%W{00R-I>`80AvGDMmvzs;X??Az_LRF4`%%lyh?tyGc*_#g$)5Db2Op& z$kBoPNx#Mf4hW^8hIaT!ZA-|T#8BDcFE+qzgsdzF5K=2{F$bDL=wk7Y*zv+uL@{;I z1vc!*8W>AqRx!9V=2Qy&`g)sOLZy+6MM8_31`L^tV7bKHq9!ohvgLvo$whgzJn$DR zMM99rTQ(bVM{y8lV;2WXESW=z8fm*-j;|0tS!bdU%WN}QVL&pYl92IMs6^t{7t&{# zkr>c{pHrI(rnG|E+7L(y%>7a@mw{Ox=5Zi&K;bYXD%QqeBeDq^Q=TBnFarBLxfDgD zVNWQ`YKEK;V|iRoet%J)mb0)G{$CIBon?B^XIpdBJ4CVrZSwp_|Y{D{L|dqxLA6Sdsg^NV3cc+ni?QZ!8f*Y_qUZHU)Dd z+ouFn?V&;32c|paRYgcKZ{HL+aEzg|MQ_Jm+IHiUHz#xgxJ7;Jipge)v$n53VaKGI03L zKPM(yuYC2B53ar3@0yzhafStI4lG)}fxa|F{hzCI{cY+#<9L0EWyh)&JBvk~*@_%v z$C2%T>cwElf|AIZA=Xac;B7_s4bDRK?zvufr-wO(_FP5e>bVJ(-r;3&ZSRad) z=(%V)j*|7#fMUJoR(&tbt_F&73iQrgQM_8+u&}33t9fa#l3^c{T2R6@cYE)%E z+A6w8jKIocR9LirnLE+pAypqT5Nc^LdC={R4T`&7f4$Z~gs8Oi(1z6RHOvXVYqBHYTkc zM-^>->EHU!zLwQw_xU%E9{n(KbtyS|W@pz}m-icCj04Mm9NRXw|Gr|n+JOohD218} z>r>1)h^cWXyi^2!^>ht?|NHVqZ*T9$-nTaPZXEpP!@ZLaAI_Y;8#_Dp{@tbJokzaz z-_|}b{%~cMo1>}Ki`xUU7UAc=Ys#q4^l!NG&aak|-J!i-!ujvc?O0A)CBeqM1g|X? zYvUTTrM_qrZ&fh2Dm8=AF(U%UO&l{WXH)f5zcVo?E&M**J=46KEK2CFo$g;df@Gf{ zWZ4PHwNchB@~&>vreN&9uxibplxzJq0pIwdO<)!qvG2LY zaL7?Q9B4qw6a5?~HahO)(|9T4gzlzGS`3`=3n)7~wVH5|sA&94(PyRjTxTcI9bj=j zBfv@`bVj&vNdQ_9I!^oVTqZl0%?gK3N2+N}gbsO`LZ{{FsNiKflJ*K+Rl^cWXD}E| zG_`|TDNF(f(Ues=wd#$WsCq*IZE(0#lwdk_inq2sWbCn8L zY1A|NtF{V4EZDH%ZrlDQttWgR|B+m+RCs@robrZSeo&rs6Xy15B9_nLvw@^}cE1|e zf;!$!@P_@eHX>QIgu8|95)RFgMu*bgMr}xPxINHawH`SdO&%6RSKe71I;SQCi|B!i z?7VpA!GeJni*D4R=5}OQ&E!t1W|Tr;dDnvV3NuCxoj8OBy4~Zsc<9hDDBIF8tiIrc zrg0n=&>imRYfl^!sP!;h?&!JQ(JoI+6VD-3I57lRU+mE>a0=#o7~OFDxxNkpu}G&B zeCtqxn>v>;XcwGJ2uq$!p@wEROY>lA3%grg1gH89CZ>Xu%2rdBy$Jo40`P>XBMhb{ zQky2WOm9(W=6I@qqMzO)sBaL!l~eT?)_yr4kk95g7`)9O z8liNMw&LKVkaPj!zTotl04D&Ll4ILJ2zVP(arJFY|!HDa+ExBG8@OW(f;IU8t^3NM%$6>szhUafy;M_}} zUHk0XM}J~h3=95ZNh7d|#tLk80oQ#<76%TGYX+ryRJ9r>Y3#sZvq}tyg#mAItkArm zlV=luwP(FSUaO+ez;FElq#l^iI>I5da6#gLyjiVB@}u0);vn43(>yGdOy~ytDJjdsoMo0>9bz-qv^D zJ>R{$Z>+WS!HzTI;n?RbJBH7`+0{Q9i&ebr( z`Q_lQ!NEaf(7kUZ8@fER#qiW@F?psdJ{unQzkNQx{VLxLbrP{+ad}&4Hf9jFX4KmS zogT|A#r?fapBKBmd%up=l2bEBVaiDpG#R$aj;s~A{8)r*Sf2^J)XG8q_K=Xr>TY0b z0gN~xSu>%W1=BcO3)ed?MvOsUrt%Ml~cG^_)>{AX*GL}`g;MCA74Sm+~CDlT+0v0^I3>=rZB!GJ(%fTJ<2wVSk#T zbY?Cuh?&W6^$aZ(lWwmB+j-s zoepJaC^X(9A;v^f&T%{%!R31*M4VN+S`}E0R0*$iEkp#WvtF+^+A65rhSV8funR48 z2-x%rLlxeP4apl?h%jpQ5-u%(`jyL7k#oH2IBN4^1J034`4y%k4aCY(#t^84h?rE_ zv`f=8S_3&(TaMv06J<~|#2*1GbAuBM=&C7+Osqgoi;)(TQ>zEbrO8+>dJ1!p;WvD8 zOGd}9&#gJ6_T7Y|5q#xtaM+MV^I_Sv5H`5&_6BV%q{PV4U{e}Q45i~S;wm@xBf_v6 zfaw-fM+iDM>XNJFvApSUli%Fv@F0tJ>s>!ml*WtlMl?ims=Ni6{GcHKxdSHL!X(er zBeYmPV-oFY?-*+D6PnvY^@0F&g2gX#tHg8y_)R2ILUZA+bTRxraX9EX*VBPHxQ{M| z>0pPk8sS6g8BP)U%<%a(?jy`QL9+ptD{iC9N*#uFB5>-_vcWzSQIjbGD=`c8O!iOW z2}b6uX_Ebu#;|)>VD~(I3>pZnX;+<*}t|3d$!30A!+81R;Qgch%(Hek)!2u^I# zxadua(G(LRuvYAyKF4uJ&*;L0!za|cgeW=zWD9k6AHDm!-Pe3LY6j5VqiapS-2*>$ z3S0d~^84qhRN4Jja()S+%z*B>tet(0FuH{skH~1@;LV%S4>kAqDg#;tEzHsxpaNzCr`LjIC z|7&V0Jox0v@4x@<#u$TVOi>@-`U5X;<=(x2-@ErWH6J6{y0K(*&ol#D8I(y%2{jeE zsNDjja0m+NWKwe)G}*~yVyR;#d^fuNeDebRgR?mS{uZ;3IlX4YK-nDIOT3(&;&vegbw;x_vad+)|aJDP-aA0+2Mb7SCo|zpzd!#z6NM$rj z)>4_Bspdx;OAiy>7cYPK@jvDl_`9ojaB#z5?=E4%gG;%icknG2YsKZR&ZSs)%iC8I zKMOoGHG#a$%r@u1h^b*vV{gIetr3FV-@EnB>Y1&P&jl%$yhrZ{)h+&#|KWl)?=V*8 zdW({F{p!EeI7whu!?4nSMdF%qAt$X1V)e2`qg|_w%${ww#H-L>$P6QAMVsf|EjYH8`t;^GKl8cNxsq zdSSaVVEP#@<8Jb4KQP2sKvrE!&*@Hb3gRx3o)vfc?IkJ+1#~;(88pak zRs(0^&bT}+kSeSeFqTg<&q_?0g#ee*@y={#oJq57GiRPe( zFrJNaoZ3N*ND;wP&7_P(1%thjcqA~F4SB0+pqPdvnh9C|2IP-wG*k@<3hQtg|F1U? znF~edLRl9}Vj;n;5p^mBTB9JXx9VaVO>Ki*9jHV!ha)H09BNw#xU_JAyr9`o;Do#BK&jR@jHqlLxE(jm?y~dca-7*N{&F+(hy4TleaZG0?DIUI zZ#gfPq|k3mxgz&{`g}gm3nM8vL8Xp-?_^mLlV&Ie`ti?i?YF@-ZioE{5iVs;8`OPZ zyH2zHh!be5liOgM6Xgt*E{LNknYIZBmXnD+2~CN^S!s1b_lZDCbsur~T+C!>ISmPe z7R2rKL#pDet7QBYPFe(DM_tM<=PsadrC-P`G}1yL{79X|!Js4VNFirK?t;!a9)uV= zUMUET(es!aNgBOTVZH*`DSuqiHXe8DA^MW)Rt3Dr0J+$l!fF&9bl05^M@>bO8!G6r z@aQ0&Kk;aI6=9HrYC~!xv(;-A~hz-UB2 z%hgC5=fNB_V z`0^W3&@Bbc)sHQ}g($3S_iG)%LW;L203XgzP6+@XK6UZp8M4){ftY`hj~nNvxCB-P zJheVGzdnEYu0Zh0(PKAn-FkixVEgYDh_FsSxB~{9zqxkvlt4OHzdFdqEL)!Q9GNuP zG@os9eSV!w;T2V4aS^=okD;uwf5+($AH2AqKUL6f<-y1az^`7dnO5Vo7kWXbP)BhwrP1<^G_$l&rR4WO z)em!M9@)#eGxS*+39TS3AK8xK&i8|l&8A>4Y z$Sl2ecp2= zN7B2%*IBSQr=bp$-%TjZL@Z1L^j%jW!pqFK28B1$v6xv$Q7E#2(F?F2-=f^xGc3Pg9{1gS)efr8SD|TRw2Y?$ubtQ+mHrajyfeoNcWSl7De!#7PcZ` zLu}OmEXKlB`fxZBQ&W$zlfYJta0V65ehx;0k?hIRSJ!={miPb#OTsm<@V0l9Dm*eL~ zGyuzi8u{iL9X?|;P16$Q((FHC?p3wf{_Cqok6{H>Sm+K$Do2fSSwvyg$TO6X0)qp~ z6^OAwF39k>kY-QGRout4N`cmrR{8oWGP5c`ay`hPtngqpTrw^+7kX#URXC844Lx4c z%Ka}i(c^zG2hIq-LiC34=GJkfLE~Bl*7thShEL^k%SK%mM$iJpE?W{T zSpF%U$?G;j-Qr}@X0=_HzpA8m9$~pl=dU2JjXi~sV1fI}VPVZKr_+!5GbYhCgmM6h zFYzp7gZ7H9Bp|M412LdLu(l4A0R~|tLuZ2iO3s}juIj}&8bfEGuaIG3zd=Xp63oHz zXeJtj7g+Gw@m0owo?md?AjHnP_YDToPKYD!L0EtVp9jxlH0=%tX$gk5craQw>P9Fu zXs>%U-o;vmXkA;lZX;}i)}Ls&P*MapuiK5*zz+J3Fh$1XIm{lUFmI1CcoOE|F7V`z z5sb50lSCVETSs_=O-iGjP0Np2b)$cfl?)t5Q*bRmc9aQNN_Y`~MIJ1;kM{+fNh1kM z?y((TevRI46ag0+ehcMC8`mw_jcP)bXl1ioK7bGS@X`FOsXu;t?C8p6n2-RJlwc7x zbs~KZvtu}sCNIzb^|D-6xBv}6^1tSNK2H&r0Q=C^k01OAvC?a|1j~=j=GUjde}zTg z&C-iH{)`U+;6$wH+tVL@_u@VUT4!f3%+9WSMEC{%zB)CF zBcQ+DO5w+Nv{XO{NqEJh!WJk1*hvVM@qCjABfLG;JdhGwnox zA$1OEX@SN&c^8z;(S}1#h!OUJnYHLu=da)mz&l&KEtA#w<;Bh0=7bR+8eVD}@I6sJ z%}KSf)N^GSn&h;hfl((yW`Gs3en^=l1jXAKdG=34puK$eU6_CO1B9D)H2voB zTyxJ%sL*h%#lo7Br7mXHD-?WHY;jb_av=dbrUPer@r(pXq)j(7GDx5*0|}1hZaZvt zYG}%+dzLe+Fibnc0)doCwE803+3GB^B%x%c^%o0aA;p#?;v+2)wh8uIi;{wgR!fA5 z4Dzr(3lk=-Mdg1l*D40kVu9Iyv@8_$Suuu&2)alfh&^u-o8O{7i-0z_%jMYqT5JKd z9U`v7QUu5EwK8N>Mwr5JO=xm`pga&@B~l;z80rP48zPZFV>4F6g3I*?i}p3v3+y(a z?Fe1L0Su@c>mv=&Wd)dv1yU@uI08*pGrnk6=Mh3Fn~{svNQssYs^j%p4@ecP{D zgb&;FPX==kc+~VS2uxVGvE6FQqJ{n1uRCcia$*lG+}Gt&RhHG|(rPufFgRI$WQX7r z>tH3mLW+z196s9}ngiq_9YA*~%^H54$q5tAz&i;G2U>use~t@{g%S&s=M)6cLW?s3 z$aRj4KU0?i3yx;u{__w>2ZQbm*2HySxs{oyKb%4W7O>RskGsDDr3^AaG?)4yMfPi2mkz=(-dJrGIbeB zXp&3jKId1~Zr-_b=kDEm0+Q?N^YfGI>ysDP=ivqx0L~vhwsz~eK&{DuPqcsh9Y)Zz zcc!M!%+DS>H3_nNW8?BQ1YNwG0SzXdo~JJQ9vJYiZ?5I@*a2e%y#N*Tzh3+{f8hc} z&%%Ju{Q$sulL613y}yiEvSvc-FxqSGf6ZQ4vsPWp2ovh*)H89R@5eA6HVOcLiP7=_ z;48DQ5K(nRqpGNjKCrO^7A$^%&n+D(S8;D~amv-(i-hMOymq|+SjL*mJ5NV1)Dgmu zQ!b2p1ckAa>4i2cxD={-L-Gs@u*$CV$lj)=0t|x&4~^_%6eaeblsSPS!W0}cX(+Ri zjRabNw_~81&_HFFmDom@(A;BzvF$X;E@&hPD}+M}F&$>(ceY&7Gfnlhk;v5y%p|-I z_w9Q0*{)9C7df)(A^gO-;Z%2s1xX=(Gjb_I8sNdG3qz}!jD&ZKAn>=}fAc;1EoQ@ZP2)iRpoo#q7+!;gg?qPyeiQ&z|9)w(d}F`e5ff4T~`5#zMC{oh=$?mS*Ut zRzL9F)1%=-PnMtdZM&UKEFEuHM4%O30u!M%QER~zIh#vf{+bNad?mkuv|*U#!G`W4 z7QFfNoyAf%E_j!_ zxa+)`+U8gU%nc0VgL1Ng%RP-)DOx_D9)rxpi)8J$}6c0fmYpsr8nwAI1s3~ z0dB8GcUUIBqoLuNC46`Q4YSMaey?F`()wS5Co4*ZuQk+t-=LG~hN7M&_?i#sGMY1) zOlwF70=k07Xsd>`b3rg!(N{RG^5Dxk`WSTboTs`Wf^0f>Iik30gRm{RRZ7Bx8yl~9T3cd*v&@y*8q*`}X%Xz5fzEmwA2EV%RGC&(zHDucM1|LyZs69| zmZ&C6H+qP7h68(O85CMS28dPt9E@uR1A3GCAT8ugL%i)DV*KVKxt_VRubLi`mnbH4 zX=1R-)HC?fDFxvmgJ{9vYROkl6FDiTSJORmT3W7;muY3te!^0`r>B%IkF)S)_nQvI ztHOH$Sb^DeyuAE4CDeABQec6t>SG#@7*7j~rLsMbvn+~BP9d)VUP?e0GEDk~T&U>? z(K6#=X3r%ASKK)@9lGDC z_FuxFd*uOUd(@_+^t%UHm|BiX#wL|rPBD${?a|H%oJn$`x7LQ#_tu>G?S*gOn{L84 z%}6y4tY###pjCu*V}9Y1`hnl1L8~{(NuY$A&W&m%gM4g1*xo)R3|P7D??*=;$({Cp zdh&07UXn967iN_KuNd+x$jc~OF8`(A3n_L6+E8GH;Pp}1^umg>10D{3UnT_-AIzd|@GwgZ?gsli29*`GU|24PY z&5#-4Gs@W##ah;g(O*Wy?8ZnjRPvz z!L>wwuCjScPqz)LFv^{ghR!>rE1m>)%94#}pPODpO&x|g8@dKMRt!*nAmZOct zYs?5kZY0~1{Hp@FlTi-M90FP~_(tzEMjsV0A00vg-DpY})D|2)L>gAKpf$o#ZheOY zXqU?Kcpk{JC&1vjP74`aY;#!+yXntzd+W*Q(BNlMDZQ2FCIGr#X)uYMD|+D9B8?Q3y)+wTuj&%k(2JCaBv81k8UUC^`@#^Z2fU)*=GEH73= zLU!v@#6qW1=%j`JrqY@>8DEZL_O0qbI!#Mb+Lsz9)k<(Uj@~()Dvg&zWI?Bd3KNJW zUoWSYOM=Gb^f>juu-$1mrGgqA!UC*>LHABiYcGO+uo7nNdY?94lU9WWS{oHK=((#i zOCrYkPPlK^WY?6o5rU~^4~+Q;+C0@uT`;wS(B|y8PLWY(g-TN>t){!ENJ{Hq8={Q} zyO$E+(Ea7EDO^xfn2)A-kaBC9RF13$b@gPc5crb+{o8L>E|}@_*jt9Awj`fj*MHJ=I=E~yi zz0uJV_fS-;>RDyb|5Q(tI+7N@oLyL)RRq59@{;iDZNXiE?S*r!ke?nqmiXbti_Z_g z5&)jtnw|Y}WlrGyHU9qh`qJFyrI!~r=avv*Ioc})-U*dmIon^>ohFK7)wq8XVdE!V z%{X=I2AsZ49_VU%0;;ML>9AJ+qQp}FuL>6xrZPLf>=rtBII$!GvNayV`yy zp_7(j`L1V2KX{UP8Y~n#cQ%s0_^Y++4+|Ckf1 z#vUN|U&@bx!4 z%0?66webUiv2Jp&zB-Z{3)jky4IicFflpt565R-gZw@B+Jv{EYZRQ$bWv>(3Wn`x1 zrd=V?ziNijF!Idm2(=9kGwya)*QlpQ^ru1MmPt5Oh218HLmtz4zt;VFF>?|=iNn+H zsx-)p>Gu^c3C(H>Vrx54*Fd<2o0ebpw+taQj=#YhfDjYv3bix(}o8izpR5R0a7}Oh_x)*k*NN)tYib4XTkA0NHAk&i#7&J zO-F44sniZy7Ce?)Pv;}rbYy!3ryGSWx5VsN zYrci=)aGB*S+HOByn?gBUa19^FJd-hV>`ySmkemdU(e|)b__|he9MeS^ERS_t+tKe zSuR@(jd#fIXl8QPAbdS>yfvMcTTg&EI~J?TMy zrO{Zr4lWc-LvW*A&^kf}Aax{$%hN#KhB;1g4RR3}tu!EicB+wFj!FweRtP2)3k|ea zgDAV@$JH2{}b0v|SC9ZLJ;rAreG zn##fIMFH!S%1DL#rkc{evY=~ym96l2%9kPzE9g(D1(-;zR8JMKWdNO49ac4+CRiiA zOc-T}OiENt^bhuiOd#|)O0AR}W8{qGM~-OXq%`w;tTOyLJ8g=KA{j_WJgTQzwk~c4_H#(4=Ga z6##y9gN(_)?;9KI?@$%==;-GBtJzy}&>0h-nmchy?&-mU&CRXNt*tE~yq8|ST$#V{ zavm8p7wmx77Zzq$=2V1r>{$4RJtzOz%nta}mM~@jc(FEs{vTae-_zE8MrUKA*mNG( z21H@kW%jkPEv`dV!i%vR&!kz`W*8bJ^IoEXjK-URKo%k;WRNOpL`4FILKIMN$r>fy z(yY@KF(6I1ris>lfPS7m=lrg-^^YMS=K5k8f_(0Ip7R0*{QFfo`VRr%yD%ZC^bJe; zObN7d`$kn?faU*H*$}$QqKK*xe_A~c%s09Z?Gbpp&V){#d6~h%Rt9VO98yTE{sCz% zcGvm_uu^gRd=YewL@aS(E(f;&HY}_{LJTF0dvc}eL}{=K{a~&~hEiQAe%o4ZKw=(N zYq^1;JeXGRqe~OV&bjv($!zFl#gtXxNAgBZREh^c^RN|W;XIe#9K)u{u}@^b$jqQ` zD5|nJ49mImc=E@8i9Y#d=KS~fHnpGBj2(V=X;bc>ery}7aZb}Ud^a&U)h--yCCki5 zc{usKLVuiPw}OK768r0pgcS;%L8|25A5K3M@_pxccl(u$ zqsZ%_QK+6CWn%3@OZDmNW6o(6F(QwH4nl+Tcl_u5?eO~D(M{jPR53rXgzz`aI0`CC zMEyDp4v{$*Fbty{oh`VUHI#Te#V2P4U+Y;_8eHHJOu%t9BR?3LAq;(UiA^?$P;kRi z#AtmtUOWX>;q1lM7h`0ELE0glLL!z!$PMPiHY90i%8TT&KgAhr6Gou|$gRBW<~@D% z9tn9xnPJ|R7}OYyl^5=WvS001-jUxx?~x55&;VsJ>4ac1<4~KIE=sOB}74?KaMppAlUEsU&1CB=&BMY{U&;W z$$D5a2d^_R_c10A5__h32YB=rAn3XfIU$U#}8FdpnqP)iF!MFHA{tGM2?qV0CzB ziL(N`0OV>kCe30M%n+?6+}Y%cAwo>VPiuB=GP47z`PkNU_|>c2pTZ#0_~NLJ`i8%L48nqva10w?2^}_ zh`bQxaybm3*%O0K26-V0B4VRLUZryIYy_Q=0pCDGUeSa&L~_Wy8h|2edD-Wh2?leu z!Sr$j#v(ZuOoQ(R*}RahO%JEXlfmZZag-t@k+&fT1_|_Hq-h& z{EiQ&Q8$!a98W$FG+RtRNF#T$MZhkIId776fHQS}PYVrBcBc`;0UZ{wRN%W)O_{r= zgbhzAFR)PHvmmrnEy9RfkV=WXNkB8Y8ZdtDnQ4J~3r!B)$xbE9!b5j<;w!;*G(ey( zX@*S=!jk1NT9Tc~W~!s>(x`6glBX{Xg5^_LoVN3UqtRL6p5@zb_Au zeoF>C@~hA01ppaASz2BAcxP+jMrmuew7T`|99;l%u}dx<@H13c8#=8M4;D$h?9t>18xD zaabs0Yx~lP%)846P~;k{1yn(j)6`gHsT5M##bmiFsPxs1Z<)x5eX(9h0elE5%2}(k z4tYrVeFVDDyK5jxa__zVhkEhh)pPIc-<>@cID7SRAxrVr=J43BKL>%HUOHaA&&Up| z?|=?sTx&OChX@so)+tTxe1CnoGC)EGFqjEQg3cv&sErI;Uq)N+iXu& zBo%X;fx?(ggYdvDMAHza)Om-dk@aW}W%|WA;J*+nlU)yTPR%>)`FV3O9NIbpfx+8QFFO@G5&6(`2f zWT7GnEEx$|=nM9vX8|aT*bRU##?DYv;pRHp7G{x-<(}jV>R%$U*NY|vIfu0jO`o7|K>&9hGOZ4@Fm%AFRE-t! zCm_f2vEG3M=wBcL3uG9>YG|gvCzoh>ts-wji}Z8(gUF+LL9WzpVIk3X2ny&5TZJXW zf(gk6~X=0m)Wo|9D%(kJ^r8$g}?9{%|z0|bmi7!-MEln_=f9{9o>xl=SZYy z9C9Xf94*peGy^X%rp)Oy3wK+nGfwh8gkd3-114X%iV$@L4c1w*V9S2gLmd{>&zM0Y zM-pwpumO`ev(pg7cc!OD&=WlkAiQaOQ(fn9l7sI~jL6FhY(9}56<5t_h8`%k(+_&U z;b-I-*0~wP(cAl-@T>0>5{|b2ZyFZ994*%+5sjyR_~k#@h9nGFAb8=AmoG2utj-Ja zZVB?P-rK!-qjY2b-s;v@JNE>LpUpq}Y-hf7Z}+R!+q*a9tZ)9c`&%oBBii-BixNlB z0_CgsYlOWruZpzUO1V;>RH@-exzSLKyg!=1`TiCF_`*S9+Ngi=8f{1yg#o`W40r_c z?3?g3{gpo8orTL^fB_e|{Vn$|Fa%mx36xd}7F*|ekgT|%wuuanQkEIRI0$5x?E4r$ zvvANd{bC-?Ff1fro$7i!)WzwvRSaC;Rh$Zf@z%n>&TN?h+Kqhf2#dYkIaf~ZK|WlC z{Mox<5k^2X%Q$_J?KeZvKDUNGE&F`y834`xg;vWAtU8et0*6`)-G?)8x%R1R(o-s6 zgK{B(3PZqkXlO_<#UNB#?Z+HeTizOi61d+AGog@zrIIKLLm1g2mjW1se&Efju`BXh zJ^1-M`c5A*Q7{_CU6)rwjavcM8vLp`>tx6fK#2FMMO#~z(F zescs@8eK<@7)+PSu53?CUj2OU`QfF)olLBV%&vp=)7sUk{?prN*Vs->o*!$x(yLp| zODeaTv|88yJ$61*bKG7tC5wg3XUecLaZGvL+sFynk_>? zP7~6Qii@^>9z*G^Q-&I%vy52Zypv-Br5()HsxE6?&Z!=MXG#J(fJ&eY}8#<1{8<;PLQIDh$mo0<|MoY#L zs2_|2piL;T}!L9D}jiD7Jz*sS-Jrv>rjDRTZx!u@xL` z^CEErF5ybHF*JbBat6)(E3(`wI({2Kicu3-RoOIKwcfE#GK`iZoK)S=D96zS+}N}Z zwDrOuj3z>%#Q)*y>U-L{&uDC8aPy>-lfe^zSKvRc045~6&(;{Jk z=D0YuK@(IN$Tu%bl&lVz08y|K=Vo;qLE2F%h=eH32CdY5hiU)hi|je)cTJWhk-@&# z;H1>&p659)ZVrP*8!z-67(#m;F1yQOx7%nE2C!nf z4EHa)2<0{*w>I_?+PyZjcF^ZbpeM=6eK0*pLYEOW>GM(d>40<^Q zC$N@){CQG7q{1M{nhzspEdj!tO0{wwi~^+Sb3x}xO*k{qSMwu>Lle-AMN?W>i^iTa zSVOQF2<(qWbFCOS3oOIt>(_w2%#)I54{MN0L*GO#lwbH~O!K4mPqp;Qqq!K$WEdM@WOGEId}jHtkX{;))H;|!(DeWM)w7wQ1tN@c1xTy?xu{u;1c8;j zgt=(n6Zt0cDije$j+bC_Of^J6GA4gbh{EJE`+F+r_a@NqCeEhl>d2X-VxT#Ko*hg7 z?aLb*1mHqR@OLS{wY5|*g!}H5O2#&*aLF+CR^_hH;XB6mUTL)~f3|hKY?O@3+k>q` zfazgRI-NO15taaOUcaW}*Bzt$jUlYrxPSkV&}NLZ*A^BQZhvd0Ngg#a0D zzszKsKl|6~KVSHz^6l*f5X8q`;-OG|jP@>to9m_SK@RiGO;V<L(maWDPX+Z>a$}Eg!yyWuJjQuWOI01zaKnNEdZ{Lp-)u{7#Is}im*t8 zKO;oP`z{TQ+V<7u!+>fDP_tfk8KISd9G~%%a)U%j!pneap2)xm-OS}L^+qZ=n*Lw( z+tVGbCe^d4t_?xM7k@anzv&*iNmiNO{UO~Je|BzkU%upif>PO*A*JVEgoEknHd7&>w#3uidJhzDI<2ZG!Rn%gbIO8dLNHpC z3)ZnC$%=rhDQc;#AgF-hI)qpL+z->I)e1!xmcb57%{@8n0AkxPb4IFFT?<-cnSf=f z-$2jrJxdJ)R{e4meS5Q{UdQkwn_0JcQM661Oxcb+DE&$w75Df+mwmp|~KuSOa%-B>PbV9O_2*LQD5g zAr(g1eHSFS`)&)3NvLAzYylRxH+H~#)CeC^qv|0}TYXo^M zE}Q!4uwvj`PZv3`cN}Ec!Tv$VI5bx-hH@x+OpLYr@G!MlUO0gTR?*6Uz#oXDy*@aW ze8|6YIdL{F{nZW_RY<}N!gj<2F*8V@Ipqv5Lu@5)UcN-C)u(BIQs7)bA8dX=t9a4=M>fo)<=igvk-~OLlMy4h^k+TDeEr~H#!{aBiog0i9TFA_-7(> zFG@T? zv<(C<2nZjRR#!_#dAqb{?BxY@-);-?mJi<)D%&N&q7{>UjFXer9$+0Qkm# z5X5oY(63%A{C|nk<<+HYum1U00bsb0sx81&S^;NxhgCN!lYwo0&5UzsJNnJGd9?Px z2kdxp;moP?%(ybEj|6i+;Q;!)0^}2l_$oUR>InOs-sOZ7gS=^cr520q7vopXVo8IQRf$yfsF_cVX@$WKV$f=4YFzo^(+8XB-HE@y z*bEF^=Vo}v^2gln500)yLB>tn$fbL+CujGA3bB}`h3`0!VN(%2yK3gZA#O9%si21D z1;Gk#2Fyf_$4}06{if+*Pkh($lnEiho`?4NjhmYYw9M>Yx&H9`XFGAuhmjp(PLc2QrR#VsBTEr7%bhVy(uls7J6`YHVEX(orPX zh+S_zmb%;x_uqp#RNjcErp7Jk@~yvDXH!n2pQm63=Gb`(6KM;cRtMT#uLM|N#qcO? zFuHO|kQox`sTQ;k3S?U-rN(JVpmY)m9Z6xeHE3)=*`WOC#{?QDw9pUS-^tL)pO6Wi ztU*;nduI)%)19En9n6kKDN;L{d|N^-?IFZ-w6`M)tFy6FRU`?#B03szSdGG(1#1`o z61p4e?(c3~gbE8Q;qHb`GxutdU4#vt?vOjQF6XY-HY%FT;WM_wya7jsmB{_zz_3C*$@nFXmYb* z37cLtHU#E9)IrZfW91<&hQiqcFK`ni(}4g5(d&qxq&gZkz#cH-Ca`4>m~z04Iwax5 z0YTxfq18HO9iOsN0u7~|Agc-k7c%T(eKgWc8BK|U7K`miVZe4&0J|)31AFCD`?%Mo zM9(fOtAOox=1;N@iKvTgXn-!N36ZtTE(7tdA&28b<1R}A7{>D<;WCE2)&TtAsETVZa)~ri7jPbKt7T<<&%0QZ=alTx8BQu~WrX1*<07rmLw}J=Olf z^jNhGscJ%!U$g14^vTy>vJGjikT2!)d0k-mK)-M3`R%>KJwsnw6(HW;)=L#2FaY_@ zo-pH8L#VKzY2~oA4Gs0%;@DW*Y5IVvf<~dk)vYBV)AG!{{6WRQQ*>d`dd0}=g>pXs zXiwMoDte(J9}PKN&X>0GmoHwt`1!vxnc(SP{}wyoq05)Sfc5XzzC&};N2)tXsIV~L zB{E>(Yo^UC0cIf*_P^6g{Tw7ZPphOx4olnACXny2%>XTVE8n?0lKpX?K^*7N2P_cV zd_f_vDrQgzPFzrWWyW=!IkTCaRE;9OWq9Z0hZcd)u-_qhLr__M1AY+`osf%4JFV|t z6n5Hu+S8LN2f8YMuF~MsEFUy+*Gz&oeZfUA;O8&RmIZTQ8duFj)0v=J@DhTNeN_#& zqFk%F*$lo09flugg>q-P!xlnfc^d#O{sH)N{PEPK-*>u>k96!m_WYNrbM0yKKErr? zLOw(m#xhE5u)ub0LxE9+gw(MO9o?302}X+|QB`3ud!qz24y#zSh8WQ(Q=<`#J3<>v zB~&44%OnUxi9Cyrp@@}%YS_5 z@~VQ-8brRfOPK8BJOK~@yqN`@S_8!4Q;WM00i z&3`<4^khc9i_L;D>k6(uIc0u$rjEE`f;Xuk#wtp+YkA9p)G|=NWP&DtS4z z<=S$&P6OMef=e2*KvJ9`LRZ_6e?CDR6Aa2#9XQo*Cfk3^C7h%*{E*~ z7$2~(R{|#G_6$Q}Km1tOj#FzHobsDi^PhR>w%z{nHtXMj5*=gnCD5|Sp4T)SQNw_a z%c%~f0O42K!+=xRHU&TnKz`2lseCVle;x~xZm=Z+p6)YYgd4mKFA-QCC z^bL>;9qaBB@|zR}tfpT9WK2rQKCL-Ie#L4ysh*?(-3!Yje9&DKT47DfipG{>Dszrv zJBkWsV+w9+3J&rAJgV#cE24Rlnx5+zVFkNjR>8;`Y=+SBXUrr z8OxIvHo$vH!a@Np*ozwp`4zF2%`MGGw!KAN`uYR(A{E`X0Oh~(&&WX%mV+&?odQB{ z(P4AhO-2XMtIXG~Q0!7ow1BbOYu8nP$EO-R}4=@bpWLW$#OodukhdIW#7OH1@OWQT&MrVzF&4G5yTyzo$eTT*DID{sRaZqL zl2GD>kp;o%Gs1%BwfPtGFF-8!EuezNe1zU=UI0}X??U!WPZn$O$k)P}m$ZZ-yM&Vo zr4QEe$b$Zn&1iJ=$L9?ju(bi6X{e${XRKK?x4e1f#!Da+ z0ImrJ*H+87b|!wmUM|<`*CxIxuh**rvDMZ6dVT-F7v=Jc`U`>46@lIt`_)@3)&JF5 zz{GhNL5CVbW`>EBK1))z#`zeXM5_lt9RL|DRrAN={|F4ar|=hgf2@O`QvcB=Ke>uW2Y+*c9SVx#wW zPSYl}l0oe+M*rId>zPYft+=o?U3_+FtGkXyyPm{O%-au)<)~3UDDaCG%jyKyq6WR! zQez1{-aL)ZNE2rG?D3Ke9g_bD4pN`xzlW}f37hc-N#BTj1u~p)eGfFE3 zt(*|#ya}pkaA0fE$whg#idu&Rp$Z0x3I~C6KRI#v{Vxlf>FA?Gi7dyjMw);Ahvn;x zhQA-q#G*ED&y#{YDb2&?<;>u=kn37BQ{tT2xUz+|X4||C=*nB!Q)WG^R$aA@HA0&O zaw`ebt^}?o%$LX#H{XdrH<8Qda{0E-w$6NK+na4|Xa9XtPM7$&^fsG%)2Dpl!qK7Q z{bv&jyyk64dk*P!1zrsF=5#);Z_L_rl|sRE0Mm;k-%-BZvJfi{%fXv}@sPst(ogav z#Wn6R_fv<>zb&Y|?X>$d0m;zv;k^BT!21uo(0$85IX?MCoc?Dz^!~*y{l4NLPwi!aCGw8eoU+MkzJEsDO zu4rGd-_|Y$0aikv(ONlG7(JE5ZDd^rmAeDInQr}zbptpT=8R;@OI?x-AA%5;N%?kt3Ugpg)pTKc!;Hn^TuVQc1Cl?^Z zg1f$tSr{v?jS5b~g`2*m78UN)e>c_D{5%U7{0Z#R#OwDhP z9GFed_Gnqs5~klJ!D{leXk^GPFtujxYoeb=O#3f+lPS;_0?Qy8^Y8pTsaFcSsIib% zjbIEOF>%hE^8^CL0=hsm*&J#YRz=pxLaRV;t1#f6C8pcxwP3ubP54&pg1)pc^wh8^ zXBgIat!$48?*f3+UP}c%`r7yVdLV7(bIi=l7~z$Ly;c~dVa1~}XRk1V{_ump?eDJ( zx~;DZ2JcQx)a!Tmc0QQ6R;}0f{y8zRQ`@iaeK9d1bhui5F!5on{9=E9XX2aH)faW- zRQIqU9eV}9;I9BMn(Fo1O08NGxV=>q)+{`DRgrghzg(@>YPG%fTYI}T*mSMFzE)Nh z^nV0^`-iRoz(4)d&ATfg@aLbe?bg<+`>QK!w{~kByYfl(+ReQ?5MYuvOeI4j0n0T0 zS|xiXiK5F2V(7AhfO7-@%RRZofsUX}$_7064NGZd^jIbg+Hm2Emo6D8mYnX4FtpLh zj$msrt_GwKlO571gWixs-;=srX?c%1?(oJ{g{9@eAy?0%wnh)(t2j!_2;2~5y-Mcj zw|q&bgaQ97{=^EUFl5ohLXzQBFp{c9B8IZwE)9aN7*no^aqKdtUDG?L0ySo~CG`R4 zOo2fH1MZ#c4%_vE(bD2qKb%r2QX(;P@c8csi(qkLQ{T|dDT`GXvTl7#rsiJ5AafO+ z?rPqr#(flE-uiVZ?!jd%szf$MTYfnCd+tB&XUE?g8ajM-{KC=0H=Z3HK79D_zYibY_~@e>S1$f0 z*XW|msS{dX8C0*75{;Owil&9Mn@&X>T;>S9O&7q3xbFPbWiJW_3RMxTbdL$d7X7-@ zb@+?A62{Hz^dpsax|RDfu@*qJZ9Dw#0FQ9EZ(~5x_CoAQ>LhX&NoBAFZfAgGdWHik z_F}{wa8IG6ayscZg!c;63K|oO<;HQm&7?VC({wF7!%ofAqLL83Rt5!@(-Z*%$pXUx zC%P+uc1p+5g2za*dbF-8Vo0N2XV<$1o4;m|1R5#=zY^mc#nN!uKkk zUk$<1(!r>n)bUHSMsM^pAX=_q2KH&vm9I~`fP16izTU8@1LgqXu%K|u0QRGB)FfWX zjWJ)eB?2dA_iMU5YBm2iI!yN zm?Nd5-b9E*Oy-3q($qsmYXz)hjiNeHqWqLBlcN3~d!P4nZqqp-7<_gRvhKO(eV;FK zG?)VF&d5O@kzdS}Q&;HApd3x5f~gsyjphK3AaTfOG{#$B-mm)oDZ}&Tv}1k-Y9{%PU*7wP2YA#l1dHlgM#tEXy{2TKu_j>F^t{3%tS`|A9AO6h&ee-+qMSJW4?1)~BW&MQwX8}2oYsf| zzl`(vnH|67`d<;ZVaR0(FGM{aJ;F24oDqJEGjRw`B-gF(Q-8F52@RGQJM#({YTaJO z;|645iSG+!7E9vANvp?NO&5=JHCc@mES~Ss9U{5ci4u?DUzCXhebpP}Z2Bj7hG(ZLYTVlZ5gayfvFuIEN0Dx?p7gry=j!kmj zNRDUh+#ke&7)is&BVshLGv-8SBeyCiepkY@m1AL6TO7XHWEsdYk&T~E#tqMsi?g%v z+Wcy89EakeT#~3NkDNutE}<#?jNu%l$YDZOVz5o2@cSJ-?}vIqN1?~+>Fw?49cgJO z!C_6j6*-kHgDsIr%i+Pufym%T$95uvbZ_UQuOnYyzI^#OtiT<2o=r@@SbXvP`OBBz z{r9`=2j4$=^5p5Gr;q6N@X^El{f+(o{fC<`2!D45SitQyV#2ua*SN;;ib1(cY{T1_ zX0s=$+@ABpxQg6u?h7o170ZiG|PF`dME5pl)M z3t+y)d%K;4zg_Lbcx$?AI-Nw3o6T-+VSqc>*-hBpyyWge1P5l%PWKW&$IWpaPP22# zJnwcoQI%jO=;o>$U;|L7)4{;T){$U zTRmrD)x!X6LCRG%2Ggw2vKVEA7O@YueTpl62alhjdqzSoA~`C#bpaRsGR{5qm2`d@ z_Fyc>g@oh7R-X;Mzr(0>8sDXA$1{!sC6Da8 zjtq{m=r{tOQP2PZG_hkDYGxRfJd!WCA#V`MdSs6zrKI2t0Wl<5QAtRxBt&8bH!zs? zPx+8N3BnnbQi$hB#fSo@Vo?H31b4*x5k`rILaCpQnhFq|?T=jn)-v?64QY~#8DI-$ zEi~YnBe4j9`w?a32XxbG1Y*Q=L9YYEe5d*uPuY>=p9;n{xFQLA-zx!#v|}5v{?d;$ zLzfBBDS8dg&BR6+o+|&0up#|e16(G(2IjuTi_etNcVa^9fB7J^At8tZDrimDbmG6N zo+lctuc-lUwpB$QdpsnLg8v*b$xwxWp4Dso>p9ir|8d%9K>M& zFg-m>fAYJTOqLEJC|8w>qj&R)UepSgw2WFT>Z^CNX?-tG%$kstxUi-#WOWrI=#}T^ zr$hfbY>2QB#KC=tAO9(<6YwhObVj|skYCGx%m92|sI1~Y1Y$7}h8#F98i3>Fp(|iS z%u88&gz+t4C4@S{$@=Y)hO)kj5!dJf9uWFxA%kuhF#@5nCjLyaTF0uP`G=LxgP9Gs zEF6S|YfUa2K^!!6T6B+HN)DN=!Vc?Z(`yw-1{H27=U}xE#p^YCf_Xp806YK-rgJ%F&N&2F@X$V#BRFlMA0zB~)&y)NXbp$2d9QVZn+Q~iu#Wti@GTc=x;FB7 zWMt@ZOK(G|p;Rgj4$|MqTZ56)rNPM0OQoIT2X=M_OFJ!*!3Kl2{-^E5^u(E$FBfk; zzqS4SgZuX%+<)@-r%yK@{eJVwoewXcJ{oeJ_}l*ezrWpEezmt(+$$D~e^|%ucPlG* z>D_r_<=q>2m#!4|pMQAy*icV6X~b+Kk=%)E1+37MqGeFnmA(Ai${E)hAxx-~MlXd6 zNtH+dad|)cOSO%w6-*X;C3eA_onW$@g|URaM;4;2l{nEdfwiDM;Tue=IR?4{D(MPH zah8!D4W5gtqbd`35)zCi@VSp*RZv~1m-|c>Cc*GC)h-($n0;^s6SZANWs<$>T$QLG zv{xjMc2(Qg${5~PwJZu65)eJNw-fX2TTaxrCu$L{(TecrW%z;s5J2z0TifmJi7tZR zDpWCG=8OI`U=u#%U32M!zSP_v0mDY%Tftc9i%kE8y2ef5^ZQE46KMkI&T=8(6l zWs%E)kuzLLnB&P?o^cs?YmHh#e8%LDvpLHtzXupmQ}#r9zI0LM^6D9wyvE)4)abK?KPC=C-* zS&?<-#E*oy+>~TIh#~Yu509Wf_@Ho`$gYkVG|^LRgR^-oT(z|#;cpSAIKc0l1iyv1 z4;2chkO+NfZmw|XBCNcx7AL0LTFOzBs-h^mqGV8=bYb-3nzpvKIy!n)%@^_cMuuLt zI6AtT$rGO*9lfdK^}IfJNloXA1i-&3Y)?;nxes`Ey>RvFO-=_{01wV6e@*L3mJnD; zXVr{4cWHf5L_do)F#CMZi&RQ6hK?JHU{2!@(`O?9$ty%m7)IXfdVA7xPr&NXfav`d z!{`B_zT$5T4GDT&7Gf>-d+KEygD)p?(A6O^U{qS$So?rUw4)LQ49KQ&Aom>2NIZdd z1UJJ501M;MaYJau>Z{Xi1}?WU94{-grUUQ3^E2t5OSqVYsGGYLLjq#j*kc7xE7qqW ztU0-N&?Sb@F0PdiyF|K#XmDr~8B;tphJ!fFf?rlN#lx&?3Ikn_5_|3F>7Wm~-RT$^ zAc*Z5>K*BMe67^`xKwIrDT&*Gw+x?({JM!LQz{bRwh9|o!nt|Lof>aD!+9q^GCY|7vi!41e_g)qJ7wL7{L#X7bWQX`JLzuBGLA;hn{MuLe)= z+xhlx9#-^KY2PAcirvTW!MV+&jvdOr^C`YlEGaOng5_zMU~5w`O8i+___Ac0_K$?1 zNf-*rLKQpR4nbN%<48RNU8!+(Y~$JECSk8m2Milzdzj*vQHAZ(P{?+@0rxU;!9>x^ zNi6nt@jBK<$wH$3jqBRm4SHp&WjC=QOgU{AOAqR0lWh7*m|-IXF0&X6aiEx3W-=1H zyfMyPF{sd5YkvFXFtF&^HI6ONAVgO(eIw5g%SlQ0B4f*%;2{yqR(t&GNc)qI1Oy z8Y)(T2?1pb9k47Rx0IfthnYsmQZ(r4bvUL}RB*;?^tvrm873ncMH@pWGo;YLhOvVJ zmzZT-VFhl1tk9|)yyDn%ibl^CamMn9h1QhEZSho;PjP73=&(7$%u+Jap@Tr>_OC-a z!$#Jjac_zP&>r9zS5o0$dpzGz`8uRR9fknLYlO*OklNZ@oa+L1(QoRvkK`!$r@WR zLF^PKKGxi10T^=F3}j1WxwE)~(!lBKa6;?`oY2E!M``vYz9*Bv1)lZ=m@!2df+EYLY}UUQJez zTrC4kNNR|-v|Qn+RWdRF=r$zldU3%y?nq?d4E-pnmP@rg;Qd=I-`6O9Jr=F#+w*_p zS^e5BFizWtX+;SDPfliU0J(E>StwP-V8D2JeqJQ-@9{o3bG-lvzgGZu3+V#i>OkVc z2tBTrRUYtj0{GKBo(B<3U(3`$;HD^ z#{U?b$O6cmYi1nbt-iLZ17gJS`3LFr;&CmG_~`MWLzj<^(y{CE)rk|M*~wEQpU={W zgPlw$UHV{E_I0biZ=W)Qu2dRPvpDKzzfvlZRo#j+Oe1ohOC5pfJ0zc`j^K<~Sl)WtWIHkWL{|7h);S@J4$q+O1 z*fsi9vqUh+Z?b8-p{e2O)>bV6Si`V3owe)8@Am#OagF6+S7l-y&c;JKz71J??|m)txecEd}AV z*0r@gYkS^U!Nmcbtti^=6(IuU>7e44$s0$<(2bL%EIt|> zK1ieJi-jRUu41k{Jg&ZI9Ov()$HC>9#e0tiPY>ViY_8H4hb6hGc?b0TIcWwrt79?E zvT`$;QVveKtF$RK6-y{q9+eB9IrSybv-I;du+d9i>go5aBXj{q-89IlrvsKOe$p_D zOTyxA#q@-BYus+&FsxnlF(Av%Al`!w;!H{5e9mMGH=g2U z-I-Cpxgd=<%Im$}4BNdy75WQ2L;G?|$(sop#dy+^DK}<97G*VQ5yvcdh}*tyBPi>Z zMPQn6aIY7T248_ocSda<1>)+^U57M^7TN!+a{ zgY_k9(uy-y^oM3Hp^3)O#f)VrE*7UNrz~D@HPS4FIqmI;-UJ-aGOO_wUvZ$ctE0mS zDV*?e1GqFw3ywqpf|w}wl>*OQcqGBPb0BJFQbVA(rlw{9Ky@*;AzIVXOCt^tH`)vC zM(b*N&20E`?I=Q%jcDD?D7eaQa0`GJITP&#f5qjBS~Lp4CdoODC`ZNhnX5-N5y?+z zV9hv58!E_B?)pNrHZ{4D$s^oDI+7GK4(i_I5gEW@Gnn?1bxq19I>`iK`d~>Gu=0bB zBq437Y6p^aO7GH|1A-Wb0uw>e&MDreU;|-(^l<&5fyPXb9MBc69Q_O7?-qzNTE=@oJ6Truh1KKA}`~W%p z+rw9XIB|6H)Tys$+q5lT<#r{ulFIy0h12h7R!CY1?fuelO=hiV z{d`b$dCRKR=vA58OggApQHnYyg=g!0X36nlq_tTBI?YaBl%xKoB|eq;)#WVqiR_i~ zG_G_}Aaf3yVGLWjgIksxWo54?vt%>4Ra3(}-|zZ(??=6}5>6{Y12RL#{;rD8(^h;$ z+P4XYRUDGm+HKw;;Gqkr=COFLjrLh*tM}}D_uV(P{d{NZ&TR+wZCjDFgtE@+&ZVWZ zOFhqbJ>58eegmrY*(01D{rRWw|MI6NUqQD%e*ECGh6gPVuiU)3YQC4dm;+hw-&wx1 z`h4(q*=_)B;a>jw%ysEnTmV}63BJ;ag|r+Qr%U)aukaU_%kVKG?rCyu}|Kwszc~Z_XVAm zPmvg51Kw#l%S@O`@wsT)$|Ya$Qy-7nP2x>yWph|Z^7`#olR*@(K_`*FI)goqFZ~xO zOOq^CpW~3Wc1YVs8gzi;%oS#7+Cae!G}qEZ+7FD!xSGU-Bs>;_EUxtvvyBD=^N$!y zSa0y+A}9O5pl*4zXDdkER0Vybf!>TmjXyh#9@zti zxGi@;^>U5K@|~@Mj+Cje!x5IiU_3EZQ6V={EJw3KZ3KKhDNaD+(o+$(NhTpf87gc{ zR1$v!-aY<>BiJe`OgaDhI;!s)gKd#R1r_K9{$=nO8FW5^7%ym8MhY=&h@-nO@1Pj|F zn=<9WOsWNTXXZ1zcJ0_$j62LW`l+KV0sS^ zvk^)s8~*U<{}QlHS#P~|P_v&+^0S4>27Yx%JU)JN&1k|87l+irVq!Qz-puLP8Jw{yf!THnHMV;5Og4W{XMGfX7`m2sJhC#ctjMd&mj3xh ztC>9W@m`mvRdyLG(kE%gH#CLd^Brjr5MB&K8?=FNgzhh|H|z3!LEAjhCJWv2ue%xYyq%FRMv|bmJ8>v{yO@kUANjMhNClsOv=LDPSXc`#o(@T z`zxKM)MwC;x=hB9JuBAHn3R6_kMPzPFJJuk>*vq^{{6q@f|lt||6(Y-cYMrL`1s@= zGvQaC@9%&5IcH;E8RA+K>RMY}ReUWr7nPJ2Yp-4^Q|;+_vJX%yhE{-C;M82J0JA2j zRN=P%m8i4gOi{iU!Q_$#rp@VnrQ)a0Ke}~8{>he)VZaqSK1#){qobqh5w(^py9e@z zit_tP#Y%DY?yteL!t;TTjQmNH%b9ua8is=G6@WU8IW z=Nx*J2-qCEt=45I7717bIM&-mIp|~iY$*IJBM0lhIbGYPQxjod>c3;KL zO@F=bx-T4;C9i9ebZ9M1qJlx-Qb?_UZsR0~dZz6Qmb#>L2)}J~U1}2)MQ1h1v{_Ks z#gdqOEBTl-+u=)-^0PeD$gN0`o}@78eJvuC$2DCN9^CeZTX5H>?r!aa9`o71(X9lQ zUpu2|ho(%W=l7 zJ`AtJ)8bu(5~Bf?AHyC*p;|_$``@sz0Y_AhWC1kJfv7rzujf3e5zmNF-NkTAHY?=U zdIr21%}3!Iaugt8nTJr7=KWDFOD|}hfqE)V2lbH;v3f?w1z<|27|Lg zmD3Yiw!rE)p|KnctU+9a&YD{ZtCn8}0&6m5Onx&3#IayP)1M2m1TQXPdKctHrV6fL8==XU#a)!H=$ba|F$7RogZh5lLq`0a0Dz<1>czA5lKE$0JO9Yf#IDnog#0?WJD zkcLbQmJXdQoQrCOsItcCkT}BgjHI28Q9g@-z&Ji^U7%s}xtw<-x(h z!KQp3Z1MSEQ(L$yFku1X(mo?-Vb;qh27m=;OU2vT&hfX6joa1orlN0&-y;n81P0vo z143+iuQHa{Ox_4;hRSFq(5K!Z zsH?rsaP4YZ@@q@dn%_4pH+S0!pZ41Z@C`$AHEzpE8?aU%jSh^_NeKSR*EQr=-Ohnt z0ayBf2L=eaaykK0r(7fcnPNftF0f1%M=$Q9(O&1dK2oB)djaG=L1T1Sy@I&iXZuF` z&voCscaHfqQt7ispT&J4*1gz(r}{hC0}~@j8gvJ{Ul%GXJih&nQ*46iS`a7>O?9yP z?Eq&PI-fl|r74v1G*mD!uNHWn0<#IZYWyQ99Ih!0NByjNsT)KcJ%!H7buUEphJb5Z zQwNzF%&58LOe0-KL|dV6Mgwgo(UZhes&E85^84_!A+)l z(A5-r{|tb9NmW}E5VoBm#)ESK-5zt7dWzq$4Ge4J6{2Up>bV)2q+?!9ON06fk(JXq z?LPX(?jEL|P~)IA^AytT_Il_HW*$v9Fx954f{CBRfJD-y+=Oha!F@f@;!tU*gQldG zu(?wXLym^9M_I6(|9hBAJLm(ZO@^JYTozG7D=d4mEm@BMui&iw7l<oIvCLmt)TjXSzila z)2ihC?cq`Zb+9TRvc`5lKF7jvD|L3|)Qvusr*8_UW{sUHM?Q{Pf|& zg{|!}GU)y7T@{*s1@WoXY8Dk{0bIMb+Kdfpe|h}o&3~FY!Z~)pWu?AVM$iJDx64eR z%PSTD?`$3z1_g}6fg#hS3-U?KWbJV1!z;i1RvB=uSlPzYRJ}c0)MT^yu@+J`0#V{8d5g;%brHpbQ9BTj#TZD4uNDOJ&X==RRxjQLPwvak z*3;Tw(?Zy)OxWVSU0MTN$7C!?UB6k5y>s==?4eqSdJK)#o`XRe1x)iV%B#Vidak05 z-nBcoXUNn7b(#lew5(xCBcz7D->;czE`wg>sLDtUa#k#yJ>{#wt$BdqttAk3u5wCZ zD>KDsFF*PfWrIV{pEWC3n~8EoG4@~;kbPi^DYtfaS9W)Ig}xpw&>dZ+Kbjb|a`|ZC z@yb?BBf#er;!Dl@haca%{MJ(YkHa2GqF-vHFG|@slmD_DoLLQJ-T# z`{SG%@yq(wuA!8ejaUHN25feGLw5Tbh3g!5843H{5LCYgXYhw~>nm_+v$J8g_d5JO z#L%YNNbdU%$rX{$2)2A~EiClgP&revo5E1*iYm3!?^$BUXR!N6PanECLhzXR52m~+&4}*y2D(Y)hz>G>)~t@`7SvV+TF9!l zU9Qgq+81ncpohHyxNjgpK-Sm2F3t1kb#*Thl*M7-u^=cK>40lH;0<>NC?@oJM_gJ+ zI3M}^k&C!!ufQeI9D16kb}&5RI!U5)Slb1mwDaV2jPz=-N4Hf$7$BpPP-vmTBVLt4 zhqd}hs~Jwt2eg?`50LvfVedRA54uAha;#*wygV!JGt98(@0XPMI!eNDX(DuVa0NCb zBv+nJtpJwWtr7-1;m$B(9~79RA94mf9_>D*aUrNnV2TPEG8;*j$0QNJ4!ca;}irJ;+X_0ETO*f zkl=7U(G{x3+!+$G%IY>sB(<0!kqrqRGk4Bqv(-={#JDCw z7UeDBotm}`-__}GGM5z?#q3Lv2AxRywE*Z<2GF|b9Ul)}MG9?^U@8brWTjl0izAyB z_%(}VnhoX3aaCH6YJ5ipn-ghU1XAkMxl$#HD<}N>5DKpS!~)Rr{^3?xyCt&m!%Qw7 zGEtPjqQ0}onk?(uHUYMdnw_<}7%ZF8?Cft}DFYS&Mr{1gwXbfjeYH2WU&k`^*Qv(a zM&n>_>S^n3>!^9Kez03_2~*lRI1*BPBy34gd8fSto*dfv&Qd|QSRoTFy}J2kQ#tkW zCW5Sb^XRb<;AV60i4tmdf_H&n0bj<@i{SUu=K{cg_~VU@AKwcA*Y-CxqgpU{^`<$k z=u~@idB3JR;7Ln=rRpm@NNPY5RN{h{-N`GHic*?IX# z-Q~H&dbr~fhXo7IdQK0GSs9d8AFyUnl1`~G{0YY3Ap^ihlXW(9=A%D{o~t-l0R@J8 z-inmebtS}pPJYEn%bKLRBW;{85n00e&x0?P&*+M-jh}t7a15u`(6?sT>@j%qjTs#) zZ8hBW?t(mGW&^8pV)J8WSNrNi`L7-L>1e_9NXu>VlN3Q)AFl;&6>V47)*hJCg9qOT zkA1*`VNFnYvo24Tr?qx%CHH*vzw0+Xo|x$S`MplIReN>JfaQla_vNo!)TQ#m!kL5b zf4+X>(^DUwm&bU{%HkX_@Y}9f(Em0AvC4xr|JfLWA;4yFd|b=`05b??Ye(>g=>zs_ zo4PFzwLuwO(uuR(moGW|ez=cMZNMcv8fLb)SdQ+ON_n5t;muz@+PjMGq1VO9_>Fu z1a0$Z4yCYQWLTZbg<1TPlEutfuIuRR5+F9@SI|`u7$LKuGQul|5MQ9x<51n_3@b6= z2MABx26JQ30w}Uj-C&_hAQzKSyem;i#4lw*V?oilJ6nh)1a=bz!C7}9k&Vq{Gi8C_ zxZH!Ao8{U}LAY)rk%?sr+3bwKZ`=fA30T95;~7EQj39KijHVgutQHc+lksYXFb=^p z`I1yhvN;5E1rf8FK#4GF6rT`m6mVqrt2xj~N_xk~D?(=>zDjuTa*3*2UY|&3t$bxk}t3Q#tPzC*lX@L8jn$7E$>eg zQdQqwpRTXG*=@C^)^}UGjiaYnd3WEo)~A|s<8EVpdUyAiH&zhGtOD>qRD@NpGa)94 z@{Q#o63ko?&RTCiZs-Ks+98^e_FbK6>xWLTpU=)se0u8D^?w7t0$ig203ZNKL_t)* z3(ZZl0fzlzMv^~DfCYfpYXZQUeAP48V?OJ8Z?dg>{!v2?HF9DC@Fl{c&uWU-j6+S4 zdKtMeZu{0Of32#cF)Itp>R%W;ZJbD_3^6`^QIoLTq@f21<3Qgm?=ur<{0naN+HpNC zods4dG%!#|7`#;AI0sqKRshzJmLFLLU@H*I@*uT!(2B%ELuYemKKfJqOUsb(Ae8qFih2~YZrfcxB&q7_55%IghP+H=@@_^yas#)ekqs) zb-w|BIT-+6U0z;3YCiqj`ntudYm19-f7p06cD`re;rk~ledet}8-N9YS6BBJYU)Vh zeCAk$Wy+u@OhH87!1)1_7lz@;R27=HC==}_!U-a(C$ye$@{W1Crc;wID?yx^LT5}$ z29W1UKfR>Q z!6|Gvay+uvPN`u9eA5jP_B-oN$A$yJx03Ge#G67jag@qYI zj=Lk#uwbe(NP+J1$bS<+g@*k+(`}!MCQHSS|2>WB;PGjx)9ND zEP>u|7+~&psW&(fj)dohG>0QXg}(-xbwJGmm=G)wcw1G^x*N8TRdBl(UaU*tfXUtH zmZQA*fP2-MG!j1fXg;j5&m*dQrj`LNtYR!VYPgz2&nHilur;m!_U$>V|NYF39_25|?gK$=KsmcQ!!72-@3mRuwMfLNGuLXAgme864AV4=B6#M~OZ0pWci zh#O-MEOa=Yi7};qK@4=coXAuKyc35p>_^E=OmMj1F2@DU%83}T1twSHj5rN++55a+7xMhAQLboQ6W?h-wZU3S>f8bH-By>#gJvK;s0)_p9kwg0n1wL1?0% zN3Y`jJ%k>!J07J`iRL3?11^WICUfPA?thb2HphT1KMY7SXHHf!I)P>q&c7q0Ih0l1 z2q!aT06AIh(l(@DZGew`zzV*zZ5`He8kV*Gy{3Q+Bwzd8jg9wMd8eu7l`})&+Gn-e z2a6v(snvE6D(`%@&}=pu&7JAJ^!#9zrqC{9mKtnVVE5Z>Y5GA4#Xq+KklWiPY4jqd!X%|GPwxnCrExVYe zP3qOOT}=Hy_I#e-YZJ{WV86U}MS}c&zt8hMoKn<1V=1v(8gl4HA(9nGc}aap0>Nii zFI>O)!)Lo`)49;90n95JEir7ZG;a{QVR{#+4bmP175wV;hc@uNYb7@Gd4>Aifq(AR zESjqLy8+B@KiM`DV!16YGHzJ9zXV{|xu#LTGJmO#m3Gx-h3>YDUoCxl9P= z-#(pc2(9L3>Hz#w3Ghp1&G!X1mHf)<835LMu-PRv^9KtvC*tVZFVu$AnqGZfvu+Il z{)YnaR&8PGiCigsvQa|?Ee!a}uRrg{FTEnyD{O)_#6*+PR2jfDUIkj;m;nL58Urhu zmZjG?dcM(S4Rk)5@Hh}(xjz95f2F=AnfyKO8TYwXSzg>c_*#!JIk&rLBzOQtF zT+Vfsvwd2e)R$|@QdroX$aXc!si>a2RU8fEX3gGLeZSqgj_#~4n}})~0|!XkK)}3? zev8D7^^WO|Y0bEj6Qa>Bw9x3V1Z~NkMDE;H7PJkbqVfqlWn|s$>u_~Hr5!1%0xO)q z#5+f$PbqGQZu(SqC8&&XxE<=-7A10$<|MKw*(E;}ES=nJcTGlPuw?<0v09+%~!v+%|{T&!wDQ#n5)QpsI}vJtqraQw>c1 zhSnds^*HL_$qT@K0_vS#AI;rg~4+~TX}U4 zE0{V_)F8?p4Wkr9CTvo3DSI@g0{{l8wV44VzZof<$IyfkNvn|bn4Zl4u_sc{v=6Is zxJQ0~%sA8Oh=~f(CuFM00tTjnrg;@Eq^d>3fPdU5VmQ~p-v6V&Ci(e8O{7%ttuKjh zee>dus-Q>A?aIiTH*-`lb5??;LC$uN}W!Tie@S+d10V-q|8tYYP?h!S1aa zo!|TN&h4wOKfOLx+q)+`nl#G0IFKIvntMb|-&@+AS=c*gk>6Gm#vxpXJLp^GO><>f zvxpUeO=+J=BgRK-fiT&^&wXcq=H6|gd_kesgkf=CdGKW`|ElG*vR{=)U+wK(jf6aG zcEfSawlWf{ko@jCJ@NP`E+iawbTSNj)tJX=Xr%|`oM*pzr{zp8G8$N{1L#gu9As&E8B`DVYu4gGx-S1V4MP}`bQB8% zHV`QYDj(Yol;qFLr4z1daJK=I;N(5Q$^D(J+MG3K=5^lw@1xs4xO!@3r4t6cpwnqC z>dtQOze$0?-vR@|kZF_6# z1b_vB89^Tiu+Q#nObG*i{U1bF-!(sPXMJX$Hrh0G0jDj8u>4JQu4n`Yq`0-ylqV_~ zwjwN*0iS0C?eN=CGn1PE9sXFjjK3sA*uml#rYnH!2VRBX(Dv$Ax3DHP+jSIeN3`X) z^~nPT*nn{9rdQ~$++Ksm=%xYPKEJ@a-A@>nskto|^4g z&$)86`VzL`Q(2bqUqRjIbWk0`9ojR9Vw&>bsGKa+_ou#1!D5~OD7(7J-B7ntblMf$ zlsnz9V7hyK?TWZA@K%GaVw1u4NqI1dFF2@O3_e%hHMuE(|Cs6&a-k#rN4$UySIi~p>6fp#&AT91-3Xue!u_Fmw2XQ4e6P*>yzopS>HUZv%3gm4i zo8T|oic(3#NVT2NX2Lie&XQfb87gdl*#x`)U}}-PsIfvGl+r{~Dgzd%by^wFByTuy z{W6Aj()S{7M;MU8w66(8fCz*J2M6O$%8`Z!Jvb;s$v{C+UgL(<+nlB;%u4 zf;~xR+%uk97T`soH8h%xrwZ|;fbNi>E%}u3WU4SeG#-gl1zae~m!Z)J(a^+Fri$am zq_AT-pj8Zz;z;r^qD2c;_%0Au9M2Rp$!DN(Qa~}TW9W=_5cOzB;e~kvxoE7kg7Ca% zVIgVO5@7CY1~ggF6I#rWnE)%#>q59k!zd@P?<%t1BzoiK1rtWugY4@jSsw=6nMN1T zKToLrsGyGIapvLZui08>B8O_4DijViIZJ+s&`-W-q+Dsz#!2pEqjKRSe6qgxRhia@ zW*B|zy%%@>Ebovfm^)^0*L+xy#>P&txB<)@93weH;Q3GIZrn=uQb#DaPu7l+T(P>n zyRCWl=_~}`}OaIAwh??7iRWWP5kqK;kSkitNCbn#q9b_(i4uIR(*3Fu=F*W z1FfLd|2%f~m)~8=q)}txa?F*9T%5$ zT+5}VQ-A*vA)b{afKlp@?v50b`GQg;h9r`{nw+Kar3H- z%3{Fsnic~#6X-hr>dRU$T&KVrwYiO*wf!9^_QJx^x3^zhm4CrU52xPVLJPmY(Ewnj zz}r&`wU-a>K3=QMOkLmm%OhdHXWn7jOnV^%4}jF9lCGG=uI|Q-n|eSIcsOlvSVLP{ zN#$HgtEH>6fA>5~UQ?VdU&z+*67lPH&^1@F2^6Dhw(BaG+9Ld)_E&zdy;O17OMHit zLEOUfWVc2G1LBTKrHqA_BxyFrG$RR724)3wHR3}vq6N$mLpN!lR;4M>MQj!`XX8Y& zCFCgT=W@V?{uvq8!zS2pSC?{MB+KO{=E{i#-rz)8lR2;?$^9%2q&_+c8A#{)F#D1~ znJ8l|N+eJ|1G)moeK{%y6?oU#0OuYi6l(={JIdW%g0!20(t^=nDK+k1Ph=HXaU*q4 zYb!%rn=gyhD!RU&g&@0J^dkvtC38ci(DERs6%FKB1%px7G$GEDLDgRc;ltBDL2f#I zr(G^NjAELy1rJRn>DL(?Iee@7Ab;jK*d^xXaSa^@xRg=~3ldrCP zY!iDgL+Kbmod>U3>o&XOu&FG}^Jg-@=~FK3YmVu#nyLp*X%?1D9igyWRtZfcsAv(E zYNG8n2hG4Fr`akjd^MEAOFgBVWiSRLgjsev1<_o2O-BP$X<7@NbQLm#4!c8eWf-s{ zv`qL$7)w$(yv)GOG_k45ipD~DEGNc|T|?fJl0~ASv2hFuB_0YrONEDqgbh1W@ld=d z2pcAVg9&sfu+MlNKG`f8wv~?QW zTEfNIvK`Lh+{YreWU@eMu0DM_Y|7M zSJfc!#i^;+hld9rHqn>;13V2fXbCFD3vA6}a2}rX2z;H)__``wAKd9i9N|kcVEIQ$ z4tkC>enA}kXL z39=@$&y;YQl?+SPoN{eh$v=VHOhFM|?E6x5=9z`t@LAl`8aVl}?KMRO{8UeJj^YFS66i!%8VNObVR*@L+I%0~Z0W!L27VxpnHa z1b`K(Rs@)fhP@iB?lYSZJpcgz72wGj3YAx>;j6j^=~CBbbQ8lw7N*r0n?#i! zaGKU>%FA@S*9m4D(hD}C$}BVn)0)L_dDhELgHex&1wGU@y3S6d0>cI=4pf$db~sou zf5E11QBkJ*l`#}YgI4basE72_M%(1^AvAVjIIWALj0_3|pcV|(+u`tUSBs5E9m3t` zh2H*TgBzBO)*E_E{f0CvN_$Z7Rd#oT5ZB-ZNTWf_PB8KcjU7S1zXS71s7nXz-eBNI z_JF;?P)LB*Kac)zFyJo-09SbDkb{Jpw19I!5V+2dmakh$xPk$<8=SYoiv&VJ-Z^xG zgJ82lk1O2FN)ou8t3&=#1!~uGLXd-$X}QbiIPgnh7W^hF2*cKLN1*7eo6*5mx<|Vq zqDHaVdYAfVs;_8)C0H#hf|TyFZa7XN2iQSTmK=mlG%cYWj6-tVW#+HLdJdz!7zRe} zAmSO$3G6FZN(3>Srmjlh7iN{`icVv6xW2w#?pjYP4mxmftQZAodBDT70AO5l#cgWZ z7odvjv%zMk>zy=+W+@sz9m0KG2xhRr2%2JOmHrFs zJtuV0PB;yy1XKv1P0T6BJd(l1O0-EBE=th1(G)iODt#`qe3}r5)Q+(v*kL&nW^+|S zz}V+Z_^Mps$39e}T`rhxxY}J2$ekmtVV^*3mFqS@^)bQ1{#xnEdVmniTh?^T1$CA^@haelRZwV-v@+PwV*!)GP4$~S{m+xMy_$0~#|v<(gp zPVMb~zOnb~#;@;={`>a*&+mVE^9G?Zhlj5YHaEXtTU*TCz_jLQQk|p~EdSr~p}VI$ z);6`j2nw4AZVjK+joL|_4(r&Hqq*E7`^zg?u$;*pTtDRbuP;9Di8a^me=*nyBaUQN zh|(@j(Yw3JYty^3JW1uQJ(833bY^t(4r3UU1vIBj;dGzf6>zXX8I+ogrbBUOd|hIxc7n)P#AAugC$EXVFgh3d8@P=gj4>;v~TbD-Va z4lfQ@Yb8|vm=Wfm1==!|u1X88Qd?aSEspTG(p*c^tJ2y60t+h^0?a*X^G@Q*XCL)F zP;*qwBO-b8FhWrC6%n>J3!!(9(hg|}Ncj{74Yq+p^oOPp?JvJ){drQAp@jjTB)}R{ zviP7;U`;EfF)rS7H2<@j+4dS@a<0N$M# z&#n(AZ=eS}wg2S?-*fG))^Jt*9(XjlGrm(*a@GpZcsXZbnAYr3zS?r(B3Enzz#zMV zuW_9M&SIM|mN*84^jr)mHX0yUmVE}Df!Z5eryi?1yI$BV9I?Q1bVdXz88Q89)TwH= z(N3*1h_ao=8${?h(t=@vr5C7#TQrjljRNjA)S_+rP$zt{U_JR05ZZ3{8aaf7`m?Nt zgeYVF2rXhv0AoXVaEI*i&Z8jRp+s3hr2lppgLZEK&0jL%AP)%gqW^1XXQ9R#!8ouN<{Tri&9Yhp);jL5D+&r0 zg9lrogbtRMGgQ!8R0q$h5%*k$0Biu2=8^IdeiSin5Fx-;nql2_p!tiQF^7MP&N?a} zipI)WT2g*@lTMThmGQW9a^&t!E3BdG>ls0a^j|BRzyh^5h3tYKqk;{ZTLdah8FW1= z*hNKZ?@h;PIRw5fs9Xf}b*MX?tAB_PVF$#~vR3~ac&?c229`?naee24%@8l9MN7Qc z0%r~YuHJ<3Up<167N~nR7%V!2?BW=b6Hsk2aVpr!7$g_WpPg{Ng%O9zQfz638FVGU z*o=WBv&GVGh7Q`mDGUpfVay~3=GNO#hx%|{@;L=yX@@0P3)^S2xjo@B`%tWt#Rc`1 z5I%Edm7s5x`G?A?$PYf4QYM7{Cg8ULkE=>Fi4h!#HgM!tRfJ|65y+u$RfY#J?(4&h zFYGKD5;!KrGR!Kp;2<&_qJq3&oGO{M+zj{(7O*1$I-%VQGp z2-MdD$_fixOeECOfy3WM<)=3PdHaM3R=((bsn7;iUK{eHd2mqU9Sr5m&F?i@XM|Na-?@_+t)D8T$-^WYWD zDRcBh$PB;g?(dI%IaRwhN(x*6T;T7dg5f+OD~ilx==gGTQXxPliOqlh9P9D?aer^> zCDV{r(^O!|`98HWIi|)|wyv$Dp6mjEFQKMbt?^$~j@F_W=s-!&MPprN@j{DX(g^cm~Z2>%59*IDf}? z@SV@ug};k%jjr$^hZBzt|E63;6PvVcd~Pv(=0`BJGW zzH$nam-3V5e!QOBO)ed61LZtgywF)}??m$smR8Ij1gl*@5HQA)D31|<4I=+2=!HqvTsb_V1OAF&pkf4u&|b8N)nw9l91nK? zkE^r$ZTdc=c(D^Jj+y1yvIWj?)4bWq62{al3B&;pa{-fRQn5_#1(K~q%d$iwi6V?> zLJ%mON*732Xq%#zz&b*P7)-C-%<{5;*w$ z&hwm?u6BEN!q{+JYhfrX99X8LfMO_L4m8RM%;q=Y>ja2VOp}WhZ=7vZA43@8e3wkh zdIRG4Y?uZHpAst#jlo$s@hoZ2@vtx9I~fl&+(pqP@m2kmuy2+w1qq^iPU1*1q+~Bl zCbV4}5@NqShS7l@yL$!F+~5mKkJS@b3MDaEYm7eNY)2$N&t4Iauo%R`)M`gZBGlxNE3vG*~;|TJN?9`B>g)HIwIv z$9OM!8xmv@J!wEoLS?N2vDgAfoiWKT|E~K$*o{m1Sb8*#GdOP` zJU-n73a3X6dDAiDzD>8LNwqRih7hNd;~5nY#d?zz6{Zyc$@+Jah-TqkCQJSmpxH-4 zbgVCCq!%AAuA*N01Ic~vLuCcnp2*69G-+__Ou-#$MuG?1UHcIO-@cfO$5^_s5mJg$K#b2PR{aYG!h=UGydyKc9}Fs4oZ5001BWNkluvMnXb{qt*z&N@crY5_bQbC z*#kR|2$WB4+UMrxu}4R@HopGm>+ZL{dh+C>FaP+?=k~J$$7VkL$G7Autr{>NG#YZD zr0yx9>@OFdqVIwZ=-|RH%6Ht2^{)nu0Uy|$+4%eK41kGZ!Vt5*az}2MwY9bDYb)0m z7q4DFV*u=OuUsF4Y6u6M-DbqSvBD6ScDdHuW`!X2YiVk4zFVklD5`znJM^3A4Hvjk zHX~6zI8vCV$S(NV#q2n|T&3quB6rDZeWW&H=)a zTF7uN;`gWDKP>*c!vXHmmZzSh9i{JO8MF*Z+*ywN>fld1ZjjxD#%yAjE4W{BoKA#x zL~>^gtp+({8VgwzwdnG(+M1U}Ty7;(co2HmJ3j$*sy(j> z^m}E)?wq0I*^3t!*VY%#to>o`>f*YRu#Bl58A5ISCjhv3^RIJrmshyqcFGRbkwDLt zMOf!67uL#nfFCa2e0bS-^TNvf+|~JOr9YQ|k6j~g83Vq?occ168wwH8uNr3M^~E{t zNM#lDfjt|}Y}7oWJaA=?^gH@XW=ZovKa&v!db(*e$ze>W)nV*9ln3mY0^n+t%HClL zY%m^qwCmj_Nll#=!-}&4i3vR-F*^A1w&CDlP%12Y)GJ{11PAwd8AKO`gJ^WnHrL@c z8Y~cv#J-nBFw0(h+a3;jWGV6}5V~rcA*4reybnIS&!Z3yg0JeTsvyd!uv`>~fv%xx z!7!Pc1$;-^`?eRH*x3LU{)^(dP}NHEMgc{%TN0CkWe5LO;8qv(myK{IwqMM`twc~# z4%|v+bXTI4c3&LAM040Dex-yF=f=iF*Y3n_C1M#WH+H#ntj4b2k_8=Tbo1#%VmEcb zT?AAn5Lg-9hG|`h2f7$61I*#XY@$+)ln8YCI^)2sFDwalB2gcXHxLvZAa{d#v_6GFO%B{$1(u~=N0Ib+FRSX^3B*hC!#cvqK z5%}COY4kV+Or~8-WGvg8=_RM*glYwmU)h&5#ThMc}~KDh)e@+xsgb)+34>m0!)Q!<98NGY3) zzId;@qH}ih=86#de|mx8z}?OO4D&71;4!1Ec6GL3r^(X634NOwBPgp(m+kAsfKm>( zHnui?{MufyZNAJUzzqn5a&f~|A ze_sOT;(F0>t%cH_dEx&rs}Br-AGtch9~QBDUMR;y$SPAxYC6N4?(Jp6-w~oVTn1J- z@W@SC%OQg!&82D}B~LaR18#N&eEnJme;7FQcJ%|znO*8tX%u~YXlUp#WSBhYA z@?8Vcp6~91RZh6WMRIhf4<7tp_6GbF`IPDcDt}=IFfKA;WJGQAveLMMfsp}_M_<_k zJ54m5!u|Vq!GISieVqT`&IP;SM$cLRKLjV|&c9jq3Ta3CUPUdXUG3b(`L!ZHKX>(m zReN22R=oZ7E1Sppr`Ha+xc27U{N+3BfXldE8FJseY3EX0IIFsL&Cak^S5{m`c=36X zp3f|-&YwNI2mqg1fBc`B?L)>+9RQy{ckz1hX_T}J?JBN6Jb(7;_4PBS*ENDZ`ss7b z-_<%<>Ngr;v0L``G7MsP@MRgv# z7pxiFRzuMZGzVX>zJtqy!|)!D_P&HwqHx7yR3~#0OI@SURdqF=3?t$qIPsL2h%tjXkHv=r<5qXHst{B@R#j_Nu&Tf~ngriu%Djqq#mU>~WYyb9D3<7OV>oWO+7+Onkb$%F zErsI=)X=jeV$qW1Qw&GFLZcnxV(MiIeFc%#NjyksqZ^StBb8#5z$J3j^=9Z^gov;jj~CdF)2L0{#+6? zmSz+qhd*fu9KB>uiXetg+GEM2Utw7Ho7l1C4S>fHWTlX2;X)#5BSW`BCN+)X`4+n8 zROZ$6_-KYO=nT-CF$&2PdK@Frt7#_H6a&Yy+35_mf9SV_#Rh3tL3V zbT&IaPJESGdZos4VUyB5_Ziq`)rzE&2GCZ6=Z+IuwFU#hy{ZQWS`lwyb(&P@RiFNR zzD&}T#I6`^w4wcU2T2?Fl~Tx_)liHW+UUB0Ht3wevpk*gzxco@uf|@eWKouVzhm7M zJQm7o;OwMV-OdCoe0`zY`GJ91cYxz#?rJxuri9V}vTj!{WBQz81#9nM6BA=ohe3;@ z#||9WzVpcTou^(g#%$Nk%~RWl9&Idjf5V3P$>*PcX~6u&tZm+tS#1iOM;ttC>{TFU8yZQyr4G5oTE7cN+5vqGYZ9%*PLuxcq zY%ckLmxx^0Z*R>X#t;2^@Lq}Sy7r^vO5JF2BCL`b*kwYuw3MdM%P}U;)E>#%9!bJ< zS+h_>Se>)05#MSf#G^bKsZ9~Y5jA}F`q=^RcPY^B`m_tU{Gn>3(n6TKM|ZR=Hytzv zd{23r{r#>^!pVr-t+xHTv(#KFK9=ODU;hLH+5$^pWKhDuUX?&x+WuLF$+L?v;A;;{ z7pH$N@!#|1Y4Mv+39y#HXV0BmTstiQp1-`xY0~<)%QHs~@3+%~Ki{@juDC{aw>@%t z1$Zsm3;p~`apidewJsD-lO9=laTnYwx^yC@7x=$So!d{__Zi0P6S8q-VUR6m&n~s8 zZ7A_l)h*O94Aq;|TofWzmAF_X5J(7tgkcdugf!WtMk-TC1Wh8CCPKP~WDIo|+tRgC zXp}?Os@heQt8}Tfe`N3H`TmSbievwL08-@V_q^|OI5=-723t_wmHlTIm)|#(yt#R1 zW$WCzbL+QM=s{WtXLk1a*^OK0e}De`?ip-I|Ni0h;ft@lkr~QljuJ?_Y2_GoIUC)K zLWbbBgHyPK-3Vb2d4QZ<-0x1~GRhPGvYxnJz3yjON8Y4F&B9{8ZxU}OQdZwRVvl@8 zEiiyKG!D>D7-Zlam+lHr5`mLJDh7SHLJ>vVTW-)7n?y%V5uwaZBDmq0G_;_p5vVYN z9v@*FaR<^wWkH1l)oKuxbWjUm3LWTVP&JaT+Dj=z;aas2F9dsIK?74eO8-J{tXD}` zhQ}CzgA=`U5f-WjyZmwPBh1436#p&fHdzUCbF)%_2~+j^uu?8pTp(6qwKA~^OJ=8Q zEVz;@lea+()>*0vEAsr>$7)N(P&n(1#90!b$%4+Na+{S@OEkBt>shwGtL?c}vO5f| zQ)F@wmX%$~LXDAJty1V9O;swY<#0jiE*nL3c5(?#CQ#q_tgBYzD|O z`+mN(M8Oe>(CMox09K|m+0maf+9n2?h^(%*rIxO?_I8<&j0mI4qB;p`+%NQPS2^%+ z2&Y6X-Ty*Z(g1QO4R`~S{!_72iew1~aAS# zq!VX3%yq6{1J4mL;F*P{LTdy_1%nrOoI_dtEvz+WJOT_a%*@%%Id{KMdCm^Z>C*eK ztD|#s(1-U)qcnCgUqijFP~h#_>zJ1^5JWb-@AY3_?Vq zvEPsM%nknR;>FXCpM3M}=KlVt|J>QK_ijP-8O89gt++`4wUr0k(zi-{r`OEjRWoqc zcG7;g$0O4uOy2C>YkxGAk!xb?o2g{A0 zm5Svt;bsQqkuLh(&g0vWx8MGC-!?zS)X>xvKgkrn8LfG{T>_X^ywKvoDVGi{ld!8j z%8U+;djB9Ut&<|4D+^CPTVp$8g-Duh(6g|& zVnBUBAIOeQx%Qu(UVhbZ{pN#}wF4vN7cSk{+1=RPy-RB4&aF!uJLm13V13;Hc+C@G z9d`aa<8>iB!8?BGDG07YC%ZEq8Frg;`!-^7$VbUQXgC z2D%?nuVi2x!}%Ml#;alfl~)PEGAJ&WSCx;I+Kd_nF5?fb zw4^{`QnAh&o@UP)12zT=EN6jXz%?CRBDKSqE!yZ5nO4yjp)?L7QYh0DGhhowxs{G; zhZ{|24SieMh1P0ZXqSA7y5OaL=x_^A%Xm30`BnOAe>$b{blQNqYe}^W?OFx5r~BKY zs&vpIINfHfm|6xZkT3&lIBgKz*1y!Hgy2;%UOywMs6*;6B}Dq;vo{v05SgBWN#zo&(e!E{0yS#aA{4WN|< zt?8Sxa@7{hwv68Ld_v=A)vAs|dP`W0m_tV{vl1R2H{>;@JN?CUBws2fr=hrpu?Fb* zQi;Mr`Uus>VCX!J)z^S_3}+H^=6bRAadG&zAuXi0SgaHBj2aqlTdNfp>l#nngTTJq z7;f3L_EFwTBo;>pB!%u%9;N2Pjik%lXv_~ZAigJ5{aZuy%z_0@MJS`!^2cp!tmzE!kZrOYV^Dybu@p0!a~^@N0Px-@OQ>B-vx2!5x`b} zD{SWZa}20Q=YZWAT>`m6UOPC`GrBN0$_+4il#8APjvH4VVa43@^ySRcp_gAp+4M^1 zD|=`)`nd-F*Oa-lw+b z+c)JQnd(u!0O`iU8W*$JGvxIy^r)E6)!<~ho%#3ZVyOG8uGjyRxann1GJx*%k~cb) z66slz#DR~$)kNbDw(I$hQpjyl@*UIa8cZY-c{U~P`_PqlUpc-#{tIKk+Zojb430`xrD5`*rq5)GICrmFj+neMmzRr1 z)9R^a*rI|eGcM%#%G{IR!ZeMiuESv04sPApxN%E^;R8m)J3Evod?Na~x2Jqc7YD6) zX!~?I&^v!L06tJ_gE7^Y-XFBD@DInW&;4cn(iS%uzp5w+j`^^n7&!y=p)` z>b_>X`YFUy+5`K-*I3|A`r~SuyT_C{9BYk*WC{)=z9Hd=x(2Mf@`mz6!%_q|!BlaQtV%(jZ$i0Ok7Duby$qf)08jX;6ET1FnoH&| z44#O`)QyB6>6&)E@q#_F?1G>RAgTH7Ue|j>_~eA~UAc^02sFT) zJyv~akCGHCiva5(OI}4plSP>;*hSXGaa07x1^JA!WfCY2PjgXk3|&!rR_g5LYN`Uu ztx!iu1PArOsnjYww>`UR+&Gsb|Eh(iLc`=V36xza4jJJ^iKPa@tg3@sQdj9jB3e?P zR0gi%Ns6|ox{T}J2>qv>hDKisy|#Q+;(+}8F&JjSBme;vV99Du!U#5ZKW57!M^`4xIJ89rs_bphIe znW2ON)K0^LJ7h*O&KtgG?;7@~fO8)Kv`}EBLEG)I4q2A){W5(HA)qoEe7U2QcbiZ? zJQi}hFnWIzN&+(0%zkXV#6ArBT88jhRmr1>{yM}KU4N!{)!+E2MMPN8N+rY`AbZA03W``G(efHn&`Y=(@5lVlV z=+?CKt@o7%YP1$9`k7+DqTyQty+B+@Kt`7 zv45w6o@q7>9tB{{G*wuxcF*j}WP62Nv)+?#32%rr&f1`W@akc+iYRGA8yfk4X^ zG$+|1fr2j_M>VWU(Rwk(S=%g1o21e%s$AtN*(UXm?0ug17&RjH@i_(sg8cY--{*tG z7^q8TEC5_l5GD%qZyrEQ{LKTT0mk_XN(1FNIKZVm5c^l%^ZEFPp?v;T=GEC(uRc2` zuY}p({PY))eSOS9HfGs!`xNr*D^EY0oczz5eEGkxzyJP!ufbhHYPN~z0^ag|~zyBX4!*DOzDGtdqX{WhCL5Xbv}vEM)KTexbba15B~R}^6pjOVWso)wMn zkIn@kdmaqfU4zKG!lc=C3y$B|oZQQ?FkU-`KG@LkZ6=CJpl;|}`uyDFd1PCX-GcdE z(M>Qg`3m({=T!{d?Fl}A{?Prw<+oQ3Ls_7$B17DKM=_KI!G-mT^VL!&qvL06d}&n5 zl)(GwTY^e0Lknyvp3j6TFAvrreg*(Hg^8jfP;(x!t2a9qSPICbEX}++C9t}cmyhPg zMu*8&Yuzm9Qs^Jx);mY*+c)b?j)@T{edhrAqpf>#&}yHY2!m}ljn+Z4(|K^vHjI;2 zW5alO&oG+C<4+y~PjO-Gk2^c70N_dao(?}mZUG@2N!v(@9lTni_sY}7xe1do%#cNL8Vs&P~p zkEV8$W4oF~DM%eo0i+Q-iHBikKm&h~OBvo3)(nYslo%Z4Iv4%HDT7W0u?WTo z8k3OYoMdrQEvjc7$uI)2f(~^7N0CSAp-xL^aMjOsFcT%^Gs6x~@b8WYrq!NE4V6oN z_S07CHwG_A-slFvYfBwcei?bFBSg(ai8*U_0S}=T`MXc$p8{=mx=&k#> zbF-UaRv;ESX+m$&?$m%RX8?2<)9Zkfu3xJaIxHknf&oAQ4M7S-Sc23-hGVcIkt~1! zqr=<{b8w$4=5j48FqC7_wTR9mEYTJj(t${<(O6(Ha4QC(X>4wgVUq&0!g%Kf9}T8w zTwMPOHseZc1{3I+(R5mQBGT=9du`<`f*DlIuU>ls6 zMiC*zS&&iZ5?!0G&b4!tc`alAyOPsrj`T9aIF#e2bLsv>EQg$E_Ajh396E8sRASBK zD8eeg*A0L+bD@<0mrtvImGG9k==&oerb$VKSY>kwtYc_ye+7+sYa(%3No|>vXGL83 z5QGMnD)1^HR_e>=fCB3Up}zvQ1YiQQ&}0_*;`8!lo<}T1C0@y^pemk6$ACadHv7)m za~Cem&(BZ3c=6)W(<@J&{6vBI`t<>*pG}c7{IDernur5^L+0c)6Y5T&L3*={r^qS; z#yEN?^HufT>7M(h$=3{jp4SJM5Kj)PIryqMd>$r74}38ynClkMI@WULr{ z@W|%4h3FYq9~02s$fjg4`dr^)`s<7tz@fFk1Km18)0xBqLerKc$Cq&S(EjreemQy= z@1{%+g>IYPUsE#_GTlgO0S4e?LveFQEZ^>jal~W|v2YI%oP`7}9)J0egJRfvPIgQ` z*pIfb-3mfQ;Z-&eViB;$&I7R56R6V#H#-loL*7~a;m!4@7qaqC`MQlw!I8jdqt!Gz z?PjOZX&tocg1C)F`@pETo5qH~ZL8C2*X2^%sLR179vSV{CZb0-Zwdi6SPZg$c8jrFaKy3yFG8#e*U8}jdH9`CFv06!gm2Tn6h2ID9M?ZEPV(`jU; zqH!jIpP=~%N@yj)*r1zww|MEx8M_6uL=!cgRi!W#NFf2+BVxm z`Lu6u%J+QAW*OmRS~tZ6R|^6=3VQ;um_0)UJ)+?p2%tnYu&;>m%YDGM;Dk1 zO+q|2R!D;9%BiSOWcV401%;Kvfm9B^zbaoE0_ZbU zwi7!1k!lU%E1rh*D(DwH{j`^+BY`FTUhxzv9iFb zSCh|rdh9U$3KHA*tyW7Ba11t#unr5nNr330K(PH^Zh5N3ZM9gec2*RE@gnrf%|>AC zfLRHQ5wsvK;-G0oT96keyetV{o`dtKZy^ABFoK)K=})f+-Aqige-QNu z46H(ZFPn{~nYaNmObkZm#`Llv_w=Q1}h|&P4{mXfX(eNy+>rYrskP=TjqROG5B;S4KO7jbG=Khs|#O@pmp+$ z33f$~6^|>5#pX&Fr}LFEftS=b57Ab|1Ze;;u^1{Upt7bppJFsnnkgG`-iInY&gXBl zW+3$H?AdcH{^7DSf2w|l9?9f6oFZn3Rb~O9FkUl(k{}EtQs%43`+o|2(Ov(l*=S(0 zdrNB)L3#M9nv^Kb8o0lVijkO5TY*_O{YP^Gzk`T^cFp0fBDgO6?I~-}{ zvw3{dgp&QBb#TyZwGNKkN3G))t0K`gDF7@`y|ec1n~$Dcz<Dae2;8>n!g4n^9z1LrM*G2L1KV6f@K+8DJb(L>#|S5_8yy4cYBJ!T&1drQ z*FUUc1iiJnDb#vvduyY!vH5ttzC~5`=4PXF@7=YvJAeM}%|{Ha3I-AeM-ougcR#pYAhv?n|cP@(HJPPaN9ybo)(RA7M(;E2Sm}) zXXD9{a8j#-r+~WS!LVF#pjaX5fP5-EPL9jvu7GoRmvw~WW;cVQCdfMuWUPVxMiGg{ z8MU8PN?^zW!ch;}kx*6$AFu#uts0CVkJ1xVd2`s0z9WyI^Ig9pvfM<1ptoU%ns;?7 zjUlq*E*8Fy$OO^zjAx=+MTi#m!Yn@O-%ZzFrzitmT@Em_G~c_h=S`M z$e>BFz%e$p;!VmX71IZ_NK-PHEg@nguvI}tVfOIC)~Yu+4kQIX*pB3shOzb`ikn4f zS<;(X(bu5Nc#26` zEEPsnrRyz-sWR3%LEB!_?k!OKcb0fi0)Pbum%el#nM&vmL~}5U(rH5w7ORn%houEb z4z7fqjJk3P2XMHZHyucXc2oOo<1`u}95x#^!RScEbQ%s|Tp4B3Mo>^#KpB!O>Y;_^ zF38hUU@rhO$0&BX*a@Q{7*3=>Fx~~3vpSQ4OG`Nha0teRb0}R1#tVT_FDiZm=m6$k zIDpFB0&mB2@mwza^~VL~S|pPx@0w6#_6>pZMw8)!H|br&;Up)}DS~uPJ`p8I@ZLf; zwMO_&3F>nDyK3f9M&r0W9acbw8%gMJ7<*n!rNb%CspZZHuuP?nQ)qXHr!d&oOMo3r zJTZV`8YW-p!~nd<7*$Wh^_%m;!kj8l0*!CG;Pu*|f;M}AFF7yeRF@7U9X6ZESIedt zdf8;ZCJF;aXI1M=!izEUqzbI^%ewxh^eT^qurk|Ou79~5&YPSU2Z*$JQ@rLXx+S)-1yX^ zqYd>;*-!Ab;+qi~C`dd56R^Cza9#b>{rCo3k2qq!)hBd&UXl3L#n$)Qf%TvT^p)g}pCMK0VYrAf*ygEjaUV3Q8N&We0ukLN3?9eVj&L z=5ri5umALy(Z`_*wN(UL{mGePT+s;QH22_C{$_m@=1ZhC`YGhA@Rx$sIG{L9@mhB9 zcihi5%G*L6PwR(=r;Vn(MLPxt!KbZi{je^eh(U3^Su;+Wheq|VUaXze$!beyXIgjF zZa3LpwDIQOyYJ3}IDXsO{N(P&6FJ;&7)G;Ms~N4h{(-`(A8$cXxEL`MSzd_Ed1URNiSccFOWszuvyLzkiP# zV4=elVePm6c^@k1FYtqB-_K(94Jc58v&iUA#HN$L!RqRDSm!bhb^xPh5F8lS zDUh~+zCzXoJf?ivqQM&$#!bQ=Eb!{+?d=eB2GC>N4CFR}sPDkr;Nt{*eiY zpd%BDXh(V=oHsV^kI3~HZM_kJX9jFw**iWy6!D{eP;R0U35(wmE`!mDG(>k2Duahm zjr3rAWNQm>91*~c^gqDBdMjeT66x1;O5wT@jic;GyKn#2!8#Vffa4*#2rv%}9U$Ne zhwXys;I_=Y!sP%v-JyP$!0Wnc00yUZ(IV_}AqIM&2lMBiVFIol{Rv+lfG}eze1OWM zsVVT`D>MPS;5l;jXm*F7GO{j)EF{{QjQ^}Qr<%aox$V4!X)qxoG5h) z<3%*I1s#Kqj&4Yw9o+l&IvES?a3b>*c~@xt#d?>sY23mTTBxxN30asz3(h)hCKyA2 z1#1$Xbg=bB4Fg^Th20dNPzUPS>$*9LtZ3GkV`K-NsLh7{7$Lu-N%=s4r3`xuqXEwn zS_c={Xr2^WEX;O+l?@9^@zMAwHoro01z>~0LUL3%?lGDd;$2I@Tp*W|+qqyN=uM^q zUwdIT^1{6%R1=F}Sb*htfSFgAJ%>5gMH-fOO~|j1g z=T(}K)~4x8!rORM8yYZsMq~#z#;al8G3;HX0a)N1`B+J&d_d|o&AP#9*r4QZE`(7N zELY;w_;!;(<^U{9@F#^4@|EPe+KbA?r2GA^CQXa)q-vp6@NCvEfcNrno(|v(2Ao%j zUg4N|cG)x@>E@UGcI5}lkt&??mv2_ofux-GV(Lt?i>lme2q=PtZATK_^WBQYVNV@ zO8_{?v}YTWpt~SQyovt@LAOUvHFZ0Kd=A+5JkGu3v)|~-mvLBqmo@z4Oj}+nwt_^B!T_3xkZDNkCVX4XMh?m#v`k7C)=J{`x`$?$aQw6;-D}~?bp>-6|>@E`}}#`XdX6;Z`$>`(QY-3TDA2YXlv9kHm)^WZA_J$ z&^|rYNN7||w)R;^_-1zZ$MZNH`1X&RpK!Qc6q;PE7Ue!o+n|gIFtrl`zy+^705Enqj6Sm%LV_ z@C)Kv=C~w=b*Mu>4U(x2u6PC2wWrWQk+U_E>CO;mq1x&NLT8}17Gy;xrG<;+#omX4 zv#14rh;Zm$0b7f(TXZih_IA?*+>7}#W1vwEJjMpXiA5_M!HWXHV{+K9i5szr39G=c zpOP#;El3zV%XL9Uc|Rrq8)LvTsu)0f$4ACMjTfP5j>t9GlCbd|87J!<#}0Ue!O)S9 zM(8_=Y>k-R3|Iq?+l2}DkH7{j=W`UbD`F#8$PXyjA&pp#*0SglDYDnu{gTNVcv6>{2S=|m

7m&+RQmF6ff;%a9jVFa8V;arrGiJ*28V;b>w}5m?bpM6}$y^+2tz$qfD6k;w z$K=Jw#|Ywp3(1>9yajAY0eF1lNWfysa+CxUHeA8q0#(Z4)l_Otz7~rI;o^;l!GRG* z3GR#aue>VuVhtQtvoP`}IeSLlB(zyM`Kqf3^AMOtF;YCL189h>!wlmnL?OjO{jWg( zbo7`dg$0<9!uS?bg2M3v_QOEnF0>&{PF@JHG~sG?_UPH~U(PNc0gUf+_I$D5T~;Ts z25ii(sJ94W=UEe2iOy;4eoa%6`jAYavt9(bl@trgVuwrdvrd*(@2ou5oI-=)$_GL^ zh7PS<&YJ&+?vnAQb@z);1>4n?a44-EK77MlSxTrTvW|dlavi{)Lc<_66cF} zM%BTy<^iKIXok~hL115HX6EJk)jxC|G57fbaOW>HSc<~j0h>Y4`Z3y&JZdUpyESys zcAsoR$>7GgVXypsDfzW5KQ+xP$BSE_wR8?fF64!<|qdFT2s){e|j z39?!r!0>4jpwlOKLHc$4sCVun%?q6@< z+j#~Cym?YC)oME>!QW!lDDD`B0CBs$Q#Ps?7q?5>uMj6`7^R)YX%!_%rR`HWA2=&- z-!muB)kA2fKR@|?_vg3X_W2&4Gm7%Fv(KK~{?#kBC%?LT7wO<~Z+WS2Y;Jts`sV0^ z-M{@q{;4qukkgdGtdd}zlK3v>A$ppIDKjSv$oG7k4;coP;uL4F0!=~UMHI}#>Oc^O zpzI?GupS|GBNKaMadsjp63wq2y^ffL2n=!Se~G&OpEUD3E)QT4GFRjv4Nk(q!UF@- zWtyNN5WzNl-#ZY}tq# zxg20zK-_F8jshfi1gqgJqBIagnS}MoO|ez7loj&ZiIk1_o02V=j3cW9=A<}a7#<_R zW%(RjOHl+Z$ovL^EJ0g&P^y&7hWa+*{)j7u7!F~-LSI!hmOoSq^d&KAj--^M7e1wh z%|Pge%a2OJzyij~2&Z((=Lqvn1zZ945hnd1P+LN4JJ!B_J`xgWZgAWE;KTy1{!Nr3 zu?Pt$?VoQ?3-Shpz6#%+KZ!@USU_2UuzV#rg&}?J zVyI+05~L}S4tC8Wa-$m*I4E$8JuhU^xTm|@6-*2KcBRwoZ2$*uGk=uwb9Tdt=9Zrx zI-ptNfj~8l*E9rf2+_500BwOJOB)CJIy;>R!2;}BGaZtg!BzNh;XZr z(BoxGgWViKV+cob%rx8%K1Vsj>}8k`jJ0`;=*?%WZ9P&(u&#ymK7N+V#opZsGG`ETB~15ps!MtrK*8_C?(9n zyOg727`;e{namxi4nt7m99j*1>|>xhx>8A0t2t2bOolat(0n0vTK;-0MPiYY{Plfs z0?Wgq)jWJuhB4gn$t%^nFltu)atM9&!R1SB54S#lINEC5FGW>!A&rvuPQQa)Q+GA3#>~oKG^@6}V`}nD0z3^URjXcp zOk?gmX3DF0jH&4~u5k8@_{-T@bK$EBSXrtNn*!>}VRi~tHnCZrHkojY;a311ZhzN$ zIFwcq`)c6Y({jT0nm$mBVAa+a@QceKY=Q@0xG;jI2l(Q}^QT%0=mAv+{B9qND&PUr z5qx@JU@rk+b%vo{2qSU>dC>SR#!E-$Lo*+Xzv?*3{|4d76Gc>pIepLGKlA?%;M1qf zOe{*E<(;TJLi^Fk$f*%zRgRqA^Pc_HN0qH!vsHopf*|#*2d2Z7GkFzcJT*Ahk`;mI z_iz$DsHz*V0$wwtDSGC<1iURb7wa`hiFXBLpYApVWSc+Kgc8?|mt%PwznIN=F{DKY6ShC+rNB&NWS&|pu<=Yed%UxM=-m7ymGT~c=%eb zY%eyKZ|yf~$MyRDt->KVaBcreVYvx>Zd@uXFVay&{N3IClVZSIw|{>AC%uD5P(d#V z0sd-bXaA;IVfgwrK4C>z^zrfIYuB&ed;GV5-~R5*>7Vwh>GGhGr^&y6h${)^U&YpX z)$hw7qOJ(eL!8?8j^SIx2ur$L?1*h-!1kkyz@8Ha)zh9&HR@5k>8=wkirh6);X;!;FzLZwwg`;jf1EV<() zkl$=1DNt*B156cqOMenVuu2j304EWOB`5mgDXe?n^rhmF4Pm}nc#j02iOE8e1Kb7s zL3~rxRYCI%B~~OAU=k%_u!Qk0_yfrW-W%Ew{Pm;oD3II$$z|qbh>c0YiXn6+9xu>m z6zJMOAeO)`?tz6V(0(ImI**{of)@$%XM|WOJZA0{N*M%91tmG3mK*3Wl!H*!0K%{4 z+k>w8Acb5w1kX@0lq+0q)R?}B*$Pdjk$Gt9)XqE{v!A}o$flBesq$R446p= zQSp#&qe$Lj1=EEh0NJ9fA=D5=Nj)BZJM41t08?nE#sp|;pb@}fcWRoKgJ%x{p;-j% zVNH@9O~DSYmC`GxQ=V?Dg2~>p6Ll|M#8z6_k~#qnV4r~fk@LACOiEtnVhO#~SLG>6 z2lxtQC>M*U{`H27Mei#58NB6a)T0+yi@NY#9Zg7r%kr4A2cgi$%&Hv2(R?_(8ZPUG zuMA640=(E@X5~TE@O2nQVy2qEn?HbKNf0fe3ql`&=~e|;4b~0$jJw0bDv}vhz==E- zvvBO@6Eg;c&k4ptjA8GD2V`HaIS?un!mpB_kic@M^l1IN1ug znx4*GwtRWvvsZ2RN7p|+aWs18?jsJCX9>0( zCKI8#{s>~=#}iZ)d$>l_Kx%Dx5(LO?RhT_w34qB=$dosQxryX2RyKMfNU8oQS1{F*z*=U z!XA5gf_~t#?hS{Xv;-^RgTw2Y5CEPC+pQh;s3-sIyo$g&ZH8Xa6+Ck0oe9`n0=N7~ zrv#YSCqF&=;qV?aieqaG00W#dwYX<$$P}IN6^ANilSC5->KIdwUy&$LkRG0qb`J2t~`|kM#s2SZye*}_%C&0q&#q`*<@$JqVUdR z;il>#m+ln`JKMGGmBqtC;a)?|E$tKv z*Y+FR+x4AGg~P^cIkkW5@*#phz>DR}HkH8;wlK=Yedw)1wVMWA}*$++q z6#%$~+>YIA*WZH*`uD&7{>jhSIyo3at03%HYeR%rrgpN!(bPKQ6^khz2McD?1qSwO zsINpe*5Hf0SA$d2sd>g(L+EzctW2P^THcb_z`TpRjY%7(%MM_wFycu^=L7hLxdcRp zrMx4?%A(nX;IKr&L2cH!fa?R+1S76PBN%I)4BBub!GT*|;kUxLA(ggKj-@JwzgZi(uZ?(%xinV5azjo>Y$Xh%g$0*T8=UQnFdGZTBLHw8 z%t@uv1`3i=S(uGrMcN2Oa0!s^!z4P1_r6r0Ttoj+if?@ZwFORXFb6siO7;l?3x!UV z(PQ~^6-L~_~*$977gIgqx> z(~;b;t3qJ-f3XP;dz@Ae68gLtETgI%TViBEd-Mr!krU`}xT6d>_Hqm@7iB}A>ClT_ z$VtNjzD7B(qa&%K2q|<_s4*N!GX`oI^kUQ~=JR^AdXQh03luNRB%-QqFfSlHgCwk| zt_uF-)PdkGw!|~hVH70^C{|gNgq|WHz;}o9m4uPWaqvrGT!nfWwMBr_#MO*yTHx}x zk`q|I>SG*MrGk)+95S;q5Luh6;|$T2<|Fy?*fC@BEL3?Icnd%lbY|2gUIA39)eQdR z;i!=i#tu=KoV{xx4->O?D72{2iZThSztwVN_8|S}?E2{5^R3_grho6mx##`HFShh^ zFaBsvUApjR_xiJQZ6BQYeEs3MZ|CNY&Q>^sR_RvCeWU;uKymKvKGtkx4Vf~M) zv;S%9zQT9`2mb#-gKsF2DbZz6Cwt9Vaf~`(oix8Vs zMXTdCWt#X@pQVKY3<(*-rY!dje%DcB$>~T~0Z0L}|22JdpfC8_p%Bax_-XU$KQ!Gt zYZV_E5VrQfXWOmeGrlC_QhIybu;Y6-qN*R{=^b&xav3f=C*(=q?On(0OZ%6G)I?eZ zqSpyUkC^`w&bG&hu-e;e30P(b-P!(L=SxVoGNMm)S`|rm9mB)#EI*AIUsa&iH4z|G zQpeJXS_lV&_t6bgcw{;Ub^E!&bqP~?48m#s!N}QHiQibQ4P6(^7)Sf@ZQ?m zv$fU9Yx_B}Ed_}y*K_e{buL z7@<~Qe0S-Gzn4phZypK*HaVFuOPX{OonwMsJgA(ejNu>hZG7GNV}9!?T}7m-7b)oK zyJ_zWGL80RgaLnOw`)R&J>x-PMbH)C8s=WmqoOQ!!W0|Q4NQs#8faH$#qa;npV7A9 z75|EGY8<KVT)q-Nk1pxGX}DX05fux8an`)`Iq&7TNxudFoNH51FPi(bze*BLv) zXFEjLBmWR_(AbbXp);?v=*1M$I~tMX*W+kV$$UKn5$Zdz8M$>FU2i-}a_QDE)}(o- z4u^ZDRproVq{-lD7}NeEyhfm`fUs9kRXYngCOAFCI@m;FwQ4y`tGB)h1y;m6A>7z0 zq&F$AR&qDe3iZW`#8v&|3IG5g07*naRNT37eO;*SEUqNF8OVQjKJiB7M)V2USP@~r z(WG~fg2IRZZqf;(ok9oQ7F8>7av8tTtl0!7ql3n)v>erHU`#y18`!qazDRLE#ZXDA6qwkFiAJ#`2p2hl`790$zgV3d$~O0EZSc zXdCc|nKx@BC2L@TRp!#HhevLhb?}?)pEdg#$}1<|P#R3)hGt+b>-<|T50V6QX-wCk z@hjsI*7v1WwIP}JTG?R#=C4oOg%7{_^ZrM}r$0XL8{TY~dzzkqJa@f+bMyV-!~RE( z&8u^tUmQJrD`GakX-ipU1z=sAA2qV8%}s${Yh-;ft?Fnc#-rb3yfu%J#d)oL@Td`F z>FxQN#@VQ!jkIdi5?~pzRch2a4(07Ixy1q1K%0@Xw%^uvzsC5xVZ|x}F)^!Du2yzr zfpJ2+fK1~;ZRMvztf8R|=FhJUDHI?2Pyeamo@PzLZ^v~3+}VDt#L_Gd?7wG^y};Oz zk_0_BPEB-!tLp@svjdK3ysERi8*#&g6Wvv}Q!YwPARNOWRMOGEy-n|t$=T>U?f^d3 z`F~=p&d&Ev)w+>70pN45zHv7}j%31IkwAHeOxrKmi@rM+NGA*ys}l)%Q9?)4iP6AI zhOFSM)}`3LDP#CZ81P!Yx+5%Dus2_ws}>K6ySXdnUtTB+EzUwu3tIxo+1Dow^Zf6=dL1PDjH1Ird0&9ETG**pDwX~H^3G0K8?6Y~ zs+21PTJCQZw~n$$IXaR`d7-lTe6Ey}?yAbyQfD`@(>+A$|3AJ9_ZMkX9n`bBcYNNLdapehQ--CLJwddVv$Q(uNLe zioz6sNd3Zrz+szLV9}U(>lCqzp+%?IHt6n{W7;h!3l+A_wA9UvkwD2q4#DVKfc?O9OC71sI-Z`f z-5L;xCjVKW*hUuv1|-{bU7V~At^U=Cvs-AaoP*{Hi!iPuVYw7D0J^>L-gsQs!yLt^ z1o!RLzs#BA(>-xQIl`1QU=|Kf3)a$CNZ1Dc;CLT0sbG&u;(!e^Meg+(<+I)wFg9Tv z!3;RdINIe?;PsJ~C4d?ZXI$anpM8D4OwfmiN!V^rMp-dNU|-PZ*#=oNKHg{0sD0a^w}vziLEt z(>+-4CiP0o33<*m;6QTgszOu68>}o!S{jHPC-7Ot&JFdA-myAiz+MGoLN`nkF!_{? zgb@(cp|&Jc&zi|$6emofz1qs47A4x)nx-b!HMaozz-v@DLX}7>hTy0Z_AnKhl0(r} z(yzMZr7SWy<$W+aF&lkA23E8!A{gxLCYCa?kW3B=Fekg)l2Z#PpxFQ;iax2nU-rIg z^&y3WFbf#)6Q#Q+2bUH`l1u7bQiqUWT@oQO_$Hr{)J7!1N|16%twkzu9#MrAJ|t~q zpp~#q*Sd>HvQ&V@V+39;E{`lC&Qj~Ib`T~PX&I*7=;Rv<0_WPtpekrNjfL;Xh!F7+ zVZF0t;Uu^v8-Tv#t z!?wS0;PCpyV?&NH6{!N+x39fw(`@jWBn9LK0=?X6rcscw<9T zop3fI-`$`zAYm=O0~)@OGUEu~QtTEg*nwFIUBU2<{6|NO7@8zx_C9Y=k zLOze?CNJz~cLmM_ZL5Nx!cHeA3j&n8*{y=yC@NvSRv;_7B%oZ}dnkX(t40O=-K7s+ z7tD)&{wbN=JJo81G|MV)G#;6^viu?Ma!*L^kxrhoC4qARV8+^|D+0h+n}h>D+^Z7* zvHD`3gsqL#(@$3~mrK+{+))PnSBB8f?pR%h0>I_dg<}T%ZOkYEAh#Q;gC>hboZSc_lUZ z8G+p~wtiy{p}=)@8fI08U|G4bFOd8ZBYEp2UEpV4WEfq*Yf88yb2Hg^u16|L_!fJ6(ce!o!EI^Ta zH4R!Yw97USH~Ze6uIIg=aBtT(bU8i%)dhD7$R~wTMU-1`15)?RS z_iS$m`|Q4qD?>7L7(7OSg+z-?vl{0G(gy6xorO(ZJRIox5Y6O41chXR z#Gn_!LE^;+=HimOT$UxvepvS7{c``v-mlmD11>1`+kRUgQv3S8-tX4~8X8)K^g2k4 zkqnKqLvsjbjR5H4Av8*ml?z}Wjj2JNmFdTaGs;P(~SMG_^jl|yJN zEk|yxV({V|t5rbO=M)wUhp^o)NBBZVp|@DX6~9}E?|{{Z^8v*^m(}G{9jIzmpcO^* zRYY)BsDsnRVnSfCkmRa25{pHKUFZX@KB)>r#?(&;EQ$z)`^JW2Y54&c5*NQ6>6k#X zYMeogDO;)`6H6ZTLokiWEgA}e#2q(#Z^|QM)LhlTGkZ~?l=F|J(y4SUCP+%dZ7PQX zUJj83O2_bXj3tA@fzgO`_AIx*HS*mtx{-R$=1>nTPfDYQu!hhMFk+x>O;|L{!YRg7 z=9uo$L5LPeje&!sdoU*tjPX*yPZ<{VUl>$Fr9IX`MV8QEw*auJpLb-?7(_39dTP&h zf92}A*St(12+5SmM0PMvvtNIR2Gtor3mT#Wc4MX3An z4#rjG^t8^UeMNiG8y7&14Es<3Y#+9>DT$>e)84V?M-Q1g!V`w<8aI+If)$aEAKJIu z${+x2`Rxb4_Adoy0IW0AmX)dcCbV*=$+AVW;N`#NOjgc8%yCpVVSw z0t^0P)vOE{i5}l~UH{=xxwP7TdQkuvxsw9BENB7=e)9#4OOr?hdH9$+U;yx!`!i&_ z*#vtAbz70pHwM^lp1z66UgE4D&@LniF}MnDwKPmitsp2cP@6y!s?zy&W5+eyc7 zV2vy}lGUZi!jmAd5~#$I(J4jN!iyAf&^y1xeA4gz!A z+Tji!hF?V%mcpm`?{C4klE# zvW~C;fgA$O=UZCCm^%wHYc@18pXX^L5)7tv3kF}}u7jDCjGmMe9>JC52t5L04za;d z2(G*mcD}-kg#w?1FF53A5(0cagqj9us{ze*jZ6ZE#~Xx~`5R7be6iTI+`}YAZj~%< zBtN^g6d1#1tHwJEE*A<;%%1C6@+&aSjA+JRfd~uLWjQd8?W_f+1=4MDp$FiGWGgBP z3M12el%`&MNJU^ff;D(}V8G>e6$NIs92nlo*sv=$J?!(M_&1I?tZA1IEx<41{zyDB z-78GER}fh+xGEs*7ep3*8@m~k6Hxj4GS(Y=SxrZ@xn3Tt#b}>JSTyWK%zpOAs(3h! zo+N}nrv(0LOu(Q+7oaO&HIy>|6S=d6!b(@a2)tq`tYagufiYCGP>F1JJb7X97u-UCJg=>+N(2X zUGy?aqic3lZ~-e}tZ~)hOT`sy19ju8VMV)qSXEgGP3i@)rS_=I{boW#p34lxibgf| zic4Q`T~oOLlPrgcnQYWpe`m641KuxOIJ^juZ<=tDa*Y?CF{1G(J(*h6RA>3~j-3rBddvdGg#ql)FpZF{2JGI$ZNn zZAsRuTl#c8A?9JSnrtt)ukl<+JzMPkLTYk47s1?hmto*{!qYIHYR2m!sF&{1hL>O!zX*~dl>@KPEM$2cs;XcR?6<`+FV7lxG#_cf+P8tJlF&Lc{#ko~*@@KL z!e9U%cl3*~)ku>~D-dul^%QUU})pV?a z8|6q&2%Vi?RwRK0%PkFO|eaNH$O z8}|=Hs%dm1#pIN9uRJ{sTM|^n@pP;jhp!e|E1GxEfh3S7aNSF#G1z2|wf6vD_-_H# ztV}>xLXJ~n8hjyQPSvoqP4yTT5)M;-CR3uEA;-hqSpn8ss`i8mXzgM^d^Dbqkjffr z8G4Zc-Jy0Q;BKxb%{nC5jamQe&mk9D{%9b_xK5B4sXal6X1eOv>@4qRult#TRU!Cx zjj{k~w0|`{ba3fa-;INRzWUSky7hkl8DYxnXRcN%ClAkZ)_nPsp}rs0ePY$pg^^J+ zf7Xb}3NRM4=-(V(>aUFCubz26>Oc2vBtN@a85uQ6kt)hE%U`;91H{}4J-?%BEJ_$< zRYG^am1iIS%DbBHUw^RvTFy(%RstHb0iSPFN7C3$22A)y!2Do;UP4W*?26-#H=)R* zn9b~`ci@7iUs4}XT`iR3_?b~0N{9Dj4ow?U)3F=YC3uij{!GRT!h2#jiSmF@;sZu~ zWdM1z>Y@fZf}O6s$pO4}-vIv;xZ;SN6hMZg0X>{vd5aezzY=DQYtEbkuuhx}2Jftb z6_pRMT>1E+cX5=fh@$LS3XsXEwkTWHs}e>?m@5=uF%{7}H3I?Ve~irHXueD^<`qym zgAp|N<<4k$C%d>dtnJ_$v%}VhW?;N%?l^5~HUeR(>G_c!fb67a#xQyX!wb zjXA`B77YL!2!4mX#CIU@!<9R0cizgYLYFm#;WKu*fZ|DryKdipi&tK}b?qX>T|YT0 zf9roey>MY;3jFttsVBzIFYdp&FDw}8(aRSuK3;tK?SCd`Fz4Y~K&in~hpJp8N_{9P#3TLll1XLL{4EiyJB#d6l$ zsklM~9X@L<^)LWqKdyw4zBZ0s1=STJBAkS)Lr+Xz^vxHuR?Eu1vbq{L)N zTBa>hED!{dHehwmw5HqArbVf=08M~|bxF$FG}4kKsHv8Qb~Wqe&Yo6ah~)(bEv}*W!Xk`=$60 zh7B~=0OTmWA>+8&8UtNrcaXQyi>_GmP1Kg`Ovz9hDvYg}m82|+ajnQPg@oBbf;ebo zFxleS@XG^=xm}kd=Hag>sOMWhk2#)EdTq)s0yikY@O72YS=wQO43~ z${LLEmUQB)t9YG}g0Hd~oNhNTrD8#oX@VtV-B|INNIHkNG6 z7FryH?56ErbpN&sMClwfWTw0~78dU%eG=%Uh@mrP^ta&wkF&c!2vXS)bU9Z5FGLrj zY`2WrRv@rp1#(na9qwEUJ8rD;^BS{f%+1sik_2scBj_qz*;{GIc#B6Fbun~iDj$K% z86vSdpF>CBPcpP%#0P@V*fC-NBEE}3dJ4alpQ>qX8~Ga*N z{mmG%0{(y+2$g+>yTq^3!DeJ&S+J-yg3O96E_(r zv_4Ltf!&&9_8d2I%SKXNKE51JoW`1Ux-LN?Rx|@^{PmTts~hgj40kbcugv@Vh`O z;lh4rsj_<+j`lAY2ktK;`$`6;e$b(@p)Vy!44aAAD6o126XrfDJ0g8!;oQi%97Tk% z<^B0GMMwo%o|!!x8#b8D_22C$3fgrME2)yLBZ#;vnhJOOHJP^4$zwZ;lyp93yV0DN z{On2+&Sv&)q4+MHxi|FkORHXj^S8+By^8gEDsNPpunTzh;+uE1;9_xm&%T%Ue1CK2 zz|1dOKDbxhI=JM<(^1dwT#P#Bl}nqPPC1U7nodd96e+O-L`;kpy@G}5sI1IhIO7;6 z-Ky`X*Y{fu*&iL7cE{zy8kGY}erR0Ke{9}r^LVfFo?Q*_u;94ul)P6bT@Ax-H}Jzq zAl{0rf3h_h#|ORK>^#r*pNQ4E0O_l(q@UaSdVo4kMWJG{TJwMFdfr3ZHaB8M!Ug@C-9hoSPiO?Z|Lw$BTJ5b5Zv&Kf-v2#;8CT?yddnCvO!dkYd9W}+ zR{{8&cfWTMxAA`s+TS~WZFlT^>;C=kD!_QKZew${hYQwatCE`va&3UDB#ytnj|Oa? z$Ug6n58Jo)^`9wYfcCz9=jof*zxcxN_w8HvB?DhK1pe*qPtKpe@uz?O@AY^8G2A7q zcgp>ONIUO=(z@`L6|ZVRcB?T%YWqn=-OM_reumL#H8w2O^I2X^gnm|mLsLX4_%?i~ zyY$J0Y8VW|YeOsmhiWDI86AG+N`HafXX;C`=iznPpqnPB9;C^E-QrrIwXfux!pMx* zS`CB~L`~M#WNA5^(j2pwTMSo_s*`x|U0 zVSi>jX)sM4a5r^?2C3a)bm16T8!>i`9vHql=;cFrE{vJ_gdknO##bwvL$9R)+jfb& z9VBbml|i!R&p~Ox#&R=Qvw{Y=;owKWbVqweSCvYpfuLyhB{g)a?Key}Lnfoz-wcN6 zF!)>{fCC#=<`;H;?{kgv2l$(ifL;Cu0WFd+0NshH5YuROkkEuT?Dz(%uYs{KTKrb5 zDv1Zz>&>UQNe!S?5ghP`z*>V|zdiL3$A*Y%dL}k3jx^hHcmT3GD#S8 zB6pXMX)DBw#cI;yL}WHcYeAx{0(%#EWyEnl*AF``A5#?}v}!Q?*_oxy zgPHM%4-eFiug*mbfEORlT$($YJFz3*)x|USjt)IJG`pz%-m^#D+_}1agu9BQ=S<5c zRM)@f$yQ6l&{^#hEqXPBdec>E*Y~W>1h4bRE>Un871&!rDt7PN-n{tL=GLB{M4Aq~ zy7OdD2%%TmR&LE`T8>kVo_ngtodY`MK3qw83a?J!lX0ofUYhTU8$*+;;8|TIjjHxn zz}usDT}}Y*(jdC)No9O#C%=GN>)alcF73Zg(;2_Q0an>$-ycj5WDpxO~y3*GLJK@VWS( zYYu>SN5rDOH@?GFdAW1@&Yh=E#Z=i8f}!G9#G-NR)NtqYCp;niq%v@8Z_A(@;f(?VVSjult{xu5C)!mNvTvD5{hrOueP*q zeAig-I?G80&V3lOI0W35)|og{!N6sZb|kc417>-yK->X>u`p`r*WIUV=nIq;#zcJWbayOk*X;v?!q!;KYbT`f_o}g3BfsLlN|>bfh*AcUEH41i zss$#|s(}c~_O%OkuW&4!M&>mLUh4=G&|w%}LFdhofyHak^D&2mm3Clu&2X6XW}>P( z!=z(5Yjn7?p%PTcWapX@UVCJwqagz_Gg>B;gW6w;kvbYW!kr4;=*W;kS>ae%O@y7; zph=+wge%Wcmqj74Pk+3zbT;MlO-%Vh%DX{4vXNgzVK18!61>dRE-))iZ8={DAm?X|3dc|9ZNIA`d)pd{#g zIgxk__9o};7~KuY+~wJP{;o^1Px4jp^-*y>^q2E09Uac=JBp})v;b@R-l#j`tyTIbGI)nC`+EA@BL z+xA_2rDfCLcJtV4t6L}fT)CijkcvfhD@eMh);aDCL3 z%sIL%`fC>kkWuabj)??!br}$kb@jl289@)9Jn41)I^lQtWHkvIdz6<;2@n1uD8189 zWLv<{7Vn^=w((?hQb8QREEAx3z|c7ma9Nar*4Aak!8JGMwqKCod&C)`cUO^){GY0G z|7r8S!gy_L$C%2)fTIY82R5}av%N^AgqVwH9VzXq#MY`*ENLTn=>4DU8| zN7E0fBb+o^=i>7HV(EUVxO`YD;XQ&-mzHO76d&SKB0{5BJd|e_WRGyxhmdorWqX1nHO z*)qCPM(bryB9+cQU$=QTe9vvP05gKtl3)Tklm6sLQF`twHi{1 z0@}0?68Vf>I9NN4$ZA?A(F~s1;JT*p`?^*tTtV$%!1zl~!=nm*3V%_BPN!Xugf_d@ zAiH^C%7j;GCI@QiH4>*AH0cWTBnG;nZtaZL{N_ynmQrN~*ZF*&1WK}>T`pF{v<@m0 z7UsJ~@T7uogJx68p#shM{A)h!M^t9{v~R&p4wlEQ7IB4J2(X~4S4$SMS^+HA)nzJ) zCXeG=53wC~bkMkz*!fzEUslC(H|8TO!M%*7%h(GW`s-KOi5!APg?v73X7CSsSb_Qd z&DEbPREPZPn+$0Mk{mh+Pw1nzp-(%Icqq~wDwC^-dXff(6|?M(^b9g^W)M9RB9pR5 z-M=G)Bb`(dqRJu=Iz}_n#L1Hp%)f$J6Oog0uQ1BkZv~0J5acE4u~YjPGy%F3hZ39F zu?fwn97BYK52#}-W)desRrMT=B7mlaP`)Pt;|Wr`Rrv{*5v!E$g+ zXWH!@s(+^If%NHAJAbJlagXsF2@H?%_8`Trkse{q6D+2CXfvjdA=Wb?5B8`JShK23 znIO~X;XA({`lz|)&D~t=%KL3?RYN};9&SJX&G_(FL$}6`U- z!^fGDCcBvtvjxhz^zdbQmR#=E`R!o=;G@jvW3p=!Bwy*9k7QT`QG%#O@2mi;bLQy9 z%jcd_;q$m=Bbt6()BN;=QYyi z+l|)m-njMkKz(;xTbmKpfU-@7`F3}Mvj%l_>}H=vmKv!)98 zW1U88`s7)&9>$hrrBuElAiNt3X?l!&_6gn&YS}Liq+WR=>GYea4k9h|4}Nr6^2Ssn zDdotCXP2x6u#(>kM;2hqePqQ!YbfOfqslsc`mXJrcP@|KB~+2NW3$=rQpb_1jOv#V zHV-gwRV*=sfoRm4I-@m`|K6Nd(WedTL#*~fqbOey-dDGdC&hxlB}7=bk07c#EJiT( zC8k{vc;P@eaIr9{O!arae(%Q&a_?)@@6tnTAM>1 zzHYDf6auG?Ox8qZWymJPQ^ZsnibT+rJkIk_^oz=hA+=^@L6hya4O`OYeXcRm^1R*_ zD0R|-9?Q3$Rp}KDBmvy4SB20m2&GBj@Co;g3&8fT`y9e(9dSnzs!JReyjNJVz^o6> zOIHJt&;6}QJs=U3+wqn#q}S3q)0HHYI2;bP63)TYInfW-MTtdYgC=DKNahIAmZZDk zz%)Rsd>B^|1r4=eG*>IZ=_#ST)2%L!W@pUN!Jw*_U29IK zLC=-7x@m1lqI@BU*GM4Rg-Z$R?zC&|k+v|bRRE&3b?QqB1jubh=Uh>R>I%fJ3*@U@ z1W4vp0qv@-Qa$t;k~u)=Jn@qaN`ucJzQR_VudI~YCNrANFlm+Si3z?uLr_Ou!)tb* z+X|z!3Fq}`?uJiUt_L}u+nu4=sLah?!|mCysl>pODZ?TxK&2jyrSzfKDAhrJbkzsk%7py91_Qga7fy(}7X9RarZ*^Z^=yP_yFyO)7 zX3kOMb2Nu~&_0(7{gsnjZ!@L8A@V5w#zn4IJ7Ms)^UD&_r@=u+!*>Z09#gEI6Dld++&lmFlU%O;>4}Y;ps@34jX!7d ztyB`tr#g$Y%!s>|G=rllYKna==aHT@>(d(R-1gzmFGiye&)rKu`S8;p{NzUZPW4~j zuj<&P^r*g3h0hAK?D)D&97ne`gl_s_cOyPv0pQAWzX?57-SZn~4GGqTuk~@tasnUw zk}j!Rc=x2dN2G!<)JOP+XK+vp2;~K9;;zv1`B%O#j9UZKTV^v@atsTj#H zdU0#^U}0IapyvzEUtas*EsQ+>=9vp6f+AOMmjp6z{%vmm>gwzku)Tk^FuOQ2_vOsy z)!PE>bAr2{6c!e*FJ7NHoL`-t1Fo4r&&u=eD6s$I<+az}l2^sQ9_$rpC}vx|N^Nmr zRW1dgz1%i8_BQ_@4EXP_pK2tR1!K7m;+u>zPu{?!O=*X59hnveka%EeV4%s=Flb#c zAs%LXy!6!|t#IaoxrFcy67xx=vTv06G!|0MpFTAS+cFz+o%K9-P&)^(YS$n+3|YZz zA+1cTwOm2dJy`GhR6V`n*znH~ByXyLHB zlag|D3-f7Qz{Ef&!bu~GHbqE`n3MQ}`5IR3l|!(2Jt0`zA`DkO!P<$$by7#rLUF_K zU`wJU7!Q9hP>ueopA<^LUSY%G>FIDhATXS$ZRrodiv@&PAGZdGqofj;h^*RHLa|m* zJjba4CZsaZS`i12S2X;2Dp;ZFtcrl@wSq3e;Xp;4PQqHDz=)%v!@+ z&$gkCBsU!kY%_dr56K*KG1%QgbL}KPYy2dclTOX2WZ3NVm#IZb)z0eh?M3cfZ9+Jl zAx)e2gnG3ZRZcoAf(3fngH=1roqZuWP4&{w2i}qNLy&jO3#d@R%n~XYPjSk#hvFkjdvvw8KKga z-Px@{>Nj*YhkQAdfjcQ(1WhEtM5iKKym&6&vLE(?x!?A`?DahFPrag)em>MMSb09r z>-Btj?t$i1s4U#U-uQEQqF`<+F5Gs+6L+L0;wU^4bn-?VV|4ryk|Sf!{Q}2G!HNL9 z;^4S(7A!DoBa2Ap1a!!F7~y6%P7dmigpo+;XUKCH(457HI-5WpVTMh>nQX?-w%?vi zA_I%CKP*QOM(LOL8Ne{$S%_~ogI|nE9i+qXDER@v2)shpmcyacUXdP_9zk>UoD=YD z+|O$X=(6Gyk*xg9vY1sn#vG~f?a@&+ey)}Z5|6icRs>b&ceZkU+dV>lA6=Nw<(_su z5@!4I)bD@Md;aCU-Y2>A*4JZct-Cj;mH7Hp{-h$seR~CfLk+tgrIVo(;~^g{!qr+M zmFrv$*WfM3U@I+9gDYEphVu5}`~AH0ob5))x7AhOm%e=R-u4G(tI(0l4PUB9g;kMEo| zgofLDH9u4_YEn!p)^S8H9U))F4B))8U|eYh&lTJcz*9+Znn z3LPw}8VO1VyPoQ39F-R_`hev>h$S^^#9Z3WdWOi8v-|dG+h0|7q-uW;9!ClA@iqdl zCc-+dL|AQG)~=&_GAsNl5IlWqor?yfX5U;|xso`Q#<~~T#u|_ysgqNAVZ*~(kCH-b zAfLR0nD?mK7ga%2uIz5>`CfWC{k`O-<-X z5`YEz!fphIa03!1SwSfD7xfBq8gu13W<%drB$k0#0-R_mVm`-#ph;lY#M~^w>lOi4 z6-$pOOuk2oQC)qs~ z`z#ZnQyyUrBX(~ibDmumj~70q6wF3YLkl^Mq+DYo7H`}ooHvD;vw${a&vB1;M7XZS zGvbOvEbW;UB8(=&$VeQ83j(nZgz&r z;_q?zY0wP|^%QpcK(I2S0wy_wX7>?p8K!FBK8su|rdcHzISGGo;%0(l>(87>{|&zepPueZr)CBcWx!qmGOI{O46)Ct+Xx$&Y^+Bq0?O} z>2R-cG?yIJ|7k}cc3zV|Q{{{$FD*vel2Jy~F$XC@h`m-Pv_*<)hO+ zcja+%^w_bjtsAy)qCYF4V=)!^tRR;^Ef0k~8a%K55X#+3Nh6@aYLC6@&zXE+v~o?f_H z1kRSuly4Q$dyxNP6C@ZIOuf`y1ZI?`Hs0p0f8Pq&dp8b3Tt?B+>LQlF3+v_0{IUQm zz*UGV(RC4MdQ_3u{8WCbYYKRZXBG;$n*#kU5ZJ-2W4;%!H#SIo^Iaso?{CX;e0llr z%lDV>-+%q~odED355{7+9s%Qzp*qT^Iu?9dG`5dl1D~2lM+w2&Ri4T;Y1ZWRAjpp` zwN|=C>g)Av0EP@&U$ZnseGSSObo$yQ9iSC#7hSJ<^PPTJjTlsEu*&z@K{;t&>aXdy z_Um-W*nljD0NafTG}4}dw?hWxVL_kOj|v71p@$Ha1>G|qz`VrZ4xOQX=nYb!kyi-~ zmKD0JZgvREqZ$~2tpsJmpuj8&fejsl467V81Ud%M!ax?x$PI{}(Yp}nuJ6Ej8sS*o zL1DhmZ#x)*1qF04Fc=i}ix6mGzyiXZ?Fe`77HA%H27*p1qdNh_LCCU@Lx~>(tpTij zO-QK(lqwe7iNFoKZ)uW~!2phHYAX|>ut1ZWuorGY{VzbZX;Sd`LW{Ej#lh%BsuL_V zVPD)J)Yr)fjV7jH(dk>)bfC%9V!BY*(6Ybb!sPA!V7^FrMnp6R)(F6AAlJQsrX=(y z!SPF7)qdn%$vLHWhTM5C48tZI*srA1NWj7h8OfG=;Q&4WixO^f{DUQ()ojHwUoS6- zAuIDq5tSyFT3GlZn?na>mBL@r;eO_9K>duIN}Q~%)itt^ka^I!fG0Ln>^xv(Kd`#l zaT=;Ex%$^rih_PZu6nTmmTy273Pe*WJN2M0?#37ioszc^yU<|a6-a;v?e!p51BFKj zp7hRoK#@Im7Z`BdGUD~P#t=sdp6ilBo>`B;YuxTgVK(iFQ#mb+76}~@#%n+eO{-C2 z?7Zd<&6rb3&-986vvUEK8s+QtVQJZ{rS(D{4ZTs6<`Kn& z-O>5;zsp74mj!^22B`H7ojTDMt(*^r6zXE#+p6Vnyx#&VAa0Gdw&sKif7$xtwCzS? z<>#R1Dg)lfG%TX7Cd1-rT9ajMc^U^?jV^hCyI}u?;|MaW5f_~R@|tJ0$bgs3SPh^p zwWP}O%6IJis!g>pRDHfxHvB#v`r!MmaGOHuO3jfYdom#{`3k7vQ)*uFwYg?3mxIyQ z$`4KaB{C0dt|PZf@WgxAV&$uu6aX$vV^Dmxd@hgu?!}9*rq8VvFBJt?OJ8gX-Mw_> zV)@MUOcCbaVyRTd9J+XGwX}*k@vXbXSI^dGggUP+=BK9$i*Fx(_5Fu2`O~~(6lI=s zV!_l>-d4!Nm?UTlq%II(aYNhSG^|Eb?;rCNK1;Z-JX4;(`1XI-fB8`U#{XyPT7R3o z&nUh{zO-%}V=H|Vo5Uu5oz%99a7nNoV_~Gytt4(YHd?J(EJyQL=tx`?tjJr1gfaz{ zk~AS%m{cw!A_#?M61N3Ph8Psu2t`V?PwV)=KeFeX-|K7+3cg1;#^*iHb1wIvFWk8^ zKQAaNr@t=Txbav{ub#hp{_NSa#b@`{*4Eb7*Eha@Sv@g6{${Is|Iq2HEWVxn3Q#AN z37C}>N-&O*3FifqObl0zN!gvs=@z&Zvk2GaC#c|X3Ay?5`3M!OywqSbgDU=H4A|j>DK-3f|FQ6Bi zX|xfR@HuV;=$g&eQi-`+LU0MeB)>(9pyeqzamJ1pcw6MESAZ7#U+jpv`z;pH9gJ9x z1oArQ42~n81Kmd$Gj}0{ayIc#lqAVzYga0f6e1j9S>bdtC=?k%SMg*Q$Ib%I&|4uM zIwXa=^$b%YfVAzn;>=18bn#R69&gH5yJ@#*O4p8JW4QLHXpf0TU?BN zmWOn=F{*=6lN?2JFpU8;akZ(tX|x*^Np0O%+eQUjA!`=wJcB2~$ZysmCtP;hU0c}IIpq&Mm9HP*5WX9Cl z!s9$vA(;WNPP-3cEvITGl8-+X9-)>(%9!Stie8p z)O#sV0Urhud!fN{L=jpb$Xq6KxTg<9k*Gnvv*7U&SdPk3hc7yi37-?_4VTO4TbMXE zBs>@q(dArJP!wC=iU4!QuL}oW%;@WkqOi^qfk1RJx{E8l&O7 zUl151R*#cNLT`@?t;OSkrW9e(qBI;E z9?q*gO9o*Hq^A8;cjYrZJ}dMk z{Xf~hfB6{6ZM{+-%paIN|6|KiCtP zdVhK_i>+_AZU+YQ-I*l|Zq2rm0=H6{)h?G;es$oq{mMaO`CCuh*ivM59B$q!BkW*_ zAQ!{SI-^t_ls)KCZ`8>^4vc!j@+NmWpo4~r!RxR&b$MT-G8p~XP(@^J9qcd$&m9I5 z?^WAg=&|13y9L6i2R4GSt`rXJ|M-h3(lnzHibp2dom)eJUSlrZkMyTr_6~NcOyjH? z;Rou6E__{aj5G2BHn%6g`u5vDU;53`mtP8@{lh;5WY2ys5d8VlnWeLLzq)(&?xmTT z%RI47fySbFY+~tGx;8HmE38!TR)F%me~tePB}B(I=f}>BDR@1j&=r9E$N!#LroH#MQt5vDw=^7U#%?8x2mj@}m7)!&QG?|^Or&Gc+ z&H5zrUq-ed)JtB^+ZiMSnm9RhTJ7cn0u?A{^&oW;b7_;?Qn1iaWVgAkb4W<4^DzJb zAOJ~3K~#-&m*mD0D6SjxYvx3IFkmKH+wDkvh9=8x_ShNWAppt@EZ}L$UGi9GNqNog zC)PQ)XU<)UkP}-yN>GhqG#VN_vngw-h~P<>lmOk3V?hIrD^Us@NqOM@m*T9lP z2+MLM}30GPWsTwsVZUB=tUW>j4^ev!{0f5}V{AiWH zVZ=_3x?m4x2uEYnHw{_?oJtrdw|pemcOw~^DU>K<=pKa@3pS%}h_1RDpuTE?6dI2P z7e;aiS_$RmhHXxG)k-F(9F*CSh4qj=G{7rN;BwUFVJR@~20@h_y-5}m_P>@nGsn** zr_JQG*u99TWJaY^g=0Z}rD8XZAPCxfgu^yLUK{{q=U{vX;slPixZ1LU-T2^Dls9)s3Oe7R9>b0l|fMg&l2v2X%mVe z=ebACpRu;hsLBP5n;CwUrYRUXS!&-aXBKO% zA>X3{pXC4`m+w(zo8i=c;pm{qSOT*pDFe_(z-FGSZtpMd8}et>W5h_Sx87=P?`;pL zEi3_;8s|N95vjH#6%tv`wCb-H4=QaHlbuzC;GU`e3-@n7xOM7w=SbhF#!uUBso>^g zYPH)>4YP6{sfu6bI4icRay2LrGN#b|Bg=a_16Q_NR+*ql^NrJiuea|WzOb`*kxKc=-sPMZ z)0+WMUWX0!T}Q%Y99G&`%Ybus)CA+dgd==T{yRjG5v>k9V}JX^5Lk6I|33|`M`9gf zG9}l)#+AAT`~S0k(PMLGwW37xGM_$XWOq@sE%rURn~6ab-+QN?xi_Gb;5 zxf(F6Q95<;?AgCuo>_w0`O;-U+dCJRE-uV3&CCe4aubWO?`}?gL1V|T?LB#tuxb$3 zGyEDO1K#mYR^Ah*7RCUsAhM7#kEw6i-C|{XlFM2=@662m7#uHrCWQ9JjT^6Cy?Xq7 z_Suss-{G{j{=@p_=H|wO4N%&>@-J_HdcEW6uGM|7tyWj7)#~bam0#m>zWUzk>S}ez zjvf1U?RazFpy;hEyg(IK$ji`96F3-$;yZ~GO zMUO{Fw>c$G5HShLx>>p)7%P|H2nIbyFA|Cu1cBX@Ko^k;ok(>F4=yIUVE&y&?JqsR z#YiZ^MnXYn$e@vpB}_OZS9B$`2*Wo(mlM;|SoKB{T7m;;lohg}0Rhm7AWcb{3+vy6 zavQ~w|15kLl}8vf3l=BiO|>Mmu+W4QLe3<#R6#h8g0)dCgaBv?qiZe}EeKXOHPnOw zpO-tdv|!ZC9Wft)l&kY0n32#2JgQMrP2n@LHLeP#vJJSYMn@8uFJmf!wk=RjkD}`r zkyb1uY@+>_gJl?$a6<4^-HId(xCzA#kY2$Jd=)X#AAte0f|9W;aE4=C;q*Y-Y=%Lc zz0&Rin;1~?fv{(kA;EVf?>3>vW|hTJU_zF~YheMBvw%hh3)_&8!{PPu5;nv(hCn;m z2}2Dus>tC2R(dRYGZ2Rxr9M=suY;55Fru!Yw({vdoi^Tb6e$}vUH1zA4c`lgedRLX zIXWP~8Wuc`h6ivLzh3s`^r2iC92i&Y`p{4=nu`fM6KOMf%%ICTp~e+|*^j;j{K@DO zdANaNdPRX8ZNhN=^hA5oxkaM_p$7xud_Jd^x7hg(bM335uZ##RVsV<)z?d@&!X8H^ zWe+9I!>}bGbdp6$FdXGUnbQdNKnaq7JuJlOiA?@Djt2a&|4z_1Tw(4NX3pFk)1Cwo zcPvwh4aE>B;u8j}5Ven7w-1*NkKROf>$4XtMar{T26qy*}SE5ou{FDtz;OeP8eQ>tUd^6)GgvU!d)Ar)c11 zY$OnLYFzPOx7N!G6rM_#i+bf1U0qYK7;)(AR`HU-a%C^%Ry6Ut%XkaBOWHl|X2v8x z3Eq0wf2-@0U6;SvxAbR>L?7;pq*eN}3QsI5$0bI8Y4xByR8$#?K%JO2d=^Yis|B3^ z@O)G3lie5H;}?#+_s6et^MCp4fm8dsmz4{N`e!0BZ-n}uWd1YXkOSQWN!G&?o&Pk> zmum(!tI@9{xL5ICU)Dz*7QtDb`D!}vXQ4Rii5i+rToz=MO zIYna?o7E=9>fXo1*pL6FxU2j+@M!f?s#X53@vm0|VzHyW{{D5L%Ac;Rtl;-&Yj*@; ze-Vs*^7zsBn~yd(e-cLfoNV^>#?NoI-n@GG^5u)|v~#t0-C0`S4^TaO76)}ITXcJy zd_PnjI@EtCRYG1#ug{lt4!8!g+2O<4*7)#M*VU%0u2uw{HL2i@U@=bZJTKyMUKI`w zp<0}&C2FdY<_efA5YC}BqZ_yFF}jxS`%x%|h$?`tUN2-9_8`Pa>N4QKP)dQZkntds z1AG~`a>s(=BXA!Z#jwJOZORv{H_)C04-!p8JX>dk|3Yas21v$(cD~!_OybPiM&LHs zb%rtQjiIt)cBQ~DjKKz!Eg%9@K3&8D*v_3WlPLu*)!rAy3(#oM3ydy?QG{VZb;Xb1 z!Wb_L-iAV>)I@hg!caUjkg{V`sB8xmS?$&q451qsN7)eOMpzKGgVhVo9pO6oe#7mw z{D#9|#m(nIhpiud1o*{N87pD1TY$2asaIhvfaR^dt^uNF)wdvzS1zd7XDdn>Abv&= zblsPbJj>_RkXLE9U=*(oe!TQHnRjqoKks$DVecX#iyn<{i;8NF?6 ziRhbwHb8~70Fi;WaFs);r#Bh7_thCI0Kz6c2hchwuLOdrwlX1S&!RD06Uzr7f;P(C z3I_+wgkVdJ+4#Ni-U{RpI7VnsszFweiCbVtz6OCC7Kg)Q8N&2=uBK+rJZJRJ)d+JK z$>*`YE>5JClwQxZ3pVQOk@9FWwk0j3*c&Pw065^~qA3Wgh_qZ|>k?T(Np1pMD z($>btvyH7=aw^*%Ufn*JDwTK|OO+1oFO^E5TEotP!@~pKv=Ti}slEj4ZOfkCpjNIh z9_-p_3{<|}ph|EqcM1mSdC4h9@3@+bYSq0e;!2TRue+<`z0={&Q_BzcnS$VD4|Z2D zn>gsz7ImDC7Bw=LQ#r;k(hxd|-g2h1TX7coF#m@=^32_LF3N)s>UZs#pFeskA36HF z3q`1|kaVR=kg)U(Vi4VgakMKJ_X2#IVmzH8@zN#btAnbGc>TZ}&{h=eW&H=e)nhP{zC}fP^(ZF}JEAQ~_9M;NzZCewJQs z>&dbP6<#8jWIrJbno_5?-gd^uWr_pZzt3s(&2K-wv$FPd z^-St8Vo$anJ%04R$D5l^6~aEhdru&Cxwu+?@Ee)q@Lq}4=o-eVJs!NDa8&3(SC*EbWW_mC zPLl>CDcHEaL%lj6nYw11-pu!cBWqmaI=@r2CEU$v)BME@Jc6> zebiuEtgxwAEW}hIn*&;AoqchP;Yv1L1Ym5inG8zij92Qh-8G=6FoMizsH0m(Z74hv zOa|`SBlb|lK<5!Ukw9MUm^WkFjEJm|A%rDy3oJ>%S_2(Nup)&!kWm>%MInUEVGN<0 z!Gi(3&F#SI_7>z}v8^z?Ab*1S8)5b>K#_$UN^E+Y!@_pYhr$b$VJpPa&2_+RWMwsD zm|eMmMQ;O=uz0>#dD@A%n)Uc&`$`X9(AAN#TNom0v&i)tuHfVt;d)nJVay;c z4H%rs=u8ehH1#aJ)GWVX#71^A=$X|)8jLIs;kls6$bCjw7Q-l!!XdYOS5cHE^q~p~ z#wglcfypx?IZ(aeU@PGex=~^H%|l8`_eM<~Gitv%K_K>z$a7IFfQLM{{dque!jtgi z{nKWD)I-MWzwP&r6lw#3LLm^%M+-=!6grIV!Rgyq5`pPNf|4eG^t&rUgh6|!scR}E zr#WF}RuuKX%xcJ7Fm>nu#=OBgH9?6OwKD{j4?Cb5zW!Z;H#+cP=?Vp?E2;rZa9kYBETk56d|tn@&C|CuvS*Zy^rLKV#Po(R=|Hs$%VXRlwsncotA z@nUs7wf@8Yv%Yj$!Ynt32M;=X2f!y>jI8jg6)zpW<6aJ&$&7=!bS|w$H!IZ@?fc@F>Dc9sY2xSDN&bffZ#Dkw!YvTm z)%u?gJ1Mzch>HF{>$3h6FIQt$ilI;dHLz{d-pIZ-gtHCOlp|w z?3ddwx3lZ(t4`lBf!O`);IRU>CAsZSrGC?&8XP>dj{oWU!CvPW6Q zY4s}IV$d(giyCE*BT7^0skrD+R~{<8`GxYTvHv%wt}x?vY-2CBnd^_nf_%71?AX4>cp&m&9Q!84Yyz!dPf^-bYE(yY z6_sRll2s|HBBV()g;6QC!iS2qRYF89O4U(mpb}6cYs^IyRY;)zG|CVBBYVzyZi+E> z?zMwZeDj|7JkNQ~$uJ!l0GwGzDj`iaAcWp8FzRJA61Z~TKnB5seGzD@1gRq#D4uZ$ z@{4?=zWrV=(Rc-Aq;4lj&3AlY&ehtb`2d4t|dYydA) zO0A~Q0?agq#vqeGX{1N{!Wan-c0eoLv#eHF{th6tU~&*y41jn+TNm>gAc$UG_M=Me z9}fD55fAJi_ER%GeBIyq8=tLghY7fY&5HmWIP3ujxGq9~+k6gWOwT9-MzvWW+2;{P z3vIOB>2dlTGYAT1{sI8G%>(-@no_C-v*zZl7GEA&0!RqRLPj z6wrFI9o@1@0?jg~yS);^1hC?BViHQy5Ge3kGMcQcCBo6!2mE)$_j(e)#e6lSNHY0OvLKsdDA? z>Z*|C?Y-LvUmG7kF^(Gc)UkcX_H}i!mP=m@7KrDS=2q$BTqQ5FOq&Iu>qO%c7XOlA zxogDc8(Twi@>+v2f4_Lt6GL)VYijk?R&+!5a`i5JQfjRb3WxY?|*!{y0>K z{o}|TP95EOWu)<^*Bi0IXNPXF{=5^t06A7~S8vP$;{uUaPEZZqd*_`)pN6h7b787~ zr|vAox8IuoReug^LJ2T|Q&V@t?C;8T>m>XlWC0UNvX7+dS*~MvWL4w{imXZ~D! z3qu@9@g6i+JBfrk^?O1sHxPpKGM~Z9V!)TzQiqPb^;tt%EW;L{+O-lI3#drPjGb)? z_+LSFT55=;Hl5&vu;Z+N+e}(&4GW!NCi?$K>bV+l!6>J{N>japtGDTT_d>e=US`Qv}srU>VW)gOhd&4xHz#pMC?Be1wT!MU*3lW*`pQ>AOFed*0|t_;F$O$PFqgIH2$nnp z*hTSq2L6;bm|Egr5VW>=Y?rO529R5nqir^NK-;J7(02s_Ia*CaOe@IRhN?2ibdDpx zKDt{X#vxGl@f0a>ZdV|V8KldcGZGxmK#?UJSYTMt7lXgTcymxRU(V(B$9-t`q86RX z+|OhLfQ9>JQlPylbbV8tM1mKzK=C?42_u*SPGL9+_$-jz5eMsK6!; znTCW%xnJ)Y)&wP&7M;OxF}Wo0JnTY_k_);k%p?JUQLy$yhUFCiw$C^M_A(j`@Pf8` zWcNfH%7D$$hMk*_;g%S0Bh6(tgTOI(tj?IMWMx6z}lFc3ul++(#+SzU=bK`4bSl6DAs_q3j{vOr@}?lmw}Av0*4pU zI(0-F=-Nmv%siwbxbO%~p^FR$hG+{=T!hF9Y+6T%m$K?FO)@R$zreaRdd>j%ba5oF z!M|xlN2GO&AiO!fBwK^IVi5)NF;HPzj=YIz1xy<1*o5} zU8jHlu2LE6nL?P&hUOO0TGHG;z53zFr%;&668qCn&r!j?vFAXu)!e(X0y3_ zbab@EguaQvL4jqKn@jB2G7^xQDwVfLC|1)$wG-B4;$kom= zcrL|W<_MDdVx|=xIi=^!8qB`>&+f)Mr>-{6UNvLi{PxqUfB2vgGipcfysP3XYYtc^ zfO)@w5n%Lx3-9)J5s7cTb?9&3qXd0;YC`dK!t#Q~NYa!Q3~V)k)gT%w=rsMFk>xdu zD?c>3=1#zBrrlYACM!fprtgMa_sNhGI>QPJ(TQl{+bMK+4_oO+8p2@BAc6kwvD~jt z=xaQ>IeqA;0C2aZfUZ^xhDoatmKtcXSf|1l0Z4{|QWbulV2h@e3T0@Eog+5XM;o_B z9#HM{!w9s+PoK(X50Djvz1xrrV5srz=RK{7{#L8mBzrx+{Tk#>*rFYjt77-=y`y^% z9vIg>1OCrYt-Xh;ZNcp7?b=7PF@f3G&nAUWb(5JH%tSs2+t;0=`ka4!aaYI!;1;?hkAEjX*)s$J#|qfW2ug1UoK6VCi(walg=wy8z?Dt0k) zrdq;*#w1s(mUCFF+p^568(+H}S17=mVV@T>nr#7=5!=epu9kPr*y*e<)WwFP@(dD! z1Lc4{fB{d)t>7VP)AS?QYCv!WphcrN=Yy~d5Pb!C!sz(s(C9?~u+Q!RL1wxVG|}?C zkW=%HoI)EXh3(V3kb5LF7rxNDAi5F+hTuxjnEhR(AH{R=Kq@dJ=nL^xZaN-_=Q4pl z_&`s~5zL@dnacp)cqV>7mAg+h7D~{36r`OV;8RLS?=(3vQdbveTG096J};$Mk#$TN4Fm^RfmTcCAi{tF%`0TN9r6yr zQsAqX_g71P--Wsu& z5@_MFm>{YxEC}}2iVMZsc^X{-e1WZDelKAdAq=pmTnGbZi)yuzUtoP2+Gi-TA)7`R z1HP8Wuke4%Q=OF-3>Y44HH876`|{&6pWt@p%ts%6 zOvt5h29Jbe)vRs|X$cy7DZ?CXuC6}(&xY`zi(g*6{l&({xy{XgJ-~b=n|M#qz`OR# z$!9liG;g%98gI+PF+gRB23BT2f^(1UdvDMrtU=CKtjcKARWfF7{pF2>>lLSQ?@0XK-IZ6rKKa+zZw_sJaJzBAw5&JG zUN(F|dt*8W+yx0V_-_}+kWBN|+X!Qr&;UZ*CoCnFoaiU(B^gE@5}(u&>+Tq>o}qJw z-<3-Fo$jPFw8l_i>^=pClTl(WI`vcAKVW~w?%(yibWu*&FTufu_Wa zCLyEe6y+rcdY8Wb=Ie9ctV3h%2|a%J+=|l{KgZL1V&&9>Q;TQMx}TIMqDdQHKes+} zd->YAnas@8RA$CbG9x42aVMXt_r9!q8ILYwxpc9i#t2W;&N(dYJuD}x+u#gVZa+|%Q99ViudMo}F&Tfj%R)>~bZ0OLp zq0}qQu2)MvSMkvx-K6CDka`>r?3H_`*e3xN(?bkN{+oV@Sc8U~?C-*|6=C-!Uyy2r za2tHJ>o5d^-6S5#Qe-zrI$aC3sbL8GHwY|oy?|QhR#;2kls`(yIVzq6`fA)3WuxW$k}WPjvM_Abqq$6 zN0~y?UN{&{MJv%=^j0a=G+;l|hsB5SAyEzN;-5o^xDZ(l&(h;C7IMTF+B}+)K%D}+D+n9l| z1Y;Z?Hl#kb#`D+dbd+tj7RR<7h^;|={jLcqj+VYpGw6tGW-#VzclJ?I7!X%R>`bcy zjYoYTYF{AW`WS|=CiO*fL{)OHl+I$k2^PPJ7ExH(GE^4hZOjt=Eg-i)v5DU(q3v(( zpr1@X@~<|VO6DML5<1+GgGtx41~X%#4=o3*V%Z3o|vvB)I;BT_ktQ&t!yb@!0b9nv2c%4$7g6AMXRqA-xC zNEcjH_JSyt0Bs1&pEY6d!Zt3XGJ0nw%-c2lql@)uZmx-Z+WCU#Tp9AOS>{+UWv(A8nH0r5LeDTbL}tE-vAPoBGM0DMDEkv(S~`L&FhPdxkH zjT=wCcjI-p0VMU{)}x1y{&V+>&%Y7{-eA)^v%i1Y&95IkSUh$7%-L~!&pvl(2)4Yu zJaZcy6dUDD5rokGH-8j>pI3&H3?QBeHSY*;&)fZK99hE%U+8Prn(t zZaAw3LIE+}U%~A;w-z2}C#S81neZd(%%C1AfY#ON6Lt*Aca< z_8#$E4Nw&!VOY`=;oZ=Mh}|^Xb;q04j3(1e6Q&kVoLD@uviM+e@$C4aJs>+@&_uD$ zvoT*S0YM1*r zG-uA!zH3ix&udY1=dyWpUxuj33ds09C%HiNnZU{cx35fk-E9%7bzS)VWTrTplC~82PJ|m!E zCe12h|E$Asxf3=zOWk0QeXu$jVlJ7|2cu>H?NbjDJ%n*um15y}cD-w_2G?R8_Pu_; zp>v1Xbl9iPLc?!BTAjhPFd)nVY|%eY#C;@A;!c_m`V;~^ul;XZL|NgJ6YZdjgRW@P z8KVWA;>N+7-v({x3OGL(YGP!^P*+8+TMXmjHM<${L#LrSe;{e{4Cs>)! z+mdRL&#|!G71}PrnW=9`Cdq}KTWHdL#59|pU>Gf#9co7c>&vx5SMzE0GXcbNHHn^= zw#vx@nVDtI5Ozto$Rke{fBB(Hj(kS!*SU*sA0FS|fB4Rg7s21XtG~GVCqj6C|NL)X z(~tZ2U%UVOv)psluK45iRWHoSP;}(M`2OX8{q6PlNJQ9k2)rjp%8UAF4@BNOLS<|# zgb6;nm)A#@XN-@sjCH+5m_uA(K5wuMO_^Q1Q^QRmk9?WV&`Z(48+ZTmjJ;3) z_^r=^Z@y74Z9o0^)6ussX0Z9D>lYeo9CUIkL*Z*^pGORonLcMOj9lZc4<3Kw50UHZ zL{EwXs}9M2Kj-K#QY^udCeQF+t%>h#A!kk$BG}pw4iaA8IT*_UGEr=41YHz7_eWYo zi376X>;-RJcg+9}Kq{NMHQ=#$xvJf6Wb4Is+R5|^_ftRj(yiatpp)o=a z9d8=PSK1|X)JrbK$x|8qKU6V)G4Hwikq@eI&CyGL;#bVkW@%wdb(ezQ~t# z?c;G2uPWxF;eCBrcmpP$cjl*bso^3&cxXMTw3+FqU1FxFaL=1%_t@=oJKs*2*h z^Q%t6od(h!K=Z#)^Mt;fJsuvptENorxZ%X|LVhRhK3eNCQl@Z`Ww%~cd3{*lNPDA} zhQ4upTQ(d%+gEP%oSvHhV#Arv(=MJPUtcZVDf$C}j`7$?rxS?}7Ttl8^pBmKOmuleoV4GrKGCSsD0IzZ4i8z5+F`_p}<{){x zZPd5zo1bPPP3B~Ka$-^~4J2(CG8Y};)0<0DEqPjGNxer zS=}9-g!bCSDnZhiS<#eLqq?HB7?DW9s=lmQbfu!sqY8w$S`7_4Z<3)g86CSY;Zdbu zr3khf1!%b%(mY7+bJQrZVQ(}Wie`6T39;Q3D65@;d<}-x(XnjQxt5I9l6hrBl~9hs zQLMh)d}WZ_j^Saq@x2n2^>xiSyjj>UTA5 z#9_4(t=v#Q^p{@;#)vojbGcfgXsp-X!g8B7Ek4_eATgaeymZ)ji0g@rVV749N}He58EM1{;mnY>BE*d1p9rjAhhXw9YB0hbMuyX0EQX|&ySyI#cAhUW`P zmj>z~x#+A}46Av`KzKpHSPZPSm@Y4MYfW;ayJ*Vr3n#lg@>{q5$JF`#wpm|coWypN zI8zimP1GiJ*2HdIJB?X|A&q0Z*~~?E5jk4a5lx^Z*it}6G(;#tZL}XSK$OwCOPj8} z*rtuHt0p?oq=~hKQc<#vae)BsYKTc_|HsbfIp0(itUB-eCUwDjA3x_jKL+Hc8YtHe z{_v)R&!H2wvwT_JywF~RJc1aDZKm`voI^()7r3vm@f48oQA9wzdxw|jC@X6O#FDto$ zUk{?i{;qN64~;Xwd*olA{_OKFKECyz-#zzS{mbp$`|sSDIed4|;X6n7%+1a14%^i+ z17$FB#C^YV^U|vheQSD~Aa_;WCrOxO6m8ekQ`+%9^7JFQOh8;DRw`UDU|CqGRu@?M z?qxT*VE@4D_KuB>-F(ad_>oENe)ns+t)=h&-N!>A@cys@c0Mc)ynp|#vX@!g=fuVS zgZ;~0^Vr+%tNH%EY+w4^Vpd_$5$4c+U2&E)=itW%*qwc~+q<3c&IIqTw-4HZxtSTC zM$gRzPHYr-jz#g?qYr)War%H;9*Etlf>kMeG^uLNQzR-v#FjI~l#dexrMg09u9O>v zGtvi#tAtt_zt#hUb4in+Gm$~IpVi+VvmM-b^aXfQ+HCm zeg9CYH&f2aTdiir)6H_#FtN_D;@=7DqDR7U-P;s>1nsXm=d?Q~A5ld!c&EM1@Y$mp z6nqHya^ac3e9`ql((4jJ2Msg>nr01$s{ zHE1p+8ncGA;BsQN)U!pi5!l?IPHC&Br_>e|j|SD1NU7{+qrZhj&yuH5!hT73HYgTQ zm!gK2B}H>kN64(&VA>dN$yl(ej|$__%_Z?*W5W3&sGH9p7$>mOLpE>-tAim=R&-GZ z$C*0k58Nvhiy2#qMj^+hGq>&W5$!7wHD>pe6~_-3i|qWx(8##A(z$_@*Ja0V>}=tOQCVSwkHP zon&1Md+iubZYZU)BROFJ-K*g-Q|EmX2F+Zumb|#HW8a&!5W;kOf!MX)2|Kkm(aYGn zcY<2riyjJ%BpM_hLXY);Txmp%l3CVn|C1H?+~|y4>WRy3)YeY!Br?5-Vof99FO!v6 z=w?9r3_8b^fTc&glN4wvt=>nfHGioyPVj~y^*qH#%IJ_SSRI6MMM1OwGJ+eE7`kgw z`M4~9`xmo|X+!6(S{A;@wm@bjUa{a^DGQBxNvnslhrExNPNeApFxbB7(Ddp+En8cB z_Ldh2D#Gfyx~huyZXeYM`ix=hQ!hUS1E#X(rI$p1-!uF*0JbxN;H&4A)r_qrmD{_0 z_m$^A{?q04^<;$2A^0nw ze0cRiRn(kX_u;kY9<85Ji4CR}K>1lheE&%ngHh!hH$MOP=KsFD^5yk^Umx3^ymM#! z`***6c+b&qZ6BS1l&VZnEEr@RQO0C7wEK=!Le~N(rEwmC85-=qj`l~7jO(CB^v#(O z09XrPu38v*=SPpe8oPq!=(u3lHPB+bPiX%;x%d-k?5;2-?r zyiZ*59aWp+pZ2$HHXU4AbqAPwjt?x)G&NogOLR3fJF*IZCPy>g}5Qp00TrS{cKCTt19jzBmSM$Ik6#<@zfQdbIDwdsTuj1=pI#;T6jp|#SK zh+86UJ_c686kXnBz0Ugsk&1d0GaU}WiQlvc1z6*QRdpmPqG_VpmGg6&z*UoS+4m!E-_p9dt9;!7W8kB90~y8dq?FxpN8MFZ!!e z=>Ya#yA)rNofx$P<3vN34iq+*3}~a{c~-uK0*tkAPm5j+r8n}$;!^QmQPj4eK7~zE zur^U_Ks7pTx)z?`bF&oXD&81}orr8*h@hx`0^+vkxX}5B95+I7(0K83e|A}WU_;o0*>hcs2EWs*P}|jkWnj9DAR6|2khm+mh7=Ctz9$S^ z=>rzzYJ1AuwpLzMk_B7T*H&s-B*p_fzi{P>6HnJx)rZ6;wuVGXY*%AtiJqsz?$?V6 z4Qv(40Rpd_R9~Um8CV=+PQuNE2J6VlftorA@fz3E_Pe6=XTy8XzqIEklnA{-2uOKF zFIC>(GRkLQxqJfI_LL#=^0T)bcD=vXOL`|^z@J>bcIw9ufs;=e1E#(8JtM#dz%by? zeswC4<1?4fw{q$)VvSq9`yFGz7??sz@A?~O19%I*^`MUZ?AZ_A3b{z9&itcZ2@AW- z!uE{)(O>`O!n#NMuDhSqA7?y+&^WUkQM+U_y%w?@44APk{~q_tCg##lKmGL=pBq>H z>MH}~iqjD%wa1Sh*5dTo?qd%>eC*iuhsXAgEr6^okDCnCHyDnYOw`^c+q!;U5%szO=mze<>C=a~z#QpHe@Vn#h&Vhivb6!lSuWktA0BjZ*O4cjL0OSF#Vo(8eHuz3I?OBG2~n_ihPNT z=R^bX%@%ERs9F=c?>5L^;Qp%)h0Zo3yp1*~w@L`3!P|EDZNd|;3_%;XkJ?qF6G_NR zj7T~vQxj|7#u5<^0$L)UqiS#{krqu_7Cxk?apZ!hUSUFNQ`>Kp1u#PBe3Ui@ijVT8 zEn~*{P`i*X0kJrdmI_e@&rse2g(ZXFQM-hItRg8LhOEUrF_d}mxX8r1XplQz9NlEE zTNoT4-lV1h)D9k`@op@^o5p{O2(s)e~c(#au>r-w!r@_d@84wTZkg7NxxZ)}L^CWn*S{tl|fP^)7Av)eA&Kw%|= z5mmrkImmw4sH}0@-XXNp6KiWwVyN+uFqYOrqOnxOK*unYxnqK8j$ZUyjH#1rFl8~| zMj}BM;YTE?ePnMIcDsae7|KRm2OTGk17UP~8@)*FEQb;M^+(!bS^*mf_w`5S6F~A?56d9uCDdB$@`4XmqflW zYmQ?pO=6G4jxUKFB_dsJw&P(wfV9Zg5Nb9lBB?E9D$%gADj=2sEi)5QAz=#`f0z>1 z1(vPRT6LWm3K0hYusmNm?=cQqz<4$8jL$gzxl=3#_Qzx4_^DVf##OL9-38`muH*s>?EDQ2;-2LvRELmIY=2RQ zFh0USN*IcS4C~~1gdm#)7(?mIIB0l}G?fx`7@^T}Vv^w-<0EF{ThTJ$k#s+sxNV#GHq%efey}irteklM<`4(zoFQ6U= zcYb(F{yr4$eCyIO;QalK6`f+ATX|a0y&LGx#N)HOFaEf77cs$zc39E0BvaXniS>EI zj8)rp?wo0KJ!E=a8-?nJ4J6n9vbFW($!pFAIe6~MOv7tBvAs8aeDdtXvB_hD69?Xy zJU(%}N8$6tbl=g=zBdJ3F@VmV%yf2j!euH@+m}6g66R9^aP}kwSUCFG50CuPcip62 z2?Oq78Z=Ev!S^r@hs z6Pij9%qjp1a*$~1YS?I_yCMx)Z-PM+`frv=%qtC5$ujsR<51B1SPnLlkToER|Hg%a z*_W0%f96EUic{HC>AXk57sQ|9T6t$gLbB56&ys6f*_>5XsfZ;rep&U zd&rL+D8eaWZ~U}WgC@rV8J5>((aI!ZDzY`K8p~l3s?5wueDV~XzjzwA6j3p37rYjh zJZrVE_Sf?iHAz5U^$3F#V=WAhE4;R3M;bJwSICMU^H>nm;T;o&~AMUmHN4

g|Ut3u++1wJUi4ec|% z!I(&+BY0TgR{)zfB$jQUc2F6v1;S_sx5$IUhuH}L*9FdtvS1rnuFFPg7P7B!gHT!< z-`T81?0^ZoEHQM!5A0Lfl@mH>bQC(91bZE5gE2j9F3#xU0AVKx1Csli{HuNvh`6TL z&!HA+Zl($KgL0zq+VB(v&X8u!<%ACl0LSJ~7cBT3n9HS+01biGy@m7~R9V;?qx=`H zUqo@l*%*`?K_OwTqTbm++E3dNayHantLe+&q6?ae0fIR$CszU-6OSVqqhgFm0+5&= zW7rJJ3)K}vC{LfR1jZ}qGC~$5n~~TGJRFG;@V>5+vI z1bt{6NF^^M9rJR*f5@&lmWDqmkdJAf@j`lpg@n%U-)C_G{?2QrRUxsxHvs@%U#ZqF zE-!EXq*^D08vctF@IOC2Q(f8EyuB$HeLcd)B5vsffOi4Ftuzn|yq+YP{ngjg zZQI+A2X_aL9hewA@W$i8$w~N9N2f>MK6>;-R|ZrV%BxOwAqgSw>g(+M>$h9qQvg=} z%O!Bz=zb)nB5s>D5sqqS(&*@e+*Fu56CavG1bl_sx{#jgn_<+OQ*&o1$_mT>7YeW- z*g|=Bk|L}DRaY6p%Onm(VyK?mCIx^e)ecP8_-5n)03ZNKL_t(;d_UECFU zM58I$ghDlju#DVRJ$b?yb}}Z-iL^MV3aB+Iu_B4Ap{6V$(B*D~(k?={0AWIFl}&+C zhERm>sH0mnVj$p?*Kff@Het|lO@Usgyi_6c8bO82FimC9XcbX|QDP0+_lPzm1j`wN z)!@28ll=|896T8@zMzOowbmjAkrTm2yC5zkvl;b5motK_S=EGLOuvT93*%o48bcIV zy-}QHASt6On28?|22yhWjZLx;@%cZ;ZFXzXRXVeiII00pzi$-OEa(*b@YEMyy#Y&`9KTW~ijJ=Zk@WXZhZz|Q?F0A=RvwXhfMvgN|kGkEVpEDa8 zv*z|ti#xQ0jc$ncBVjxAOITv zq+y~m%Nkm~1wozN!!dNp@>Cur9wc9(K}#MwwqmhpvwB=b=${=fuwa034Q?ctMLrg| zmh*g6WI240LN}q8P#7!@F>Mn3)(5>aQn3W2k#q$W7ADT<{q<4m?Dxs_KPn1iep)f6 zoc?&&84t6t9J?`>Gu-5(16b&U6Yfdp+!R*C@*dkYz;8GQvoLa?b2F$MOviFb9RGdJ z8587|_o_`Rj{_fw9bSAKQz56fq&b=2EoZi#56 zuAaxo-u?3Sy1*hT&#To#7X*KomoMq`S-yghV8E{c@CFeYFV7P!P!$X>_f7PCclX7U zI?&Z@kuO|C$vbKELlE(67+_z$`sk6M^5(|o#>P&)zQcy~byLc&gKEBO1t_G#8MA1UmpbU(Dgg%sdJ*( zx(T|%rY2&q-v>E_GwupIr)K8xAHau1%DE;LKP3OwNWq$HjGP;>lUhND+a`4z3^f)G ze4IM;&W}F0p3$I5#Drq&OQWjEElFfF@g!3~90fP20x+3!wh%FkPdQ#*gn&hX{i(vuY0l_omL6=5L7jp*f96EqO75tWQJ-A^oy1TzMKNp!(- z%PN*8^JkM|R;TzRz_^Hrn7%Eg+(`5&%cCywQHm%R3xtt6z?<3P%W zoJ+K2VzdydF)Mw*IAE`NOK=(qyOlddYXY;gXeLC=C|9QJ1+HU}RoMhLLhi0#;+mN`n)T!=4>(G3;@dcd(e*hbnE zrg9)mCHjsDGCkmDO`M;yAGn?kKJqu3>030j!ZzvKvO}RJJ8b5c%p;OKe5WUUE^3gi zq)@>BrChH0Vd4lSuYNqQoiTy+2SXva(0=U)+bQ*ip+Uo)Yzz6vB3(4bAVUXPIZ}I! zG3mA-8^floV|Ko4yqp4+)zy|lc9Z2)>bi&Z^WK(o{4Bq zQ1DqKyiwX^C~^5^MvJt$$+%O=8x zUjExhW-agIfSH26fpR+eee^H8e71CM{+-3e#od+P{Kr-1N?72+b6=m=5Z3B0x;ej6 zedppL`YQpyAqOoLH3h!!aXnU-{$2yRE30v2JVV$cNrh;e7OBtyy!01 z)J?wj*e-YN^6rkg6I_B#z>9T_4L*g4?WOn#3RK0kQ;itj_`fL}c2>8)!8)A6lq zus0IzUCaST=m0BsFaph-%uRdKXzwoRwwMVXYibJm3EFH6M1o-7WP#hp?3S5N+db-r zmpkZyS0i5YS0hsys2hqVoR>pT}V4ZSIL_!^G1{DU3;7kcVDX7Dh9iWF(Ej#^IQ{P zvmk=Fr>bebHT?ri)6;gP(7pCk`)coh^1*A)p(fp4E4BbeO0~O`TTp%Zh z>$uU)6V1$6Pv)f1OiVLy)!4u`QVufZVWF{1jQblW-ZL}YY+6iF+7z`*G*xSe?%YH4(IHK@%~&Njp3eN)8a(mI^lzT9VW4H z>~fY!!h}O}DCsEfz*q}?+4VRUIh;sn;tD+uCoX6|7*q!X(uoW19vz96tg6xpyzOSz zd~VnkrWvGKh=t8MC(I?AXfLQ442a_b84KZ!e23Y6%q6~K>az? z=Kr$Ezhz3y`jN?UM34?xSZ$#%n`rt*2qz~JMuX2P$LS@?Yyg{*W#W>k)s+RK)K-U` zF$X@1gnLsYusUSJ70qs94})^6Gd#Sx%NAKGtH!Ll1=u4>75CgXCDGAdhY}0c()Pp@aYZ#02>JKisS?Rj)1n@nUsl{_(}d zOV0YLfXx!|C3o3gTH5&N=Jv+w{5LhXjKXB{nXjL|{Ev^fPl~;T0v~@zI%_`qhQybT z*YrI|e6L+w-WTAVyWVBTUEehqT{RJIo!|WqPeSw7zS5CXFO4_{yt}(wt^R+-y4t$y zUBOY4He03SEs4JQ&u+DVDMO>YW`LhB9JRk69Blnv6&R@y(ujH(pZ;i zZK>pC8FYGmjGI|iE+ zxZp)^mE5{{9na-R9Q7jopSqOAur(>TubR7nB12|L{inAY{NyDtLgn*MI@hb3v-ujz zji50ALI)Zes6YF(7pg=$jXFC9G_TLOW}iN@8*I_q4KS^>l{4RM_BN24Box@B*^H`b zv$@%vJ$_Fk1JL}U#hU|HDHt?S42{@diqY@szyyV8Q(+U~i9RI-Pk^HAB?1_o&S?Rd zO(b)}IaB2IMggI<5G=5Und4sJCQY2x1WtgS?CI^#ewFR-=x0XlGLz(FE-s(E^rt+WgkAdqlJRAnb-~!BsY=IVbcaoM=fX15;h5d3#m-VyJ`n%2X0a$pD+x)Nz;<;YPWS>wSi!&W zp{Yc-xa{9UVdr&Y12NIBlnXp(#&=*YMmoc$39vcsIs4oW9wH8y+~5H|JmuJFAXfY| z9VnTE>q(LrM2AiW1;$G9OF2lvqQVza_}ml-Xo3l4my^kN8liCF`AvWK6VvznTyF_`=S4>Qum|+HsndccV zb&ya6g)t~&p)#XLLZ+*RPcUso)3~C2B#PIAdFHu>PgE#C533bS+EN8io5@$~kt%eb zO>|F0#pB9HHAr2lz!GtrQ1(w4%s4n@wD{w_w9EVJOcOd(qDXl3>!;6a3VLPx&E@4C zhMmuyJEw`Mdf9k&Wn~p}yRowULic{Lult!}Ps{<|zB#|Nv22#Lx>9`;&-z(ifFJSu zk(Bh({Uy`)7vP;8g-NU;!uP)yGI9t3E)1P|;+BooOm3|@NY}%cHv6@>qa)nzjp^q6Wx2oi*n6R-%Yoo|mZQ8BSdMrwsx=PJr zII2{0^=Iy1Z}4h>Yg+H$%!KP<-F(;om^%NTw(C5OTUvUBMnc)zEQJzAE1v@8OJW^Z zTCNUr$z|%eGt1#cb2P;ekDVZQ0WfSSdyuCYj_S{R)ojZIX|Fgf$&GdZvp?)0xQ8v`|ATC|$LUQo0fr~0Y z=s=mCB4*5pt|(OCmDgTbBbq1sofVW;1!XeSl{qg! zQ9HcY7gF(&1XvJcf7xF$NcB5=Q5AwLpP_r{k=-{SIaMGO$T8=}-6TmCElBDP&KV@P z8RSN)FdXR~qraGajqFOGRkxF4@|-goOv-aEw*%&Ocem~2G>YyZCQG%yhPoYH2ESPY zU{bM+6L&C}Rw`DO-XjC^ZlKwYOZbooeP%X|^@v!G?yej0?&ek%CQ0PXyg92>=-^v% z(O`+6=@#Z*9L0oH!hgfvGy#LDRQ`susG(btS&`TgbZ8qE{SCWz;MQhxDCrcO3D3A7 zXnByJrds$?v(TrAO7^`>m0ML+IMYD2QA6W4+u_DIL*_7P8$qd^=}1EF+~T&sGl-BzFDAXw;&cs390tN8Y=hIq^_5~e zIi60&^58E6<+R5@+Mt(`BPtmTQ)x(2OA=#S5;n-^@RVcGk26VeQt-`zf$0qOzs65j zV5r7KCu2i-mw-hJ!xXaUDa6fcBNXK|)YZXMzw0KPH27r&OdkV@(Vn8P2JHI|OwrQ7 zA1Brt$lEPQyH=$7a?OXDck|SEjw>yN48?~$ay&S1$Rmd%hSV&BHag=yevg(@5`~Nb zjg4s%*h!@C57>|lfZyGB`On9p9C8K&$E%x$f?HSa>}vJpf|&;&_DThP>C)EX(&hQp z1pxT6va|js1vE2g=F!VHFYjHs0>NHfUHzT}jKXP1YSR-hzWvYt{dw<`)!C2N*48#x z7q%9cmo$6U2cz(tmzSN4OEYLUg8m8Y{`jT@E zf#deRCJ^7_?O^Lb)95Wo@kuGWdVUx@-PFnGxwFtIF|<+OrdLll9scIYtJS*{F@ir;i8FXrW~UKIMGCPyd(?eN?1clPk$+Z8VznqT_arnWP0NP1j}`-x0$dhSVb% zgfYOU38);ePEH+OAmq7XKXQ}jQ@zI!tmDd3_!yOYdym2=&(>c%gLZerDTc2efS)Mq{Cb`y!CXP&wJ*>f-5 zzy0~-y@dbS56+yK?791zLA8pM$Ieso(SE+*M$Jy*r7$t4HRn6xfxh^;=l2bVzNumZ zr|>}ZGh{xKhyhXcMTU*CFla0rf~tX`j<`XHa!3sf>~e=4|MgcX_sSlY1JvuBY>MS_ znPIaJJCiZk@2GC@(X3EqCx(1>N;%?_O^Mww0n(8Gg6T-kr|^xs0KG`cz6!J%^iq0c zP+dnB2O*OZP1luF%up&B%Z+p~Znis0JBXn>j2t6>Zfn~q<=V2j?v4^GV|Kya@+YYy zsg3z_bDMqnxpm?$yL^ln_UGG5m->#X7^?!crM(?QP>e-x23N7H!S%8M*S9AXBfQ;chiYDOw%@^__x#&9%2+|_h3KS10? zej4s84OVPw=&ts-F^#5&lo~l{)Rw}9{-JBvoGCb_6iQKILYxK0q-snGXJrGXjX}d| zII*3PnFhwE2Zro>L1-t2Vs>EQZ%cIP6CoW+o6G=9t$7Yy6Gv&ZzBP!9IL^YR6MbYmv#<@uC|Ke07`O5YER#~&2k7Nd~ZKz^q{EoX)m zS{Gc^WEZ*GXPHEBnevXxe677E}4<-?UkLXi^@=4qCnJL zCk$#Bo@l@RLBs3y*Y2eb=U)HS!f6)thKg+L!^*mZanCOT}}l~ z9UOe&awba;$J+*Hf=Zb4k;AGd2 z<_Rw1MfqYH;{WGhK7CqvhTezCSj?g1;XEj zu<{yNEmMC}S2YYJiij538D;P}fT|1aGog}^h_uoQwyHJ21a^lbkZsV_1zsslE8>fk zj>&IZoxK~h8rNks9moYbc5-zQA6-ZWwrwK6I*d@okn3nedu5+XfgFuUIp-4YFg(q* z2K1;7q9_T6?keq+6h4U-E2okMGPAmoNE^v5L516}_u>Yo9jUpC=t`u{kXnMEhW}LGN5V z$fN8uG*#h-W;G-UhU1Xj=54ILjadp7;&cKB9l#Pq+0f9e*ylz&xkUr%uu*39{I-Y$ z2OEW|cAgpw?TcU|ESIHkkk-OJ2G}!1KLf^LS_lE)?LNXNjVRYQv^<7@UB5Q+RD2Ox zz^lr35fxGo64!D*ba*lyDd);yn08-g(4lIdG2b%n3n7Hg{%`032{CMz6uR07G43Rc zzf=O#2&{I(bwyBej$(m~2ZW-oh{16AL@nCUBrP%a3boF3Zo~+1bTn=Ek1}|!NsbyH zj#9ml&U?z$O^X{F6Q+*A9y>wev$yW8OCLS%d7~?axYH{!Z@L)sR$#+8eklUBGcyyQ zFZ*D{acFuQD`tj@#)St~)VwS0@sKo627%s$;o+2_E#fH#$}|Py<(-TT2u=Hyb=7~o z`;{PTa==Zc4WXwp14_0UU~4={iy=u^uFQ}fu3Zw4fn}UFGZd3jtDjmzgw3eF`c+_< zQ7Mx$EAvCsEFxq%bV}N zzqx5&Y<{}*_sz|<#gFf7?r*+3Zvc7cOhGI{o3N%AUwl(O;8|n9^Ghx;x>DPqT0^2J zsc64-a4_pe&}$2qzE3HGiui`79x@&N6czOUiMsxurt>>|h0?S%YiLV}DYSu7`VCqy zSp`?x9s!mtw>!(tsoWBCH0?t4;6S%nLt2VJ&RCBMmT&41%XZ@C&GRxnl$#ec&LuP1 zFI)Ea?DahFPmw5o=m*M&r1E^8*X#LmXPy8&b5NL9B5KXZ!~ypFg2sWF=}}xdxPNf3 zddPtJZ*^O~LkVi=Qb`zaQiVDr&8qF?`v!h+RRI zG)dL4TH8{bg=}qZW6=VX5V%!6RVkHAA@5TYwB{l)8RKg}Zcr~{oZ3_A2P zpl{tshmsB)7HVl7q*MZ*MnrGmm#xa((4iEEMkC~FWa=&dkYi&E5@)9Ni_6 zsG>HoT4o9+!Zzx_hOy?gjzDN-(QoK1Jh0HuBoMrACBy=s0lIpGL<{^vuZ83*YuX2R zM$M5m!ih7w7;3$Rk#v+`oQ6JHXz%N2I2}S1bX0h72w~9CG_ofnJ}980Gzy1=7l&g} zimjpu$BMcmIDE}|V1d>ONUtXvf=ifj&^!%&bl#1na6asDzm9qYEK$Z#5qQO*T0oXY zVIjS!QNTPpZ;R4~Bv|bhN^6K3(9qy?!<1BU+VUJyo6WYhH3O5O(USyFwY3Wu25DCG zR;aC-N}KzD!Ng;mqQFjr8NI&3X}<+XLv>|9ztSbvG_sol_rm2bP5nrA`dCN6*F zM0;P86LzFOy@$F<3`(HCv#bl_&7dfns=YcYp3%sFY>qmvcID3o(oHdZ&S2z>7)m_M zQ;vE&SuR9ab}(Y$xD5!~pu(h~-l0OU0KKePXh8h}{g4f#$R$8_C5CbV*d+sSDPawK zgB`zq^dSX0#}!NPJDxr09KbHk6bRTm(R6eJ#f1U?fWY$D_%lBPIRuXFC||fZKrZ|Y zX;^~T5Mn(Tzyi1jNgX{y@+sF^S{^8MGyF+d3C9uq3>4&imy1^*CwS?QFy^VD2M{bz zGkQZn5;@PR)d<-eQ^${!>0$+ZoLsk`_zP54&fk9OwdAwossgE{zaPE90>7A117)W` zx6%9{WSUpO*k?G1k0XF99-qcF#aThvA|Ld`r{pp}ClwwNQjbuMzI_JFduzoq7#|*c zbMnhC-+sNDE8Qy2y(+w#`%9r%EiT;@EWYz_uUOsNn|pPCsa)MF76`zqMGo)&_eKEt zzkm2XH@jOd6w0gI;&NlGO|ff#)!X)5Ve_C=dPXF`csSYC^@aevn#+~v<~PeTv%5u2 z#HBn;K;aicp_P_eZGq>@H zYQ4%lkJ3!8v^~Fh=yWCmGq6hyzVB;}CIR3@Z#Ra{SpNcklil)R_p$D_r)QcMEhm_C zb(UIZHWE?{-Gu@4DYh{Xb!(m^Ik7LV%o`{=LevJ-&*S5!@xYj{VJun@D${6c9G5%F zh5+U}@|t!aadi|@=!Pi-adfFoFO0tL;y4aNp~;O;zOVFI0P4r?=A$2OU0}48)_yb* zOaW1owXR<_$CKs;6$$42l+r3vQGiWC=;pIxa1<*zlAnZ?^i)RtqtZJJ$=iWbae(32{-`$BT z!+lSles%hH-+gn`d>gvxL=tVlEOkKWwHMvS$;53A2BA>vCP-Ffnu8xN?LUg*;sWMb{laMoI%hP*T0sH3_>^LLm zj8T3U>qi8kDWH}w*W(78G7P;kJx6FAL>{y-Ux8<*J4{KmP~g1H8K$Ti(`cA~x#9J=^Ou|+XT@DX520tx zV^~v!7_({QTN&~;PM^(aDMZ$!0U1}$Z_SLhGJ_a{1w(jclgC@NBg9jx@Mtt7Vd>l6 zddb#qwxQjqwH0N*C^<57(riQ26)GK?T7lPG54Y0(+m0e6(B)Pqnt*MsO%zbK_PwXl zznR;e!9)b|z4{DWw2*)$uM#6;ur`#Yz*uj!8|&(8J-|R>mAt{}GYSZKhNXoKbw**u zEGdK%OK^D<%P=xrf^Z{4vY10juf`aap^ni;`wgaKH8|kSa0u#R89Z+CJN%s{MsNh6 z!*cjdH~c6i93Ki7r`E=Rq(^YxxSZ4?sd`|D6LX;Jdx?k`V;5-F0F;>aP8TpLOZhV@!jNHp1%A#AQP)96u z84R2?OrXPZDJ>|En8pPU;0poD*LtpDIxRO5hQ|pN5|vdn7Qx7W?qU}7`I*^UWnsYb zRwxMkE(!B}b*Fl#D0FzP_)rjdX>N7)`x6@avb68z%gew2H#Jn{`T0V*SgclW3I~?wX1sO04hYI0+$EM>m(j*W0?glh;4n|8RJ*q4yUg zwq2U@S5e@zKRc@=&s1S?|4R;x()l0aflh~AUbhaDAAP`(^N)?v-CmE^J0>?misc4$ zjA50qA<+_V7a*Sgu1lLYA2M8R+50h_NleI6ZNRKU0#g5AZa)8$trhH8RWh=$%#`ZX zO)jhEc&}n?NoH^?)64^cn^om}7}icOe}Zx)uNqe`Cx}6OJfS5xsz?u2Zsc0o5k|dp z_v)3M3AlH9uZ%_mch7-%W9Xu;1glz=9*IX)gVl0ETOm`^MafvOmL3hH&+>KqWb!vV z!PMhk*VfU>N^m88{>r1t_8n!F;>=q$C?LieKhSb^*@gP2tWuW|Jv&qmTaqBDL}B$xjA{b+^6BUX)b999hnxgX&&}OJ**Ag%pGI zFXIPD-Ss0i--0k-_Ah{!GUa(hz?DJH8KY$ciYy_o09a25|4jg2E< zxTs)2uS31E3PYf!H&SB-oV7wnt=GfIi{=NqjVRVaZIX`P4VhS291B`zh}c%^x;3-z z(=m!tzLZntb=ZyMseJl%n0`aTf+O;vRR9%vl`%}3g$biD2^1NME5TeuR04aUxbnq( zXjc#bb|d{N9Sg_O7%NAp(DKEg!t(fp3!~DIbqtXZv{YF4A_ogPElRcA5yWtyyAb-S zd^BHif+nM!P*AzzcB&Ra@KXdrI~g~LkJ%QC(2b~yi}sk!?x-1uX5qJPXT_XHdKNGj z?AGSaLnjSEmhf1o&FqG@|{IZpFCf$*YojgY-+M$&s)PHU|=`o zvox`gP~0>2z{n_lRRu*Bm1bjuc}z@l-58v2U2C1W^$q})Xd^V=X=?gv%=`|~p=A~m zzac9_CJg|ra#UkQ!N0=arm;+(A%_x2SWsdDppArG$43%Z&Y(B#Ml~HtB zfhdj0`eFu+d9>K$hDuYozPz3d4I;)0LkS~XAEpwcG`Kn(uC5+ok`isIVRxj#G2hTI zANEz_u2~+_ptOV;k>kW+PNYvfbA?4o$yTj&lf@d2)Vq$Ur+7mF;*4X^%HvGcZRY~ z|D_{WyHDkox z|LEP8_gS}mGVuPuxrd)~i3$Y{>1BiBP@SQGQZ~Y(O9$HedNqr+?vao)8&VxjL{Npk z9X+?iqNVHolc!p)cE0~$d9>$L%g?Pv3caCEv~|^G*f{Gy*lQ~|CcXMt-ARbbGcmcIj#({yz_K}ND)%Sow65rrd#7lX) z`lZ8UF&b6#!eG=Ct$=)*&@YI`P_VEpXnExez2z7$GxCYYTi(GMIJid4w;VAh@H9*q zM@J3fTaAEt+!MLQ2lg@wY%y9u(6W?^u+{G*#+Dl1$#rBvHXG@(ojWb#}K*+E4qd{;CYXAfV}}z3q=+^2Jfm99lu0F zx5EX?4|xr+&*E#_kG(1^boJ3$3T9D;&#|OJH)?=5AKwY zvDRtc)kc%h~|6nnZh2l}K_Eu+BAAl-oLtqO0`$(U@4=9wdZy0LLBqM0hW}Nn{+C zSms91Hps!MA_1$3aIC5x{KjsF9#j+7jWt2eu?`l$jH+O9!c}JSpwG!Wi33JG7C@pX z@!%{P|16>i{u&uPGMMfGaV3A-@U-QoTKQqZsR01cBBDC|uPCo6Tp30Quu1H21Of~|hv=*+97Y7vlYXiCia<)3@Rw>O~gHYxQP}y_LBWf`W4EPFkY4~fYYl4Ppo+~jiMz_(3S9P z1__;JE0e||!&^zOHHKaW?2NtEWDFYZV?5Z``6!?sD?nma&A0yJdJcGeVnK{&p^z#R z3L6(Lr1w*)xzxmk)l@+|aA9j@YAUaGz-_7oRvv|Zc<+n9{#U=DN>4$7H}dIxzK~95 z*3zl99g*_2ytrpkL0L3hi4XBY~6hM%O%67e`vjO(%9|4IZXSE>9!(Kt7Ztr zk)%upAoj4YC}N-qzlb|5|L&)w@f@`ELI1sO=aT*M!{vVS5(nYrcZK|=oD~_;S$~$a zNL*WId0Zws86d@~#rc!oRmjo0IQ!=VjXC)WAO2CkYsr0QIyvxd&T{g4_xkdOXLGpY za_UKDUY}+4m9Q?p*#LZYAfSIM5fA~cH5k|}h}xPmgJBTri47kEL_?5Kh#&VXmY^OS+H5v?7JauaN5iu z&x`c7gMD=uDPVbjB!t`fYIxsXPN`YRAoBWZ2qJ8gk7yT_zKvGkP6Drp;1G4~uuqBx z-+t98Mww})4!B}^TZP{cWo@@j+9xN;h{iM;EG@JE+b2aVd9Vee+c;TeuenX7wl#L) z6w5Ax3-j6qSfyxfT^Ag$9kXUck>F@+*oXwsq-dwQ%0djd5lw`=b*`D@`mqe6!}vQlSa9|n#SQ{KSTxr}?4czSXms;TSiSMm%e5vG9%~|rP6O2QLh52cH1T5PiXpI% zf=f&WRMOg~*i>HSd9enL$5r(p(!ZESvsDo5V1$l5RA1Onoo(37ekuxOteB=wmHXP?J|0m#DeQ9I^rEsQ)7+ zzzgHowhF0CDkTD($`t>U`erI!*crdDH8u6kemXCTj4SBHQ>g1>`|ia+;1J3fzFsWO z7R6f90;lqs)S4*petsvNUz6W6YlYNmMy&K&CY8_cXC`LfwD^@a$|rgK19QL&vlFTG z^mKY7zryMD;$m?@=S(U<)~w!lctbg4sPya&rPg>aZ05rz`w#8=yuVWyXz76i8dLk6=Y5|Gp)PoE>+fv>ej9Da zmphj#^3Ag6mofHs{l$*k48RxJ7A!|WmuJx!Q=bM2Q5`D6)E9K!h_*pTb#)w1aYVk+ z9qS&Ddn$_ij`}O24ar2P3l3Dmf%$}I0)-+)QG7wnvlSLu^e_m_8bT>s&674db4FS zKuAnyLX}0xOOQ(-OHive2BL4-t;8)0gtTh4m$R_EZ~zk@Rs)djE$soq*tb!l&jiEP zXp23{5m*>Zd*7n(2&$|G?|Rf_cM*KLtipd};2uIRuXw!>URl@WR4lJ3WU$-U(LvbG zhF^@GtzK*Uy1fhDU;}++{Z9ne&_EO3c447w6&(zA4M2E~TMDgoU^UNy@Y*qqM&uQb zkgMh(hNeeJn34DnZAc9q%>iq$W)AXZ14lvQM~FBRl%CgUl5)_bh7G{H+J)kZGba&# z1*i6~u9s7$*aPk+`9(u0S%h78QkRQ?FV3x^fWh%X z7p!$Zb;MWQ=bjQS$H9QzI)dCtJn|xPKT=HyJRTWsi?B|bXs&y-8z5ab&WV)48OKbW z2z^8VWp6OTp^r#j4zeVf#aV5<_r+=$X56~6eF&S|Nv?1J<(+B!8rjc)Upa|Vt^^kC zz}*)_T_M7vf$Ed!Ibul`9oBVsqu>FEEO7RMEO+kah9A?;mCzegXU06t`_X{Wc+l5?V`^l4U zA8ylo*%OsoPNguQhB<1MD~3^WNbh%NQ-%5Lz4?vQ#xY$TjL;>*2tfEZZ$5gN^2*Lql z0CzQ@8GG`Weh0&9y@;LUd!dJB33SJMZhS>JlA4=eR~_;l#btAVK=yEHH+yO})9bP*QK+))UjLL!b5 zy}u$!OZ46Y-$RVma(9*o<8O~=;8c0 z4+j47qL?Mu$eSdLCRoPK81;oFqf5z#Un0-g0lSQ@C`V)=3`+>0fw`>CqVv?uf&tfH zyRH@%J*(kIa$!0hVEGmB6>%G2x$SZbgQ!A65T&=p)fM%E#DePDqw7R^U3Q*GbD~B& zI*^duVYha5t*;Z!1sJ;w$mwAA+lBAoJT4w=XotMYj#MlIok~axH@7qKBG)Kz4-)4?@)>GPICFscB$U zbkczO!3IdHz>}M*nhZ&^CfQ_eFeDqAl2ripDg!iDe={eOmFHnrYC;kRRMJ(@YgGZV zL7)*zi8?~DmC(i%gRrKd=1K(-G|aw(gYX`40ii;RD>*ts5{n9fSW0NHR9nzpfzV=I z3}rO;4?+%&AP!8Qb$YfMXPtyU2;s}T|3!M0Y&q(#lN*3pe$|aAEU_W(Mx^8g-Vf7l60nVQ$~IPK zb)#^Q13I{MkbyQrXguD=MkU5$9)N?g)8}!dUXAyT^W_4vH~9Q1E=;5oMt4QH1d^S? z+;ux*Yek#}M$mT;bGg?i0)c-{7g>;%J~{dMq_DrgQ+Qk`U5wQhtV_j0@m{)+E-vJ9*_FacFEmuC3K0|9MzHTB}>Ft>t2*VcCOMG3?OO)85^E3UIw%wjb3u%PZe{0lb{S(Q&1o z9|%0Y-T?r<1_lhQ42PiHb;_~LlDEGylQAiuFHM*U%KB=8en~TwIsM4Dcr`CA`EKp5 zd3FsStNb2|Bw0!mzdf=z{obD5X)IUSd{b_;l4Vj*D_a=;Lel3wr7>h&eLpnxTx$0% z4KPv-KzJ1@*BFT*wsUMi_=ecy16mp?hkLL#D2t#1rJhy)yF_MsIx}%zvH{?6KDRL0!f0%i0honrYvP}QJx&}`Qqu7&rCu3R zDbe_=;ulS$kvDlP$I`ME3npGACt-mI6P}tdfkulG_cLe-u?axwreMR-7M#7%P!sRn zV#O?W$6Blkp?C)Ja)bw5q#W0QN@0%QfXo^@WBNi236lV87C5V;h^nMNRBb}^WPlkj zzUblz4$-@y-h|xtc9H3@5mU&nN*G%N#x&#&lsbr_oTS2Ox z(VieCs2fULavlS{lk+aSW%0NDykyD#k-Z+TcUczF(tg^0AV&J^^YwauVZ$q=H{vI- zqn6RLAhcf&HE0Nyz-%nyr=E~XB)Jiz1lV5-%cbR4b0&$?LZKD2)kbDWp>)>zFUD$X zBmS9~H==^9m_}UD6Ko?GnlvmfwKHC)05Po#HvC9ffCX}Guv{-Sgz_}%1m(Wm^^@`p z|8>&FK=iYbM;A*O>TEfKv?3_A82-cJ;p2?&1 zP1W6|`nO7(2q^?cJ8jc0LP6?xSoM~b$fq$)zbg4+q@>hQ0s9@WSnjZ%u#^&j#UQ$r z!a}yZY=AAut{6D;U@4nm3-Oa!eeD{9rMBNvH$YpV6%1~Z&7sls&|o{7tB^2XH;xSJ zpw+$T5)Pcg5*a9$yFwD&g1&?D-W3SB23-MbxjKXYO5tF6FzMD7VA>jByMn!`WO_{P zN9hDx;IXlCw9sk%NP*zBYsqWD#I=M#Y$9p2&j1#|97#$W*!N~KiJqh<8K&u8JN*P~ z6Pi&e02|k}YrEDDc}RQQ~OX(OD_RWPs{G+7+%cI8FJ!wb%84u^(6 z>+V-6a@eer*$Vfl7YV+5TBS)abJw$xm##T9UC z{`tw*%7CXY?9A!(dTwrWXh?8dPI7nX`W%G1@a(fk^SRC3o9v@U^RxNs=_id!z)#B= zJ{Rm~2i%PaixP&}c|l-7U4iqwZj;{#8ZWGFWf66C})2Fq`x4P?3!qcz(xW01k@w8#UxRZrKgWCrgUO&65DzDZ2 z&Q5OO!SwaJ*>AoP7{B$l9^+AUwNl__`PRx;YxNdUlx9Piy~%N!fGv~8dG ztdz^x`(X&`2ou^1QKP2^>DsXLe9?G0nftuaCclWd{G zUGA!?>ZSc))ywwLOnFsO4qxZnbA*i5yGubO|{nFmtU-=bJQrS zM~xTR#AuCn_AebeH_`Uu#IfZi*U|WkjT7Tn+sc0G8?cOzU)2PTemO-~mj;@sPryZWVT0Qidnkf)PoGttJT)vanZ^eJkXqRnQpO z7F%Q9QE??v{A(xH3L4~KwmdQ*IE@o&z)|*XNyz~8RyV^4uNX6XEcH zDdLUkXt^?i3QM`JpSE9Uv6pHj0ZLM#Bjj;_yvUtz%8M!mpKWAv=oKvsek9U10;Gip z`@BRy6OlDz6V}XV+H1SbVz<)g6QK4}fJAgOq_>g^VH-tAl{TMWHO)Tikkp4{t7WeX zQwD9R{3VytCj{B2-d?8DQ*~O|fGmqPLSr*>Dh^i(EFV%$w2yKI-_)VHx?d6KApktW z$QkMLh=T2igJi33F&^PU8Yp#;c18S#{SG7Oy?Bz~z83WsVL(EJMcQ+PIc8-VU2Fn2 zNNm@+vz^^R#+O0+6IYdRb8*NrbIdD(Ugf4xVU4zO1d{0~*zXV#!`GM%kNz$)~pq!YX z3W@ZqF#BPQ#Dr0YdnP@K!yf7*?ahuiOgCC&Tg3rr#1Y5$P}fBXIGx2unZ z`sH$)f}`w!bA`G82zxCEAzuGp@J#@Cb!|-mxJ`R;o9W3tEzqq&9Jq)CuX6=??cB=s zyu3c2d+_Vu2pkr2JD&~Rnia%c$PEoWn$2Ih@b`YOyX!P4eBis+-~DJ*TnpLkd=?U1 z*qoos7Zw)yFt9l%+;_oHVFl#bobYI2!}Ix7hT7Tex&SkB?FTz=1hU`E{+SWzW<9|*xl7#9oQ{tFdn3$4{0mt3b_Z73L@agLB|e71^@ED zJ-tZODk>~@O8yv_kpK3=fDOhnbw2sO7%a0B#&`rf76x3bB!m<1+o}S9 z&#NYhjAj!QrRcVOxJ4o5#*012Up?$Nb-3!`UwZd!Kkpr1u7?8lZgkKys>r_L?oZ0ei%u&nLH@$skirk|junD3!b zr*586<4E8Ce}uZezp>tEnu;yGquNf0(n$+@HIb{cYwPIo7x52D`ZQJZ^0~+o`YN?W zfsOl3Hgu!@IE@Pd{mprc9mN`pX)bbt6!OY~u1`ry0W zEkBFjt1+dHT{k+5a&1ld(4BI>{-VZ^#Z&gHuIv1=hdyWq{c< zh)v|>2<;CgNUhY6B$$i+NbYqAvdXX0z=<6l#A(U-G*rt$18~D$rNwaJVMmj>-7qX1 zSb$czFx?9c4o9@3Nv<23SowC`Y#MH$Vxd7Fj0g}%{SC3En7lx)S@=@?8;L@JqyDIB zuxL6G6h=#}O@t6&p5brOu0ns4kmead-<#S8d{KZC-;qBms7kmM8PXRcLWg5sSg{wB zWj%}(+Q#JBS?lx*B$G_(_0DK3p(?e!8Za3FrYmQt|3zOV#Mev2BvLG@kfv-GRdq#D zw4gSUXs6#hMdpT%oSi;zRh{p)X&vOdN$#K#m?I=$X-R`mVYiOnL0B_sn(ymRFY=Q+pEmq6O9gx{Rz@Aq_p)0Hdb_?NGLVHU}QDND2 zByC4#g%zn(6QR|cMCz5b!c8(|nj1)=VE-HUqDI;cU>l>Z_I zEhn9il5*aX7Pa_Svx4Z75h!(~1aKEqX?bH?bfb9=1gs%Blt`sLV}xL3Qb`>`r{qX7 z5lW6F1MGtZoSz6zB|{z)%JC$V3?{VCFX0*U1eiX11d}}>#WNc3<Ah|5y)@;Xd!FY!=ggm5izY_L{taI#m`hcZ{nGvA$D9BC z^}+n;6M*Op2B4y`M~U|nsmz3IZfXhD=L`zrm`7H{XhB>uWT?DkvjX?2%vO|uEJqxj z6z=*TIXuh_;W#VWzI^%dhzcD}M5pf0tUXFUfYj^36I7)~A$T5RsxT&i$AlZNOisPO zFTd2+3b=2S{Zd=oR*MjZHhJUPWMSjj?)dDYve(!iJW?TqYV?TS&zcbygwkroTl*{$ zyo%)Ctiw1f7okN)d(j8EuAD`th=b^h4?8sf2F~6Ys|2FoK>I(O-J>NS9Z;i4WWq|w+*;jXg{66X&~%6{ml{D%Lhfu;mXThsmgDPF?O0^eWRjwUE)(|&N!!9yl6tgk) zwOq9T`viJy@PuiR6DRC^1x0h!a3{imG1{po(WUjT&b+{vFq^@m0%3LTJh=Zt6|Kwb zWMVL}7!+2o{5N1+C}69%VDMNwZ(~LnPS0{iU(n}Rav_n{_gUObA%xz_&71}|^v;++ z(lLh+_LCO4P+|(H*R3W1D1w`vSm1CHx@8!Cm}3RSJA`Ex@Z`@K+J)hM=GS6PBOb%}h9 z3n>^IPEA+I~s5YDTO68goZH7RF62M9d}ANpfnDxl{^Y-tOD>{ zlgeXY>XB)DToCss$gEJ6-XTwc`?Jt)(_J=+<;UGpP5VsytR0+PDy0mo$yAOgh608Z zVhm}QkYpjiz;c0JJg*55&xzntEi)KKScnO3D&6}H49_emXXxmKrffLS#K_IjLvhuK zMz649L#{HWRE^$T3ZeyW7a(nh=@r;;4h%R73vUPFLJLOr0MLn~^cwtqEu_TAXF2HJ>wHvGK z{l#_%qLA$Nt5=(m$KdxDU&Y#fhyRTu@-x$t>_U6x8`x?m<_cY;NIC)oESNY7>3xbE zAxr|h{8!Zw5+jff7e`S1Mee=Fg)(n(iwYd{aL|ZVXvKe376a&Si)Z_87^*AH`Z??g z%PU+U$%n(rxiTz-*5jv3CDm0fSa`Su!sQA829+)sWnN(qJH+9`I67#`~BTY_e>kBN)`@G1a! zH9h~2^xPF8(3gY)3x^i&j4+1RT9!g01LC~2G(+eH3r;NIrE9Ax`H_C~Xf2gm85@0L zLuI(aC*-vD%k~)3lO>|Byli6a;U02od!{#Myw4BQ^tz4O+()w)GMA0NTtqp2Wby4{2S{&l1iP2_p@P%DHlG~7&!@(* zG}`WSsu61^H?4}*){eLXt-3x4tiVh<^A<4L+h;a+=Hg76Yu4$721!1fO4$tu4*Fn~-f{}pTnDfnnbujABI^n{7`h{H183}@; z1Kin(tRsPLOQ&UlD=oB%20aEIvn7mqUo?QtfM0!0FQ%3(`g=JrcXkWT_TJOi6OViE z)l|DdcdOkfJlEIg1xYol=w391>rj-20akr)WleQ8a)E)h0<|!@Y9RULD3U;ObuS)4 zlNWVpG=a| zqBGVFNTSQ>kYy@hx`K&Zmzpa;FvA7~h#N}E#|w6-rE*g#BNj?Xgkj%Yf^M-1Mv_=A zy$kV_kYeGqz}3-Y=gWt! z5QSy~)Y1lpta(HsF3NAQ$L#MOM&E_mxHj<}SZn5jZx7yYnWmP8=C584^xs3dl>AitfE`O!{M;%^QuS& z>vNC?C7{A|`zI=>sfL@6%9vPc{N?4aocp zdwPTdJJ1Qn)g?5Cg~$b_4Hgtwaz$z2AA$UZ2o#?#tP%zc7c8ya+phUgg79|Jl%u`9 zTT@~k=oTW(z=rIZ-K}S)2T(HQ1QOASc2Yti-GP()Kfeoh_=i5+-sy>4Z_a=Ha3p(l zFfQ~o9yt5hJ7;dq(-MN?f$Ph!HecP@{cylb+YPFwLP=GY^=T_eDU(6p%0Qkg6<*vcO&e-)_oXg$SGJ7>%Yc>)A87ipV|}oVDG!0R^Z^Q(SZt|<>#R!} zoq{14*ix<)4Bo&{SyC<+SOMLbY#MUc-9Qxsk|kM^R3|Lg0?(2i4+<8ekPsYL;M$H^GYIM|Cd!RlTde)XKv{wE zmYg0H9&4~i5uGIfEoe(omlc4@20{aqpY5~;W8hq{Bc4N!M{&5x{;ZA(l}LcDD@31J zaaYcQM$3BQJpx0~BCX-OM*e({4i4?8X4GtaphNx@3Kq;-EeaSIf`!r}+;~%?Wdk90 z#K^#s^G4+)gu-7z!7(eg$#CQnw5gtB00io23gbS^LF791jO2M20 zOmcIp!X?8jT8OCzq;u3@#j0Ll?1sUH(H0z|(iwe6@>rfQEf9<%r5JTw%)CmW(I}O7 zp#qp>mJ@04a=DobPw+wjubJS2IChV>Tr4t9sB$C-xm`#SiQt9T%%seg+Hh;5=pswQH{<}HB|M|_C&VMTv zH1M~+x9h0ok8eMGa}_ou0bu$3>*`8z5iq;BQd%rOL6cLZbf;W`giG*P9=t;UZX@GO z-$=I!01M%-uTKjEUq85b@~-o&g4HVC4l?%{MT9LZA%p|CTh$V_sP%B>kX;NWXTa<< z4c%9H(2iHsJR@oqg}`iLz&jmp{D8c>hvdU)44NGI*DWpo-+k0FaJl7J6FpE(;%E^N zK20=MDIEv)pHqaT5~v6*V{G382Cgq%x^VK>2cfB3dgsNRN0&6lYj=IGe|Kv~PFw1< zKI{qo<$U`(i*FkiI)C}p*KoVzLcZ!3;uyD@GUe+-!C;73${F;-kIpanLa&=Tq$5w{ z001BWNklR8ks}p6_bBO=dwH{x!?Kq^8uT}LSfsy9bSOME*(EqxBaw2~izdy($_;)9IQ&Joemari~a#ib(`#ba+#9kqXqXSihaVVtYxmG{5 z($Hu{IyQvd>H*6XZMA|sV|5hsDUb9pP3H458c6M+l^ixY3dXv}H+>(BD}CF>JuB zVc4>$vIa|IU4b&_0+?-q79#@#qYdtVSOCxllpYx%hDI-g1y5ptiAbH5VgA6SBq$7zo;lL1rCGR5>$Qv9N$Tf|>$_4}O^wPYW1A9K{4GK}Tdb=P6}Qsd5D(Fq@EQ`&DCTQr{He zIM1F144fgw3QutookC?W;yIY|jID2;cT=(HFbB~o)wIOaD|uZ(>DV+kyeb`4zQ+z2G<3T>uZZvB;>b+_qs3x* zf8^cb+}A(M6=(M4(B{mau5@98EYNg4eWU(p;3pAQSr{xwMdf5DY`+%vDpK#6G*7otopB=#m{QP+t zaU1A%D8lF@7Z~%E;#|2h|HIsTX+=o!>f+q$UU9J^2)sS>e4(ozq?Zb47?8TsT{q+> z)^>35%!1?gDF$Ixlb^d)8N*MK=l^}QR8hM7^@LnedL03$Tsop*#EXl~p`oM~rN1cn zLe{y%;WazFh&*==8IcQzZHv6|$$*cOHiTObD5p_%;(V%QpxTObdEm4P=8*rs6$Wfw zy4{0CuIm3IG(jCKFg1CYx^*Vmw{y)pJpAp;OT*D$y!0Jh{MC-&>e6qm>kXktox_LZ zdZC@pzx{L4x4v=a+$0@Es`s~{+O?~8s|^fc1dn|B(fOT*hx$&>!Q>U+E)_6%$%}DP>iZ~?x^8RU- zi_>&lcboi``3k?&)29Y;X>+=}8$b59pUKDNdS62|`wC-pAIUy+V$D}jN7&!5hKUcf zI!(V$h4w1m!iY&6(!olkF*5gA!whKbgUyHph9QX_UkbJ4s}Af)4<{2h!tf;NH9Q8O z?H9-vJVo$iwa0zb7Dv%TZCnuBW&>1fYU5fnP`6ftsk0uPN!$rT|EwQ{*%!)ZEw{kH zVU3M@;aXN6VPC9g(uRO)t`+9rI7zVpY|j4$KpJ9bkInx@EA(2qc7G1DX93%Y-xFs6 zga5}?jFshEu;&%+W zxf_@`H`ZB^4-N1I7cLkIvx1ky7%$tISy^DvB;?Zw+AtKN@=yVzX9E+Z-S#Fc@S89T zy|l37f*gcQ%We_g9E~a|7D@~4btmK(gMl-ywNRjenj?6PSSW4O7~dcs8a5&`)%C~Q zU$qRD)8aLpMPp2Dq!|g@;5PtXhkP69ui42g4tRc1Oo)}R1Dj)~$$XzpNQi+pq5;@s zGJ`V65ifVbW=!nlHg>&Ur`MYeIQSV)n(qK<*=H^uISsT73I;TUyUJV(_PGLK=E?u`uP&P&`BVto%n{$1a9qvbl*<@ac0d);EExrHku72uaQ8 z22m7dt}(I21c)8lolA5+Kn=a}=^rMM#PI)1pp_`hV3IoPT<_Sr05KI!ZG?Cc{Vn^)$Y z1VcVCjrG|c{Q5HbfERms1Rb3Qaz+sg-PiZ9j~z{*&Ja*1Qwg^264%`Ui4g46R`tuR z2fIX}4=jQK;}yhhqk!P37-Gj5duKUK8kx|DpiB~x#z!hOu`oNEqPy`~W2ry>rI!J? zC-Jnv4U}gOk*}IgFq(EAB@#XH30Qx7afT6#4GylyMyCfxql10)g+Gk0_YGim{cv=p z57TU7!2Llnb_VD7(SZ-}OW*sQW9d!$QOvon@nDD( zxQ?uIvj~1R<7Zrj{@<4Dzy{Y5a;zIt;99gA)B|Tjg!LwMQh1T7kj#Qtw?8RayLb45=uq8NSOUBR%Y=L-SbyQxHUp?XIK5Z zb~^ujdT~x$|B*~%JfU)?_0ok01@jeaSTV>Y&>G`IkkT=RO?Z08(pqNbm35-Fm!qqH z$D``HF%f0SLNV?f6b(f@H*e#GEgr^<+|4D}?9i>_ku(1@(5VPsSwR2A!RjM6-;v;v zWh@T}Ww-OTA2cm57cBp{?0@;vIsVh!&(Hq*{P~OL{V(?Rc6TF7KkPmKad`N0Q!zeE zoBOpk+@0QE69bl1GOc=HOQ7*H<^ZPeFY`(y217~I##5B*vN-q!>1(a(np=!dw`U(7<4~JVxF#2yls=o`8l1M>%v? zCH5k)VYdC^+E`+-6RCZSW6YN68AzP0z<{~}{$4_2I})&r4$hxMu%xac3p|(r8T=QF zID>9wA-F?FkAV3K9hQSI`07<%J^-1>bhnX+F>z+Belvi^Iz(+4Gxk@+McrV)gq&GA z6OyB|(2rDPG{K^T{Af(8b=@WtkFA9W8vREm&agycR=!Dx&<+$8noOBrXM$PNGa<+_ zWfB&@rHAxRZJ11-M5$TS9Fk*Ep->x`0@Kd~U2FA(zcRW;_H%9SR+}n4Bn6kTU+oZny`oNvr6HSa5zj1x2q#8Sv}}Rvbu=u zN>WE|uGQ5cNgfYwkAOIOU<-C(z)Q@yQzC|p6h|nW8#Ga@683+f(Enm z7l#pqVjYU?%deORr_(m*Zp@{HI~WAG2J2k5EfJbW2sJqny0*59x5S*d!Euxz-B?Q3 zbP@&URt8izu+AB9i?aj|^w{`nU4-ABj{QDidPb*osPoV5!C;UBBj_VYf0~=Ckp=zx zy;;EM0`bu3=z5g!jL0x%(0!@c01t#y@hGOdU!AHBiVgC49}GUkfWJ)C69C6Jj1t(^ zC!l+PQIP;NHIEH&GP#(zn@Fzq^wiWr1;(pn+sSPaMY-4`0zimGk8&dfy%khk)3J4k zq!@xz0N(lJDkJ&oY9bK_8Yfm0xJ<5cIP`34HhJYr{26Pfs*#{UpJ)5M%Ue5y^6@w^ zbDpdZjGj9;(K~?L>(!pq9cloq92Dhz~A}3 zW8VINlLMgBZAhk0YC9=?~7lDm%#&XdGZOe6p$u^XQYDNy+d_?6~aqnRmRI zL+$AvAIwn?BB=^pe10dAv2Im%Pu)LL`GI0;>gdNOlyimm-oMmO?D1A*)?8`nRLGmP z>72V(yEash5%jpj+v$gomJ98LZwFkM=dS6TM;xtv^3lvcj{W8j-g@unk&FIK%ZWLfQg%wXMz;wAp+(-K6uQYIh-)&gcmSy8Ft4+ZUJH+s9u{&Hd-+XSV^f zGcR`ceuymXJo(p?f8Y4_)uUG{D=S|m=5Ypj7ryZi6Z5Zjej46t$}1K!tg$*ip(qsV zYM{IyBWO9d3PNB-zc#g#BHmf8Xw*Zx8X^W83Qek!J*W;%h6pLuXl$UThh&ZVkh~F7 zYdun;0j3ZO-g@RKgyN^)FN1R)Ym89jHW7%8ptLN~Hz3T+!MJj}qNW52K~fL5N%4 zijpJFfQCT{wZIh?rM(1`W@5E$NU{^k66po&t!QP*Ghy%z3t+d^XxCY|n-GB;1h|jO zIW()ta-$W7-x3rDV*u^I5}1yViB(Z#G-5dncM*2P4u)V1r(pngK#s+>VWeO=igb`Z zV-}qO4HnuMj5muML~@Nrg66CA3f)y;F0Xh^NX+^c<7dQA@^%-Y&?chL85!LKyR5;w zY0B!pX+qO4QaHGzFarlBBVFY)z+y8@;Cna&60A&K24@|3ds6lih+9LI-PTr-=G&;!iPF$BZe zbQ}&~XC_JJ?C^#M#lTjMsPuR=gt6EbTg?&(t|#1K)kq^QtBW2Z=p~ZdvDD?+kcg6a z4!I<=%jN3m2wQVUTx>^j5fpO^Fc!hChAt?Yh!5v_gu9mBUkI6LE9!V zU@dmQzB~q47CobkFepq&N7DDAn8BA9%p+_(Qq_EKB!}A<;PMR+7E3v>*qJp_INds^ zX>nNizN)2j(l7ya4ijZFf;f1tEGm$y(tQkK^((?Rns^JGeiGR5ozn*{oEbVb z<`(q}EY#&yXkF?3{(h%_JiF3xYR>WQrP@>NfqJiE+`V?}!x@5*TNg5k0sCjZ@ODq? zDl_i%UwVJdT{>>KTgyvdLK#klDlJU69;CYo89M9SQ`a^&?>A(aiVOSDz8ulT9%B-p83gWTS*YYkFMsuT+2*?77{U1~3`qSopNAdWA z`xt8o+reT6EMjA9OrU5n#4(0C0Zq<}f+a*oy1B)1Qbw2-f+`##BM7Ci+_;3>NTxN- z#2k;295wRj%lAJ ze%C-)kxrv^g&^t+z)pyxVaGCaT!hnFWHe~HxItwn={P!VP~UnrMFmPUl8$%X_tgu?-2Sf4Zoik7RxM$ubQVT2nQjod8~wXF{rlYsy-fdlCM))xVk#iP2gSm0na zxL6Ei2nNG|aNvo-U@}R^8{ndE9Za!EHTt?3$8zCHbsY-JNo)+e!O3zhU3Zt^AJXVEgYAd(RC(+VdEh2}R($rflcRM%pv1T5NwiZeVh{H_H#z;aM*V$E6X zZ80XeDvR%xDIiBNq6@L2R91|(Z)I_ri3n*#5*FL`6x0^b3Ai(QE?>d{O;LiCZLfDyp_NsC;9NWucrp9>hlR#MPI zAOT2}iVoe=3#W_KNV7d3idtaq@t1Ipw9oGIlL(C~a@6PZ_-Bzu=tn-oK(x;f%0~23 zwAYW=-zYMJMO!foE#?-xN4_3k-_QV#BfcSD6ybzGLL(d45gBm!91k#t<-p{yXxosZ zZ74DTnWLCFBGI-7u(xQqir@{fIm_W>A|oAQT9Gi=jJyR=+^ce+aFn6JbKF!SixSBS z5Zb|JLOR-5p(dUq#J#5Gg9pz+%$wUV@jTcz$avwwwg`5QLix@ws2d@i7+}vAHavu1 za%de)pkAY}0wlU1mSbefdq z5m1*ek1S?K((7{~LHLxT!+g>;^~oENwnZfIa=vMF^y6Rudwd*e3=p)L@tZeSKf8vZ z>KSk}#;zYq@6=+R35phL-QIqfUqezQXdahqpvp|vr8$~V2{LU1_%n&E(!dA6swgo6(-!n^|| zYEkIWmRk9Jzu~9(XD^G-dr%H#e;c|m1+6BfH;dmn_Q7;Vjmq(DIX$QHe33_g_g6<# z7dc4vE7ykZ=`zL?-=cxGhek*llr zuPZoTRK@9HiXvLTHL6>S`f*EV#a!q7?atpd&EIHhn(t7MsG3gZ6t%Jui)~t3=BhbH z^qy`dn5v~_jy3AH3@o*LgjJ_}e%F<9dBKm$*}0H6Pj^BtY``OW%G>o`tRdI6oy+B# zIyyRk==kCG?br9eefjO(S1cM&f4936`tHS>3*uT6YB;(=r4V*LTZ7m_V@KpozdxN; zpq4Ba!+F#H|BEwI{CT{)y1pX>;r1ssV0AZgW`D8q!}PAeHfpgTFPoDK#MmO zkHZr~PPG(MjI?EpUde}Nfu2jhdNIG;NeUMslRaf+8Z5$&@I+&(Xqm34NQ3SovjONy zAT8sDqGeW-r|f`1XkfC96dM=tCp@j4;UHnf9HZqO-tN6@lV=42=# zFwr)X>+rp@CDfxWBDT(AlZErn?n)=-o4K`QbBm=FU0yP|Xo`z%;7nHDgU^L?u9T-9 zK8#7O!!~tLS+;~AhQq@kSW=nA8Sm49d4>39oNNL23=ju6lv>=nf}txNN1o#t9^isG z2cpFY>lGndV-_%~&PY2dDFh}9w?S_Wnw@McVkZj`LXOHcHj!9(2AugU~hQ(k2SehB?+iEyrv&gq%rN(Y znHdN>+KhyT5a|~nWDrv+j@Ci&Gv}Zg!_eG(6?hI6PsrJULs_P4xJr_d#8i@=C zNylmn<$KAXZk+?F5|M=@b3_#I0|HEg8v&boC?wW5f<`aqvDyFt5IeSB)_#eyg>xQue*zle_`b>rxf*V_B z5{Xldu~P^3od2oK-?v{h&+ly=apAXA@h1~+>61r(YW^Nkjo~f4XVF2yM4@g&2tI=~<>TOX;AEbrn8WXWZqOn`iKE0)lN6_~!Eq&5Z znu~RQKi|=G_69^ zzIZaV-IYTCqMFN+-|74g&dlW0655+r-u={CQQ+*z<^0i}1n*Z@7FXAI|2y?_Z?2qn z9p^V3aZ~w(=r{LYj9}gh^Drs>ia{i?2*C;Bc~^9pq|s~t5<8PZh1f_eG&YqGz<{AF zJx8=)dkJ!8FBsEWx|9J+N{mB7W^9~LEYy;9oUmetSA6zkJ*m?gxc=a2A=?o3>=ceu zVZb;sYbvc<-G)gchL3~bfKpGD;))S6}7BTw2L1qJ^ z;cJv1Vu=H&CPRqpj3TYc1-XZzzkzy8W7XGJ0~1{rsD|@Rx?Lzi%W?ez8CRIA$^_k9 zLJ}J+iW+u{uG$F85(5nlcGqQ`^6gp>1$MhsN|MtJ3S|b}-;7J7+vzgZL1!^Aov{Rw z(%=H714CB;M4Q0Df+E|TdFf^Dg4_l(t18pOWlq>!o709quV}Fix8h4Q*fhLU=~B^1 zqRAN*AY5Fgm{{0FLR9cl*)WcWE#yg;sW=BRI4VWuhmoAb5v<{1kgzl>J+NlP=pG6l z==mCS1~p{G$vu%+&9I_r`T{w*L#`15wjj%*rkcWXU?Uh3O3AfjGTKfarDm7MlrWM3 zQ_zL^x-$o}7?)J&VITtm(X2(=3wlt91N#}MdZ?}k6VLx+>iU10&Op!$D*yl>07*na zRPXRwX|JUVJFGOwmtIQ?rKK>;SrurZqh3;zDQ2V@?ow043v-YIjiH924xDu}139Q% z*ez=%(!vbOU2->ITMigE{Bq=Ca>VQhzbrBPWq-w9&-4D&9U>>CMZnMXc|Wh$^TjNr zR}j}D?W$ZFA(c7htXMp zD#GAEJSQs|gt+IZVG03kVqz%?M}wk$5`< zXjO?E;JFN@R4E;x$;`%za6ODgaYU7G%4R~D<}tbE^lP9iRdbToRdA&MoUFku97j9ZTskX932@uwQcd$lSKOQle%UL^c! z9cifj$S?14QNm#Ex7N#*?dfr`_}5H{L%l)RG0aE(G$onM3_`C*5C?S7Y+le>f4jR$ zh$*{LIUL&X8AyyM%AdW}`BMO}^13pLLkpVf`odOm=IGF;gKqc2um64_bpF&ApB?d5 z4=yZtLtX8Izwc5Q>h^xr6&e%pfz9(=D>F5cHX$z)vPf1{JOyP=?dTj5 zuyw+=q~a^Mp@q`8-H9x6j6o0_=?rNGsXz>Q*CzwGN`=i{y!i6e%U7=!KKak7XW^h>fQ=CISr?_OVus& z+m;`}N4Go%q~rrvp+7b$U#CIfxEMDg>j)H>>{rKKFYls<8cQJev`#QzHE}i>W zkN6F2dIgH-z-*C{1>}X*x0Nk~g2qL_<6d8BD|>)Ri0wXKk*{v9X|A=Y2HGrvU}&G^ z<8b*3azo|}>ygmrM&vw0mgQ3=NiY_H>iU4*jq=et6;gS)aSWnqMsPF zRroA-tw59qa-wSxongVi`7nG(b_@Cm@fbT&tQx_1VMel}0LgBd#o|{LBU#4mm3AYf zT0&(J_-wQby*1(va$lrF3;EqYCZLJ{X`|(rLUbKaTJ2Y0OaYdKc^VeSNQGkz+0Vw2 z`}-{w@>oa3eL>!l{YQX!=Snas0ePV|IF!IbWDk&*N zfu;OI7VGq?1W6AYcrj#IAjHtp@9RSahsxyu;Vp(9T3@WUn)=F^LumyR!v(BECbZlE zAq0lvVx(|DXGKFWhRdu$V$NilSsOSPqlwVqGKZPXhm?8@=LCXT>83bC0&!SSLu28K zbPseccu-7O?-9B?;7XwD$YT&9EXa$PN)MVDTr6Y=3L3+86owEBSsZHvm%>Z(zHPvd zEUaM!KMNE`{BoxtbWlPfmzL-RR!$&nWr4d$!mmKG!y0fMbE__=N9cf?>) zUzG-ZOykG61qFuCVI5;IRzxUn8)w(-8ipMy!bP#X7xqH}7KGLrg~J1|91o)%*tQf@ zhXXa4wnaShfJi1Iu3$3RL}4>Fzj`VfI~NlKj>ckf=l8d+Tvh;l98YpuEfGq5M=`;^rWVTAgnYO6O4Sc))qj%v0<_ur!B2-`-D=!>u z$I?vqdVtGQy>(*kNLzEL&UszaQxX9sj zwb#q|Vhuk88&%#_NVN^RQ8EwJw7ZL=;%cpe?@blb^fOc`I5~`F*N~f#%FV2^p(+F+ z+%k?rIJse1ALALKqr3UwJMWx0(b2$>Hlu>uH zas_7QKb-%IT!BAMr`2jUuT6zV3sIt=t3=3A-f)1o$&I{4FjD|{>&n4qC%&`xkfQSL zuBEgZHw(HZ(@I(|2eI7d=BBzzrmjxODGiRg4DnYu@Bsqwf8>9cfKwBbxp~B(X9|&7 zPVcE(Wu;)VCUmIx>S+Ac86dC{lEdvTF!Z0N5ugEN#jNo(V7SkOl3y|%Jz_I3fMx(k zAA%!UTc`tphDW%SO|b}>)R)XbU8O$_DOS-OtAOP}ra5#3>-0rv*dcF*sJd02x%&iu zTZQ!^dZUD#T0R41R;Xuy=D7%5*jHE5ItLdp_-{#F9k5y0Y%8|Fb!c!9#08^;BFonb zpRdpNRa2{gXYb+O#;?GMOQD0d*VWWD6$#0$Lmd*!34M(MrM^0Bej%ztH-o)*wgxsN zh_CP#4y0LuR>A67`>e4MgJ-*)XbeDZw8LtIlq^PL;X^fzvz8{@1m(2qVi>dEh3UvL zR)djqMU4^d4FGM6U@Qj9SQl4}+#RcAYaz7FLRO7;S(0S2U`8y6>o7X(oJv<3E1-k6 z%e@?0JO`Xej**c{hd}dPc{p4~Sna+oY}ru>T~_5tMJ4JNg!`hrVdQN{q8)fdrTTRg zg-8y^_aIw06=QV5RMLGP1AGn2gQO8%DzKP@g^(Bejc{fw+sAn{Dv-GJH9_NS_!95z zGlAb0n{;#_A#qZuGFlo8P(Q={3#$92wTF}#f-CNV*;unldyLMgHARc>3bT|d|>>_ly- zCuFk%neLDl23;@#t5OE;hq?S6ZX1G|36Ex+#xZi*;bY2HJdBbCY@4ZpZo`lnA8ccB z5{?3qAek@{K!mHefhXfM;P-p{O05+{XA&s!fPZ|NjXEtH!XWRq z05WP0u3f`GFTcwjauncJbx0`mt{`|iKRKc8kZ)YSnWc<6do~L-^!3|kbBM`Wz4<EBz$?Jgn&6!P#y)f;@X(7EQk5&GofN~(k<8i^`hR@zRK5jnp9oMhMehc$w zd5trULvWCd4Wz{D9;?gRZ#J{W3kj1}WvTGo8|0i))zT1GD{y|r z<;@+<0=9?Bw`yxU4lVC2FF%vlmqKh`yqK0FU+Q2$KJDPNvJ!Ruaa)dhA8I0~eEtp6 zYS$De!pQ@K*aL)C^=9-o;P&?aS?sk@4Vw#;RX)ov7Pkd}o0|jj7qy>Py6I5$;6sjY zc$wyNT0!Oih&unDrtdtCr?fPsTsR80A=GtHq*T6i`vC^jQk(G$m)ty(#au57TN&HP z!X+|dfEYFrZzMBUb*_HPZqwb3FUA;iS?1hbZi+j>EoL!}_>*pz82^uZJ)ZB68$v6e z)`C*|{5)T;=a-}BzEESdYl=R1bZKeHPSehN&u7D50QlkZjrOr!n(Mn*5(R8N?N@r| zlQcwEvCl?dMkkP6p}S%h><|E5uD)@$3Y%F5%5Qh*@P#I0G$;$Q^){@R*jB^ z&)Q>PCJMQtU&Gq7XX|`{kXI_~i-Oc0>K+IKYKGCCB&;liOK5fw7jWqspx5VH3r z>N%@Ur15~8K^uA-1p88TRpaDrpoF$tQUPUjC>Poo?iq>~h^Ax`P4csWDLdd!f;lqT z-fXrfHU8gJN>Nx0la)Ei*csO^mL&Tlq;F(W_-jMDCHojCD*NGJ-&4D zq7jv)#d77)wSPle`?|)u`rhp78r#^MpC9MzqZ%EFo?^Wo4 z8$kBaBYXe(=f6Mv;fE*Rf4{xG{o}oR_wL@^v$bWL!OpLIyFIwPv57xv z$hmjz*N0mb_oaaEn})tZ-7oHcasU1=2z=De)s7ngdvFh$Ut7XOTLkF^T_2?D_N^$_GBNm!ET`DlFhNh)9G3)}gd`m+pRClFN`suEj@ z{>l&J+K;?i8)0HM{Hh%c5kQHiDhfnv7Hv00xxyIi*1%DUfx{toz(rCjHG}g5yQ&K| zR!|MvM%k1#BE5>T8Z)Xp*;q0Q*%IS86N{y1h|B6O%*1jo4jNC- za4t7(M3b7`brlB=Xd6tfqwzkdt7GafReN9 zW8L7G$utV*=>v2fF@g3{uEcu5?%4D+WO+Jg-vCFU-T?H>u*^yJosvdLjo}O}B`C+xs3qd15qq+g@h3zPs}sv+I@fD=XIwl7DaLH)pV10f2XcVw&et#;|<% z^Of^2{`#VO>^%v;DrGE}YXIRAau>wN-Dg)D4tEZ^9A%uBnLzbW?%J-9EkXGZ2DXwP0BVfk$U{OJe#+9hPeWvuU;YtxYzU& z3{xeA&wE*w5<+7J{@MVz{>Y!D!IGgzmB0|#lX)E*+U*K)4Tgy7Xx;VNYx$k6tpteK z54-QpG5hPIlOJh!1rSDLpM7a0pC5W!HDqLY*Uq1Qdi3+7hYuhA@5zrp{Ah2V-qWUb zee3$xoipE^dHneC<-c8CxooFqD~e*Vf7<8PD$iZJaCz&&!TD#~yG|;U(l~YgbY|s^F0Ut-gf|O2yAD9hgUEBLajX! z*2eQ=0Pt=V7h`4Kop+4b5ctC*C7effx5KEM>pUV{7Ya)!#eP-^3og=%Bca<6WhZuK z%vh!HW*Qfq0$S5YX2pK8obA>5w#phJESY6oa&u(bmg)k`s~Isf%?=n(wg>WM>jD!j zgxN5TM%(V@ohC>4cD zc_xI?&$Zp&*vN;(Rz`b^)x}U_b*Z`(WkGC2piR}}yhb$^RpeH}$I(GJ^dw@cQjPK6 z8gRIy?L+~6R-travMpUe7+qrH%i1?b<8O`_tXzlPAsxf9)WI4!H{4<5cB&1j)}%JS zG1jMs#f9}4#lNv!Zi?k;PSp#BdozVtcg|q0dkX%^hBhaYZ482H7Xum`Q-?H6ZZk7x zxsLSKO);>Np@p`vVFI7gHV?pwjR(hEC4-Y;VHA#uD=THoC^lb0B@Eq#oQuNjCbMG? zSL$de$PY}GWjE%f?*DUj{Xc2vclZEhfE^JLK#v zFJ^7CbEYZ8iCT0vW7ScmJ?WO(ZmZ~e?0&fP+FRm9atrZHF3pQ^p2>Ho3U^Ll@v z$!G-xs-}|9^Lbvc=Zl5+(e(0wYlA+Ym~RrTc4ijz2qN59%qun*!=3ty9-6QO$6@4e z47U>Z4Ob5j_XXi!YQ!<$ckCy}PVwk^p)k58%G|jf8s2O<{M*gfbWFw}nRw6BXU~vm zupcB24H-3IaQ<;@d;ba1=5&9$sPqyPC@UR)qe<+O>0>&Xg)k^)h_oJ%hv1#2!ox3!u;E5qDB=i<;| zE%NbteR-KE@VZznucar`2f=V%HQ{fVqc|LNLc%tr@K-;p{FncC;dg7_aJZ2A+*j;H z3QL5TuRxOTTTMvcFb#3jpg|9bph2xi{F`ZP1YLyC@sA9#`5h1qySr&f4X>U6U?Fwp zAdZ6E85tb(c_C*bvX9j#u%Tg>RO zQyA_8Z3np?@cDdZv+uDv@5|>q^P5MTN2$Y>&7-3{Pe59rqfWIT1DVj~^o!kxPw4{T z@tu3{(F#da`sW?#wCH-QfSf zUSfiN*6TgJo2>*$Gs^E2@b`-^-f>|1nyZP#?9yUxavF+6@apWBe}DQqb}GNg4k`NC z8#&?nY$Gqo5$tt(e$2q}8))>^g4Pm@YUt28h<;#bm{p(NfclxpsBDl~ubeF?GTs&w zhN`&AL9RjzthPj@ivX{Y;;b4(dr|}g=MrEk!muJ3OX~&^a;1yN2N9%1+*-@kNjjA? z0wxUKFAHmlO6%lK8H`5Sl2I8_C`W*95Uh_4^)3#A3N*nC9k`)l+=JqZk(<}5P+P@|g=5!8%PvX6{ z`W0k96N=iq?2M^Igr^9Eo9S5;0vql1sQ-mA808FIV9bQcD_H!t8*7LpPjvx*rvS`d zQ+6P9{dJD$fZ__1=c#%lQCzz1x{iKe*nX#Kke3Co5s0p`UZ5`K%tVVJd{)-he2$lW z4zCfBV)Qg{FA||Cy$&f^gsrs|We{SO(ev;dDN)N%R@MX8Z*7mVqNjl&xe6c&z=F%ynW1ivP5u&d>PvG5IHkLwy2VH*N^UD704JR)+RT}+U{g{xdw*@(pKmvboT zt4yGguni>*h^6dB@UshvA7I)5VOXBda|3Xj3#CVh+Hkq)HK;xU?6!^jfzRkD#!eY& z90B)bFPm2eM2Rdm!AyrGRhE!u(Zd3js~MdIxCp&3dzTPp$7-q&SyMLV`8>ml@*KOFMLQ<@Us7td@})vc8~FYyhWEcIPGKfo z5NXH9o5Iy62120|1HJ)YKD3$d+{Dnh`}CRD^b30R>h0SfoG!qWj5K)$CCwG6Ez?_^9If;1`g&0!MbL}iCPVLP;ctRhwmXXtme&OM za?f-0+}#HU`B=5tivVaZmfRT4cR!>boz+#zY4CbD6951p07*naR0iNx0PpwTi>o39 zPAn}grY9%UsKLxcD}@UB)MJMyH3wS38zIMd`ACW=>Gb1Yd#kcGa&axeOSn+hzPc0y~Uw3fH5t5HJfYHX6BL z!N_46^*p2|s9u>OUTZ9~cU@Pa4+$3Fnz9uveCb6s9EF9Fq?&dkq9>=yl>8bXbVI$e zi+Hed3OOAW2-YARhC~`Y4FtzEmoT*^=3CB@S4gR(E0h`5))LlM^dMB4ZV`lqSPeEU zH8ikltF{8MSI}5Bpn3uIz+Azg>{0e02I~@r(+!C1D1T4Rr%qa4KhPb;V1!lBTH#Z} z*&I<~oVRJdVbiY=W3k(p+ZYgorQzTW6(X?k0VOn=fax6wb+dsuFVChmYQ0LKhC@j~ zXZacvjy9YOP3Qi41Dh~l|3!8XG%L_P4_QVG9L7OhVMy&~`w@~V(Hvu9R!b~m#7~&) zM|>p#@t7ONB$LJJCN#Dh=qb~L+ikU;w;%y)!+PF--fe2DGC_I;cQ4_t)mr5z;#-A| z2I9c5Dpdvi8+e+iaG=dUJ`NW!E-tAfA;7h}Z4>MT0`7vsj$^otJue~ZRgRs+GXaL- ztL#`}TxJC{dyjz3JiJDLRU7Y-KcPo^Ip{gSWSgL0^aG=l0Wb}|3kf!q&&U8ltuSJw ztJt3eP!14%?}c-?4V?M12O_LavzUzb0f0MMFT=-o@u;MbmX?}*(v1}F#P=|C4Kf;6 z7b3L~FC9d zz%Gxh|B87vgsvUw>^b_A?FT0J6BiQuJ&7L|g*lal!8JydL~?LTugW~fp_jH*fxN?;cX2zJ%}? z;_}Se-KVdJ0Q*|e`I`dD(6z^N^FLWh9|h=T9K*PRagR@wDx*b5Q1)arIX#_3vI~9I zad-FdV(f(ZrN`Tnf<^eO=WO?0md~$Px))t5!0r0~-PvIP-dO_DVv!(-?+yVlu6h>lJ|FHlG|fFf&)4huCBU$_R4U;t3I_aD6!vO@eJe_hp-|wvlb1*1z&?4(mFIueL z_75UGjGj3 zRQkyA`iHbL@Uy88220`Sl)q}K6jdNcP}(aQ%YEVMD$GZv5{@LltVq-$Nr?s7HI!8? z67C}x1|1B#76vjl{BeJE$T+Z6SH^<$xn2z^$QudIw472-&AwVLG9l4dc8?;-7Ox;;>o^h3w?nv$@<{ zwwOy6?qsKP$+Pfa>KB06EF9SWJ<^?=8)4O}%t^yOqsPUhZj5!2J{vP0kQsMogziA7 zG4o?D=4!-?fu2zY2h7(HTRc}(cNQe}=rVe01MC4!lSkAbJOjT5Vi8J98(kRUU0ux* z#lUk);uvy;4xaIM1oX|}mFn&;+({Pg*DK6=QPFlS(S7Cg&-)EU&|D2pIP4spsQY%} zocZo%ICIoxX1O(|P{!>$%g+2-9+eBWT=q(V3{~yNQp|@;ny8`%@N2Z6YTo7(%>A01 zzi1}JXta!x2>=#7K6n1^y@P|@ufM+W`u#6I`|$J6KmKU{@Q{HuA<~i;I`G_AdQ?k!GZ=Ypa zB&RtElw?q(cJDdz3W_P&K( z_s@3;@cSabN;A9cVAsQ6`&zVbEHA(R$}3y&ajx7}*#U1F06+ZrK?B|^qus+w!Mw4* zI={NSxctWLrKJi0fBKgP9N444;=mi%mJEOwFYN7j0Q_iX7vomj7tN$WQ=!=QR3jYN zu1s$HCS)IsCBJc5IY~+-zf8R`@mkRs7G#v zCFvWSHNYhuy1lc-Ie>|UP6M)(FM!3JJ)O*-4W_9jgzB=?rH+BsE_3Bb4?H&lirXt0 zE=SZxScCNWW=%~?AB){|3JTn(YKD|C-=61d7NEW@TJ*Y3T8 zB(zJm;CpIE3acl{AAFF%;fvcJA8mwjk|&J{-|{7l04K=eVAUH|AhbV0Oou`9IB6Uq zVkwbDC*H$x!61(CjZl~^FrBH|m4!fFL*@NMbttFs+?>I!%8`sL$BT*ST+v7}6n9+Z z4E8X-Zx}n7#qir&*q@v(7N+F@HVRAt<)pzeHsG_!ptIBw7P|{`g%^v3Bt^S4_!SDp zWESNUxf)2Km626AJKH@cC9>2}vom;Y2WAFlXGdm|3WUbatNsKkkO<)54&WUCg=Iye z7^&N-uLj)cdWZr-WoMz+5|?%(=aCsjOsX+h99xkav&n*yVpLzod6mSGg|*WhoE)(K zND7dIyaj$`^wNd7ftQaB;~8mae)7rTVP?m8WpU(={sOrX+;pPLz=m=2gcm?m_aO7h z?S@^@6V|0nB?wtrj1z#d2y)rI9+a0}%Mf`~tXIQlJDQjvgL<&s&^1gT)mXH1S{wJTj^Z5%OeSByCaQ&t*d3#etnJpu@yt?}Iyo<*| z>NUT5a{Ei^mAl;A^^ZMv{)vyj+1}VVxeB%zp*Dor*;A>~*2d=F-+$wcix)23UcGP; zME>W6YnyhrIlu8oDX8%{K^B^vc3j0m3CkkN;&8*WHJh+)aA|K zJH?`uSE2Fgcx$ej@MrtGoX8P76Hny!jUF?{QS@qvT83O}0-5wALd2Q3Git&+S}83Co0=lEI!^J#$ow!fk*vB^Q$m=5_u1oWxtRk@2 z=HaQV->>PM-2=d1UcGuRV^>lgjg6<9X*FtFS-G+962zCVeeY~J9Te1`}!jR_TEH<|HSI(V3$W+P<(TE9v-LGJ`y$W_$u=fEG_TB;j_BOw-ExzX6 zbmp?&@U7dc_EXsJZ|-37{pLUSPCZe#ON)cLm>Q*m-g$1rUVib_`3eL6w8DQq4*ag; zz!&zeJ-4yAhzf9iXX8x+;K#?hTo00zY@}SDZhmRFjp~RKH?HJpYAr>XAO=a*_d|N4 zNNA?=d~PzJ&Ii3!Z&lSTp8=(h9>N%rSw00I=>V}*IABlXG$p}O$r>+?k?(8>e2Z6- z6-;`iYJOw4a3f7IWeymrG8!E~T+8>S){Wiz0tm0fa((m?BC|GzYy4Mn&y#T z8y)U+kyjXy3{ThdG%~cW6Np72VUN+@bur!inKSA|GE%DmO8Sy|iGE(ED#=jUI4<0| zC%_|~=Uhm=Y3EZy@=OS2uQXPD&WYq~!hPwUo4|2Ti|j^y3wVDGl(F=tdJJy+6otiO ziW|}kO6Y(EJBV$G)EJ#kKaWNl#;jgoayLY7)tHnLJ{!4R5D!)oWea2LHJrZkCPmip z0fWx)+6rQ}zAWgv>=4p~7sN(oZ6U(!CmJxplHTM82fO*FJmu~*2j z{Bc8P`=EI*Y>(__2P9-wBg3K-i9SNVVQu1ib$pz@)bZ-cunb5_u4g4oay=TA$xyXF zk-N^YE~h;jvMf709S=>CEMzciNIh8$70_Q5vvwDXEBvaMqhSFfQW7Fe2XNM4wpc9Y z&K3)Iy7vuJ2as2xfX-zL^!Bw~^DXa~swIe|vpa(Gq&%(#URBnuq} zh;beok{FAr^UI3f7;*{FLSRL4j0l7oQ-jCKpB$l(u!yfInVcCKxI+%5>JDcWwI!MK zEVW6bV9v}A&FM0Mg)eSj3KIuhLUd8>z|df7n?{QEOU?vM=JGCZNjAUAj{dd*89 z!#YMg4IYEeU4vx-zF>c}zss%$hF`KbZ(ETOs(*L4e2}>}Huk9TS7(K~d;a{Rg9p1` zef7Kh_dirl$p4u-x1ToeJB-IRb`4IgyilXeB(AZ8IRq1?K?n{hUg$+`0!$2vO+te? z6C#ZS$tplCP1Yo$Y7XRpQ<78~Nw>D)B3Em=c88FtO`1qmFP4a_Mx8Y6W`D)LpXc|I z#(<5@TkJ;2&-;A8&%x2;uRi{hk+{#51$}MT;lt&Rzqenf>2W8Fb**<{?%V&|lv~+d zUjI>aJv;k~xU-RGqNG=hry2UYBm>-rGKCX@;L4^7Ri~!->w}?n7?ir*>#d>UyWl;0Cbiz!paL{2EXB~ z$~Y6*sV}?R-IUo6gGLN}uvZDt4GxTZ8+s28xoRYANCvYPF7 zrpotDx>@k4tABaXNW0M{ z1o-5lHo&JG{k7*q!mK4QsE@(yuPa8)Z=AAkZ;Hcz^>k?A;p$mcB9dK&=Xv-441iI? zU$$cxo$~o#8!w#~f0F(0iF=pNU%mzapE3qKd&U^>H`f=|9H= zBCLul6WWVPiWR5FAuc&pyby5VNE9^CChQ^PiI+Sqr9nep17Z@f$Tnnp4H!#VrOrZi zAqC>Oic*PKER;CTV8z38(71*5Wt&mR~ze?a;qkek!2*|0f}8>wJS z7bOd#ZR|r-Z2VYOUBpp+)9OMZ3fhj`qgukgJwlBA3b`+KK!eJfg{`;IWoXU^Py$~WB{6Yr0vb> zL)Spf0J$E%Y*%N0qe?zyQR2)|v7xJ1V*D&BXx|NQkYPbED_>#r)^1oaU}jK^^tRLC za(DLuZna6~;LhKT;(MYRo#$V#U$5V}ZTP@yH#VEi_g{51d2ViQZLNKE{n@i;KYaJy zXXF8Y@y(;hj~{&`<&=?MZq|RYwlMmwlwL-cjW;9q+P_~&ykDE;@{dF8Ss#1s@m)_0 zz=ubF3kJJ^Ij0Nu;_m$Zm3Ny4({;`4|5Q_37}QHSmeWdpC`{U%qxQeDCk0cgVE(E(yKrP z(`a;ACCCpzssPETr=BBE6?7pFIhQ>aRLB+WNYwd839jL7YIEl0l;zh zpyDgx*ldvtTzj%0(Q)`eAzo@>ARQO}qR4VKBvIjDAXhQ&Nq#l%jjIy4!nkltq0MV4 zc)5;TOTM6}Ec$?113SA?8<5*p(VbWD&LG!6hq{H1$F42f& zJQp`_wQ=A~5`If%!`m^s8e~_hHl(dag~eSZJhPqc(xI7{FgXnkrl%njn=zD4*2ycJ zv^(iovJN(!o{6PYmPF+sIaqd(UD0;LK)S9g9otepgY%c^^o&4QorT3R%ID+;LWB0=(MKiMw zBgjIgrP`we(yOW(mq@8aSiPo)J@qP#F*DX5K53w#C7-T0h@ zn!`{|LHnp`A4Yw_G#;R{+qRL^|JrNoMm2WUcOKZex=I37@6hJ8wO%s3Aj_M7+Q6C{ z+~gd=81UMg3s1g%q}*UXQFB+hyi0i@hQ^1>XuX)ox&?E2qweA9=y0dgU-9DH6&U>G z&tHGH*x#*=BfkaM4F$RzG@^eY>(fuk0+8>FC7KLtvk9g)jT0K{po?Z6Jw`BA6SgD5 z&a3Qu%t&E7ogAsGAqj5k?+sfIwm%<1GmYj$=A-r@*UBJa^pJ`Pl|l8{%P$>H|Irw5 zv&+H4>ocIvq2_)4cL^#ZEYu)zmgrBXXmWBU;BxWaYG0xVvx|7`xO*au;9O&1q=!cYGB&O09(13u$KSoep| zVml^aQ;kSRACzZTpy)U3*jYuNOF71x`V2X$I=Rrlf}Mt3v)>8;!+`(0@M?P};|0x* z>i3EMN(4@VBicA3&c)J22*8qq~_xTPi30mXYCc0fyv-dGa;5=M$xnmwq;uK zDFf_Oo`~nn*NmhMb(id@B#YuyECRVrDwonQ*0?b%;H3OWOG*1lj0rN^;z+f$S{g@J z=dlT=T-#tQInR7q2_0@+Tpc4X+Tc5avI@5m$|?IjG$v{K98>RLlF72OFhwN1s-rGg zmZL~DsTy5>77oX#LNbmUt4?oWRz1Uf+CEe1F638TNV2->XeP8fn@S}jTgU=0MYXn| zevq>@W+C?10tXI+ypY-~gM@FubCFn)eHDG+i=L~%-*6(NDKl$dH>0jn9F`&RNKF+! zq!H>G?2JEb?=fK_CtMspk)@ ziO9l8_~lX*8$&S>*a8F*v0qp;q871=`~Y+jFdbQ&&2CH9P_vHJ#57CW_>*=&Ed4+B zdOY8s!yO*neeOK`Lhku_zFyBSHNn1MFi}kUvprZ$c^k3yp%78_giaE_QE7z1-o>H` z)ex#s&~Q1ikw|o$KR;A+UPTO^=cq=`;A_xgIu|-PrWh^T;@MoO09VLH~498DAd$Wb-_4kLh0Gb)CSj#Ba~PjIr?Gaoq@l87%Z zqfzBzwbH(noNc<%bZ;xhNc1ZHh=Us-ngH8Hm@N3tmCIPWsK;#h~95hh&aQXtr46C8Z zBc~0R4Uq?pH=jNYBwqlMz2eq3%5K_mmKq-Kqw%*>60F7+r-sUE0Nn{W25z%n9kB<% zz;%`(FYukUhqL5u!KJfOZ1Fpt2${!o>Z-GyhWvP-+B}kOfLupIog~ZjH9=ZiWKG`w z@y7=*zWx6DKU^gz#EGsE`Xce#+*E$o&k2)$S5W-!2?6j~&JB=ai2!r8PiG&$`HQQg zBRPK&)90-A;BM^f?SHF0cXf$pwJzxxmgE2cAOJ~3K~#CHyl2`o6Da)?HMc_Ka)gRI zDie6-iost{IVvj>ox#y4YC=XrH)uo3abQPrUwMuUbPa%e#ETsf#t~d)0DL0<1C-Aq zzVy{91B)hw2Y+3c*+Ke~16x-r`GeccMa@@u(Aeg+#|A0XUapzL3OmXaI! zgRpqgg)~r<=ZhFQjs#dF!*h){Gh8Ms(ZXm-yqn z?tzH<7wio^VBZ|yQ8m$)0T+)&nzWB_tVo~%b8zICVkm3TMK?f=?MWZk)}P^4b!~uh z2Bgjgz16f3rUJ%*8v@FWuB}!m7CJ0wFSa9lf}v@=`s?~*_39hEQ(sSIVO&i}h_mP- zEQ=dHr)pEFsgx2d!*}8hMsSV7rmBrI$4k|Gqyi*+au{JWwMk(^T^bnTta0l>>ijr? zlX2wF_Sl^=JV&MRFmkN?@Fk+4@6bhPfE>OwM#u)*X@k=-U5q}#`~!Y5xi@mEmZU_sQE=Nw1fc|=j>xiqXi zR=t>igMJa?LfMi0d4|1}R4xP+JPA5W{v7NtEL8dcUPxqFL}LX7zT`mL+ffwTMjuTL zY|Hu$TyNcyaU(Asq`t4;cM4oG!Pl5Od!T;jtOH?LAzY4X7wL6t0efMX2f(O zWm;VbN2{|RsRv2zziuVW?pFe4SS(zbvS8Pql+pA#sR=Y?hplOf3Jqw7GdOzzYjUAu zF5YT1-KcOsO}cdPG1%4Q-E$Z3>!5Dh$Dpuy zgwKP*Z9p4r2Az#H!<7N%LGXA)RM}wpkaV{D)%B|PCg+T72bSMqtK5i1=&a;S*5XS{I$tSpNwYnz6?AKC{`nlu3Z zc6N4ayFz6QlnF}4^vTnAolZ*(_-1Ys`~Ud6vjs+!JianBb7gMvI?0d*VG~atRqWVk z&z)m3zJAjv>rFPY%dfB(%@s6VBVw;iLl=-XH#eSJTbo~TL1v2xu@~1D3_RC7-PGjz z!~g#9Wa9Xv=Lg-+mK-qqmw37`x%uAx%QLI%o{Am{yttsuE;>Xumsi(T*Or&(?X_=0 ztI32$1^sgNjjG=E+uGCYzn#mXJm~b{`ybpW&hs&0cHtUoVSvmSL?W;vR71fEepkEz zRwBz%u%taHs1n$S7jfku7>L}96lgo_8V&6=iQ|ZX+H4E$Rqh#38w4|%j)2h!cMN|6 zisrD#&m1${c6MQ(FEBtVho;UxL)tTbnC<}g1A${78}IcIR0;1@0b#AOupq^RZbS%w zt|e*%0vu2Suo2&{Yg6^dYJtx)=&$a;i>uEl@5;b9m9pPLGFGi2t>JRqSZ{qbq&J0k z*p(kOG^C94PBkEOPL{+=v z>kFpf^1Vmzj*T6KCGUMLg6WJ5jv_SdcK&7mQQfEk`~`03OZ%@s@7@5WU_;!f5-5Xt zk-~y|g?=SJ2ZIs0e}hrG7BFq5aJu#Nvh$T8?0#2)dA)S_~mxe;N#&j{nVwt4ccAE{4 zhnq=WZl#JB{WE!xnT&DQOigUqurn#I5UX2PFX&Y?7$MHMWDbPU8J9}gs;@D{XT{V4 z+&WD5RYq|e>KitEPD<6Ks1Mfxd@*@3=9LkOc-xZk&CA8xE4a-7-Y^kiqil z)93c9l3nji2h~Tnuic5T->Iu>JWJVuNM=?U(^73|W8AAvvTVjoqa9t&mbkUC09*wL zjp}9siXCQaV%_Ti8u+ZM+t=7`r2K9Brge`R>neJCAGK6%R~>n>Wfup@yCx=j9&JB= z`QXK8-zrY?*|TRa`7?1YkR|u4rLk9I=+559Z=SrGK3(EGz$I1LoZr{Eqy@e^aO~w& z+Vyi9tL=w45vsfurNKIchOm#Q8BKxg0LkW1-^w69;F{uKLd#+UXaTUW*J+LN!}q2qp?WK?@b^1!X=`vf zw>f}rhOtL>AgMy1JvTwK3Cy?N7{KHqn7%7XLUUeK!RfVZBsJhvYTZDZSYUNE_E<;%-6Gi&RUIRL)tUEMU=lV#DEK{VFp zrnc8gf|h_S$-uDy48W@%+y4A=m8yQQbT+ya5 z%Ka4wAAC@$T`yLWB7&_7{TPKPFCr?C%^r|EpvLukE?&cbk3DdAp0QdOs+%%0S~eam z&;-0G{O$HhBW-xu9U;|{zCsEg40H+WC@T6VE@5BMK+!Q4z4jLVKd#QMr_K8e<27K< zU=0D5EkuF~Hnj~Hi>T(sj!9f`!byQDL&`~1Q(9SWB9&wni82=`UEgR336Rh(QWL5O z=(?_oqA2OQPTjPn?HAbLb};RG?EYQ<$7wp!xc1}6n9!8#x$gUV0dMWz?t+X)5Mkef z!L|@rHw9mkNArcCI)0l9t;Vm3#3FdIiQ1&X0O^xSLZiv$knY(&R1j>Ow`sumFBu+L z1X;Pi6H}QqKvrIKmZZvDwh$-kDk;#-Ww*0gA}5n%& zDLc>NH@+Q%^2TeSS~if2X~+yEj*-xj3z0908#re0-KEZ7;y1{CR@_DxMGJO(38)5s zV{wMhfsP@;F4evi6$aqb=w*l*%_W91B+C)HD@9O-42JD)Pmeuu zgScoE&z!}m`NkOSgT{k<5Kb$lvZp5$s%bM!2sB|GhRM$`Y?hSW)mJtmpx5@IL91Z9 zsKNkDw5k0vhTEXH$)GQ&uqy*k15yk~h@^eYo^_Pfubu4=?h1j?WcekE4wHcEF8m4H zWAzInhg-smB9KEVoO0G+#GnYH`EixlGz70iDkCLbsj;23M82$Z_{V!ll00;BijQSXgnM?}O zNiY@%X(2+7CD$&GGoY}sSaK@Geo;+jl=AG=FVuIybPgVu!paEoqHdfTOI(=GLKk6l zu{aLNC90B84$?KyMvp5IllLzwcndsMHzL;phQMbRQ%b`ePou+9ct}ahYMw7HeKYzq z1g?Yc^yp7y*!%6BGVSqW-Kjn~;$9}M%1gKSN(SuHcaHhea!Y=C^O zzq@~iAl@0L=Yc~oLVo$>qbCM?j}DFuzM{V1DF>%#w0+ek*sYeuhJnTrhuCPk^4B2C zuBr)-lP1-28=o1;>%Jq!?2-qKj2j^zoajB#`_I9t&yRjI^0~e0@$ku$$DSoEg!YMN zk97+9_3mdhgm#IeX5A}QV85I8x3anA zQG%?=3KyC7H#btkj#RNjWf*We(ijel`||$)Q|ZW+uZO+muUqwcF&uDS2gavd6T>N? zu%7MwGXVVQIfAc7GxDhk_B6~ zQ&22Z``c~@eY@?u&|MNL`KgT(tKF%x7L50DSzyrWliaGcwa{7!x^hB8-B#5A6OlEa zWE4%jvlR9KubkSkD##6Pht$yf8x-kdy1 zL)*zXBIhBx3Ws6^jKOhxUN+#kVmk2m4jEIf#kvfjZ(z7 zghIL&2#qQJs*MzAXfEiy)FZkpTX09{?u{daVA(TmN7QH-a$Goo?H93?GYbdqc3}Gj zuRE5;+B%q1k8%3g7(QS*zI{M&!>s+cYNb*O^hM}yJhwrS&<4o5rwXK21!5@+t7TT% zSkyEu_*;BxMru(B5_Q0IF!79I+0Qu$KfNY z2vdjZWhjxrfex#zDkM^}#t$>m6czSGFNzXzbnyc145|W#9g`}>0(VlCfQD|F@l=!? zj&Toq-Rv0ZdqpuIvT0rt z_Ln1#iNuvZ30E024|^+Kulje`WkA0uXci?NMiYJV#o<5x@)xhSeL5}h^&*NL(se68 z+($?VRAqo9*%|!Jtu7$*qV@Sa3O5t@fxX z==1IF2KgB~8>GI-hflasV`%NBZK(`VJMO4nxRA{asDgp+V0s4Ua|2AG=ZA=S&ccDU z`W;f})jY{rEPw|nW1w>(tD+z z(BeRw@m|8V>?J*8V{J#C(Yk{9M#FAn>#W)(vGq3T3JpP?uff0I$_ecP4s%kA(b}L0 zuwRZ|f3RUUZ1~#J()gE#mb&&C45pzlERj~2$+Z8pAA%bZz&88C2|x8mVXpg|{c8UW zSM+0wYBstV{C>mW3S<|j1__jSHa7j~=G11yNH9{Cl7P55y{X%By3`B>zK{ZnQ|U4y z=x8ZjG$LFoCLR@y-X79DSWF+H!@_YS`Wr1O5=(4TwMdhtjH~38^oq^vBJF|rVjCNU%Cr3%AQo$k!xL;RBT8IzN_{I8HMd@PG_R&+=J2U*M9=v`sf+VbhNix z^~TPcLQlIJZ)L21SDyyxY461jdp!iNx|h1&ZhBoEJ+A|HTXhR$Pl`QVb+~NQ`22Yh zWrxa)t@|at?nkvNiY%hcI{D}cxa-kDgJl|pr`$AJz9y-)fM4xyWrmv5(%9QEPstP| zk(U%-uxLAoe@bp&5nMQQUNAo>GClW7-ox~~(AQq{;HBr^K0Dgkc}AmW=KyAK-kJC6 z3FllQblz(N&daZKubhgMi7ZDvSZO{TE|=5gP55qD68~_RfDV?wc8OYK>Qg4W(m>m2 z@|AB~zwUEh12E~6V!SS!68t^I`d0|7g2GdsfB4{6uXns%)mE}kN-VyKufE!SVx|wI zyS$@0?m8prpRy72Cy%3|L?ja2(r96=x)rFt5=h`XUsmi-tO-GjckFs07I-s8XEkLAox{ z49N`%1*yjmDMA!Gz-c@@M?f=;MobM%FXMwQ|To71(?sLxbgHxru zU*EgF_GJ0dlC`!V0Id3}}|VlH=YQ!70hha7(s6|0N}HGCjek=?uE48e7vymU`b92>=nzdRd6d?&un4BmQ@oL zY_}@UtX7T1b>-tqrMgn9wdk1G`0}f7e*NmxU7^#x44(B_O1?BnpK|n(&5u@vp^Re` z(V9UQTfA}Tu)K)6%P<$+_qr8qRZ`^|cdJktOs26RG*k{VZic?f7YS7^yTc)me3iQ# zdMxC%tt-4r7DrNBktP{U!+J@=B9fBq4Z=9URy10egmE2F z1}xYd&n5FgHowVyUf6983{7YoQZn%YI%oxCIY^wgU(86R0(fz;z;ZW|@ZDnejDsm2 zTvQyU7bzHA{D9_$xQ12vBA+D$DG9xbYbBCg=6&i;()I=)TU>U&=$>&L@z6Zdtiec} z0IcAAXB@U0i5$eBL@4D!U+16`4ow3CKSh`?rr@620@4RiJD1zMG*)U5hdP2W2XngR zb;(nSG;!Sn2Lg;v*5#y5GdBV%eI{^Rdw`itM{)hK{RM#`zS;pi5pbJA23W3F$ITF2 zIqwey0N)98R$l+Az;g*i_DAKFi;}jK*0+^}6qf|1OR0_-3X{^_i4HP2ivB5oDqSpo zjsRBItBNYPxyynzJj}g%AXep(gVYokl@7G;WR-V1C$^s=t72z*V3`# zB^1xaOU3NK@YLL}33z1pI(O|%wm4kWp1;@}Fvlu3#@_d&DP}-Hl|@%|(%JQzJP!3C zVKkaG9$&6wvu9>w;5cjIm=lb3W>zgskZihwFCm+rW4N3(%IVl^knpVhQi{CllTsyE zR`{~e@|ebB$tPzhMbbXPx#X{I-rT&oPk?oV3|?MT7HgEz&Yt%>x~zS)op$imSsYLA zZ;r=a!t~h7nYB5*Gu$4Vb_Urx#AbgCc^2Sx)Ln|mW|6GRY3?}!DboF)}?S1#%qbIs_o2(vXCAYd9Ht4K{PAakym|z0>WJD?jc!WcZvNxm^@YaL(lbk)I{y>>w6B9+ zUbeP{Y&HdnTV!mnHD3JZm+wE_+a)yeh6&^7>mK>{E#a&{rhw}8HT#LBmLW#R>LhMF z*x0~ByKr1x)*!l|7+X{)h~o#l{{nrDC%5nWj~PJ=S6;Cl_pPd-(8M)hwQ|TUd#Bm3 zZF#rks@b~Vu(#p5w5_dXy;^HFYgW^)av~wv+1e%x`Zujl|Nh3Sd%O7P z;M~lN`)+2WVQX=?kugS3#fS>Li zC4@sTSZDjBOH;ATv+~B~Cq=jLlXV(e+2RUj!iS03Fj+-3`?`gsnv6-oS>ZNr0au~6 zSc2Uyw#L|gU1iOW_6U(?L@dCmQNc=RsZe6ZOiU7@=TMu6Atsf;t^gdEvOzLFLLSu4 zVX`{}>^= zLXi*1KW|+Sm|Si-BMW=voXzdRD(+Sj8@mdcDFuny>bi-9Zue4;B&4?;X|r2+FQJr7 zo{8uHT?wU(x;xNE<4OvcP^_qmudo99J9IM~_410-5lu~ay`|`cJkFRoT8jEtJN)Sh z{}dru%b{y;I6F3kuSQx2?tqZ!u2Org`m z>Fgyz zQg^6+B!zJp@HK(tIZdvXYkCwfsc%WJSAXqTY$o%)U;O0lo_t{SRt8x8WGlh%d!zlpL-}Lg@UVcGC1Wo^+<3>7sY+sM1Uvc*Ap+Eod!0Usb zc8_#p+ctYv`Rg3H0oZK{>|7@M+G-rXa%JoP0Qiv-SYf~)va+qVHZD^?pepFYyS*$r zd;7Z8NPGH=7Yhq(wdG2swy{852gzdBnH#GDN;O_a45gP3ue`EVS=L&E%W6Y<5&-*#)wK0!Sy<;5;^VDWOQ2NVw`*3*-jW+zR=qCZ+5%v|Y&M0j+E$%=E#k|X za?ifs5;}Xo#wvH&;jF^F5n;Xf=id9r4)yX}(Fybs`ExJ}c(Alm{dn27SE|*OXDiFr zg9k!+tM$s#)=z)Fv$C=x=)CsMJ5Q>brwIe54;TsA-ma!#k%1+D4)V5D*u}*E?k6er z>$GHT-4h_-xAjDeWdPrlhwE8!!K46aqLd(TP z;By`%MsX#_$xN~g?#F%9uiZ%W{(3SVFx6~_HHae-#ITI2c zPv+x=t)B=Nn@dIeB+&+2h|_k z198Ta1PjKfL@-CEntG3z~%OJ%|8|yp%9uEcFD!m)Wm_$P`wZH9Z zZDRr*P#>_yPinqKdz&C`RNY8{$8ME6dznYOkv|8_oZ73pXu1f664OWsA7&Cw2ZKMV z3o=Yc-W1Jjs>WI^F^EnH&5ioiPwAaXlb)OI5ORyY6j8K5FI9vc!@34eu?E(Vtbu`R zQ&~tcJhzxa-W*E{Vh^th>79uY13g@fLWHxwJ2QjT_rFwK|5MZV9WDgYMDC&ilVjn_ zNr;e;1icfHgn&`!j_cNdWw>0uD!H)b5LBQ$!@S@J<7&4YAJl*{k<+;wOD1pp*Yzp}nQPufJ zBXYNswSdmx`G9==;}nPG(g|ej zBq$p&Y0P>J&AH^>ioFr0l_Fi@zn!CRjMtsp=aF!a8iQoR&1DdATu*lL-N88Nv3ekr z-YBxPj2%2`~3b=PeVvSZ%CzV^nIYD z>mjw6%*ZaatIYmIPL;`upPfH?KhV&(-JQ(x-@V&$*$S73LaJqI+Z8PUjE)6#Xv%Z? zx;%?(tWg2kW?{To2bO2L*P3z+*T@I71UnpY)B(d8ZEc_Hrmpzt!RW z%7=wh-W@cKhn^q#`PsTp8|au~1#lD5!Xrctyf2+wn^9VCdbMPNrh}QnvA~Ybk*%Dv zS%o@D60Th8Imsxdlvo-;h0leJ)70? zi#bM7{!{L-w%)^jLlg}6+`PS*Tb$qe(~NN0JaAQUT73;|k!yK=vYcPfYa46&JfXR; zrq9Bxyu6YB1_N77-_U25zs>8=l=1V;FAD+_fPc3B`X66Ue>e2lqkaY~?KbeOND&Dn zg;T%EXVJ@%EuKDIm`6d!)#B+>h56ZRc1Dgq(m;wg^M#F~0l?EQ11*l^n23#v z;R-nwKIZ{Ia2V+vVd&5;!h|aXY5~D*aA(=WQZewl?@mcNu zwzS_)gdsp9W5Wjfb9*@45lkf762Uf@pgROx6N0b{uwc0pZS4yf3k$Ng@r$r!f$6$i zGUy`Yo)RX-P@RJr=0ay6O1nBTRUp0#8G&Dy0Q-U)eF|&?cB#U`jDRcjWekF0t^%YY zDY^rIT%E}vZql4lrH07ZXmn*>z28Wo4<_nfG7gx5jC~_u!&Wc7Swf13qtQs@I%m97P@-ES zP66pu#2XDnSjf=IAS{GHN3aPzfubZqur9PAVeJUYZueM3^&lO)fW=&t|01m_zzHo= zo56Y!>TG0j0BY4r@En6CxswEHj1wo+k}yCWqu%bWk{^r56BDZShym0f+7URglOm-e7y%G#ywr;`aGF-X@j{#nXltw=Hq)_~*~P1by9@-XoRLOuu}k2CGs z$1$i1Z-T?CslNA2eJ|}+{`x-1){v_a5ONUKE@Lx!sJ50fq2u^m~v4l2<5~QZE@ue8jT)4Oj9w|5Q3aeuYdpFYuCQpdk_{m5NSHG zJa=EGX~N24JC-9_rZz4L-WK77;+Pf_+O>7gX?3|jy->_u+I?s3@BjJrwZX^AASQ4) z($jPIZ;LQtLG~746|@z&&FcVTxnW~jmjhUnHCUrIdF#fDZ?w%#p}Cu|FKaWi;IaDV z{EW8xVupp!%V>FCPhYyU_&e+Y4?gzesnEn01*qQgRzv`JYpWn&D^R<2_3G-W9D=rH zvRj446~uiA80)JAq*=en%jJ&zd}P2cLmwcO4FTpTbVAcIxiF^Wckg-WbRIBS1Tf1i zuPjU0DuKxr1}m6Y?TkDsN4$cGt%Z=P4O)!QXIoi?yaF%TmXbE+R+eEwv>f5iCL7uv z;GbsCk%{ZYb_{b7nMDV+o$U+2+_C|^oQQ8fUbYo-C zj6@Dshq*BrYzv~G0j&y*>j=6tZVJs+sAX^oZ+2x+P>AY6D9(*!vMd{fCHfW&SKzCM z%xcEVxJkj)MnO)7VY$q8jlyJa!6z-4Dc@GN2d-;3aJQ~b;p?8Nix&Z=Rpvd_80~@{ zqZmnW+J$OD6b(a>MhOFxp|PHH3pcY8xcaRmtN}G7V_y@X7dN2V18YVmZXlr;$$}|I(&8{#9e`r!)io9eN5i1Im7u~7jJFtmWyPS^ zA!o*|acIuyBt$T74dOZC*5BLZ?~NqjccY(siB%+w^p zos9b!eM6Itd9rbOCr8LYVj<-CZA_52t=2JRwH_ZG?;oY5ODOUrA0!3qhH)}vBNGZ? zgmlmdN3L(;1?H}UzdYziwnvDbYZY_d2Lh}xH}v_32ky_^s4c}$4l$52M9LfbK_;}( zh!j$NQlY2As-+9rs+jj$5t>SWVRH&k;^yJXIM5ij2mFhm4-whtkb>sEG!$pJt&B`8 z75NOq^Pu_yjnK7RP7(;NeR}*iXU$i9-0$h}p|h3&6#b}C5Z;$VO+i*$O@DM5*%J>B zF!<^6HjM?56#&l8B0^FS7;8w=KN@=6>p6qmv!;=r8$F(;e{ZBOJ=9^sDy;l@Rq(r@ zb3ltBtghwrD{F$51x?$`udnFKYij~*a=e(!2_gOK<7?A{{`%e#W>N{L_hK|H_jXm& zgvaLd+U#sWt~T{$VDGG8E*P;U5U#`5HGfr6mZh@{I9X=5sQ71;+}M`N5PW4) z0yQkp=y?@xia8(5S{5S@+EV_Nja_t1v_xqk#(p+s>EivNC)jTLA64h$6Xku!ap4{a zaO)MgaaqoIK~A_k%3&98jx;ZWw3E~7KY>xq=!O;)k0U% zWuxm7J84a*>teU1OaFt#e`TN7`}-VeiE@w6-I2pw?)|(!pZ5>Hs}Ng~;wgs>V3pz^ za}$EBa*{eiG#Pq|T2h*{XAth8lpZb&mz8xISTlnT0mB8NJ<97^0Nzj`R8ab4p%bSs z=^QO~y4~ZPN9}@F(EgXSjyh5&(~7?`&_#h2YmwMWkywTHPHlw2=Oz+5+KJ%E80&3` zwYRi_#A%lm&1f1jth5c)1~YvZblW^k%>h) zOAfS?Wt}%rHE2~W16T~MO89IXx2bZs!mFlY8CnP7*hrKx;qHA)}L==0SrC%<<6BxgDG9YrKEGUBF~l1mxM!@E?|bzyF3itDD{Tf zKG?g!GXktDwUCmam7S&p%5qG=0imrSv7ZE8!EFF`OGHOS&9-U?DL>+TO}IQIhS7v@3{{Bx*2K|4Gls6Ag(2>eqLon(O|TE7!9j!5_;r?P_Amq4Ff+Y; z^*!Xy$-%@(GCwkuH&UEr7i?r#Az1lj#3(PRlnkSDMvx~Hkw`L^Ys*g>C`XhG9Z`HE z`sjROjCicJtC2(=9rWZxMAg9Jmq~IcBe||fWP)7CE+tT=#H>Fl;bl1ehIOW2Ooe7z2gJT;p9`9-con7Rm-5T9x>dnrXazygE zvg!&Zr;_kzBlN&<8=)b&+5Nv!55M+{ z+FBylnlfoFoF6a8tGBj#yT1MQ%6qpzy?_7nFTZ@avhwlDb9+WpDfP_ulYf=k1K9N| zg@fs^__9z~eANd}R>~y@lkX%h@!{_oj~$0T`U9EQbER3e*s*rVen{6S$NrpJYU?vc zA?RmD6>$wH`$^Yl{GoNqaCuKk*AWZ$+EcQl5*8vn-Yb4g%Jnmf@4^7Z44N>_&(8M! zuDAPmbMubKs<|Y+a^h!q;|EphPHad>2pf_^BjKT>U0NoQTUF}~9XI41vv=}{U0F8Z z6t0#R06hfDVmwRN9;#|kDlDYXOqySCGik+QNsM*uSzi+U>$B&BZYpXL_&Q7ndPvgYB1O855zG!DRP<7qC z^WURyz4H&l!+j@>l(R(bexe`_0C)x^ls$Cr(&ahLljmkGZEQR+5S+d^zjdeObC*C!lyE?sb>csmSc4~g(%@eb8$gc&N#gF8B`se+3e$@O8`)g!V zR2H?Sf7;a~s52ke%FUd_^^773G0}Dv=k`@zwoXB{gd(WVl;};I(Q1Qd<@p9$-{$xJzZQ5m!11%fa0N zA|~lK3@v*?Uuqaw5@Qrzu2Q8TTS9(}L9*6|!^-PW442(gr|~8}rQrc$uR`Qtg-Ct2 zBcsQm))1CpmcgF4T({Ke8S;jpuDF!28QCX6+AFkrElbF*3JSuK3ada9q3``|^*p1& zox)|nIIX3xN1FqTnKmTjyP0;r8_DfVH`T=$LCcBMQc!2GF;>jLO~gW@i)J!yD63Jm zJ#|rp7(EuEXXDCEQ^9sHHwpwtn>2?GPRVJck#r0!4F)r0bwukI7b!|&_#9;68#69U z^i^eWDo9HM5Z)LCFpViU0@g8CREVMq7`;g+5)gWGH#TDY!6>8~)fLShRUgS~-j)iKnNyg?suxLPY=C2%MXnrr_CBLsu$ zW~h>I+PFeeen}>G4DzlglPFpmhDHeY8_ACh5*(dNRBP63caA6=n!W{tU53p0#C7Av zS5amqwj$&~8;>0_lr>~dv|Uvb!#yLqh@o?N384*kCxy3TMv5W9;F+P?SnoY)r40)6 zT?9d^9gsex!~}cXNLM!JhR5Q-F8yj;BWFWj%6+?pzT**actR1;im&X_GpKK1drTN~ z*6o*70c=3e51s5)2ZTW^aa!4|8h^8jpUh6=czj}_tt*%7rAI;tY>)5k^QrICKKSl@ z?Xcj}2StN_0}(!Z_O~w{dgbs_KY!zm+S(4g*2^rW7wsx{scdN}wEcK{yJ34Pk=(kM z9lv(v%6l;6zkP0q{23HEHQImfqzD()cMB#;&U{urUbM~rI>Vk5wvVV{E z$SyazTcL|RdyO6|PE+|EKYM27kFVa&_B0>&`xt*vhIHJ~-Q%vA!N~FP=I2X698xok z48;{HQxP{poCw?dd59_o6#l%k2df7)bH?aCgqz*YUT+AGKXmbvBwro##m~MYm|jAW zV*E!(cF6Ium+v3mb#V9XGd(A}T?Cf>I(xD2a`?n}-`hpTi(y9Y{k#^T?@e%&r**7<*=P%97Ke};a!w}le*tNhq0DSir zKH#sud0wjsquYCFr|4dR0dKC|*+jX$4*v3!SLde9dINa7dxiW%l98BDXw1 z%`da&VeG=1R0GKa1ICo?xyv=>IDL&WEA}~5S3us}$sxn*PBrIvHN-h!ZZf7Du;+#b zFbUJ+KwT1@g9K6|cn;a+H4TN-5|(=g#+?e~Fd$y4ll8YyR|rvjPJ85EqbR9jav?=`PvK3fzYwg?+^mm5ek+4bm6cPhby?$9x{!{k zdWBO4ow}KT=#Hk2`tvb^)Tkewg$t=8Xh3X;e)GJh&b7d=!LU5P^&R#T&IjwMM)HkG zjG)yHjp~kVJ)`ET?eelZ!(uyH*1!af9y`skK9?})qCieXLgI~UW zd%RyYgqVSSCcHCwb~ESWJ}EBo;GY-+rrFvMI2mXd2`A$5k)#qg!qrY#s50Ohx`N}^ z|4-HV|1_Q7as2v)1|$;N4rYorr64UF?M$wMU_nljOQzzHahojJmy((gCZ50+G)mX5 z_$6|HSQN5j%9m;JhCRK+9p@QOy%RNYf53h){^CEf*W>m6fEk*zEo~tO>7&p0>-l;< z`@I#8nouIayHAp%C-2Lb=~9VnMNd+{&}FRvZ&J6%Bp(;RBnBmL*q1%O6NHa#wEoBRzz`bEtkryr&B4Gf^!1k zvlf7#eWfe8wQbe%ob6X%>VbCF_@AB%Nyo87Es7$}j0%1ip+!mJd@+E}Lh2>mc zAX_L1{?i%l?M1g{=yQ_4Q|pS%B^2;4ZoealqvZ?UOKE*Vwfu0Kcn48fEFglH^ZDgG zK$owF{v9`khpCitrKRP4fIQzaGj3f&deYPKM|1Gpwpr2Ge%vaGTDg%x@aoC4yd;{O zX6kB^pxB|#D_tc*$hcMO*d4ZcyUj|D=7qM~#5p@n^cDY>Ih^t+;i(8%yK)i{tvz)c zBwg9(FlIUV!!=zea^v&rW_hV>jy$bC`FgAYC;R%e57kAezqBC!OB5uYLK=orln{&E5`P`WgU_F1{;taH)=qRRWg=%>q+ZX{p9ddOXde&3X_m&r&|BfgW1U5V$Vf^@s|V zn?0j}KzX3NYIL+b5NQ5D-Rk@jICbb?>n41K6>_!D>-)GeLN|;awrjAdTr1P=UmIn= zy8Mg$C4+LC9#Wg`1&8(^aUv~}xXAlMNrjiXh9U!AttRw}0D!MvHKurr`i0I{N-7fa z2-=Y3)xN(b)T>p%VbKrXlHQsty`laqHANzTL);z@SM-N#YHC99k}F=a?%7YGq5*%E z5EuZgwfPNvTidVk>j!w-H zsk{>(YCQJ-{Mm9~{l5g>Lhzqp@W~@bPM-Ya6H5snK79DluYPyzALYNTYA(Iyx#toL z&(6l80%0gDKV)G?e+R>ITw&@j+ka|Oa6BnEK94}YdGqVL5AHtv{^6thD=Sy84i483 zv$9dEo#-^dn)>1TK@{jPo~mIpPd2mNCc|Y0%EMb^9XM*8TwB?fTQ}1lv8jfeHYrT6 zlW}kBQ#D!ActCF+v^266)un@D%W$TVAPkUe<)0Z<#xu3`_qT69Kk}jJTG-uUIBe<% zHG^X-e9~$P)@9)q0kEFlsE0qHwte17mh^^AylNOD1BFOl+BUc0jwXvk?woOoKU~O9O)q4!ix(yqbNT$!^wPv>FqvOkx>ms3bz3y+?M0ET%TIIE6%u-tnHExJ z1eh6-th{*;`tsId@$~8{Ye*NLb?wW~Sq_tIpiZDal?AtVo zLuf0XaqDc?LAS3>UrV)=VWZgIZF6w4T)fRG@SH~#OJbornVg5K z7_vy(aFZvk{%5Dno-B51C$Ri+78keLi)lJ^vjWAVZHQc_Q}eFs%0%+o>okbcX~LnQ zav37H&OK)^Yj%Da{`N8dr6ozgi`JcEg4;?bQfnltj_B4{U$n15N5R;eHL?S}O66cQ z$bmEo9GoyaDQk!X`(m?E{Uj9(W)K{G?q`tekFWuZ%w;M(%aL>`$fdMUL~)FSj;K&I zO5uWGtn%1LXvY{ST4YZOeQ9!qV4 zZZt#J(sDdoY!Z)(c=iNIoouEl$rFIVoJPAC56cx_m71kp9u1phgZP%NCAlaP9@RN< zGkt|bb_A+!nL1!$b2Dp5W%Ii3%Z!3uBMp|M&N2yvnO>lU?Mh$LH@wLo9Nn5W=^)vZ z!ogyS83eV(#%G1;3azZk8%kfglDz7}^6F=cDl`+?QK5;@-jW)xgBU)qsN|wvHj=cH zuwPH;!pwm=j22QSdP~CL@QI3WC@hrK13l5b9pTEbCSHZv_WiCSLG}h&(2ZeDJ{ajg z5vsf_yhw06cIS@oLUFmH@B`mfNVIT>uq-`ghRd1?JyIF(4ADG9Ekosgl<0^tD+_%a zMbUP0V7$-TL!w#%qw;=rK2MrcXfAd(?%!0uL-H^KVw28+;5B7Ql}wFkD8yJ*335BN zj1UlaYUKirM|2R%gH8;^N94QV=(*99A8B2~h@zaPM0rcmdhosXdGq7_<&Ugm=#PvF z-n3+$Jo1}Q1i|>SKK}U7Keul`v|T8C3^9DqbuV~sRxmuvQs9QXVi2YxKNzYY!JAE#cwp1kz>^`%R%&tE!k5&6M45C8rBqc2ykHXW@OBJcV_G;+Jbf-;%o zwa|FbDs?c;OY)zs$PN|AmZxjr=Jbv!s=&ZGyd z^`>F7=`>(uF-O$HCJbayoz;TlM~BAF-`ERVu}Sav{rleE-CM@1J;tGh6?%`+!QX^x zXk+NDq4l>noG9rp(gNT_qT~v>8wqU+)BbCXg2Uxsp+Oz}-tdh_n=8IL>O~0mm=I{T zg1h$YAcvA5EJnl!R0_9z{pZgPy8fnH!1ZWWjY(`Xag z>Gg$ddT~+2qFl;k3Ky>BGwFqNHYG|HN7uS)$cev-Abt7vFHc^yAQ+Fg>27ZORdTh+ z+Q=<0O%w!+qDl*jTe(s&iO_#9Xf$*|Kg}I-@>fLnQxUGynT#5zvclnPniXKm6okNw zn*8zZzh|C2YiX;l=gfGg{Jx2dC(K&DWWgE%i=NKQcbiU6o4UjC@yCzHQ#uCDrhXKK zy`EbJz>8}y-<~<}VlM%o)z$p!>XtQBucjQhedR_)QlU%fpbqHl-5U;@5VS~NLG>0J zCM^eByy}z!$V%m;WuGRhLntbj$_SNa1gyDOWoCqoU1z>bPb}TkCeiy~*Zm{x&`#0M zB72KB?DK9XAU2!9Nn5u=*N<>Wi-v}^8eu8qZIJu43f$}5wEq%3+2*^>+qM{+FWem@w zni4Glme0qYvzJ5yG$+zQ99h~uNU{d;8;plz%29H!#)!oVj`?H$u^{nPQ6EMtK{c){ ze=y*W`N)bsClBOMI;gcr>=VU;S`{qv7hDEK$NEZjorpXvm&jpME#1FWL0HTAv~Sdf zZA*)PeOeRjGN3Lc?@C*ggs#^ELQ^s*J+85PDt(y>S6#=##obs-(pBNAKsnNy@o%6i z&H`T5&e4#x-3O>~+8Fuyc5dI%kkWVem;=k9Gq_F}Cabo`I1>wjwc zzQYAVnuIeGVsc&>3<=~DvV`kZ<{^YMn9b|iDj=uLZra5QXU>IIVtdA6Xj1&PItU7= zRa8JR#B)KttCeeU&91A{)7wwI{^YGc_>b)MJns*%B~_B}Ny=%=^Ld`v^LidjtO5XR zvf(%zYJ@AGJX=6pG)--K`b6}6lp+&h69Ma73fS~fS z7W%>ghcs-`p+rG*2suu~6AZvQrUfPhI|7H`k^>p|jBTeOWMMgk+~PnVgD3G*fgRH&7NB(-DbkLx>!Vf3eN#d1o15NV17Dp5 zQ-@YW__xA>fx$w9Ax7{2Sjo}d@9o;KVef{$2M$~p4Boh~P;0z@|Kv&klppnEWmfcU zR8mWozZi=CA&TH&#HfK15FQ(Qf$NPI0>uF1b82E75a9V$R?b^j_7X?v! zE^NW32qwuetCA%*wdm2&J*+0yv2ra%3z?Tp5z(3RYUbq;WzbrEXmx*C2XW=xQVe)) zXgtUnvEs+LqoS)>i99&i@{RR|@AJ*g>jl8N&5A)-9RDf@bTf+y3C)7UD_AIsqK*)6 zS8`jq&!`RPKALha?RLRn7ncJ(2#p@Qr2;7FzM{{WPG==MHxq+l#cEc{ zG&&k~Z(r(uV@J)+mLSW3y9S#6$n3BS#JZoKrG~f83DeAsXR?nc$FavViR8t}Y;NZ9 zJeG9@Ge-cO7}=(V&o9nCd-dse{Re-oN1ilwwFHB~fuCP54lj;B$wDhWT+HTxfmy-Y zB2?q-Xz9#{XC_NofinT%Kg?ywAn#FvzIyK^X28Eu3N9q_rk^feUK~ypSHTw0i(mXt zzrA)rL&Gc~TJZPrIN&#n=@($uwO8vvNR zIuH0Q36q9&4I4CGNiR5l!agUQkIanci}G4`?!ElaiGBfKfnFqFsbEVqZ>lZhu3P6^ z7AzcH;RYuIj6i3&O;o`oBUIXyljUG5iD4WHRx3=*)hII=SC7 zwHm7b4nQue=q)#)-iRO5CabCdMx1nqDh)<6p%CQ`Yb?elLYS_~4e&-+1CcQV{sC>k z9cmRxz&BP+u)Q2JbYMU%K-`K9Ea9~saAYBcLl9Kp79m+ebTJHO{Il|6A>-<$C>T!CjcFF#mRc+4nlu<#dlW;3g z+?GZaLmNz3MmnN_&hj+alri)bCJQjuiyCVAu*&I33qxiTQcX?6@tRApS3!zadr8OH zd8B%iu%KjQq%?fbs2+4Og0fa_9dCd#EkydhaicI`TJ%uBV1jer#P(>o>JYwyvo*Yh z;Lj_Mm2ub$Umt=gk(Py%HdG{;F!8ln>^Ky;8-QI!ckK|N?UbY~0@Il8h0EYA&N(59HFv6cT;ll~QZ6FTk)fdd@5Y{W`!3ujU{~q%J;d}`; z>Y{`pES#A8!0mw{^dW?J0QZK346_!Y6T@M+soHh0+cn5DfE|*?*xq3j9IU&U2@nfe8ExCzjt|932BG9y_Nlr%wZn zfyYY%$Ux+W4+W7Qz-oPjN)qbYrku@D# zjf0b`d{`Z@XOOn7J=@f?_ayc8X7$XZ{>pn)Mtw& z;fPO4hd-33kT=c(Yvn}+2&c~!1$?uk*=)X897m262}W+n-FzuGUdqDiJd-PxGJ@uE&E!kO;3r>>&P{%ajik)X3?%63 zufPA--Lw7pML21zzSPp+PO|0-eS66V=h(o>##d|H* z-rin}j(b^T2oBB7E#9o8ttkiF51nIWdY!h}thY6B>9MR}|jy0nR- zUV&R0vkc`i17?h6pu^SdUNBViYQ1cYA@3Q&v)hX9L9c-cmsm_PRCjng{ME?c5R_#x zl2^Xr_Ill1M{;{Fg8;Y6)qUA*fG#aqeMm6ZKrz{E=<+_nCztgS#G!+xfe_mRwJ{aTkFw12!@;{4x@!oVA=?;Ree`uBv_!jOBDTIGHc$q!+p- z4Jc(-lCf%`p~fl17U7e4GPy4ZE$SMag3PrGfZK+K+Dk^PIMt#-sbM1?fO+e<5v{;R zD9<&QY8w`q$MFUyzg80`4){wpl~+O;DZgT=USf4(o~N?waeoHnUK#jxSs`ah4~6G*31#KFhuQwxuCmT4UUGiL?R)~EUpEPVe!`& zSY{Ql7WFxBBb0#S%A*w$7-t52AsiC$5s4jPYyk@*2T%$OChT)0upC4Y_?Rz%JtSm5 zwqK`qfG7W_Ul<_lBh{k%dPn|0aX?>eEt-GJ~ufO!aXx2qp$2rDOlj zo%{Rx`abUdYEFVx=058fGY)=j{pzC7UxY0HH| zIII;41)9x}M=~}hUnoxt8sEUc_y$mzb7O+B0%Sn)O=#8v$zMHu_~;QJ`P#+go*rSP z!alIw`cts(LLDzy^&M29A%i`8231lB>1=XP$L1unsE-`cxifJXd7O$vCsjnXZt_|~ zV71VkB=JsedwBC(_k-=**SZF|{HrHnsW19IupSM~Jgm(tnkOMAl-&I_<9&(vE3-%N z6>nRty+>T~hMy2{hA%4~kGSF<>;!vkQP}2 z0RO7_E|5kIk^!3k{$8MMu9O)aElr;{)&}qXblS~Yzb;f zTL>+pNZTs#2{>Td|cO2+!b3!a#NHBsP>^gTLfcDB4 z@Doo(julu-k82p{(^NV{Bs4Z(zZ%zB1T#JM*98=;5%Mj$b~^nv=w2!~9V~!tU$@L6 zcR1?D;mbb}8+H}Kp;7vgxE`*DHV@auoJ2ZSiH=J6%#Jszo}~Kv<$_O*hLr*i;EIOR zX`U}RT3j&Xtq_V;SOS!hN2e80X)tWSOW0LR3N7Z&X=B2%ywWHQe%a?19K;$D!+N*k zL9)B86)B+&S<~rWBB1FuL}6v08j=$KoYvqO3zFeET% zN#gf4(#x2-7QVqGI`7(ok0gU^fen)zWd{yYbwm`j{gl^%)<$qxtd{yy1QY58m0)>L_oAapTFxcG9lwxZyOx z&~|4(huVgnlggn4mN!M~9Oc#Ec{mWIL~B`vm42eZ{q}zHk*!7#a6o|^&|jY`Bc$e% zL3BV-9rF5W_DmaLoJqALSTqoF&;Zv@7_`5^uUbL^2*OSgEgHNJf?#A=ZEchRkEAlj z1u!FNAIwUPbuWYH5n6$>aX9Zt>Qpw~P)ZrrmY6+fvzaj?zXVYl3ZKjr`9}27xlCrv z@YTRJQ!O1VYVm6fc+3#`Bn3(3OtE+{3%nAWr3thlFx9$M;Tr&0mHdgKBv)+Y+K`%M zB$5-D3I+$l4rT3=iShxIRI_~wpgbU?*21(;-3u&(#fO^_K^sJS^$SFCa7aN}ZW!HH zEQ|R{iB)z%Sps0j*i5E#8jg?ecwobW^w5tUc;NpDu*ZSjDtL!{!H;`-tXG^t*om^9 zdIAuB>d>PMq?t%R{j|aGuXpa|Wjw@S4( zoP~!hkWJL)z@|-2hePrgX`?(;W3z70%la2-m&cc#r218lGaGVNdR{v4A!(w8fcX`|3?v`2%rIx}iyKbbk^3C9=O9hbZ$D6X*CZy0tf9*}a zM-k_Nrj$LQ1}SdH+dv&sxPcLL_b)ttYfRVqeY;&Bp?$_ky4%x4Z+8{J&+PhOeABk} z%R`DvRAs5r)GBJHnYp(~Sv>aE3=vRa`t`5U;MdrL1JhD2eCh=a>mYiUD9qr9v?- zt_pz9UixO&JBOe7xd;;x0R4`IL#bQix5x&NCw8xvlsabLO_V8Ey49lFKZcKTRN zHZ_gn%NRbkr_*yQA5DF?dfCh zPaAZvz4-3*$LrJU>+5UJE!qKlHnT=5w)&9XoYM&Uw*B^h>wdw-xadOgWk-Hxs2Uvj z>_R-GEWyw)cBGim+bH=5q0q4Lm#BgB&9Ch>r)2ewM(r!mOmk{gP&BBiSS(-N@@O&v z6crZc-~zgXKRs6WM-G-AkV=xb-4k@y~a ziZGheqb5Vzz&^uU3AOB~|CGTj79%92S%NkiMzZle$eZ_-vYg?_i_WG>sS)-6rb=T- zuw48G2^@???Xj4hFyedC5IJ*@tmjN~)^K*LYW%l2R#HNAv-<Ia?V;?RDyPGRMq@uJ3yuxm`*Ra=7pa|r z&}hYO96g#|?5_ufwj5Rq#d!Qmu;chqoIk z0?qyLeQ~>78y>*Lm;NGKc7Q{@B`; zE4MJ;7zo{3yTv$GDq?oP#vlLj-R}?oq~)iw6L+!ur1$4TW582RBeg0@Dnd%7?k)Dg z^YiD`NT`jhe%_h^`lYi|Q?H%9_|10em0*st@eB-fe)u0F<{s9r)S%Ye^(rJ2v#$FC z=F_`$8vHfLUwiY*Ib>MCu%YlYE+UP-=Lw@+q0so!nSZ@=_>o-?szXZ+f-euY83X=k zWyZjE?l)JAT-zub%#L4sDpXP<9Ns#Z?==G{~A=CCS); z;q-0SX9E-;g_ezwjxsL{4+~t?jr284)=x|{b4GS|UH}rOT0dPlb%IhKNxLnPyo659N6^I6|93kR>e^i)X|Ex&M{ZVz!ciJ?x>-2 zT_v_uCsJ#0%H+AAD#G6SdWXA4g0~X95i96cDJ)fZPBvw_hm2^tfqRVq%728^xniug zXRG0I!9Y0u6(j3>Z=s#4q@JFhd=Kdx6fdwT&XX98;Ho_h{Pu1&UYn#KDVaP&NiYeN z=(FrBW0-3Ana@Y^y%9HxPPXSGlra!SX$VUumQXp-`zc?OAdymLqyh-!5e0D|injYnhSUbR9ro`uQkNvdZ)7q_2?H#*u_G~Q=o)Oq?#slWtAk?z03ZNK zL_t&$5O20DlbT8$tlB?J$wh{+k$&TtNelq!5A6upqQoapukqDj!t+ zLVQn{3`)*LMt%4A#C=J;3QKrJC0nX#PXIrWaoQ~L^(53AGG{XTpu`lrHJoZ7n=(Vp z5Ci8^2C>D1)DvcnAR7kf2z)N3vc=3v+8UfBdTcCJ%qo&HTPjscnQ9TSGdp2=3yPUy z1}jf4s}7`MuDMjMMOv^{rQZ*05W1%cvLFwZG38F=T(wbuUx_g^oksoALHGB2iO}Ai z3#lY>!&NdIa5S(_PA0j4u`B_vOqvazV7>;q2(L)!=xd&^7m25~`#u=@gsOn6#+RFw zTB&pneyLpU#O$FR_ixycbbAO9)(?2_j_*5?gu#Zue1O3Qz^}X_P1X}^gpp+d!x~5L zesuSf_ZbN9eSYs|yQ#PfeM9mLzJhd`D`&lxPzxXfz)QxBAdh18RH~Y)UbTy!zG}Hz z?bqDhK==TmorcBQ5^Gz0!95C#@18h*mm&2DAo%D#pxB<=^M=+NqiadKE`NUGFL#V1 z6QgMe+O|a}-_Aih33qmO;g7|Hioy$R7m90TcsW$w@3OAT%GGr+xHd5 zV;ft(tX_;`FM@!;=3-dvu+&Wg7!Q?oFRDe*p;Sl<8^}@6N*h=lTKAVgsWn zTp|TXbL*r;Nt%w(DXE$zFCul?tNk%MpY#1WX~)gj#^(Ne{G9V#>=*7O?o}5=&ZZH# zx)8-tkX?Oe7i=;stM8_wI>^zvO<%CJr^^$n4QfIvBj;M?Jo1oqCWw@cW?=OP_Xtdf z`fC6D$asy&c-GbKls(Uwd zYil?upm=Q^3Y=9<)P(Y1=OIzJF_k zGKPPCd*;kndw*>874ah}Yta$(`M-^w6R?$Ud6}vEwN?FeYg8Z#1>d}tKd_m9n;PJ} zJ}a2Nyng8i4c+Nk^Z2F;m%GWLtZXThKdnboQMSJsWBBz7{8FsI(bT_~u~`w78q@67 ze-4{c9FC}V+66P3$scfMSo%6L{s2Qs#?Y*YnPmH6Kz_9w1>i+Yo9&AMyJlY6s2S{# z!?!~X!^ks0THrfi({RcTd((p7Ve7RAnrKj>nSrh&A;f;wXZ5N>iCAcmx26b$^*0r1 zRu)EK%8}}uG6KOWxhkUWw?0s`@T7)7EIhx8$aEehnvzJSlcZ6q{#ig*@U>oRfyUEtu@uEr>f*T7ou9u7Cko z&>XyrO@UvR0&enHY!0)KaHy8Rt-oD*kL>D0a%LyhFJ7%J>z9=Z&&%P|h(ia_WjH2L_l3t2}O$A|JZEJr_8wpdb{afMI%fgde zW0wh?WciyqtyK(LtbVBvt_6QlJgK(0Ep?eeaEh*9#=UYXJd}b!9Kyh_Kp}mDZCXAU z*6e2^KPm{Z1X$YI2BviEtXG)vvuRNpFs(?uX01G@8VW`^CS$s27J z+P1ZwPK8g?y^zvGXcdTs_YbDz<`)J|y?M}r+aJD8qC9B5et!?V=X<;0pA{guz=8#Y z6^GwbB7DmDgx`7R-M_pmApFL01HvS_=tD;NKggl7kbgxaTKZ?Ty}jslYzIx2iU$o| z?E`(Y*tSFdNvTQM6RM2O>y1p+hk7Cro&3)GW zO8__z0526Z$s2-+J3BC7OA>V+CdwU77)pJAeT^_jRM3}xauEvjju#$n*GIc6x4YL%zi9_{7GoRiw(x(`y%pH(33SZ=AfC9UBvtz45D))8{`s zKXz{J;-qea$B-^hkFUN-64tYCFFpRc;ji+wQ(jb=K2c}Z&UyH?HV@~ipb&&5xpLUV zaSrd1XFbbX3Y|7L4=mky_VU9sk2~KoBj+k*)OGuSTBd961~Zqq9Sxwg5?weKdDjIQExBtkxli0 zFRS1uy-b?ErI5w zps;3g2oRS*drj#A&ZDI6cH^qKB9=1wCxv44(XCGCU2uH2@$q-2PRHg^jEyD9`w&9E8YFPR%I*Bv3i74v$TOCb7Av8fI&_F*Gd zBa+KRRSuONc2R|NxYRXNA@A<8FR<`ONYlZXgRQUp>Q#ZKxoSa&`i>lnezy&>YYRey zotksy_L@Dg*D7o85-zlB%WVLBc3g za%s42OWTbw3x`oz4+{2cn1|T_3-k{TvN}$+;z8og;9z*_tT5n$`{-2~^ubqW|6hys zI+(-S1+xvd7QzPtaGHbOQ@gwIRff$Mi$1 z_ufr8dxYo8gGDFp)?K7h3dVNDf*K3m6Vmu|{^n=oac7LtbTrgQCbXdRmCvhHX4TnH zZ4#jsY74$W_a@BB`bW9^yBQb zvGGh#kEw!qLY@o*77D!d@yJMiNdb7TJVGg}t5nMkcGu5$3oI%71i8baY8>!(@CdYxwiVHr%{{!?ROGcz^7*CwwHx33yZh4P&hAQ#U6rJQ z>E^e^G<(R&qp6@E>{CX;4vkf?dlwZ6=>#?u#@@l$*{|jSyYYWINEt*4>sPiDuzNc) z>N&||9CBcGx|Pd17QODGj7IirtFWy@cxy(BfHMfL7K=b!?o*)C<_*~WPvw}tz|b1? zl|r|_XwfE=me66gzeP{MU>g-kIGvD8GkOk?&!LOpfS-z_8ajcE-YQV9Yhe`8Gz62- zApl;VScs#z0;JjfMzACGmM640DUwVG`OPJ35LQJJai8FalE~#;30%Hfe*~b?EvU^%Nf%{F+@Lr@1=1+n zUx8hMu1d;_HJ(zgaH;RN+?S&($wwn$iE!xo3S9`}{`KWtLq3q$#SRz?Z-u44vhtoa zxr5xvdH8N=g|Cz$Hid%%+@n6tq8vI*Gq9j8)S2QWF2aC(xPm+nVZx=mbcf*J_fG?Z z!-lXf<4_qq!aJ6~-VV)dQ7M*F9@IHHbSf>_YXY*ojGyTv1c0?9ST7Pb>~ITgx?#ru zW9#~Vn#}LGv_RUDp{4c-L19Rt&lB#cGtmpZw!_ZOWVv_?9`Wop*xHn&$uX}DA!roF z!FiH7yln1X)-o%Egel_|t8-#D8S(*X#2Xx7!}tLR(6rR$kBR z{eFGHeA)$M_QvfjDHPy!VeRYTt`~YNk1L*#=RH2B%UR})#}iPB3T1E!_0@e~x*p_B z8W6GQs5o-^kYz9T*W~w{p$j;t^@Q-=C@8S*iRy73DIGvmU!o@x^$8FQ$#n__M|+kq zfsQ5&Q|HpxWE`{^gC1JX!uuQ3mdt2O*l?IbYD7*2!%W2p1|u<(0_H4yy{3s24S_`k zqG6Rm$t7@%oYxXYhn4P`jfRwCX^Q=#$RVr*S>(k+ry~fv%m~TO>LzeLix-&@7>>0i zc|g}<-Aso@VkT0vvdrR=pA<1i6aZUDyMJ%@`+t>K$`X8VFPY=GC5isArHWQm_<~YK zUpRY~{v@>#1_+-95kCKJN5^?ZgYL9)%}I;npwBh1`YQq^+b-aBLK8g$?h< z#)b!I47r`xSo3M%!%M(nGbVpLA;$d6SPF)h%rO5dgCxX?3XgJ0e3e^bx!kktO*{AY zrq;VOIgJ!`)oN`_!;>0S1CkXk6O!Rb{z^#lpI2|*xp@aM9<_*VIDF&{VactlmC10X z@@D6`>bLfGzNEg&`fKsurs~(2%z{FB;*p^XvGwV3Bw{%Qe$fCN_v&6RWdCxO7}sG? zN~0Ueqn5u;!(b$bGco#UQ?Yxn-ReOS^leui!77d8*gNg&=9n5&g8~1bV(8b6N~qfk z_S@J6zin3|?YqALW1Yj&_QoLDukhc2;jsZrv^<6;T?RQ~VtjdGe)}K2mmVVvT4i$L z$9B~shyz>O*|}nr)ZD`6!i_JXf`+;nKzxd-vAI^TfB3M4~;lQnnGcfDQnZnH6 z4gBQ0w^nB6Fyo$|=Q+Vl(ZZCUC<5@wzx@uo+FGj;_=lg416YONTGvH<;w`7mi;DBg zhtT8v!+AMATVCE8f3o}HaqqQDKRE*QWg|o55jmB>ISC`)YF9J#f7spj6s;pEJI%mu zrD0WCD_a|?5^QZ;<;w5RNgGlK?J0pwd_O2}ig^r7rvzjR3d2e4aHmo*^V;bzhF6K+ zQ94FTnTLf-Wg%B$D-FT@Yi|pcK#T=w<=olz6N+$g|LEr!~pqqir&FCLYCIg6yPM$#2WI!H7PcZb* zcm;Y284fL1d7+%6BdHRt!3~y3x`8??%$bi01r7j2A!!cOjf4B*2^9)0V0^UVXdR8h z*yfT1(+vyMWtO@@)Z5r3J3JEE8~TU?l@^vPy8bu3zr<3tm?os-fVy zs+?60eTU%kt;3wT>I9OmfRn#Mx<4T24+rECelq=~o$gsfel>>cMw<`pf1!`~C z_hCugg2qB_e(?!6hsqDM2!i+Z?UR33$l9?bfUZ4NI_YS`=@k|hm6a~A;7R1TlvJi1 z@`jN&4Gt&;zPw!?1bix@&OGCnd z7`i*r?Tjo%g$X-#Et>wVfNvs=s0cWO<#x@8boT&tbpcbVuC!=Oh;jn8_K3BJXnIdf zGuOa*W3e8@LYjEMjA085EpjG;01c)x$5f?4Fj%x9javLyrE&zVbZGKmZhA3I4suxx z91o-WHw-SV;eJF3r0H%#Bo=d{~4W6b~# zM+A-K;0;&BYr(HMQoxdU6p+hg55O=2w{}L=E%UeTjZ(<9Lz1lQO|Lypfa4KM#>K0} zkc$Uc^3e4C>CYd*ll-UWtMDX`G`mIu)1B64mo8x7Z0DZr3Z22q0DP{=Dhh6@K2}}b z`Gv0Qh}B4=3CRE!C*r8}LhBJ?DV>G~xQy|0+T%4mai<6W3pP-7?Yp-sAbS#OXO7&@Mi~TitO^5W3D67(@a7G{Or{?X zL%JlOIgBd%K}A?m|8pHa;5)sSPM&+I)a7VmKp^y2TbSU^?FCuPVwkkG=)duwHZ z!In2}&CDuhJ}0LTdHI;nPpD&2aQ5PaBCi}7t64Hh?8L+6?Pu47!@r58ZEe@#R;nKA(S>7pVPU{kp)^=oQ^;vI|ZqBZibnA+pq}= zJM4myjy4BPNXVU}CR*@TWoWtSY(nu7RabB>p?|3aaU3ZiIzSlFSPE}dMn@8JX?HW0 z!IdciWp_%6qoKzVSS8-(5UUkxOC?JyOA)@|4?(1rwC=i-0APP}33j}o!c31AM26{C zeuO{CiX>rF?p`@*ZGC#vhL_aKT#Kawk~jj#e|6FxB{6LRMD^iL)VN@%Kkuo zO@D(*?hxSZ2jB{<*4;*`GZww_U=`|uAJlOy-OmC-lq%Ge_dlqpqdf_-=klt0rgLE5 zTTX+KJlH3U_;w8@&JaLX)eCO39k`+f`5X#&F?D7rR+aGT^7@(s^{h{l=l99Gp$*G= zyPPelv}ZSi!CfgiBWptjmJQ7d^cgwuK7zU(qiA$6zjf8Pjx=y}ts#jDU`z5dm==*t~+oY8eg6WlP0u&7i|7 zjxv_9+L5fDLgYbn|7*rDgO&$0Rv`sx55{vse@%?Csh1{Sj(}-Xo|QGTT9(^q_<|8q z9phRUfgQ|*#tFf_>7mT&Ep&kLLWzP%f0qmF66| zoV!pE7|v~22T<5R)EU;phFqU0Rty+k<8V66WHFeDGioo)MR8c*S8!K8GD=dN*?Fzr zvIf&vNA{9GMqYE{Atm49r=hF60N`BXesw%HoO9)pjd{ zqltoNgif*>_!znutW7Wjuoy@QC06J32m4M{eNl@TO0HNN*$fQoT3h?gtBc$Lg8)Oa zOb!eej{xPAa?%RL1OQ`xy8_$p4BL>Z!Sia1EV!}p`PSm~iCdUAZvt)y2k$~^HM=kf zCDhpP*zCkCEXKnF920{HkKG+yMz$px@THS)wH|Kd{1(o!RRlBNT^Hs%HaD}0Uf;Wf z+l9H=c_^Z0W&|8pfUz70U%b3%VeRG12d&vL?(9vHi%b?retv8FU%i*UUwv4y)gvmh z>f3EW+GV*cFaKV^_GxZ=d;7`1$vXR|rVl%gHw1EdsL>>l(`YFq5>g~oDm@XR%^BNM zCpVNbX**B2^u|u+;GCnJ;whvy4`smYpcxLXuIlp{^0pjJNL`} zk9}V6?-#VInh=t}DSngp_x<_2AHKPN=l;lp>wo>vz3;yN^Cv$%_wS7zi@#pEW9I0l znW3Rg_WRjQo0c>-HZJL0$M+cn%MEsyS3jrmHbR0gPR2?~&N6%s2Msx6iqS6-V=*KS zODg5qOVGM{3D)q-cN8fJLTABTF&hsV3wq4q!!3R)mXJLc6=SK4L#;2q%)lu;@TyBV6g|tSED! zieWgR*)&NUJd551>XD4x4l9DA(kVmYWdXXyvdksWPOH zJV()xBB2SNL~xokd__a$L*OhIup%f2qrPi{RS8M3B!{jNAZygjMwl(I-LZ%}t9<$s z9b7u7K48yTiX~MZjUkN|4Zmd2MLTzs7%Sogyx5UN5;Q@R?Wp(Yy2SVk)EWjWh66J& ztKl-QQ-eh826AWvXEh*o1=;<^_#%{AfG`b7c##ZKW&4Hx)>aVHF&dB%E7eOBr4a)I zZNuf!(Ey+u=$@ug1|hV)mu2!=2E&H~nQlrPrfT!~6xB$%d{=E>UygY+R5_*84FleS zAuv+td_J?s@YkMFC>ZYU8OYaDYHv@AHzR_omkpTCp=Ll&%Ugp>fW>-KRcPvY)bO7`zaj5S{chwv(Go#YL-1L=i@<@1F2Cj@wv8%z0w7HieK7;AnI zz1|%~Lxp$KA*_Y)ZwZdpEE;w6&o(dEynTUT@b+K6{yHFRr+!tRVwk&@sNBDwA~Le1 z)8qEK1%xLi!V?poS%CP~<6roe>-p&Ts#_hc7H2qj$k}GlufB?t z&a{8(ZtFQ$!37H2$78ZMIi&dsOa_QY=7iLkoJNiu8#$u=@rXOR9yt~Z$7<7mbEH)@ zYvxAHosJu+re;lz+efH-cc_xk0prD;U!_J<-L<1#DFS4=898_L_V#w8zQP$COJSGJ zI3Kz)9Nz3-?C6hm$1>+WA>>&B&~2{Y*J(rQP$XsBOR(aOm2OF)e83yeZ~gtQ=;uFo zso6U5U);d#KEKom`s0s{u%0&LJPidtD9}8l`X8qQhz{I?r%#=pL$6_8`rGe>1Ic*TX*8oxFPC?_SZ7By@V!e^2`=!?L4-+SLH^@!C9^xs4aH@ zcYct3X?}oA!6LsdT>bX$e~%8$w5?F$_}a1MV}R$wuO2+O|KR#}_rAFImq)*O_wvKb zHJ96t&dkg_dvs=KQ{$$_CAT|}oZIQvj?T`-8#k_~ei04*2|E#4wrpp$;y1MXC5w_# z|2i(!U!F^OgXm<~{~E%|n0Nm8X8NO+8tKPip#QYP0`RUzrL5`yBY z#Cxklp=;=~5|zf2386GTd~MKIwKTLk25=S`#l>M6Nac(Or(^=QC)W1HRDwk4WVi9%OnfRsG-bXolkdy*<(V>P z`V6LX^?UI9ssY%MT;=lhQb-%n<_y#Zguex4Vm0q+RtR*VKBw}8f>JaL0W~*v_r1-! zJoX^DU4#IyHomehwZ<_CD^Pl%nWkU#)o7{+wCZ;(N$9Q$%H5zR$<73T?YK?}$OVy+ zmTW$v`-ptxJ#dYM+>B zY4I2rK06!sg2S`7Zq1h63K$IEs;Hg5HR^O9W~TFC@wELMrgKwhruD-1GT*Y!`r-4DFf48shDdz3IqbR z-Kh+QcsurkT`43Hfzi>fK$%ft1K^cyHRzv_VRf|C%q3o-y|TM%gt-dka7{_ZfVaN7 zKJ@w6Gnzgti37uxOfzpjk`MSI#q*~Qo~HW;)zqm|7Y`nO`_Rn;hi|^~(ZwqYKV}F$ z`G@0g?YiJH;I(7UH&i#{GX}ug+P;7D@LO+u2K*wR`qgowqz)Xoa%l4SM+m2k0-yTu z1gQxy}b}1Xp<~LO1KNEqm(}&Y$LOn@dRBS)rSeP8)Y)Ct zIufZHHzsd<$hOv4?bUz$Yy8`9r|;hR=FaEeeZP3`-lL7nv;d~Pm#bxMGsbF%Zg<>n ze7fVM+jf$}f8UFjI}K`2tf*eGcHIg4XFgKrNO4u7S{wYER1%h`r!^?{s|Uz^_9|%5-dH^vTzgc_;5E)l6Z>qL z;cXGL)~vZbOoEo)j>&2;cm!H0aQC-s6YNK{Ra#`V?2)P1shAD7t0t)=BK32mv`GGk zL|0A}rO|7INU=P`P~stbkVi5SF&OB;;&rXvttqqatbu>iw&8+wca z+lv~!t#i~_2DeF|+0dAT=rpR#I$4jP%h~KdvuK_rz3NddA&?Eq%8@jjO{NWX={ssd z{fzM!8xpkFKE;-l90tcLwd87YTZ9d%hZ8<0slz}vQAr>)iO`9r#D1TFGK=7Zw#K2* zdkmYK0AQ)HP&rr12OL6$MMFcB8zJ7ke1kr>tRducl+sZJV)^E*z0oT8tx5~=`z9z| zKx}2iIOJ-e8B7lvh%Y6YvWi%a_YAWaJr(gw7w->;+uJo9vHyRAS%w{U^pq6a!<@sh z1ujZ&rNqgyvIq$rC5E-JV426@*5h{qpzR=w1xp~r2CO_-fjc+=A+BKXY~URX#B`~E z4IA-A2F=ztMM)C%VB~!dbA(AG)FJMHtqSlakI%BYF;5%Aj1R|H| zLtbUDY?nQm-qh4oZ@fF65iQQ=Fb?PA7?4y#Xt(V~J+WBEgfmnk(Ik*JfK?MiZG2#0 zkD>0L41np~&1>EqFBrq>2GFZX`qCfz~Gm&4S%IIdrRQ`Yk9CT2FN%qtz*_ zxhjd!y69U1wg3wK!{XJdY~T!l3WkB^J~qZMJ`~dOCexS5!^VpH&z~PTw_tf6wpr>!8Rz^7u1cvoUuz7$0- z^Bh?dqKDoQ+jKXQnGDi1LMn{urbdT{Cme{%U`$4xN8A!`vfT+9hKd?P;^I$w{@_1y zujhFe+%Ctrwzi*!0QUJjuh;YChS1^SAexng4-d*Y_wX?5hJ_U`&IuIHEiNudc0lIY=#vAFAPTLoj`z7g7lBW*cp*3HJ& zfdOPe&(d||vtT~sV*)gg+38I9bia>v7Ji&#>dt~X!D^qWHQ`J2Pp&V|v0H#^j3}%+ z7-&gqDX&(sSj{a8i(}1gV8HIrIeD%xIuG7^UX=wDl@(1w`#V98(20qeJKXwS{NzN} z$q9ik=Xxon_TqG0%TLS1%G?TyDrGV6i3Z` zaqd>%<#U(&ZcR|=1+5p8vc@q;9wkSe5&(v*nu*N#9t9CEEm3Mrs9iU`N_=y=sNCRL z!R++t^z_W=_~?{^+AG%=t}fkJ!u&Y<`0=CV<>ODEK7I1=<>aN8e|u5ADY9YDw(jmz z-KS1}8I0eZzb8-iBv1Ai>ncCL|t+i~1ir97al-F%3lDARtvOmIDNmlXfHXDAm8(AbLg?GzuDq zqu|D94OY<{6#~5A!N|U<03;(8x+)p^QNX$4M`U1CA-NL9BtWq+;)>*8v?^3liMch> zqC>%8R6sa6h}_9wWoa~6;jW-G8s^|2JVT+N+gb&=G_YBXoJ(1l!^yL| zG&BhLl^dt}%*P4^3q!@$9;>^@O7AbA*J^b`>8xBuEI}$o2!~q;ue;D%>=DGyKUV7Y z4n2MhgSBy>J%E^}-VCcGcJ5VNiz~(&(cC z#Ddaz;87-epcP3FdHWhQaW=~DJCBiAm|mD{JZppIT?MRYDJq~fW87>)C>l=Z3ZUh~ zS)Il}=s6Q}I6!<^5sV2l32{NIv%sXf2~`)NQx@h8b2X;Z%z!?e79t74E2vhN7D$8HRw!{t0Dbqh0U~37 zl?Z{RT$yh;H--)<7S`XP`he90I^2;<-Uw479Z=ZI{$PRRG^>L;QA;QwPHIdwG-TDC za2O;0Io#O<`7<&$T;Zm}br^ehLc;|$n4BcQpVY)230I(#0DSuQyWafG&%&T{EO^Be z{N@|~V?|o^1g`@FUWw*V8PU5|DhrX3wR1%l4PEqB6_f>s5)@hZWQWp@-8=T~-b;Bj zGP4dIJaF&;B+_q{l(6hN|El~w3JMns8^*hw9Va1`9*$xxZ8i!YHZLyDnHLeKg`u?i zaL&#S2o)AioTYu(KidQoaaMjE+3akSnp6j7n>w|M}DXzy6@~W<7?j4ezSP12o1n0r@!q_$xI1-0nU5{&?@j z-mgDF7}Wb;^RI_eg-n^S(Ln`{=%5-Mv z!sR=Cx6X~vj3P8+YHFM#-_fC=nd#|WL&8^wUfX-rtax45^w!aZ~OL{Al^}pKgBp?f1{0OuqZ# z#eZI0yH|bh?)=(4LTl%{*UoQ<#bVpID<`#$?0Y-Xrm`b}phV5hYIuA|MRsC`t2zbo zD4c8v=Ut)vJg{D&_aUgS8XB+?hxQp;=e|DJI-)h#7v_a7``f8ZKp;5PL zLyog%w!@)R085fxH41W+sF_%h#8+XvafCsVLSF64)dXD*GdM z9;TQAwQ`@C{j$)}4%?%cKO5=z<&@fHL+G>MtWD)_7;@oQC_{oI8noA5i8N@~k66=y z4nla4um_IXllBS>qmz}WN~!`PS8)Pe5o9ePUBCccL_misD-eiP8IlJED~0%0k>!>~ znNe9v-4*gD84ryORb?ejzQrMRI|SsFgGh5jNjL5)=AhaNW3W8J+EeNl^exVJhpgyj z2qEkWQY)dWxZ<{w7^`?nw;NcDmSBaVm`4j??iq9wT1#1slwWKuM3{#)zbD`7>B0U? z`0P=nOBNQZWGt+TZ+I}J_Rx9>Ttz{!hY6R+eHLiN5;(sEIUXJ><l1OAhCd9SO{?%>(@?hhdY~? za@-l_R8&f!grX_@w@%V=@1lVmGFmu!905J?j6M7y)Y>qyz-|%96WFUC|t4~ zsU4oet2Yp|ddzy`m@r{Xr3a(n!pY&}a8&W(MF_Oa5K9XTLoq!^5O&TwgbE|t8+5o% z-gBWIS!kzcm2?`HC}%PwAd_- z(eHCh-!@3FRO>=@%eLyZu|0dbySq1)uVg{5f9*#C87`0f8a~$j~1T0dTv{X1X$GKgz7jWV$}esJU?_lgV_g zDx-D|jZVE(u2ACVIj4TmzS4+ zdisxtPyY4%`6Yqc_4n?TN1E5)?VfL$pWieuP+Q(2Kc4btEa=-J*CI7FTWY)w8|BUW z8S8%q96#F#8jHRJFOx|SYfYR*i7&$`sbj`Z=sYPoPFLgs-m={28RlpC>Mh~}1>w z$}_!(XC$6CtSF(&zB%s0EYQXsFhe6%MxfC=BA1Z3a-?X}3Px;5;fOO7+JLl3118M^ zk)SjwI)vqpI7Zpv(HK^n?WwqiBn>;fy;?j4{7o4_Xl<&H!H~x+4nv-KWY}mxz;H^l z$2oD9gYytmX~z=)^O60m8iYBCj@nWv14daPA((r1RCm{-hIf))d z)!={GI@{l-?mLQe?b!2!a1$F_!KrWkgl}TvJP=bSj+3|q5U^DQ5MUutu^h>&cu1DD z1}%|Rq$w>UGzdeYZLk&^s3R)U7rgKblqy>V6qbFVlkTN3PzKOC(#xWbl72z_2A9689Lk`r>(qL9=4-S9pv_sDCAO` zxQm3zXd8nG9X7-x*^pT0b6K4(r#Raf5|2c#3)EpT$%TR_u)O%3_W2q5%P@vmf#o@$ z5BEQP+K3hA+mWZrl3ff20w3fpUoNxIj4VPdRklNoV|lzA*cZ-Y3ab_fnEV7%Q zGIE!5d9l9vSZov(=&8|sXDzSNfIAt$fMPGe(8wnQenaH;ve@1!a|{}8by5vo4T@YM zf{0z-#? zI)|EzRvE(Q#08%_rpB^Rj6VMs>(K}HZ2o97z3}1V$3=xjgKwQ^&SaXG!kMslX~`}+ ztcwQg(^Wa_R;vh45%nz=J@Qe6*panBi1~)*@TyO|FyiZxKMWnN$L3@6b@{R`&xm`$NH?D0*c9`0k{ z0#}e!|F^Xlh0WR7_xLuu)yzhMAKqq?DaosR)XtT;f*d57Mi|2Z(dI8>D;Vh_Kw!yD zz8D%U<$}uqDog%(6adBg@NSPdI1@98_`&r7tVSe5&&UY0x8aW8-nR47q4&G>FVqBd zC}gJig7X#ch+qio!gbZMy?_4?jP3&`L$NPD`1pg5uU`M_)$8Coe|qN=rs-0E*9Ic* zu=Wh~dLdFo0fw^vsiCmHzp$l&wAiAyfK-pR`^JrK@x_O@OZ(vOKR$i-&$ahvFZOK5 zJQpM|9*VsCFHzd>E`5JVl=g?`&;R}M<(uzrJG9 zIA6YeYGCK~<>h@ZBFn>(*F|w7!`qdfQVju}yf!p^Wmr`JLg0OX7TFM7akxX|SPhS> z621DX4U-E(iB;Mf?~r@Q8Rm8KFArgUr(INglHD#y_6SCu3CAMxK#Ia<6=H!QZsN@M>eKNsP5%tLh7TEQ=nCXVD`z7Re?oL$-_&YE?oy zEM{dLo+q4rcE}5{1D4i;9xxM>Aix-`LRZ(bs98a_a>zI3h9?%r09!!d@GN-XkF#3Q z(Skq*O|%$uR-|GzX{28P4V}$;ik`#*aFtDsGzLsZ^BtItF7|(u*=)3!Bn>OkluBX} zD~Z$vxZ8wS*`hAeT>LsUgB_(J_L3mTaLUmXhO(l>aM14RU_ux5D2SCod?#I`!lpr@ z)b*;!YXYndy%>!K6)G!bmwV3y(_mrExaFSqwA?OuJ|Y990k$-oK{Bn@xN&M+30psn7D zH&|gju^uLj|;UG87E(|z&bRT95BDg zZvYM#SAH9F3H>kupcK&gqUDRNBd2fP1@RRJEU#Q;c?oM5_glu;RV;5{HyEEV4hKXW@6^UgHJj56dd z5;VLY*+%&Fg8}r3N73$N;TvPuj7DN5yb~x6vCaqw4h*tGOb2{>bKi#A^J}kGl6GvI zf`086cY-&tvHBWtto51b-Rmxxi4DIozzd58FJgDtrXsTN zRESZ9WB&GfeYHL>B8+d>Rlk^T0ddJS)U0cH0Jn&~tkot&l>=-GjBaFxemBR5Pc89$7taD9sp@H=kVC8Y|K7J&poIgJN@~El6y{0i%C@eFa5OIVB&^P5|D91(-+gQB} zhN{nyXYD+~37w!+`Z3z?Yxfthg5+ee#}63m?Yph!bn{3f1L+7E9B;D>-NQg&$}seo zmFiP}+xz~m)Z-AuqC+$YvGG7*UlXP4c>beE<2_)au3o)<=l=Bv2q{9|!5wVYqEY)f z=oO#e*mc1iLjLn--~I zFB7dDk8=+gqgdlgWg}4CYePfI5}Q8`D9;G&@HpDL!`OWW{yBba7|~ntj!=A9{uBA_ zIH*>mJ3^s@9S1|deO!idK~30(r4g5CtJR8p1z6OQwrDl!MlixKq8PHmehISYG!AbO zqHbBls8o}PIcwSShsTQ82^CG&fMZ}R!xOFn6Wy?AS=7W7TNs4G>;+(@9UAx?=>Ik? zG-;?TLxeq==qPS(S!gLClcDG-VcAzim3S;o46Y};K<|r&FQ>2)P1ywqa8itLBB>#W zuvlbw7yaJ^+rXesic}ZL-Qc=WQIs{=^|jnfylgrNNseYy+zLjBVG>>6WD)~dh$9r8 zb*JRtKJEa#WKxg1#X+Z&;Ad5V<`9pZO2Wj7J?@Im=*SG#t0|G$v>RqwEUB834p#LU z6qmbnj64TLGIhE83_jY^RZ-KF*UkhbXfi{8RTxr~8^LY{`+DhlIdg@e2Xt-4-=Yr9 z#&BDZa$RYwVE9?S)|a%y{eNeN)i~&Vkt(Q`@w)h>LEB+ISfRjAT3wu2Llc=*^kz6 zp0ijJXaff@moGLf_V<)~R# z9zX=)(Sg=C`^7S74x2Cbu+>!HBk;!S%Sg%#iwJ*VVB8AyX9GD%$h4McyCEjnSw^=- zAvxqUX+yUKEXtUiD)W9~p>KcrKf2EUr|mkA<11|$w6nA2Af|i?{jz=miWo~6rG>hp zVRw3RdYqWt0!=X_Hx+K`ByPVfG1J8*q-H+=001BWNklLpeDw}Ew|jfA2d5- zAd61V%f;*mv!8VPVY&a~UXSPdQ@41z4qEz^ZInLye7&AuFdex%Bo}?=*hrB{-v$y>}xD}o%*>I?inpL__&D!&2+@$1b@MvaTz|%OsM~WUdY#k9@Oa4A&ztXytAI?+rPR7(5$j2heaeN_K3#6)#e> zQ8%^?hYrxHqVOv@kOCziuHS$`Y=(5Zfl^)Q%%EC$ODSQUF9(Q!u7l1ck~RVwLbL15 z7#Npu83DV1HUt@*E+hv?-|&Rcg=F$%p$@k#&{C*0j)IoJ#c)O>xwwH!OLJu6H{wZk z0NeE^i&qQOEXZz@46`5(7y4p-R0sF9x~xjOzO_|l!Q#R(3ABppB#bE)S_KQO;q%F` z2hB0Ag5k!)vGb~7FhU#eXL21T7aBpc(?+YA5Pm$?YBU%$w!3soDUGF=Fv|Xz(@k?* zuJ7*O6Jdm5Z^HcclWr(XoGpF?F+4wLBmfLbf+0x-m^?@DA+gX1hS(9eumCoyyQ2|w z&@T4-JG^?}U>nGb8Y_eWN$JoEdTyryIH=G)%246OY{uqczNy9a`9)_-T1**NMruWD zki9VFM0t4;%ceAFrt~+L?abwrU?7!gb}^ehI&Y_!*a#!Jswy2?JqtM|&RLl8P?z1m ze5slp8tOV`kXs!h0lHkR+3B%khRrpj#qu55m6wQsCWW$AUR@!m5-IbF6D+StQ04Xe zt~O=R-gx=!LC1o1&h-#_+*kVNA$e%%LpnH7_RLHxszsvY2#{7QVOeVDn#+zJ5)rq{ zyQpixs8n0+DxYB#ZG8RgDPzEYoW2(Y{fp)A-e3J6;_Ho~WelEf)-+7t(?lO?I+Lb< zj>z&NIv&y(C@q%lCB{zT(NU6dwKd1J695kLR9y?)mKppWoizHV`%lCQI5N z_+$Icxq9Nn)f2{oi^Yu-8}^h32$JJ~0e2{K>NE3u1^zF4vIKw)+pO}91(C@<8w+6oS zN`93+$z*x-iw{1y^4UK={mZBCcl`Yk;qU3gO)b_#O#qf3=?Y@P6lu>yVRgcL?YXN3 z3V>Tpts4%P?JPr~>^$|>srLCGDbb6$vmZSL<<-g;*qxe^sz}-^A}T%Ql{oT@%fy;H z_0pb)lV37+O~1n|c5)J2=@n}I_?_UkY4CaD=QVB9SNr-KPJ8^WjI{4wxNz~Sn|EG4 zz5CQ=@b2L$qPq@^5al&8?k3uXVwDBM$8(9qxxocctl76ji()?E$&u9oF*)ga z@1>p+=q4(zRanm6-ioU_T1Zd2QL=96w8`luX|B_vx``gmjFO|P2b6gk}I;;@tn}&aORy9hn*oX>(8?+)3 z&S96$`l7zZreUZ7ZApAL+EDg0RY`Wz!l;=ed`ujrHpxj+2HJ>yMKh-3ryk%yhh!e9Ha@ z8Blj0w@c6WcaO#PM5$c>WLc7Yz=i3*T z5r%4mW;DX60_(p{`?F}2BDHRGVY#zfUR+!UcB=-s?Eo&_gjj&fxigr8jq4gXpOO2h zT0PUHk#rXnxY~8BT+1CZT*c^{9WoZYDn)UP+^eI|VWXPHh7Iv1#DOJDmfm@y%e5J; z)D);8K=zU-Cp`RZ3UEbioBhCNoli-m*BemR7)f`bhhCK>`Jhu&3*cAX2wG9p0$)fs znHy+}$_%LOje<1UIHI~>!0(Su@87@o_j~v5-`h;%X!?Km|DqoFe=|AmOU9b^AlR*e zADwP?2D^x?>H9ar2&3ITm{ByMEbK{t_*okL%Hxmy`jy8X|Ba#WL_$u>g`-Bf~xP$$gGn0;PmIgLA?S*AC>bv3F@}ZVCI1Zth-r3o_7w6Go z_-pJE-Ik$o)}^}`yzN|bGI>7Q*J->&z?EfTY)EWB_Dl9NN)5k!=+WsXp9!Vj46ddh za_n~8xsb-k=U(jX9i1CD{(0n7`$wX5M(Rd90rZ^9>o_2())iu4{Pw+;Ra%`(Re4&s zqb%evvq)fh&Y`hgD7|5)Aux`-#g6yigZe6LLwOqqocTyOSR+cHM4vUqW_0Snvr{14 zL#Lj2?N9M5`O2+(>=2TvmFK75z5B`i=@yDZZsr~vFTUVnkKdLM>h4`5wcp|%l6-JefRqA)S7HQ-q9N7+I_qG_C0&u82JcqK<38hj?9gY9+?>( z99-zJw*#Y^^CldKRvfX`@V8ep-=`~ftiP|fhSfK&IL)-2&7?l26KQW@>nWA(YeUe= zI}lyB?iK%aTVKO>*9?`O%yYZ+*We2?qxNTJ^vK}Mdn@Q@>?KcbBzqwZP|8W3QM6MfubN2< zpj$MUZlJbu8^0~PQ_zKVL=<%8i*7~SY#QdeAK2~>V;C2H0XhP29HrDV5rMtcpx(zP%>rR39(?y8Im{DwlFLY z5^W52=rfvJPf|fh1hm0!rjM=fKw)E;K8EDRhT*YYKCsc}K((kuNrufuSTBxXAq zA!+P4TpTvojibQApkxpm?{m?V1@^ps%#@39VxZ$O1#`q5+MZXpLLWg_&|r9PyxVT$ z_$_#g$~o>BvY|1~UqCr_oQei9Ty8`igWW=idp?E%v$gd&ZeaYu{jsnTI_zjH?EJ%H zd$yQL$llGS-yhjR#NOt{%|?i4{UN+bq)htSLJ^7Usa$A;Ld0ajgNdl@=m4R2ocv1S z=Z+92Vfm2kLPDVJy?sclUrLeYjSlCGqpZ`H1R#f?!8tKt0-*)M(QfSntv%i!evy;8Q)#)QXoe;OB|&!Vy4gKRpY+`W&_2c)iP*XMkpmKukx@CdS9Pi z@m#>p7Chl_S%w&I$m!(J2PeE;FqxEE^LmPCX?9n=Ea)1EmzZ7u%htL5HhrIA93KL9 z0tUw=qKO^FIXNb=p=~@8gH6Vva?>(Ws3D+QkUCK$0!>CYghXyCp_U1xB#LHh73HF2 zQY#_o1(VjQGD59OyQ@j7xB|MH{vUfk&)0!Yn=!8AUy>%o@$-A$_c?&UdoS*7Gps&1 zfd7a*E*grBmKzryBg%Tj*ts!acEH;%oI3!PZhdvrCIjMk-Z3x+j$hU7*5{(=|6K#S z5wtA9&q?qLU$Aopultf-)HR%2Pv~gugP%Ku-*zTpSKi=^!Z6`CuN@xWa(m0klgCaT zyU9TMw1M!cJz#L_TI<*yZf9xy3xh)rxa6ev zkoHUr))EB_lRaX?l4ik&8TJ6p_GL}ly$CiWU5@u1*^dU=^${K?4$FmM0lcoKL7?1s zq;TuR9}jfjPbwqPn4cTKvbQz3dh+P6e`#EtzekxB-+pUI`{NIvKYE1f_$PL?|N6(j zfBEdm?|**$_=_(f_zyBJ^GQ*Zc3U`p8S(eShsXE7ynFxmJ9g|Y?kJ6xMvJ4FVkRCh z3>F3rq`=qfxdsCjS&Zvzac&=>p_aG+?&Da@&4fi|mvaq!P~H(#5Z0CX3U=ek80smb zyEG!?lfBD49Cw3ckdn`V(+IvA169G-qd;r!X!3kA8B-;LW3)+;V+DNW*!3#Z8T3DM zoe}k*aofRsG&3_;$Yi4L8OF{OxRmT-r(%551^d?RM8htn!pg_ZG{t$FU7%opayyJm`CVZ{)}vZr`*nfy+DUBLBM)#D^O2X7Nn)-10lyua z3cF5VkH3P|C`7LrZX|=?G||uM3l3MD2rH|MXLT)nr&3^mmxXUSDSvmee9E9CFpF()L}F-z;$Q$U#`qf`eG*9aY3JM2G(h}SGxT6K5>zoc!SqW# zk=evqVkwOz5Cff<^Z~@P_R_@?cosGsp%&Qg&l>AR2|Y{dAG2w_pi)qn08Phe2X5=x z_oudf@*`3DJ3BOBAUrmQgO>7zp+v%pQJ^tGhukSi=0I-D; z8y4GjgYIqGYS&jc{g)p}gXq_u3$d6+J7cgDW32~8H=If54k(-hNi?JeV5#tH0r_vW#iH)(P>bqXrHwry?W+L{4z%RPv2 zyZyOxrCVfJ?Mkaz_QOVq6=;cKy6&k|s`XGE1981xsnjTYn5fpPHE*@n>@`5H`81_A zaMrLIDS|<=ljPTs(kGUr=bEgXdh4~94qbRRJT|}g?)Ldoqkf^}bkKHNh)zdy?-ld$ zOuq2tRVc6l@a9HL2N77sbx%_9K2PAL+3krYNUl1OW`n_{$sT)l&yu}yHWBP00b6n` z1X@d+7DS|)zVS()3XhJs+3gX zMk(MhhQFg&w119L3ANbKTahxA>I?+EKFSq)+F<}A3aK4FkMY`oax zq*$%FH0$B?&J;DlsH3N-WFU1T?LxHFOo-SD2HZZZ zG!DCCkGH51m<+7N6pR_i606@~q+60*b*I`pSNX5KufcCB#g;ck8B!+LK#FrI3*+TQ6apN^|Ixclk3*3tNmzJcCE~g|_O&Ij9wqk8%^{K=lJprAHsrmi=#4~M+vg;1%ncn( zAjXmsYi=Jy;Ds^5AdL^(JE$UI{-Ci=3@szbx5&#dNSt3#&g76&)4JY;=Xo633Xe3L zzzT;TX`?}%Nu)gJ+6adZI_w?V+s3S##qfw4fE5HX)Ck8ilpPv7=%}&bww)%}QFBU8-DQ)z zY~A#$h>iyTJ@nFZJ#=FV?b12^9}N}=U-%UhZp@;=;1lnkaN}sZQs40A;cM573copi zdz_{4Nz_@VZz?%!&o(f)t83d@$Gx>K=F-sND;t?fuclY+mwOfep)Pi2o>i`NwoasmAj6(5~^t$k4_4tG800 zDSKnoH89BG%lfr%_hwYcuk`ia{pt+^;L9If-rZ;@+%f8!7zDs~T;en5hdA1Ki)jsI zUg)EB9*MS}RA_syPV(GOAVOq6%m})X@~l;`xUSk6_Pc5Z=F-w&sgZ$n=)n(-0jG=s zFRSuC>FNhu13@nKlwIx9^Ut0c)IQw&Q1j! zfUVG6boES(p>XW_8TP?>vBta>u=!=Vc4D&H8bmIOHAk@RQH$~=h)36kTP7I23Z>lDK@z1qqN7(HHs*h zO52wbH%6Pk9=DT*XnrsgEeyUl6SdQbjDe?d+L>Z0Gh@_NXj>%IyHG$F#uRZ z5%>jcjqL)@#Y`bSXrC^wD(QUg{QaOjnE}?fG5}B53#JF@OjEfgC@#}r6Y#pEeP0O8 zE3;|3Udzg-3sOoM3V02dj2(;WP+$<{0?+olWI#NX4clQa_?x91SPaQiJ(hIHaZMVa1w}cib(gL>yiZ+&CrPylK)KR30I9+37 zv6^NFM^FrzM81%iK{F(>X{JpG`eEe5PGV#>QRB=QC-Z^*6ZY@f=bZP#Oj~ICwp@PX za?d@_bDnb;2Asg$Z)8-tO(r6v5&Bd{a1FCe4U=fNM^lV-Sb!EPydDu0POYl|hHxb1 z2s_pVU?XmnqQi_x>I%748Uu%b*Hf^Pj)cO(Rm1ya#38nRA-!71{16`c-0SNCx(Y`T z&LG@2D`bj$p1>t`-%Tm0K($FfEXqi=o<#2*TV_e&kWUX2L5ALMu}kvT(}|8cHFb zP}WzNFoc=k%nGbG*!)Ee8kUsu`4M}!2nL2_IP%{bVUun zSnd$hw0&mu5xuphRW2|!(wIo1-7|a7&{>Vp0}C_Abi`C9(UbD)v>Kea(UeUvzqD9~2W?GFD6zBYJZQEGJC;56GkPX=S8M3O z*}tDU@nB6uNXN@}n;YdrYmLJg;Lcf3^5lHbGyiQbB68lmJt+VH4M6h0eDS-BM==d* z0(gPGl<(vmFk_lb9<+no3j9_CY-6!fC0YUi!$~F@eIX~10>vd4{je$l?CF8coq;Ts z&m_5)+cQ+r0>B`_RvIwgkR&h*8lwlCdb>^3>FeMA-(8CgW1)MVfcxFWivZf+gPuQv zfBYA%WF;HxM7wsl@O}3%Vvv!848tddvZ|yFMhS_rkm?>`!lzYo}Fe*fV^xjh_z3%-Jw1w<-< z@d8-|K|c$+3iiTJ-&}(=7$uMjU zFNS~(d7Ku&P796o(k~ifELcwBb*3IIBDf*l7+f@%K?u7XVY_g|!o+VIOrL?ds6r17 z(i?hE%_qr2H~f zly5`mOBKR(hIQ&rmK^0BgNp^ryc~;3sehwfZ9@q|R zEPKFZFM$%nl9Ktr-~#Y_j&c~dA|y9Z3B>&ViX5$C43RM_kUBFMN$#vjhG;GqH4#1- zt1O}I>w@qKSPaf9*bG3;;;Y-S8gr0eZ0p4{FQO3APe6pF|u)o~9sq>a#GBw7IeI%X~2C5h~N0&Gz;N zJ)YjIEF`nZ+2rheXZg-TPyEWic7Fct*Y}^^2p(_cCj;q7*R3yCuYPml>vIe;WUczo z%Q053zp#YVf5}a<{5b@Hl{?m9@K%sg2;!?S}0VvHB|T5);O>oG@6>+YegKYYzKnFa_(6F z^2E7QXTP~-1ai+imS4Vl|2Ez^b&|E`sUs;Cy0NpJS^QOl7kf84%8wsE1_QPLcdHm^a_Wd__~;T0&*kK@B0GN6U&HPn^Xt)C)b0`n%wDg; zU*$td(wkM*8?&^)A`6~X*3j9)QvmR%(-aQFjzU4NGGgpom^uldotpYdFs1J&VS;j< zp;J_!Ww1!!V`A<$fHThfKIRVepgGHFpS~V;m904-`3B!J{cuM0c4w>{M7li_jr;GC zg?IPJ10l+)N6U%YnfRPA+kUjGL2Fr_j>}KobGIjcAN6WVl24Q1@|zO#I020K1A0bw z%TGQA3OX#G`)mia+67Qq@K->p04%^2&xGer;dDus3&7+%!h`Ri zoIHHz&KS-`x`$=c_!F?59fzgKT>Sq1hyRqzl`G>{#-RsLmz|xR+T~IBV8K;GSFJjP z9C5%%v)PNqVj7Q}dJ~S#Yyks*o4Vz{pz4mW?I6t|#npt;g4z~=?7D(kOspW~0a9vj z6T?MX5wlKSuTA+FA_*9+;5MgbRGkoG!P{A@E(#WVL5YpFs-b+K3A;dN#xt<)Y(Q%P z<_lf4F}T=ZCa|pHl?E&*0lu);;8@b4F*=xTGhjhUC(5+2-9_XTG69$nJS49rhKS1P zArNIKvm%ipWk)&6Nnivrj3T%+of?%FQUcJCAvd{jDv=5?6A2U;wi@i~0zxsJ6iP8D z3DxL&I1~ycLhBKq0Ck;Xz32z;!zC->PNDn^uMKVif#tM_b}+3_pjK#Z-Hk@B`-#Jc z$Y7ztaIhBycEBN;`ewkcdmp?v7+ddle39psetB z(XF^?_I$x^=}(D4CB5X=?Iki_g}NL*3TPPo_1iz{x=StiA-#ew+Ql@&QYq^HEQp1i?tKpu{+E2ENRw^#UnJ zpj4jDKmxtYp6oLD@7D74mL-9v3$%JdB^EiZh0M#-E5O@j>ZpYiBc0Ilg+NC*GY!8h z;3|x>_ybVp1(e0)@W>=*kx-sSM;JyRd2VjL zgV|s*=m}=Co@915n}nT%9FM#EuZ-{f_%jIdn~kSilTpox_`bTd`ryXb0*N<6)##VvaBEkZ}XHQ&KCLJh7E4NB;;TsH3qFdGt%c?`o39p_x{{YIYOV3^d zgypg;I4l?}IDAu(SZ?im69T{O$M+mR$nLy{|APIH`w2oF>T-5mum44;g@A{Ifbk$( z#URIv>3TyB2#xe2?X?VKFf|McxePC!9$>o3Ie6>BDbU|Usl$A}y!CYB{j2v@`0v7D z@R1Ot!u;4+=fKHk(rIxZGZBq_V#!8_-D721P z_JfsD$4qcKi!Pj116d0!%>;$*M3R&7X2}vg(F6!_B#ZOKX}c7qMSW@wq*vE0?U;#T$cw)u^b%CIxxO|ZRNp-A74Ir z#tv2r;?ZGmYw83>Gv)E}=%Co?SQ#28nKZg6q9wGi1yo&Rqmvj95AT&-f+NoyE;}96 zC^?t^UQ@)y;3$bwV@|j{>UA8A4VU-4RW8D)879Vh3_`2hhCo$oSw5TGuC;2lDr)O| zK)Q-RMzvRV-vBurScL7eVVtyi+|ezCbpP1NSrq3ZQdxJ{sH(nd;_OE(T9I_8Hnugap&rzGpgH{ES|IiNs_BxStV8oa1 z1)gpg+-_B)wt6xsO_4PD6Rr~)pK@tjPiSpl;y?(!>U@*vqz|8G%z7o3*< zN(yH~;$%UMNQ6a`4LwvKmBXb%6ZK34$IehO0GK9sfJ)&jNzoAna16gxhNJ5E|aeJLg1kOj;36Ghr6Y0Wu4tF zvuHd>l~T#jH?y^_EilvQigDca-n$hw0N-7&%qgy;WH_u^UIxh zXM4$spIy2kfesfoy*ac~XhE2nKFgd$B<1e}S@1hIvDHguu$yS>k9N=YK<}J00k;Ov z&JSf52wUo9xS(!A+^iE5pWlCCfNP+8?dC7P{<^<-=FFsl?n#ZL4Sr{54V&%bB;De6 zXSRQKa`O7*Byg?R+zAS#sy!xfTvq3)b zrw#JUFL~_PNaPhSGFqyvx8x9J8ck}nmzMR8GbsHH7&a>WsSp@-^w(EEy?XW3sjp8h z-FWxir5j62?=QWFO-TWkNAdGe;iLF*{-1E_uS6}_$op>-?sZ4zS$%6-9z4+#~ zCw#ux*D7O3T|C=2o9au=oZd+F_oq%ii{5rS;8sqh-cp`z>6^|v+CeARXRsXOhquX) z$AFf&4T=5H_}5~fur$;5i%^g4);|#gCjQFdtGlO<1R$SnWmJ0n7+@ZJ@Ycs4Og~eV zkHkvlvbO_Wn_(v^OxzPqr7U=lUGebRX$O?*BiI{thFbY=C5#$&OJw4qz~9leo7L7b z*F`iA%kMMhHT;g2Pmf_5HvAm(nClpad+4KB+OAb4hvFSI#cnICB#arVh{~TCryXU= zYdCugl5X5~Wqf$~7Eo(2YuJetil*M>i;K(4sf!}FjEfhwFhG*sx9FW@kUWoeYW|{O z?TUScd1JOKtbwr-*#(AjsR<4P`>Pw(JGbGt=iWAYE4clG;Tq)b{~zK$66oso;)VV9 z;>CBDU-tV%SbWOLZ>Jf7@|qxKPKs*|nH+|3odCIPMg)@~eyx z!iCr>_^{iLyqQj5xUjL^Zgdscf2VWEota_NRv6CP6Z74yet}>=_MvbZe-c3){u~a4 z9C6V0EP^;F8bqYkFtnw*fuZw5_P>pS+(!9it_VKoS^pNX`mzWvl1Iy_fxN1NjUzKl zrYz~eh^s1;ig_hWQpzw?Ocuz6J{TYyS`A2uvWzYdz=xBxuiay%3&CZBi|c4e@XHEV zHNZnO2!9cg*y@XbqOb;bs8w*)ghWjaFmPthd~DCa6KvocH?$s-2n!UBkd77aVIeHb zl8Oi;iGl5Hg<&OdDkTy<=M(A!j&LHb^NADQR3k_jxUUV@n87iF=yvxb((a--09a*j zbQt8?1OMs{2BRS*QQ9S+&&aQ$DB-`-JktfN)`gBB_^LJrR99~P91A%(?u_o%YRsEM zF|v$m$}`Fk1Y|E!BfBGdg`$W7^JFd4%wR=|HDk?@jDVM{`#KJfCgZ(ICN`3#crcUU z^(@O~H>=P|DkX z_x&$3=q-%DnoIYphH%bxBYEY&5MEc3#3%4=*hRpF%0%xLnUt5dln6cX_^X*W`p=wv zqkrv}|NQpf-+lpi`;Gigo;27!(|=}CH$z=x!jmBK$yx688#}&+{AO~NHks?Q*X<-3 zMXB-8+Z+3jo;?5lpU=L!|9EpQ6>4-YK3on`L6WQU-rDGa^a(%^Y0(^9L0}x z33(K-Bg5c`{aPIl*>99I)5po7YIAXvLqYJX0n|`lQ(10W^AOHtv9o^PRShjktg7dpYS@9XhPt!Q8vQ$$B(Xg zj^DG60;gOVVai26D~v-^>FcxCB$GaSZC(uc>FKhw0MB?cTQ@D^n08 zK|4M@R(6it8AvJfW-kC^SmSJ-GULX;%EnN{^l4W(Y#*u|j%h@z`=fiZ`=E=011l_9 z+gw1_C14DX+c$A@aQNo%XH$bh+FMhaAH!>nmadG$P}#pa@ss`4E^COqsBY$zrpRn= z`}&pv<34-3otj#fPHKM9O`_+=4RE2iH_PRlE*DF#q^gndvFe6#+uL{S?c6yBxPQXi z{YSq;?i0N|@|dopyMJJ>-JZMKj|+c!Gh`s!p^RQkBl4_(la z97l$@tG>{x?`Ql-ENSgz_|Vhhcxz-lMTm6#%%+Va`3?yR_O*6~BGf^q%7;D%JFuxX zxs*tNCe&XcnLqnQiF0n~Y*(N@rBnJH2ewBFVZY0QrUCe2Bi(HuR(Xh;27g+nqcG7} z;j}+&XzHhifg}zxq0_2C;+^4Y?jb^GKi9le1n1QgjP|)vgbEi5)45_Hoot8(7t%vW zo{a(*e=6VzF8q|w=hV^Ako1ZILi<24Wq~`8;Jg9!z>Z<6Ho^$7k~=80>{Nb;XpR8B zqX86IMu6?WUJa7lb`UY_HCB8)uoJK|0U$X5{Z;*MSJw`@=B|Nlw!>Z9J8_~Y4N;2< zu8iY3a_ijq5HPCn4wAB9w-JS2#kKIoW5jwmkcbS#T{Z{v=mb-1)K>u)Qi%}VkF%jVp-7^3U(85MWP1eHzfHpu3tKj7&+rIimG!kSYz(oEHx$gUVsbCnL3Jcer&&jcr5MnrjhXs&#aw#NlMCTnt zj-}LBQ6_Wjr0DR8CR5~~4lR}=$p#{DRi-sZ%ZRf=jjy1fiohDu2GGc%RK8#4ZlKtA zFEwj>)N&NxE20~qQa`l@Z4#Z8NMJ7z9ckw>gm+f(_>Rp%`_?@LweiWFHG3W z{ji%thV8w^y}d@4ps}E^Mfr$*7C~XymmVfOdz*4SEWG%kE0NgrJ&bJ%SC-4>xUgez zWA~*|OrKAC3?+fztu=w)m6d~idVuLJ!Zeelb}|4ZR9o`c{f3PP4=y7P|vhcXTC3;YVQmT*zo8VZ@HA+*2thv@u;tkB<3nGS{J#V?nW;Yz454M&s;Lf?9V z4kS|EQ)5{+{z3pv3ou)d0$L{4nDQaX$8@a;1NOaA3gZ)LRfPm1tE5qY(i2_PuhUu! zQ2HkhpONf{S^=$|h~^%7SnQw>s)Ih_qL5c5azbuYk%>{`=~`|@MCqi`YM~3Hg=VX$ zMJ!`a+n&a& zNRt(-UY!weDzqx!f-&_V?MBS@kf(VhZYUazVQ~vVcTSHYBs3KY_6F%r0`U#Du=y9e z-=GyE=vm}LBMd8O{fLoRLHGebiq|VAuu$V~(1aA!I+0>=5Mp!#Gch`jqQcmqD}hE} z!Q*=2$-WrN8RAH;L=x5@m%=d=`3ffvLhy|Ja2#Uj7-r5W|Aj-z0voW;Vu2KT*~0!o zG!dc<*ax#OeM|3rfK{Qlwpe1*W3wQKQXq7BdD&uPQYD%dT#Z`#GXUI@u-u0{OG8wO zv6SE$kZi&F7YL1@EP3cA9kyAhhHkV$T&q!-RMNbkH(TV^^ncTrJtQuehM?=Qdoet3BJYqm+?)#>ca zzFpaUl5HPrngrs40yoK>kYk`SAlEs;2Y}n23GIGtOncnJr#;zI3W>9fX9~!zEtB5p z6Fi2*dUdN@G1j}Aubw-%urPY&`w zT3QE694=jags_fdFCdX78|G4YO3AalNU-ep0)o9>?>5T6wh_vTt4l74EdXKMZOc8> z6!PZU^Ccd7Hhn&ZZ0*VYrcmd`W9QEv|M<+cX1%;tlIx_uE2}GSo^3Gtxu$IX;O;#& zF)$ySHT5+K0`GGN3G)=37+TUSX@qj)JeJ2+?w;O6gQJ6QS#uTiA%O;qeZIxLSnW87^SHm>$nmHK|uu<|anc87i32Qv@y3$gPo?-T``ifR@xmjlfY$gDtnS1N3{% zDAzSMw<_pjppBbbx^E#~7RbwbeEG9~!%U^~QG#$B+N@^S^)k z>Ae;?X+DN~Q%;|G_5kac&C#HDI8X2bs!3Bj%3yfSA>19HO0~;8aP^nkrOhIhKN(%^E(Ky(Wp9Re7(Z2xwmsKgP zF|VG3I~bZRlrg{#3}j|yFk1;*Z;)8dOmdxhV#iRm;5D|?SzHjgji5{m4DLK>Y&FdG4TktT_7 zjYi?UHUV(>kr0`M#v`9AA*d_(Y_WOBh`IPhITCiqjmyZkvf;yQ_m^!Rx7(u@!#3U! z9o_#gTR+mYTnRXWZ8mqaSD@MJM)o9-9q-(56H^CW2Q?h?M9p~&Kjiz4Fb;%^;@kV! zIA^w+fyMB(=^9kAmLAdq9nv=dxMs9V3l3uj4NBZl2}0;;D5DX56-Jz{$sgJoE+LjO zRPh6UO^D-A+0VlQvZg{RB%Bw*t8l6yxEl@aIKpAUQ(?eM$exTYg#>EnDSZwtg>sHm zaz{w-u#jNX5k?)XMOuVdOL=h_(~*o0Q4Z}GVoQQU8!Ok;&#F_0Bj_A0!dfMg5@C@8 zL%3Cj1qlF)g)z7_Ivjw@Wqi^yoxcp)$Sn>nE+sYnmmDi&28}`VBI|`2Mk(}K@Obqg z>+J08X(|c;AO8IF;rl=*N6pSaz1MT`2i-w9*4j-;y*!CmrO z42Ux)s?|&tOId-gbb35eMF?_76|3ALb1gbJT8?z6w!dmxr9cASg~)b&ee5L z?KADY2xsiYs`b_k11u(io-1>ZPpcl#f*noI_U0$c^8NiP9 zEk?8mqwg0fgV+lr8cT?+b?$$Zo!w89c^1cQX=?@S^u;z%#!^~sd1))`RKd2qSvBac z0^32#1a_%aSr?VU&NgnQHzXuv5|WV+C7GZXh6^uc^GtB%JM|rD3YIY4tyDLLVFu5c2n3jf z=yWXIoyIDh6!=8|9os^L6>9>fkz7&!s|sqtUJSrnjwJ5hv<6iYk5x+>_is?xEGlVs zzCm39JMaq&s3MFOF1$s%uTGF5#xPeoBEL^Kb4}0~%#E~FLtdH;1#{D0FWDVUH4}Qp zFxjgmO8OW^frTp=D25t0d8>p$t5z%IZBunu8}&(Yc2&EOK#7=(N)2L3x)D z0FJV*!R8`yWQ!t!g-xOr;}7GvNac^aS`2JI zM&O38u7O4;&2-JLSnC6jb?_`?S4)tnhY?m#EE39L_sIq8JB_Z#1MH)eP*Zb>)ulvL zsP256U!C&{xwvm(L@NjxKMVFoe~9K5{lsvPxWNWE5Rb12)m=a=9q1$-OMZTl$8N+p zS{}azj210iH~;`307*naRJDFVZdn9ckWnGS6(ErKs|0*>DNzx^i~)GSh>`PJN0>_- z65l%I9jL%(jmAoeFN@%frMg#m!04}dxuWhOEs$5Wmi&1Y;yEDKY<5B6rF=eDQ5Uh! zs0rn&1hk_tp_;5b;UEEF!~;)X7utpIHsAW`AO8{n{_*FVN{HKAd!293dY)Pj_8z=? zUV80b_qfLqW9jUfC#`+$!+rI2FzBliEdk+H){K1x9atAyhx_WlTewySWxDa|0L_RL zEte7N_V%`%p1R%B_2}H@{{EW-A;|05xHS`O`|Tyc@9ug9n!^q` z;N5jNcKLP)4r3+=0?50gEPwwv>aZ`41eTtztt$R*Br=(o$L_W$|2lnWD>4C-lmRXU zOTKdtuROeR;J%`nnY^$EAvr5 zvFC!mps@TGST|9WCTX(QWL+us?bT(lT9Q}mn3N9eBx!BM&I zGE!t{>!U%C^&XiO;~HGiHF#=VgQJE9Z)up6ilmKvmP$17?xmY7^<*c@}eyQ)Y>{|#?KShCz>Tq`vL(U6dMZ8 z;udyUw&h&Udny=cRodQGo@*_~GM;j|TzVpKOC$bhic#vGtniRui#F=tX^EfgoqM*YC6PbV_e+p;T>vfE zTWhKb@>b!vL`??U5J9Wz${P;VSn5^*U~i3@LHVX1IHV7bZyfv#7XWw(f7Ti#xw(;F zA%t%8Qb))?KKUvt$+M`Q-KlSnMy+XZTAdyfwZSe}HGYkD3-SOCT7~Xf8H|v^A&0h| zWKROQ&LRt8ojEJ|`g9CUN3x#5^*r#>tetVHk7-~?wzka!f$+fFE z-)UkwnBNIHFUSi;u4@ZSqNBnk78bzTdDULA2bSB56_&vx1aeT;us9OWlTA54qH}0L z<=n_hT(GP&H-I}>uq-#C-lK05+7ZkySQD=Tu-u%9;#d*R3F)LhP(V}FSDNok{n23+ zL%o!NA+s?kEoF_nw;qV4je~W-MM+)B=U2$mGOh8#XA?_oeQ6zDqH{Q}GifS+2bA@$ zusj~2x-hRT4cSGsVfppfea-F7eXX~DQU?6v&$rP;_g!f%lwNn0*Ou1SeH&~31Iy{n z+0EhR`c{}3Gh`U}?K9h8;lKi{V6i~!usKCwSD10Zz_ET6>hn{7%E*+m0INq6cyM+9E>~z4-Nn8@qR} z-e)g;W2XGwNFe)^>9hP=&syD+j@6B^j|E3{9kd+iEwuK{Ek!av+--l@{BX}Q{`J=n zO%m4W`mh@E+oD+gawHlRavMJuEzZj)#!i3S&j1>UVJCRo+37dg=h0*K=se|w^o|_U z(%{bZP2)162#LF?-d=s=UK@bH;@)dUkENBt*T&Xv961x)GZ7WgRw27xg0QEIPpIqU zplQ{6G&uf9UcE((qspSS(O^h>{}>_<4(TS9NRHb*##nn(fVRijeSpp};Pbp;uv(L> zcsr$bpSe2b>hwSt=j?LF&X1{B3aB-+WH!Jz$HqE79|LkbdU|w_Jfww2%)n2Q-+XEu zcaj=`#+UDns{t3#y$;9yI9mQNVgBSv9f5)PG?q093(Q38JmItp3~NB8 z_N`l8wgz&p{swy6V8ZX64KCLNXSyf~hVQzRC868F)eFX2tlCa!r9Rd=ftK23oWMkM zcwCk;U4>K%0=k0OjYMJDEZr)7&e&Y8j6y9Hz^(>%yEdyeV=0;J4WYyDXmcPB3)fM% ztvjZeibT4k>gO1qf>=tY)SA>$(j$Vm0VVTGgai7EwWt=9r`}+isdOmfpt7MUxD^Ujn;1Sjwh&4Ot28%w9da&`tC}_& zIjVXHcdtOL(L6JEZo=gx$AV3AVpTgD2#NN3ABRKXwyK6<2^NPP45azpZEkN>4m*w< zjxDGGZqQ+e&|w>%Uz}v}&pg5ELCZa8)9EMCAgt zpye@o)e>yQ_1j6=f~G#p-J<4h%$vvgXjE`FAl!IyfwgZg(HT#~b2%2ifjAN@;llFt zMMYlI>VMqu1&#xn1g&wDi9nW(u)wfFCn=J0pn^oIvSiwhFaqZ{K;Df& zrQS?vGAT7rL;b?)Q37;@;0mi{9h@L5Izh09im=Qe+N4p+UtP&(i37>2>N-I3Mi%~? zH5t`foTPzS!j;$G6#7VsnEGcOfLn(D-r6iMI~JO}bm`5rxP8^0UEQnht&MI9^DQ(F zx3WE| z5@Tk7=*9s=N@3v(z%5K)SAN^;qrmc$Loo6pZxYK}ilRZyb6hdg4AhZZ_+2iCe5ta^ zyeO9!1b78>?@bVOKWI2sLeI0VaqExwOD_6;-+P$H0zo{)&>p!m34kq4YN-50 z)D4I#U+*gQviFnGkE#M%&IVIoIg7=@XD-et~|+h$^JKKAv? zMEizN-30o7Z_g(Z=1W0qU@Y1h+8bXo6`Bj-5s09{bU}hGeenp;H`~?Nju~_|i_EFJ z@F4ZGBB6_hAuM?zg$DgyX9IAphEP=!)^azn?NxbLRBHjxapkTGhX#Ny!2zr$&V*kO z-G0VhcF}S?h@S`(XPA(o4pXfR7>^^yi(~S}!PUJWk~f+Me*EF5j~_n#^@pC`=HOUx zxUQ+VviD^8`A+H}Q+)kqaq8Ccr8=N*Z*wp8&zH!41!0By(ihxo*^xkgg9Ksjda)Je z0ys!qhD3{+pk9Rw!)+D}v!O>G3<}-zI6D?=XYin{|U&ok@df;)`;Pux21b+wyaSpIVQyqkz0UzGnVy8hORpDff;u!u01g7U+U zq>G8Zhht+8tG3g%ENIZZ0;%8gLu+wdO_=1mfjMMt%+Kdpwi%l@6Y`#OL+G#(xGm3M zq@Wuc1{D2f%n-6X2PxLdW4e%fh8aJp{7BXXHooJ-ZFDE$Aozmuu4cOW-H9oGm2xDE zY*CNPkm8}Wp>yZXw63)xY~sur3{`&R7;k!3` zN3V{m%gfIY#=5#Rm<Hf*(`#-<=>;HD#{GU%xSte(t z^g1YK))< z7=-28@gsdhM?jJd@@GIU7Red}S-j~JCOe6%!c(VjGlPsQ44UJaR3wu`EIW!8kPC~@t3Q(Jb{0Fq zm7{9%oPpj-?if#ZvYL357;m5v+Fwb;Dr973Wr(jSMVA+L8n0 zLa47Z#K_w3gqB*<`A;vs=TSCqX7%n}-VJNkP42Qzr`Y;|A zQmZYvg6k2=(SZC7^Z?7J@TWq9k5Lte#wyeeq8SM*eg}b9V>z(SXckw=X3)^)LAVRc zjv#>sIP?9TK&*|=HhPaheHr>JPa!yhUAPr6xC3^$1&SFrAS5^M5&We?IA$0LT9pj9 z1Aa*(!6HJ|G2kOlX*9}Xu-Y}DDY&AR0q2{UUZZYRv!=wpy`cHbmJ zcFSRn>|ij_${;j2CNI2=42#a1zkQiaG=9wzh7piq5MUv^cjYUBx`KdRFxmEJ&5?eU znISj()rlOKl}1F|5i}t!DZab3Wc3m%}_ra10K-! z1cpyV@*UgWz9ZM;$TGNYF9NazhndU4(KFzwTRx_^Rn+POGnPAJUBF;@cmc12<-yXrdv(uyZa(D@S zcO(RPcPX)xjMmQ{pISs{rj-hEg2eck%FC?TkWVO07k0>tUrv1ixABEvTsVI5>J=tz z2?Sp`-!1q5Y-U#90R6SJSF8QL`l(y6Q)O2625O^Jt7d^5SD1g@z~Hvu-Pinwy0NN< zHY8+01Fc>ifhaD!CMd}osLs3h-P{AuVXo88c$vT)N6aQ7DFbeEA6pjrf+IkY!yIan z+EF#K`ox+Q@U2TvFJ*23cSFeCj#6nG5DVt4J-sZr+{Zmt96|h-Qe}riWr#OICnHZ?$D~uLEY~_5T zmBQqc7$*M;(q#CITUEdovnJVapF_|jl*&0KO>wZC6Ht|lQ$W=muvkD8fQ&tFPEMzC zxJ?bV+;^yh8O(UZoIL2nxzhsMLVz)3e)8n?Apm#p;LV%2N3W{Y>a$nRR#sMaS9jOf z*Zc39`}+YS;BjQOGuy@Jqn2y+7q5JG=bM?uZfX)P-v|2sKiI2IY1fXxuZHLih?Vg= zY2%8|WgsuZ<+G~SY3CH0Jjvo4OdK_q2s5U`kLp400DV4>z$-cnZNidK|H}>rHWJ!O zCBGlbLnyawemnCvAhY6HxddWNkuBs_e)xiIlO-F2D0SphmJsWViM4<*1k)KGN6S7a zo)ILS@e2#qk$r`7V9cPCum!`Z6vwbS2{_*FMCKKc812ErY>RpdTVafylX@zNy)bM_ zSP>)qDp?Fs6pfgyR220_g2$k|LYt9xg_a~i;8Z9X385}2ovy?q7%0Ph1P8FdYy~_Q zgXao&zo5F<2m`GnkX|7bIvS~Xols?^(_0mqg_(1e4y7MOLzPJAdw7SP-c4`#QG}W- zSdCykYN7ZF!)h;gzFsVN;d7Kntk8`_^KXd0U*K-o3z&9N*45yAAbj)mV=Hlq?_4inpQ&o3KtS8_{^hW+3R3p3&JQ})()8R0-La0 z0b`G+1UNPftA_Bsz%$mo_JEs8EEG1deZkIr%73tSeLqblXmo%U+fqBW40qa6`BmCm zX@wFI3zW9nQP8o%EQ7;NB(}>=x*1mJVl=xMUPwq90trLRG6`Ad!S%rhgOb2TR^mMQ z;v_!uG?V#1oR|I1`EJc7`#4*r6mHuDXnOAXzVkzkz%2hI=f(Zt{zU-;R=h1O_U3R5 z1xdn`ky}sk3PSs4%rK2fMUvexj)gbPSaS?47t3F{Y$9*NbkgvP49XZ1pp7NLRufZY ztb>iE+&t;mR1wWEXqNxV_d%j5iH7c~vZ%#Nm6XMS z6A6L-G>)clB47n(VI2(l^E^U2*qUev19tbfyW8DU?|{I+1_WOF-EMb#GXGM*cJ|Aq zg5!e!z&^EqYt%jE&gur3{v(K>15?ywW&4#DlLZr(Id9Hdu3()vLx|N+Io6c55wCjgb6A;N9 z2$@;k$hX+K?w>k&c|lXG&wXU=kUu|Bt9sJOHDjz#AT<*~nb+^!yn+QEw9nVt!fB&s zJz7~^Y-n8Q6JS5_@drIs<*`H4$k>>*j52o)Fv-1T=1y{JC){{8MDQ7ni|Z}yt;#v5c!vl zWSRY()ZZx@kg}LgCsm-OyLLJKkrST7lb6(+ zP%XfE=>4W!fEG+1g+LTA4{7ccbyD)A;Lf4(I2!4NONZ7oa$~(y*fmnIx@$!YRs|Cx zDA7B}f}%6uGG-DcA@&54`r@h^Ig}bqi7B}}NDBzNt->VvfCg-RG;^Gp$lUnL;9xhU z%{yB=aOJ*ye)t@&puN4lqo=qC>h22D#Tk_#Z?(GdP)>xOuY=5 z(IMD-abaPh?_bw3UitjvF@W!HM_;*&30={Eeb|w{~N z5Q1nIii7K*lJ?HAIBAmDE$^!Jv=ZY9P`W^!G@Ekj1ehnaKgR>Ai{3)dQfYXu9-bs2x;9&M z&Rg0p!53VLdJz!~1vFwfY|(8m^v^x4M=C{o0Mgq?trWy9^@1Ox8%eNMaQOi|zg;DS zY4o7|m;a%O?rA$)iUxtq2!8H5i!t;-FTF{hg8L zP|PC3)?n~Ku<1TQc3H5r6@?3cU*>VJFG&swkYgN8Q8Y@9Iy&zATH8Qx8yioxb_id- z;JYu_-O+@nXp(QVp6VbDUl3?+`~b5G$E3pxIlK$4&;qq}%z&m@oc$iy^kVU=F9@8t z+2uHcu<8)N;c~R#3nX%2&`jKQA)^C1S@sz?kQh?=iYn+ZGqS8s26+flpaqp-4z@SQ zanq%HU%9WdY;T@n;$#a1(lJ1A42Gk0S=jDo*er%ObEb0*M#~snM=>CAnA>0z2%KA! z_rG#37mKCmD1sCSfY6{Lj z5$F{pU#bw{HQR$oEH@VO45A#t7&<+Ia|9~|8ex>^3kCxosZ{p_QQgp8MQ*(N^_~AJ za-jp*0#7Fcf%g90!}g<<9g|m#3&@E;}BNYo)*s+x@fr~$B4X24j ztisjXk%C%~hsHyp%oa4(2l9qneVBH7hJC+3xd2U<)=CH<1Cl?iRUy|>x<35qlZ889 z-}O06Be7@=pI0}`;Ke?KdwpEM01hyUw=eSQQXt1VAMH?AdcPU5c`1t z$^q?;V*>Z@_8#g$`f02TxCH`lvgrun8@X^y&ODLn7LIK?XRz>fns$45vrNf!OVL?u zme+Y1QIy>HvV0KCx1eq>hEO5|OS^(0dt)qgvfzK-d+D-y5C_^?)rjv~oZcg?KQgU9 zm7mdGDw5()ItzkZYndPCC>fnWh*=&-STggZ&S%!+w?nrxu=sL~OIwoG53?qrHd{VT z6I3^w0%06RqDSVB-J@sDe9H(ev(=hK7niNV3a zpSQMt-g<-rkw=<+arpLd?_f_L_s!AX(UEXnpf17pdw}oC_r%`n%4+q;ABFekM{=?7 z3+F3&&)N1q=o}cdqyKT{?FTfAT*8eg7};E0;^`Zbg_;z2N8^ zU{&Dtl}n&i3l~U!(Haa6Z0B_y%8!IOdtpK1BfxV!laOqY6uEdkS#QI0VS$UJ4Gb_j z*hbp3P-Haacs#FBZ0H54LMI{eq&cF-INJlTB_`Jo&tdwEHU^t#*!vo396dJN6i!we zW-lu##L7{=QO~E$6 zYcPncN_>k_W~Nap69y^^{B{Vyb`XaJe0^5hm7pya#y&;nMsVcTMxnz#l~D^h76uHE zmA|4FiDq8Mq^5l%361h9c~!XhGQmt5F8~MY1+6A&79=@Z9L>$}Cdr|C7x=H>v0Njd z1J{V&Xr|B^;%Fzv&#)oE0qjEfB=%w~NCydamR-)~O?w$Bea<2^S~Lcm$gM|CUkhS5 z!r`KGGlu$KxQ>K12{d6D+>K1e)?Jg+k&Gr`n;EZU}M`n}# zpv0IeN7O3A?J)PFgn|)tjx>Q4C1!1ATr))9fzqHS3+sT{gX8fDL z@7O&@^|@cYs~pi{3rrH6{K1_a-x$~~-+%~f-_cDKH0lVa{X3;Wfc4h$7DdoQySZYq zI1_Wuz1q0YijEqMKoK9R}drY-O-2kUBH9wgkF^5n_o-1J*PkkV+1OZg<8*@>I7&nNDHN ztSpM3U!R?g$7j!nM$cyicaJlp$7d!6k0-WnZ2bZY?k_vSZhw0D)7!U)Z{_ml&C$V| zg9CxvH~UBXdq?~GM@MpFfB&h)ddYhQdskQFFIugxK73f+;2Vr*>eH*S6Z=h6t)3Tcd^e$Le}sViW4D}Ak!ELe?%_S!Y4 zWAZ<&o!?8Fc^bu=U#>}PXp~5e5@XW*XiPE+cE+mPxMOEmcc(KJ*V%L!*`y-bZo8xF z&@!;z3{yFA#a+4=DecVufXyQ+l{I|4iD3C@#y;f%%wPgu&j>yrgbF=A;0b z(93?dwjfop_szc7PYD+I*KsjHa4F*h?}ceqVsqKpMH(tz+d=C1|nn z-h8H-e_Y8|BtX0Bql!kr6(w}A=R7t>Qz1^JN-DFVfiTO@;Hs9d)YCu^Wy;twexy|D zF=a=5f2;!{4Fg7^PNh_rWX!ngk~fkrCmMv7?3`pBOOepJD>SP=nW9%An(Y3Maq4um zBh3JLqu-!3spzckPdbw6jR(@1E{pEXFy&< zWKuS0W*`pQuy(b~j@Fu1oW_ZT*2I;?WjHT1xC}R)RDHr~dG(hPLgBC%i#2)X2A*_| zBvPPP9U-1kU?sj^Y)7h05|tij#LSBHI^7SlIQ8QFwZ9N-xuA5cH7K##8tnbSno_jN zTl;-;gQEcODDXOHs5=Ohb`2UL8_L$Y?34?^A|9G{BzuCSXjpJp%?qS74tzrcV#*r& zlv*jDQjOqB&xBNSn_CMiR&uP@3D8ob#dBp6z5zcTl`y^FhL+Id5wG9JVT=d7fJ)9` zv6HA>A0J|C&iP^i;oOa!C%}G)!Jb;pX*BEEtBZ>Rm+ozE|M&2455;;l;tysne2wYp zqmQnC`dMt!;CIu}->ucyt(&ms-<-3n@gMG=3p_o{vHgq?oAdgB`M}R}aq?ZW_scoE zz06*AGhoTPAD4FjJ-awG>AUOxD!j zYy3CSW?MR&=xOuXN1)!^&S`7S3m!vY@P1)uwuEd=?3J-;dyBNR^y1o;fiJJ!`|af~{`rN0?f-Dz zo<4hacxq_-_U*~(+vB$fMsW|0k5BgZ_V$mD4RViGPfb_dBtjcbV5ezW(vnEd$?gzx|3e0J2b;!tS<9lN(Ei|rvFPO>%5+@z zU(zc@cNy*mms!LDYrR^AW~@p~_n7QQ8~`po}IlDzS{^DuNjV1I5g8Q>1cqFxyQf zqpU)U1Z$NlO3Vfgh4#OE&_Tgb^mVl30V~uUv<_+%%qDb7#-wCFOVQ~EYDenOdAmOl z6YfrT^l#9q)Zd>@pYut?2*@-Rb4g~18l6uJiM2uRwGjGzyn$29xYrLHnP;pU2+S+$ z8Gtpu3lm0*25RyCl6MtBlE(VmBUdnu3!%F5phF5Ckoz}W45{`Ak-8nR%M#hp*+wG- zFf%W1wZbjCd^POyR4){!vxRm~wy5PRm-Y8B6qY3^Jgp??sVs}mBw`h(io`*;(WJ|G zj~ES?!Q}#AJTqM=ua^r`D9-FQ;YT9q0xX_cH_W{&5t=ke7LCg;xY;-jjgrGWHT0`YY*Fwn3Gm(_iqnSg? zzf>j?b6h12_LD%AjjNA8FK-_8!GMhb&p~WQ2N%HIQNpnp@w%i9Bx*9DjpmY6X%Eh- zn}HmTQ4GQWZ_Vvujk-uIr9+?1hK0t;##)dpE#&pqsfD^DvL(?$yr2c5n)gA#EXJm> za7_Yq%{ghLsXCX^h^zVW)M(eqC-+j$eTkZ#a|*Wjus!vn@!(o6_koBlXhyDflJ(N; zz|hCrG%vo{44nT<@21!^tuPXAaHE!km!vMlv}rx)iu}GweTo2(Y`Y` zhYjhT^8rJ7b4x#b{q)st@SB&~9=7^U zrw4~`4-Y(kyKg{yvUhTPc)V|1*KUTqCwm7+C&vfIc=z|-80|ee+Iu6?`|{`^1@ifnWq|S0^D?ZBi(;)1%pM+(*{Naxm@>Vp=jj6<;O< z8jv-vyMvcFuBWP^FsK{n4OH2{Qu-u$9C&;wNirxcG5H0dC*p)(8K0Hks97;0T%r{z zXs|jF-?1;*g>D+)mP*Ey^JHgLh^8bEny}}5HB*w>{Mfj0GXpO!DUULf*NQX8`HXr8 zE2*k>o>7!(Ng87Syn)46)r3H6bfZ zBf1!1#;DT(fa{$-E_*}ClXjkCC~&w(sg&7pJt0tz7$YW%pwJTtvpH&@ zjO6U%akEs(WLxbvPT*p(E={^f2NFdyVam=8cMFAvJ&>OZDALodyV(W~q~7q|-lE~E zY`^S3PwBXKeSP{ly!UQ-s{E6Eo>ASxI@JrkWg<9w0lnvPCH0QC41?EdWir1L@C49qWPOhCXUbhX+?$xSzu!!-D7l&0IcXM8byi=+i6fc%yz2;V}Rf9xS z<*G6)8T%5wF#}OXI2RNXomF1j+BdK@=4(uMw2y?J)(gCet0jxOa${r< zsafc{v|sQ6zOdh|a`pW0sgke@vSBZe`;pDJS5@$gx{!HSAStFJW4|>MR%X+HTqFyk+kP!#%}NPs3ipyx0py zgtNw$6Ct9r!r>_c;F{!t5%;D-KM`D5`C~WEesLo;XI9etnTz|)3zI(_3|!UVc6ioF z%1c1*%Is~L_()I|Llw^*eqjf<2MkUJc-R@Xt5#M-hDnoLM3A2Kwy!AL#jQLoSTdB30lBBIXw<6RlOOdC6>0Bn)W2R7F z2E0Ka2_`X^B^RL=DVPw04L+3iCcV*xFLRZUe`Vj#^Ly29_p1}zdgV9D`F-B!`+W{x zQ!>kMed*0h2HN%#&t8Ay(wA?%E1T|DL|<$V%5x2O33WU{@PohoUHX9c-ewi?|K9ul@7sie6BMWKo1aJK9E;3T zjwB_GE12_n)xpMvyAgWTBU`F2q$tT4Dm6&4fYD?k3KdGp6wnK<+q82Hbo}_wQJx5{o#92&5;cs$lO0r6?WwU}* zA~SM~r8Al^BfALpg`!DTyDt{zN5E@#OkOjc$Bn_ zPTpQ8+Br~%IYd`0V08pXQH(NrE`_28(BP=@uZ$=!p@oJWACSpWDy35YA{bhESgZMF zYI(V2?~P?irBjtvgWBa~JA-OJ~A9J-y;4;waR>69%t+0+6*Pt{r)Rrk}NL5Mp^6f!+60Ep2IT%tq zmr~0MlP*Z3rPM4~atrMitKqiO6tz6kTkt$KZB_0WaL#BU>RE_q+75OLo=CdT)=1h* zZ4`XFrl3~K17TjWaN23O9I{VNZg2FQ_2_2uGdF$y$AJD`zWl21#<3?=VhyaMNsbFG zLP{#NVDl@DpclS$BCNrx_59J%7w>qH&{rNWcbW^)=+fu`wbdk05+0Lpj^w3>wtvuM zyN!;heWYwOc_~CFbTc{{>$pB(@Ryx0w>7%w;PzqWml;6I17MenRVZvv7pFIN=H9%n zhM;rm8#4H{2Zp#%ReOBp9P{QYui*kVl;*T^S^!_CC*k^ajf++Mr%L-l74kdE+GL)6 z`ue%ozB~8q*>~^Wp1VCa_u|X*cjgF|B0c%e!|f+@2vH-n{lsezQiG6M3=WTuPLBE~ zhP?g3HwMiPZ4Y-(K;^^z{_Y;5=l=fg_x;`7{oP%+?cLeieY~?bkU2kQ>J0ckaLgC@ zy?K)=?$ye4xiOj#Yz6J=zF9T0@yAd8{mF0NXZP^YTYr6z4$V`qYVZ4Np|8CS2M|%A zvtlSr2z0<(3;Pppu!xt0mO}P;@|PH?4f?m{=etUww99hHP7MU-B- zn5khPGCD&W(mE;7@l1F<9KNfW^xcUt&pQsx`H*SA*)4Wi^Gc(|1bV{G%oqp$HcNWe zg$a_SGZQLrn22X4PQ?<0qp+t}5~ckeMwFJu5~1t0W^rdG^u;=kx-aAt*z)G4&nhDf zkpiuXU@_#7gI&)74D}6+I1IKs{unI`3jlB@B*j&LvbND^C?9odEIY{#Z{G!n##>TFt>dEr! zUtj(D>&Kx>o)4IYTA}WPqj$VYq-#6nQl}hU>f~>+*QH@$lu)eETT96LmrA4LU`0tj zw|mjftrCIf;Br2?5Q=Wxk@cw1a-JhE1;v#kaSOs9fK*uprHwJ)pPc;5gV4pBH;%P_ zy=Dyf&({aZ7{EamogZ0j}$7%`#jP5jt}EbipB2f%Ly0CZyYrcR7!_*%|ZK=NGg|u>}Xw> z6A{DeNYWRP=@)Knv?-Z%VIDkdPjC6Vcz+Y~KHoj;!v0`l>L*{Yn@sxI=`OPL?W!dh zgzi#_w73}bBZQ{eXsVb9D*K9Avk}@Pd{@Uzqp=~Wl#rZC+63*CBp;`eWMchNPwoGu!>}>Xy8f)M=n>?${18$=af3!w_dAJ%7CmH?Q=RuY&1*XT-s>x zH#zdHYKF%3nvvvqJr{-$8y{BlLOmNsjK!m{_Ppd#D&pDbYYtm4MZlXZal`A`P4>vh zq~joRIDR)xo3Nde9cCImJgj;pY{GF8Iv7;bExc}z@2+vEDK!dc0GHNb#Z<;8F0e{A zKAfHiPhe`Ym*V9v#8stw%8z;5=ltH0ge1_KK!dwV!{XnH-N5~5r>^~W$M>@#6Jj#+W;qpQAR(Ywc_~(*5MXTl2RoWKH z4eA)m%c*61*jQ~!i)HVnRB5(k5Dcz14d}E1Zj!i6_b*A0hPx{bS$x?3Hng496qqQ; z*#mI6GV6jPkzHNVfxJkuFeDkA67|e37+!3j*bz&f1yUOp zD}8cI$wMxF5}vh z3ZN_$SYO8^JWxh^?E><>y4(pxcWC=rD74y>1M{%5kK4bvlbn_scy_93k==rHSwdy6 zSQjit&(-3^3db91-)Qy2kKTLRU6lXp?LV}gU2mK98OBNCWPT|Tc4jYikW=i%HYPTy zl!n%EiIJIBI$2E#Wd&5QWr>GkSc0WSlZYlwij+;Q6sD?)RH->A9JCUmiPTE96R{I^ z!lWGbC}oF;WA*`d|E~X&GClw%aqP!2LdNm+T=#vwTnVq;o^ahgeo}=4V58qtGE;L6z@AHFV}`7(}Ajv|pfirBL3~4v zoaf~RbB$0aH`1uC-K-zBAk`IN;!Z(8+J(6ZrzJDgyrxb)oBk4~Sa%WuZu7D4jun})Fm2B!!7 z+&%b@AugzEfZN@+1G;SQIso3qn@eZkcFzv>D9-KiwY}f#0lX}D9qbzFcD3?-U_|%Z zoi5%YduWGlU8$X&&dR>OvM(of-qOz3E?cX<;MqBS?eFPMHDB@a@nF!fB|DvpJoCj{ zZ@>QZ*}uI)U-gF{e)y`$@0G*N@4LU`B|SUnqiZnesu@@bE8vJ2eLFU<_I1_0sxUYh zZMC9|mZ7Et$g}!gJcF8mqegNERItPp5~IohOtue()Y?>C19_6sO|aUalvv7WFbcO) z&O_Ah1YO_;!)JuiE&;l%6|k}2VdKexzH)hkR4gDi3;(4N3ABY9X9K0-ta7kG-atWf zX{s4CdZu=eMx<}D8|iYXP@*ZRS;%fMl5S!#Di!Rf0c!yE+bmEzm@Nu&iNeat<(pM0 zQi1ZLRKZAaDN9b)G|5=ki__V(!7(1;l~NH|mIPVgagvzmWN{^#k`RkMaZxjBMPexg zI)ddlf<~ISXuuPvk-8X?L(Bec*^W}O_WEKh0c(oKWl(}7Q*eY#nmuqN;?g=|%S1s( zB*t3Cjznd{F(__~T*{bA8^(@dLo(z}#ctR$mS0*P69B7LQkmba;r;-dicO-^?4*n! zakVfY6+p=sC-iE-?JIba8X91|@L@yPpldw>cJU#p@`w$u@#CPpM@pXzVfkIRTSj#U z1jeBZR9T77Y<)AjUXM%u>=_Y8t&)l7rGus~DPv$g&fe*?Q9@THqiZ2Mld>&Z9*TR&iKP60PVBeL%SFZ%wmm?Sk!ALPD)2 z%tX`;w^fCtf?#=!l)WLAtcGA#&Wnb%l0PdL6U<&Z*)d99v(tmwwVm0DXoL_jU&ewWLDDV*C5uBWw#IZ+k*X>^qjAN zrb*b9BOP~pUq2Tb)9~SP7@3gdSqd};jFl1%xQN_M36A~Iv_PSPx*-4nAOJ~3K~&R8 ztm?k>XhBgO^##B9cERyL(PW<;Py95Ib}5&TV#)(2rk=>CC#Ih4jP;DmTah=0r33Vu9VFaKKLFcMAeVikG$t)v(@+Pb^h~L`S%W!u>2+Q=s_otBD=c>`@MtxgPu{_UJn6tuO}oXiAqOY zUA=vG?Phns*VUYv>iP%Y;wRc+z>J%BXO9#Oti7`J?(I4Hd;h)gqLS&$s>!^IcqO&)Q$UNBBTs!)TX%I==PH+pnMf{Oq63e|-Mqj}o}q&lAj6Ekc(L2 z*v(<;e1n*J;YagI!U{?{O)C-+SpcZ|V^yU@t|b{9nq-r48Bk6%mBi7e(XBv0;gr!b zdtR(aEQia(twLFWR{(E7@T!{Nf}yst-hxA73W4b+EH|_8=cZ}}%dU;kXssPC%9GSA zAfRrR3u&ZSG!g={^Z^&j#gcv(@fKx;g={me+Cl^2bRk{xb2zT2iwbK&CE3p;(a%Y>4>F@RD7`l{cEeyghOrkCjlU>K>uD@D7P%LR zEU%2kTyxTptimsi-QeExJxR8X-55eA{mj@?(B7zuIHY-3?j(g97}Izogr$JSD?X@* za3{plMUQcq@v}tq$f2ROp>XS>{V9YDfiuuw)XyW>e+lLo49OWh;+(-okF^6HiLd8n zMUp0zCGom_SkYR3(QA+mlpkrZPxJ6kVw?=}iRnLfSCEuB>8Vuv?rBt_?qxClr`ArbG!4MioY~*+`AvO&B zPLkAd(zO8BgpMMqD4f|qE&2u{Xa8MvqGoM`Px|qcq)0De5w_>lI*gsA(3)M6B#U29 z%qoDRRypbKd?kfe+Os0E5{m9v(s==GO$?zWgsz=jdtf+wQ9Q2+znr}HCK1p9CEqN9nPm+OcwAwcWAG1S&U91?IW;e$bQArf|1!d z7ZBwzw!Sdx6XLp$*3RGLg0__Jaj4509eq%Em5*gO(f@<*@2_0>P5;{M3oZ=V@n2#a z4OJoUM<+Vdf&A(5BgTN^SA76JjJvqB+B@ZEU!3`>k+Jt{E{_kG{;rY1OampBy=_P0 zM62qN5GR=Ni|Qz(k_r&yB99K@Y$oQk3Re4yP0z{AI&_ze0k>a<9|Fxk?dM;f7XS2Tk~T& zf|w!i3Uar1p}xA>H{`W{425^WT(0)_celIUo-ladf$o0SFt@wgWXw%AN2H3kw0S;Rv(h= z!PF9_p}u0u5u?2JGik`Z5^iPE99iQ!;K0xm_7jNzxE?h13M6J{2^t@GFS2 z2;+#QQbYGrU?uBd17-Uiaj?w!Y zF@S{ zhVu^gtDA7ZuU$|>vrp|*YJZD?hI$DLF;85g__wAo zttBmewH2OSOn|nkUI1<3!oWRI9Y%riM3Gjl9Oy~iW->mx_TV_-&qv0;`~JT_{P4r~ z%%WNGvf2F~Z|C#c=6%QU$odgU_SDF#gd+{bSdFBrvL;ilbsd3Jymd)et!_nEue3$3 z*tE@CZ8U1K)t5lP6asEAjv=f*q&wsg5(g?sl(5rw$w7aCM_`xILr&cvu+QuLeN@V} z>uT55Bl%H_vHHCA{(Rm)&UhneeJyy#;4|X8ID)k#c9gg=<$$yS&hJ=JKt z0X2~x0COc?uc~nrL zP%Wo{ZnZpflDF4&!f5ZiBwe0AxcaSiaeI8G*mC12YV7x^{}?{I9k74r0c+it9PfS0 zWm^~)SF5K_SL>B{>e-7IE==7jJmUed%j=k#dG7V|j(E|c+3RZzB5dA%|JIKnc~RZ)d3i+ zB6@us4?$dR1;VU*g|Z`~z@V=X*l>AdAUwLyme)Q}THPPsH$1l6!K3@^eI>18z$}07 z!@B_S0QL*|8tf8m<@UX>UT5~bjm^kDE*;)Jlxh3&&SmE}`pobbul+`NK_g?zzGmM7u;HaVd^WIFb4^IZ zaLmn@=1^c6u$CA^=b0Lp;`6c_Rr08#$%LM-rcTXF#L~a*pl{`v{f3_=C zA=1eOB~yvy3Q01BataedYSpV3i$Q$8g%aNV2v6$*hGj(pW z&ScmzTqnS~vN2Ac)W})JBQO5SPP?+`IvGTg7d4T#_=p$SuoUmc3%XBRy&m zJQ|D)W=9T&2NE^k9}Eq6$@>?nFPM-YeBd_J?JHg-gf70C9xrst17NxwEX2FTXfqHBFx|VjSp);;~pxT8f znkt`c!J0D0qg|{>@Sg*}@)>*zfi?j5O^^~Drg#u;aS(%*m$=GcH?KSSB{~U9#8Dc??p5rbihvDqYbszU5p-3`Gix zfwB5RZ|7wFt?6byyOyui=F$~*#B(vM9#a zo0jJY?z@!OaDM6qPqC&9WWd%AC-e zKfGcuVEe0K5AX7BE9UpDOt_L@dmrXMu+Lb~UM5l3vBe$aiE2W?ZrQ+Xlc6)6fT);Ln<+IVY@)6LH&b38 z;gxX%@HbW@FNyM;#>?z?HzjpmmVL>IrN`aB5MwBEnfMNh3sGUQ=S8Wdc0#Zo`nya7 z^`;(6p@v>&PmPypXV4%4YwE3k{>$+9$&;_)vPNweUg)2@HDe(8%WCz5YD;@y*_9x} z1YTiRg4VWqcEdi~b_j1)Qxd>zxJ#(k6j+Uk3AQ`cSQuwwd7$eZwkS$s-s~c>ltbCl z^0M6?Kjh+#-N_9PfgR`dq|jBT{B`c(mJ5+?xw$kweICsfb4J^Bb{r?&RxF27w9Yyc z@K~*PB12>m0)NH3Y#wcFhe zC150XBs-U{GH3RBl%0sY(RMhj-=5jN8`?KoUU-S#Yy4(#xDl-%B7HhO)&zNEaCtm} zx{kD;H6)f^`S@taTGz1FnS>BnIl1Z;i_7z3poN54 zyJO?YDyw6uOVkyRPQs+@z~Pms;VTV<6f>|0wo{|s3A8-%u-cQt`6VCzQoG9A^*we# z;h@28*g)8h0xk*5P&OZ9{Ja(*g;ETd=x3M85tH5-t<^Q0!iKGCXkg}y4cLvL#dibw zHM)RV|7r!C4;YWFlyD#A^-pC9A8@Hch;)f6B;Z$&ZGgNtpVxkul3;0}=UMVnynqav zweb90jY%}pD|W%#`Mo{JGoq^Wo@UbAq-%C>Qc=%DP7;_U8k`N;52-(zoKLGk!9JN= zXKU%u9r}eaE2Vj2C=@a@CiDuW)yJf77`tX?Y>b$L%zkKkc590Pw1m!+)7gx|wCF4J zVxMO-q0H8P$o^AXvsox_NL>t|G6@{`f@ec7?q^PfyWthOBNYoC=N%Y)*sm&J{>Y?I z8o2tR3WHV}$6tdo0lUqwN|2<0_Pex6ve%-1*S?SdcM}vf7(9o?j1zJlB~*&!UixuJ+ zpII`lq}a?PifphJr!84)qE1PwmMusVL+QLmp2v*Gd=oHa0fPx4F_gs@V;3ESC5B`q zcF0xfMGCnY?5gy>kX~(nz~0aEJ<0~_bsSm0EUS*<>N(H*K0j9IAFR#Mgj8H1{EGBR zL*W%dDCg!X#(XJUplyf*NCQ7t5D532b*UNJ;r9Mp|En;L&Dq(05mG>o6~57PvC*?G z3wpWI%Ywl!&T>|XRz-zkRr(Pfvx>sfVE_@)*pQ0K#3cWjABEDytjmI~kOd99{rX=3 z@XK%i{RI8!`OzK$Ib_A)&+J1?YQ%3gvSHH^iV|e z@fdEoTC3S)#3P9nVXE;sRbG@2`Z(vB_ABjU7PiC9Oe?-|Q&Kc%&(bJbf0JNMu4{(S zl4QB=Wxa5Q`+vT7EgR`Q)RNZNDm0Z(ro{Fs+0<9!#e4e*nlTLl)&Q)LT*;ROwlLg1 z0GN*#`%i#edz5|G-rkERXsVv?340A{u?`vN?i$*{eC-p`YiG}$(TMf#(?DTmu)8a+ zYqVDmBfEOfPWPUIz7ORz3X+|7l(Mno+(y@~BfPqM_ipdYO*_u5EOaY#eqpQWg+jz6 z=9%st{qXRIAN=Iqx2|4&`|VFooH-+V_rZg|e@E~O`o1Roy?l0If0g1SM84xL1XG=u8e)u zh!D{YbR?nV(TI|QLYahzhPDTl@vIJDSnzh|4zg#v3c?z}?Vxh5BgV3u)v5{^42tjE ziB?0Z9;66(DBr%*Rt%+Vz(bP+Ku;2ng(Ny()!l?p+KtaCE6h79QV9&sWBHw|mT)7n z2cD#FP<0EFZG+)X%Z)OrHl|C=20>Z&#dQPE+YGF=|4pSJzDLzcm`bh69&ArJiuie8l^|%MH&A35 zEW2dN#K0;*Ji2=LKqnMUQfY-oPT}7XA~=SW2M!Q>$oT4Y39v{8*AW`99IMmLV8?DA zT?(u_B1oSh!4Tf2>mI~@1hDGVlna=X@1@fbfH?{ zdC-QoMZ%u5MOlGsOXNcvuf-2sa~H%+*_DFCO$&CD8r}sGu~g0AP*5_c3cY~~>K6=x zD2uKEX*OtO5VwW<_KT1hLCZhP;C9Rs6qe2@qYrqFJHd==C3jyotuAn_{eU0arnr|MlZX2?l&tAf3WLA68-{a1$%oi2<;myVrVJHB@Bv17o; zr;t65A9=8KvbTHEe<0J+>76)q7w?=O&%{`xpmJ_@TLnMUV$VwgN5OB_(gi#C^!+XS zUGKJ}LQMM`H~SlL3B3cqG%wV+R^*Ns>lLPMDmb&h@G*wavAd5Pi!}g6t85q7;>bSuII0VEC`oK9?9j+XHUp zWietuY_ymbh8Y=>#!y+2UpYfmCDN*#%i^Ff80A&!s6FlvcK^BzOEU_DRsyB;TgH5E z6NSZunKiK?=ZyWK3JFz~eZR5V+bF3=FLg0YiQW{_m3#_%*ClO8o|Mq@f0tv%xC;; zuv$Fk9=OY_Ibx_9X<|TP$gKPgFXrP#YH7Ued2wZ5WnvNKZN$+}@IYg|X}=ZoB?~pq z>t*cCDV-_k!ElFovyhp{_+6t6t(d*78RoXS1@>zbH<&(SqcrqYHdeN9qo!r>1UGB7 zx#b!$SW5`9CbDdKvjw)p=8DD7>@G5}1jf=vQ-5TG$Uz4+;f6inUtm#pv7v~8IoKmWgx*KGi&P5v=mn^ zO4@~0&hsSXL5m_wtQD|ccZZ>BFuIIo#?Qeb1iZ>N+^(FlgKuhOAi9_8XM?c#j)jVu2*eAekg?fO2Yey1NkD-55Ntf%VUK{DS?GKE^v|?3VqA-7(>}{4QdD zqTP@>$dP1+q}Y%O2>)Xl9&+td7j%VJdQq>M*4K?799zd4ykuI9&%4AGLS9{N&>?ya3 z@C-g&bfn!7_BvCqK`m}0H*wx&!fbr^A4=2^;v%)u#JMkc?#D|S@b=lSOWM%l_shGR z*Efy(y3!GQx$Fr3nUUXWbtIoKzVWAz&^`b7k5}LSMB8{rOYnZ%7SDyu<>oQLc^wXikXUv@qS6Lelk~!H)y1XQiKD-Tw7LTq&b(7H!(Hcnu_3BXFs4#iZb`%h;8`g%B z)u6BNPN*|jt#-(xWCM&X$>?!36m1g(U5+wio}@Ows^(Jw03ZNKL_t)^?n+kMMrTV= z1!O^R%f^Ezx!#r&$#}BiDcj*Z^}yh-Ve(9Vk{n9l_m*O=+9hp&iO(9tFWd%cCk5CsiqwfiBv<Q<)mV-+Ed*3KW52|781O3lIfX~~{y@$Z{;uY%-}8S7M$lh>3DO$1?Z4B$dbhFm$$YbSwN<}OK_R|iK3!H$v_h}Q zngp&dDUU;m915-^esU66#H-|`4eD(etbl=KVmP48FzALHNlc}ifl~T^pWPQ6kl>)h zL7M2MGNQj>dZNo7cRcTT(wvEKQySG|$Ys~D&wwCj`S4)4^;KVDh+VCA6hKHy2O-z|>a zoVsxBTHjB;evt6Jh>6jIy=SNWf7tgv6K6wS+`av?qf^0A2PP$jS( zF}_RtLe)@t=23MHS+s$1e$EaUH0O!FLWV`_LMgAnX9m>OIckEd&V_SIg3j5ml2hUD zcwUXa#6&B3qhyCM9g*#vS8cFoMAI@jjvmXP_;cc+xt+FSOsvO+vMM7S$;a-*c1CvW z#GRdVTBcu$e@W3ws}eZR&evcYnoC3nNP7qE)<{sckdN))?j6~on&Hp5j|jd}HE_&; zcZzZKM2s*>WYbrs?5CV#>l=>P#n~5(JP12W4X?6f(4rzdOh<>zzxyPIhb6>{dmPqK zT#Z}Cb|VJYMs!E_hwR~qLavC1#(0#Wbs-}~mK?zbzJnd`I(3Bd02c}wq*oauzw{s> zy8?9AH(&^(nbA&x{aImmqq9L`{l+@-EQ96^Qm|kbg~H~N@#S)v1JGXWitFXhrUY5j zsB$RrC59 z)>!l6#EPcQ#Sordv5@G%8YjrRfWS)$?`nT7=fBoIb#&YDw zjdv*_q%`=l_Q2=m7ZwdB3hO-K9G8(oE0wZ&S$G^EuQOYXqcIkV2P+Ah-a=8^%S~ah z^IWwJ3cx)q+I2$;r(AQ3a9{-vGNT2~gW>@te9U_eh0Xz;8xjQ%$_s_lMb~5v%tvbh z;SID}MO7`Wd4u0t(_<^`Xz|(2bN_D#9KNeLa&a(&c9HYgnEj1RUf=> z+dn;p2y5Wn*XFk$l=o6&bo5QWRbSA1eBgrT<6}vlkDdAgye@e*^j-WrInP~t@gE*; ztS5#fP$}UmHQMvkXV@I`+W0-M9pcxc}!Ddh^GHiKpwVs(DF zjWwx_SSJ-$r5)i&$!I8L#M%%!C2ciNx39$Eq@7G6w4rX;ZrF3xDEDm}($Wg%GS&tUSITCsZul=Dz)rTZRU~M2*KQ1OC<{iz17kz zJh?D1XJ(`$l*K_il4O`1AL8FFk_xY4H&Pb|&4UpH&b)L`Ju8qBWizvA zXzjzHjBBy58x1Rll6s`ft_IZt-QkQ@!b8lV*$OA@tmz>N85BqfERU9n1X|x!Ebh93 z3J|Fjh^tqikdfhC!rUIJ!_wgUhTZKC1=Ez%r{?=H7DP9}2Y34z~KD z<*x5?HInXX)9X{|N?jc z(5rO2b~3RXl}h>UJ;h6|1S+h5|A+B1;m}8Kd~)*3r{DV1WaHzT44R$oUP7`p={{e% ze;boXqAzJJ?1teBC zw2<9tWzoL9T>r(}-&R2L_fxOu+VyOZkuVA25iM(_H2?-2@3 z?4{0l;n~|i3{1l>98lAh7$vGLky$rpyIVFi9>U8$JzY2UYY%r2Wf?zSHyCEWf@`T` zuv|E}Eq3c^R}J}&8o^H6ZCUdo!%Z=Mtifvi$p?Sxrch&IXt%HhDCzuf_wPQBw84TK$G<5f1=H@(RYbBcibCUX1z&Sk0>s$-c7_4%(4&)tJGv_cPc%g0f;0 z0CA4!jo4=s>0H&Im_`PyN1somcVga!6x$|-!`L!mmLkj}X#%m*DoZk44{#U(7LQGl zegzs&#kRMRb=jlm+)|cmYv-RN?@ZTL2m>OB=EJy(3~PA_p>|d(M|?H%5H_q2k~kug zS$X_;=HXCccxWF#FcFjy&%k0Cj2g=x69FD2BwDo#5=1958=cYhQMSoPVOGB79;jRHk}QP}nD*Z~_*+@5SGq7>&`<%*o|mz>{9oeE z@3pP_4CAqWRX=P|*+@&|VHs)C(KJhysk^wARykF-)!Do{Q3GyZK|-u9^ICh^W&-n# zAz%gp6HIIfi!aJ9a#7qGY>3ma-L$(%AUC<*U(x;ndq2(TSR z&ktX_+V88SL# z_ay<-r{fLXvRi|4N~f{vx_&Etw!XpTK9q|5enUy%Z$5c6W1?m&Z= z$99OH#0|g0V5hJ%@9o_FX|d(#y|h>@WsYd%T=&Zz{Xz@_Wtcf+#=ck-M0ffO|X48E0|jeUk!2K}}i+hXQ_I zJFQ7ytHs?2Q#55P7^qGy(T|i2ERiW~AWptB2H9O%}_BArlMi4stvFP z&2x&tQb&@3sNp9-T$?b!o~ia2JA<P$BT{ZnZ=Su*A>g zQnE1yt`mmDwNdWSG|0Z!j;gv!-M&yg(mG?yl*!`LxB zNO*)1Ku>7LYjii^IIvOJ1Y_lU6Ip>Uvt|~=b~>9KADoRQQmc#GH@Dl=9Fje0hiXV_uS+Mr z*5)rU#g#X4C4tt4=MRnyI2VY0F8=46Z@>Asq9&)W*{R>$zyEIiJ;UO|O62+$T4%%4 z1-!r)m^^Dzttc!bzKboV$fAB8XOiM8b1DheJ%CylxD1a$LiDsR&T?f*>Lr{$TmG`^ zT~vqgq7t)|jkUPg8T1x9B3y5&;-TddqaDBqT2)^t`H|BdIT4aFpq%!(B@A}9CAaSN z*TZ0KizP6z$S~nSidOv(-YXx0z#si@5T)Iod$fJuPn2|hz-)NmbR+2L#kJ~O^C!1j z!?}ZI@w*_7;`!nmnZK`3U61`t%?-ah@L;$sLt?Sz^iDw`8|iSlu+t@WQud><@^ZIJ z<~jA6Mva5^j1F^j`>wX&b(h=e_Yb61%Wt{D8j_S)}XfBkj3et+P^ zbn+g(1pK}6!5#Za41ftUg4KrOz$ZgPvaSN*)KECEZ!jE>?*~)+ya*4Gib8r(n+GVM0G>`RA`Aj zN-Bd>r6Gc_>=B*nDjBL71!mmbXH$$lsbplkR|@qFS@)PumxQ{dN{VJ+Ql5cW8I+9e zDr#d6u3IUE41Sf+LFW;>-gPkQPiy3nzOIIQ4XU5RkgiJ{^B(WW4;GCd6*wA-3U)yxmgoIDhhollh zwGGZ7(n{no@u z?;y$|BaO<1=n(p6mcK!@4H|_to*Wos4UF~3rEtWVK;t$7fa46F<7px(gVA){U^nJZ zp`pNrw*~Esk%7{7)GaR?HwZ5i$CtL(B^ZMpP{ObS5_<)5rU);!z;=qMvj^L??|UqJ)q9j_+l3F?&1S*Cw`r%Fvs0Ql zJI61`M=9^khP1~{2HlolR~&ea8S&b8r3+`Jggz+ia8~r!A41bfX!obugEnD~3`Wk>OF?yAvnjSMadYnEh6SHgfj%GYC2hxBkZli5CMF@Vl3EC7COj04Z!ka}=r@Ah2{1@yPpn-02<6ofU{bGO|7yrnl7 zeq30+^QQD^e>~b+TMh(+g|*veO z9f{}KS)w=$oJ%0L48Rqjc`jS2)k;-3@XS|p&TVAOw^z;6 zQMfzf@;CA_1m_9mC>he)x!r1ICR-y}(nvG2=UrC9HHn+;Tt1@kXZu<+7{!@Xok3SM zp{?*lqH44^n>8w|nuW-Opm}q{;5ad}nV(5)QoFFpqkyaSpcf;=XBqe!fz6L<`W$h{ zj1)R=%yvW0VQq`;^CI!j;~S#N5gCNR?!GMo-9g~v$6`lmEk zGy&TeT)xVuOplR8nU)%w3PLIg!@(F~(8~qN+3dXM#bZS0LW);nF#}=>f%#;gTj;`e zy+XL#B_At|w_~T=U3Ilc^W|=Le#Kig7+%4LwCZ&|yWcdZ&S(*wxw%^Q{??=S4?`6XuI}EKVxGOKVA??wm)mfnXT#$dp>H$2h|4r3Bp`as-=--ICGvhB>qM_ z_S81Gyqj-#&Yt!07STgUA)$JYiW*AK7K=sIF3hM@LH1weQW^~|QcNfVl6!(#`Ua#} zt|Cv}kT=QMFPmU*MAC28XHqRa*0R)AkYHaF_jLrk&h}rJkI+cF`4=<}@}SpT=G&hf z2urp6T~!5;1X;oESOVan3u$6XGCaB>DexpMO1v?sHSGHc*Ud>m!t~n4``wpr{=We< zK^$kF1<@Nc`(Alr2<9f`%HCqS`j^`?xBG`VcEHAfRRDZx^`EKtFJ1aL{kbl_e#qMu z$yJ;>5qp1jbKP25M)sjBz)uH5R=&ewHmk9;lF#ieZ_m{ZU)R9g#cA%gl0|w$DI{xt zR-eq$nx|iTey7XURzH7uXF;Nk+R@)|@C#Ry|EHR=w3~aK?D8QYtHr zR+yAYqs^53BF=&w*TXUcGnzgzINqu&2ii#O7OlXoN~!)Y%tc2Sci<$76`pk z|3X8`D#pzuKsU4k##wZtvjxNH5|S(8H|)xjc_?n_q)|F)CJTn!2PMo)rHoM4aJEo- zRN7|}-IVpn*zQ5$M4Bv0feVC3N28A@M2dR+_-z)LmIEookXh^DxC(Yhc zd#|HJXye5zz4JXIm)(VP7Q{G!@(adF!Q&1q*npL)l0j5;#ctMjj@m~-=+(kbFpC!T zZM*GAzgp=jw4w$Y>;46-`3uIlw!+ZJ33$%@1P*kPlSiGRu z?cIG$7sIT+E9rS1=DIw)KC>=&(Xx-3i-y2Z(_&E;;PthlRL>Lz&j^%B=ujgAKO~rT z-;q0ziqb&?^D1GOU7iF(t5}$gLm3AE03ZNKL_t(R^oF!r6Xv_5>9vPnXkBVQrgQUutVkCUcRzLgl`=J)-*UXMHoJalP^skKU%$ORd%w2|02>4Tjh_8D|JmwK z|55$y_t%X!U%y{gI84p(c2LFz9M6ucIm}4q#CT|+Ya3v2yLZkQKA&OvJ=^7fr*i}tPbszdDiX`4E3MO3V=>uCemM8`+wZ>h z&a1Dz_On~JuDyBfn&Ge5@Ap*r`@t*U;rdq}=_C7ucH*H3Sw^U5$W%y(zs9~o6^-|E zYLl<4KrQpfuVM=RRSOQ8k|AL++u?hZ86l4yY2@rBhA6J4N8yksJx`|-b|y?^Aq*;& z3Z=rT*g2#fHhDOURNEOA$cwb7SdLRQ1KUZO2^X6uTi(0S zXi5lekcwT25RHli&5J%{K53|{Q1Q?QNdsp>B<(6LZ8i;i3o-`VrBUhynHu9YqN?E} z*(}h*P+-q%=b|W~RnbsLiu{(MkD>r@GHTd;uxMuvC|+Pp4MvmwoGBDMhcdcP(~&{v zT=c4pM6?kWK9Tn~2|+$kHBvHKiYougDDTV0j17_t_I)lnH@ANo!mR5v(N8WLL|=#n zdw(L#?%kscnhdjuGNdAWxMv&({Z)-v|FyJ6u6^lG@7fY=e2IWGuEEB+TF7s<4(7>M+Fjj zR|In8x0yxLJxH|>yIrHXdvr6nJ!yehW_T#oM1*k|5F>;JTz7YOCn$Tg^1^?lb?{2y z0dA9c#Vk#nSQyOUd7-UvE5$gs#cs6|?m4gR=~w~KjHvT%!mo@E?CBM3eF5#f2SYQC zhAZrzJtit*w!glPfO*Dom1qtECyT0I@bbVSZ3~w`YSz9*l@iL81lXd0c9M%NiEZ(W zT)}QXvfra0bRo%})L#xp(2mbD5_U;qtyaTHTnB$DuR{6N5ArzH`V&&T@w|Bs0 zW5Dp(8#i1AeZ%3H_{-vr+G05W+u7Uex9<#p7}${1#;|J7WLp<+UCexn3i>dMUZFgw zjpN7Vfg65vxp6#Ec55&X_>zv}Mv%t@q8k!-Yjztt900&U{HBKO@-h49dAU!pi6Sc1 zTj2_}rKKzW&!x|8ZT0iRvz2Z=z^S?V%n4)($xrh&>z z$AV&*FBd+3fxa3)3w>3e@W3mKocTU@k*)FM!M`QAlE;Xtv#)+V;n_#eq&y3NWjg|W zkv{JnA)sh?+uhpJ<65Ma-ORSWZdID$#Zsk^najNU?mKV2_3Ep@@2{@C`Afs!Km7d1 zq&~m##t;51_*M4R@80{4@b|qm!}PO(G6ShxFc6H55{efLZKjmkOVYE%Hq#+&zY#@C zj+ibR`58r05&L31N{>QW$KcH=wbqTu3QjAz(BRmvPj3+xeUDZol+LNJgw9{5QVHY3 z1Zv=0GVE=68^b6Z+Z>%vg%$Qp%H*j6uncC6CWmoBadHa`4u?+x-I0=@Sr7|^rM7A< zrdvjbD=C5{nLyX;_4%!qfvb_8{|+n8}meD)uF_tMl(rWgJP~0k!Upv459HKmF$?tBSUBd?}B<7 zl!P^(Og86@&URYj~ZBCJzd8(USOc zp+NJXJrdUuE$o-@9bq9h;CGYKe!=N5qUWnTJC`iT`+IfnDwvxg5epqw^73WX8D5yy z-B*nNoT-@W-92Z?(TI*yRLe-j4GWTYA3PNBde9GXCAyh+p_<;c0B@HeI)j(9{( zg|U$Pf!PjcbD@Dfl6xifGtI!coF>#c3JJ@EL+6O19Og*kD3`PGVR?Ma+^$?6VwzN% zZf$4;*9gP#qZ;*uXs%@KsMf06Fb?F;5mou5odL2=9Wdf6 zwey#j;HFay3>6k=^a5FKKQYIKg#~($=K9RH+@#7G_iqx3HxbFvL<_@alN#&>?oI89`pIRp3PBPzWNZF&_bP& zrUgSWBC#Bp7VKS{fU1hQ(A@n(X0^scnofv3^X*DT1 zH4Tiz5>zRbx$UewS(W5_^ait~{`E>&>ysS07B{0#j@y^+3-stZheaI|m^Z{ew zY%&rWez;cKM6`?%?DY(zO|KnxD)K4M|F|Vk9Y;N3+%$LoRCku*rMfDuApfTG`PA;L zdhs=#0pPou9*fylRxX_EE%a+a14F7-V{hl=#j|HGoZ+$3Si-H2r2)a;!B7N@g<}bu zUJcjymN!9DF9SBv+N)A4r_zYni;tfOyCl9Z#?e-fwNCJ7=$>`%4AT4aj^j5v8dofU z`2v6UcK7%V(r@$TYB*FJiG zeSMwQUjg7>V*87KznlNZ=`-tq1M*Gn^o><_*U;1iyq>a!FrWd0t87T}d0cK3$}x%( zKzzV~wVYYSt1A^;E^43Ad=wI(r8_tPZ!oT6IJh@v7=BhHYbk^H7d4mxG#TJ3P!jtq4_4W|Pe9 zNFr7Xlo;6?+k(3gLgOo(MuN0iOqbLCbSAwoxGcmr4SBRfgj30(fNpw#k|Y?2zu6Z? zJD?~!?GHZ%Lr#Z>{)_#w4x&g$R zb-kW05-A~)M=Ta?XfNHYz;e0S-{FaPM z4D_WfxHmIu&sZ}USM%j<3o*N_WUvxjJZ-ei27JJGEMdEX%nf!RSxtJ73R`zDmPRsk zBk{0MOKjFOe8Z|0?lhYZNrqtxMimiAF&JrrIE+a!Jh$YnXh7@AHeC{X5Z3~57>U;`emV^@MY56X04#u((h zJW0FnBq4p$u_aLwT_@*d6GK^%ca82Q25=~LPS#ILgPAm0u8%E8W0f?ax2#zl5G{&w=Vtr{F!xx zyWeXFCEdS}Uuh&|xx7;Uv|v{^FD}auZO6QN+6N4DzWU`CpI`o!b~wzxb%f|tNT5d$ zU|Ee|1F@+=*pW<>Zo;I5#mdY~8_)b6iVN}1Gl=0q@as_(7Q@*PUV$frp1J4CmKO+P? zSDdg=!6Ci4EJ*8A_u}hMOtgA@;(R_CJB{??2=IHvoiBa?eDQJQc6kOG_VYY;0Tu{J!(s+vndq|EA*a zJ%|2Me)T^9;7{aFk|)gXe{uVr^^J|iH?FK-`s}k?9qxdA2e5Z`JqG~Ykjov?BqJtf zAn@1i@*&mN1+K%SEEns5Y3&8=#o3p*k&6hfR zH;)MD2v)vP7XC)6v?1Bm;v;V{nwN(xdf9mt&F8auBtUnByCSJdP&segSP`S-7xB+o zj;3<}-+YC2z>nk%BC#s+5KQ5yJhJlwu^l;6gfAG_TB!hyEcI*l}ETkv?8ET)l* zB?ucH+8jm$WFf)|hwVplY+G>IpY?C67g&x1O@)98aTV0IQ9%fqGjd9 z0DKN(K|DyEK^!=8NIel`KZn?tx5%@$bOADM$jfE(?P=&7;Xvlwt7ep(yDSw zMui(#R@{^qu{O+-qegHPY{ad2tvzDoRom({o}(#AfORxu^=gn`jexkdtu{1RR;}G` zY*|~4hgM<++uw$T434cv;bEhZC^YWK1xuR;3(W#L3mb9?Ghfsc0%=i%1RoO2Kmvkv z0yC}ZSogSd+J)5rCm*mj4GK$knt?fVrWzXhXJNyAEjxmMt4Y@{O+|AxLNn*n2@ab# z0r3z=_X`khZO(0BEsQE)^g+Oqw2AnvO`+^iK@0RPPyKOeeKB_7aA&go<+D=h;?%_Q z3S?4~gkwQS5M+KT4hubIAA|7aaV`f|#xw^nEBQqsQrWQ|p>zV?v^9m}m-}R;jM~EX=6a96OS3gG)+|0iETw)AR5uDN@(D8!kC>Xq8FpN|;+v zI+y4XM))+3tc+d2E4nIXVAP6Z=#i7RduMK5y7iw_(3h{O@)^iFeU;wcd3cvsK3}jq z3vVsozrXyX1^{0E%l#6L&CmaO_rYJ^)$-u!>35%)!5RbIdOfo>YRPlB7iaX9K<{XT z&Ov!XkL0ar8*?5!(Sxu6z>O4a?R@BvS8Q{J3C*leK~c0qDfaAJMRej-Q9f!%kQ4>-$UlN_G|s)hrQ$D zUYixCSYsBkEzBlo{okZMp1pBn>FcEr?rvxctc+_-z~+F}U(5qlm~CXmy*JRzq_{Q!>O z)m4-xAkvw&3m#@Uzof?52e#XdbfJWmFRKxxjs#YjCrO1YUXkUNuCIXL2yyVjn4)07TZM^VXlhMtjNo5^eX{c1W$Jbiz7L75_XtJ z*}*_M8trHlhv0e61&dL!+Uex-@(6YZexwNGRh_&yU-T9`*-q}qVlItJhE6e`$G@8v z3<@4c1($P=s$jV`Qq1J~e5FXaRV9a@NsOV96J4~2HV4g&+K`hl1kply1!;lNX&V7o z#q60tRVSWNU*S6EnYyu;1FJ4p}pa3(r+`3G6`?+FwH(+psny=SdI{Vt%1(~A(w=cjxXt;wtUFxe`jDF^%B*Y#8X>&qNfZi7aTN4e?d5 zWg@TOAEce#Pg4mR#-&iCA2g-4C(>q0rw2IQZd+ld1GVjVPCcSqpfg}stcuwhvNFm@ zI}nK*xgjCjorHunMo1valky#)nLF!PC^Tj{D96egg3?T4~0!H z{4k)EO|w`~=oF|hNwLyQHRx6|)oSZ#_>Mhj?QeY9dwpnNK>#>- z+}X=FM!j-N=ZZAjW1hFdauRu53}rDk3r%4RaY0+FJO*t^u6`aJVaZL>x!BB^g~H3? zxL~htfhvX6QT>2~uAamuS-eW!^13>Aa=9ODSzwzW&A9~J2!*>I;rg|;By7o0)gnk) z`9ZQ7DyTT~k=#FMY&X{N-P?Ds=!|(h70+FKu^lZ*QxS zGF+h`T|kG-y^R+DWx&+7+l;FcXqMd`&yJ18@)numX0qk`GRgma@$7n z*{VPv{c2GqdDuz_8%Q|@p3Rdk{rh1)^I#KjC~_aHfOo*n+9Sd zoquryWX7*M|mt7k-%6y>Sowgb{%$?K5=pYWo&S* z;&Bq^?(8~Ffd-TI20US87FwS%=5efrqns^BQu{cb4Meegv`(tJj<^LnGa4mvmVEVp*zgwg^a0*<}nVDU#ZFGVf?&y@jNr0Z+ z{3@9VGD^IM=^SppjO)S5Z;)rAfz|+eqmvVmNQoT`fTk0$02~r9hm)1q?L_9U8;QUw z_#7b&LZeKLRv0}*9(kK|m#lBiN{IoZelb|XUPdC6AZff2cN)m$3K0jrAu zV9^sK)T&V@ja^L8;lNN9i-~VZlT&1k-Q0?oB(+(Y;;?-j8f_5uvuPcBWCnEE9r3G|Ioi^@^8oUrvp_JMUlMhi|0 z2xxicB*&2Dnk7fKARSy`mL1Dr#V$e1#_-wOV?Wl`@`o4Tfp2ew4DA1g zmNfbjT6Aq|0L<{_T-{Y8JDdoiMGP9WOAXfFAR(BpCNT+}&^Eu2VQ?Xf3{@C=rSmmK zwQ5l*Ppa_9M&^H?5us-R|9SS+QaS}+Sui!2;2yWD(b^{yY`NUmBEs#qHCn}E&8)Hb z!w6^SueIuX)Nadm5xd{^3wyoy*B38NO3#P3^0N7rd1sq2X-6Aj=y}tIO&)W~(N=4( zLC41N)|Rq`>)ZoVJ?K=oL+?p<`W!t;-_xh*^g4SDzyJH*>ys0u3DUjGbC(}Xll{F2 z`6d7RH*5OYhEM)a`K1%?-i4{X^5-k3FI_rw@!a(6^4#py{EZto{CdBMu?mc;aRJ)$u zYi%}yGS22K78lf%GZA&vnnNO$g} z8JvaiBhCm;qr-~{sx)aWP6nAWlg;cvOfz|S-YAaIOcI$3$)^BQ($@?rbCjKNe0W$! zt02d`*GrEkS$V;z40F;#){}-RKaMhk1FK3{SR$4EfQtrfgJ+wcf;s64#3R`7MLijr zN2J?<=*ze#PAbZk=4d?f(i6=x)H%RxNDp;m5{~%L z;Sje=ua6EV-F9#$AwZNJ9h`;~#2A*71vtn+Xn0`sGkQ9i_3Xqf78Dm%YI-h2B5mO) z5#mXPmuH+iovJ(JWZWchS#Ekua=H>um$MeE2RW9(l?Y<%h|bq)i8mn)%N#E9#i%wL z>bD?MYCvHXRj@dWMYYJANK2Y_kWe(nany?{Mxs{?%ws8-#L^51FM!Y~W5p;gp*w79 zCOB6b4q!hQjAjlaS!^&50S6}eQdN25tx#w@hm6^8fK zN6S3-%&2G(Da-wwNXS)a9moz?T^_IM7YvqeZwRAT%p+L3JPr?CwUdO=6CSm)88Blt z!m$lH3vR{U4CXSc&?e}6MmSnYW}5|VDFI3&6+4I6Dn46WM(zn$My!qD5kXt(Vv%;f4%zd`IE7G zUw-}3;NXS9&o6vFfnp=D001BWNkly@SQJ@|O z3siSarGSD<-K}k{s9U9`lfrUA8q;cNVw#j25)*eaCbltZ(yVjQnTuXD(`nM#?9Mhb zH}$Hw`v>j!dETRQu}dQy@JAXY=Q+>&exJ`XEl1O@wmtH@-w3+cDaVnTriifvy6Z<{ z0*s9dE$g};d0>aDsbjPiIbaxKcp*9OI`G|OQyO4Wq60|;Q=V4E%*u%y*gH#NPg=}n_y>1YAgu_~=MF=)jYk|7>h z=W$9?B@B5xo|I2_F&9JT9aiRfH3)69jrPGr`KENB{-F zX!4D*>lb^y&{n3B0xvS$7smE4_kzXlM$kyu!7!HG515@7o)_2~HUnGO6-KdwX$}x9 z8N;?OUqeM<2f<*EIAUtDNj?X{M?)k19ze0UIXtk1awN=2qkd2%x!?3090Vpkljat- zmq+BN$BS7yw}Y)#_)DP@*lTksU3mX6b>?S9G!~sjke#SOa*=-pGaN+ag5N13?11cs zV1+{%m1a#6WY{J88%O1W+h3;&yL~l(%_YJsCfHv?1}RAlN6W`3lIU@(2Gfhy@`PLN zlD;zLR^rJ}xfYKXTVj0^^%m+FQ~^=~Ii+$LTr5sMqZ|pX3rWasQe5x4=xib`^1Ge{ z8H-&E;dUb3ZnwkWafHdlLas;d0i_JLF$G-#?lDZ0*IEXmBA5is`(o zT7XZBkZ_dSRg_8`a+Ml0(1i+ngf}+MYLV=$kuAe%b%6S%0?tX~WNn67!^DS*nBQEH z-WO9~^8YK6mYLoJ3;MhW?Uk#6(8uVcd*`Rl($k%xd&AxQJnb(G@G!zfqNBreL~f9v z!Qur`-O?Oarqy^A2Bf*sOLzw*d2n1YwnQ+Y)XP-y68Rjeo?)C4JFWu3gEsnVn9NF~ zi@6*-pu=3F(rW>*8qDJk@!=^c%o~)xj!d{F^W@pKTXYmhARE z?)#3NWtb>hSkrx4{~r>TA{hR;CoT^7tO$vBV_#kWYV92@bl;0^}i|* z2OYB9UHMq;{P5_5c8%-NVq_D0bxaca>a}tmfuokZr|YeHXs=e2ckEsw6fe6`8ypYS zSP_gq>{>0+ig#a~j)Jp;VtG`Je28;1yEx--8W+SeFi)3 zuRU0M&^tSOduHZ|sP8}S+_`$^kGS2q(0Aka7y8ciojcdpbM7yFIPAOdhZ~}_@-@#E zAJ44LuJ$f1t=;!@ERy(RSp%eCaVL{&s}Jxaq3O?_h`asn*3wdc@0Q17>E1+6yt#N= zxnlYG$2YHEy?Xj+;qsM*g{f)CY;-yry%e3Eie8$U!Ygt#&Bv%5-rda{Zx`H727h5< zxQAC|+b>|v4ydPB?5pz#g+<&A)*VNP7AgL-PB5^O(^^e2K7MW=b08XwB+OHRO4&4k z)iO@BBSYjBNhO0nL!6WR2;&e0Ed}Aw^ZBNJ)P&;dPEB{@9Zdd;*A<1fv=q`thZYjT zy4YleV6~d& z7mO?@?mh;ZBasYxkO-S(`4KQ30rS0l0q|L917;y1Qb`@4Br&`k0a(NIjDS=%5HaD3 zI|m~$xsd}Tm^vsrl7F!+E=xmfnH@sNNOajWNxK>{w>%?ACvAx|gH3rLvKxp10c}pw z=zc!{^2WiW_+@$QAM%(iDMT@054*2KTATO_J6W~h*Su91vELZLaskjG?-mByfZy;c z9;Msm^kXQROUpr^D50j_ka`y6nlnk!Ua`C(a46+#fV?6A3ph#DPOhXLontQHk|=R*n1t4CMO$?ehax2@j%8uOYEWq`R-VtG(DQ?$sN>_x+$}2}r45wkB(&mb zDEeYa(Ja;WFf8$yT7gzUCDq`^U1GIjJw{1ZFJN@};=l8^oMb!h>~7@3Vy+P!j8}HPeTR9fkEfdZ>C9!t&k1IZeS za|NC=8CM?_V}rw1AMHUa$S-Ld)L?PGkX|l6Z>z0e^$+sPqNC%T-Q6$8#~TDr77LZ~ zM!Hgtr{xzGl8f|{Bg1=`I@I>Fo%iBB`rj|z@BRDgs<_d=K`Nj8Y31?CR*SY&8l+*Ha$KR_mC$vJwc|NdI<((T)`Gf$pi^LFOh z?Cfmst@|T^iM;M~7vF9ice@BR|Lf;BKfZo_ZQ<_1%juVw7a*-uFGXdqOh+$Yc{u%0 z9Pg!R-l9>F+}}-2J&Zn_`bM5#nzCP?deaJSZ^$_lG)ekkw-{5`5vU7TF|J}Ri@x|s z3=NV)RYZw?aW%c@DKY?>bfDoEW*C!JM_#Yta*FI$nOQoKZ_!y8j0NeYxLp@AOQP*g zXC9|*N8V}RXNbD`MRi>w?s=`+MAQh1Y9I-mKg5KUdJRIH*G_b2Lr)n-!)T~i42Pvd zm31R;S-QrYk%l2?&63AFY8b%eNLlJ8LM%qt0gS`QJn>oP1G~&DmU~3FvO?nIczb2tr9!^~isFq;NahZfdzYn0d`T*0><_HQI zFh+ea*#kDH*HM)lblB^1G@Ybv=)6|5QCM6=VNR{;ma92GOfdX0G}Yw-1`BaRKc3O{ zIxzn15|MQ)vGp_Y3rUv87Sc!lpz1^lVX4_2tbvd#CmuOJiTy3Nf^j4@_G&@!IFba~ z^Hh~!8PZ--l-id7(yyF^@YeUx3EaZIZ!wvuy)9#>w;skoR04m&QiV;# zIq<0!j+&~S#w-?6RF#4Vu*l)?qm>V0nkK*f9PIYKI(~5T{JUmpjz~%@HG}e8V)*F4 zY+c`PQVALz=%s;DNr6BtP;8-aTf!wJVQq*0x(#t-YnXOrc5RJD5H}sS#xhQ(nT@=V zG{bIeqNcGXX6b|32Ok21i%Mv5CNYMClW5)`OJgzm7PS>v!m_w37X0OTCU{&>IaWIUU6_40gh>RG%f0(6zH6tXhU8I!iX4f=WeAxhmGQH%U-j!zU>l*34)H zCzTJ^bR?bmHuC?opuhkA3$yn^N6P0jH-W?%Z5Yh30*}3b)VlO*h=30N}T{}zo(i-Ke)0?c0XD5h*eT+|cR^9=N>q)q}TAZXw;s2^%G^|VV~RU3498=8(jSjCS$Yl(DjkQ>(|x@ zpKDvd*tNCz)wS7kTcMHhz42toYFq6>&T!?7@)6!;3x2B|8X2Kkcx~m%{S^^Q0lKeT zy|y(Q0{sp6!aKX&Zs+*q^zHli@4;;^es%BO`XrDQ^mP&ddS`KZYzdG{a*Mw};K@h4 z;>~2exF?6s6N`%u{aqsc1stz0DLy1V%Zpiqhv7(Gc^3M%6oXu7@PHsY*Vif%S& z;Pf^>HAQ~oHJX6|iNRvS0${m0L~L$u;H)tKZanbZ{k+U&GOfUjzX}-54Kip-vm|IT zAP^p42O-7N!7N2sE><9I(5=L~;Oe=sW2RhzJvSM&VE}qvylxoTU_bR)ijOpkl1i#Z z5VsM2jU%DMjVyyHsl93xL}-;`EEX#m3?ajSXcjJH4~fCR-dy3ZQQ{sq3+SaW*vhfh zx5V}Fp>>!|mjQMtt6dB?UcWqj4^#O#)xQ8+f+M+2jO;qD%Nh7 z4p~`9dv7V0D#@ytu*zsGkwycLLnO%lSSmEm9)%civ5kwxSm;52D3oOVui$lznUjpy zV1omTfCou*@sKzPv|skWc&LAmyI~HU+y4wD!GF2=Wi-~Fe_Y6Q9A9ZLG|ogzRwc0+ ziTDcuo*m>47{3@zyu#x6S$Z^FOh|KYh%j25NsM!$KX^zwC>csg3}!k9K$fyACQoWN zAtlfel40gYgYU8?n6_Wap1sVY1QQ;JfbdeE<)Ph|4q%YqF!=B$>j+tSH04P%&x#)4 z`t~+ERpl=;{puzN1a-|m-(wJ7ew5~J7u>>5KQLth`~Z+^+Y1j&JI%o}BeBf7SqJ9@ zO4+6q0M|_dE|Z^u#dd`==P1)RK$2~i1V?QqUMz4B9hEU}UZhabsH&l((up9Dq>Z7b)kszCF4VQJV^GpJ z=cuMtNh-Zk)Fp2QhKyFJlpgJ4vPz20_aSyCVRcac0oxwe4u;d@VCGoM>f@`K1e>z}?Di1z-un z8tZ;_`Mic!^8M{jgd>}DJ+g^cj%jmBL|0~nMqtNhN3x5Tj-EO#Nc0R(h0}mvqH|~6 znX@a)<&WTmZY+zn89(_PATb=anMo!3Nr~hZa)9p9>g8u%8 zmS2GH!9j0#t|$L@7FyAICC`Oa1W*G!u>2p}v5`D7rK;J+UOKTU;imxyA*`0%k#KfxC|uiOOWQ`1lqM5|0Ft0lO1KYJ%>f zpf64)CK8FIi6=a{_$J)Thb7dCMqju07p6E5Ntl&evnSnnLgfHC;57T<%4G~`kcP;a zgKibadfm;ox>CL|BxAsc-9_Tssk;aCCf4rW7x;c{$`YgWR`ld?dCu zSbGF;{mAeu9F?<_MzfV6YXM5xnpCz}NXY3jSu(9fKv;G)NCqVXCyCTd;owvmpj%2F z;xJ}02&k8|@2SOrFh0N9|wsXZ{>wm&)EPKA>3xXi7&369g7 z^e;UK#bcp8j;Gm%6!+6_#H=f3VeQ4AiE~Lh3jKp|-g}lVV%+pakdk=r9aQ)3a(}|V zDCf+o#**I!u8%mTChHxbB+JWXuc)xt5lrk2 z3pjo(tKg{Zvt=P{+dJu3<_<%j&24kX-q|tne(LX0Nq&BnH|>1>m1!@$0_2*SzY)d5 zTSQvwpj+IjE|?NZNyF_zCBK`O$|O-I(+xDQMj|l>6HO~E5jSffr5Jz(hGqTB!Xq{M z&dsY@T4E>Xc3Ul(NUP|XP|RKi_7u($e`#}41{@W?FhG}^Ulugr8=Bi`(E_Zm1m!#P-WxIbuCKfW8jip1&Az<$;@zdi3v;_g#&KvS2m690dXk+DMHxgFS0%WT{Fi84 zbP}^JDBh~pYFKQ*qbx8ilE>mJ)C8ADH496mTFcHhSn{uib?{6#lC%d8bK5(r0hA=m zGRm$wL*~8{No>GQ^c4?^1Yt$wvo)_Xo~}B4*~#qCtSrYR+$Ya7vO{KRl5#|bbY!$} zcslaeZ+;7*{4W6B*?*~^+b;t?e^WjzW~$Z8m24wA_5-6R?aMNP{`U;;__Xx17?vFB zoaju2>wsS~vYnnXcYXr--At1Nhq+)e>tXJO0ml5bXPOLt$Lqduy3Y8w^g?H{D)aT* zQb$--KUK|nn~`e{0cMsp4VsaZ%;pfoFxSL*=pSF-_{$}0r>jBBy@TDkg?hxp)EwV@ z_xR+^nX1`=Sw-Cw2X7sv6|bmx{%~^QoN|mtulq3@$4uwV`5Vx7?cCP2cq~>p@}}+i1N_MNPT#%*xqS(C`*eD2`p)9I za#>(2nC+uUIV6=$Bqnu(%M-UIo{ZfR9hK~O7oP~cCMFjX1l@@x<-3VTi*g4(YC;IH zd}bhWVuDj?eukHGyOprlt!Y+N+7Nt$VUaIWJq7%9ZHVlZK@93ta`u7Bd%<_T;{25$ ztc{`a0BEgNUwi^LUi zxoMOImJQKAgVZwmDu+9;jF2v*hCx2tC^fP{iNeBlpg?C4-ARFh$e{}bI)A}!rIi6J zH=Dx0Q;x=@Mx$UH}W9XFheqeI$QiHj0K0*g^Wqujz-vLv!4+g!@d50=KwiLa8p#~Y z;6O`ZNsgOW0qHfzQBTUTQUDTXksoE$F>6 zIu#0pY=yc^q{Ofrgd5&uOrVj+Rm_l@v!VfQ5#2%+FkZWOdl!S^KYe^I7Ixn{R0L zOZjiE!L+T0rixma#f|Va-=!^9CuMQ`hdUuEeTq4;TzS%^V>?Kw?JwosNpN9?dgXH0HH2;t4>-5jp|YV5+mj}YS^rQs|p21N%C^7a#ocJWWK+deD$*T z)i7z}m2Ow)^)D|ewgUO3)kqK*i)eXDSBvrrb5;lbtCnGVCvP^kddv3Sf960jkJScx+!k|X0IN{ivO?PO5-F}mRl=`;ZMaM_3`)GT z36NEf0oavC3YQfiC-7CkdSU_tYAlME$cWG7|BJaGx&dueLYv^_G!31ei8!?S#>LqiT)#uo$)YoCr1mX zQEj*gZI^&?9ZO%Y=ea;J=FJS4#IV_n0wgShw^S9w$B4Xw#R#a2DfDyed#jfg-x*A! zu?EJG+*^3>)}l9y{qG`6l90c_nqL4g@~~!RXJRvg#aV2AVg1c!QHwM)1NIAPG}O_| zoQ!4XuCX^8nLRkk@=7dr5W^H2=!*sL!O3h4Z49U;6izIZH{upR9*>}x0r8Wu6V^4j z8G40!U<6sowG+1xYSLvnj?j1nq=qm{bsGsQ-G436D?Ay=(J=bLigXYe4x@b$)p+EK zoSq7>Bd`+wB5JJcEMpjVF9@>xqER^o2u3m`g+ycE|xOHp~iwkN!u?3iv9AQdlyVixlL+xMjC338Uf4H; z2t)Xs7LFWfQxJWXYE}m+;l)7UW;*bVAa6?WwOSH5uF7S%n$DD(DPg#6c_;V=d*DF2 zRNDSNlc|1>59HhevlTcXC@q%~O8<~S1@>EDG9<5(*LE>Bu3ckparpO<_9QV+QctE; zY&18q~2}Wbyi~=QA5$nhfWMqNWF7(hHwik9U z{)ryKk=2`mudC;|U@&?4S@Lq_4-XT0%AA$LnX_cI0tOC)x@zi6oizKCNSIYOQm`^Y zNTs%lw_{dEPywjiTI;J6uyQAisj}kD$^*<(sv20(adKGCP#KP!1-I`qu#)6Bry@G? zL`qQLiWX`$azkNOzM?(A03H~bC=piBO^=bPD9~eQ-OZo|y4pcpX*{!is)IQG*9-jV z*S{|vzPLFYCnt3xC5{BWgMSHZd5Z}oVfBiiF$rsxYOVQEcL?bWjwyJDZ%~juX2vk!xd}{U=KlDIu^~hQ2o8Jz( zFS)J`w|Y60JS)l7wZ|7YtbD$5rbp<#>}!?t#Ub3ioui|GJoBrCKy85jl(f7nIOJ`@ zET1#bOe!A)TrP*n(QeR+B1yU|BuA-8>N*1P3u zooKbC001BWNklI`o=iOfs$)nk z-zZ!TZvvm?zQ_Ge2GELfbuZi^V7?$WmiI2?YFNmOTP`#PL*8uh%HIyl8QyWti(U}t zGelFuBy2G=TM{`*g00U%n#>LXQhD$8T3hm9btFW~O}(Z%Fc&3*Ci$)o?|Wg$La05~ zGcaAV&{|yKkXb<4``l_0*6RWLeUG3?YO<^3uX(~nV8EyuFr3ZKVg4*AD{MFxal;4<=Mi$S1b8FJdzRac<50Ph(1;Y_;hbC* zY8!LQ!Q6=*fVnS-jg%|*!T1~{QXEOcG{pP3Ple`Ej^%z$t+O5GqYy^bIJC2V0X|~v zgx#S9jGd!)0a=K#_EisqP+h@S-|4<@0ghrcGq}-B2yQ&K9~IcA(Rd%)tQ%JB?j2r} zOJ%6Y2dX-zCiv*)vAD1ub}&NR<#KrtNNKCrZD!bju@rWo(Zj;LEA$Rp7>9-7v??x? z*VsFlj9lhSNCUu?g-LsEQWq zo9VJ22}&(FdHA-%f(4zZ0f1ed%+H@ECsmumB$UmH#Ht)hp2W>Kg@*DuA0+YyS*Mie zTz{6hl;}@@G6DX-HJ-fQn}K)yRe}O4uOlq{sw|> zP|u_Dx`lzW=ln2)W2nbM_~Nxtnw<{J$D$UipRU00|QEgHaeUaK&mvhmFS^_TxA z2pSAH&_7lZEMjmn$52X~sWe8Gs@cUtq9Q-n{t( zmDS5(hXUlynhwAG?^=bI%4np=&YU=_9WTbqANofhE{=+Fk*93CEwA9F{I9oDR|CT$ z|7}}(1DZ_vOm6YEpwS7r7xo`NeDGj&efc}+q*m6}*VgVoelQjtv(GJhjOJBA(6)E^ z=ItAJZjXGzBe&_FTrs!#=@G|hOx6<(%V}==@gFt0bo^loB)Pm)C@Hh@m6j! z!Ey4Gx=bnXEl;S~^F;aIOG}$&SbV>o7?NVJUx8Rq-o%pnUgfD0IvW6Ig-;P8biAY%8 zEbg=_My}*kbTUOMsx)qpCZVZFq>9o?m6D697rCfb?XFU)_NKYoKeh9D&P#f;CKBM+ zKk|$C`99}7KM2#nOoIJLg$inC$RrfQkp9sKZz?UEO|ThefeSW|U<7`VF_6t9z8qmd z$vit@v^KG;k>#*KxZ$w9a*x?D1L_`b(lqVAyBQ2caAV9zc263_g$t7hjS{Qj8I=th zkJ$XOf`{}%eaXWzzKa@*@?hd9GvMmT9{+yjJ!!J`P&*qG8|G#>M*XaLbG=^oDqw|V z)%U)@1>7jpxlk>`Wo0xX{;FOzfG$?+)gpEyq|c9x87n8taF;8z0I$v>)G`D%7+zgf zNnz10kIgc+o<#|57YW45+mGU?2GB(|zj6tq!cqn$;gfZ?!^V~;XOEBb&|0NN8z){> zOM~%Ux{i*iQ&hDPzS`DkY55u054Z7%4WA8;>(!MjeVe zOT7#PO~%is2n9+K)7Qx=Ew|sVbb0?W+@<*lDORO>UI~r$26iRTMZ1X{OLORwecJDL z!<^lD*k{Dt%=L2yu(_>VX#5z&BHB;u$qT8GAIpe51RuGp>wK8I-r?XimRMq zB`Pep?`laKbuXMnJ%mvqgT$RUEVTO_xB}|{-nfv_x1hN`N0aA&XtS{gBf zx4CtnJ5&Dv3nnPK#wnn7(9BT{Ol8D@ofMw@z%Y56rhvJ*pXR9SQ8OWH-)-R51z49| zc(ttr4kx)Q@+5gbl4Q{a(CzWI0yq>?$u!wJ9fZ|TVoD9k<8TF*>_?u9O*q3uhz%XZ#n;K`=nWls+Nn9T1(peMg_V% z(HMKj=hHjUH8j?Os*h8jJb3W`ZAjtiSDt=#ZTi|>M_=G~X=Q1teLuN6vbJD#XTGP+HtdwI?EucKNWOo z2kRtZ!QH@6nf**~@}cv6uVaj&uXkGBw!m+GDT=jbP!I)@?09&|PSl>X^LhOGrFVbx z>h<6Md17dA>g4pv+2A1P!#q>j=Gi}=etW@lee>(xy+(yEX3o*n*_XU7t$ON+i;d`P z{lBOM2Vt;f|MyBkr(dB`r4lFH-A)sB_D=U2d(~pz-kRQAG+`4t+ z)+_h!-J6&w=JQ6uQsH25Iym|Fw*+B6|JvB?hacU(vjC@c(z+l71WPwJUSlY{`I+%h zE`6XFjDj$AVKds~N}s$Sz`f5(RvP6+=eovPVXGp^3xZb>+xvQPdoni)K36u{YnWRw z0J@9t%7+0pxY=iPGI|G7GBrz*&b@odh_XE4a-ohhkA9`_{@*-p1+~S zhG<$(`#8GiY5VdN8Qe06wyOr6C}P>_CWc?U*fp}-h*3fKB|y8IMrozwhMwnG4i9|+ zf#&KE+BxvoYJC zcmY1ViaHuS7LZ*oE|-hNM|HBI3B6i1c$V(UfRl;yF{@mr)ztRl3g(_M6j;aPawwZ} z%xE!ayBq~SgWY4==IVh+pCP@GbZeA`1;btz!#uV4_()-rV@87?D|ACOgJ3Qx&Pshg zGW;!$P0oV3NUK0r#>%5JlXPVQ&jz*M%s`TlCRN3dw;S^_Gh>sF=^>oIdi5&v=gIk_ zOTDxjff2CBVm>LcZ-m{{aH^+ega@TTcH;>@ei28BEK9atDW$O(VPSHgFO>~bsf0Ge zO5HFd&JJf)aTLb}98VFoVKCc8_gFEgH3aS?<5|T%r=-QQSF|JaxiN?Hb1r0+Vc*Y| zWG(8lR141grAjgky62^=x__I2@nU1UY=T2^-mq3mHj_b^4HQ%v9_|Ote>L|FnR)b9 zrB>VbEXv#=ytkGkY^qs%M!clqS+j=0b{%et>e!Gkgn1g`8DCw`MNJCIlU!dvJG;oD zjM|XaFN%SETCF*=)8QxpdY}XjZk*``kXr+)*NENPItV3=#(7jT;66YPUDICJE*{WM zc&JC>h@!Xw;*opupZ2zNRZNJt)u-^&_~mUw3#>(21J6;)K;6-tsuVo`nNQx;z;h92 z0ms_@Vo7SLAJ`j?cp`IW`|9%2^p(p-Zi&{o94&-F*>NRtD4kO9x-#dkBlxaDK34E0 zwJxMp9?Ef9ol4$%6iKJsk%GD%X`4aZ3k%ar{_7qk?p~5jSVR~e?K#RQmh{9Ofw?I5 zjxT|K&4%>$+wUGA!kU)(SAO7YK87X^qrEu1+^B7SYNwo&=9LQ{uwnGq_0J{TGQRx2 zQRhFM1f5D&UiFH%cm>}7Td8Eb*)FZu$!n%P}B438-M)!t+CR;H^D}N2ethU|8*1D z+S$p|Us{a5bx*Gt@Y4u!J-b;H_X*NvzRPQa!B%st(hRqPXDBMDKVi|7H6W;F>Z^9< zpPBgUd#~KPdDHOrts6It-2Uz6I};Q4#^xKKYPL`SuUWjpCgod^W!^rHa32@ z={_LMc?%m4jcG0}77T1rBpcSDTZZT^7VIG(Y(89kZKEK`GSI2}9&S2}3NIHQ3T6vX zV*6;X^b0^2X;UXKPdrQf=c+fHLqZ%_>FRLINdLOrjfUp`-9;T^b@&Bc?2V)%>Q19ZkuG z&cqTU%A2HUDc#_6n(*h|t^;m@1WOojqskXUF=NL-tbsEb8wvO>qG*Z<#e9wQ4#{tn z5fv_z5lsQGF<*mS!`rg)UO<_paheb;@#7H~F02>|yaxql?#y;~uf8{8AAiP%RHe6J zuc`tWE!0d^LYe z|Iw(uG8!$0#fF-y{~evNCr>^WCx+pEmp4G2)i8PnldtcBRXs?MCBx_m!{Vb+L*c91 z0?*G}RWH)ycQf-d_=V?3FDXLQPHMY^llC|_rN5*RE0tmIn~3cWrFuhrktTOCmEKJm znU!t;v{nZL-(q&;jis{jU6MDH(UD@9981P!2SyXk=hRd(MJ1AfDTC)E8CuDBDvtFY z8CH@p9aR}>L#@|c zd&T&=rf!F|b*Y^V_`N2nrpylIV){aQt!dW|?Kk@5hZdV&BfjI?v>X}#jp}^ixrT$= znoC1pjSLKl1(q&#RpvJ7}K?LVO9jV8)U;!TVLEr2(wCb z0e6UjPWF>_Q0*icLwDkplRGW7Jw6+6a9$Tx25{_TkYGmS0B9n z2@rh!`d{vq_nAYVoN5job}0<~A6sYl+thuBar~0VcF0j|FK%({U>p;>#_@>e7L)i5 zMO6n3u!v9tEsLX|h05LHqBZJ7ZjdUWDv<(;0BsUnOugW$FH(_MhnOmDnY2Hk7rSe3 zdbR&y-_P?qZf^?0aqNQ=6my>Qe8102Bv~TrNj!H5w=(OJlL5nZdlh?|4O}R?UAFf7 z9jJK>}!_{M=v#xY5Q6z2pTmK27xsVHmZ3{W95Qlny}aG39WVQ$sLxp z&7FJBcH0sQZHmDbnm1Z*(JS8Dg7P{6m1u8vN6O{bGQ;qyOx9ttzJWr)Ie`tH`7Si9 z23J>EE+2ypw^|14knelIaK?V0;F6$V7X&-PU~QtCAKcwtv=b{UJOYg%GxRJ39oLO8 zca$SoJV$D(NH-W)5~UZ4Xkd*C#bYNcHtQ>-rP)~kz!@q7-kzr*=@9)3Qbf}%%fQ)F z|3W;zP6VYL9%B0Z(4O@eI~$BLjwTQb#9fd93DPTsjn6)MxDc+!Wkxa*91fRfgW4T6j%7*A6tmC4JH*b6`BOHwooQ<+-xqaT$jaQY?Q2y${|R+f7%c zfUa@BTAh|x$?!P6T~h)_8c8&flPI7yj?VA1+S8WY$Vl+YG))nK^YFO80Ol^4Arxp z(TbD3(q5kgXc}cYof3seGsVX9QZLFWf?kFWi5s0;siNU(=Xt;1XG`4Z8`bTkN~x6H zDK+~2idMgk&Y)7MD2}qy=vOq{O+Bq(69#k#sd|SrN=ccC%1Fs{v@}R5u&Q411y}Av zMa0)|b$8K+S09y^7I!yYZ{a|j-ntuGQ~B$ffMq)(TY3}guiV98e7(Y|SsBucLS~Xd z2Fict=t@ewSq|mYQvLCZBWDSHX1{w_gXFVEbwd!e@~!;pgu`u(sn1f)KrMqHS}|8g zM1sNL_EBD^?Wzmsm6Iju^Sm;$jKf~~B~iP-dnI^ZJ6wj>M+MQK!{am8?tb&@C!bw8 zIQZt^-~dQG><(LA9x9_9n+1$73_o|%Y~hM4Y;bHA8mw|cX^xI8|Fr70$4*{Y9!jI< zhxe4%sG6i@zc9)D^$W{Gb=JvCu|M6s`PR=g0)KdD2>?Fr$gfPkG9g_#PVK>o;VD7Ye;! z@$dWa73R>t`NKqH(@&uyAKLy$;nq(!b`5YJYohE3uC^$t&BcDBUhh(wUmLI`Q`TbLY;S8AmKNe*W^gYo{hYo!(z7hm$MCMdQlQ>K8Ab{T*(5|Nf=y zCFD;9;Tv8Z(a@G*C$?LRJP3>#BeTuDVbpgu(_Gb_^#ljrX!^!mr$5dB+JLDZk>JX( zRHj^a6xonB^wlKBD!2{qYO{4uxX$z$G|jk|-GRzxC3{wIqoq+NLT;Al2(vx)uejP7 z7)R4(=&c*{D%mRVkVgY@8+qFOGJ=NeDwJbk9k#n>&};BJ`;ako*qAOe=mi2gNak3Z ztx~=)2l$q;_Zqe?tQor6lhQyNy|qslXku^`z?wCw?C7w60}7?Qia z#fW+e{AKQJkSb^IG*MU-ASFhn$bvB=&q{oX2{^Ykkw_T#oya8~BoYs%CUUt$c74<( z-P_}b+(lO9`J)itG*nP_HJ6TICs*86B;?k;G)aTMA&@s2h>Q@*G0E09BF;PFrqoHb zB_$1OW0UqQYO6^@U!`&+C4M%}yGPVy)WvcnwLUT?Kv>X9bZ=vFqvs5hbeG$KDNbOV zs5S_mEbf*1Gc%o;#w7gLm~dxb{MV2H6D)992+jUqlIq*|#)kMT4Y^L^vKom*P< zl1%yZ7JUmwb_X5#kTB*hRZpvbO*37A{qTzGBKHU2*4Rf&U54l*b`az0oQm|Yb6Bgh~y#WCpEL9ry!2l^V869_D z91-=e*LSCi{3@GZa> zdEpvyZ1rSD?>QFt`ADSXlIkvh068z(T|SY*-#tOACLH@g|D8z z?#rdG9DnuoJA_?r@YdcV#e9Z~$!N64{$&rdZ;>=sgWjh=a+IMoAGyl*W{j z1PKG)Jp30Z+C@Pq8u7w`wFSyir>!VR(FrZ&GUnYnJrWD0y)dntR_9cMza=X{8^FL?s!ZZ`eN`Ms71 zb1U=S$Ga(nRiQ}GU*&}&vgohJbTY;uT8uXyLl*6IJx^{GHOU%}4#Rc5_3krtabFT8tL%sK8a5?7@Hf*8RAYo5Dq8Y)LP!7+*U64AU&#) z^c1S;9E0ew(VT&?0W!j^L%|4?H%#+U>}BwgHW7A37Lrk|ive6Ilr$3(wBaml=%P_O z2aOa*XdxUSdc#219!(Zc^^x=$@RBB?`=EHhR6uVy`pF_Sep7#f{Q)2GGw{hlB}frWEZxMJs))$mrQ9 z?*=tT4d&0Cjg)GV8n?uFQ;kpL`Awxdjg2Lcw`j2YiIO<#DfH2)I|}=31!~S_7adtb!;S=~lpDN~zVE#8Sd8PPi$Cmgj!3UjewfdJ!eT zUEKBli75F`gr}PU%&IOm#$8!l-ZUAX=L?(q(N!GBDlxhace!^2@yf^+KZ7xzvFR zO9bk^khQAjR^&?x*u0%dYbm&HLuQp%O*Qf}jTh2hSv0O&C@TxRHI+1QX2dzms) zRts>&lpN9RBJ^kd<>JCO|18x!fxTPWVUd-wjsZ=sXAGBGhRl7HTxFN^>+NiH$8wG^fL zTjX(@17^t~;o}LK*N=&|djW4m@qcJ%?s)fEtgY zhXF;vS^+FXIPMs&>yWxmjWfbIup_PuD5p4Zeu6#lbbP!%8j(AUjfT!DKAI9lji7L0 z^eQ&NndwL!iO(5<;1r5}*s~+qWRaq4*BzXNM6Xl4z!gsfUyv64W9S!;Gy+F zhCpL*J?IRD?hHEHd^WeefiNuolDMdkU$D7u*bzWugNq!iU@U!Y@=J09eqcLNuUsrB z#L*5{5X0#JhtC`|3q|g5*>QaxU=k(5)jKOkhM8L*vm>4HbpS+AJn}$*nWA1f!Ax@+%Yu&*sjotbqB# znUoNoD?p18^z7`J*`DMXfN(CIOZFttz`&*NcgW)q?91hlK&caHfn&D)qViARPpBq* zK_%iX!!gd52$JY4nlZ}fH!>_!cGOa4nM{sWU!m@VCuu*LQROqUI6!vO&_+*cA#kY& zV{bt1S?+;R3NZ<1R1bE*&^=={oE9`b2W*B48b;tblpbZd3C_ZZgz0jxnM}`_NGz5P zk^&E4rmQ>{DOkN(=%tI=(lEyrFdL7U4^5kqRt9GW^82gR17GYpb)x#^Vi%hT0lvG6 zwZ91VzP?sHaqacn0Q{E|)ql(9-50mtKk^7vSd%M@#mAes?iRJU0l^&QH+@M){7j2c z1%qz^S}h$=QFJed&P>B9w)Vl~ioIpEEvfWb-M>IB=&3=5ixYN~F|7V?AJSKCwF@^F zO$Wo?DIvm(hT;kd-us8xsJE2w8u)W%V{J-BSeQI7?lp8-o+SS+ey|a%&BA~bLzE1t zZ?YyRE0>+Im7rkrl3Z4HLWaer5ma8+FpJ*moE2XDU}L1L-#d5TV#q9 z>-v~W--18Lh^~@z z?5eW@wz?2UXp?97Y+jz_^19_TU&Hkisu_GJ_(g09(w>oPrP*2-E4O2WjkL)d$bj}X z96mw!#sce*Ts|Le$dm29hQKenkZj&*_>=@r8Os4e+;GHga(lXt0wt)cM(c=zj@Pft z11SeOf~Q%16z55C97LT$JU)b;B(LDCW?iM&j3jW4jW6uJg0}S`IrRxU8020g4*M?> zI#O~DIt9nC4%IU$VY^ph0rs%pS6hMQMErq47)?j822<;dn~-KjnkZ~w9tWxkBV6-( z0MH(=Sg5GAxe)8zK6Wfb?l}9>qd{0q{Y+mHHobE{Q|6rQh5cxbag=x*Pv|PrfCSE5 z1eIkpG;4#qOd|tdtc#f(4C%l^_~icTso-bdzE`dO=B6Bb_NoQG27s>#4LF582+o`Dh-MT zKgK?HuW2JJqc)f@PFZkEcx7hNS=|h04S-G9zxqEa=(ckgZfXeh@YEPUn61Ez!&7_9 z!(*R6NO{+yP()pv93unn9iDm<*fC||D2Kxvf~c|1S^RzqtxY5YD+y#yqJcsFUyxtc z02>Imu=PdT2&%4QY+?x365kwWv~{_XEo-i3v9fyIsC=^c;XhbnZbf57d}4v(NM#2ZVffJNQi!X|HnsClw9VWeWjRn4@OmW`DmWuR`l=UXKe@VF>(O z@DN9J{tVR>sA+*KVNQ#eqt>zsu>$RF*@dFfeadC?$D{BZF%x51UXm*3%O^RT-sTHY z6eZszr`Eh~;57pW+fl@8926|h(+jNm9n9mPg&4xFLIHtVmi7!r4I37wi#;%ZoT#wj zFsQw8H5K^1z!P=l!e*{xp}_zwn=lrXFtoQX+z1Pj#KHj!}0of2DJ==u1}ChIh{#8L7^a?n2AJ?*#Qr*Kr9m`>&T%* z#xvkJ12i>yXl#auXh_P8a;nT>bd!2477bz@Jd|EFS&_)utFcrpw~eidVd+9;5NQyUe~Xr^Qjw4

dvmMF5?zN>TvLaD0 zjjyFE6^$h(Q|#0Y^|-AqBhOArTFEZWlV1WJCRmV|uowc#L&!r)VT{p0w~j#|4c*J0 z#vby}ZG9P|8+q9uu^5sRrF3#(xogX3NzB{sqACqzQD z;BM&mNgRXbIRIov^&r@Al$k(~JfoxmB51+qCsJ`e-XdI>R*OpRglHe0M21w%f&A%5wNT6QZ_}PP4zlh`$AVW@A`u0bqh=^_RzWe z>QJYHQ8GJ{IK}RG4EQW#Ip!H2U6>ap&f4MmhT8^={3|$;;Xf9RT%YeY9@B=@O~Da- z|97>8g#~PN7a){E=P%7i+IFNyq%zxohsWGLLbd#kmEA@pz%begl{RCPEsPgDn2TR( zorNKf(NdKDiQ|OIV?D~=FekDl!YasDUFk!*qrcmCYcb(M_hssoEaSBae@o-J|!6dt`Jlcg{4{$lVUUtpG zOzeQ2sjOL*<(lgkUj9zcl7=r&ul%nzU=8AMb12mVjJiRA;kmie)Rg)8sK2+3 zc#gfEs-PF9hE%EL@nqaNe`CeSQLd0`Kr&D8#oV53cY5!$2-;l&ly;SU&!( zX!gcp36pp?j&q9eO8U;RwA&`()=@Ow4k)aKHMv6rw5|;vXFdHDvS6%&zkmGo)0f_A z7hEw`$9ngtvArkv4lg3UaXWL(rlp2foddzDbOsaSjF3ElBuqgEgjjOe348GX8l)=C zLANuMJL$9-Ar~9ur9{4o+tmY{wQ$4&BQuXAu z-J8OI`3iU=8+8`h;YY;Q44)_+RXq=b zgjOW1`C@@1+=F^K#OejChW((q?4paYXb=#qangRT8W`~!i6hJ`@y(5UWWw|)$?q6E zC%$CupdXcl5i5b+ZW~<;jD1Fz19&r|p^>{m3$P_@HjdeI!kUgF-zu263r~`usn239 zk|1p`*cM2}fEsAhcAfkZXagLySfR64y#YV7$6D` zjNr;JvZ7)61IcGL&cFpR;V!2;P(J=1c8O)_*^VL9_Ukh$;r8#p06 zdg8>u`1mpT0AO0d{e1+ViU>XifyfcA#3IbQiXm-9F3Pau4RACqP#anb1T=e+>gbT4 zg6B{mN`@?`s;QK44C4$i+oWJMkTsT+lUD|#gkA$Q01*WN;l)M^5|msHzN8jPfm>O8 zS7oDhIoR6zJeoxFuVGY>OG$QI7rub`vzyK##5WtQBn5CGy)p^{!^nuP=TfPg*%bO& zvz5vUyo-gaa*!J7ogG2$`c5M!RJem4JMYS{8qDQDN~Jq^)<`T3<)A|e36~AE2ICo(+v*33msMh zLktZ?HoB0y9e^?~8E`f_g9U(LK2rHJx&;>)_srEVSZi&8`&?}T?x*|;<7)Yh18Q*M zVU45IawIk&^=p$by+@3W1_%R@-}}JXTpF(RHdoL6^>3eEaUAF8F9E*){_4Ybde

yzwp91H#f%*OH?#&@hLH>z^#_Y3jkV@9U1)yI6>9rOb?Lf(4@$z+?2q!~x~a=EMQO7xU)ZCIwU=u&?&Q8227fWL#ykhD`%)hH)1* zZfuyYn@Ao(-LAe5c~7UR96*~~{Ms62r7tO4a{4<0`N61*Z{M znXuXkEPt7Kl}{9f{8D=*+*u%5?g$pc0^DXQNAPZt(UX?tD`E?b+tbAa60zi2GsWOc z-a_->jB2jr7pe$H(YdgWqz!nKW`!d^vyiTlpMD0~duuGKbeAee$%CJA%EKKC^w0J-?HTx|$TI#j!h+F#d+g zmrh5eqrzu@f$cAb(<3||F&seV(UE~i;gLszsUy4N zy4np7?2cO0MTXdF4<{DDDbkIH0veFjjI<*S^WY z0HUA=W63RsbHosb1sewX+2kk`&q?&BqNaRBlc5a+>dMzuHp+o>9e8UX3rlFOwlHK3 zEPb16!-aZk=c>RL?(P)o5IZ*tl}5Ip z3*Z8a2vam6F>MM>MBNVbP=csA2%OLA0vFMdWWb$X&r?FHs!DUAbx;kYMnWYZxH0dI zp|RP8yji=Hx*cFUHPFyx!Tto;mA3&^*jdyOBL9j3Aq}QuLA}~VZBw_=ZQTE?MyK!a znCk)tbkf&bQvq|oJD-L$dW?!@A}%`@NRk)&YeJj*$8;r(v2$$!G19~G3T3Tdpwt-{ zJ#^Y}qP4{f0=(aTySci$>NuPK`sVLnT-tP;E9V^Nf<5~B2LS=Qhrhgf_OosIn}7QQ zXEVU;tS5c`zj*uN7vDT@3Io3I9`ZY|ZN^%7*y|h?Q0`|)hnpRZWJ{e)mvx-%_8Mw6 zu%~}6ExXz-H@Xu0V>e5>tZ|gf7ybWt1l`@ghe0xSxpSVtihneRhJH9_Pt{6urCRfT zVVQM=WBTajAy2A>pUXFxx&dKA4mE_?)|OmqW<%K!n+FYUg_F^(>>ze6Mk~6-b|eFr zl*!!QwPmjf*sXACy0BYnmbF=8nKoh9Smnlh)x45m2+q!gz6bc-1Pk^^@G*$7etcop z=bu3c>nO;!$azR-PA=?;Hnq)q*`d*DQ-2h#yBe5EyA^RXlx5pCTebY zk|3yPYq%Q(%TXVO(@!|VgvfpPGZP~DSsCYdHS*QiRW zsy_)oX;Zl_6Dhg%UBd*M@SRqIZIZ92PaW=eQp~)H2!RPOu?XL>N3lda6lp`{EZ@0; zo$+|gtDQ?w&+H2<`B2~B3&~TK;t)~;NCkTl<$;K2;5kCFZ3>kYHE}OClYN-V4IXTz9hUjeguaS)XtVX-o~Ig4r`L!u>6*`{#s1pK;LhW zZ4B#o^VWJk!D+L_P|70no`dVp5=H2(Fp{1|BnRWO@{`to=sLTfHV-R|2aHMhC<~#s zX6!iFe3*buZOvl=8{-A34V9A6(R8TZiV+O@m64Gqi>BU0Vu~gr0gAdx(UeVG?ILTF zDw~pa>Tc3%e?c#HF{!77TplOJWG8qQZW9VGN!Z0BA9lTxsdWkmz$EvU-+RYl?& zD4)a8dsX!JareSizqKBaU{9We6la4{B$<>N)kykxjuE$N8?vzMb>!DG$I6b?vLcnD z=Q0MgEQn=1DtTiPzZM}K(U~j1Ct>o4a2MILJV{#iVocK7SF`6%8G}L5PMu!h7_MCK z(|p!^MBCrlKQNh|RlyOjIXmlGtXSuXv$fh&=_g*Uz4T)PVCkW2XHTE_o(>F+&o4e* ztG$@d-#H5moWD0+xb=K(wM2>G^z~b>Bnlt@IS_6A>C<1-YR^qjb2uGyN3i_?^TE`a zYNq*MIUI9i(c^`%OQm^Q5aOW(tf1u~h~Frj^g1Oku@CwT=jUJfKRe(H&s->NUVl7J z_Ra2u=LtHtk>_sCN=)P4OQ4<0;t_`xpPWT9GR1dH<^9S<5;D-es}bOLpBD#+lfRIYDc zondy^PS%y8ILH*FtM`C1uR_c1isxwWq9qB<4IWSw&|QLKkT%pp1Co6fFL$~7Xs)SC z08Czz+@gB0Nr{xYXZb*Pi)TgS5|({QMZnNrW5z?1Elo=(sh5e}P%$u>Sy+nfftC@_ z*_bai3%=r2?4$u{_t+Rm#&buIU6DZ9&9^aT(qlu0v|#MylD89%jA`0DLhaE|F1Iu` z@^h#$@f>Lik&4%F9MO$rAWJ<_PDD7T=t;^6jSI_JBv~|hl?#TPr-MScO z5zPJ=l(zr#zUJjQwNN6yLuu880ARTtvv1cNt6$z0f%`Y~cDM_<9&IWx-sW&mlilu- zMvLXIh%Xyq#?n1RVX2F-oqaC~=y1p=Zsfy=R}-SYiY%}Mjx5xH=>^iU>TL_4@HWm3 z=FE{b&6*del3ARvl|=H3^QKpk2ZvB(ekgsVUjO!2xS#s6(xg% zc*g>41<4FtNrjq-jP+}=p#U@ z=q*Am`H*7s`GU7J#7;JFxRI;n!e0;L(2Cb@IY~y)rMWD%N!~JS51eXhjG+H}6}-RX zBCInLK^^df510pyiN^9VU65S5H2uzg-OW*JlQU{bfKa(Tn%-AqW}OP07*naRPSzD_C>J- z&t1(e^bSf6O~C_&!G^=jYGPQP>|Ww$3$;ry+sUS`p=Aug94m*C%A-jVDu*UTnF-Ef z#jDwK3v=j^k)``AhV4AkHVkO(zHSns4UnO=DrG26V)`vkj^ymlrJO1WCjr_tt|RpV zr%^W(`%Ectv7<=$FP2^~bgbr4Be%pqeYz@xZi@J;4b8UZwES;Y>dSgeNMOv@Aj_hZ=*Ylt|>?a%I zLy%;D zwg}VcaJY@CBhSIICvq5S?=du8=+{^}yigCfh54WwZe!?N4^+YxOk-(ZjFxmla5vX{+NiGU^e{7_esg%f^W9kn#nP7Szpd zPyozbc8LB8B-_~VMkL9K%Lt#2Rhd8w7LA!2^%OX=0cQ2;+_rSAVLB=`_P{~%Gv7*q z4~bCc=vP{353EFbwXT#(7QLlX*83LpfOf!agK0!O7PS{3_X_eWy_mT4hMiF5TELL{ z%I(6elB|wkMiOszCM?ep+!sbX4KFTeDI9ZsmIl*0QaEL&1keOt=}dc8Oxxfij~fkT z8b0%Cz;%D~`Fnr)$>i>j?mSa_`Etm(@C)JR?168eexX+T?#hsp7{gA16D%4rut&r2#@@CqfKj^|gI zm-9h_r56|mEZK$91&83r0hjqkbVpzXo<4Qpe;9C(gtfnXWp_f3BL8n9*ziuA`R3>u zGB&k*PF?=s4Mxy!#PW*YXdtk2;O}qtXCSngeTOLC+>H<^t5Zs8>d|;rm_VELI+tQ^FCkZPZ%tCy`pG+UUDoAs`JXlI(hO``;-3( zzpJZX&7og?ap>UsE>d8lwGSVC@%JyjeDvVq-f78|E3e!bYg)Q{ksAX7VywJOptrPh{iL#$+R=+)#g#*7%BSGmUNkcA7_VOt z)|*%XTNyJ4Cn2K}^rlilrGt@hX42km;u^@PrxBQn#*Skf8yo`6R)|9`*r1XvvZ^#rtTa}yYQvmDTBn0~4S9%P zB6+i-L~@X2Te7M=WRqr1ZIV^1(d$JfXjG(X_hhKx7ft>zbZDEJ^NZwYFNohC*Oo6r-OFMTB zZ$OY+1y^9wE|(Bu0|mg)ZY?wAN`pFFjyd^_%Luj%Aff|{U<6fa@P~`>S4`gEw*%1X zf)R<5EElVQali~}D3%GiG`a>ce>Pz|!dN-u+7Vn%29qXKS4hPYy6Z{`5+_lAWM)QO z*|fP#CSg*cE3nZq8)3pnFDx;RrIY;%NG1?e7R08L|j+PQ&?| z1*&GETTvWEPZFagu@6QFw44zo9(QFah-Ugm*5k>l>qze6Y|mp_kh*TIdC*4)Abs4m zhE8B~F#vT(JUFtA_Jtl!oKHhhwH*cX#i)9aVUtQ}hp2}ZR=nLW_c5#P;h|Q4>v2zX zyCqL-BbB3{i5!?qceREPQ27{6V8m(xgAXAM%{%AVHR$+8Fu0+N7>@;tkuPcJ&;%Ha zRA?tRzf8J9pOIU@6Y(3!bY}hreZOo-^7)|L!YN^2$Q$$8nS6#qpLkjuaVIRpa zycq}!+GI6hs2-vzIK*rM#8ie6ZNFJ6`08jUly3pr`uG8Gxx`IdBC#1xB;W&dk zAar3|Sa9SZh0?)7VZV?X7r0&7hf2DTxU;&7)oLkKi0l`d+C5lSM^7O~d9)l(-HD{g zNZCb5MRd*v!A9N=h`a~Ro6p(4U#(oogY!1Z4ST!G8=`U^^JDEL6kgk~39-gMLzdM9 z(wEsoNI4ehGg3J6sY0GzOvnc*BdA*byZbl?n_!d|N9;b}?qfv&EpQj>VEBPyH(~(; z;wXW`-Mv&utD`5*T>kX-=L*2H zu>MYr+4Y4$;xm`W-de9<0W7axd>l*wY-8}&B`We-AD0i1^$Njx6Sli>DB+9Q-CxLq zt30?cp@m12TER#;)_F?GCR9ykcP7SFy-F`a;E}8faU@rD@N)A!axSh0O$V#yVrZ z3<31OUBWBeQ^OptL!PxXa37q0_!Q4O4#_vPW;$gCR-dpX(Zg&4rgC~|SSJ8WGwqFg z5yWkKy~_@75TYxC(UZFR1?Smy23&qli5-r)x#c-6WI(b8kykG9e}?=cybmK1%O3A-g5brTLClo5S)ByIRabut zN@(btTSL%13luXK8c7~7{`L$-sntSm*0vm`9&6|jDi{QI4L=Gs9Bjx6GI<5EDrg4+ z+9e&}k^(DWq;mM(tkv>j5-l)lVDD?dS%lrN+{#CJH;_4GEG#V0aOC4KI_&o@083+j z?0@0A2w@B@??@H5zm9%jUrhh8mJnQcTppC*@r@dRQQl(I+`;bIAUMQ`|wH2&^qm9rm2F^2r87a-EF3P7GxeofG7RgSdgv*z=c^iOp`A#oGxvXGJ zf{O(&uWvTx_cbFxVaS`os+mQ}!UyhnF?%i{^$Nrr;h3pLLXPeu3%ZH4%-lVQu)3A! z3jLie&c4WuSSVZ%C&G|A*DLb6uU81eKKPO9 zK1`nzg3Yl?Z2$IAo71Y$3jh615G6l$6elOxkYq2l$NH!%!`B#r8M>{u_mvLlQjBHa z>L&Q)rPI|#+yx$>8nPmEW1hqlTy1 z*0LXh;{Z3bkU-m_X%ZdeqDGUbq?VNL02r=f%!A?x2Gw8=k*c9BA%Uq0VnA7|$ z@Fv4RRfA?_37QLcg}s;q&4644ij15Orzw|nBJG0kN*HVqGi#^mTK1a4ke3Blg~A4R zun&%7-W>c4i(aN-Vf2j5XfpsK5(BYN3d}8WoYf6UGrk3960Eks5#heT#i&Q= zanzG-^$7NQ;9nYIDhKdZ_00mILr`RSgxt1xE2p+vJAR`)Qf zvL7O8#8i4(r-u$X7#NCV(x7e}&_;=ug+u4ka%b01i%|gTXR=-`DD*q2%0eu(pMjI4 z#SE+r0gFMA-DnjI0h3YoE1=6@N~Cl6vG4VTFolK~Yavue7ZUX;o8t(?a-+!HJubYL zEpCuN!)yepGv?6+bP>i%70j9on+M|+xQ(;`33mj3V=ItgttKM!W3{jvDc{+TR0M@1 z33!DgWpp8xS5l?=Y9s;+4^lYL`694Z5`2rW{U}8@5`ehCc7_zNnB!hnAT+hwDAzF| zHS)R%ZoZgC=U>jG6^R>I-~z47bS339h%)yg8>?)`dmsZkA4!!+iJJ`D%H<1Ggf)fl z<_pSu8HtGnF*MNS=EiU4nYzK+U*WE^$5h#jJ?}9)KZC<(_AC%*XHm$|$DuW#mjt?x z5-qeVFp&f1BkX|{!dX!$P+jc%K_qgKkVl8xb(elst^|mbQCsRMN ztncJ&i|2k_?EB$+i&piCpl}|eO?1;#UL~Y5Q zEh&;J|Cvm+#FJ!6LmegSQoOlcH3YGQg4NCIoVrUkm@k2_P!#ZtNdtlA5OV0DlonR# zwlWxFJ8btJa@#IBZ0AzOD0@H8_ow>O5ZltvKPj>!^yqot=Z|YcDhsxEZlSDVOM+(K z@HN~!VhTM}!*v1N#s6;aH4AmaV&YVJ!)a7FoanV~JtqTmQ{d|foW0yluZTf8ST6TU z?Srhi%gV2G$=BQEH~p`i&Y!(M-YojX7tg=+THukJ2*3OV1o-pMnL+;qJI^S6aU=i! zt+l}WgWi59^j_!gr{})&y&qIQkO*mB2$W-C>%bAh%S2ci%xq`TAgeKO$;k1NWYmbK zJ-SL8;H#e7eyhsfG;gKs=@Pu8AsU0`Eo(N;y^ZGWtOs}Y3oLhGE2F|(9TpH5}4Y31u z#1m2f7C~3BEqR4wVz>yPLqMzXU|zc6!$_p7P~f0HxD{32RWKG{(aR+lzY!&xl6!&i z`l?md$EpL4$&6%hYY(QH52~&(n2)jyrsv2gYmnS$W50%}YiOdY43k}HaNhWD&={_9 z;?+vNnlV7mR~So|g4*&Thc;HcR#N5fs!?SwuVwNJ#+Wm%kRfl^OO6g_R!^uusz?Pb zv2#8%XICn#m6OWCBESJVPr zImC*jkEywe;-ArA5q1S=vMzQ39h`$TcyekoGbt1BT*?kEvfWJ?ZAPDUZc60~lZz?P zcJWZd>r`rS4unq4%o#IIO=f}5F`lc_K$z7AxJdaz zv2bK$xX`O-3xz!yk_tyfgV|&&xtBa*(rn!LAX#kf73v2@btz*gBsbo!x8AE88?MvX zP*@S|Z71JeY42@N$B=BHf0p4#lIiw!oI*)gShN98m4#O$W?=NL)K~i}Ue$u*zx!WB zPmWs(wfL=FABROlYLhjUD6MRG`(U|{+Aft+ken1*RvuT)Aem9LD{DZOZ7@z)h$5@) zA-?62d~zxvN^_w`#pqZsMNncePg_<3Wx)9cR;cDpaV`9`<7O1OVSd5r@$O%qJo(q(oD|w^e4A{1Rk1Xy zVX~K%C8O{aov`j1g||JaQgb|U9!GZ&jl8b0v)7cgyr;NYjP-6M|dC=^tcC! z9k8Rq7i5pRFkOE2(VgDMzi|M3`80*Y8$iRBU%gG;AWGm*L(^$gI*>mRuo38i7}1)5~`jr6Gegst}%bm$9k7yV57qWsBI9S4ru3VFl~TJ0<~0G#8r~XQSJMDtauqT2knqu z_Ej~XX8jAVjTzuZS^Y-WB))nFf00@U^VJdw(a_s|zghyM^L@o+88(;5;lPEIN1R2- zMoE^V6PHU_>1Rr61}-6c?yph7u&RQ=6T?^vk)*R)Q}za0EfOgaXEB7X>ku9=yeMwVx$gw;r{ zj2zqH3IkjuKclI*C@ez$+TBT!rCKE$4+{rxxI`+J7O@3|z7HVSCNyIQ-B zaH>{6Fb2$~*4cnv4#!<#Z*83K>=ak~&WCgz;g-H9HcW+sM9)Am1rOtWuDe}L8Cl8# zacPu7=?(X3U$i_)Jp&nCOvc$oe|lwh+M()YwG+v5q%MWa(-J*Xc%;}#h^d1cXy8rRVNHIjRAjG zBCOc%)#s0AXRkaqoc#y@h57UoP9r`w% z+-ki!J1+QDJHz@|;EW<#0E}U|S+*al=~XAWRLiFG$;v&v?I3)6EY9*6@Yjr>UrF9N z_R1Gt6`o#j#SGtm_QSv5t>*7NuAKe;{g0Zz(4SvztBueNsZU)?OSg*zZiIXGS&YvNxpRMDgLZD=zLzOIDpYKL%mv)0@jm?%=-COKt|OT7?}?TMgumgqzy` zUZe2H1IfmwGYhL@L4GOEuq^7!19H}+T*FmE%sU}8bL&Q9T-%Uy3TVPch~h{S+2I6P z(rkTebH}Z=?H9PTtRKN~YW%?I9RuKh97RwdLwTbZIDL$op}t##7)#vy172PO8YvHO z8Ud-i22%uVTxhVRsWr|d;`#&5Cp-`ro?y@%^sCmvXfK307~6{Z4RW^_H%Fseq(u8- zgV_D3U(@H9j7d?6x2kb(cy-KkHh6dZ$)J>egi+q|&DV>r&LPKA;@TJ9>$9REL&qV2WW(XaK3Tn3k>LRqK z49^6Xzh0ZP!k+__AR)qv1mcmXgjW&mef32HXZWsB;0{ygP&^(AsDdFu8B!!MLFr%u zO*Gpu!`(nwL6mXLqmPhTWeXkSzMVt?4c4#+88+PQX?B;j*Qi9XRqPaofG=s#tqv3x zI@~L?>ezpapllsw^j>{$udZqau$j&yS{fKL*AJ5Qc6|jKFcHu=fm`k5bpzKV<-m2q zE(*qb_ur<30ReOyz&og62wu7F`h10xqPs5fN-(QP%F}49yPgi(Iepu;yBp+D?$-q6 z*R}5DL#t&xNko5~HZ%}9Y3zE%3AyklNd|@#+qiJeh#<8)9vB?QG z!43EW{1NOBuxyo4YA|-$LZI-eXj0TSCb3u_2DI{G9jW`8`XFlEYS(Jm=!> zpVJW7my7`BoR?i@PHsEYPDD{2)2!eYa-$*88Osuk9Hf^z0mk%~@GB^|RK8?uAv3s( zUgP7F!^1zAwSOEQ{>3yudvMdN?WPaznl=CXrs+wyzyf?N{-J4}Z>*UYcRDiZ);o8u zA2pb@1r*+c@0sT7oeT2t@$y3L&c*$1u5+E+6P*+ZJ~_@asUeR5rVa)S<4B#p=qPt6 zFM7Og2DU(zb&7Pp9>$QbGqK7r5S?WRv$uQ0jX1*p+WD2C{T9ma!-rj{j&Ie6#b>o}Znc7IM|g|mg^L$4NY98Cabl)YA!P;#4iVis zCztszdw8bzF9r*cyUx+`~5-x zpLQ%sv-X`rL3EE5<_zZ4EIZJg#Y%k(IM%c#BXLQJ7TlZ#yb3Y=Ag%`A$YZQU=aj!3 zS0k+`+EtA&Qo5wb=>&(aIptx62<56ziq#m!WMD$0Q3bE-ZWMN#gNmpOo>j*oc8?*P z6PS4eilsCS(PUsVLlNy-PxGrp_SbdWii6+?VU;lc@-_$SOTCFLL~d9q}8aP+q=lDRGK$W?heuHwUHe=Rq> z2#+nXauNwIIpAF~Fb=ktY%m*p4Z4wRL}PLaDW?DcAOJ~3K~%X|F56xss==FOV3OBc z)z}3a*Rha@1O&7k!S-wPa2pz`4D%5dp)mx;%vXwBxl`)gUd)405yLSIqmkSJMMf&{ zOsdy`G=^SqDtkm-L81hZa;BH|5U-_4c^10Y2 zRq+tj){ky;Vg!R%>{|hTQB(skf&ww&75y8wlFYRXwicmT=@wO@wLFHH0?lC&q_yhR zl;9$Kz}UhnBAnIF`-|9>Ui7nCF3P{WB+@Gn81|3A59NpcqZIe!iU8zjd8)h5^VSa4 z%Px%&q`wzLju!AV)E}J5>w*kF#sOZ;9r!^@ENg8rV+S>KBN{PIK~ta-2weQ zB+&Wf*-g{@2ushyzpdS=E!?h|@9n1#?!kt1%`|`hpl05Cmgz{#@#N7x5#YS&{ovcC z*?vO=cq5b95QToxS_4O`@sd1)m*2iQIr-ao-AkkyO!e(&;;{(7Vzz=NFO*xTsx9>l zLbRu`x0Ei|Lk-Jk%hOh_f!wZ>u1nj}Rh>VJZsMb<3HnJI%8& z2Gg7yrxTbT#8?70Is2G+EsGTuQgDan1?I@L;1o8e9LLeP)oZrCeVkL^Nbc&dgAwjU zu~ycV<6JPP4_qf^ay0ii$fQE(<8+*qNU2D5my2qOau-oYqVR}Kh%kn5oh!{~t_Km$ z5ae@;bNm}8@CsQ^c#_kkV@1fZwAhspc?_><$O^I>9UR?X+eo^MMi7m3r3M?(jaA0> zx)6Q?udm&^?XEU%yIBgO-zX|u#b%bZfrHkuTdG>%CSBa0mUn2I!=*tEc5FI>(9y{7 zL5E?uf#9$iC7Z2^;#kgz=-Ry7v<=(H!1CH0HlzAVMBMQ9V)~n9@-KPN$Vi%*vD(m} zV1cb+^km82$jTW=ZZCrfaU0C%egLt+tIR@z5g2iV zXkc^tn;Hn?c8Yf3RCwlzHkeb~x*7noBZ?FTIr}Oq;u}W#5vt$&XiGnV^;h?>I`3=J zFRS4wX22_&&#=-@ACib~z=J#n7=9te8h|w5JCu0@Dh%E}R`wYEa z#-=k=+XFXIK)0T$&AukRi-@dlIYuiw0F&@LK3J9l>@_dLwA32t1|ADLTdhwuA~>+z z+E60i+a*7D2&)n`FxzJ;gA>j)qFm%c%f%={pf_AViZ^opE9z>;A~ZVEPT-=E&Vc5# zn=}r0^OQU?1~qPUx3|07_zT#1`3nYMk?1LB8^{}o2yUKoxADEGtvR_#xs4&l5O+4q z8yPlNVskMdIogqil)#_l2!L2gKS-1XL=+~ZM3%#O^r8X6LVn@M=ZU$`{RRKm6@TBO z#L}a$`}&rWg}&tcNCA3WO!$jS2nb&C`{k6sFw!UDH&+A-dZaLn<*dcwrNt$*p|OnI zrw(0_J&-WiYgP(0IaXE*5>72rilMnhDyX$2M8o$>(uS%#h|mmt&~>jx zjGcj>REw}&4e&8T3z$|fF8WF1KtRLB^D+jwFdi{p0gS6WO-1ZHqatQIc?|nmRwiK{ z_9UXS#_AD;Y8Y0#5%fDlXA&iQOgS9iLVy4MN2!4SdVJ}Zrg>pf>R0%EYYS4)njfaF z%kl3p1HO&6^H4hf&D&^Fzh%}|^Idt`kQ}Ih7rG$87oL5D0{E@3%Cs4mkKdfUIc~|< z;|McEaZ@oQ%iiIzvXw;d8FYaGk*aSjiraeK}dPddFDr`yO-6yMe(wNp3;i=(rxJc zS>7W4-|6&L_TpLd`Rv1z;JXczA1@5*fOPhUe|>*?divwPzx!cpBF=T=!7m;RqLuq> z^i?1fGyx1BIZS7nMowajwTu;I@6${L$gdfx86JmwThIBBJ!`d@Vz@kubD_z%e z9I3j^YJJNFt`y8#?6UeC4aO~Ti<1@^;leeh(4)Gn%yIH;M447t3BzLYG%IU}_G1Px zz+5DPiDve+vLbcmnZ09eJ97hinpN_sRI<~-$W?8XTU~D{Z{^d^a_bRZFTgg1p7=Ck znSw-Z>NI#dj%$J-HnimbzO}Ydpk)M|Wm2k~5aTM%on#FFX9gn2K^WDn6-9!`hD zPdjz_nHVh3G6Wf`&nR@85D5&}1~3{@2TP&6vV6aZ_>FLPlSRJ*eZxm9k%wNTFowEP z=R%B|5DE-?a99);sY-!m+y{TK&&T#Pm>jJE<~Vp7N)EWV@nZ$;8%b8~Dh>^J)|_p; zc0>Fx&>M|X^NRLDS`E8)qH(_23Is-r8A2C7+bM%4E{)L z9NUUFHv~JjBV`jrU1+w@;L2n;aui3Sstprt(tLx2s8Ax2C<3HN^rG5DE~<9Bn1obR zZVK1CnED5Blgr&w%BDT%JinJBHYI>R-Zu$~<@28BIUklB2;o)G6>72*301)_YL$r~5CgM~XZgN($=A_KZ>Wisu@bRlI>Z!S-F z=d4*ob+iSVuR@!Zq7M3THWL5M!}u zXLHy&(Eu?yayK9h_}vgJ(qRL@<7aIYwzD`OgckU{bLY;V7D|g#qvsRnKN@}GL1J$q zyhu1Sb{mpHX!mg`dC(2wC4J9Ib?;eo6l7rsBQN2m(B6!^@{vi2j1G%6BcHD`_ewLc z*mOkrEn&kuW$+hsY1Sh(bQHa4dMl>bkTkWt@4mRP@%HBTCl$2d|ES=PuHe*$KX(^U;9vyRe31cYfV!p)#+E z17XKZOK;j%N8w9uX<(NArQHyKP5vOzjcsjVr%nG;-JAmVZ_V!aWyJz$^khO~rzdN= z%*LpmWxzt25lB)`OroMfjZ2C8{%6}=Kp>Jem>TH=RYB<>mVS)(_2FHXnk#lNcwMT1 zhAS9;Bl(991pFO0g86aN5s>FxbRN0TUI)yTujcOfE6`sF3On40r^No(|1cnrbG7WK zIN2SH^4|y8{yG@7ffccE-~g4;LWTVhaA6*edP4Yv18WZS5khB$j$m{k<%AsrmWw%9 zgz-^<@5qfLN}<372%X&wqcnk(gs>@%70|4Jcn+?J zvFhDRPJl9(IZG}SqQZFx(Q-M;6b^Y1$yaFZEfxk~z{x+$5d(;$kM1F!1F=_#h>j-* z0|Z9L2Ojy@OL9}397%d;79Jpd1CwUtad?o3b;84$G|&~R-x0chkDh{$DT-WY_8n24 z<%ynx1WRt*M9R;r(?wA0mjdt-R0&Imj1cIUcxaa%}m_+Snj-;Chx)j46o zCs4+=TrTGZAunnH?u?UIvhnQWHT0?mSS=PJ?vGP=3=b?U< zD}%n=?bC|X4>KpTiXE`-dEw?|p)YF{sHM^suw6|^VHF^{bnK~?6S4@2TV4S>(@lsx zECO&zbE27)brQ`8hlhtRUi>q=_mAhtBK2RL+gw@OB%aRr`L>kWzUmOy5aVG-ICGX_} zF!-{Kp`*#(Lj%n z+biDp)7LIc@9tihzIHmjs^jU8>@;YTh9y{>zAaaYS*x20b=kvUwK2GXtuE6<;9C}| zD+;qdAgKGPMvh~4q>;_lL0 z0Q{B=ntzV`=2CTfi?lOQfA#Y9>;Jq&5@p@+S^`x1%`iA^Ym*q+7#*T z&?cO=%|BxawJFtOV6*6Spn2HDEi+jIwqdxBG)R(Ay~DGqG>)l-x6Y(z`i^6EQnSvR z3CiE=)LXNs({_qv-INb=_N<;|ghfIw1$^D&tawMWI4rd_jRNMnJP>L0EAUrEFF+D+nwY-EML$mqOuh zwmq9o(H4BK3tBOUvS8+3&9&#U?XV^9YzLXp5FANi0c2!C&t_(`;pyhSXlnsLe_eiqAm#cZU1kdP1dWI30y*}ADNOYfx znBn<3vUBE8_QLs@&z_i(v*EpHE`t1-GieQmjvRYx2SP^{)OQ5>3-d7Qj(~M~4%|q9 z!vs%9w23)}ix*BQpHd@DbFSlC1IM-^e>@o>jAhWc5c=()nOTr6Tvx=gL zwGH}{OxRUKJCaNcCEZ61;jkkr8x&;O;T=MrX`*dF1-wYzPfyt3s&HS>9$ZeL>srub@6O-JPKQ;qS)lwrONH6c-)g(sG6m+*Aw zJ+lCQ8-fi0A7A-+`-1Q}LR5PH)sH{E+Fh?}E>%pow>HqENe^qbidaB$UA4&c0l_OP zxK&%1Gqk)wT}E{??^VIEf-AmaOsOUJsqC&#*BLumJFVbNhb<=1HPsaFB$Q&W$7*k) zu&ASg|47wZ$dSH6a}c2K3e3kb=1F3AOs|tlrxPkVGnW7fg?9N?-*d-{A2tTsk%nvBDxOx^gE(|#1B8S17rWX@vOq?Hb-3#){ zN(F~JiDXKjlZ6U?u*5tHdkRPG}ghwiXq7o zM82f@G|{2beGyC%!9Iifi9N2`%)L zSsY-w&_q`NtK`1e_CofYTq`q}vY11QaD0u{wgcS|>=frgFbW)LtVhBSo45J)acFH#s=FUm+M zbo65T6ZZG){GRhFO~+;@w)N_@6ch74dd_)1jM|oF+zXtJmr8d_pfhla7K^*I>qX#P zpgze}TL_>}ox43lnQwem%4g8}oUz^X=~YdbAD^2!xrzY^JMg*N@xNg$CeK5iz(#y= zEs?4PLq5TaDN7sbhHc zrt~X-^rnW-QbUi`$DoFE_9n;{7fA9 zhhH{7`(sew@Y^?bcO!Ho^#@%3ly6Tko8#l1t@`nfY@(xYFfNdM6)k=P^RjmuuV@cEDFF^rpb5W{tW0cpOFQ5d<#4P#oIbJt|K6}69i5l-slq<< z`cK}!u7&EPg~%yw;H$-+qdq_&>%I`Svawk7tVr#4&j{{{6I9lg_btKpHBvdK5UPkP zRy@rj@A+7sf5ozuP^vtrR&hQn!>*SmYy{pU7jWgNMesDrMN!W{n0=j-+&SdYT0!^* zXsBT4iwv7D%G|4gdc_#FdxiBGkYzS~-4OVULM~ON=q@v_bX)w_Xew9O=~+YG*=cnOLS=<6GzEj;@MscBne-k)LGUp&n7MOx zs@*;g?@2rOBxtNDv(iib|9;k9q8Zxm5f~kz zSvq5^7h5puW@gWk$Tah1LMNfgY=b$<-5{{tzauP;BE8B)VyLoWk)6n}md$3EFe6Th z4YNqFm_nD013X~7%$2E}J%}CD9`s_p8$@xi4=$5PNlWm-je}b3Mr>HG*IpujHbz{Z zGpxPUD;qH;j058lo}?uJnThi)9kkn2FBoPS7{4&^?f2+kSi_Y>{8j&EhaD@*Vz6%M zrWY{GjlDX-ok0X+s7vA1`giSB8*tD}=s6rgJO{UK+ItXCsmfpA^aZ2oF)1JY@i@?T zfx3O>((4_u<35$YeYzU7h+gW*FpMHw|KL9F>;1#e2TjeF#a7jK)ZJ`CZ#T8URgJHz z2XlcliBYu+vYPY~8u|@#j<|}?63ntsc6%{1Y0d+dH@i(Oh&MUNw7QuXcm`KDXIR{9 zzWHYJgO9(2(msv-{q65XpXRzBU%Cwc+TDHI7;xt4cX#*4TZ6Uz-AkYSVt@BXUw(gg z_sVnPpPK|_8nk}RP#G7J>zwUSLb~XnrNQtfF$e-Tn%}H>gH>;k9lbJXX!ypdZ7q zt--4l$^r4wiptUw`041%w*s)f1;B5-^X}1aBpjAP$*}Dsst8qe%j(wa{Jd(Y7$B<8 ze2c#FWPs}kEJINd2wY@jT=6*MqI2Fe3aP@a8w{`^*Twvqz&zwNN^bwXxTs_+gG`ty zxmwqX6_-P46kHJk+N%W~IwyWw(KbS5jk6WG)S>Z zhEasUn-_(-DuK{XUQ|mHLTXRkWMFO2b#YORgwmQ7y_Kox6%U@<@!26ZB*VpNbX8)n zQ6)Qv_NKN|+jfmj&W2KOTQ$%nqsLQz-fYxaFd30v4Vy~Bgvqp;-ixTZA(~8)X*Jc} zHt4k{*`5w_iak_{cn+qR45yPws!`d7lY0iSc8PBr*5W=gSj8MXB?WZSo=ey}EjRFJ zG33-bPSc2_?j!Of)2A^e#Z|+wdOGg9X%JdM>9m&u8`o7zbes*a zU^#tq^|ni(XHMF^>H|(rDTf7FJlgjshOG=RBIw?yMSqV&(LIA&17N1o2EUBfxG|!AOJ~3K~(csbTmXk;8`vLPF|;s5 zwEgAuNX$OgGud7?wv!=|K0_%(t)8vvx>W;gjVahwYS=43xKZxaWU8#!UvNUbW8?w- zbL~a;!0@$}si_0FhvKSUo9j@-&^O2>4GSyM3lcYKR3gy@Y($tG=(#1D8Tur0^yj23 zM(O0iSW93a%oNP+dr)M*g9muc6DG$;K?wAC{b+)~fd<+|SNbvlUqemt<8iP-Ce@?w zoO;P{dTxvXxF4vX-7u_1L?vXZED-|CViny)W7lU^R3N|@b#e-+v6s&M(_;Ri*;}RH}=qe{`Q(4i9&>~Gb0C9%YInA#Hz7#qLvKdS#lrJsS zw4N@(q&U&tI`jUg^LA|hi@*Hos24uAlPMnrENkTl)F#?(eVNdvACD zorl1zFLrY|&$|*O7QE&LiD2R!n3S56KEg>5rDn_q%q*(?5GT5XIw)w^@=AvD?aTkO z4;Th~@8P_=iUg(?E;#I7ohYnc38XJL6uUg@)x;VMzJFMc4V8M8HJ%&E4$=D8={tH! zC`WncAe%YJ8a&%Cayb;Mmm?W_p-FL){n`)zTG5LM3942G!S*+hUu}5?2WDTTL+hNb z9KcO)FC6Hb9#*gX*Zlc471ovCy?gk9CaVxe&xpLnfcQQQz1LN$>j}>K;*3>_x5_eB>w=n zHRbccnA!6+4Er2veI%Y2Vi(0gwUe%B&5QZi;P)+$rwoMEp5t6(TD*}D#?XP{S%rp+ z`XQCAb$wCsAF4?zvMA3N1N=8E&My{&$dLR7<%AkeJBcpp**A;h3Lt4PZbzFtD4;lt{4FkGB9n8mV0 z0}|@#Xo$4R=_o?0J@i$Ey6q_@(GccQDh%qj(Os!$kPR{O>vpnAoEE9iVNkgJM2lVD z{^B|sJqZ(lH5x5E0eBb0YGJ~SU&a zt?>o@q?24Lq`#-35D31BKSqd^R^gF~8lb#sC3loSUAybCiWz|L`|l%wy=%xmJp zF{jzvZamn|*Y?#9oPqYr%O+c}52Ry;!Xm!psObFHy=?V=xc{g7 z?`MDc>rXab{_4};eY)1~D+sf%r=SSQtw*|a5P*0tKgov{0d5f+-SS=rPmNadLhGP) zM~6cKN8UNG@#2lm)Xzm&pJ@{P@!8c!A$@Yo@idH|pRT$ecq^nttFU3~ozb&*2Sb^A z-z0{&wOS^j6Gvmb>itbz+oyRrG*~tiJ|UbVbG1G_UuVPj{_x3*KYDGT&v|=3eD=Ar zcLE|?s))~hxuc9`&5gZK5Y)jH3)U5b&=_#;O*X}2ue|Stu#Fw?*Jvyg>IW1SxyZ@* zEVmUs!+FP}o$bL#p%1v{_(#D)Z<4tI2&+EHXVBw{i=F+k^8Y%X%U9$z#2TO%d;czq z+RIxsX;s3y%h(vMTahVPJ7d)khDEd&F(`QBNd1L!6BiX;>6+vQ1J_3A5Mt16kG1%UEdbI?yp!DqQ6k(LirEwx< zVv(2~J#92MqlD;bO`T^j8BxO!(-QblWk{Jr2G!Gc={A!&v0Ff4R={tOfl`WexJD!p z&frXz1dhbXwLvjO=902djbz_xs#q$mXTL7h}eaw$V1R=wuZD=>GEJGV>Bc|qYpTZM#Jk9<(9Hoy*D zf&xp2S}$UF(YZ7Fo^{$2P;Rq0?gR`5ll;Ow5bsrMnxNoO_L4ZFpN)*(ek=M{sM_t46v z;1!-zf;6*f!71h>6$g7UaOe`A6dAVotFOL8Y{mweOG3=Oz5b+-SO-FlNw#8f%hZ~w z^2Szgr@#64AO6NbPL8SY4d96WuRwJwS-&FcO7yktw|eUAno+{;h#^s zYu9uP*0O7{#I=2D6T_21BEv}~(O8^#qUSFsVn%(}aO+{F%MQw!a`(-b9zNN3#8m^s zhNjSlur03!rX|=F&`&)4%9{(7)?qw&_3Ootf2MxEgW!9=y??c-P$$`KckZk;4<la_Db~Ci(rU&GW}@XPdj7KxBxkwutgSW_&cR>`bDx97eJKjI3%S=GcgGa>&y|FWPz<5O> zX-~?s7xwMdH*0*A?z7>I#HN@s)Ap;H-|1OnH`EIXhall=su+i^C}^nmoX^{{e3lm zJdYdL;CJe7H|&mK1J~#)abJQb4RE(La3&}VTs5eDwca%Hd#onHrl1(`-QHH&VD-2` z7>D-04N8%WE>n7RjNjKizl}y!j$kscO0xbE$-xL);%9Wy)kj2KH9htD(IR+_Gl?be zCH=sRnjyQ3ZuD(XFIe*3uZoZsQA0PAiH9~l2`1_k4dtJ3~M^fqn-K^0d1cO)hkuWxJR+O=UVNNez`OpYNv448wp@ik;M?mOsy*Od~QV&Fk{ zaBA?X5~Q5_j_TdET{>lwEAcaKquuB2zrci*hye?&ce;3hI`#7$WxQ=juqqk6aiJZy zyg`K3_6c<0xITeKXQg?x!!cUt5Eb2#s#-8C!B*Qx&Gp^0&^|1&7TaGJI?EB2JI4yu z(cGDr-quf@sd?_jU;A^Oc16x4<7A;JQ)0CqEveEszx1Q$V1bovgY$cRSTM3@0zATa zde2o_a{qF%52YoRk}>nrM8?(kOlkXP`kq|b^7ca=4EGgnUJ~%aq$T>AW09+3rF`JG zLRZ7dji>K9c>2CMWL`~F&IhgVFNzT7h17OX{vfY<1@|ZQLmbC{m%(#=O`+W+;_!n1SY(9076*FhnyP=a|YwJUR`Mtn{!$f-3wOLy(l@=hc?p)PwJ>7I+1-MzE&OayhMQVDZu zLOyt=_mvF!pcnSCnky^j8LH`kC#;)ndfChx3Li;=jTCvs4amL9L&_MAG#VB{j*skg zBIvZk4%_WVa9c95Jd5KY{oUNshQcxXnH1!lXqL(hh(gMR(|R}O39I;UiKL#&9k$wU(f$UF)aL<#jyI? zM+WJJuOw7PkYwTX4Y`w`FnQDa)EpU`M&P3cLXlre2WbNae96HY85g$uwn1L@x2f&* zYRW*ESPra81ar{O5Jm00E$&OqBr0dzzw7i4mX4z?wK}fi@HK3O)HWL1)yDcG<#Lo7 zGW%9FpKdn(bqppOv#qM?*R|4(V=1tz3V}{GRK0*LSb-Zn-2QGh;w6GP1g9WzvLWqr zfvI)D=&_-4y0l1%q2|ek%gmDv%`ptqXlPhVQ$m5pq(wtx5Z%b`V%(0#YXlqWa;;_1m=!S1 zh3R{<^HZEJjp)h(WFtmzNB+i7$M&aR8z_es2I4tpp~5o#PLs}o`k5An$ZItqfxQ2r z>-=8Zyw4~e*^j=O&#g53CuUm zWg(OVloDD)p*Ld}yBK8`y$B4NoAh7U-?Qg)p0C`lY{79}N$;x&qWI{X=Q-zOvKgga zWjF?N?bBXP6%53190V!!#iYnmr0jvN`fN zgJ64+3H02)s3Qy%7m@jGStM41borpOsI9C6w;#RL5SQ8Tfz)YNsog^ymah&D99l(` z4?13`q_MBopbuu-&|%4 zY1hJ1A-9OG%g{#k%49_kU34bq89lmusP^A-s079^>xL!c(TC;Gkt8dv$n~%Lzx?CJ zKkq^c4EVDT9&Cmhqz6uRZ*=A#73Yw7b^E8^UAH#sJoro=-zgY78Kc^?;?kIGXnWhj zepzl9=SH~(fgI!9Lu-`(E z-u=4&(a+3BKZ%CE^^4zq^CxlDJ1Q464!9wG)xEusy_(lmTFJnJunHxi+7MRO9)p_q zLz&=*=*Ge^=afA4sY|pzVRoZ%RnqROu)0k6)d1mFOxIVB!|oIG+m&JEc7$aqY1gNJ zP+6dV9B{`jm(n8aHA}AqnE>f&@I!Ik`l+VNWMzoRf9Nvwsdphld|kDEMUofZU{AWD zgJHcI_MbK6t-8>z?96)@l04y39}+h1fx_$6e?9*urerP~%^e*@ne2S_THMAE(0K1x ztU4Pu=G6d8@ev7G>_Q_)Qf*WeGfFZ2CH)zB5|(@(sry$P*ekb&T3D)!(^gQYm5+tr=-Gl|CRHD(q>h5hjw)XU zvl62A>J@bMJ~c@7RlA@Dxn1MY`*ttsmJZenTESWcdzY5}W`Jy@cnuP~w05gV_(m#~ zrCjowK|+3(LOQ2f;G;YNltofp=9B@=9+u}`G1tgngS=U#QYsvpS+G{4Gsw;=L;4;- zwgZO2IoNNB04#DS?ar1#^%TZ?l4Jj~p?NTLxUqba8|N|v6HEs9_ZNY2y+v(teEp_X*VT zNwPgM0=&PU;QSd~?#tIhE;PMEc9t(mB~${Fk|FaETUEWiSp=4sFo43oe$|^ff_oQX zKg-TfNS*9CKX&oiZA{cFcn}A8dtrZjPxfF?wI_PKqP8RzAzl(wN&g^hm}xW&d3*o! z?d|8^sp06r!STTBfE9eT=o`zOnSAWISiWQ>@MUMJeBd1o%8FKuM_|a|ydg#l}-B*_=t@$Khhq-t1hdAO@0U{xk{f_=&8Vmahb%G4y6Qs?-Kv;Qwa8vx&a z@cUUK;iCsLybVCS>5 z3{{>4WPj1T_1`UoAq!f6{^d9Cz5GOiv3C?OMapu+ri5N5W6JHCrVzu!i+ zs!^#MiafkI*o6k`feNEri#mHy#rnS=gM=IIz(rYpQFZr^^j`SnJvH5X)zLj+Gk|%A z4+tJ+Rh8#fKF(wXyY zeT?wj%0RK-SCfO6BJz5~g;kX_&@3EI?KMt%20Q+%0WfPb{BT7`F4~XBl-iNzQ^k4E z*T^i6;1qF^*&|3$impPIvs8@a1;D7#E>jynDiW47$960!&_!i;6u+mDkZ5Pg%#mu6 zqI7h0{zFvke}yg$s!|$!mWs5|1?cws(NV-!^LfOsv*y2%ap07JEkV%qGi=!j>1fM< zmvBnOZuFf4_X8Za`?!Jo&32?rtTUsq2-9r^QP%CK+cb1F`U`13Go)?4d&jCYi_hIH zz_;60+3!xjyR)Uu=bbjnGPrBx8N*R~NAqHMuHE;#V&9nugT(M!)aiDuQt0A7vOk#p zLTlm3^@5?W!8S(WrJ9S=g=aejT93X2d<&I&8$%MVU;2e>N|US$cvTO4r83}}w-YXr z$pKA9l%{2H;c9hZO{IlPS654`#(-7jFzZEHyU((;kzvka3CpPPeZyq!Vy&(%tX*B* zN=4WFGe+4|_8Q$op=jsDe3aLoRg{(cH!}ym($2uRHw0f%voJqb%2JKA{Cx&{FKN)2 zknGKpL4O`oz_4ui%%1ad7WB<1A1hay*mqVwa~TC-=_VWs_K3(!C`Cgmh_|vD^SuQ*u6l)P(w>c;QhVe zI1054FJ~P|KL&AV4_d%0by=6V!D%0Nlc!`|sB_rv18BD|_Af68ou+!&gR+RDPJm)O z%6??8MDbWJzdH_t-f{p{ANu;_)(~>|RxQEWe@3Jx=2=MDc`Hv+Sy5Rc%U;i5nE6&N zrP)|GD9~jUBQ1JkaCuf)2*q85tLnxO4cgf5T`ggib-}Sq$3t~J9Lv#b_YV(w8Rfgj zWl?2`#^p|+#g5jjQwf1Rf`S-_zk8l0?x1T+fX;-cFcV2z+!3PfoA+ScT=ko}T^$%a%+t_e* zHMH2P#Qt%}it?skO=hcd3vFz;Mk^bxPjxp0si)q?8y1r9aMFfjwYH^Ru!*cQ@HbVp z!==TqfVA4O(n}kNT!+vr=btVZtNiGN01ZI$zZR(0g|EI4%}iO@8ZIXDxB{YC{C=^) z5doLg+25i92cA`Ww~kNc)e1)7LCDF{iT2#5)l=D7zd5;IE<|umPw0c!JX@cAsSnrW3fYP3S%z-ZR*5imoF%fcw$b zS!C?CXh>_n?TTjFU^jhc=Rt$dFbA_69id7iK=Z3f=tkR6x!!!&XZ;yRaI@Ln>bAEK zthe5g!O><0T(7C0VQU92t1u2@!QFO+1+4ncYbt`(o1_Xtn6H6vty?=&VDz(KOY*g6 z>W^ymT8P4`Jo7-TTBZAGjh?}p(j~h@Lo@EJv6{7Dhzq5~l4NilS_fB^7+r9Ixj^{U z5;qI@kSZ)tGd!*oIBk_FuXegt3s+oA@CMTJ)xz4+eZ$+@>QW8sk#XTKjVc#bD_5*Z zGaX)fZ*A2MZ)w?%Phj>>Jb!dPe?1>%^5VdG*0PMrG7&B+tYsM*yqrOtz9t<@fs{v5 zmI6Bk`~iDj@8?50P3s64`|Gbw5;=MM{XFjV4OPra<<)l07 zI}m1j7l1oycUk>~44@(B@+=_%TTo4~6x+LpAIr2mCybSS2!RxoI9Psh3wanc2s`(T zj4VvP$e`7L#9sKSWYjVs^?M{`zq^%~V+(5)3au25evOQMdn^*I$_E_87?QQ79UgW$ zwX37S=&J&K(AR!}%vY5X;w8n@7{gqJvcvvO@skGFBE!RO1Qy(0<$FKiY|v^?1i-GW zT@fg)&CS{~u7x=@O!2#KzyI4`=RAv&KH#4#WBA?S{z;{B#~TP$2W&ulV-{$=5p-5} zE>^$@q3_(e7*SV3d&3O_VD)7l)ksdQu0wTGOGiW1BbF(pqf%}2Xpj`R6gsTU;CQ$9 zr9-7eDqZ`_bO2KgmoE}2*PQ#h4qC}q0dC2jT#-bpGOJ5FTshym^j{&A|AED*px-Ua z3=4jJ|MJz#zn@=|CrIH>(hVCaez*L_pH4nJKNlG`*ed_Z6SC;+D;|sRs&C;KpAzoc zvdpngCyA_Pr>&L%03ZNKL_t&}@Ty$2N2wh_B=l{JK4oo|RbNljkeir-yJx!SCLh00 z6H-XE6y6?`wTYFdN!><{&?@MKlb6RO&lbGPXQf9U^9=8FTrTaEMTB!4i{fvn2HCrl zoFo4q0k3lG#Fprm?nTjxZZIaQoHlv{hbtiCY?Pae8M_a~_HJ66^ zGJlS14V-Hjy2iJ1hNt%6srVM!W*opqf*pY8XN)1c3c6(scx!?lq)Gh0#>QICJQk zt>+A+CqdCI$*yLM@y<*(W~K~bCqvb*A~+h_-okYW%$ij9!YP@QyMO|aD+ z=?&}+DEhgeVRS}K!8m-;HfM|@%c8{R<$=A7gwbOKqrJv@_by*2gM(140phbrxg5cb zG-e-6qAy`bOS3ybRCSijY21-cMxQc1(bQQv;fcYRN(!?{FHO=Un%HO60E-!O&G0sg z^OyZE$yl-U;3}w_NTP&Bf;FUkjv>mBh^0)>35*G8oyOpV1Xx5sKUrr}HiTO;LHl3| z!n>)0q*{u~g~zqKrEP=Q)WRmCX$haVrGjS9i~09%bvti&JgL_1;RCKJn{w%%K`#|Z z%S#esEm!FuM1zGmnyz0~y~~(=>UE@8H<4!LIk>P}$NkfM?33cUS{Z=i;5Q0Jq^4gF zZAdPLZtf`j>ZTuRI)C=k1)c80XsN8wcf4vEUcCC}n#z^zQ74l>;{$&4 z7mx1WzH(*O(e%!RzesgRO5C^;oWIK4xX9>mF?0}NUAaD6t zV$hBZB5<%*H_6Z2#)sE=$7!#3`?rB^tF-XR!Q9HQ%dOUgyGrA5?3Lu%?Z7Ky$#%5j z0%*J9!B~dFi|3>NFA3|9V~?)Ap$v?6=i8SrUi|pt)ys2%uaVPhpMC!Mm&QIf-a7fi z7d!T5djFi(-cI>IW8gLmQsa0N1p>KOyG+NybZErmcfbWnzu5e8!s~%!yWct7m5^$83%Y8?k zVsTo0yckkLNcRY?q>W609Z1l`d zh_lz_UP)xXW@W68)vVObcI#{A&8oOFs7t+pu6<7N z70Q5TrcRCbZqa|#knGA38f2Ym5&oQM5WQj8+aQ-ipiBY7gpw+mM6)0^fNc*?(inRWebiA>?HeW9=_9aO^38lq`JN@UrBk zT{@v?N>tDkFrbG9atDA660wak!oOW{oVpO(0AWos4p!o)5?$+$nLTPM*U2{V_x#&ywa!Cc);QM zF1Eh>G!8(k;h_B&AwIPX3!=(G&B5Yra8bKQfKeH#S$Y5k-nAi^*1&3X} z#rcvnv;LK?icG71NvXm>c`@W!YSC*atoS}ylV$WJAKVs<9glzW^2HB7*x$^nf7~_@Jnn3i_Z!dqa$gzNoSa{~Ul@y3@1Jz! zwf!cnUdtgT*^u#|cRLv+HO^|rusu=HKeH9gG?x$NWa z@q_8kbo*G@*u?|=v;$1W{`-^Wxl{DmFLzx5#l`6$I~(8d<+c4WH-62`eEhQqhpDj7 zi$$nfC&D=yNuNdN0;Yrz0dy>fB#SMt4rC)fVW#lN4#m1rg+_O|ktQv=YljS)lY}?q zlC&X3Wk|xt6g4b8%jS}VZ;<>!q;xcU7S~`pr;scek=$Pt&viq^!UwS6RyI4il|@xW zyDuqNA$KF*inKnMoD6}`x##hD#XwJqgeH+MosabV9~odoJ#7unATzgBk{DS(q`LJtg#+v2|~LYX(l+0HH@4 zghQ(-X+q22`H5bmNBAT;Sy}~S?{yg*r!xzE(&Az1P?RDe)}$uj6I~M zVa#)(QD2RWj9sRi(C+kXtV{O(Y<0CO{EeO&4^G5Xm6cQa##6k$XGw=y9ObcOH<5^8 zI${Bw289i8huHYShZBQZ_Qs^MB8U=g3Drmm1Jm`P!Oe6G5p;S`*&8Jl7TO(9Qhk%e2d;eZoEd{f;R452vSn6O*~l8aomP}=M+YfF05_D|T=*v76~deQs=dw(jwU9Sx$EAzU;M2{vFtCN=elzc=5`P$_l0bUU_xr zarM%V44;G3rCb*l!Obw7V<9!{%6DR z-bkL+3>L|k5n4N!H?n`GBWwTuyaxuNlaJqD@z@w}2&Q6(%m_JG zsxu>JxLjD2PR8qv23K%o8{y zr=38j;{;DCpd)QBk&g2X#FzBS(7y3&$_LXS7Q@ldL^LetZx!F~1k8CN)SqC+9G!4y z@Wgx=*)!Eh2CZ})83OlFUEvD`kNbTDSV*zvtAtUKg0+Dun1OS@c0UR~-cT}Db-5ok z(5|S6S2o)JBDis{I`w(mKc#neFgc#{I!| z&$J=*@%S`0q+y2hFoP0nyf`*vRQToL@i@em8ir$4Hh9^Bk~*Zx%4CX0bd5;ct#6F| zdCYKlTAHls9A8R*8BT`dUR$}XgzzwH-=zIgBiV3dJ0kgWG8Bu;^oz{d z@HZR)FskSX1q^Y<&UQggCGxCfq$~yu*h+PkQ}U!eCt*xjQMg!>NTSR=H4?nHhc#oD zfZTy`fZc)7;Kbm(+#Xa=VI>e-RT4&dsg^MiK2Pk@;s)%VbG@=vSwQBD>=d)o(gASX z-Ws$!?Mi#nSTkSR2Y_<>hV-+>!ghUAp^t73 zA{ArFBQrcpQi3b!D$JL??dIn9lc6_*DYLWRrNh7!%=seUeno{_NS_(C~b~Q7DX-$w@O6I70uR^!3J@AyzjU};4 z1-M#Qz@Z3#r5n*LgLYSQi2XW88uAN+ec>hWKlX zos-kOm#!_JkR|m21o&(F_>R}!*^vnAk3ZH%_^V3~PcL3_`>*retCD2BjwnmwXCznn ze%IGuv;YU}_;nRC7(zEsD_PWpZG1DhBPjy(($c61?KtX_#_r;K2Ec!RP3-nh?aZT3V!6kq>yNLM9u+&EJ^HlaG}C(t3$)x9eEch668RPe zqQ)HGXLMM$5+j}SZ3=gnz+_2Wd1X9MNz+&y2W8zFXgWZseM6e0xj2D*~PREj22GO~M zVKy$LY(g2)IniW1kAz?)61%%)cE1C=JHdKvVCcFK+-rzij+OTYPZx|!wC!9`J_oui znt=^h6LSBu1tx$aSJ|s<4GtE_elAZQVMDTSDM2zYo_v4upnb43S*a`?5p;zf8W|R9 zEF-+`2JT?)L3*_&V=!!(m<#)I1E^b@6d~;#Vntf=#qOrEHx4%sUxY#bSCMt+&Kg0_ zhM5m>7WSMFS}Z zB6l8sxKmGkj=+j7ZZ{}gFx>4bVzMhHECfz@R)-*Xsv9VryUMZhy)YB#I-A~<53k*h z1YQT#!QE7=?oSepMoJBOY69;4!KqRBhN3r!vQ#REop(T6HpMLsx?7&|A&A~dc?3sG zW?|#Hidj@ku)?vNChvH7$CRYaf@UeRK8*7h}pPY>U<+JHWEK~pS z-Scn0f#^M7aRJvw^anfOTfzJ}uptR$J#XXcdcbuxk$ypXMWCNzxzW1owNrvp z7jg^d_BY|~xf+nN3zUuQouB90jDYO>cG&H2f~U-?!H_+J-7rkhWH zlZ)l|UYolxN__I>@5Z7h*St3=@b!)`j@m$Bpt!8=P{D&CWUnCUvlg|D-rOje%H6vS zx8)YJHZ2MD3XLGe66MsKQPOt^;Aounlr;(U?lprrX2|nmY3^?gPp^VIFM3V!XpM_+ zse~HZZA-|t8YO40i+ZrMSp-)X=6V`T7kX#@n9|*naQ+PElWU^oXfm>^{-i~1whKO5 zC+rJ(wPQ6UNqDmmR6n_WShk~~AU2d_ek_>{`sQ>zf~G3T5!aCOSvY3Y#~?DEcEb_< zgrY*BkOv|mZ$<(QBI6^9(_EOM_n%Lg=y>KY(Dl9C)R1`+(O0uUL z=-PQ>n^m#l?S6VAB$d^~ee_pR!EY5*O)rDSBDj6FzUZ_1^Aos!qw4%cd}W`tYP6=U zZ@+46nVm57wpKO3oTmi%UKOQP)yQ$JY5;3jxPitap{`*vGOX(A7qjBPO2Q)hnf%F` zBv_JNJz**ugKv);{Ih@Xm{N~kv z#H9In{8+gi^ft`Q7$DD}!J>!|J1|il(=(ZuGnedF!5AdHKQjIz$RqDL;!9s|1m+Gh zHgF+9h?!D*I!88UUy)&D0b_-6#3Q+QGLeYvDib0^1q5^4 zDgTGBvwLmpFvECd*{VK_s3asBNp)f!xsty`1Wx0~k}NPQGo!7+>(ItP^1Px2wX-Kk zE=F$*hG1eyO-KTU_M+^fg^;zdL0Ch3wSQq(8@t*?p<@@@AF%iLyvHdkqawDCr6Z*U zMbCNO_xV5|osZT$hJ*g{Tmq=I$L~F@<%c!;ViMjA9E^HFzLu}mM!8Pm zwt9>ZIE&@FL70axg+eW7zV1`RR&zs%z>kDAV+=Uz8hH!-2;ctKG+_{%4P`-f5nS@m?FKZNwAYrhJ zNOCHJe4T6#I~e8jBfAh~W<3mYg~wfzHB_wNIah|NgpA0Q6sB&FedVbf;4tM-SG{r3 zRay&Yt3Uq#<7Xvdz4x=@H>HT`{Qc{1{uMIdf4{~od2loLli2kiCC@wO=dW~+f0{l$ z{#+8Hf!lAYtVX+DW7K)YyM2Yi<+3*)RJC?>KaT1gKw*&DdzLz3!=MV1lmjh?@kLpJ z54#mb?PKowyX=VPRa>amgiw;)oe$%ntNyI{MF{=CfUr|tROz86=JVuX%4~(C+V1;6 z>)9bx0xmcNM!vR0IAb8U^&}I7@o#z9|U)(tu zk%_Rcu2=gsjZorh?3PXi*1J&>IHF3vV(o{kmm&sc$ckc!PLaOgwZWN8+><#X1bJlk zwJwgJn#Q4$jzo7L)?{cgM2;ArdIT9xPq+5dkESxz0#Bt|)C$smWaM@_jyl>%Fbzlh zuw_iXnN~V#=d>~pk!S5mYz6R6d-5{|Bx10LnpEQ;9fSlvYgJ4gu)%TIy+8&u8CgDU zX1$Aw3OzJDc*(v4yK9V@(PN>5Mk|f_iruhrT;s)+HFz)`O1j29i$p| ztV-aD>!#WJ8VpzLzT(_!jK{PHE<$nbt}Ce+MGckI8m6WD)Em)2nED+XV1~~)c2n$& zRW3-PGeOTh0P~GKK$exgl9fj(>^{;#3V$yVSJ&+&F#iI{3cE^q0HpzLEOk43+fX<4 z07RBF>xCV%$};v2VV$2$Dk}}2@6^;z61y6c=SPw}N0~8CF?N;&%N{{@a{@DPo?4_NEI3LDgMqQSfWck_p+iav;l(v9N~3`u?R4y8>|+{;ok&$ zAvSk?KuxA|QwbcG9d9*u_S`KkmBDIQFOFY*6SKXx_XMBsoyN02wI+)n?R~L#`Z7-7 zzi9+*x36CgZAh4?M%o-sMJs>%*YmHv}FH4VwEw-rm~wo*xF|C%TObjbk!HbO55%h0g|M{IoINYG~R{^jX@ITJ9+w8Tx)4a*efC%WPgdo-RG8;_@j=WYwAfr3#TC!GF=nSKUlyhu02Wfz|Fi3aFMX zsqBl~Zugaeq*!tgDV@@lV|NGT<+6xw`EKZCLK?lSUIy*OLx7i`*bsHOQ&x$Rva#$n z-th)uEr0DMpr=Im0}a&eq|Z)IgQ#~0LSZ1n55J73C8UAAg0PBob}w*rYCowU$%sp_ zcJ?#c4BKN&BO|D?B4G2>&eWIM50i_Jc-ft*uLt&Ia zFAL(e)l{QWL@W&+d-LFGC8gv^Sn%4a9jr+gjp_Q;iJO>lR)c4w!6hlMN~M^1 zFDV?zq_31-x}LfoE4>g&M_Sj{98NxB&V zG|>4Os!)yeV)-2^4(pzMX7!B}lcvIgE-5A|0U`5WOV+U-Zm!&2)mR2s*SM5u4?)mh0=!>G9Uq zmLT?ELtJ=cqp)(Yeke+OxJ5Ogfv@7U)(@yf?IdOi&S_@Do|s*sN6StVq?-{HTvZoPPL zbQZP%hlmJ{Mpq4vQ`CMLd?*0&glTns_Y5W%&`^ z4d>bK0pJ&3&mRBAhsVZ%zqtV5x1^|gZ9V(>d60T`cK&X)dX!o}I(~MuJRb_Gs#OHP z{HaP2tWZb|mOa0s>PuZ#tjhqk_xU=r?1n|dqSDI(Fnd1;(J z zEH69ia!qo#%cEfuhvv_A%~0llM^zNgo(+=+fVjQPHBs$>&$;jV`umIHQ)4ml89czk z(I}#*s7P-7k$>jK_p$Gyg#PoC+6RsE7`Q428mAIa96=Ae5BB0A&P=sPmL^FfqSdit zqgBK}j3I+eDuUC5O{)Jlq6P1CdIwh$!5f5RrRh7A9ceF(5h=q?*m!TI^>A7ktHR&u zSC@?GKAe`xeppg0$5^1&j{FmJm~+VDp)!24R5iGeg3~~9nJvnuaUL$}IFqR2eVrUP*I0(R!k+7lf>O!EWIv%O6 zR^P$zs;6V!3RGE|OyAPf*xMSqUT>(}Xt8PC5&)v|2Ssh+L=rbXSiq}Jj} z!0%$I@JJ%8pMHAt=IuW&u5VndmOjk(-9@JSxTJr`rUT+yB*269i3SQxa;h5qDBgHq4NY3O8LHCBAYY1+? zie^F3+;cbfbaP}FuSIvWa6?WcRZ0{zVBZ+M`$F(*StO&$ZgQR;`R4dIJ*xj5io=A% z27eQwoiM{>JCp)CW2qrkIOJf(B)THAgG%5KU%`Mk4x-r5pn4~jlK+>~D<;un6QLx{ zNCw9dY8+Cb9Rt!~^1ERumK;XHn2mlm`uNFROoHkWz#OvS}v(RxajA)_ZkRl@$CxG`+QBI6-ZJamwn~2KS~x_UHC29GF8c!bZZUc}7cEn5IGI<% zRoPKh3tlOk4Z)uj?eJlq>?=Sw8ucWsCx@yEJ}fe*o|-Bmi2jN`VA7=jbf~CFP}*?$ zu6h?{=|q~G)f)J2bop+6dD-CmtJ!lyF1E(#TR_1c3O!RS3y8eqd&!(s8$&FE1$bNyN%3&pZtPNDrAWKu9)m!ou2?f+&shF1+Y=vqm|)1X5Y2xNh_-(S5j8#9IIL5 z#W;g0JPLeC%Db}nc96XV2CIQ^oxMqy(8g<5DoHiU*!fC`V#cTIgV&@OC9nj;6a% zgw_f6CjAZyxpJng6v~zdMqeO=15uYmS3btpI@l%B3X1kwv=q~ZzIv*7vS(M)mb*Q@ z`SEWzd#_&!aNP&|^P4|kAeORq?NRMFzbJw>27G+~(Uo_eU(b1dcSrPh6vd(G^Yo}5 z>HP`QbEW4e6fV$l)X1Dv2$*cd)BBl5J-v^XP}K|cUibTzz9u{sLuvbmarniT>&%+n zaMV)*hhZ?1EM-w%Q!WQR4B8X>8dzCbsHT_f4>Rb$yko$h{=XaP-0x-|eC9Iahi^3) zU79;FE=lF?D}33d~D zdn9yL-sGPBY%1nibho)KQ*X(wML~db(>+Eva2!E_VY^3!Om2+qNyc=mA8<=T#}V(N zda-%Q3xSb#k<76z&31F6^!mYZ!|-w(P#r3OBPcS8QCbABKEtKN3fS=U?~xEHoD?Hy zU;8GV-_k!gHVhkhlHp8X1CWefXDq_0L&ISsu*u<0^4TzCL^uS-j->`M5nt(>I|N^i z*-O}~hv2#POt98Cw*f8D90tCrA+S76dI!W3W7V!qFnSm{E zr!(K7pRhI`S!^SLeu~nHlq>83&T;_4Zn0P$aTavShl38!*-E{Fp*eMd5R2A%NUAOPzb!1 zqpXUfsuG6gmhuiM1 zz6i#ZG{(|<35F&P>-?-S;&U`wjU~gwXY^DiLt%y<%D+N5 zKzBztoSKmKS=)@THX7`JRZ1u&G|3w>C#7RyHlwD>SvT>v-}CgF;uudKp^K5O|q zArwx>_tO=rqM^f?-CbfTjrH1BRi&P>ucec<`hH`#vEQ%M(_4YE)Cj|tg6)x)ack${fA=2v+Ry2Y(s1CGO$E%|(td(~%=+#j~)+)1TC(Z|kuq!Uqa^dsp zsyxL9#*F1UUQr5%La*$tKyX(GgYGV@NC^!+mRrdqqwymlwY~*GfBv#}btcGk2Ek+l zW+v?+&tCPLP(6}xlKHf}y+PI_TCB~4=S{MtWf|;=le85kf)#OM)Hd8A!vmnb(CYcX zS+nj<=yW2;dFFL63eTXhqE<=qlWHZ@?_+}PsLIPIgK{(2`X*Ff*wQjOFdFrOA_wJD z^0Z#hGb+W2dk)N+UH81RK`hw|gy()#;M3cl>!(|%0^mEp5XJGU2M<2fJXuPtKOskvDS2GY})p2v6lXZv+xWXPmUr|mM)K9(o(lX@Q?UO&!dq&?cF zn9#09chlqcX$Q13jhEX&&PL0A&LO|*wbXHBq&VRl;UFwprXyz20Cdl#)7ON|U*zxn zg8cbC13tcP;LG0fNBN_F{`cE|{-E}RQuXxfSFcX5U;6wyfmfe%n#k?m-g=NTS;CN` zfvyX=j);a*aI_Y~asBYxnRcZ&^hBd>6i!8B1E zhj|Kq^UL{J$LYKzTlwg6ZpzodcZta&z9X*=;boS-QWEHpvNN;sr&XwX(ANE0!Y1q*M-LmEK~dc*Q3#TYn~$zf;ij;CcA z4jbvk8$3ZkRyt#6W@NKaNJm;>(Bxa~68&ReId-Q46=oHjNsrfMl$13Rw=W?a{WxYL z{-PwcueP&z{mj7iKZKpnYuoo3$D-~J>!DzSi z5a;V3q^;50@8@|xuXnCwUbkGX{IT3Am7Bdzvvyhm0}T?(-e3hhqKgp89f6DH5&cIa z*WFGHG9}7e!B=+AA!FIE4zR~jx8@sJ_N)+?IYv73dfrB0IGyG)($(``7HDR z@A+--S;NQ4x;?5j0=LrB(af~vsKtp!cGWuU@vJlDrOlQ@#}q|N3=k84Vq>}qmUO@P zb6c@0M!}jW|81F)g@XWi4n$~otPv2if;L6dD#?Go_E;xI5?H># zf{4%dCyBn=j*fQxtT#-gUHEq4XnO+~QnFoIT@3poUBpp5|{5%W#tFI@`gPK3D zh0~+$iRMa`-+%wVvd_9(+V)}fzB%CJ)BqM%wp8gQ%N*5Rm(AoRd*xCV51f-fPEOhP zbB7%bbqzFP4|3(-Ka%g&;&+F*^R_OGb|#$*eryB-y6rWE?1D9c*3p&*)PG3)+z$A& zPd|I>H;Z514@a=A*KdCK;fFVGzW+6XxPhzOr_xs$qa{FB8tne3`)^fkenpba;#zDJ zz31LL`T{lCoa=@d87-A4EQwfA472B@NqZt4k}60N3PfY#7QwA05Sp4BL-;7FeqrNMUu_?nBvN{R zDV#3zUxJ;kuY*Zj6@6o@xD`Ke_#ZbE3fs`&8j&t;m{_;|^5Sg3t0$%<#z=XH$7R~A zg7sKNSDz60nLTEr&#}AeS0IE#J~}fUAL?~^`Z=a|_)xq_lhR<4CDitzL#lvrw$orG zhirJGOr4|AI%UAqQBz!d*R;-jKoR)JknPo^K1eQ1ezYg#S2)_bNB9; zs>X*A-IJyHU!RV}A%#bWB%+5Vv=LxeF&!esrno?gagHPsG-2oIC_7&aZ%zzou{yFb zcEVY~IuO%bED4e$X_mOeNm5C>V1DY)IsYn|JTc*&Nt*sbGE@vR=-_e|01Z}J!n~2(DOa7CA_U-xVk!< zfGGDS*TBj_Tptb?0=UJT!|G^W}~~{p{s@2z^3$WU)(L*-pM(VqE-jYhGnAZXjoYG zi(-kmR=#?x?IUV3)CZF#^MW@cEwlsH1Fi;NLD{N_@ElcJNUF2&~1{MPBqno=)anhoVh zc!_IbdI=@;MZXog>jQ0#kM&alr%&G3+j8)RX{I7u2=BXMceJ?Z_2ulUHq}d>$L?!{ ztvX+_UYD9J^W|~DefQ)1t1mfPv*oZ4;Fk+18&?pw2fo4T3q50jZhcl+SdLzI8Wd@ z4+X%Af}8|;Rkx3z!tmiRqCy6w8M~WNxr0gVa}A-*2g?noBf3`7Kj}c*h(8l&gM1aI zMw#?F*Gg!#J+4-XN7GFR9m}4q5W=b|5)A5XT1(xvW^cv zws&vU`5^h-YGGaRXXM$G*B;!!;HZ*g<~(>8I#yvTkHhtXVBPp`=2uq6gsJm*;Z%Ni z(+zN57r|U1-K6A_QQS78Y#|otSTmwgn(<})mc0h{EJE2AXLt8#@F;Q3C;RQGY^wE6h)sM%%4Y_f~x?KVMlaF#T0 zvfD8a`IvLy(|H7~F@nm$JlZP=yA8I!_9=d@3pIm)Rj1(#-P_Bf2@3kk9{C}Xsv6F2 zD;oA1x6asvm3$T-(bOp0OC5CTtDYm-Yw8Lcd#5J9^NoPv0#41OT7&1tIiF00vCe?) zZ~Wrr(Q>F%(1npsjNIzZdefl9c-Bp@c$FT9^2GGVuYUL7!TzHUc6JVD6|hol%Y?eE zhF?XbF|{~hcDugcWv9I0Nvnec9TFXID;(fevl?A%G(79$>euFqZHHb(=#2{P*&|;HOKSDOj`si`-S&hvC4~Nlpq1>0b-VQS_@^8& zDXg~|zkLw;7k;H|)h&tRoe6^DmPzRq4QnBW_3^|FzjOH&$$WiZ=Xx;AD}!XN>|FCo z`I_QQL9c|KYH zt?jXCDL2#TSBX3SCk4IlZMG(K|NO^;51)j)nwC#e`yxH>>*V*YSdW*=Fq`r{G0Xby z>ZCyzulXd{V~0})gdTdj9J zRK=Ru`CLn@`>KWjV%ZA(kBv*YU31Y|gResA_@Ic3X65VU5B32?jivW5zq@*on@JN| zO;5+v!eFng&$vsXYLKuiH%R1Y(rLZ=P6v7h6zAyBwDaL~RJFjR5olvYeE`{4H0ine&a(KW7p@UC*vDDl>$bm0b@Y!ms!o73_V5xeLLcfji&3u=iti3rKP*alzc#H2S^8#6A43N{^U2U(5-)0WR8n zZ^8^PxhxtBzey$TnAcU&LdL!?(AO!Y1>yv;Vh~GBd!J9~I#}5(Ibf4du8`ROnj3~M zshi+zjuci_7TCP*bXLbnQ!>Xn7|}_SX0(`X@YGC&R-}q4w1AY^EU!K}ZjiG4*2(p9 zQwTH;7zEZyGIvsjIytB$OY$_Cy7T<%m(?e*-sJQ!)uTQZHURFWMq(SWd;rp=>H z#mw+&^L)P4BrZK~PM2M9SNtmluvq_gPeDy`jAUMz_3C_=i8OaUM6bF5fDr;%ri&A? zo&37Gb;5h0jv-8>;dX@I+5A%A(CA*Bd5Bttg$OX645DpxmC~v;iCUkN$hK$a0)TK8 zMGy=QRzr`vBNAHnxtt+wV{6;)HfP<@dNuHY1E4ix{*kY9du{VD!+31To@IGjB_Uy3 zC)<)G#g;vbIhA8ew!md2bnZOTfEi0I<8)f_M!mp%Gu;#dA=qFS;|2oRMXp*1Z3?~U zQb=$19}Ik1=x+KC^bgqkd)`mU*eQYd@aYss`JV52-{-*6SN!*eX3!HpXC5nL?|ss2 zudJM$oZSD*XHUQQ`s+vUU%fUvE4*`8ueQGvbtk$C#~O2-uHV#DTHD-0a0idn@C$-q z@XQl$fX<54P(82*ZH&1KNm#1wb$u-8O43yNrakw~LQoRSE_5TPM^ewP@!tYHNm4`K zbQ;Xww4iWGJ*JFDbw=4dqmnp2>b*>&{L`x>tiT8SNAEf6Cu}VBdG7dlfU&bno&Y_2 z+exseUrbDM_pLetwW@cXteRlZt*WHMw*a001BWNklrlHE9r~(56K6G*>OQ?CLMsejQs?njz3v=%D_Hlc1lSKPX+^9_HFbp^PPz3g z^X9*)pa12vcYe_@04_O^oNnRsRVN=BBVak}MSklWzMw4fW4N0*VE$7@)JMB(q-!oh#T~Z~2 z%6)|6=GZ;U{50P>hTN6{4OL0ftTXuNF^v254_}ni&!*?e#nejJ7%P9yb6A6Lsl`PU;%U{=gc6Zm_gu54oY>yzd#dw{iqbbD8n{ z{s$dSt6>(rgLWcS(oz333ZHp6sP0}W2`OHPk+eS;Q;gN%{=l|Z1+TIhmh*^7^?>Hq z^v8xrMhD2HWZMf!lP|eVu5&yTUya+N#AED;_YJ}cu?%B&Vb>epX9B%XBuC8GysN7N zbGU=ud$bz=*dUmtG3`fmFzkgF=q-%xEru06Nn;Xi3q(BcVHBotaL;gcRS{U_xws-J z_i!3%DU1QQJX6ja=put&#d!qxwclYw)H20^iyX|BTKN2eF9_7H%N&HF~_P)JkrA{(ePMi-L zc#_J&xSBpffLN32;Y`n1ZvJQr@IA^aU6R`}Q06FdtSRC*5>Y-h&`nPbi~O<}PUz3! z-UY6t%;y;tSde1R?MNgp8k3o$*U({I!7PUTh(z%HQLf1hbrpZcX7{1Jg+d{hNlSZ$ zns1bp%8+3wyWtVTVm!a25^T}Q*S~9qT(6jLFn8{kAk}dF%Ih24+8YN~4wY;vRhJh8 z)3U^n89lYyA4J1fXhlkE{Om})i6@xp^qP_=SM24d*X~P%b;I+UZ)g-P1lAr{+g=Z; z6hRKq)I*}{YEgRffnC$o+D%Mf$&tb2NPK88lwLDD{_=~jpS}L}`mLLIjD*47mEa?3 zwH@M2qLOIL*{b8I#?TTp7y1A^rsS&|4zcnRODiTOD|W0~)_st?5%`9^1xc7Z<{n_T z{mK)(5s0V*+6+$);yLtEgi;$@o*_M^J94K-z2E(hI>L8O?!7-AL`vRr#np9>pu9f& zGV)mw(c{_%u3 zNhwpNV?T8R>~6LF^tLi4H9Xhq*K?j7bC;A6?eeQF`0$3ZuLz0W(iinD%t+5(`#%i$ z%C8z9=31@G-7^W2T|O)Vy6gP|$d#Etx4f6Hg)L{@CBd$$(%5y{32sT`RRi7Kb(IP2 zdXW&39H@hpQsF>0uV(<(j_qL;kY(S!b4Pg?YG07F`b@l&#sv1o2$`inp3kkXUtXSF zetP-n(UV7)mpPvQ+0*CLCwQUJ{m_oH+2i?X&A>?rIi6SJlELv`@1N|zTc}ze zwUcICK~|hOX*R-qG9VLgEJPdZ_JC2ELC?c7{xdK#8dt;y==xA*l#%UNP+F%Ea}2sm z`+}XoxAzTtL$SDb7w(4)exbxZ>FKbs!xRv(9Gd%@woU;KoMw?iO!h?s6 z%Kq8=l2BT~bQwo`z$AL;nT#Y_lfx{Fp}~Ya3x6phG_akNCJRN?@C8HXC`T|B$qQ@% zouQ2ZQFAnL!K~W8R1bsii=$KafRhTGR4i6P66q;#Mmie)oE{}U$xlvZ8X38f=tna2 zK1wu>GE+xa=&Bk~{OHI)d^F_hyzQY7!K5JxutIwOC_6l^@*~<8wk5eT*c~DFN|75O z!_H93z&DvvSyBoUQi>d`WQ373VU$R)m@_MUGBSi6I7uo24vb=OtiounlR^&NiFoug z6X=6VmqMhgB|Rq>U)C>NX?6-p#q0bT=DE= zcdc*v4Y1aE@Mga%c&#ta@`FCbK0NeCS_?#49(kqt^JefpW87%JYVJ%rBrEgqkO}nK zCOhC}&G<2G43EFOd7}_i6S<^nLh(~$UPw4GvE-G$-+WV0hi|>$mf*sM#?ytR5BV82 z+qz1rwGSv(F4{j{EVj2`@Av$`!+83!q4ARq09^xY&8q7jx24oA(Q1#*3Q{gb$654Z zGb$9u0$~;$ST}T=FXrM2Hy!DKm@gdqMjw60d<~4@sIcLgmVwX;SPm+Y>Pq;46sxt+ z9?m1ACi?c_4Fy@$H?}@n_-_DA8uU*d-}~j#>`Ncgb&0Fg0u0{Xx*lX+jb9I^%(a#(AuC_|Kk{1~` ziDgQgbyIIivL{caT6g!55mG>oM2l7stC973`~ECi5Wb!b8WH9L%TlS8^Uee*l;--0O z_4i-@>^D!pJ#(jWi5KvuX#*iJ8eyEqg{b%tILK^ajwupPiQ%pPn=h^%G?+>wmui0DXFDt7)lrAZa7 ziWb0CHJo?4c#KdvS33_>eN<_8EA496cyY68thm-j2wiMr6b{Ts52_Rv8u#t85l$<9 zqggc;+-x4yC|)?Ai*U2nW(?hw0g0XiH`+=vg&10vAc3jezz(}7kJyyX26jYt%?-k#_23(=NT_kVB>R zuqukSXzf3+_w&48(r&Bf1jqK*b|4Txet$flM@m2CtV+8!zv*d6+K#red}?cJ9{d%s zOg<%F$Ud`0cGLI_E7R9L8DVj1Ay{x0xXM?f7MP&Qwad&_ZQ<;sb2m7+Fe}$?5Y50{F)le)b8f!lg!SYrAcggDsaZ{>av#_;A3{YWOjmrPeH>L^!&M8ZQBCGBV$(ZT-J z^fMZ?Y)c~}!5uHWuY#BEvi;~r8Tq!_O+asjbPEX9Z3%Cp*iIMcGQ16K4iC4QiA>YZ zX6}~kGhI@u;H+Sj^q)^UY4V(k;0od!jD=Mi1EQ2CSmm%?J~(#v;>916V7DO+TsIUVeK+uhcnk1u2tZVrq za+Z0l2C5CW)-qtt2ZguPcvZSMNuik+{mPzq?}MwGcTeqIjhy+;RQD05dvJ-dANFJFEA^*3KWd`QQ5Xz2b+D=R;{W5udCTUd)ll&)igf`Vm#;UwMY zRq&H6L^mdP#E_(EUVno`!>lf|&IN-~Z#gD+7)^_LC1D;Kn$#knjR=ZN1TaF)>^IV7H&O6HqO3*WVR6<|GwIbH7EBIB1xMgu zjrL3czlyA_IT@>)>F?TDgvIBHF~-9aHF2Sp3cQBgmPczsLsv)F-m58n&`Q|a1W`xj za&1h8qtBsil&xeIZlhezSvj1$i4Az7hU>_eoXb_n8_b8R<*}S}nBXJ8lfL#0fn%_L zThrX~&3=@2P|1Uktdvq1xR3xrLxn!#$%DBZ6*Kl=;h+aiOH+e_cN~!(3oMypbF2S! zN{9_R>%@eqjHzdBzqVtZZR8bie@>vv{?tbu6}z2OKMPoP!wI>Lw19=04}4^5eEI|l zN}Yk!F&41sKp%N7v=3=?k#r8;I;~?WBRVS-1%m||oTd3L(^T!#QxWs?q-$2y0>26? z5h+QJ*|azr)>JpD=mi`{$)s1d(cN@&H)9f;C}KsTIHtyx0jXv0{^t_xLfgv}J!oEy zVCdS5S25Ej{fMeJk!Xp7wL4sB*>BV1wyE%g0(kpYu~1+Et2lSL-JWS}6iqrdX6A}C zq4~h;D=SiAW6Mh8UU`r%_sR-91psS?9ERTUt#M^B%>N!Sw0oJ{Zfz01YZ5(0*=Z`- z>-3EIDaTj^?8)ojM=?lhuls)1bt|ad_3QHM#jo#W1%-3KzdA$wk>q#YgB<3CnjY86 zHK~JBy<5EysaewkovAd2c`ZjjkWz2T2dw$-LZ3^j!z0yZHhpx;2KQJ{s*!9)eV%8; zjn7{dHVlU}-F)&IH^v#F7jCx;t&R4KeY55YiCQ&Zp|n2Q_lMzRkNx+m+8fV~6*@2r z%$CY#y0j-1jOcqQq-SEgfHaaqo+1b*#nI+B@=JOIXiv&_BI)Vn%biJwMkL{)0~pqb&xp@oqe+ua>=rYWxrJ7{7_}e$D5MROWqzPr ziK6}FLyNY;xXnsdCT;&kFu8y7x&T*{>M|D1&IYSiOQ@~}+)F+IUg92}O6bGjieEps zba3pqKkflm3;NfwE0;`6c5vh5voADmu)WmSv69&2=S2i3>!E@{4sSgGWN(* z`UgLM_0>Oq_xHEX{_g3Mdp|rqerILH1lUebK3rZ|wxg!aUw!2&{OMcERskz1Y4z|q zSF@!Clu6dNwScwb18`IPtahsiU(&k@;vB31-pOVswYi;NePgHOC9#B9_M{8;7UT_- zyIvBWLtSd7`qJ}uXOIM>jwCrq zBuqI9OEfGwlkCE~oq-NMB&(JOI;R;ETM7J}_TvKhDEO76Kv$t|_V$8EB>E-cE~i6V z!P*r?bnT)muXxXj0}jX2>PV-PPK0K^N@L-$6~Ck(C6di#0{8~oC}LmPae<*Tt#mQd z8n)6`UJZ;&WXC9+94=O&3HK^d+{iFCEBa{;%TeNiuvi5Z!wKC~fC+7dTY?ne7VHf+ zv3lp{#>XAGQMjzVD-+!f7NCpsGviymrmy2On1Ai2IV&`86GFu5)%=uzk(9#fK+mv- zYy!vzmiDO*>CgNzb+~{!(FbTFZ>`17w-FS^W;N#NSzJNX%_GfLm^kBW> zXy?A;=kI)c|KQduznXq|1dUYvN>f?uRlDQFm_PHsEI(hc_FaGuIx8MF#ZD{J`TPYXdH~%*e z_{!B+Mr8R7G8d*re6Dcq_1C67sjxEgeOmCeB9j8~bzn#SIvZ9+8qly+=h*NsM1gM* z_0?|e7EEz>3&ZrM2}6PuJ)GFhC?jd+ZuXovo6pUv#%Hx^R*a340#Po3eIAkM!sD1d z>`+6Zq;YLmM-EP({eL#3fh*@tN6x=+>eOC6|EJ%WtbTS-KXvD`Mt1M+{Y&x&WrJ{C zD|xdwoH0o=xm0pS1{2erRYy@Mso;V)rnQ&6^FlDwEqNzczq0ki^4E$}nQ80!7jN8X zsBCrGiErNEGh7PW6Cf397B18LK%3h$S7!GOByXet_aSvOKR}5}~7~JH9V4wAHjd zSeDS+9+;HfTEPN=wcbNk1FCD9%kowCT2KX>7%Q5vr#n<5oWZoWCt?+CWNb8qLXVA( zMNs8K8CX!!xa2ncYJX_r0;D!>0Ixmee*+IIFh2tkeJZ>9#0s? z{>u$4KJU|gPIjf^pg5$=Nt03tl<7aSg(d7WKBP3eTAVVOgmMX)`!?ZBHWTS6*bP(Q z;dGM@waKqNpoQw%nUx4l@EmPzt+XDr3MR&dCNjV-%kIDVy0)LT4>KBr?U+khY{yni z48-{IbHGqgxj4o)j@)gb6@@KIZPXfGH9x1597sBCe(rCptV6lg9j98ndXs9 zN~A(i_tL1EG-(f&GO5xsB`;YuEz45=fPLqDKa-cJmIcN)nc(>R&i9>5DI*ju8U)gU z`pQR}H`9a#rocw@(;y_!UL#YACNpJ}GnA8Mf!A_ISfqD8lg!30XUYtN{wQX|Vg>*@ zi$F)z3xO4vQF4Hgi)3<+Dr5?tydbQY7@JYeX0GH|9f9c!e$k3FwjWbzhH|ia5ZAN0V$v{Od?AV4;Mwx&s znh!H2+Sj@nuSTOKxkFRX9c*t)g-`p4qOBtts}-dreb&b4+}1nVY}iFt@c4w!%(gU@ z&x7Q%gIX7ihG3s|6f%Ef(hRWlAwrrl9^<+cK8-OnzPFlfgqSnqQLTeJop*iXYuV2> zhDU1Kx8EWz4+#GL>)EsCPuZgcAMhu@-j`)@eCKLq>V%ToFlWk)gFbR(zwT(iAxR1G ziLhxC4pSFR?)=l`jDdx(9KuB11p_j|rb5XRbR&F{y$iu=7164}0uM;t9%vm(O(jF# z-IupcO{)1y%}3*EEIO?`7$fNm1KI@~#)_C(Sd(F>rtwvyIR-YrZ3KPrdo7jsL+O>p z`KWttyE0u1rPppcckc8VBcbiKvG+o0Q-Ve352LHn{s*AAd2|2Ew!f6w(3@XUh-J3L zH9!}xUP@^$G%Jf3`OGEkQeLZc<#hYb?#9O4^7@^X4mJxzL<~|c&v5PG<42E(vw!?r zAod&p_$#tp;kl0=|Mh@i?3Y{#e{p#B)xUqWKc1Gm?fpV-+)af>RyOagX`@15I8UE1 zeN`bssPcANit~YCzrsJNj{?}@Y6FDOWSEyiAjQOAwlSprS|vfQzJ$1s-a!61Ou+TI z{N3fboZzXYt(mzmtn$^ddp!tUm~1W8mB=%(br{jf6sj!H$8s{kRET44}@P z&^Qk*^x+dmKotY!1yWoVAa$zO2(`cqm{)T`E%&r{bN1Ygo?x^xAZF5a3uDoVxFfV37B5RTcZ&cHt4UW@z#KX zPYAFeH8su-^dD&h18hZ1pG5vfv)f^F2)JTdj5Z{yq1`#2p?bE#h$O7nmO~DQn>%2P zpKYF?4XPF7^PvI>7n@3+9F!~3sv$t!gdk{e+!8XcO3`Y@C}j|0FEA_TAlWV!#aIu= z3Pu#$%a7!mq%gW<%rKId0km?8QI7=x#vYjaV3Zq_v-mmgy$MBh7FEDmXpT{iq~MvI zug6S+1Czp%^v3t&IOLjTGl()?Zy=0=8Dr54q@80Rmg=y~d+27EiIa0!G&7bG4T$qz z?Fz>HIg3OrJP>3UR9J(#1ewRk=e=WctgwD3tjgyu&3o>ez@}9lNUdFGCbR>IBIyZc zV`!x>VH$}SBXdb_G?^@yIl{+4A<6z)^eG#KBv$jnfjvK3ydXe}#)dBcIw~%LNx>Au zHfl?UsdpBpdU`u1kdkw|8ybeXd+ts8nErvu@LRRr?VZh)htyK!grh*T9i3s z%#2aBvOg?rQAmu~EEt+_`~WDP9Mr5y-z0U=+%Gc@dVJ%?)qx|$MBG)o+kN&>xfkZ8 zBTt_{ezM)5bi~DQJr0@y zTF2K7DD|VPI6{7^r{M8a<-HEiyP$3rhnP8t{R_cT5^wvU0Ccmb$p{JquDyd+Bh_4u zlL6C%G){Z7;B1&TkoIaR;eZlk`i}<2!wAm$b_RT@r81RH@4oWt$&=PC_r>3=rFMVt z!PeCeR@Xu`SMWXVgj4=&9TYxOKb6v`3$_Dk;{cdsM@loHX}E>;w%6<{VpLX#ZkS=} z$)h>g@Ar3@r3--d$F8V%{T4cGC}@Jbpwt{m-w!egFIJx!J$$ zVa@yG;e)AbQ$jem4xc~&+LpYe2Z7D?+}6m0hyVEJ<8Su9-rJLh{aaxBcV9l)?SAFt zn~vM?2k|xc2KEQvOI!pi)BSy5Nyo`7I%2dHR{HS&001BWNklHd6*b6kFIpVvLiRIKB&ESw+v{^~8-w+o*yTDb_&_bn2Pw{gp@Rm>BBNs_k`OQkF!x0IKab2ZNZ)Rv_2n<+&v}XoXH^MWz7chbr zzB?3QViveBQ?u9>%mU!{1>|Vi7dT=D_6mZwVEo(;2XH3>p23Iv>=a~mE>N9?3!NAw z3;!KL-!Hq6nEVX$u$>W<3-J4Px7-p;cD2Ye3p_GrLrCw@Zh)vjudCe!q(xi@+I)|> z?CnC67f75L>cOxM;4;-#M^TC-L|JaX(c;278L7|5g!0;t9TM(43bT?B;n6FjR}M5- zR=M>>M4J2&8yi1EA9N8*{$@b$w8a8k1to5ThMxOgXskeTZMG&<4+dD&E9y-4OTV>lQA zU7uH*#SQbqgt6$w#+N{z9n)GQs-g+a6kk#3HO7f^oQ7l}&yZb#BWL1hBaEp%7#6AJ z+9YGHnB3etp&p-Bwj*?@Tc~T&42xz`7V&pN1FAqqSF+H8XKu;)xKb(@8BeYnw7DadGmNif zz{X}220!^PV`*@E7dLh|f2KBTTq7^pKd4F4+6O#gCUvxG)dEFX@E7@@xx#&!y`gJl z%$LKt1x9(LI7k5?`6ZV<=XJ0@3^Dn-6Bn&ppB%YvE!)hqP{^wLJ^TjgqmnbaFOp zL_eo6f@UE@jUcQiu|k0pXw0H>_5`niVBTsH3rn7777}CVR5QHRs@G4EGs1YO0>7-3t$T=EOLxYG*mXi z@w50_`HKQzbVSfe=<|KSZKOW#35)WIV56@vqTZyhuO$wfqv{K%z(wovV(-`OaLuc> zN}TYjk|dx>U39)EB*d(l9IPP0SR%`SQNs2@a2-LnS3^l5>K4TEI#@c0M3$J~85gI| zpkHD73@S8o&ti=c!*b!OX9inG!3BBvQd@V$;U18?GBJ(T%mr*A!AyuLLkc>s$xp5s z6Jx%(Wm-G(>bM>^7R|-9-fTjE7tMHDU$lU##9ESWVCy$sO79rfP7|Kj+SwuTN~G1| z5wGZ5LsjmIu8AYg>$ICXIm}!}0*nKd3=MYrHj4GP85~72INGbf>OmuK52N!ZglILN z&e!X9HVc3bs<~Zph_?XavXL&SOUPx(`vDrWjyr%n+X$QZ`)P#hAXwuAZKPL8!kU;+ zlVw)(PN+?zZpC(1D?j|hM41>3pqNR1#y-#<+_Y&m<)LnU%mOGyXoJ@E-wcBO2XC(f# zcX>v>lbXZZa zsxDYeGER_3R3jnwX64%B>_KdAzm+(X{8{-??S%?s{iQ9y|Nb*hnMcasJA(cM9{7i= z%eU>lB9(GhHNbD}0iQ&l->d?k{8GA|*m~*l7+Mu3*wo^PUB%_A8kD;lxuL9L#3Prh zI0QBpEV;*tYcmK$csw4q1wOLz$Z~WACdldYw zD9!K5SuY&$-EVI1JwKd;1>HQ@T3tSv9P3Z4ysM6R6JwLX_fP$}et1`0@~zn$v%mRh z<{a zNA$Uai%5RwJm$|+JPqzF6gn|~?qKIa!SAHn$}>+ff#&|NTzOK%(XcaB7#w6eiy$lj zp8ZTagT&#)Ca~&98qC(X_lu=pamw(#gV1W?HnMD75J#L6Va|d}DFR$e#WJZ_Dh6d8 ztciH$eA$>PMnVk|^f&fZM#PjctQay{;A-H7klzeKSHN?GTN@#H)u-WDt_x?u;m=@k z!+1Ufq7_(_BJVf?2B@RuV;vz(a9C7yDT3ABR$o^R;VT>lhkZ+U5aXs=V($ zf-1W}ueLIfKI~ll01nEm^On9jW`MdS_nIPKq8nCLyI^x+t@^k&2@3dal`T$M%B~|90+?1 zv${ZjZq-^B(KX<0(V1l6^cS`l)Mu;22BaMfqT>c0#&P%y_9U~=+-}t^y(v0ufJLc; zKUpd@(l`N5H``lCB}lEVgFq>2i7F(u3p8$bA#p1=Z#N0HI~ekBqRqAnk5fpC_GOkK zwO^M%sSoB%6Gf)45E4_NF!_j#BF=!jd8j+U z?OzrKPPC&|Bb+${f}yk-o|B?XL?sr1ju26^EXx#!_RiLr$V>Fjy~js~`!9CuY?{&y zbFr!2-R~9W$-dxwMT{QMkRdlxKR>uw=~kFZ5%-~0blc9zx7p<#+^?{20Z#XPy$T^> zTHcW@B?h{?)nd_})-#yfkh{>#JF&vNLvJo`?;nDWIeM{IRJsE9+pcVYF~+YE#jB(X zX6GSDSkLc2y}x{17=nWLr(OZ5T&}zk;0oot@^%XPlmGhf=~aL@E)FZghK<~q=I@I( zfYM$AR#a$4uZEKfNXgh1+mK$Go&`^JL8R3SAl5pVsX+}0Re;;TVGWY=7U%ArDgOdY z`G;W1!^Pd3?ZRXDUqz%WS8M#Gai^+?&62y?7YBbp3eyiu?BHakzAc%tl6-m`EbIf=>96k}yu0hvrcDyJjyg zv5ldhNU1Rnn1_@wWBn(=Bomn%QLY{n*cg2r5dof^r3zm;z`OnH8}s}7Z@>NSyFZ?~ zG5hh+aYOU(j;`G~ZvEoj)2FWnkD_N+!~ws5EV8(E{=)2yTRq1gx21gc^Syl$;Gg{I zck=kR|N8qs{>HW<`F&2AS2Po%9I1beMt+Xd=piJp=Z4NH8AYMt90FKFSo)REdx%5# zes$vkqpKicq+G)&^Yex%<0M($3L|L3dr>+F6?RZx38r*7{a?H19b5xs1pcPJRKKEc75PEsE?c zpa&T0j2>Wr&B-360-KSX9pFIVKDg5K6DTw{Y+TLk|_2mAfI^yHP7k=CmVp> zD03zQ8h360O|pt%zAeS>px?zS4ss}6LAU08sv#IXgFRud8{iF)CSBxXY4EtP!Kw?` zL-)%)Bh3|Gs46?W?&A0vlDt4#0Z)K&JRIaW8kObi!IHR$2OK{ydUnu_WR}czR3XVv zHIa={9EZSYLBjT`=&>Pk8;_&#NCfvm6#*?wp0QYyZs;YjCe!03qtpa|vS}fMrRxn6 zDDx$bdG$OdzUguDo0am_^E9t&Nmt43LlwcY)6hk=9c&xjdb=3uq%w&kX%)OGs+Hh8 zC(LTISRpya?W1D3TB?`o`5m?PgbzU%Po6F|@_G|*1%@W3M_gHJ6VR{%T~x&O_mBnB2+%)D__kkICOK#q3rWK3ut3QI*0N9#5}WBFzuv3%y`@ z-#diR;=r|gbKFqbb8Fq>zJD}bp%8X6F?9?sHyW>k!CL(snvyVK?%g#BI|C*>*x7Rg z#&mfA^W#IqHG|;1*NfR%EFAdo+6ULKUB9s83wO>mR=1uX96URJIhq_fqiPqJq-JSD zcbi&SK^Cjm3cjdz?rm(2?ClRf${v)tYWzlklSFouHv_kB{SOk>*777X%?d6#J#DWU z+159iB=$;WuPe`USdOt?btpfwy`x6i0vc>(=uQgp(tR=nmF@_QmAx?$XIZAMKu8P@X)F-;H#(3p1Up(yno~1%K5*) z_~O;8ZxsA~^XZXO@86i2n0Rx?+%a>y@ZRC47fuslI}(o$F72O~II@F$%z=-mC#Gw= zNB9)5{3lPJofLHbg?#Gizy2Gt=&vGbDcuY0vKpOZd<^%|B=@$H2k1gRz-~bmXc;jo zg7J5soSciWWmpal^|Rz@r61QB+**@ZtBS%E`6T(02O`fO7OM{Jft**pEH2VCs-D%Y z8#>oI(>5$7ufzMmWaebrgqRL^j2vdun#Jp8?j#ehg!Vq*S=t1xvlU8c=$_qmD|FLx zY|Lb~;yH@6yaLq%uE@X?BsFml45<|d+#Eb34cZHt6_&wxmV#$wLR&M4#-dEi+LtKw z0eBOIw16?9v9JNA%8DgOUJzuih5H17t$9J`%o^A*97iC$lwhIvs4pEwD{zKVXhd&J zr8D;+f6ipkvyhJVr9&CvzUkKARQXXldJmx->8K04-Dn8IXOuEf?<|M&t`^46X*;s9 za1;tGNTa(E(h)*M1Cli`Yo-7zDu_z&uglkM4~Oi+gYyEXkY9L$Lm`@hDaR6AhCIuDEDQw}#@L8`J{AJ$6)cC_$Zp5J*Vp60GhqgJ*x7^R zS`53wJs*dCo=}gkgLCGwI;YJvjgO6)nTm$TP(N#09hDt|!G3UG3%IXl77|>Qm#}~0 z&V@2au-`c=JmHQ%R@1?EV|ua{s6jLu5NrsbB}s@{6@sgzjkGt}(7}1jv6LJuK^de2 zm`gfakO0Q$VL&W2TuID&63UwjRu)PXq;O#RoSMalC?3KS+_a`(`mLzWd%|xqMHN(~ z?dmPIVfXdnb338(wvjto+(YJ|Qc>@{=6G{nxsT)?xGc=O$%SvFsRB7F)I10A`&UrL z)J!#TQv~v2I*oFsN@;$c!PU2(Tx6`|8Nw|a7E}|VBE@IUD87p#q(cm@!aW%AA(c=0 zBv^VJoJ}soblrA#qcgtGkZ~P46ko=_YWXn+s^$~xo$MYGoc+AAzz~$#WW(uxdwmdJ zb7Y??5ngSUVH<16w^o35ga+l2k#D&PJ_PdOAL;N{vPh zvoEtZ+PTl9xU?gUUd$l?<)Q*z_BX(xgh$!`3*z|x2->yLJ9K{IK* zxOSJ{@~#eVxGDp~laoWgYBw3&1!X&;8;@);2gE5aDHVOjUO}j(GD#(ID zY7`ovi-_Gqg3YUEuTD&7HV1T}vo}-c|MB9FfB0bfgWtRo)cp3v^%(8tzPv*<*T260C%cr4 zF|pD0B!5VvsPT8{$92XvW_Ycrwk3e`wf;Fdc9ae({0qQ6JP8WSz^+LYHVyTEwW1QC z1*AWbkK|h9`K>0@t8)6(7`tHt0TzDiz);cQMduBJB`t9DQiG#uh>i9#+8ICBP(8_VA@lky$aZ=eo|!)PQwWBTmSxD&Ri zP9)|}%8igJ>j+w9j!*pLs6zQMiqaD_~`(rjmRR8sAnN^olB2j)1NYN{q;Iatkr zsq=gg7AUzeK=p!v@xnagI*Q1i-JZ%ipg48)&+g^K+WmbG;4F1Sj`CN>{A;q-{8n$ zsHww`)@eE2teFr{+b5UM7$RM{u-Ta%VL(=nQ6GqmX7ClISpv!N&GFpNm*<{m-Z}Ot z*J*p6gHF0D{$IF|Ai^>X#gD?@XTYkFVgId-fzEakC7JGcyX46DAU-%~lr>NT{nNOS zgtfOI&i3AhECFQ;F}_g)aQxPA17UO{S!*=>upPxv!5L#TdLSm3o@FQ>f?MN81ZCC; zpzKm}XeEZu8rYmQ+6QqkE|`m7BdQZvj&6E>ppLNPl5gp7Omb$p1u+!#7st_fj|51AD-SV7gO605pRp%CumXsS zV6iMON3?YRqc;RQ-G?L31U+ZAzy0F(Y9;)q|GfNq>12C7eD%U+SY8(0yaWC_J&mdL ziO)AWFoK3Sd-a{^i5WjI_v)qH01!a$zs+;_id*va@afl=BZi&n<;%NmA+ws14A;-9C`%OL+d``}L!v;|>?4++j+6auFU z>BPM$tak;O5rdV_^DSe}jGq`A3;NoH=cYq~s8Q;#gcm~!9l8%} z_SygJ3sJBIdoM&-4A7z^no(Gx`*izu-)Gk#fEobZQoV&V0Q>0wWf#&SY)Hqj0uC+G z80-<$B^|ym^!S(nF^YjZ9GH339d)+~+;HGdkeDTe@@|2UUJapHLkLAQ@}B|08lAvu zK>a{7$z!a8ZLDSh_w@sXZ5F46k}Mk*ehA1yCYBSEMpVFPa^k@Wh`E!o0AwgaYW>2Q zVl^fPDa)iBM;#LS7|koP~nuH~n#JB`Nng<_j{Fpe!S#ytGGu`eE5alkRQ z@zfpBq(h)WL1ah)*G)`CG^U9XX(Tq0keG}uQ51zrNMXUM3x)(K86_c7HtlLw-E^6* zs;H_aQab$u<~!$i$z-IcRcgbvO)xk<_k7=ZAZALKZi&GchG8Iuc~n&qVF%2ls`3i- zQzrZ>=Gz=K)z8hk399v@3PSW7nPRJ~>ToCv>oo__O6&||HW;%4c0$>JY zP3-uDN#Bn7YM~a-^+#Q1doWOZc+>|8)-rw{u8!ddf-N!beTbpHUP4cm$L;J*DJu}$ zkGj)OI&VfRAYI5%#Ku?*)~6_2woLYQ?V0329Bp@8X7>mw5FJuW#=|_9{dGs%CWc1P-VIq-iyA=A;>5 zOUz9%m{NU)CGo`J#qlfemO;y*6EmHAlf~Yhndtd&;d8HZr}KJq*7szb7Y78 zM{4b9HX0O^`M01Zw*zKK)&N7BS(Dk^aR2}y07*naRM`;506J0R5|yKBVTmUZrvYy- z4=xnLCYpsQJuVh^g}g3RCX2UD2mt>ZkyZ+F&mBG(fj)Xp0q_(5mH8_}2QwH{Ukd&~ zZaH!5)?er6KX_DV6vEs1BKCv#ae4BpCU>>%zt698!*iZ8<}Y8uJNyEhUNCt?NmAXN z0GUrT8e9oCm=MxPnA$RwKr{j$s&aID*}=%L)+{ zgjTLLv;iYv3o>a?TpL7KZUK3$ZQ7{45_$_vMir78Ia@7L-)eFB3$4O|x8j<+qPgQ0 zw{YPclPI-Hw5_7WT~Up8U}3p#;kNOd1q)*gpDS^&layh9A2%wV~T zzF%y7Gn8C0J!>!tto7ePxdMVFp>xJ+SI`w-1bo=P>UXj=${PuC!d(5T3W;VVv@IaCl8?U&DvVGp zghtCn|6Qzm1)F<1<+j$I`!_pAIy>M&0+KuXdycUQT3!-z;sqyKm0JpnDnWu2x&``q zSdXk`Ed#g0SZE-MlD;Gul$ef%JS^~CRupmz%qu&Z3fU7Z=<7fyq1Um2212_~W7sYr z&B7nM?r70l?DD20SiGTo9}8IPrO;!!T$HygL0%*=!44Cv#dM#JG|E^A?Sv(Kro-mD zyd0~+b0na<5d-fn<@Hz@*8;l&y!jH6j!V}BRP$6{2|#D_21BrXkYf4rhS^8x^AYgi z{=rq*;BuCdC-q@Hn|*t}Z0>@aZw;l*n`sXQu$mPNS(7@G;*#;IFlhDJD1ewP#0s0K z&+;+31Kos7$TGN}9%UV&kD_R@V&mRk1Sym-AyExYDfE~cL1V}a>Wfjd8c*ZD=Y3f7 z_OTzSJ+dZ0hh;fi$uD|rA0K{#$_05qS{|@j$0^OCoCC!|(a!LhF@@aI`$*2J=~!}l z{912BnTsj*N_RKbLtlp$h4;ye!*w`uRzPyIsmnQ&ow@*9@?olv6-g9pcdeljizQng zR%f9c6SF#tyf(Eh`L`_qJe2G>x7pR6Rxy>ZPr;uv)@~Lbjgc!NjjP=Zg(e!KcX+Jp z6%hEBSJP?5CwE(y-lD)a-f|+HSYP|XT<-p_;1_@#Iiq5*lnzU-Qe8(&;4_>-AJrj6 zB9l#wacU3{3i*{+DY_W!p^XsgM(jEZ8RW-S^LS=wVNa3^k2kak8HBv9AAUNm(w?~h zM&2{&Zt4hr%?c#5qd}!ZlNhI%9}S&W>gk_<(+AwYBgnb-v12%#xN7e>a9!HhZyxMc z{(oUDam33ieWYeLYW1OPGD-Q zI+57_1s7&{}LU*J`M+REq+f~^3w>nkg0vR17|<%(&Oa`zlkqcyZQAgF_x9E^jm zMB#7}qPzv*1qaqFnpLoNt6~vE2JA9_17qo^7PV|?2(^j}&mBT0rLbIxpySCn-A9$7 zjIiM-nXlk#1#V!}0p|p2D;cocq}=mPGKkqTF|wgMxD1M}vL3g!T&-bXcIFhe{=Qb!QT+nRA^Aa)j*9&BZCQV@}pK}JCXwlS7= zu68n%V~_)C=UxBmDkWCJa?$bYmkazAKxiy`TUmJ23Oq)1v@-~$l@nQ&{eq?=5ODcB zM|iBq&uMdK&xjnqInwGx6bC}0M_O49j79KB|1s$6$-wVHjAJx zR=`$=13slThZPLi0i%*t7;l?dJ;?V=R3Nd0VRn}61rXfA0$@R22L{ic7E~a$;2j4Y zc9#ck__OqL6CQ7Nc9!E_s*z0-FdakGWR0CgA8=OAQy`s+*=--~o?&j)bK>>`1NLh9k%bmx{=wb| zAJg59D9U_^PGE1S({p)ZjCH_$v>d0WpT!_F!f)AOS^GqwwrdY5q!_$zw0Ps$06K;F zzrf_D>zt3sE6$EB2GsRnz&4v(t0F!R`>13x*pa!~#d1R>iblCGB-ClvC{0f@?1Qxq ztV?1;;k2p^?)vWa>({SRyjc!x_m3})FTG2MB>+5$fXNF-(Ha-bIzpv=j+hAi|NbM> zuM|<&T_^87j$xe}6W%M&3x$L5)5%M@R*QMD_N5yhE<2TiH4A)>L4N498+&IsaGpq^ zk%3Yy7935a#>@@|90DzdHcMbPLTeI(IFL}u>Ggx-zX8C%n`zxYIUoQW4;Ko<%d1cJ z)*k4UM^|rke003OK0LrhZMe6foUsdq!a~CYAxv_6=}!_Y{S3*`R3I_-nTT9Kf$(Xi z*jk__ii+oaPe1+opUuM60SL1K;e%$=gB%Xq6myKgaRh;<5N|Y9odWA|)9DMPE6V6Fhg69S zNCIXRVb$fZ2$*VwVlINQ55_+Qxv5&65-O}!(Golbt}EEv=C0b>;PG|4EZ;(VMd_8$ zSh<6IY;mCpN!YQq%6%}0&N-W#+ADWO)dNGJh3w~VD!FL90+X+%ZT*+8v-xfMzTR@;M5C&$ zgcLNP9yl3C9*v9YQ`}27}tgDs5 z_-w^48Q~?BvVt(n@YjfLUK`)O3=UtipBYM*@-!bAB~3wti>g7Y*u~F^?`hJUFR7xi z2ZVTf;I-u7N`(LjcMjPWLXakK5El9qQijoY20j8ZU&-Y|4-BCyIe z^@}ar+B^7R5<$DnMmS5thB0I0Sd=g@dR{P$#sFMn3_aUqsi|m=Yg<`6!GLs)h-eJB zhQ?bYMsL;@s&-SNdJPZmY_&^VRp9&Id){6e^dm*qqiSF$#Zuu>F9b_7Y6V2kN^_-d zB&U4V09raLDX`Ujw7H;SCRH&d2;^dT4(t{d6kKV*xo!8@Cy0Y$U;CIIbP>>ozKh*e z@W`h`bSyrMzFHiScZYQ4dD1fu?>7rVQ+uR6$M;sI7e93+gNw^|iPz4_6_$;L8V0n6 z$_Bu@c4vE#akH+yvOhC5sOAN&XAS)Js`gCCd}ePQdj^Jgx3l)-+ELc(svY26l_Pmz z+J!-nZ6cWV#q7PtUOPm;c$G-rqQ8_)73z+3>c#cOlna#}Ty|YbK<-F4q(iO3uJTB^ z(9%T@y29Y;<;l-KS6<}^_vmFo|L+#~2j{MwS(%)h>*24HRrS&+d$CxLOuv(pkC}s= za_gD;MSJ~rVjW(%c1*}N*dEn*Y%LcYmkEGIhB%#?F_-Yh)lgx3DB}wszwW%gDppYU zkrP8pceOOlpxI6bd;Np+Q+EAiw<5`1XLHMs9DE_Ro$rj-1=Sdg#c( zJG++~d)KSit{kEMXy&BKeH9tWM0V`pu$wiDG#;+I_34C&u!1U7aO7%&>JwdS(uE0F z=1Fx9qjYLu6s9g%>*8Us^Nr`;V%q%MuRrA3#xgMUAGAa#|iL+lRL4=bVLf-53Eo;oJw=q7Cz3cKrhFv`&+O1!>E=K$5 zjPd^S%Wv%C+rRJex3LnwcYf0w4lC1{*D;es^7X^5mR&?lMR-OFtrUhNZFW6MaVDLa zjs~G}K&`)+dinD9{Yap4AWRHL05Z&4xD^RRx&vtY>+E++OWle`W9vTXE+NqeumYp6 z3PW`(+#X>|9Imv%VPc=j*|0MP)piYhIHP&AhafCvJeMMQ1kV|)!hNMYWLRz^8G!Kt z8~aU{D-51XDe8eM>!tE~rVk*dp5ZgQju?(qQ6ZI?wD!Mcp=~)+5&>pCjOCa0ul-+N z#}tf%C`m~}F=?C_8?bV(O6m8CNnjdDbP>;y(@d8!7ZHJF_kq3cB%?`AQ&GG~^ezyT z)lVk_{5VM*)(%+wnmO#lauBy7IWl#t>my$Gy=a{l_d{@*xv)!Ns`R52#ckvyQG5WR!3 zj*)>78t5DjVBU$=;tZ(Q41jU|#^d(3g=R-eXbEl&af9RA%^b5#Sp7EFavN~B zjcj(iQ0vs7w;PaK0}VPEYRzrK=UOmv8ygZ!U}RPbgJzyv1J)ANL}43*Gj@5cmUu_w zU2d%=lnA+L6jX-Xi*oP^`Zgby0J|LM$D*HIICKw^dmOhrhwhD=mA~P-8e}b2d&6vX zO9@=vdZbP0c4BL*syYZEGY(*NMQ9~0e-d)&{ToX_D%IiyzYQ;|vVlSH8ZQ{}%kA=K}%=O8E`gx|z9m=15zRJxh`JhJR-yIx$ zVV0NZjf(zLj*Yd6%?dB6oq zD+qdd-hC**qc|M z*)+(FWof?-cCt#E3?ks zCSEw<=xyEA^s`Ab9L@v~z`jOf1l?5$^w;|T?h4D0Y=c*afCX)v4_JE?ns$0q^og9k~_I(V3=^n-7|wvTVV{PtfbPD%)V z=+^$lU`X<*FmBFJ%a~1Dlf_o3O%Ak29-~m8jU6d`9}9{xpn#_m@z7ut3E@2=i4gGZ z`|v=Z<*C?L^m(O)Zo2?Oq+AgX0%%N2o(~Ox|JsM=H=x?W55g1_wj)GmX&R0H7r7M$ z3pj%ND)Iwopu!m-HMP64jyEbYAo~FGo_w?our0^MrGJR@5N6C|i<H4BKzFelXx8 zDO${z9ITL2VKFKUA-Up{Oe{73hFl^gGOU;u!jK>z`(I|wF{CDOC~j<(aI3YT&j>Nx z*FZRHSFZ)_KI0uIaMlIs2D7&T;vnMZ+s(M7S2-5Jxf-yXu-j_eolX`~o6V7awZYW6 z*-X?nxWod}C~%@l1yZh%omDN8LG2d6wPEB})}sRHj%h26 z#xWSm0z2d$ zx^?;L-CH+r?C$SxR)eunEZkcEAd^X_`(Hl)`tpcMeFwTKtik2^0hd!rE~Q;EI7S}L zS=A-Yb4FQ}aw|<6eA(4|qu=2Je#-!OLZOq7Cd`CT&OIiy>SbiDtaRabZsjqlmfd#d zVivJ~Fdn?LYT#-IlWWa*EK9sw?zW~qOnt`fCOPfwNAJW8eMxp3k7cj_e7;+6G`}=C z?+TEl!cxd2qUo4)TbK0Da8V;aRyZKY0d5Yw zEiJ0ZhDMxvC2T1QP1Wo$Uyvdp8cS(}2vQ|DL>!nD(IA1ukBVKoe_@A7JM3P>f&Kw| zzn+hi?obs-f@AxOZ3REy=lyT;Y3QAc7r(e}_gFb|@xuA1tcsI-ivOurJ-KKM z_`!wVPB)OX)CynQ@;BybrK7NRcJ$8SEOj!BV|im>`SfI7UviGrTz z!iGIO!ZjC^c5M&p6Ia_bsk#Owb__eE)%cN5$E(NQ8?J6`O>XV%+`V?^+797ajMrbk zd<6i%Gyq1{H95%+*ci%fgWI#%kj@6!2a`uh!)w4Z5b)7`6To>CV6p2B(4ExhH56{i zpM*1oG>sMuK`@u-Nv{_)C2NvpE`>;5&8GW=&n?%3L<>Whku-50n1D%nUi6+l1nC8F z4X-DR)+&mll~yMMP^`o&X3OL{A1eJ5u@%u+=|kKmObsxsc9ASfcEX0OBy<$gD)`Np za3H0TI_C@NX=t$K&h~#6@CCB-N$QmHBw>{lO35&qB0`sbl|YuI2+FhyfQiF`2H%`k z{7T z17&8?@x+>+;y}aPHe8s9EPq#N#XLGPlptI~8{$ZR#MK|!J%ugYYnjszC{A`jA3+tKV`s?$l44xq`>W#0>bTNs^xV{3W|VxyOA6eF7)`k z_>Ksm^!n^1&S|Xh3zNoS+}P`jqJajBeS%ypNtl0$iDuKqTZ@t4=zQ;h zsk$0i@79$8og*e17x3zh206#E*o_PdEW=m>X#-^Axs)RnW%Z?k!7$jkF1-xMkkL1} zB<9tX{Va~6_^h13@*H)3bozENxYNbiGGz@el(MYK;H&%oUza28QYXoybU5sag9Y+k zu+NDccR+kr#4B)KY8qnPf?2c?V>^pzD3uZb?sg2y{X5&8LXUJ)I7So!Z6Gy^QrY!2 zxLzb01OKsSuZ6u(nM{3oDegaZ6!n!svmK04GnG?yqj1q*?T(#0E$Q;qu}-Fv-6Rqv znDV{({M0!$8xkHV%hSkL*O%){QNl-ixBH&&tYkK`^`#V>2v2s4N8q9*RfV)uNl7T* z>+K6qf4DPf|AYa`;EC#|TU&e2o_@P~?RuwNiB3G614|F9qQPZGyAnc`5%NsV$q_8m zj?`9fyK(f~l*Z4Xu|WFkdzXL82W)?P>(2UTM^EkRpiiCpk=J&I&&q}#Jo?e8{VSCc zt!1%%Nk_F3#gzsbnG#~o2aM2Z5%GT zcm9I2`d;|*<-h;?{QN;OwBG>ujcZ4S1;8IXHHf{mZJ#a|J{zmOCrQ?-QR6GmNRr(8 z{E{(XoJa3GtQ~t{09-;<{g)5yXlJ&!HvVM~%vJr4Ig5}>xOV3n(m``2wTZ5$u;v!S zYCp2$FJSpKHvh1bS$X*E+Sfa=JIAiAuebB*-{<~Ztu1^!w($Pz?_b%k?_d7#`aOG5 zKG~>NA9l*VFsO?cDZtoR=3cgaxQmFvYPn1fLuI0`&U(VQdTBjE?5wdQ79w&rq>ola zblC2C8$1rb5R|sIF#t1T_J+d&`_RD1kd*yz3t4o@>wHESf*CifnW0ot7IfGZ6PD;Y zI#dczAc8gqF6otFY+pE?4jTzh6N9C=jZ)!I;ZS2QHM;L?O-&*-oU zils!BRWLAJoW?So5W0RxG17El8dN5sva7supslU1i@2Ir=tf+bl!dPLYPy|t30MZH zd=Ee^7})0H#)}Ow4Tba07TgZ0%gE@iow2+2-*(bCY8wGpC{7?pA`-eq(*oVU#%$wl z97zCg(jWgureGvf2C40ce~oC$i2vRYBzQ7RX`#v&eyf<_n)wJmcv!7Ci6MFq)7`-vE&tAhJS}J4jzadnIpt8=9}Gyc|1MV)Z9xu40|ziPICh^b4!eo7 z3grx$SDXi_SnhP2jrNNe4tBrggAH)E9JqWicy?D8JH_IDP*#T#vr|b6#+9K39lokD z^VO9c6dXww3h0JQ&bq1=q_UkPNYK?#t%IF06dN6UzzUk2ot;&}GnvrRLc?<5tP*97 z?3WOt)0%RrSO%xhbD7o3Y7BkblUoDh6!}hRY&|k~J(i7aGEEK!qaQpRJcp&oj&^dT za-+^NKAWlsez!9RSWh`wml8aT^U`~}lrlO{SYJ0x3O4b0&-e5_7Qdd7NLv*~PtgL~ zkA(ejEsp--BrFx9?_o6n8gDeS$CO}a82qF%QDe;Y`Kazd7W97N)l|0!NzdT) z+-cYOdmKL8jevHk&@LtG_*_@DHFx^i&x)|FBpw`dgjZ=*nmKD!JSLvo?Kcvj)=(@j zC=H7g4pc^y)lFQlEdT%@07*naR1;$cu0UEuq~B&mP)a*$9JN-fD=kJ zzA{odhZI8ZN!O{cp%!3mscSG}v|~Zg_ueQNwjT@tY_7eXa4r4qD7*xC5 ztd`N)@NHR&ob0O4)BEBqYhGtbLU`3z!W-bVn-dRBOovOjBBX=J4!a6MjLis2z37?n zctKrAF79ATf7$FT62`HZcBO>VLSiLxXek_4E_B~SskEJ5G=AGx!eW$`Hy8~x`(W~) zOGbZjCE+lo$3+D~ZECrQIcxp4s^p z@}Y^FcB@3&wIeBrGAU(MUQ%d-SJ-V^w?|_YpN{+6?IhnJlOv%FEauFK>A1l!{vtB1 z68?5P`3;d-A%8L%fxbd`Lv0z3?5pA?ctMM0d!ArU|_yi zehU&8l#7KWILif6D|=HiPG(a+5eS5#sqFn`Ff~u40ZmAmfl4M?4{o|CbSjlm9}l_D zmCSP1$Z#fBU(OnjTfU!JU5+Uqx{`w%S4gC^3$aQpL+Njh8l;SU%`7)oiJ+uhce!Gy zTWQ4VN}I}&3Rx*Ox*5$B^18^#^2$NqU}wMksN7ux7rXfDzJ1k6t{k~73%-lp7Q)8L zK^~=(M63KrHNa&N?S`ztWxzMbQn-<`N2ybRhK_mRW5yuZ(BD^;!3V1NEhz;gV4 z=bZOE?|HthDctrv?9W^kUo#wzvTz?0=gO=Y_kPydyIs%DMD5{N)E`M$u?J6uhDhe- zDZ1OJzgyw$Ek9nd%d=qG-d@YaH`=cCloe4(ZBAr_6Ioi@<=)Q(&k}Y6R0#Ur35r8l zECHfTYR{=U?(IZ)DcD(1#C-PgbL1+5+_881($cFBD#w;hfFmR|TtA$)Q41n(u zOBivruN}qA98vHQ4lI^}kz*@$!!(;kh-LwwTDL_rV$yzP#HwZTHMW24@W=?NOH-NR zw>DzhN-G*~^GH!q3^k;+2J1P+tw|P?Fk)p|Qd`(AD|8u!-GfsS`X*?jJ^mkES0zIG&O>hz3qTD1b&7? z$)j2beiGD%)ZjfZ1dzfm+gqMobgF|b2CdloX$Zr*zBlQS6Aj{axn;3n0(NHZ1#QV&oczd zW5!}T*hJ&qxta7T-rhM=VWx+Ny+j9w7!mIZw3Tyd5Y2=~zR6NnJql z&|Ume@+!}J)Mg>C8b91YDtzaN)_B;7uIyNiy0-$%WcNElwCvDpTI#iLFX9G&p&*np zSvi}P2G4GPI6jRM#|!T9I3sIuLJ(kAv8ubQRHR<%E6%9TT+Mq<3=VJkcA(R1SCj2K z@W6imIPLrRT=i(YQXY_QyGoaKJ<%7jnD6CBrzYH3xpN=4o5s8y(R}iqMdO~TsCe1Qo4PQHXvZq(<4$j}6`auQ! zJs9P)H%UVpZiWwP+Ivde4RJV{!{Dbn{1nx3++%mx|G#h8tFl6?X2oS#r*m^8c;$q` z%JB~btrh!?Fb4Y3>5H+LGQZ*nJzDNPe_R-jCKuX^{iVcp;lDCwmCFu+wWyM~EC>gi zz(47Ne&#o!k4xG$Dk)?@t2m?LWw?!^if-N3$}A8KJ!lF%>e2;|DM`2V6j9-EI_NhO z=_}us(iuvsE=ffq-5!F+kZb>%0^k1MpG;Z5ROaC2#Nine(#-bWtERm{t7@12{OHaO z3rby|0?f+a1aI}y&(4^vUVeGIezpnfcn<`}ChU!?heOwrY!>g@slWd8(cqP(rL*~M z+T^2n*rak3lV#bN(VdB(ZGT}KLg8(BXsa*D}8A%s{tL5jY^$p z=fW}d41}N9$8E&#l$%5(({2;l1$xtXnim3A+xn1g8jpU;WHqX3S>L0V?bklB6n$Cq z;3Ch*eFglg$W5gm*-={1En%P11&g9%WpF@einTB_tcbSd4BrHl^`!BNW4~ml(2>38waV+32 z+Jg52?a_djg`|eFuT=pJ+z!O-OMCkhD&$}=>W3K(2aBEH&5J>qpM$NN>O#9>n60E( zt~CmGZ}Z|s`v8h|RC9zgR7K<4G->XLW^t{^MG6wjKAX}PTg8CxSgB^K9ANC5hPVM< zaweCZS%pfB7!VMj{YV6?_urqJc{iS$dzXfDHvUm=Y-W|E;4u;zpl{5PRY(9sLHEEr z#tS&G>SJs3@wy51+S;^YfN2BI7rYGL!nE>y>(gj&p;7-%gr^%%$sCQQ{khqJZq(Je zZcH}^#LbWf&MCN9hJs6D5N48%-};*B<+%79vPwh6qVOG41d_=ybKq(H+>L`_Z>Z~F zlmo(SbmB;+E6vU=hs2)bh&a!vAf<9|d2ePWZZBkZZgnnqv@vvipjVs1cFLWCU9aTq zg{x+x%fH+nR+()=`;fI^jS12nN&kywnX8>nLW;Ip^x;Q1*BLqFa&w<3(b+D$S`HU+ zhz&UBvaSXechk!6s0Q18k)!_6VR(_64?~$mgDI5D%0bc|QEzzw9%b($)vzN|dr5^o z(_Q(U6BE4yCtiQ^{MCQI`PVmJc_U)0-rIg`4GAHB_69C!mvS`hR(pTm z^X94VldyU`K(up44|@lkGn%Iizf;fURyM1foAjSM?DfgUOo3ObRTplZmOm?I7n^i= z7^K)6o)L__rPI~1gHx{FWeAM)BDjlAjL$nMX3>ZS^e`%YygaOshB9eLcESWaj>Drr zVZu6cJ+TXT;)M@N;y9OPUr>rKW8WdI!n%2FzsQpnSM74wtsEh){ZI3NshO3UGC*Fq-S8-vE*vrgj_fBdH{%wbYg}ubZTh#4oVMrH5A4sY4`#1L-n;z#>cN>K&xP)k z4%Uxe7_4s(xipB`6T)CBwD+x{p%We{)BVJdH7fmoCG|*YNXIHH^!7Vgmi@$)``um9 z@z(o|?A(pQbl}mg3&E+aebed^dj0Kxnl9**Jl+0^2aS415VDct2Iag82N=p~@mC=Y z?E3~utGgScHg?+_#iVvn`*vCeZm9r6cLm3j2on)Wh@?q&w|A#&r z*%7s;!=iYI_uLX5v9natf~$;x-k=T+ON?tD7V%gZvyz0}d8+&FI&^4?VyUY=Eg`S7Ni;sJP}|=iU=2>09xHpvz8qOz@CBCr zK)hWBgWm;k_=4cE{P&0hh6YF&FjX$G3~c|>d$yW}RmOTYi;>-u8ay3c40*VHzS z1$J#=Fc`Qt*Tg2V6(9!N*bP&YG$pXHWMqul8Bt71H<+vNgf=lDMUgF0Gz}zc_<`*q zlTb>cAdv=bd)V8a_L7H4t<);g*h3?A+1~e^^SjQ{sa+Jo#l8^RL_YU?-}&Qd#P-f^ zov}8e{8zV9ZN)^RMyj$Jxe}H$brpT(v7-GH2M((aUu4m$7vx6VjRakxzXbzBXDU{7 zdoB`L6zc0m7h$e|L_c{iKP*Cnwdj+#w8hBcVMO>Z2r)#@!ig7+bSYQLMM_5OF7Wy8 z-Pm#t%ikDUk%SH>lK^3q0}G^qMy8>-x`*sX;gx12)v}L3I`O)-B8Q)M%T($rg- z2%K8_Z!%WO^#7`wLgoHVnrmURrEp1g44OM)LT${nBykj-G%FC17%gZk|F$5p&u4mv zlhAGZP!J4h*0@|NRQ4cGP7r7@+r1bx%Lo%D6J{kZw!@6zxTvZboD^(1gYjBAhwGHI zyr9OrYjc28miq>s`|>K4jAGI5o$;PJajPw>`j!$$>0B}5i^wm=?rG7Y6Y|3^659Rb z&caVGtowAd6+%0Q$VEh|c(!WOxEvtzDn9FX&aKOx5a~G@ETeCydL{tmyq0h>;hFj> z%$=P~*GMpJgG%S=M1q^$tn*J<*pHmy>yb)#%^3_2Upe}nyD2@%mWIE5b$tB%`1plT zW7IDtcE3dhef##CYwMT)x8Ya8?iDqRR?4gJh=OB<$0KSQEw>@DBYbN~{-+k{IfC6+ zF9;Ks!(3W8E&zB&t}G2+TY4ii#-SIp9b?AhiFmz+H+FPony#a4)+`=0@s-^SYT?V9 z;%Ht_3^^VTPfRH3G=|Uuz?T-jZ32xXtbtlTi+qtx70Po=jNB_kI%n9JkgwMeg47LR ziHkijI)(D=794v@_B+Y+C(L=#oP^ZqF{W4o^;mBZ!U8#9HukB6k9;WbwCCv;&yam3 z4EW)fzmU(}KNWa=?3s8UXh#9??Cj0&Ts?pO z%=&{LoH@6;o5?@YH1C7z{k64ECi6X;yVdHZJT#bh^F3-{9?0hrp&^g8%-RI<;4$WB zM56(D0itCth(Y`F0h|+%3yboTju!o|2br2jKd5M_>W;Qw8(7bjqttA@Gy(YKr~Qob z2#kRNqtB)h$r~2iHg>#Ih?;cR5X~XCwobX`TNU-4hYZ>Q!IYxP^EhPvFJ#gd>ZAp< zCNqONcGz(TKr1DZE%? z*I-}YUj|_VM)6TEe8G@JGks$KH}tmmF$N0}&`?GX_Mw;%k}H*tCG@x*aUQ5!z;>96 zVDu1j20gfn;En-CaiEM4wqLn@m02CV*w!-l3Je%57Y5%ZbQQLt5|}uYBCBY{1RU9UYK!b)$=+3o>Xo%ah24JDOHH zn$E%}ywb$m{LBg180J;WUg$rt%rpwn*iO z`HUjE84UCy-HoK7_4UQlF#l45g&{QmK>D0qj=|TH!nSu@h-Zp@NGWy*suEy9V~UwE zN3K-N8bULLQUzbVHj?Iqx$;V#Wd>m-Qx&tCPzkY8^$;u*omK4gGQCC14Bf)One%YY zp?%O}FD;{q5GTo3OE4@~_TmIyf6!E3QF`Sk1NJL9Gz$sYq!1)5Uo<7s@+Z6|uSsrE zu3qlx_I7J+@9}^W z=!Skc1MIbX4Ww=$Q3g3#8yNh^RfzyHAli$+zN0pC09~Im3lokfh`pRP$H{i5RsI!5 z?Q!IBfc=KSj9~?iAH2Qr|3=VF_cK7to}Q0DU_-zgwh9U$2Rg^-!|BOHGh;VYwzI%& zl+2b{$>!V|Ns|F3DF(NscUHl%8Sf~t7wu8(7$@h;Or}(4eDUm|3Bb=@ekjm-4x%Xq zu?v4Zcz5~WE31>f!kKKgt01#- ziI0NB+Z5fn=FzL*YMpWjs7_gUF7#L$5-LfA1&EQ`fn6__#qbns0C2Ya0)#Q2W}Bf) z!&(_bXT_JHlGd0@DTnh2?qC~(S^nFKaE^J%q(OfLVNWvm3JYJY4}0G}+L44J%Z=C! zYXZzj;m{DdF^X8qQ@~V&YoLR0R3n}3>+9=9M-tLDP731%M)&p!#f9Bh&Kx+&1P%F? zE+#>PFw42CWXPjrxpXBVaI$xGaA38I%IIbUO~Mwent|IM0x>w$? zG_u@EF4S<5WZNe6A{iQrcgU?Un8y6sLAMd|DW_0Oi2O-#Vu!_QvD$&ga-*G5lvbS~ zSc29b6-fyfC-=Tq8j=u8SzrMJ7r`(97chGh5{1+xc@Nr9y}))a#8_54Dvk`5We~}E zF!Dqkbfi$o6&4Mq3>he5C>9O$9odC4v!Evjk#i13M54R5L|}DdO4{&52^A}bQrr~PNC7t1idrTCzq5WI+-l7C2>5Nh7BpUw3j8u z22~CgB00>s$)GADbP}Fb3^cPOao{%*c<7EVSHem+2W77OH`tc920fkHS-Za;^W|cC zu4pgJ%rsm2!`QaMJY37=?iqr?*c4ow2)(O=9W}WILV5lE!ULFE?VJ)Hn zE7s0}V(WN0!COTO^OvDdA~ZcuKeZs7>pB*k$v1PfGo;u`>X;cG!0 zAqtieDH&i>eSL4sRYET8ILpNp6Xuh=)uAM{%&=1^5;}|F*-8CfNG#^nPD1bs+j|2Oxfj; z{UkpY$Vba){|%L4l#=IN&M1x67^-{)w1K{Itx?XDl{Yv)1f$Zv?GCOqb}h!{-pShJ zqe?Y%zfx6Y$ASE(|N4jE@5^ENnM1q~0RxsdOx1zJA+!)2m!q{|9tW@zVHMo?AGWS8 zwyFD$lK7*(G4=c*Td^ICt#Rlm(cI1TA9H#Gdxl2Y9H)!=_4`v^|0LzTY|jn?NThxVEpc-Ny2{ z=l44wXraS*uAr)LV0;@x2P?D}d*E9F(N*6qCQ!1>&}J7bmj_nSAc$4(vK=}rb}-;; z+&2tT4gW7{6qbkV%XWY+oJ=VGg%8+=kgFjWjJXq5jf5>guN9HSKTKz`7UO$x4>@Gw(k~?~6 z_?DV_2+-muiV-xX7aT^@1uVxPCV<8nzahqw&kxvd00L+SbXW|i#ERF(07_fHh5m&R zTM+IegmnaM8Ypoxz#Cc~WmSLuJe_ z+h7a;UjtU(OgZ=I z*Fwf@2%4?IrL|l+#5gQ8>v9ZSfzK96Q)~i8-5++sT*2k6I6b7%t&bqu^5__Za27LJbbI8ac2CVCI!#qccdpnqe6O2rz31!zzS|B@9f=k_UgfGk{<`)Ha&(|NOd~w_uDQ zKZ8utXy>j&X|Btu)49MWi$ZYm*VF4PDa@3cTHW#Xqoo-tyYLbKO67D)e>pIWO{9qm z2(3Vj=h>S^7Ko{oT%f--d7n3O3^8$p$^@IH&{+wnn198_1%fX^ zIZhqMD!GR41#@PpTlmYlJ#+eW(fsnFD|BxZO!71U`014^zkh*e6~esj|A7eWwO)oF zUAvmHC~wiCw8f8$oHQ?~#EoLQcwj=>muaP8S4vy`!K0`9$;@UF4c06rOrlyODIZON zV9qQCtUdq$AOJ~3K~$hO1DT*!)*yV4lTOW8K@OZ=4+PP}i4pXo~TE(e#=kUFC9ggCkm%Dhajlf(n!b2+c1{ zf*Gr{4f=d18{^N$8yh?Zj)@TH4W>DMj!wP?7s2z4O&(W8_HsmpWC04to(ul|@!!A2 z4*0u&&Of>+aQn;8Fn*S|yn3>~aC+xwzgT_i9q-S7a_-vktHYkZ-j}y^;r9LAdw0)_ zF$*(=fJ;n{>5bYDl$_-G0ZM+yl-!HST`5!%W6n&a6+%K%^Nr6@%ETr@20AbN4w;hk z%M+eaql^)^r#_59__mw$VHq=8}g zxSY4_?#wwre?6{%hrzx>k8QSFE=CI~E3XZAxrT?TwjpY&$c=@yqNWg>6sU{1E7kxj zWtB}p)u-IVU`*)FS(aly&u|s~B#+O|B0~F?eVB9_s%aqYu-zpfEzfD~e5<$|F8O@b z7Us>R(w2Rzg|-FShx0&WG!X)zNqb3|RUC9HD|bPs1wAxkuY~4ik-z~w&LR^lI|UCh z1F}jCDhp8QQzC1L11k$@3NcrZm-4CcU&nB(aw2(U1&&KDxF zsR+slF{F-UV>jJUG&_-XrP80BkWdSi?M2uQ%s>qolAy%8gHY&LOi&lul+lP_GY&hc z$3iz!4>#CA7>&5Q-KZ)^im-Vw7RUCu#|~hucf05Yjtb?)`k3t3AM5!eQExQrkHq8M z6Y+T5@1!T#je+wC^ftuNO?bk4!jGY}SD^UNGEc3BS*d}~3qBT9=TU}b!-*T#z&4fv zGY%ROY1KvO!X(;dL(viUz;YSHY#OOp0>8F88wi6z_<)52BNZCq(2mC=!9X1x7uBzF zThlDQJCcMISliU<$mknnMxrTnDcF>Mj-w{~k=TP| z0+t1fPaW$EpBVO? z-osIo$}TK`RU8LiVdm=!^19_GWia@7#IuvC9kq1LZ~_xokA}A^7|sS=Hf=NDah~mF zTUw>FzI*Tf?d>!3i^W=+g}C%og~QWuB_Y=;%qcYY$O7f3U>r8XqmkX(j_=d??k|5X0@^NSkEv@qaT0KEEt40!#_l2rz5Wo;b9Kr5qBy7;;=__aN; zRS;ZEAMfk*u?x=)g50thxtYm0l1Qdp38G^pSWh;S%?w~zM=L`epL1=cDGWGmQtE6X zXyahmOjVYtoJYXenwmOK)1hRoiY?Eu+Qb z3VX-t{9T|uR&WNP8HkoSIjiyEN@E39Iq! z@81D{|M205zxmHUQVW-jlOG(qXhh#R`F`9{9qxRSYFv1D&FDPZ7K(d$eBu1DV@&o? zJ%W>RvVbfQx{y_1NTb2R;zol>AL9*n9$HBoW9k%wsa%tdF(JDfNRx!zS^kSjdIdtq z-&GIBAKWizC93{tf#Fu;@-|S;a0ZNDJqk;0T9(G%mD7M{pQI+)lZ0nJ@>Rd%@Nk7E zYzE#UwEv>^m*E>O#5{YTyzS(k zOrT4i7J@hkvI5b0*n$z&fw?p^SAy7(V+qhcA=G9kKz>`OBNR4Vf(sZtI4gjf$O@6p zTcI6=d+Aw55JQbL14CO`< z20k;g((m@)!R(sRS3Sl`#>jZT@ZSLd%l&tv@EFCqIA_M9+a zvRW|QQ0a?}0^>^RI;B$Gs$n_>EFkA`o|=>tQ#x;D#6=7bp;v`Xa=HwkGL zvz&gqUaX<0P)O+HHJu9dU@{PNy?r}v0tGQzK5SW#<(16wo%Wz@XxPGQN%?Gy+@<@8 zvSn(exiU7tUJGcMO*wUQq195p2nvztS?{^CUa!|Zm0u2Z*1vr8@b2~vlPYUf0322U zlqNUAP-*eHxs+eO(b*b3J{At|RvWe2%%YI&Z-oIreR}2B-@jO_F^_UP`oWu{D4~K* zjUG_o;=bB>Uu|XmSz1aL_sa+gyHG=0uHfnP<^CpW7z{Gp|M7KxuWjB}7_WZ0vSdtT zArVWeV@bB8S+=mjN*r5~1-@9bqSjl;PzOVH-Jn7W_6#$F8oI(@1RI(XT0>ZSQF@V% zu%zIYvYN4E*+NpU73+$!%e5amH|{ePqB!mKEq)l$}Tg3mPW3eHRQcbpT`;WSQ?m z7||9RR^9LjOLY{sU&TgzMKl}bK{_tnJ`rhvT&pxq@5dr01*p+S>&`A9Omez=jb;)9%ZFnM#SeN)`&u0v;v|RXCcO6h!ge z7O$cV?_faEXMgqd{oNRr%@EO3iId-rM@XUMt{O?fgGt9wI!9tt*lU=(Nf;J(qj)rq zuqu2qPLtt@5!v`o1guVly^9d5Q7E;u3GT+jo8t_lL%4hSIM0&!8QqnU-qe?_h_*jw z)r&wnCCRh0J1_yW@lDME!PtbOO5a%Jp&@Z2ItTV{rz&bCM2Q9N8k9EXqK3;f4>nTB zo7DzPX9J1PtJ?;#bJ5E3whT%J%Z*hWzm?LL4TV296v0uclx}(mG-@q=k&}fCx@7PT z3C6kv;x0FG*oBFKZj_dTAgr6q5a4Brs*Kf+nvrJTY>U%`n4iNbbZzGG{mqvQB})_KFjEqBy8Xnwo~m=0%24 zZ{_pT2k_i?X=A_!JmLY+Sd@@TU$9pto`cBf1AFD^iD%>p-`vqzOl{HQiSXu*vt2bG z*~yJF96~F?H+Et%3`pc(fyi+}vJw%wj$#@)!-r{~gZd(q29bljjlMD8jMAYc#4=7? zi>2}Z;yyC2n<0-64N7e^Mt}jv$f17qM+uJ}+6`JP*RC+s?b{74P5Un&grtGT-R$sM zx0>yi%jmESh|5fy(e@evW~SQeA|2j`@7~_e?%&RKQDWUTM3Vs+G$s&>1WGUZYmq+b z%?qCFycVdJ{ee4>R*v_M*8(%rv2TH$3qQRh*8bO<3fF=L;N88z7`$eufPL@$)!2Dg zbqh+W+|w>P>t0|t1@9Sj?*?Dlp5ig*X)Qj!b5`bFF;9fe2FJhE?pJzfHo@nfWN>I& z3dg7Gl0k`UgZGo(^Kkh=wuUxti;+e(vH7c>zDCSYiz-Z?OW)=6fH!@=kAZ z{e#>Ww+20Xu>Sk6|NZdcn{Ph+<-gW7%3iN@CR|&p? zw<_hzkgl%mDghKRlB|9U)ZMxXsjX${48p4BfVSKj39kyCU0GB%2UsKr@k}S^*KIqh z9d(?%l68sC=`VlPe}DSo*SB8OdiGnMJMBcZ=t$j>DqA64^*X|ADWlp2Z&oTOT++@8 zPK*g~W_)bmI2ce_Y~Nk8ATEvy`>5kr*tG_|&+~P<`uT`v!Ol^=j@;SR+jVa=ws)WB z8ZJUSt#7kAXcmu}>JR1>4Y>#P!9ed8B`_=0+gF>fpZXrR-7oMCHM1 z1Ww^vN->E}g;(V^8b?pP&FEQ03}HM+sc2Z;gWCqPsU7k*_!z@zY{BnE!A!w%!yuNL zhB<1Gwvl9Q3x~JoF#ReOizH}}cTNawh+OeFNG+dazFf#It{evbrbx9bHB0xiv za5`eYN09DCPCUIOpUmlT4Xb1w*>u&&2xdd{IPajPIrmZzG1jeY=-F;esTUmg2r3K1tD4ud2)ZGhe zg;q3xruvV?Eb8OOx~o9t9N2qzkKcbB0sV*!dj!@KB=&!&#dx1i0&jEdJ z#kaifQQDKyh~&$Sd9hyJxE^aoz9gk}Y_wLS*|zt0?O<_i4EPeM_+V(^U~6}^J|=Y zn4V_RmE_E94}|y9;W1SPGG!jSw_mH>XMNu?x)<3U7#&|{_p5F3Ix}c{^5suBSY_;> zcEV_dYaZdoGxx&1*~1p9E>LC9QQt2{`BzeEkSacLS%&hu`N4Y4(%tpKMb^4s^heu@x2EZ=~y60 z#9_F%`xdDD)%Ui_z@y7kC+s59SA3-@*?jF&rtzcnIIJ& zFPD@uubKlGuL^(zAFzF__;HazvfM~IRVam{t-8g-J#qNXnj&|ZZ@{;@}3?W8mV~5HJU>j%OXE$I*$TBAxJkvGE`WGyQ zJx7^DBfX*$C#4`tyulG8NfDX`88(lTgOv(}Q=57S&O(npB@4ZlA#9k$4IIG~d&bAb zdI^5UXB1-TyBe*iu8{1>ZRXL0O>T=0H|StM3!R#alDZLX0LQD9hJi55HM(jLJhhD| zi>dNli3=7MR!O^Rs0WGIXF3>`4X3B<4;G}UIs}<<2eTb6EpN++1lUpxTrs-aNKP$~ ze5Ls^sw>9MxPehxk-{P4Zb>etL##!)982RVWk4ge$}K0~CG=|Kkd!M3GA<+hMmg0F zlE+cP>YK}Xpyc7fp}K1X%>NWnA0a4_^XXq+ z=u7kpd^i$Hhmm0kY~whNVwp%p&R`?OY8s4Few09fl`ezCbTrfqmHVn@80EQXOrM#p zjNN<)=!n6a`?XAWOI>YtYqAGb<>xAma;rK@lMHfb064?mcZmB4p_Sq8{c1UTeb}O# zr&^X7sa3tExDA7oR;zq{e!g`Z&(Vg_UIfu>eU%5@-Pofmc%CqhjoWx_75(h-7g@YW z^O$etJX-SwuDv-{$W@@d65n;~4G; z4srlfLcHrmh%G~0`XQ(%#27_Q#IAj5^DTSQJQao;$9HDMaWA>bnH*@XfX61?@;fP8 z(h`|iBx6l#5PWIUMbKlPSNFTwYU?(JqpoK*Y3Q#*4F2HSR&6w$K3#V@ZCAgurWlT{ z{iA1+>2?n|q-5A-*1WQT@!30FqsgN(+tkXcOyX?d8ZbxcbL4Q?p$#q_OYGRIaa`-$ z4~7;Qi0Z?dxrG12*V(-`m7rnVG;Qfg++uo6*S4{yO`F7|DGk)MHAxc)ES5#LY?-Aj zGc=`BGK&|LF5}JgMi4|=a70uXa4)=a2k`?OaAsuo#{C2KX8(q{64t+9-{13|R2_!( zvpqRUTO0G7=Y5}#3x9a@$vOk*^)r_gyg~mFj-)YJkeXF5BQ&5IQ|$BlUoSuZfnJB| zf_%W=e*5#k=|(d627o`@|GtOflh<#a^+EFTkr8d6btEs&~`x2=`IIy#jv1#%WYCRLuI|?I=OTk0JaMWgH`6wmz1rcgh_7& zCWFIsDh0-}|Bk6RX{+<>f*%eAyRU4dDCUvY^gVO6M`{V?dE~dRUdPTY!SJngzAW)H;rCr z4t92?R*Wwj0mdlIwZ~58AmYuNd_|0xGY$K#>O#BWT*iBW8A%)9mfe(9mV=9j*0saS zhqYi$nS#TycxpR7v`wxrv*zug)KA+qBw;m)#S#M1wLTRD!+;?`3g$2}t zLZ-w?6$YZqL`WK+llhWmc9_YgJP6;?vpdG(?XfW4$&5jUCeM2@&l zOUN2bH-oQ$DP2e;fZqY_e__Ho#93+9#9^E@SC}&jj2b7z^$X_>Fa|?{H*)E2SPTY~ z&DRYSOKHR?eWlQ%&8=ljq17pNx;TCfb`7QtnTrD4QGmAfSWP~4f{X1?uF%%<*H|3x zqAPfkC;+AnxQ_U$H8)qQ8}?!b#%#nC+L)+}w|0P5B-Bm2^=OmZ_VkRy58^gH5eT#po983_)GS8kzm z%XN#bS9QbV`Y5Smxni*K@G=kePYI}hoTGtR{kGwWjq;@?2b;>bf_qoBY<^xd=;0ej zn0GMo^pqNd)laN3bybNR3)i`B^rj&+3k_Sftix zum?+aO>i}X?WS9W$J80jxEaNjo$%S)cR$;Yw_{@-P5J0A!rTw>*D3IqCvRLYN0C?V zI}*MMk3E1xo8hP)_|#DxrHn}SmhSnx!<dW?6_D@{yg@ zm}&R|*5$;?z$jIQjujYva%@ju~@%0vamnFC|9pYLdX%#0dxTh>>^2hEVYk(iHc^_EDF5HX87*(bUtzbqko<>hRirRNm2*#8m`GwR|9G;*2MQ% z1y36i?VU!qMQvFJx+RGiIe+-Ne!SmiFvYS&Y&#Q=#le?sf_)? zbRowYEpvlmIUR(u1P>y9&Q37D&Sr`6z>s9ePfU0k$FZRYhPw9w-$Wvopp%lYaP|G# zMcdH8gEi_p41Cqhpu)j$$QQtd%gWr42iRU8*#oB`zyp110yf%0A%n}b!kirm43C2W zd%+=WfmG-)NW*_21W2-qEyzKUE?`z?X;lKJi=8m&1okS1{Hjo>8(T15_PARx?u9R@ zRWBM}Ly1dOAvM4T!^P1nt-V5fw6%w`mB}-E;dZMv`k1Bg=;P7W)jCcaW5ld}uhM;F z5Lai@YFu*H-d$4hLT_hF>c&zpJ+gM>`i%@n9`$_KONOrfvY)UvSNkZ6BdQDDZEHB~ z?ZKl_GogPJX|+_1e}XsAs>hQM{@M!~L~WW}*>QrI7saRD9YlakHXI5R%o z9?P9w zURaK-!bdW#hzc)X-nHwOZYO7~mkOwKp}4`0J7lo%%KjG^9^X#e^P8*9T&~j%HafR) z-E}vDFsvB>S4rGpu3TM+La;8$z`XA6BRs-N$?A157+f1flR>#oCf35j%fEf`D-NVc z1^wGUZ@oUNAgqk~aWgUid(ohaoxx=98W7%o-tY~ne6>?h(K3AsPL^F`43NQ*DHfuC za7LlaE8Z0DH51>1s0hM+ zM&j&IxU{Yh;MT0G)dP_^m?Er77Y$kwXAn}Aqtf3^M%XJ+DCLgk?;^L{bdd4&b%y;l zhOJCyrcBP{j#9Bz>#%d~TxRNG*&cCa>YKNZ?yx!+{r}_3hwVgywqKW-zt;c&AOJ~3 zK~%=ZvX{uy$);B_XNWH%s_m_KA_e_1P<=4uXELx(L6-kzu&sKelyaoSg$d?J#fM`3 zu?H-9#d%|11l$i|Ux*DE#y%kHDz%;BSL#Ba!LP!gV@REc4SanxP5g%aalbz{oC1J{ z@%bA2O(BRbsdum+!BquDO#Ft&Y><1^-_QJ+mZOsTkM0}2eKQX{S4tH!B`fnpLC+I_ z^@d~)gX8H^5+o4 zrs*G4Cxa3>h?e^+?<=9>831gAm(eq%*u_*n$W|2A_&u~$ zhQTy4Bnj_GJ_DskM)r-sDkK`_J2EkS&mcNE!h)CS^NB1|=!x-(^B9Bq1xnK!oTa7k zS~fcBTzi@Pl?VOY901n3$G4wbfHPb)3v z;y8lCL_E#pIb_%@2^ItBM1l}#d*w{v@Wpu~cAQ3o6~r-nCJa?MV}tx3Y6;V=Vkh0v zY%U&la-;(>eJ&O^fx6-dWY zgRMrV7=rB$gWFs7-souk7OtbKMuXe+Iw4rK_TJo5`)Z94EbU;aJQ6zAcIT9mLHt!O zRipO4Q^7+ddz}o?wE6I`_E9EuZ|b~zRK9Qo&o%E#a&-2wwD%_MqOzJ}I30aVkEHYi zOHxGR2i{#$Y9=*FVD!VMvs4Q*Xx64zxy)+)li_Gg4TWQ_eWt46cyo0ustZ1IX8mcs zwPgQ-E#tn!rLzmw)z#+0XXhGs?mYVbyVnNBH*eNPuYa?uL=PgbR;w=zn7f4_=%xn- ze)A-=uC^sLCH#-B^LuUUKErtR6G=8EvL+GBieyW+rC64*!Cqv^vJAdxvSH%Q(`E|6 z@{G}jN96@(a^agmSST{M!Ni8ZdXcLRLYF`WVT9&t*QGc6GeR54{oc>>J#q?L+_;I( zIaX3v(Q}^neSR?8zDM}<#+kHKryb?iiXUC8{^XxXRT-9^bWy;99gtIw#_a-u5(+}!Y%o@|T8qntu3?Ktu*3X%x35EI^N z4S)Cjcl@RcI`;fChrECIA0yJw9^TJ5-%;DaYJ2&Pn=QAemz@o1-r?@_;3AhBeYpmn zHU=D3@O83;);U=$Y;!AFvX^@36fqluG(%&F4!ii^lZ<pv(rk7Z*NUy#Z9t^*9&p85q|oP*Ohpm(7*$VI0&*O%;WMR#m@7C!7 z-X-%H^_4MVPUJO>28<1)vz*UY@-hn(#!<~0^wxpg<3(@ts{u6TBYSj40Ye(pRUvSG zF>H@`n3hus^|SqSR>|kj7KhT=vn?qbeFiYBj2KX9MK)(b1@KISg0BM-xNT z5wdAE#yjy?l?&*eiGV&DngE|CjQ)mY3Z{%99t3i+95H`J>mGputCWx=EI%`6Plc7R zM~c~CC#(^4@&W-?Oli+B-6T#W1KS9QOUW-5;UpbMU~K^WH5yZ}_t{W~%!Q~CVsy3i zEF`0+g>BTJ2Dqom4nh?Kp`}8x5K7wnchoDA=@i$f04|6Tv*9gt*QC5EmDavkSxK$U z71hyDkeVo^Y~y08gbsQ|rli!`7xq)?Aa%HYXwY?6j$lLF6(}ad-b1G@J`~!iA3^dd zT)FEWc+zWh*ti7PT4MmIZXE3Z_~bGxx^|gLdAUcvGbumIwA;NC!4y zC(=?lHEOZ-nwo$cDabST54DFdVA7ybUTNHn!}r$k8?XC_$@8Ei3FIAHK$<1X?!v;> zS1HB^2X>ni9oZ~zEr=FV91P$N8?U-~{n0Y@MPmwywu8^)0xLw5+X4SCUbhK@ba<}q ztifPw;Yov}GQyBMOg93t?BDLR#++4IIg@HBUdUbV*=qp6ih;nr+RE3b2^JVhx4&Td z%q#1&*wQ?cWo2IhxOYW;3X;Os-lWs$sk>_b(ELI++apfjY=?2|y7~X955jTOIO_WoU zOX@pla?B~J$kAeJJE@s?U-RL~vPS4|Pa?0Th;x?3nH4emFVMG-7YPWn)DO z_(lxOgBm#dSpG(Qn?D_t!=t)09XM0RgC35FI`_gk6j${Hh z3^n45F&Ku7L1`v#KhAe$P&&tgG;0^*IhqZg&q8)F^v+a*m1>am4KTT?G4vTOCHs0} zvZ}MQ43!Ot&(sH;2ZR@C304L)Jq=Za(frE5cSa6iqse)4IP&WLT~sa7BKTS*dIO^{ zCBbN~7+o8-&Qx4MFmvO@Gfkl@L~RVAzRDYmb%~XTqmPXVgR%^!$)A)W%V=?0dCy)N z7J-xOb`5+<-N2wU?zGWi=FZ1qyusNal03$lNaIh+GH5=w>&K1%UU>`wCIagQ`O(;Y zDNC{^vY!!V8T8&5&mK*vO8Dp~{0V(nc#m9RR!kwJfr!slWo?E+uwdYKFCq(Y#QA?? zA!8>>wF-FYSD~oVIP72~CSS00 zLIT!nXxk~ReNB^j6sgKux0uAvL9#v3_S66y6+WN?xOh+ijJs>}zNHLA3aPtFfi|9N zfU;7WBZ1@K;GkGsX}Hvllo|+G`?BOEiP@_f1nJ}eB4WA6C9eN>z2?;yF-@*DP7D=s z37vQe8?_Hp>00kYJcq}Ye?o*^HG?3Us$b`48hq7&1iS4p)?;wjp|VaMdP`#ul+_oU za_0bWiLi!qZ^U=Sd4UF$;}l9>_~v>~^}ZwkZHg>{Xs@ zK*(K&hAUfIXyqQw;mKhgk@&WH<)62I{^Ysw?w8*@c-TXk7weR^x9!#U%enS^O97Q* zE*83_fGmJjYhP|9bOS>Df>+?c?_&U*gA8jn?P9c^{_Z0=9DgweJasu`HoU#+Qn02a zy=to)$?@FftDZaQauY94?My!v$Y0U%mI&d-rbLW63|J#^C7%7QtH^UOxk2(DTw~ z&ASLCOe(<>7U;xX6B+0%-|@SFcGsB|ndV6mxBV$~7O! zfa{_r4LJ7^F-^I(sEQ4^c3-nxEVOKX4F`7=k>M7(kZAn@^zR)_qK&Ec;oX{x%kf*@ zQI$h^ifyoRJskc*ogu3kr_fp|vzj&jN+cHKm=rDw2+L|2+#&aCweM!sO6`)gi;;7g zrUoyKLx2y-FJt;85}IptU&3VD8)%nhdH(+04+7vHpYBKmzIyGOlUhu%8v))tBgS1u zF6?bJqyP>hFg_n~Mo6?E!Az+)gON?6!0KC|oSjCbJv^a|CHMA%sHX!LFy9Muuj~yw zNDL*RS3DcmB){qze1vrPf(F#SNWHF9Xs9!XR1F-*v1G^N@L?4I6T5*Nn*5DAba zG<8Wcgg+Dg3=qeSEmt|POC>{H(rBZ$_?Lp!nQGkFZbgTv4W5MoLwx1!-JPY0AwR25 z!ZUh-7q$7F-K}T`%;wmIZ&WE@SUj`SX@zqDv1(z+&Ky@riq2N(MmjrA8*Q%0=bO&v zkMr1!(#N22#jrIm^;LFAz9c(!#{O5%Bh=93ZiE$yH4g3?>y;PSpnFuMfy7!eqs}v+ zX6YLq9hwNc6)@bFDhBXXQ)#;#m(dL>3Goq+Po%Rhd6InSA!4$O86S;4zA`>!oEPpJ zJ{p}k!VNtBiT!`GJF);F>t~a z11IeV!{?Y#H%2W|K&K6XlN}_jrvhp8HK1{VD4@hCbLh^gy*U@VUFmQNO71V(dlA7v zMs`bt{TJ6tYYMX`0gK+$(u!g30Rc+|&UH(qNTd{IY$&X1q`SHxwK7*EgyZg97gD@7 zXUun9AWZb*3W*mDMJ%V*RR^fH-kNZ@Apum6zzc@aQY@>KFeM}%aNowD=tzXO<^ry~ z4CtD-EN*zy>VcQ3<`%)d-dxSmXhAH`zuuVh8j@r$67eR8tHwC|u<@bNq2|>Ery4!F z60spU0L)2?#c0<)Fd4nk(P1Z#&bhAOH#rB?P-DB~&cg%lRv7Si^1Yk$z%Ef$ZlgTB zAkmhJlX709*8F`f;)~HvH1J=xuC=wT!wg3ktGc0C(j;t4lPw+HYF&`Pj&0qC8I2k0 zym@Z*p&*@To?Yx=$84rhe+ihtkijXTG8mc<`IJJ~Qb-_8O+IaZVLzj^`2~BQ=RI27 zZN>=eoFhkZ96fs8_qn*IuPR&6X0=(h#7nF5nd@V;5nd2}@CHlXrnw$(L4&nHSgg)( zfS>xSPcX-b^yC-FVNZR0m8r^c|JH1!a`%hX0V^Ejl-K^Nv(eT(mcDp)ZTf-Rs)U}j z2e;Lo)Mj@BSaDmi8RlOBVTN|_QCA;-@W=lHzf?ir|CfefSty%PnX_(pXSAf@j*go% zRy5YT+>avWXRzVq3i`SIYvgN-frFSOYV40=qsrYo3Z=@&Of(0l(iir)ME zN5gCGRf%A6#kRhVm#OGYw=i)=YO;XSa;v%ARFaBQO>HYoT6!!+<9Iqgf>Ig%3`ptd z7nTuT8P|>m`OYK8WsP)jEZ7bfZM7s#EV^lduVqvzG)cvm<6p-Mz> z(+B`f4KfzIJAF=sk&__=_v?vyN?;Y6>4G)ircw*hSx|W~vyz_TLYm5FY?SX3eYvxa zTUi~X_i=8x<=(@4@xsF|uCAVc+Ha=&^22HU_=A4@_}wpB?2c+ZJ70Am1Itb&t6Ny9 z19j_{^c2B@BzRLr+64%-;0Bgg_n;-4#*(<^432}rF-FwRAvy1uWkz(}XfQYmVVF62t|^HI?bI_$Y;?aT%Bk zE^OA=k%WXxB5pa$&V|wyIocG}X#>^;dfbA&7ek8$dL_!N;mNS4`UkJNl0p*1R zZhWvD3H~CqG7(x3GJwFwxMmoV7-F53)6Hf!7hv=(>{)#Ln|0Q zuV88&y0vMu>yAQ`NH;m_a3J>^|DbYrbBc;9gmP?h>lgb-0cJZ&58ot4FHATCE>WRLb>9?*j1h z9B0lachD64ZfRVvPdb1xI#%Vgwja^hq$Nm)RxyLZJ(`GDQNd7GS(eb@VjX3PhqN!j zBaElXrecOte)YG?#)ftas=0`WS*2;n-_|TjI+C=Xq0Lli@L4&yF*nBToKS@!!OdEH>_pw^LhjO0?4Zd0_?(Y zr@a5P9bkZr88YD)t7*UgwfsxM4<7D?-HA`GGF=L-fT#y`Bu5P*7xHW5{^jFs7BI94 zz6gQlAYIrv^DL?H#yLOZqQR5rtIC6Cce?UJm_cpQJQ6Lt76ab<9{~Q#&(F>dfWDat z0Bat!7BX1XgI3^1CR4G}C#}<6K=O8G=C%Ux1?KNq?GAPg^ep5&hSyMcU4CFh1`tLY z2#7`$bU2K! zGT^a6%k0Gr)G z41Q)WFwHvv+9oapO0ql{L6QBm+KrN0F~oqWIAv6QW=TW;45peytR>c{tsUrz$*Z+r zA+D{$EgciLH0esN=qGphCIAVT8iUznSarO$j3_%HSj;HUs83fOW8G5_sjK?9}Nq__6@B2~akf7tI`KQ$Ed75Oqk* zelFD(OEo#>%%Wn@T%!EBlwDjx=myM5KxEkTGJ@)Os9kZnkp^CV)Zz8Rw9hSGdQo@L>%Gpt{mdj4VhPi2qLo3#(>u!Or$+M zD6yt4unXHY^1WQ-m66}a3bAMO(BbCEYYsF7(G3t@L5x8s*Vs4Y&MSzn@_FHKonoW$ zG#V8i9PKoYqe6H)umCsMc2tZWH`Xa*l3PuCWV;_`&_xyzt}}M>FdAin5#lf?h{oo1 zQWsc{9x}0c-SQG0S_|9t^T|5ca{3-we3#{dtN)3J1`O*gd7WCTqB3SR1t$Fn<2e|DC6{c^T7^k| zRuaxvKdeU)BG%}5JdxP5ZEkvJXRi|3?y_Q_Gl zK#w2%;`U#^T&qA@C4WG*jbMLAb%Tas z|C8VS#D;VOfPZ%X{%@#mUfZ@@zM9Bkr9)4;2rcC^_0el<8o_aA(pGqIn9p~JulbIL zDPV%WhWsU9bT@h)$kOtZ`Fjw<+CvyL<~+QMEND%B?pCbejV`s@+jk$l17I$N0nHUl zr&Z}%f@%5e&fHW%@7)Aqx%uF|KP_HE`_z2cveKOyAdwzH7u`yylS#A%rTZ;Ne@B{0 zf#4?ry=5i6tjuLnWxsC;mbIu5$gTFIi2@2^-ZZ*~z)_RQgMxNGG^urxM=ZCj6lTbt zkm#I-k(YleOv%{rswE1R?kQTynx9vgi)$*F0|Nr z6xW;%OWJLH!+wDRt-G}L(nBmaX%%z{suo`F9=_jv9WhJgZ(ig-89%n-* z-+uoo-i;J6f<8ij+$N+`4$xNUT!j%|((r5ZBFQS~@D3RP?HIE5*MW!)^b}#K8?+&x zkSb^!`ium2*|cB_3{iU&tjU#*0QFlo(q^Vl%BwbzUFa>!j{;C-aa0|2&;rbwLL2g+ z17?k}lTblB1LG__!h*m7Mqt&(NPn)?On`6=3DG7*(q^_cHU(jY(Uxn>(aKWkTxJv& z=&e)TzXHjEtPo$N%D5OD7`25$k5huo^7Bg}ej}C8N%Z2WK2 zuv`}MovJ8H9^nE2ql*v#5J2z0`(MFo7mPy!xD2hFbDaWIV{@D>CtM+I{#8X5Q2Oum z0|S(S%!r?i#e54P1V6h@T&sYdWo6oRYv>-br4oiSyH-_VZo;uN zvJdPOVBy9Q0QiQ5;i6>P%d)`;Avin*y%w#&ZpQ?64ZyB}W*gKjP>v-?EP#u_a~OR` zP(O$BaUj%T3krC8`FLn3AW4vPcQjUHZ^fK%V(Jkh4 zEb9^U?ff;57!HBqB3}H3p+MOeSM4P?Z}=g|Ul9)qfdQl`7kwuJ^`G3HqA zr;}xX*Sbbm2@#E*Rpgh~m*1%%>hxctg*ntT1Qnu{MmNZSRcD2Kt=d4|{|Lr}w z_fZNV9PkvOzX&d{qM6YIF5jfv{MDPa22v;KWQxVwcuI`nfE5WD&oP!1GBA2B=E$WH%MtwQ zH|NpH*ZGO57r_pMTCp<);QtZC@$rL)HJ1CXtzDUmoO!e}nNF>xqF2=n8ceyVHAt%0 zT1(xiSd-n1{7fUN2h#?+fsG`BR5R9Af7G|qupNcdeWNRHEi>%8Mi9EZLg0PvRzx*v|9KmK+8$A$VhjFI&UNWNOE zYx>6a!pph_N!r|%vcM0w*mZkV^QnM+j|Guywd;-%E@wWCxfbWvO z<9ozy1XLkEgad7q{=S6f84m*gMmaE|L9kF3B5h+e9cQ!_sJ{G^@m;8_PzKCUO8kuH zU$~##dLFv``{4WA7o$g*QOmQj*>r>tXW-24BY|WLm@#c$QZ00O zsciDH!mt;a&dc%uf-oL}c`~{cyoi>>@EK#}r#T?<4u;Q=M3)hRm7}%_uv}bbNg)Q* z>?B0ruiOJJj1;V$#55q7tQUD#LTYzFhp`7PA`=VdqFIczv_O~u03ZNKL_t)eXNzni zg!M>~b~Z632g~7TG)l06Z~~rS2%U=oHW~#qeiDsG)6*vb^%T+OivkBYmV^yYAD&Fp zo-{?hm0X`WK{+8M(2SG>`Vz0_S*$R@PNWl715Z)(EFc>Q0D@-_dG&*kVqp2q%>Z(t z4`vQfMF?y@xb{&G;VivgPepj1Q$(V9XhQOM$c4#(J-me8LGWJruzaj$fFznNNLT@5 zyo`0Pj;DPVv#mgmnS{jwbP}-&h5&Uk>9a;KUkDf*-F^~habskplVLW?VrQl?lsIz% z5iB9Z2;=BCk&u;aru%!0IOrz#QM&ND2>=#SA?LS#Gb7A*KRet*zD7hKwOQH6f|n~^ z)Yey;RW=aAKdcSHT<5R&m@s7|XMqVRcIf)O0%yNp!OuM1w~UHG`V7YtZp=Q*fzO zmCySnu84)c501~<1qMNKT>Q2`#}FV?m%S>B4w3;=nT5x#uQ!OMv5OYQ2N6Sl&s%{P zh?|;Q*HVS`x0)jz)3PHvo$&9*0J$edTHcBIuT@eVO1wZk*9&C0XM=t^B7YJzK~G|P zFdA9mu)mjovl3%mW{}MgP(!!Rn?|3}D@n`$g|!>yJeh;+H`VG0cUi`yzx?TwRE(*U zZ^3l24GuEdnb{w-6|+W|?S&oKgawuxaw*n$^7+Gyub)RR{#aTeNp4(?p#O^n{|P}H z_oACojpB%It~oniVY$v0nDb{e6y9~Zkr-R)#8Apjo2e9jH+@E>%4@i9ybfaqok@lb zT<>;;`=+4_ZvuU(%Swi=eg*-p8Ov(D+FWTD8XX9o?{_**FL0qg1gW&Ap) z%)(?bE*1jlWUOZY*8!(E1Yc_Yu5Ldos|HRC_J1#+`5wv`f@E zIoCG>_I=^mpyn@a>YEY1aeq7R#EL-U44j8-%f_Y|PUo8a&GF9cIbNP7?- z4Iwn>H8`)iW3q?P3_TOpY6{Tq1MMxV?CP0`sWc)eQSnP? zeg;mQNA8u}ZZ4r5X&KR1`JZwSW&v}deqKiBQ8BknWCqqQJQ zAfP-CA`IUV0y<^`2Z4E11kYa!APDQ=U>+LkgDJo*f;#4@)S6*u!_A32sxEmJM(`}}Gypr5Y zR{I3yt~{=p?DsQ$?1Zr`78H+#4Cf<)ayqk!owmy{o21mKexPG;WPM87i%@!MAb@LhDSQ z9UGBGHMuy0A&?#nRc!?l{%s33D1BOV|01wUI5BqB zSz40hy+-Ny`zRN;08Q**$#3Zho?|35Gbp(bR*6u-_1yqT#+(w5~u6r5WJ zi^YM!?6-58C>_%gbZoA%UMQTEl3mK;EWdyLe76&$_8DIeX_Z0yA^s%kWPeLuF~08x zd+Fp>QeG*Zljo^IgBoiBrQmfe`am9s$S9%6?$4VkEN~l4^k`gG_c$AogMEoV-%9CL z7vkpvQCF@uI!@{pku`_`w31-~uR@#R=)&z!A3pfqS-Ug1dBn8J#>F30g!LfF;;D+D88mJMm zXh#~MlQV3L0Lp#L-XZWen%!i$@+uYU5KA4;uOe)_{n=;l0Wc+3jdtoPiUSmwwZLr# zaoqXx{ju}=V`%JvpS@BR%9;JB1z#cL3J0g$)3-v*<{0U*Q+ zDv@@AspWl$VDJmyarybh(?|Efh%b5%YWD@l@fE&-3F!_9umCW2)b>{bz!ukeSnl;) zo=L=Dxh7rolfY4=+T{?OLjsC!T032wR)>224a7W~{!@1kEEpytKgli&eLmv!q4jdK~> z;APYyfiA0hd|oIPgoHr5RfIGmZpn2BwNv6bVx%Iq9xJF zkfZcj@HH18PYz5c4k2v*4_)W`(sp9U@iS>$5?yGLCitsr)tFopi-Kv@Gl?L#)eUbR zp+k<2q!ZEN(F7TCFrO6Uj*@~Wr4F9OZ--uDh~5+4DWy->^r8yT4$c*ZcF; zyWUu#HO6mZG-=-7_viEeF*|@BYky!*;Trp6Y-@YE_fvLEN}YvcgX$N=ZnQs^>e*Kx z;aY_Q z+WQFAXgmxBo|mb?N^7 z_s@Ebf@murJm(aIHSdVrw>n+#t*xE~QG&jIwTM} zy~O1-Nm%v~XtrM!66vN+QkGBqa`7CrJVMb!c}EK+dp65 zdq;Tn4jJCQ^s5W6n6x5S{t~m%W~EWN?D{C*<-V`=tG1!%`IB0gPN@5!^QDAP@))_c z*i$i3J74Lz01Fyj^y)xJs$5F$TB;~91M#t!RzNCEKnP(SVnkJR4Cj zV}n*$b&>i(gV`b{32$yhM!Wu&cv!7|_q_5na-X>9P56E>P(lCj{q^b}Z{kh5^7XT9 z2KNZj&T%-7G2KWao>(xD1&cLYHvY@JnPqLrnK5%nRL~o7&7q~+N^B$&Yl&!3K4@>s z$FvnfmO~7d6M(J3tw&ELE<`VE7=$Z=!*E+I!4O*1SWKLa06X5IpYlWw?;yOIq=S%; z3yFl}RhW{JWMdf{eq#3k05fN{Yp^FtZFSYB(Z*rP=a{^6^$y`!bTknE%oQAUXX?r9 zEa_N=tMK75gwIql&=yP?gE3s~gNMb5`7-+FM+UK~A{-l-b?FsQJd73^X|!Q+&;IZ* z;U0u;P%lVaG%lol+Jof)=3o@ebOIaR?jw&LPT>bOQcF0rU6SvJFs$Kj55!`H+&xH9 zgHk6U!l`{wctB;q-utVzK|4-Fc~Et~qdg>1YI{sF2RG}X#tqiI_ZSKE-ec;Jj2vJ5 zi(zr8O9AWM0KlhE#_H{(`)|1CC_k zf#Nw1-KC3=F5onEN$}%BI&9!;?3oI7@qk#w-g#mOZP@hC?4Mm|mBY$2Z^ z&>ot!L;ys79KwcibrJW>(vIOS$s5LRjRLo`C1pI@=X0!rsar74Yhb)oT3#}6%P%jt zce7%TsIeA}3={5Hf?u{(eN<95hkXgX79(kc*DO=wc3T2vf*_Y$p5W{~Ms6!|Y@TyR z(_AaiO8W*_P+bz8w$Dmp)G8kgT8@Im$(A%?Z69?rk*2zd434&pM_N|HGYp2^72 zsIEi~=FEU}T`AGEnd=`uiwqj9z5e($htAZW-Ugtyf265% zx!iQF-q-utXPmGI z5@C>)vS(&Ur|d<+>}|=$s3^d(TCPq=SKJW|ZIF_oXsQm5p@}Q1E|giRaR%7MYEdCw zY<(NmV#Sf0du^!8uu&xIvSSF^0KALkGGgpvr6bTM4W#3}!LG!{-8B=o=vFZ)&pLpWJF%xQZ(QAYtNS3x>V~ zMH5>2h?-!PEnK~3B>EZ?=Sluvo23=$(d@AAhACtiBbQ@p|9tv9i=G)X@YL{CtVjm5 z_VpJcIbU;l~nZ?e8O^a-EiD z&|-QACk(sl|8|iR4elzOgBAvou8i$c zOc;%)*TZ4lz9e8}j?+rcQUV8I8*#ul64{EV2bl6B0HK)U@2HhuZx)R3 zHw%a9g0W#cxoNK3>4?_CO&Um4{6z*Z_dThM(rf){zJ7butLP7-5 ztM%Hgp8_y>8`E{!f8|1&CbUE2=NvxZHy{6cd;9++QEva@_mi&_)+j*LwAO{rDjgsZ zxoDKw#lwh}CVco?fov9org}wRK?AFv<|q}`kT6=|7akyqEEqVhFxaJbP;Co3FQvS#gs5N<(LP&%k6wHemXYHYJ8;Li{^>=p7k`hBocC6Ag#+VzpCN7$uPDq0vR4 z8&x&?-wr1htcvZ>BK?DM`a+XC<#NzM+$f{=hUb@&V3&)H&0@JzJ!)p3zZ^Tbf31{x z^5)7>{$(c!(K5#U{eO)A{_yrAf+#6jy8GhcvXR)XxCYMA=-)%}kknG)uCuK%>ItJ-1%DS-n~H2GKmW$SEO+q%;z9$B`k7e~ZaC2U!dEyDBf`C&Qm+&- zi4xjTVB@cAhO9%yrC~!}yD8}$Y;{5B;!9L%Q~I*UCUB&UVSX$3^5sR!mCI80GtKO0)g5;M8v z_P!{vFd=1?F`4a;vk!(4_Z4py0-fmqP8%|(v!q*%vodC)+gtp3<@BRbAIrgQ5elY$ZCO&)$k@P+x(Njcv-~vV&eZrnZ1bR*wFyvkb;UCq6 zMDVw0Z}1|$3)fVK6lCli9B~b;elZe&j71o{P2xUc3tTW3tWLS#bD#@Gh3#)kB1{}E zY}mEklu4dUD28AM73eEC0W)b@W8gldOtuRw8$JBL1q0nzhPjQ-Hw}-1-!>@QV0dhw zH|j=kg}}yw+lIv)p!wHsu~$!d^^OO3+%wcIHyRBCSNlS#^}1&SbFYCI+AcPPev3jo zyHr<9Gz^&PArVe?$n})-<~k!T>L?fBp(!%NR}SO7j)YkdW5PU~xEXww8QAOWA+t9A z>M}5qM!Vq4MHjKL2p*^G48R@$@@OPvorW)uCQsxR4>JX2*TDSwa(CLV0LFwQM^aZG z-n1N{l|L8glU&O83^P35IBM^<+o<0XBlCBzZiq6EIgi;9+fM0##rP`53WG9I^{K@%lckZY_>pZ7q@$uIiU93Z>s+obeo_09j z+AiT8AG-9zWzkpY?PTUFGyp~!H%CT-C+}Rj&;oq*4he=RJ0aGjM&ruca1TU-=22JJ zP@Oz;?%?2)Gu6p&&mG#&Ll*SOn}7bpd($XCJUEzjd*0Q{6Iblx`Bh~-FB=$t{!8`e z*5BU-U}r?~$?wE5AvOSxY?JW3!;9HYZ0sarhv`na@T#ywFYw)DggJBx(LWi`gkeR5 z&*l2dIR!zxnes+!x#iqObML62wH030o|r6Xt$>$xrTT!sJ&vM$-wgW0OKUI4Y*Iw? zvjK$#L^8WJ1hLN9>ly{;+!mIc41>MF0!$KP(w1Apo@cSE7%hB5WNTbEs2w=m1Y!qj z@Fhk$qipBdOwL~*KU4XV*1~qYx$sP}Qw+s%7Ui@So^_Hg_RnY4RwTm|{-D7UaJ?8fx}E#%0DxFdLI=+UF#MXHg)*g>%(4XgAh9@gJw2HS$& zu{h&PHioqP63j8g#G1t~cHwJdV?pN9y?|T)UQ^s;fS4=dE631itqng6&^GvxjLKeI zc~}O$Jy+FW(91$NUg;SHHZ1Nf&CkzcL8AG{fSSedPex;jy;?)`jPR;Q=mu?rm3iuZ zd-pk5n=jUS#ad;)XGa)9SJF;{Rm|rN($#-dtIY$cmC6@@?-D#1;njThKCYzveFa^` zK-UUWXjZ`$j7c@)yXn3{u?&-A{cLR<4DYiE&e9Z|$9dGxr&$jRs3Er5SU)DulK3oz zgrdh;5L$}oeJU8Tas(5?ffQ>Bbrx60_Qz>0w7cz--VqATIA!xVHH2w-l#KS`J_^y= zp#CEx#WNqX|DBpT#e#Td>IA;BK+qsIJoK-)o@{$r3`NHbfJc5*n0OQ!9`0Xu!)U7v zk%`79fHKLoq(E~qL0mNLzzm#|2|uXgE~!`aGDMRE4Q#@2C<5NZi$u*)GO@WSElNSj zlw~H*5&DkM!&1PLjI?(erB}vujii0nZmQ&^UU`ch zyWJvP3vk>{oA@gx(%is~?IFkVXb=LN(MJn!nO&2M1;DcvrYgxuEE8&vrK^1rkWPVF z%CEG~_q3@^-EyH=opn#0MSwDITK7t}wRgPXb$QU3kIC8~?keRmhu+(D{5iFL>{aS8 zfv(s6xJ-M5d*bBUN!vGEgpO+&Y>$veCz7xXdf&LzNEwZ~N`fYxik)utI8L&QOL*Gv zC#1Y#boI+pX}7#h<6tm-u&Qyg-xfTrUSB`m5(lpEceM4qT-x2)E*PW+xVWjqq}zc6-+NqxWYhJT{K$#E>%vJ%3qhZw-b@#xu+`^ zlxIy;)<<`EHIz5)J20Nz)n0e9>Tii9%5s^{c9uX4v;rrEz^x4sSce|}?aQZ^ zUW~T9Q&(CWEQ(>k?>dlf{?338X3;nMqi0Q(+4Ejroml?a;I8^M1HSxL3f2VWNknrP z0I#!5X(x6f1q{FTne+|LNP(tD869sU!U0QsAXbzfHflAUC_9 z91WR$X;#>Btw>EHm$1Cq*&7+~yPI`sPU=d}vShmNy0&8EvGOX!4Ki6P@u$nGm=X27lv(V3$B<+d*Vyk47wx{(4jScEDl}H4VOfwM!&DL?d!~rcF6E_tM&N7^ zUHJ(jYyfKz$Bru+W=Nd7NF>bbt{~UKP4kFKl$iW)lKgH6QLg0^Q{-Nk+R>Nr_ z^Gs;!z{`VGus!1jpALM(ssg59Fq)v2Ff4QM2ocdEs@RIUs+#D? zW&(f?N0X94M~K~si2Sk>c57g~B*bnBO5%wC03ZNKL_t(U=pal6?SG15*nIJqnL>JtjOV(Q$EsP?^FcHKs8nA+Fvb}ChFgR6~Qqq&|(ZM=c+V!M%2(NQYpdAqE3 z8(zl_u>xi>+{T);%bwU6T3xY}249PN-x!?)pZ7?~(s;UoNLn*r!JDD0hxU2hd4CyU z%Z_vlf?W64xR`qtQRPD@daRV6VFhLF5HYRL4V=3j=S6laXYTLXhzXxmKuD)fMItL+ zL9Bi6lvdQKx+;qapKNf6z>p577f+sFa5HADSN-DON!O=P9epDLEbH&I{K4I>a{{X{ z`0A5V+Zfp9wmqNe?;%QYY zbf;IJmyk5ulg_l{=mPh?{v?r9%Vcz9E%bB_@fYn4RVoZ$rpmk9T89=Qy_09=HZUNPp)ABn?8-pa!ejS5G(bdrn18*w*=pn|o;^^rP$UD$?7 ze=o28|66yDWm#6rUXY53dtFxsB_WO(+yW2w{~17Sxi3pG-&Aa z^L)LYU-C?Gky~r+Y~M9OLL-)k_KL%%^Y#k(vrbio9!vA_N`-y$Sp}ZXOP7^BsYDIE zaU4|@vDxg~o(PS`35?#$yB`8w#92Z&WLe5G7(ms$S;!CN+WdIz#7fyZJZxfKqLEOW zYni6);cWi1tK$@o&ihQB{r>01W11X&<1@G0M|7Tu4%lTSo0YU zEBhH8w4a{Bpu|-!28$*JRW%Tkg-Q5ZCeUj%BC+x9vfK@lfTfD0E()xmL2ykxcwx=Z znVB;ZXo#?jnbq#O3$hZ`{p`1#vS1RcF8A7w*#EPF>P$bsOg28UFrl`qNBfK?2 zIFyW4Qx|Y;w3airyhJ}ChGJlv=E2-W22B>x&!bBU+b}k4Pl-|`Bd5DiTd zwBfeWD6eTVY!?C7wH3yO!*lWiNZ}Ba0v(d*%ydoB?FsfrW8tykz=$;yV zPm5ZiuMt(vs+~w$1iImfG72r$%SK!6FHxU^_RA>=p&R`T$aED{T@h=pGL$B)3x4a$ z202%oWwc&Iak0H^PRSD~N}Y~3`sYtp9ppOglp>$q?pFy`aN(GA%<5riDY3)tdZ)H- zT%8|Rz4q+xZZwp8j-=Tsw6H8~y#ge++`>4G1sCpo^P66~R5Au^*Ii5H<&KN!5XiTl zrO04p&5-m*k3SKQ?mV&IElXkh_)Onfj7c5_UT)P}FWV$WskJ^df9>lD_Sk9lE`8_C z{$v+sq0qm^qrShrxLG%Bj=gH7w>mNL-ZWv-8jE+P^vG0Zq;u-evrNw z`QxY2kKxAl=etj(fBtAq)p-|y=bS@n^{pRRWO;7& zUZc0)L(ag3C8B=xSR-7plzYe<_RFDA&v3V-l96(0WLIS)hQ+hV(#j93dW*(`7Z;T< zNhXIO?2U=YMUYo{lpRT-L14LpfBe(CD(Lrjz<>Vm@4;uo0LlFFnKCh`7^u)F z)C6iNL1-3442OYNfHE`Proy2y41rf-rA;7=)9sP=*c9Lqv$aRqMZVzFSrsjt^J-k6 z|A67PouJ^le)H;E;^F4r$8HKeXl@^ab-EXrvb9T^_iB)1?J>R zZ_ZNkn_bqTn!+VJbd%((ys{-hP?{R@ZX8ZNbslaEi8s2dfi#TyKiRy?ytLC9$u(@x z+to)?*8}{F_7F`gsZyO#6;(cED|^fNuYY`)B6Y(@XrYq9eY*eIM;c z#%q01e?qn-e>@aO7??&}07pE6Lv$!;=IlqA3k^#)Zn1T8Ds1nJb*l4ZM-=DPv4h2x$%Xwt%>F4M;%U@Q% zU@z#)7+MAEy;*}>`!-4vB~9x|a)MNlWUN5zFG8T(MtQsvCep#aL9C&wS1Jz-XK6Yr z56a$A6=Y789`(phM1obKZO}_Wi65l~-k^FkFvza9+XKLPP-+k7)a-=474X^+yjp78 zcalq|4BPPv8@3IgzRaH486(*ee-h=vv%CqcwM@nt` z(I^6Xzr5SqA2F!5XL|5|qsYlp$&NA}%ok=Z8U-+6*i0LqXPAS6d{HarVsJGm2|} z!)E@_&bOJ(f3&{-$vtYXpFFcGhBN7(mlaYevy@sOD%g$G($G|qgxzd{^?Q|d=FaQO z8d?+K!3_MbSLXxAWXV~G#G?`4j(;bFZb}9u{)Ij8$3=mCLS!lnA-X|7jSWs=71^N( z*vK%>B=Ot8fsQdGUJH`3rC#6&X_N^9p}9FY2;xzq1SzO4VPn63DX!w!gnjX1f{}Mn zM;Xht?-SBw1=rT7BZU2SgY!(HyG16{#&nejjrq6h?yV(?BwuwGUZaApeOsJ27QD9f zS}S0N(zWjVJbbvehU<5JX-2ojE|^Rg(T36C+|q((&8V0!?U+$JJ7Af+oPp(%k_G5OekV_j zsv72oPYK${iTS!JLg}DKGh<_v1W%8So+wLlEUZAR(eHENu~W>!@LR<@E0A(}>_kPt zE{ZbjR=xJZ$;&YF=;;%3rwxUt!`H-q(PmA45MbqN=z8F)j{+ow2M&l24+Vf@KaId( zGjWq4uIk0*yEeo2JqyLmE6A7Dq7uGJ6h<5W+#vU~(57*6cWS3?oXU z+)a**?+1ts@{AR<+n_HMGH}~j!`@wEyGNxXL)O{BkukJh&p_ClE#2jDCd#w`GkqR7 zIy^W+4NVmiqG+SN{S^Jbo~nSWW z25@7KK`>CQ-XwOv8+}y;vH-3szlzkVl?|75h4y)4#U)oMTLYO?-^EH|Ji@{%v2XAvrmg%Z;w9Cs<6Gk|IN^)hX9hC^pSeZd5EWw1PXd>dhY~ljV_pH*r8>qJVsI)+YN zt73awErViQwRP13I~DX-|ECb?4^RHf*17$(eV<`G*g$+p8DOx2aR@dCyZBI83>fn> zcH?MWw?#ri$-HTmO+5;owS@TsRVp`?qD6>E3`Jp5q;ip~M5;6*byCt+>CJAV-u3U< z`+2_3X&N?Qu(5-1{QRExeGaGZJJ$OqV*@Z=nZLO4_l?TScNp+%^PT8&Jp^&N$OQT zX0VItSIgbJ@~#vFZ4kU)h~=mQ4kz&gJN&h443PT^xtM|Qmj$#`6UqDGf<#uiFlsF- z1tGpJm6EkCu$+tyb1I;324xMLll}XQq{9!wv3(^_!dm$_86F3P4J+0EOO4>(a(GzD z9C&<*pB$vYA+|>qA-PxM)GUlE2YMKvlHJkduyA^Ec`rs9*7%^E$CnL+=}0>F&k*|f zmZ7Qdh5hL@eQpI@EwE4CBjrO&`5eJ{1fd~~GN6vaJ`y(~k=NY}ef7}*%id636Xy^M zU<|*b^@zW2KujU*RA1z1v@cb!r|p(#oKsE81gmXhzS$~z8&<#7)X}q45FqBfP5iTG zH1}Dm)1hL}Uf+T0s0xp^+ulJHDBfrfOc+PN^#TXaL!Z z8q^j&qm>5R*=)ADYv|iHz|M9a8!t8RMNMTa+B2Nntvv?u44#cZYk$k!x~7QB+U{=F zwIw(o5zE`#pr%M}6rU0N*KWp5nK0KJfKm;C-#B_($(Y&VW5F!68le~4=$Z?kw3`yA z35Di?Js5AT_?S*(`|X^ms+RR&zzTvEbp|DhX&jB#nP(OyzKma!%tVPk146c?sx3FY?U@idnVXx#O-6| z*n~;Xe-mW#5scWgF1#JD$X84q(uI{f(Ns!-&-N^t3_kok(O8+;psA_y)DEW5Ge!DB zp+aftVr8t``zzqJN8E7D!lY)ot2R{c03y>gENoujHvqKlG7e;x!)Nb(^m+un^ZKIm z0pD5cwjD8rUb*2Y?uxPE`7i9=-xgubcdfrSX1e_h0`8TW<6_gEwKNX~5n`qBcTJ75 z_l-2C2s}4vj-)v}wf_gIYP16ogW_k;(nq7KPc=uT*2pD7Z#Wrr5 zOUIAS&Yu7K+dFsfM*NY9!9TtC`&%E}`rVb0ktl7k8Bpg))rhE}i70J+s_z0l-3pb0dT*oR7*VYC{6 z6~EClRPxb9=t4N`5=DeVtrK-4k-T9aKvVHw@+DanqlzZ4vXnQ}b#Wa=b&0~7(>9n; zN}7^p3F;_O5u9f&Y?z$GrKH9MBfbThkMd+-m8b?z=9RZGF+nv_GPh}8eM$Y%ET$vi zH#Ub5x=@JSSM*ih8I-gph5{RXX3PvAlYTX^j}TgAg7$nQe_b^A=hmHK}D5#KuL zEr2WNlEdr`t!ykDH#CrE}0u2HFQ+HQKJ$ zvguT|+GZBba2d69v>o-*S_d2Wrq}{|9XvvSIJ+zL7UY5KCgD&4gx%0T;Wq4KxMfQ&Jcu6t||JEKI#M zmHk3qfp`Yaavh@vgYvH4Ho6YNuR64r*C@+4yjH6gSy2~vsctGB0M@Ymn)-mp)E~GY z0}?R1Ks1)1^<#OE423UWsQl>WxMOah%Y=C0@~fIc5oaxYU8t4oG`!$igvE$8wEq0I zXMZ6>Ogk)_d`{7yJu;7We9wc-)!mchX=OpmY5Vy{(MTkyI%xmE`1gjK#$hj0`@49z z!_GK8rFqEUdh_il%AGg0NI>$)U;WP$@LzTQHC$dKMxKN# z239w2xBO3$RfkH8%Eh>OGG;-!ms%zCM9dcfDcHoB8(m?(v ziAO(Zt+E;nmj3g{!Qb4xb@S?9u3oz~GV;rjk&*Lu8o6@q$~Akt`a$S8vuO9QWh8ye z9*YPL4lUSh%PiG!1;W}y#~XIck;wd-ypGItdFl9JdCQI_%612drPF&^=FenXt=p&d zb;wO9w2m2xU7tf;Xl*NiDEb9+=zy!mfgT$Z_WN8x4s>V;U?r3T&DDVFf&COC`B?T2 z3=EV8T41h$anHbz=E(rLgwHK0pL<$8;=&4qW*A*EDBkSt&7+St_?=Tibnk30-yH&5 zdwWVlCnXXl$=HAcZ*rO&C}|XpDyvrs(X%<)eK+%T1LsQElxEcjOvt1$=vnnIP}49s zm*mV(xfp$%m3T_B_mm^&r*%vUN5gZRdFy zZxT&obkfE&VH(qDV>D@uQK!*bO>7vY)TPck>uhmhi%M4F+B&)^D?NA-3d@p$E2S+I z>S5W#4h(%c6lU5&FT3YG&EEFbLr(*-IsP6D+H3VZ>2c810A_!637136}1vV^+2HhpmOP7c{a~ zES8bsS^Ic3tA(+vZg3U9ZoRA{&Fw#U{_N$W-G`f7y@3Y`f|kel*9W{=qEsVluQj*I zHxCPxPBtDI0i+u#YLI>FQz59*p!YX%cpC}qUBovW@!8A4U@G2uH<|m+fGNADK$l=L zb_ww`(OEpAk#41IXxgl9Cxl{D9d$clG{KqhV40F&%j!x}XosC%d}6Q!`+XO~(S+l( zsGyq(l+7ZBt9`D8VZi|SZXdLOK z8+frT8^niX_zN7j**$7Tgr}cT!{C^&!X+2PfrsZl4B~JJ&}3jid*_gAvHn#e)?DAC ziyyTiz1sw@t$lTI|&m!Xl578 zn)G+H_FiHs>)H>}^7E9_6e$o;MS_(MPr(qURcWq_NFH_^4Gc8O5@a<*#}iAd8c>fe zr4y1q8!Rt?Q6(}H^GPphkiYL^UP%eLwK4nPw;Msn9Rm8RfjIo1_rHob1M@CcR_!ln6sN`-@8&^I$a$62gqD3rutb2%ao)wuR~+?1S5}56_{EN z78E)eCx=5^chDtJs)G>ym70K&P$PV9H+D<{bV_NIEQQ-uN0>~hdyudVcE1L<3Y*-K z|F<1Wuo5Hvad6luFq>b0SA3__>9qWaqwgAA_izX`C>eW&5BqnTMT6}cS;zfy{Q|~h zQ~DKP*?E^@V80>n_BKrnf4i&LN*2I9=eoL%1X=4F)>b7BAYKJ;k+7J+@Zf#g2}!yl zYeVG>t*RXiplS}{4sIo-gDGTG-r$J7Z(X$4*hMs1QTBi=fV0^s3C_!8OO`Tim0p9_ zWttU~y<||lN8AQq zDC0C9cljA)QR6kzC|W}3iiXk^Bi4wo^ZGStrb|qs>*J-vaWo(+wRT?KqnK`-&zJHJ zmFt_2&V!(@G;(&>+JrvD&(4t4?XXxm917`>t=6rK4+qyBE^32oCBk~u{kGx|Hr*ki zafger#Ce)H^F=d#3ugReGKS*UP`1_QtvtAiCVK?Aa>vNG8oFXq3ls`t!|-Yp%iRW7 z_MQq?Y=pW7S=rj`9b7Ol-|8xo5EBHCZ;pN{|B*tnP*Z`gaw9oK7TH>&y(1kLC?}K~ ziRi3mD=>GRTTqPyA}r)c|0jy$#KA4s>x%?S4y3pKqT!qWGARGhhScl`K6E0vC@g|F zi0~pjHPV}L0&k)?+5OrZji^2Od$Wt#Wx`49&mwAn7?Hh*;czrln*@LXRp#d!C|?+1 z54>>ogAugwnSW6qb-~V)q|nN~3k!Y22OIAd5x&dh5Dc#!yHfpr>MxMS)6933l-$%Q zi}=a~Br=(B-dh(p$wE{ptyC-{rfI~+jkG!l4X2IXHb%>88!RUzrWQ+0h)*{d;&R;d z6uw@`rR6x*4P0)9rr8kh)6S`ch}xAGf^-cTkfwxt1B$O?xNQgBfAHeT^QVsvZf%uX z{l|~rD7++YE3wo_tS;?dG|2tTKH$1K0mL(o^v)RcuCE*R4h?Nw-1vI)%z*1QmX%r2 zBC-iDO|4#9#R#SUlLn7ZAzY}sFeUx?=Jo5>Z+?1`o^t8YW4jMaypXm80~7SShDcaI z%uE6nP9wZURaZyoQ4X}e^LSf4_F`NO1=J55^cf;o36k~(p}6Wky8nu?D z(n^I6`NCe3pGh{fYeL~_OSlTUdgpW0GI+x+)lhRW9J*)V8(x_pK)R)0mLsHB%$M&e zg@a2FTwz0M`hxpOt%Ui~TZj;gWGqAD{;*pI8{|&p3M=vn6Yq@Ns?gG}=&Rfy`(nh= z_N6#@hq7Qot@?AuW$g+K!R&xR-6Uw58!Yyd@~rS@*s`ogJIte#szE9g5IU1LS=fOD z+okBP*!{)}@jEHwyUF5C940JTbV@nV@f{#ENg$V!9do~|B+b9CC7kz5?X{&QU_GVJU@ zmL+`_1MAN1&T~CIM|fs<6`4i}5+i4H^G?1eRTgI&E4!U9ElDI|*}Wn@X41%^!R(-N zpQ#&kWk}H|3Bl1?tFnLg-&`Q;z0k5Jc zCB=$uj@L=rKuoY! zh{goJw~%Yw9ZOq0BnYouNHR=;#mui`w;v6wf&t(if#7y)ZY9uABa_E@l^F_9N!L=wkjWmZ=@TK<4vuF07KYe+yd+Xt5tknB- zm=F-MsOax~QbDvu8mTY*+i%Y=NR4gB`u*)pTc$=~bX2lDd-4RMZHqv7gn%`BAJ-c3 zd5kratig)+q+_$%2t#V^ac~CS>HoYz(jeXN_w+L}_A@L}YXSgL|9r<8)VH1%&FzO3mn>(zu5#>{$g z{|p$-J#*#{*T=4_;i#;f%*56G-Fvy?zxm|GjVqt8pJkq$e5Tmw#M08}_05f=e>{5j z$jsUIad&2B-LMz%y?pud(E7%ei&yOP7k^4i_+<}%Rodqz1#+!o7UtbY!~V$wiY?)B zr3v6r(DZ-ay#C<_5cs;@A0!fE2e(U90Efs-@C8G}PllApK^#ZWi_FUB_4p*LB1gj$ z^w{ez23{X=R{>+dUY|zL_G2h)m)hl_dG^A_mL`nx63F4jFC5nWJ?<->;4q73Pk>5b zW4nZJgaQ*)bv%SuT99wyFk^Gb0gcQ5DQ7eJjbHjD{r1&^?rfhh>?SM37Tf^2{b$rX2AD5eSm z+TtCEuv!?HP#58~_H8cZSS}#zkBj}L?)X!KLrUV<1eXgMmc@>WJ38P3e`L0?NMfsq-l6qXY>O#PSRNqG2-ouuO)K zNxMp+!-QizhD=+ zs?>|!@BKXAUzAYIi7`HM5b*q-_k9iq!#mMrdm-@@&I=bdM%%w;f1y&YgD_dP=NcQ1 z(ub5x6wAp<#Yk{eJQ>(#@LWh4C8i4ruFPOMfj&BQkct-QWH3scDprNcY+Er98wTPx z#%*g5d_d}CmQit33=>kEjS9Z2TP%qScCKb=1hl6ZFcXczuy_k`l|xJdq|sl=1H7d) zYBHzU;o?1(y4qN?!M^hn*)>X;w%9XsND!S!IiHjgyUr=k%dV5;#Zf`g4kV%pgXMEu z_Ep_E>~L1x&Q2+-)S!SAt0YNtr;|B1dOEF=&X|*gztB-V*6E+88r`W!K^@XjOXBQR zD*?;wgk85Gi&lAtu?|n+ENYw?>$v=f-91rq1YqQ6m15hBnOi~D@Xh9dv?4L>zSwrM z9Lg42L#X5#)Ao~H8j`l4H5_U!a5xtTe(J??dqUc)u zcDnB0PB2V*>(2E2cPbK|Vh8+6h4orB@ShBT^OIifpi^MQ#cQv`VZesKM*w)zb0EQ( zC*zY|Z_@4rgB|{bR4=l#gC4pu{!XQpPucOs#`;n6yM9y!{d`#B=bY;x@+Qp+&p_-P zTV92d-bQ`w(w(J)KAFidA(rw;qgZ*DmR&}L(l*Fij%j1NYT$eKM}Rdik+bnp0lW)+ zj^#6VC7Cj4zn#M$gj`x4A$y(GfjoJVS_B*HW(Mp>>C0!&9zWXt=T_?Jc&E+3{f7^%9pvcayhP^9X(6d z#{I$Z+Osc(SU7(XUGY%yUiBA_jPyB@YmY#FWlUI^SA8RfzvDyLlKO^*41)*l2G4;s zE*DZCTVffK44_W{!_{zv|WV{}6)?k;6zb8oRU{`$8_%5=nzVUhmZO}jn z9MfHh^omum6JU{i6~TX`Mu+;o?k-KNBR7@F!JfF6U2pe|K8Du7?!9`(&Jns7@cVY# zL-8O{!eBRa_15?H-aCGeVul-VVsb5SkWcw*C0;UVP`R`C{B3)B=MGfwFoB{6cs9#wRSS$K@H^5IUTCJr{a0UNQz(Kv%)z{Y2{L{uep zE~2I)m>To1)XRiLD_+_FI;tgfYAafB8PN7Bn^6yLCq#5FT&nuHsW4h!$xzy;K!ZHOzWu3LD z)ab2*OC?WM{hh0N=y7d_UM@$c!l+79B~;2^AAYud#|}3_p>XiMXJg!@zK6#NJKRDM zOfT+EdtHBj-4c7>P~95M9(73r;NZ&p-^8aJnNE{o>BLv=GZ)*13D4VY#9P`YLQSwB zSX{YhO6^H$NwbVlK7Y&G{;vPh4BYnU(_x`5d6biJ$8aY_gvUPl*Y`)GDC2Rjx8YSM zFgxMBa~xH+QyLOlODy%%qG`VXJA`tSIkrG{rLr#~!&>d9k6-|(?GS%!o*UJQH|unI64kD)?ewaUJJp}B_rrzSMC=hQIT*9 z*EN)PwF~T2>9|+;GC5CfC=DydWjpL^iloqfbq14VNo9kv-j$VF z-~C#7kLU}gcvy}kWLU6U>XKv!UNP?L8}#3&n1MNS^C+Wd=Fi5B2g!zp6We)+i{{a* z_YJ2<&ngZYZ;?DnD4?%i9T~ZLcI59v%AQ1OHK?e`L2|H0-E|DXqoaWExJ*cWgH9L? zEgl7T-BK5hOxFUe7{%3~Q$N%7J2I{fusRz?PTV{Zu?I%j>q3?5yVU3_R}$EHGlIm* zkTWvg7wL<%&}G;~+=gZv0-=IaNb`;&=eiX7L0)?LPS>my{`Iuh_rxUgwQOA zsb;AEYp)UFmKFrjH$desjhVX*qFcHm-HL~%37Dj4;ySvRPPer59!J2{a=g3dTNg0u zS;n!gvEcQ|ARY+1Flbkdq+l!u#jxIX-GKYI&aa@WfVNodvH;)qoi#h2x2vHtk@R#3 zCKWaS0d6OPk}FJ_Wke#TZ>?XXKmpJRL*b`u=yLG?3Uv)-aU&(frisT&(jA{Xpkp>! zt{4M8u)k!tl7_sMTZIZk+Jt%>;Lb*JQAcA;N+eKm;Tk?jRTQvQNa7@}GPX_{Keb0f zg)7li#VuD;)npOoOK4@ZN^nN@0A#Lu$f(&f#CG#s7R?se2^YrLi&{FhNrp3=R*75D zYQ+%T@KgKbt)hZBcuFLTP$RYip-R03Ya&#n@TxY7D2az40O}R zfIG!lm3&chGi6VARcd^RzHX{48FY`UEA$4@jh$`_thKS~2-8aBfJu)*eoKN?Y8tfD zb!x11ql0coxqGPNMGf8KnwX&A@*1PFHi|lSId;m}%#+85o8OF~q>@1F<84)NghO>? zwNO&8B$uTnFc=z4&UjPr^NzF@)WmDR*gI8F?5Yh(+Hf66Y=-C4E-qT=D={>#rzvfJ z8BnLwV!-Qf|DP>z+oMPM$@t}X$7Q$KjXNc@#?haAKQ;gTktD46q}PVzYLUFt-lj9q zQTA&;w>ybKYcjD`PPQkgCnTfNPDEi<3jDqpRx_z4DLu4f0NerVoxwyU9^9!$r1_bn zWej68W1_}!Ou(YOGjSP$$;gTyZmj6)6iYibtk-nO>$k;iI7jAe|>zOy&-hJ$5ez}~X=^v1>08`IMl zLEpvczbzW~H2}VL?ONY6*K91Ib_TVVRMwdo1;?4a(ch1}pLjQ)+u!?DqWRgEyO#iG zJ8t>u#Sc0e0DrVRjBxzTPwy1SQNU&tHu(HDNYF-@0d$}#U?@yjGpSa=;7Yj3SLY8? z$c~0N5ODJ7U=uwHh^@jatbz@Jo9Q0(`HUFP`ax#9YH*9`2o{X|3Yg|8q*NLz&tg7m z{vTQA^V8;i$MG1OfH5%vj0bkg4;y07U>6TJ5c+_h)M?UmL!k=E*rCEM&0N(=U{pn& zmJ8CfC?XR>XpMxF95`|4+D1wwnp8b?yJffTFW6zH-ge*T_5M0ZqlHK|_G2SU*7JVe zpU?Y8$PNSF)xQu8gzSAt=r9_)s%k>y%?zYNHENLxVD#+wvrL+$dS>|S5IA~TAsmXK zRMI4OLbCnx%WN%2EwBVwxm>j^$S(f9 zK0Cqmu>fNlM*+Fr-!Uq{idZ@vFU)$k?gQ6#3S`h;*W#SZ-!PF_ z0@v)F%pqD@D6iL;FbeDwqUHN{yhbAqHXE>Jv?oSY%{V#3fBQ##mYz3!yrXn1#ZF;D zf}4_*RXHNEqdAP$PPn4BhMA3Zg)>i7>RR=()UB+~cs?R#97Y5-SKzNa%^zD|Ti2UU zC@1TMYzyP@I#mlw3YqcNeIMIuR zHJ7a&tbcoh!Ei@#b#Q;u)f8STHYqC}?7@(NSW&`C7}?%$!Z@;A!O z3d7D9BWMT1FEgP(jeW6o-33s(xw6Zo6bUv4{8{;@JK)KeNtJF}{J!JL`)g@-Eq;Ug zF0Ekng;t$cxL!rWpRW2<-5dBJrOUU}!$9k6!3 z!0;6%W~l~As_Dsvh5iROKKkve{P!gVzS#9%_Y-kX*zf4PZc#JMJEii-UqWUY}-{1XmB2xoDI;97;}-}v$0Km71FG2nk*HrzIHe`f1`ro~R4Edgao2EkRGYT?0HKIt=p=xFHJ zA=57>;KjfqXc~|#E6@T0FSd059f54SItp3s2DJSRw%@atEvogGO5t|LZ37|jwfpnc zs7u3|jRqvRind7a9F2a?44V3dXtzAT2CS>Kkc`4LVklYhx-JGI#Cb;0g^=NJjY5Xg z%${>O#bVV$IT?U+EPF$zb0v~Gm`Fo|iGv1Lb4q+BY{O7jL01OHHD=DFQkF>VC>2f* zx~*_NRgyAV%(zrY?G>;ZC5-DjjWqtEJo9T}u-NtP*^x$h6KV`LnwxUk{sgm^HEyDtT4M_4|SH*)5eP%jG66)b~lYg8o||uAuqb>Oas4gV+dx^xYYn>D4_7Aqb?2TEh|BD3f7vH+M7@g|r+fBc z41kM8S76kswm-P%fD5%!^c5Rmxs$|)JBycIJgP&)o6F96)ajx(hBSj7XogV^>D`M$ zTIXeIE`pUltt~Q8$3*~}T9+Mt$?#GYy+xOmp+ZDuWIlIAaXrw#{o(HZ!8Z@Tc(C=y z+jkLChkGUaGxCc9!LIm1`Q83|#?4%q?#(w{bM#3@X=7^shA;D_S zb@I;B-G?6*d(k#YjPs{PUL-`HQf`M@bzMo)_{#RScF9PTVUhD67#e?g`SRuc{oSu0 zfBWsDt+mRV-gmRZrTe=hE7aPLU)|5#{P_G-*ZJ7_SgebmuD2g;yF3iL5E#FD_3=r} zyHitLzlgOhwY6RQa!w)6$CkQc44_;0h58tiw@1bwo`@MUUYeQ$ ze$T)DD`UFn-hKPTiId4xDbVgW?%&_q`ts4^Z=UWS?4B7x$E}!a#ZyaVZP0t2IF3_K zH?v#$@cyaY{n5F_Ul#IfyYtj6ZD0TKKYw;R;Q#*kn#<7BExNKO;Edl-p>Z_~KRZ0kF z!RPMiqOze8Vm0$9Yf+UYbw|~qgp`?5U;1t=$_eb%OTGbuWp9G=F0l6!G>3PL``Vr5ET^h!Sc)xsL;omql&O35 zqa81u^?1}Mad<=NS4^5ckz&7b=*QD)XJ{N{jOErd@hS<@4XE@1h7u>dPydL4x`T@J1>0qlkE`W5YPjqG|Am+FBfDz1RZ4HQ`w5DjS4v&}lqD-IIHfy=!JdIU;<5yI=H6sSG9-g>A+GK|hJI#DP1t?HwvMy9Jff z>?#)^qwv%L2d%p62HHaDA=M8xjm2&pEu)k0UJ7fyjeCikU<=XtVG^xU!vV>-hK8DA zt^rMqC8l-*al`8J!eswD#vu-#8W?XqxP5mmj#-x2y+X^%B>rS9MOQjSr=PEZHDPYT zZ&^{#vI>{Qf0c*D-yLv?l||JzC=0qdfObsyMH|xA)*H`Btz5nR&W>a}ca#NDMsyJU;Qc)MGt63C%yJq z$Vw5R8j+N3W$-%o&MP7;_%TCgbuzfLjs;DlRTOLh{Lx3R)Dgbi313`#ulpNUhNK1W zsDc~Sn&1Rkr(92OQ?fk&KdP?oC#^gUD<~gAv7oS`6y-w>ik}gY!6Pzi8)y14bk(l2 z*#?j`Zgm_To08eYi!o`|C3a(tX`7JLi)Jo5N#nLjn`kvVH#7f2|Ax8Rq?_#hzR&Z6 zw%b?==N!={#^*fm`+T5HFow+MpD1h2q2W(uMCJBkXgNr$wjg3w3~?2K^fx_$ufDl) zaBy~ZdVc)k#qREgws`3J`oi6BZ>?V$Top#z+#0EHG7U%a>mOG~0I-6;W;2-V*Jt<| zoO=rzewG-&wTdg$`S}^^L5%XO+ijyqSLg4U@6BV z2CrS4`qH`iVE6vf@%gLM)0dUXjl_-cL%G@5^DXV=Ai~b2W1|56=fdQiWm_(ME`=HL3{_E@@FgSO~RpP?KeGI0dRnq#>y?uo4L;972Mr zf40!7WKn=?C_0{?{ivSd9GE;e7_bPg?{x}#@@OjMa6s)Wq_!TM*coxs4~!jfeX20P z^kz4nQ~`hvI663AT+Ll0hsJJ9^BqmQ)rsgj933FXCNg5Y9n3@}^*O4kv8RXa5IzFE$m z8}SpNlCY3?1-xbJI-;G0#x{}qa^Q?qqn5@dh*qtD){ua5$SMzz(d>spEpo2q zj*faVTN$N%#*scYCy^WLAw)uNp`@Xlfg?yyf`KMcm7ohcCOs;I8eBQEIX$faSw0gT z4J<#zyH0OxZk`ctEeu?46Sn#|YDQS5p3Jc7 zxDVd~(nk6a>a}q^gmo*TIA}cr!}KbJ6z0<4yOUK#v|V*10W_6P+0J?-uUh1)r08nK zqYCw)I(oQvLIqZG{9Nl>`kokGMgL(HTgeHvN&{=D_|E(PK^*WWEi5SFn?8EA zz$b|fa9xg_RlwWH3S95HPD)Javlh~^3C_@E2WwJ>*qmR{Hck=50eBr^(;yv2bJx2^ zZ!dX2RY4CanmjoK=1Vuy_3ojng}7~J@Du6PNBI>{86#-psdC&-_`)iVYJwhHv;m_L z(3gWTH^%yfKrS|_3_pl>WNkwX<7xyyQWGsW%(Sda;fcg|iOMs<+}Cf8cOE=l^H_?( zj*c%cU%h#AaBya7WTq7eJEH8kty4`0=r)8ascmB8+Zi4=x6aE$^N9Zp@DGm@2iR@L ze^{M@#YpHeKK}S-BCt0a2()#drDpzGH$VS7A;yBTcb|U8Qb6QZftMex3;xz|1iiX` z<)-s2(bMzihbTIPzlhDmKHqH22e6OjaycRXa)TlNU*FymCj;m_VjA?@t|!OF;Hx{8 zOM#wfUm_fcEe8areX;OwKl}qOr2oE82w`8E_4x#VHPvKfG&=reVbd$-&rU}z?W(C> zQC?`Fjaew6jc6`(AbJD6Nf<#Fu|-CRv?FUMqEOIakzd$ZY<(R?1ar^>40}=$CgNIg zA<7AhLU3t7BK0+}{uh0O_2@rJ6{*Flr@lD_NwkwrV0n%xEN80TiG~JFm>+{NQxlzH zJY@mV8_;JBG(>tibjI#CA`pzShF+jCbXSoA=FS*9_eSCc&YcBZ<@GP|xID(?AS7A9 zR)%ocFpc&H2jUnjt08oM+^<+KQYe)odH|bSe><9x;;!I!946tQDR?M|3oCH@cH9<( zLd!;|MeSg`{g4}A#8Ubpp29<1NUa=p;R3%Ptdbd zSKfT7#8L#F87#&u2hdD?7UVU;)!VcPFQ&F1YGL-TwIzfSx~R1g8G3RR@U_v+z+U09 zO)Ys`1Aq>p6IB2lehdwtB*!4NTGXO~%jm1i(~Xp86d#tr$hgwnA?|9SDc zEe(1t9UEayPwEhBdAK{)`pRVixoHTlGG*wG!D}^5Ku{BsOf1yPtP0*jQii5;FRX#| zB0y42u*dcB&CTQ{y}X;xp=q85Qqzcp&(i5|N~+N`!a`^|LIGk1O%q9--;0NL0xXo^ zsv2?Ex`qX_Cki!~2O%O_W_sgjsFM}Hlw4IkzQgvP?bKC$!CA6m!5sX0z11teP_+!T zkPgAgHW{8U4hg+z3KvasdQ z_?vF;+*}N0NEk1(3JG9*dtvsY1?q3!4@p@7XCz1Cy6fHDjHLW*=Nf}XJ`^&145XB! z=39=_GzZBOK80{Ol3{cUsp4CVZ+&W%tcrt?#^DP?g0;tJ%J4D^8~85Es4MbS1amh+ zjg~_2$3I=T{P&x;*4Njk5c){i`DmhAh^}BtE*sQNA7MrN%Y|4LV6mxhG_X)6JhIQrGC9$*zm74sSO}`ww|J6?E zb)^#a-N_fvU%f~OYR3XgzS#TUen1e%fByY0KDr`s=6agFLwbPIlyv~C3It+-U z#J>X07DLK{=3&mFnN->ED|Wv{)ki2FkBbdXN0G=(I^4h_LV@Cf!yylkX+UzY5h>LR z?G;Q&&IY7I7gD`)n9WELR1^xot@2>xaUh{XP#4Op2pF&*n&)0bWFZDCl8Q&@`|a=L z=vmIFu{1gv{J{caDSN?*BSBu)U+DJ>X-4+dAwU>$8gVs+hW6Qy)Mo)~|DnI2!k^>q z{_R89gl+BpC`N(;E8Y*Hi<&_bs(pikvq1sYU|gUTplfQk1ziHq9qmGn; zmw?!I+Zc>SLWP5JJ;1euA_f84b`%ZTT>mU}*-Ew!7s`QM@cMQzL0Uco^XD-ay}uYq zo0yk{j)qc6B}aF;#^l3QXE5@{jNy}L{Y50D#R%D{+r5agUnFa&awAsw3UNg!0y+ha zE7nCf`iw%0XhL!$@yZH0mcTRBBy?I>k;H)-a$&u0H@R`X#l4bmAvA05Mhz`=g1q}H zZvMK$s(3M)$H^#Cfgn?{?#sn2YZD^eB7_+@tM+MIYxDuHJ=X<*qva3=%-HzituzRg z{>RnX^|X1IVYqx{*ici0ZSmpa8UuD>FmZzu@Qm>w(qKzcqBb3xgfO9u4v!|I3hGo& zkfKJBBV{N`BSlLO&<;{5idt!v(qw9WLDgTd^BqlEe!-sWeoWGgkN|$)*ESL2_WeBf zhheteR@!;O@|a5u(m>}-`erP4a}0G>dftnL8E6xU1wMm&X-F`e)_Kkx1DfXzpyw5E zsf=l&G>qELV^pHVaGrAwbf-#`0ejhkTX{=-WLCWM%c(H}K&~2hWt(icUGiBoa_gfC zCu6`jVcbTODSt2kw&(MZ_4B5YK-d835)G*!o9qJSKd8G=%N$@ zy(ke@!zSG4RwSP%=N(q_?jqJfk>ftsb-CVZQH6toS}%R@g|EXn4qQig?TLMZ?9klz zTt^oBW{)DKxg5T#Ewk=Bp>l;jnS=XKO`|1qTI_D9&PLGHEMlupd`G&ge4k`kv+^Y+ z0A%OC0{KQ6VM5#AM4#)T`S7ff1?}|r=aqz!ugHR)cFwB-^re+X7S_lYKe7b=`3Txi znqEjx{w;R;R_Vqgu=&f5>5VvUA%WlbMN%X)9%Q%Yj1F!J>1+|-~N@Z!8!uwLUMKC zkEOF5F?7a-wEe3G?-9{;`7-T@8yg;VnJvu3>*Bz!EF-Ym;CLbabwN>H;BmaL@wB_? z!R`--_fN;m?*)I?F%*4P-iR+yLh<&Cf7{!O{~XL@3+2o9g24fJsaaY3Ej~zYSE^w1 zdIM|i^YwPQc%_GCj?6LI>6j|x3vMDri(k(eg_YN_WcV7ox1^wFZIeT^{)U_Hp}9h( zWnkM}MA8)|-EuwDN>xKBOzNcc&+DTh)i5-LbCe&2Ja5vj;VZ3q6?8Sa#%y{m6sGk^ zCSZhCkX>W80$!CesCI+U7d&b77K>7cDil;!h}yaTST`QvJ$f0A4GhXG+;4bEQYFQNKyH6W_W&|2VmAi+ zccp3W7`S_ExBGLYJB#{ubnht@%P@GL`>tK~miH6h6&sd8NhEj|FOn?8_Lp;T9DuECoGTQubc7sBLYu2MT>DYau8w6%7WLd#GA(GeBi(+_Rh_Vt+XxSZ#wL zQ+w2-dYh<0xN;SO2EcYtDe8Z#Q4OM;m=85h|2sPn?cb4W$XuBE*AytWA)(Vvt@-KdJEhth59Ft&x|7FJv>OP%T$- zRZ9qBsDH43Qih2@qwcs;!TUG$Rjz%u9ALL8QY2N7!@9qFRBuAK^3cH9+~AX&*7%zU-OzPkHsGHTsVX5E@S0s zP93vvs`9XwiP1X21En5Tt~~BN+S|&^tKK7D<+{135&L`;2u&0vQs_mcI7>~HI2u|r z2|_*Ds^I+W~EyKeeb6s2hJ$A5SkOlcn@7u&y&C+izxpA-#U zh83<38Awqx45Ymrpe! zsJ7LQww{AepK?fl z_mju=R0=0gkDdF=HG|kLaokU@U+`v!_^OhtRt|n>bx- zuGY|(Mb$2}`dg@Jt=Lp-CG$$~32DpFn^GO8G8bsqu>famO+tW?p_p!ZxH3BPC>)76& z2TUIGHsAr}Mf0g$-!1c!nt@5Z>bR?JK@Yz|O5M@F_l_i7YDC(F_YNrL8FP{GWia=Q z!l1j)Fp6eA{ddFQUG!RSb=&*ynRj*v-dJyICgeF7Y!9?}fuILlMGZuQ0i`)ZcZrtl z31Z1yjv6FKmkm^-!5;h2Cf*xmv>a_y7~3182MCZUa`;IEZeRYyLr#%Xjp}Pz1vvva=YhS88AK}KH#G<^s7d~ z$o_s@qUUKZW0-Dq{qp|VPe1tKAr`{DX zf3lyXyC69nFRWZhHJEaj1MI~c<(c{nI%72vm9v-1H$G`lU_)uc)6hX-Wn|^iZ$7wY zygAYZx!!L1W`-2WvVgEqE)*`TMLy7Y+K$gnY`^(9uGMz7&a#_LFW+ZeX<(}`-MTxO z3!>#jan*;(3R}p|WRHLI^zdM{e4IfwIVDsiF4$dd7zWQ=_}A%=hO>1wKPBV$_ixqO zm)3*cvhMntW?F8-au|`ZVRV-U26fLhEg{ot*DTUVF{Q!5(7LhSFl5%Cc&TOGxN>uo zmmh^;wz38p7Wf8ISchUyZj&y12*Q% z_7Q8pv%s*i-Ptkbxt{f$y$zT$z$Jb|0avN`0~}QG+gP%C$Fem15=hB>IBp27^&*aC zv)qwRF$hkldmpltgypI|rU7r8#11LWvSp*raC_C^e+e4Y|45%oU%=#}ed}RSDTGYU87b z`Yu6IVmSF z$hPP~Rbj1yGB*UBp(R?p*WuYa97JCQ$zbXa0$ja=OU4uiD{N~~4TeB`zjq=z*2?Vc ziPXuXcEd0{QuZnPMDkK|W>8gvM=~5a_g5F`QIM6(AIf;QDp}b+0PlNzCwg+Se?#7C z*fE!I*T}Ir875ID!`cRSXuW#pxC{8mj1?-M}Zn)%K{(^9bWjcY7F?VKdB=; z&7gR)T=@3qA3q&=dgtJMj9bQlIm0a0>y?}b$k>G}=zF<(Z6q+bwLdHjH0)`i;2C1=kkPyOcG(&>fAkqe)E@-qk6OM7qp(;#~d3@qs*m)2gTPMz57I3W_g zH-B^Ddz{OoM+JkptMot&(`7GVSWyPa8Va_ykhW3iIYC)5NMECqX?0hMy<`07H;N%C zDK*=^BUyVJ28{Q)FSg!ijJ6vXzP=8=Mjl0Co@3S76H$7GS_ucFPJ5Xu^X1jBz6La%U7d;Gy&QpUsJLfbIo?`MlO(F+%M@Dp~cc=j#oI1CofM~B8 zG&H7>5I83PSpm@hF>*XdO(FG1x|$;j+HO6VRTm*XEW5yd85pBJLxDlvtX7XaCu?dh zJH3q3Oj)58e`mAIg$dw5be?7PH%n@k{Wp~LMg~@Tf#Ouk*e^clvE{f1!)VubG`^e~ z@@gX^$SN`#Q${5em|W=8a;o=l@ZDaIe-_TRwcyL3*Pi#V-A;+=rig`(_rAfh(nMNR z7?ztB{q^xL*Cay^v5_>?Zd26o#>9{@<_=8G#%$GXB&##sfn@&;)21FX8ce-WgjS;% zJeY&bhY_GrsA~$$=Lkiw_9xeq6FwU>+wEFUt`_w>YxW(=Gm#y}k&VPM1UC2{HlkcK zU}l%e7(w)2JxXeBR1{fhTE$|lAoEqOE_u2h1)hyZlgyz_OT=b%Jrpo>@#{|hQWPZG zbpQY$07*naREJ$ez)Gdjz|Yn2e#1h}A)582pjB*WT{tizNtiVAWpbqzW(i~q>Jr8@ zD@081s~)ftw3-Hql~(JbM#1U>lrsuS9MCsB{LrYGu^8h(bL>H54t33Es^sG?v7R*OY2g&&+xQ7Hi zu5qsfVZfBQWY?Da-R|rzXP@qld+HU^@|7z}-B6{GCbAwfnN-Zxq6bB5E*u7MaP$ZH zsDJ2pcD(3gS?>=H`<2EOhv^X?dVW$_TB-;n7o*=HQ*yLs&*Iemu1{}}5TbakYLa^2 zDk}07F4gK4C2$DVm5b$i_{N4*?P|X|7Zyd4dA(}&suqy73Ow#k>1y)u-5WQKxbM*% z*xk@ePw$pbhdV|1o5RLIRsFIB{NqpdfEAKuT>0Q!wl{w6tKLIB_3@b(_5)go26aWw zMDMxFIVaCUZaA=?T*wN&5V&g^kJk&pxW2UKO4~g%`^C{A&Ko z{PwX1{h2gqJXla_2 z@?jZL?XK>Qs+D&IQp^KZ^U8weV7^2Rp;mx38os|QV7;`2RBWgV@XmYu<9wJxb#w2+ zl8=UsBLC{;in6SD?XP=*WRUcv-}ijfgDy${A9>7YSH8HW`LP)C$x}D~@#o2vyMNm3 z*hI8mvbX%pt&b3^OPMXGshujUZ9V_}(&mZHwjl*#q zv9DA<$WoFK-T`Fl?y0aO$wRQFW~ULA=`5Vy(GHSAp&9!Ue|2uo;CU7@+&w)j_xthXizBZEl0m_6EJOY7IS{7y_5mj=Wf^ zCwkLuEf1&LZyWNa)d);3R!5Wy1q04L?9Qq-io}ND!+lENrQ2vEXV-?4QR-=6!jUi? zFv3#saD-_tI&=>zfEm7oz7LyXeenE3!yW>oy3BN7KBi*w5_XAX9 z3H&?KGCH4))f#QUHHhaKKa4|4gZSDsiV%_xJ z;6ko}A1eqF&9GsjDg8MSFbHNjxs_`r_O;~9-jsp$%&n(quPAw0ag@m;kJZss*poDp zil>wtO6$A*K7>`9VAw!7e#JSovM0SR0g9XS@v)D2`$Olmx*Wz?&lMl-_iPN;xS^*i z?*(v`92wfCkJ^Rx0GM=g+~>eP<#iV|*^;_i^hj!Wc6D5PM>0z%-87bT1zKxHdh-o| zt!^uG(z7~bjvnX5#yt`1**oD5@KGY=3tM+@eZ6)kxck1=kTy0>m)^|3x$cRlG z;gpAMS&_whFMzjv*@OGOXBX0!4U07%KDnfo-IsW|^0eEp9e!}~NP%WzeCfB(je%x% z88ENdse#eZvuoddFn{UDhh;>0?Ag_qV{%}5*7GmB4>OtV4>4-n^X!Bo^WoO>cTaV6 zY;M~7om{#we{=3xX}j#_3wFX_{5r1@xBV^rVfQ1lsdr2E*HOa%UCPUgwWiJJU3>5v z*t@GpFApLaW!WrzOk-I=l{4mzn`Y^G>nh5McOh9rM9ua z7HqNS$gi~#BGghkKwOy}MPzl+tf34cRY6fMCbJoCCLwExCXFFF2^U_w$wb{m6PTUs zT+P+S?7y_{=lLGcU4N9eoE}O7efqrb^TP#eplv4I$`Etqs)o!ibt7b~Ra$5k#2g%g z>~j0JV}YP~rKQDjURJ#fsuL~p65FLqmu!+3n9C-aevR$YL}<5QyI^YzVk=|134_;! zD*(nP9Cl%q$ev%ogj!-P-{?Yf1papB=%g=FQvC*>-RTM4fc^}pH9?3-OWk#GhZv~FeTSx_5NJd4Px zxf#*3k|&$D7$4hx9l4Iq?6-!vxsEpoq~Wq#L~x*+;%YqZx)hK+H*bj^$9vC<2@g^>NjeUuF9 zeM6CaD6+U1iP}NYWB|TS8XZfat!gA|%I(#{crnJ1ItiUlrZk>L6CLqV5$UJ%Njp;t z6O%!#k=c->TXhE0iuA}w>&Zn!Zzyry&SZG$b2Ozg#&a7U{1>qoCBj%MW#eG028fH` z*7xmv_SsqegC0PqEVG&Y%#sTAfCM%pTaQsyRV4qg_xw#%SRN|qR)sCBjC{t49l4KY{uDu z7ZzM{rL!y%#&P!K_V4cm0_Zy*h0up8=;Jpc2M$UrfN&pUCgfaAHVqZ6;^Nys{`)%4WV#n>JSGDFSP)l+9GXC~Gk?LB+@%e$Xm|FC`G z!cUb;6OvF*ZxHVCB+V2$Xso|&Ei2-w(or>u3%50)#3CvSXHgrQ z;HGfk9ZldIPOQ*bm(s(G2B;vUju0+acJi3q*=Yq&ozzi?TvFpSF@`S?t0$U z+pBtpu8z;x`~tkONK4ExI0O_o8LooKF)A3uf};^v@(c1V#!^(YGLHtJ8C*x)w3-36 z-B~x7jj9+p70X9aQ|Dz#Vi28d7#bsr24T@|C6R3zJ4Q9FJn3k35&j&lr6PV3DOX*( ztbDEN8wIAykQXzKuvaZ34Ebu(V3jSf5n~R7K?;=vfV?1C;EWOr;YA!*W3X>Z`BrOAv|X-~ z7{Xsu{AG z8PbhAU$En}tO7lqT}T3NRU)B|7PQYoL7lQ|R>i_d zn2-2yk8HiIL0)yM%f%`N_9O6BVbw)}s$2AC(1T63I{T3%K!ZBlO^!w@!LTY z!~4hS)N*3)tYll`dk>>|+2-pFqqb`eeiTJ?_vz=%r}$)@8U}#4<|h#z+S^PoT21-+ zjh|01JgYxFxzRox-X32djpOv_`ud~wxxTyWqen~N58r*4xvVnavj)6pl>|Mh#B0;4KlmaTDqB0@AJF&D1I|U_A^gW?QU!c*N zN<4dliI@ra>OcN?;@lxH1Hg$ro)%wKdDDoMZ{L3X`90iB5?P;^xfgrcZUorPtf!_P zY&>ICYv04)yDLus&D*0-wr?E&lM!G&$^R z*xvS2FQO$a9us!KEvmY4WVlI%znV?Ag$yoRR@9V)B}u#87%7u&Ev4{}ZFc2fSFfs0 zut_YLfil`=_P$|Zbchazwpg$mZXxFiJZA@dRc2py!Hk%HO90CyDY#Y;Ws!RoUctVE zMyo{sZ;6F&8$;zbIIy^JsbmjOA#gbSf>3BYz$G}ZjKGp&Ak71e&I(yEmBx;dH8Voac6P<>Bw47g z0k7Oi&Cemo?qNh><%|<|f!c&*(e3LJDb<4HQn7@~%AagL&)~TW@6or0!TdK09Pfy` zKn{Yk+IxFl97oq@hNA>MQ?NksAVK(Q`Bl9yT-cyFg)%zCK-%syL^XN~x;8@WfrY%x zv7^*Aa2w)lkjjoYspYUy-e|HG(UKQYR+8Ats8Qx*vYr<~PJ+G+xa|=@C_1eaJ|>?{ zaIJ<&%VSpU`D9%hQt#KrD~ux7a0mOs=)5}L2)&H>)l|OWHXi2>J75Sjv;7 z1tl&sx<-Iy*jICFVYbO@>L`w?lL;Wr*K7EO?F@c-2aHUY;kyQfc#@_e$gf^)VmBt7 zd3wj6W(Yl)ez-YiFkYRuyZv-|+ORUs|FmJ|{@_C&uw66y?CnsKh=r*vb+iWta|sl~ zt8qXXK5yEEonb$3PjJwvl=mv_Z~Eyqd)OM`U+A(ofrD;2g5*WTLgl_#B|Ov7r)q4|OVwH2l2vHU|%t+g_x z!3(M(L<)`IOH$~c=l=(QKf&P>FMp_9M|Z^tI_Nk$ebVWnC;!ie1lx6?Sx>L^ZnYQI zT_NH1y}?vUwmIG|MjKu-DwA&{TJxw4^JDz@HtdHLM<4GR^R-5U4|V&ExNvZK^6l8a zClXBu8ynvkrk=fg^3;{PkJhg|`Y&1M_S5ElhjEM#*oM)7c_}z9U`%Y+<~Z!6b+B;^ zBhWQz+R)08T0zDT0hgepN>pjwM2gx)Mnb4+B1Ib)y(&^wwNfYLFl{&6Wz~Oa-_P?i z&8CG2?ANbf4kCH{e810O`@ONjR}A=z!7KAKSI$j~{My?&#aH5CG63FvC47F>gyewu za>woHOBFAGE-L#4i<4mRnpUKWqlC?Yuj)~dA7~AYF#MRlzGTzTC=VA-Q2Co!`|i?j z`<&mXwpg30?fl+b`0JMsj=%rz#~07P`R3`-j~_5OmOu-X-TC&2K3!?Rl0PlA0NC)g zHd~uY9kFMXpNS%bFkRK zj(Bx;XVwsV_e{{A`^$|R?|ihh^e%Ghj=m25w#|0T_D#**p`kIE&leL#L)Z%TB(7Lt z6uzk+Ofs=tDW9O@T9ft4&N$w?di2)Ezq=iJiJH99JozM9JbHLgHQe>f`s??paL@+~ zllJRxS00vn2<_$u;rrcqdhMiZJx-M6{J$H1a5jw7*UsM9=vHb+x5UoUZ*Aa2dhA!@ zuv#3tOTIuDE{mFrY%JthT(L)7*znkAzzh5a0!E+%q+t>IT+&n;k#q@yd=p_bQ)_I! z0j+w4#CCjAUZk7368Tp&{z?JuVz7)D=Srh#d+@QHlBRu7>MPyK$q`%thjTgA45kb2 z!3mNyMss9x~;;hiiDQ9o#y9ETbYVG9O+hZt)QX&*ew8FnCE*k?Ko36ATQ zoWP+`RVok?O*|!AV0^yBQ5q4Be@z%xFLBYMgh6XQJ=A&Du=h{BFj{SSJL7Towkm8e z91Wel-+4B4cAvm30yk7=sPqjlg%5ZCot0`{F{L?kuf>e#5wS-kF zhvvA0E~s+FX|B3ltfhJu+!RX`%`otEfwaj;mi=zb3r4bsnC#Z=^<>c7vVRL+-EP;nB8T?M@eqMw&>pAh zBo$0$51voYpMPuoZzIpP7Y^Q(x_SB2?ekaf7zl5FI{&K*S~9G2dVE^=EBO@~=;`Tm zE{gKj|H+^^c)9PR*b7*zIu$lqi9#|dMJhLCHY%cS25raa^s6-GLXuor;3E%DrM&6( z!G^wQvC0qLX9wJ;=H02C-S@*UufFkSc@6IT##%l(_V@Q!X93tnr_@?{wv7zCDc*QI z)hC*|=m31_;(MBSSL6Xssz10mka+m#8cXEUY>(P%TU#3dT&qoeaQueBAtT^17YtH7 z$uD1xE%q4#ueRJ!wVl4#SMPPa_WC`0-s)?stEU@huz&Z!h<`#25{afWJ}V_NQQ2h9 zP9vct*@j(GL*{ifc|Aw*Db|qH< zygjUYT^Oa$?~7s^x@P=THHA7#HWEwXc1}Xh1wHopWho9*lH}`7Q?>-A_NZjZc&z{$ zyzUM^X@9Kd!EOO-K$~IukPJwTFcU!8noVzXKbAWw5Fo5F4d`-y$&p?RN2EUE^DRk@ zW!#pILSwm)Cj%veVCK&%0Jis~fMPaoVnj-RW#o4vH)-rQhZhO3En(zEa+P*nNRz4_ z%(2l;Pqt>y+7=h6NNOppj0%U0*7%0>R!12=(^8X-8Ee+M*mG@hIs^T)#MDkpZ9r>WI2fr%*I~b@7@OjC zd(6&`xD+jR$kBQbmh9Do2FdG@EbO8C zP>>prjnp%#YETQds&Q7Fm*3(8sZvT)WuE=5eK1IGMCgN12h*c116yOul*L6@uG$l_ z#+WHc%A}Y*S2gy{_NOucY9`a);GSR@UTauc?a$7s6@f`}qu-rAP9n7-t%3UZ_#?71 z1?U;OX-86z8Vh%~=41hOIg@VXY}d0t&&I2f2H09%?_bDP8z46|PjGJ}S6k0AjVkVC zyWF#?KzZ)s_vc*9^NgdbgQsl@tWF1=H>_-`F4ZETabA)BYDIN^uISHcr)O4N z@Z_M|t+vv#1gTxpS-Z(K7(U|;5(C*Kr_#)I)Lb*JvqAmDgG$MCQ*llnoL>>9YR}6P zTjj(qajUf}h9u9=(9@s}1!=z=TVB!kNx~Iad|jjH8P}Es?^Rrf!nOFGhn3P{UzF&v zef}4hS{u?=9Jr;#>U;2@?1=2!tuScHjy|z>1Jla`KVLs8zoNj?tu{ghbqo}}V~woe ze*5V{J(Xe7>`{TeWxs0PGlUF5#QqF^vf0R?x25~lL#zWS{k~^eC_8o`x?QBOZ9TbL)Q>z_)&t zL*Kf*`cd?G<;3lHD-!z>`<#@{s?2hiwCAxzQz1}>uPAKG1k`J9I zj=`eW*2-T_bvWm5jScYb?Tbg+B@-rjg3al8=@jkcOo_( z`IjF4aWh$NHp$H(En~BY4C=#|>30p?PmM^m***hOhrhQkK9v&6UOMCvPubUJka-lI zU0o$NtFKmrC)e8A?imEPNf_P1>i`n6+!c3^%lUkMQ{JS_iW(Q0G1H5@OcV#RY5NKM zp;&HKP6W02&2r+7_wn0cI_x*5>U*$qa01V^K$zIF|* z6+>x3e!CA?HY{%s`22w|#$lf;UAWmpBG!i7zU>=u-0l)hz+_UER8JT%_UkKk-=vYj zaM*=R1`Ku8n1mBJU}V<_vk}_TL;%-OdeZJZo=8tpwosxGsWh3JD3l1MoJg1crF6=4 zfgG%f$&wLYvY`vP0>N21=FZY#L5X$Cef-K*5V~=+GO!dvIYC|U=unyxB>1#)u%N94 z`hZ6}WilG-WD_jS)xMo<9Cwu94O)L0OZRpX482e9!VqCtA$1|`$7x3jsTUX^?(Gbz z{iri^A0?L2+mU$Z2oH|f^W$uJbxvGVSvV|tGsfQ$I|;)uMkQp{_<{|5?~DG9U;#Ep zY;R}U{83d?MuY9qYb0RF3mglpc!4uAFxfh%a-MPOlmlSHTRIRkGAYICDdWvC&)9J=O90k?s5<|jrtdtC3oY1! z>#o)|GJ4du2tE1*Iw%XQv{+r%dh^SUdFv&&0OPP3Y;NNcVo(8fg#Z8`07*naR5E@s zF*6M&J!9q)68D2YX|lL2(Zo|DG1=|E*!?Z{dOY8sDreM|_R~+%kUl@p*X#L3+!*F- zNZe*=ykfW-+cM0JjxV;viw*6OVBuO~maVCDMoq4E-*~a1VJl}R+eGcm;x@B*8USu% zA2tAO8(Gd}V&j{qA<|G>*zs1G-UOqsWsRKCF~?+XD&JQK7YJ=9ro^~Sh}U9{>9(Qu z{Vh8wEPNBno?G0cg#!Om#;z$Ab1Nj4u)!XG;);?b!fIS?G`b9QD6yX?dPN9Yy>?3p zm4cW zSQ5!@Ea^yzuH_?EXJECcw8^4pJ`yhLB0$4r*I{f#x8X=MZ_4Vpp$;Uukla?6qZ3%0 zSOgROjFPNKoTVtS6GJZ@>B94o;?lD#uLaNtZr|4qxZ-soxh3%2l!2-S%~MOiKe+n) zz1IMIata%;ih%!g;odJN9?v<^)?SV>Z2NIX@fVcYy@PY!E+eI2upj=F^a^%hVX>|% z4StDt4X(Uv40!4J@Rh=|z3V@oG*B%bzc6dR&fBlq+4=zh{&uK{=vjm3s;7sZk`DTk z0r2Gm0no2k!Ive%YCThFFA6KAM(nFdx8vE-Pj?ZQaqU6Z!mfRL;6D?A?WM-oaPxZ_7J7Pm zUtlom?e!TE#f?PD72YMHuzaD5IE4p7zK|j~!htnc2W*JWc~lG>3i$a;0&64Lsz?&} zqS?aq8wv%eAtV|)6gJ#eN;K$tC+r^sb65T0JBG&uWraKyG+9`NwPWEB`BvmiQiP-w z4tr+80Cwz-(cUnPM`UA-!JESq`ilDBf*+m>UoJ4FF3k8b8qMS<{HqhUjo)HU(o-WN z2F9y6lHj+Xta=Oc2&-r)OyTp@9NGYPMvT_rwlE?GlA^E3iRNHBkX$q+rGqyK5oJ1m?UAF~oCEsXzm4#jA++maAOQNrHep$8i|vl#@b;k|!&;wj4fZ?W z>mBF|MEU~8Y?({La}8~w#twDa6Z3FHG}-NieRfPxtQqu1krh;J5{*d#PoCAM<*-ko zT9Frsv6{`ay+hNRU-KaqjW+Fr37iE^?IWq9#Y+#>PW*txOvSgWl<3Fh3yPiEREp;wgUZ`^82 zU3Zk&Wn3mFLNaAR%X%aN2ynWguGcV_aBAWqDUFYK^@Ols$+Da>N?i;~LoTw)d4;4Z z#$KCnWki}-E0YQUFDj;apYgVv8l#b}YHlq0UF@otfzE_ii0GusMK_0jW#|>uV%4oG z6w4`~i(cTC5f1^Xoiks*kT6 zm^^pmD7`wu>!X)MdoOtlV579EJDRKh_SHRmaM1PJi zEGO;HDAm8t{fi1q4&MbQyi%VK3{WHL%5L&s!1KcHGVn|pk_(N>CY@&bv->qKc@j!G zIr-j=3r0lIc*X4{mHO;gip!8jYr3|v@#lx5MkSX4z549Hw0i;%Q?0h~#v`IFN}w6G zqU`eS@@~9dKmL4p(lY`BzlNL$pf_rhA78t$t8zuKQPEvkhd+IK^zflWv^yLl19Ms) zsJHEfd>6HvvnkgU-F58D*~j`1*i|QRHojc);;u1Z8JL$oEmbIAR9Z)+PL7zd?D%Je zvp>G^u7UBFA3m&5nv`7LE&Y7`W-9<*_9&$)Kyk0(uYI=q)HoLiT@3grB=iYt!-PGD zLcr}B+?W1_wHLj;p#kZm={}P6ml!R7NbQB8Fo=qT%dj{c81M%IjIdEngVA9~aEOiX z8eZWw(PKq%U=5xR8OiNg)jfOEsBV}b4y9nthYM;+VoNMh7UHV0u{>@hEJ=6JIji$% z!XO&I(rSL*j|!ScQxr4U0fk?gLNhaFU5wBwPcSq{ODME)SnNtOW4FnuBwJE|eVY`@ z8CbDGDN}{i1jU3TcTC*Q?*OnnSb}HrJK7N&5ZkG69`)yEG>DcB2{fkUcclLt2Fg2z z!y`Y@k5otzMCk&djr#7S27ek%^@GY7g$WKL-@ZNg-Jr)`2c3y`P^lavXt3U~ z8yS7yG3fni2L;z~ziT`?>XM+1@4lt}Uk2DGhKEPC(OnG=Z&ON0Rq)8*(G!OV3GW+F z_mTZ*M5saP zuf&#^Dq#lGK`FGFuGo;w4r8_$fw`r{Fq&47v=Lhl)J)sX#Rn5%Tw0qkm`(%E!4>;( zTZsglR4z4D`4B}09eL7hQnu8}bjbd|0TRTJ$&lJkOWzEsf1U9dZejV5%D`Dvt%qeL z!~%beaU-^Y#H23%vg-2Ip`qZe~eGG(K% zo2O%$E#f&A8B4c_+Cl@?9v|N#?P`;RF3uTiv)bib%H<5pw^WHNX&6&-#?Qf4S<7nU z?Jd4BAQ)|T5M_63>;5Ydmbal*FCSB8z-ixwQ%HVw#AR+YoJNX`uCo*gf{W5;iPOGH z-Ej52G8Xars)8=P5X*)mw64T($jgLGxOFk?lpsuviW|-a)lhqqmd!;8r4kS{90K?OoM%1%1KXQC$*UO5m?DqSc#}a4P7_ zubA)q2V_{D2+Nf(9Ph4yPwK0w{g*HIU+y0eVI7xLdTy@%Xz}LtN4L6`rF*%)PQ*23 zr`2AProU6ZJQbR(r2Co*W{pOD{PYL=GU_zxbnFWB%coQ4EGxU%p7xX;Gb4e?+d_DvSdiC3yW;_^NWA^;h%RuuPogB>yNPG>~g&n z-@EZ;TFlo6lU1Q_DB#?^;T~hZsv`VPAfTv9Ce!3ZD}}>nSiEN7Y)Bkn0~|o(Y*5~N z(YP%ZB&wA{WOE?fQmaECbf-6jm^o~R(42%CYrY4yRR|rHk1C{|wY7O9R^TeY9HM<8 z>{m0=Jd7Ci)mVs*2EPvSYXj`RqrtO`!4wr1aQ*UEcx--xGT_y`_QJ9T7YO5+SjD15 zKGwW_k)Kxxbe_fq7yg_tj7&_B0IjydnUn!6Yu|$Ek6^M!cz5!7C0@yqG_smUh&7}8 z0%65cqP)Ua^gpW3@29Ce4dc>MpoKx9wgJoXtH5C?Kde$6nNk|Wk!E2;JL7bWgd)q< zrK3hNAzpB4G=@nCF*7D4;{}-uCNZNXYl5Dr^1(GCKt-m6NKIP0vF3dGb+?{BaV!uCM1tD$qJ=g(YcLGyjfDP?8an!i;cqY)N`_=fVqzT)x-~Hy;;0l{ z@&jvT4M3A)S(2Iyz$H#P=s-DyEDIws>6U|o6di`Qp$XJJgiB706^S}C6AR#w?@a=H zQ8q`zLh3=+JPg))=&r+HFwP_rvIxjxzN~s;Lvw<(4oawD;K<}-#mJ>5eLAd?L!-C* zMme*C0$&0?vPm??VV1ZW?5;yN88N#s{R#j~@`qxy)bLQrs&)wsjZ4OyT;KL!wZnAY ztPg{c>qxJ>VdYQS0dJkT^%F0S;<=g+qxtdS?uohW6s!_1#5&0CkfabvFrO3sO0^Pn~u;Xcq^f-eA#jH+)Vzml9n`_IPYa zmp@qoe?a2PXP-asQ4L`~N~|{3EeM7$v=txy@4=%VJ}qN7?L+Q`w#C^FJiuB8_wRik zEye8JR_4uXC|i=!-+mHGUi5%V#t1>`#M}^1!<&~JSJuYiWGw!szxb}(FyZ>uy2t%g z9Q8T$-8r|jvvZ~JVFYb21<}lsoi|SK= z&Z-MIr<6tY|8C{DCuiu34r&SDT~%i=xHM^OQ0v{?KQn|y=2E-MYC94HlRbI!cZbe7 z7buI`_Jrfp~iQEQi(x4k;=w1a zGgK`dIgZJAo*Q|qOb{mNE)jz~tJJMqFYeZVeZ2mR1Y2X%GAEM-Vt>r7&5e!SF#z_n zKW3&Uc5_O0PGyYcZjrl9REJbo?8sBP6ksbYDOL{yXhZ9BL!bTU+C_Wh#n0aQzF`3P zM=zjVuH-dFT5BSzUSDv{N0M0upvMbDUD=(+V72PSr4*2AxnYGhG3H*QyI^CR-mS3xmn@R4YdK)A+<>SykdX3Q94;ehys*%B8Fuy}onrXBspu=BoE!Zctqh%CYU5jHwAQeD1O6)p+)d=Orp`L1435^;pVY*# zQFlH;mX;zs62}Y$jpfz^8`w_-4TLcxg&fI+)iQpjpD@C#SrDwmEO53#CSg%y!7m=A zkVtOOz%!yM;Re*y8bNEjEE+BIuVO5tA(U78RfZ_rCzatdYg~=#a0`d*Q!I>l3xlv{ z{D9y}`^-wJ;7}f>3f87rB^L9dhOH%L(3p^**U98|vRt*#JViY!iW(VeK$5org46l5!@|+>p;cDOckayJy|YVg}A8 z!Qg5(zn)FzjUXdY&R1Z!9t9HHKy5e<)_TK9X4sV~30Fp{lT5lR2Bfqi#?>m}+S)yd z!d&hqFQn|14erayk|y6rmF{uxi{CFCrA)bMBjsz*h~N}b4nzxS$3PiJr=6A8p9HHg zP|IRx6qel%nU=nP(NqgE& zyrU>np7Iqxj(cqeq|M?+>R>_xm!fZ{FPt z-P`3Gx`X%P;h6q!(8&^oVMzZC`6T?YJoF*8+eRP zx4A|%|^tpCdjR{Q2l?B-& zLTayUCvbgw+I2iQ2*z)G?fHETi!np#OYY{$Oy=SB`ueYFH#~XP7_VXb+}zlmwXw0e zvAH|;TjS^YdIB`hPXD|E+NM@lb6bj>NEuyJAZZW6sNqsf` z?SF4H{H^DH%Z**TFj@L->sBiD>ftZRU}QlN9QKh3yA6blrrKwyeZWGCYgYong_aso zTw$JmOa*u^8TL6e^FC za7E~b(c#TH!7@(ax>GLo`G^`bWUkZh*R?hDB3BlNty6Lq>6FHU?L>*6kyR=EN(s@8 zBx1FS=(Y-1f08AsTZZ67_XhlTBT<()0VoTd6L4dL=R|kwiN<66r&GrO&4vE*{s@F3 zDhH0pmlS}y!e4b#k@C1F$gw zxrhm7!*2u~27|N_r*fUO2E|nPEs&_THO~5qjtTKz$L3PyR%bu3T@L_t=NtWh; z)jYkf*oh&ZV$6B(V9;?=8XTVNdvVYI+6P|q-jl)gYtG_EFAet9j$U`+4@g z<^6aZp_hT~x>v~$Qyh`6mJQS^O7t4c#*J?iBzMMcNsZtcgI|GGet!%D|*TWS-QgD zf|E)KBMaiBT?M&y{eq*k^Enm#Mu$S$T??p2Dc$aOJaqXwt#%jpp>_smGB(64IxA6E zQ!!om6C~A4onj+4!+sVeLN1jGrUkF+TtEe_8{oT(PS? z`Coo3;cWxpj<&X=2&}e6KW&mhbMZmbUjcX?1y=u}Ve{*2H#a{U`HGn|KHzw%9MgrQ zb}qbW=@ARL+U$xe&W=^=s*&It20)>5ObP4uQ}D&R{^DWe;m+>ii-GO$=i7^IS0KMo zVEg*_{1F3w|6WEUWk9njo>wJs@${6j;l+nDN3eVQ_NPW*{hPWl1(#4bbr6R< z*=K;fr6M78Myb9Gb7uLEa#)Gv34$v3L6MCer@*--_Q6Y&km#j%H;>EYJL7c8W8JU& zR^1+zb#hO~n@jaN4EP$&y)&^#3^dxNT*vE67?YIW!D{x7x090sOCU$WV;@4~p3H^R z!+*>;8JE6@+#0(Z-@*Tz+M4aLtAWYf5|3N$Seo5>JSNH2nfjAp@7j!UUUIqaeEH?o zyH~HzP5b%N?32fm_o;8d$&}$=W=ly|nJp@gVEwbs_`8}i%I?nK#dVxJ_1&w`jlLz3fYR7e&eoe<$o7}h52$h;)c z3E7iSH{(?*fy7T}ULYzOv2)USfAf?V<_&i@OQlVuScF37OZJ%$(+ivjfEhVgO3a+Y z*}Q$O#WUO6X+=P9t9}7n zQiiT1!*mz_{AD~&r30OWCpj&nn2q%CWICHx$pVOOpqjO>T6$Q&(K`4g8ZEM-CkG}c zGemD_B7M?uHcoMpVQ}0ovI8!KL%CST3{3+@eg~ntQ5;Fp;9yEp0p`&fC`Wn6hA=vX z3=23mU`DiM@9E&iLERXWpJ|X?uQXVmr(8?c!;(9rpC&;IO|%i+7&MMeb;M9vSkhp>5dm8>i{coJGPT!o6Bol zmC$KJcv6W-01`m$ztbvQMMX`h;F4N| zyGz)T?4)kDu%otyoUvS`PIG_#mb6nEZa=^z#7A-D>M115c01L+IF4CG7m8k=p24DX zC!w7#w77) z&o1RriYy3`lWFI@1^chp&cXWXQDp7e_& z40y(`Eo{VcyVGwnZ~Wu;mfA7t9Z+0(JIrv{wB$n4_j`J3B3B4`9FtPhNvdlg&7At? z+h%h&^5~mp^W#V7i~+A*{`0O7cvmod>2L&X4`#xto{jphZOpqq;0>a&7VfPa#ofdC zvw}E2Y<=t0M6lU%xvW~=&N#!~ajCEnAvYS!56dbaoSIrz#)Y~Hr<@76qaP7VFFPsp z{%?PVjYyMZy8p8O0;4-JH!%_3|6HS9u=C2w-1+Ot-6>IM${hAD{$j-+PS34enY(!N z8X#(S3QOMt*XsC`$Lphev-Bxp9TL=^K0SB6vX3unt5Ju%J}h@WGl+!B*KeJpWcWRV zSHy74UAgh$@lQWJaiX-DNEJrXbFS9mylDINo43l+V?&^YwLt%LSt_z}N9t$gj*OSp zI9%`4>x~OjAE*ED?B2!4Uky+0mmBqZofwZP09b(=_FB3wKX4Gh)B+ccRVcbXh!@G3 zdL@HaR}y)YJq2F%dVydv%97W<_W~iwn!|y_I$mIEeUpihoJ+~|UNi|x6C%y-cM!X; zpFU})7@pdxPm_k(vj39OLH92g$%Kr)hQ4{}u) z7QncGg~Vi)B8fIc4H%ytL?Ug!@Ir3)`){(cqR`xk#L-$EJ53g~4xtn!)Y=J0rJG90 zIUMrvBt=*WQ^er4rQR|mZxcSvD4C;JC%3!cdCChECC5^vrQAw%$fW%7oqClbsG((6 zDgw{oZ#NPvMvN_bksT2WifCenq&qMR8Jqh377>B`#Uc|yVXz1$RS?}SCF-#vp@GC= zbUdmZ_&I|5OEgkMewyG)fJImxx&)xzT8lBAQy6j>G=QvAOJ~3K~!QRhVt|ucMDf@ zdNaY0y!g6B;D{a7FMRNPM)_A7%}%(G$yHVEIiT89YGc@`xzT<>OG_- ztyaIyF&B0<1HR<8!Q?_O%#(w41b|0fTf^v?@OKNN-xOY` zxM9Hn7&5CZ2~8!jE?MgK6nAe0G4FW@A0l3qV+OIv7h`JojHPln-!#{5brXBd>a$bt zZ#CCuwnTk*-5C0Jm;Qb*g8uQ&U+o8+0gSdM$GS@Kg8YtMPd14=->SO zV&RqaMilE|6dIpqgX-d+8(XfNp{)E1IPSEpJxpa;%1%wQHb&{xX>4^w6dBeoe|JM8 z=+l1x;Pvn;A{&jAqS)$;FF(Kjp13jdX+vORx%i4ZQx6*##_#_Av{tm7XaM~AyeZ+nSi2-0LSYK*S@;Aa>cEZ6~!?96V^S&x0%{_A_oJX(2w%go?WKa>1i7MM4twze8mdN*JXq|U|G zmQnLtJIUSMza0N)_};Y(ori3Sry7^{?mvnI75W^tS5a~(*L%iv+ya>SF$D|s8)5x@ z8W2>_S91{qyllq(tBf<`^WqbC zW-$CDknAOl4hO>upX?dXlK-pVa_Y#YQaFCGYs*&VAg7z+M z&gRK`-pncyYcsJ~A__XM>2yB4smXJ=qH%Ods9RzSj4Qa5uhfh|S6KQIjwPG#_bh^I z@M2An1+SHCNl>dTt{`_?)ks8DW-4TBh|wAX$FU|6t&!FodRuB}C(t6%Dz1`3XfUH_ zyC4E9W2l>npUhHy%80_;ds zg-L*}z0^bvkOxy5H={?1<)RP(EsPa44KZkYgjh;Gt;lKZc0I1eL?8O8R;qy1OZgpY zX0iizung~zgV~mj%h1*jknVae8^4t@#7h~!1(mz~KJ#eRAogQ@uTA1~p>M|vo%NGu z(q79Wqq3jtw+kTP60>Vfp}R#D4lluLTjWxWNI$)#^=|Rh$kq0PkrpH4Rv(+O!LCv3 zZoegAm&>{2n(=$WfT=$QqRA2=3RCcqyK<&Vz4Qda_+D~FbL6%bdxm9%1Geh3yIUv))E4t4eCT-8JMFcXUf?vRVl z(%4(w3e2N79PLH)EGDd0LbWSxY&2y#b{UmI@t;Id9&rH^Mfu|SFI~I_O$(}J@U2J- z^LKvu@rNTL=uwx`F*^Rio6(tTBj4)4g@wHWPxF}4H5A?I>6x#okYZLnx;wGw2e))bX~uD*bqiSbvtE6MA;$# zCF|^dn>?&A-q^7lf7Fn?xJn$?#xb>Byd+I)!*Gd{QZ!;jMY;&&X{+Lpf+;CwWm{Bf zxj{ljQzm5y0a7%$K)YBaRD!fgflY9;+iBW=wDWt;8`f?qO&q_kKUyq5e$IJ5mKhI& zsZCV}bAVQ(8$Wr^T}EmnoW9!HR>)Re@g7DdZ=Kn9Km%w4S^N6rgCnITF<6FkXK$W= z&xg+(ot}Q<;aRVRs7p>o@&}PrrP=1W(Z7#e5sQ{>$*Ajeu#H}fa^sR0G|`l}On&5} z%=?&-Uf+i^>dcwbw?02q`m9}YXx(mvr4G_SpZw%I`=mh!F~QF?4CXgCFEWZobHx}s ze{ohAyxA-@wf%Oz*R$uP{8!H(?|d=4;Hz%Co9&y|5{#N7t5KzIFm%SvJCuB3Z>Yv_ z17pF9(px17-=LMj05nSU)i9BhL|d&gQeO0mLP~*+9xu}RI}lkEkb}!f9US7g%t?{^ zisXm_)vMfv0WOPT7Q14_G%m0V&a^awUiHwc%p&nunMzAXXe-o)co5FpI&4H4lTpT? zwo%c7*Z_9$9w;m>Y$y!gqQ;sWR6QXot0__|D;0Vf=pw|GG&xn7SSf`43yR%<30J~- z^yHl>KsYz?52>Zqd1QdRk(!dK8E|I(TevfkTPegPgD!X&Wv)>%!aF5VmXTqSuo{h# z!iKMX@faCfPECTDjHXo-TmX!7Ir)`X=8mWgSfLvDfyuurj3aL5irm41#L;luC#j8; z)K=@cl#iz=Bs{o2@~5~L0k5yih(w|#c+G@5H;xNfeZYHp(fij^>*KFQ*!J={ZOAyP zy*$uBOO3@c*u_^7{gj-F*@-aNAQI}Vq9kU^5lNtvo?^)zDndG@Zeeu{$Fi{HsC>jp zy%CYeA=q{ElHEZx5D`|gbc}SYnCg@4tg;zLQEV+Ni| zGC*;iOaR_ zZdQ!fc`<3x->uCjC}h0;XQX9iIg;&Re)-+#n8K~b zI-OSqMNU*bS);f&H!jZ1y;MrG^I_rMn6G?09!2Re90qNOyoS{Y9qoRd({jTxPr2-f zdC%-cZ#f7XPXFc98*j^gj(={ucdd!F0X)jMi=jBNn>MI0O z!vbLtUE5w5?i_`NMb|ic0|PE3*I}W{QaHz$uZ#u1WI><$ehlT_B>EI8=o_=g&iywD zi&lnX9l7GO~6(579em+&ODMJq|C5CG?w z@d^`DAvth<^NX8Tlrt$2meJU&8 zf9IpnnglhrKl>jOu_dbyeF)3#P{~!_Y@WLvoA&+h$rFl~y!zuqd2%A_hoqU}si|ym zIsfUSkpl#8>^rbeNzg|hE+c97@p69qk6z29`iB!IPd}{_gw1^j`z5F@m72@T_CzGZ zBK?bJ!x05^X$xGRy}(ZVTUwDWmNq|aUsx#p?bh!TFOv6h3Go(c3}rE#723O|lr|v& zCY5rCazX>g=%5R$0B9KTi;VnBsx4wz9T_6rYKRea#3j>_sJAl=4`md9wK|jux$zJN zBvld)47f2^0UUPKs``->J~^O7tU=!cBYz%T89WT_HL&$`=#~PYGc9!%O7^@mI85?Y z>t1E0GF-V=X{mIfH8EubxIrAW1kNoxhlDJCLtVx6xrN}0Q0Pf?T9Ye{6(r7NZ&WIG zWDiDJh4yNyfqHsEkbAj^IlId*esB{^0n!%)$oB`;Ac_1*Kmj9h{7o zBx(VJSJh3Turgq#{FxU>l=*Wc>7L*uf9oo@6rh65nn`n3;4iQk#{&A501ElCww~D%r&K*_^(*@fo~RsAB;tu+J4-&Kj)f)iJj zs%3=s1<9C3nAbuIoq${$qO<7j)7YLc+P$VQuwFGQ@t5isnPJ=WH9ovs)@WXd9JQ_8 z^0n_4#AfNe?YxwDNpVr3uU6t>^$1EbHKVE`&4Y{SJtABTWl|l{(~feUiQ6bjy`>X7 zGvVY|AschdqdQVm1DGIXM|>8dJTunZf9cYfZxz*zr1(g0Cl+3c`WDl^@zqS3D>`ml zmfOg!!CpEzBiVCWSsZiX@vM5&*ppnIm6kVnCcOmC&v+&!+<0ydLhYd)X%@hoHn;Tb z{2nKKWdaVj!22FPY-^MI_Nxr&V{{XastxIfJ7D9x7?J)ue)?DEfBHtDe|FTD!jIkz zqFuU4%E@jJ$d|_qN6B%XA(u$Tx~`Z==)-C(*-glU7jyyOxsSK69etzx7*ad>PN={- zA}0J5u3BP;p=E?ujU|oKthrV>`^-pR$)C{%T&M!-N ze`oXU*^5ne6xJC*Yx_&IF@h^*)85WtOi)cgYG-g{q)sXS`HxN8q!2FrC&0I{(f!nTtT*EB5V7;h7fA1Y}D4R1ZrQHZSCl{o#XY zw;zQh_)2iwnCnIG5#mZ(hLS<@%}<~GVjlpE3L2z7__XA$60Erux=z+nH!}heE-5`y*|5O5Nr?jEv934CmAJI^Wa+5 zeVtO#@cv5TLR3yqrqB28+Z*iaBGlDr>iq$TPNcO6EQ|UY?;RMhTMi?fR;n~AX@lqc znN{hqNSH*RHSG0B8AjBrk%7g5MI*TkrXzTeSo0dtW(FgiGpy>tRW!{5!x~51x0a%x z^+gip;EG)}Xt+9j5B6KJlkd^Z&_a`S7;$uK>ae!J#(QZ%BGQWRNiwpG0{ftO3Mj6S z+c71ZZ-Xu*?7=LB4PEVPf^oDWuqus)2T_8YiosGGH2)BcB^)-YJ5|U{ZUD9l+MtNA zQE;r~BC%Py4WCZ$#dBm!(g?;cbgA+e-G1NQg-A|fwRCQ2C=!xI)40BaCkWyFE{8E&lC5JT!98Hp+y8pW1g zSi)yApaZ7aF>g>Z(Co@*?1m+Rr-9o6#byNxzeE7$H`6JSOe1S%O{UdyRz<@xg-Hhr zxa_Kt3AP)A{~=4sS1NO;#t#j7|9nZDI=f;^YaSWl7&f|+WxMg;aZOx1t@Q=yc<;QK6+A2 zv;IY##p!En$9aVQ76WKxV8)@V*?D8w=(EIT`-#Mw(lQNldj{WISe*&bw7aV*oU>NV z*6jbTZ>#MB=eESWzBe<1CQdBzp8d1(OHA!&YbEMbVw?2&vp4P4ps2Srm;(k;+B1i*bXf)Jha8dNck2{-eF0=X(s4A0hTRc8mh& z@$pI(_wW`io$xcT#DdT4ovaO# zu-?AC_pr0H;$tpNgcJgwLWH&W!@~RYjX@Z+kHR;<9R0TR+;Ek)UzWaNjK&~ImMolP ztgLJ-(LT9_4Ql6`_>UB;K_&;HEg0hb2HseEmK$e^5@3y<)_{27*2UX*<~gT1Zvb9+ zdgCxi{4ybx2D39)X8!gJm?TxYFuxbR;IDwe;IFM?ovp@Y|^wQ|1A&r=g0Y`t_nAOxAgue0PMc>S% zSG*8CQi<>eqxigp-Wmj~sf<{?3{1BxvjlO2TIjA6&LMx1G+YOE`Wxd)VO2F4 z1iwixt4e9vfY$)opnUxx`9?Wd2()^SN5qW*<7I5a$ru?Nlnm25XlyqS4ij97t*Eiy zu$w*O$&K}q9x>3#sY$gJve)%RSW^bnjmM42hF}@xl=_d1Ggp;|WrVg@Rbad9v{Ns>v)oS9x^O%+_e$% zYkZKxVL+Xu2sl@lzzWp8?*Xo!N`P7J+D(i|c4unai{1xP?MOr6$BIT z0U(px@kwgiaQSR1bvC7x4glD27dLk-k$fGDMaV`2e0jeXOQ@MLp|LZxR(s#jvOK}; zFk}rD3szW%G}3nGazu$75s9doOeRtMU%ZluPG?%)W@~Q$Z?fFXnfnuK~#0+G3m;G$1Xh;b;ZND%;Z11*9 zANO~Q|0wn6GNpb7ix3&r-Cc>Pjr@{i9Y-r2pOYAi@*8XWKHb9A(tRU2F8^%}qaR7qIJI=-seZByk+ns8yw*>{aaEtT?$>#87F zb7wcOmWo*_=#Jydj?w-mM^ML2hqDt-VC~y{+{9R*>_RXm$k(vPv?80E*EauiN^0t? z$gToES}H7*OGzxYb8N-EEs#E%P3Gu~?(eo-7XHHC!R#z!7}zGb)H4{;rNt8PV6z zow$DV;AQ@>;+HcV_A?0$mqmCJX=DoQWB3n2TB{6tEM(#=au_aUT$ZcdRiuo8ZeKny zT)uqAr@xK^|2;bxLBDAG-L(Vd3Or zfyiTGj+?3=K<%p@`ljj#nmcmB`ZnJACV033NUa&H&NGKzJE?-gyq;mNF*-<^B6e!# z;y?emvsTzxRD^OqfB9(4jeFs^w`OLxuKs#*hl#EM+U!wyRCDPCEV{R5ww4doR4lo1 zW!_&Ds0;kSg9LrOa{f%y1vDFZB}dXtp%?QzPrki0^!d=xsC>W|wx*u5 zNhVXPkiUNY*_F@5e_cHFt@;skzoN!t$G2$!=3T&A5AB0g;sJ zBkRbooG~eB@QWatUWS9ldRYBO#(IHT1KlvGS9Al13A=LQ=w9zJMkX9dsss*CI~Q=T zN;SijS{EpBpbPkaR0Siwno{)DlzhK_Nw6{D>bUDgnlwNj$Mrj1^+4S!+Nym*u*iQ# zq*Yf`w4LBpJ(r6`3dgV^ajGsJTt$aPq9ix&=cJ2vF&$BA8pfF{kBbrG`yC#K3`fVw zZua~Hj+ETM!%h^Pi*859pv%g+GN2t-P&7xB2R-&3e&A0C=}?>&O@rI?Eu>QST^`5S z_L%w?sA5PR2Y>AYtKjXi?SB&${mIxz!S$HJ(2zabJFU<`l3O7NvHFn?Vq(KUEyHJf z50~bjldslt<-xIt;?|5IXA%L3?y_A`lK6)cvJz|e8{!HSat%vqyVG|CYpP9aL&9H= zL2MJsxP(8ai+1H&MO*Fm#-hyXbdVxCo-jg-^ok&lgmWUHQEa+4>C4X6Y| zj(^3nB|M zb1zEv4j_);3d<5|s|?nqa$lI9DaZT$vOP-%LQRf{-B>Mu@$9mwEH>O@uuR{cJK@J+ zbYw7c(`46iRO<}bt706Tu&UFkbq4k$2Y{Lm*F=yzik{5+xf}}DxaZ8q%8*1oCI2si zs!r|I!nJFgn-`v|Imx(jZNfJqIRw{i*}03!Y<6iO&gLue6gZxB?M@w8lU)yzW6g3M zPq-y-7MU{&XvAABXF(E)c7f8Ek7~*aX*qISYqfs)%X@py=7$XU=INg(V{qKokKu5% zcJbWOz2A$V@2(6ID^L8qfA!JVKO8xD7BF-u=Zk zKM-RHg})rS^662Y5%LDBR<@pEqjChX>SfXSw35G}#^4>6rhsl!t|j#o#S$q01rvzODSFAXVdYtY^>lloa`Nu*X&ksWB6*9wdOdayP6 zu6V(oI(R5c(T>~QKG4c~R4?hm!dCdqjw+#)9kQ4&JjGDtRMGAcS`jaj%wfR1GpmKO z+LSAmHB~b#76{?sRX+dzQ9G@m$&jM3B#kkYWu$1|?4T~HMr9&Y2FC&s3@A!sz$P3R z!5PeBjVv>zUOxy2wHvk%%R%jVjVY_KK_QnccVo#B?7qmkqW``_S5BWVzA zBw1tTK%fyE2{d}^Z*V0^`b-`rOJPM)_T&Lh+8>WG02|6qan7U`#u$%`50jFmAS`3W zR1fwhRZ7^KZcs;PXzcau#&n}GKwG2AQ*r^5i&eMZUfu5W?8K^~D(z2CeGHQ{|5hm+ z^z*Rzv5yOQ-`lUt{#$ixVDc+-!_%}ZeCJU|D5~svxqVj2-f-Qs<8{Y%#|faso)m@m z(u3sDY&4uw5Oj{Rh2i0P3Ut0tkrD>qVW)hCJ2P13OeJBZTx$~B+$i!aRSvo$!knlr zZ4KC&Xe5*%%gM8%#|?DPj*-lPXe*UF{*hX)w95~~UIz!sq$6Qj)eKUDK?PC*waHLY z;w(efpvx}}X>+WQN?~$D!Y!Abg|O>@xA-B0+k`Ak>J^rkn6nj{MS}ElLSyEbYcG@} zE9MNsVg{j1QJqS5*&<3q(!w*o>rFb8dspuFC3)?QcqGtBMA^)Z=7I2({9E zCg=T9dDq~#%cGRYL1dTu-3b}d!n@3iUoGB#a$+Luyxed z4ZRa?zN}VW1y(AULuninF6qj-l>B%~a2kb{3zE*hYgX#`!O%(qY3aG_E1bV+1o+y` z^Ghv%Y0T`p_J6j{?x(H84CBQIQ-3fgjMofS9OSxVBR4G9rRXK9PD z!zc<}Lf39lF1SIe)(b~MQ`8_;3m4o~s#q#5Qd*?srgzh}e`)XUc~3y=CINxtV?%^F zkDvE_K5`yEtvt(|i@Su1d38iIr5T&iyt!W)mduz%q4PepZhBFJ%8y|3U@I%;e$T!F z)V-om)knhfnfy{NRA@C9bp8xtq1FHZAOJ~3K~%y0pWyBx86Nm{w}G(v_2gOWU!n2r z(*Nv$rInt&H9q`kYiqas&UYupnP>OTXB2QF`9o2w6toX^jcth(%OVg2S-_b;13i0r zsfl4=;|F4`mW;|a4N@1HLd^r}mU)B`2_&%so0S|F6QS*Vpe&-5svYjom5F(EwrSzZ!;(*nhwFjr|yN zUDnK0G~AhE&P+RF?J)I{Bh>GSIvC{aOFdk9pK(1CK(o2%1p>HbnBo(9) zT^ZrE6F}Y`lCbPpFSxt{`ZA9u4;oc8YAm9iVaCRMd!M8`9UQ~;Fc}&iT&Ewnm-?fQ ztVyavqL!hzRH_^Coxtd8M@tI7vU4k)O0Sl^(`hm) zK$$=+II!Iv9du!{N(N;C(48LH#CinDl~w6+K@#Yy0cKUUBl54Ro<6ClNrPXKH`E=x zx#<9{-oX)RsF+6&ZVuX8ABN$P6MgKC`vymnU-cz7NuIQGkydd?x~rr&DI`Z&@(v=s zQeWYT(IM3ysfj@v>EwwAqrbGTMu(JpWoM0!4ju1H9w!)j^aQsZe=v#&E1)u(7#4C_ z?3EQ&z?5JaEnZx)gNycQhQWq1#iIgPO;rN*BqcoURKOZdh%MX2q$lxG5go*3!FI)w zeIV@<=tNclTM4%ZFB*m$7{;Wjj%Hq0KcEbaM*Tc72_<1g9ZcD!ozF0fA#)8*Q zZ`s%JR=dr-JKLTT#Vt+|BQlj~lgW7=E{@&`#AessHV!^X#)FKd?KNJfwBFf2>21CJ z-Y7_<I3X`Z1GC%Bp4Vt+y7q+ zBG4>Z1LOyRgjO&?!gnm6e$P~S@7vG5_zS643tmR(MkM?A`)~*R@Shq%qj?@z8E0f?7wiaYU;9AA(i175l>$v5mLc(zdOg*7Qcw5l zV7jN1?$py&G|-%e$taaFp4;Jgi4q2xkLnXXhQ=8@-RV?I6O<#BCQ2pM63UR&s}riF zQmLY$wCa8<)F_a=K{T}9N>w?6D}}1Y)di!lm5Qdx+5m5|2(FHJBca_^VmGY9BhYn( zVe{WSjiV2bFvY(~ZXSGGF!*NS`#5QjNdfSn>XV4aO3H&IH*fNR)L5vlC{BXA5}Ae6 ziXNn|47KqZB?skL>ht+CeGH<(^e_OheGgQjH2Rf+^QL{R42}m5(@9zx!0e%+H+p#W zl#1A|EYd>{2d}hN)JsW_+9J5zL*7+HeTASj`Dcq%2s5a**L3!dZW^(lstb{B;U!)a zFcVG5vniog;V2AR5RPUVC9_?SVp3}nZ5eO{5?7|qu;mUWo{F+=1aWPEsS-}Ki1TpS zH2lHt2}{l($kOUK&bjP<6J$vjrHziaGVN9-D;n)R!bMQjQ>QaU6+(bw#f;0HqElg3 zFTsIXm~cG%g5Z4eLD&j|m4eSnmb5CnnUrpNvh_*a{mPT=^V{b$YniF|`8MT=ZS9}4 z88DY{Ou7`~#TV`Dq%+wfs;{_Y%~@DEXE zs(-qFIhR)oC16N;qlUwvXx>|Y^I=+snt#1WK@uni%gW{uq17bXs~nbC+2&kAbwx_9 zT$osycW;xH!pgZ)+%wc$y$n$6<`;hw{(k)at_ZP@ottVV1P5Q`6?dhdBER$s302NB zukt9J;n-e=C~($$erCx7v$X2%_h5~tgx7R3%y@tY4=YL5f;_*_;4p$i)ryd8Z$tV& zGiYPL`&(mh-rFvPK6&fp8CPT7nr%LO_{aYmL7$mbNc72*ze_yd{o)|?EL<5sGin=T z-BuSI?pze)DqVvM7}a57Pra6hyTXE5;=FTU$|J*&?s9jzCJir<%aA_K1Tqqv9inw{zG;cxHHyF1tb_|m< z>z{8mG!GvhTfVI5YvL!DS%&Lp7_J#}E;HHIyx!+7hq?xaK{}dZ`lqsmh#G=}h>RzZG-O$gbS`%e0z9DvD`?E@8$K?vL_;f` z&@Qv2bi~q8gJN7q3!%V!B>J1FdXIT9KyhV2Pn~sncQUYv5}P*8qDO zZ!gbX3yL+$z&NutHH8DDB-xoZK!Ql{k z9(N2A-N7c z(}7AwSedj48<$y2OVeoubt*TNqV|GHSrny_B87|GO^TXUYHkuKyIC&#KkfZJ@8_hA zhT0VS`)mlfe!k~@pF^uMD z5=|>R+Qn5g`Dy{{CZ%5apcpl@w&7>~=j^zTgU7uWm@)I@9~nR!0RMGh>r|K_DS|CM zmYRieAT`v2uv~k?d(m>oi(}^g%$$4 z8VjouaxFvU$NO&43GK1Ug7%M2QRw;&g0L7rFO$|hbNZ*9bH{Sx*6KBnzpT~v3eDM1 z?thTDGBOl;oltbi)U@AuU<7o}h&jPkR5##VYTmoex;QcN8}C=LBbp_EZN2|Iz4WbOSTVN5^k zV0+BOo_gJ7D}3fxDNC!$yM?)}?4xaak^m7TXnLR?~2ndJSkfVrhWMt98~5aUh3MXr7lBaJ4$ZH#ZvCl z&6Ia6{kAMu69Z$mxaAg*ZU+oHKPFjHvh9*WxY+N)YI)|1<(9a*os73x5hHN%n*cR^ ziV9WIg9!lR&(}|`_G%K;WF+wFgOTJ)pOu_XgB{#(lzev zRV510(m4cGUg_)4qZzSO)%M`kP0yBIZJhf40Qw6AC!U#!yN(=QCZAS{nn$rW6PpRGpB~jY9zCK6bm7QxWS!-+0&7`8C0k8{u=X_7x zXczz+IK7g@aoGX*q|)p4-8$p_g6bn&SZI9x#s4W|5C?v%^xk{#+&U8y;vX)ui%ENX zm@?y3St2EbeVXju=l?Irg2%D6U9ZN{*Pou*{M&Zy*24SWE$kM!1vvoXI*oh6V09i*%P_fAZ`OAT zb*Zm*Xu~C*62fatlj0wRJd-PB2wtz%Z@eo5lDdvS;FXcSz61NXd~o^lfj$zhMmC`RJQ9QlN?FnAu-j+s`~Ms0tCqlbp)Jx7zuIpH9Cyk{A;AT~>Cb zY8|f4e0XBtW=-ZJ@zY6plb;@rB(7YM3Yu~Cdk?k8UfQ)owc5P_rC_;g?Ar2c4{L?p zrDjbXz+^f%(ONNh-lNT!0LtUZdQDY~!seakagB&-qyM|QgH7;Nsv0J1KYVk&?Ad_s z;YBsYkkOba``WaGG^AE_I*P#>3^wqaB%!Y_0e2%B+0dJ_0c|>Z*Y12K{Fb_lw?{j5 zBbgqg$vukPIc?9P;^6=(*RY$Jf{l%+-qN2D#}PGJt7s3hH4KawzYC&-P_`8cjUvl{ z6;tqC5V(J_b3xh9c#qnQo!JPZkX|&vHC{Z`-v)x)lr@kH4To)e{KoX+^gM_Q{2Chn zSF>qFL~9=mD7WcfD7GDc5oOIwdu7B|4qtUQa7Go!FN0^qSc2Q5e0v(fGh^ui(kjR1 zkBHP5h}-e%*dq^#X25Ldt1PUz%u2k z44v5vBh@-Q>~qrl4E0=enD*$X7i2}q#dQ_04VOzRoF%Q7NDz%hW1T>9EPF}h ze0ahn+CY~#9=oV}o)iHVSgW5fP;jM0TU;X2edx5-BP_Kh3+(-f_o+bfm(Gl-Q;LN+ zO`1oJd(#?1qu;V4Ug_3K%1cQNaW+icl7ve*4d$Wax`~O0+t`_4+AX4ZbKPwus@t)a zvODl7QGA#sC7N`t5|4lcmyDp6?8&+efR(nNGO(pMF(;dGs+;RFvZmYNl2O@GISu4y zvnA2jk|8kL-cotn$aA(#Y!`wog=gBcbhjyx5Qi>HfJ~Bg5y#^jmt0O^}?sdH%EN~%tv;e)`s=H#?=(YWQ7E?Q@z5d^MGTV6C`pPaB9;8mr%+A(+?E`-QB>;c2`uP_PEqxm= z$`~Al3-?!kk-YJO`-Tj7=!4Jh3E1kSR*=YXT-n(%x~U=pgT);>ad!*n5HeSmj@4IK zSM|cu@i~(2I(RcZcg9E$Kml*Py@!J0W z{-00ksuPlt=l7mYxyAzc+Ww!0pGh23IG<(z%M!UBltsf;e*+pQXZxtNe|geEV(bZn(^ocsbY@l*pM| z>4@QF%wwSgWgSI3!{WYapFv~XHIAdnqH==mP5F5cbnML*{}B)yM2s3ek2+9m)Xk$P zP8v2i-{6Tmk>uboNz$qVPAa~`z9r(ZBE$9t2c!K=pOgI?q)$el_tRL||K0Fl2c`71 zEJqMtbkN?;(1ssR=`*^K)XC7+t`{qkfh}NNy)cF9x!o`5oyLPSUu7c<0#|R_N!97a zsp{0!G=eKpVkx0RDlAR2;J2voNqUfquwJ9Z)6@8mq_d(O$vX*Y0WNY_h?~KgG=LHs zbUw=Di$|0;kWtAR`B6MG#vq!I$|9vn?0Mt)_yA2uMWsy|ARpbad!fKcpa(`#Kxa^6 z311%(-{D4}MfzK;E_ z_Vq5w9!zO z3rmZbUC5CKo$f^LrajU_`(UL|M+Ltz79CmxD*NJQjJU7aZr$P$2G7I5Wt4;Ja&5g15Pb=y>0#@g|e$cCi zmX_*WMkp7N3J&VMUA!Iit*@t7`9^qDd{@N{gUVxG@}x>P{xE}{b0F6ecu9rA%7B(F zsqX9Hx##aX05gWZedvo@uM}q1jOpps%vq7sqaOC`)rbCl8|Dwx)2iCgayXL?; zF);f!1NP)+NO0---(S3QMFVTQ=jE6NImT$Cs({t7C+@t(T>)Xq6YZ@Yqu-B|JVI5}*ya3(~kJq-c zOk}g30L>PZUG4Cv`!n;N4!I~{)XX)}&tIH7w|d4t{%lP2+$xh`c<#>4+o@+rmMg;x z*-Gh8$0(q8oB{6u6hQ00?A%U0*&DC9ylY{2v$Ch5ab;rRtNR)o)9pKRk6H)gzt{At z-#_&xU?{mU;0Ea3`1bzA)$?ekg|v$oUO2WQ`ECq<_uGpe0!{YE;?44l?4Cr;m72kR z7E_Tr7fM@u_OINO#aQ2gDnhhj^b>A+9(30Jk4h9Fq5Rq^)wZ7RKNy3ds7z2cUsVm- zr%kXl5Gw{_ai9d6Fd9yVHF^%k^-RTQa27>~(?M>fx(4DkbZfY*{=vXWaS~-#lLY9V z@V|n90e756VJ~zbZ#twdty?r$bQbd1R2iM~Mi~s=n3j)dYU=Tn-B--e zheQ#f;;*K)2S$vga4QL}5>vb0vM`k?E0%*1^vEvBl$q(WFnL!ENV|r!8409G=P-;# z)J#2a0&q6GE$5J4fw*O|IugWi?Dm(92P=Q0pD8ph-~_VhL`E^t2AxQrhZ2`EG9+O~ z8bRm$h?zD0d7>) z4`Xr}LnAesj(P7Yd*nh?jFK=Am8QdZqXv_)wA~oK;>ib?ATy`!(_HOlEh&W>Zx_HvRdyues*Yl@a6ej zDjXaft@|FiuCz>YCndaMSFCmUoq(E9WC4%o{W z*a5%ne0clA=z9a*@T?~vgwj&}N7EW1p;1hW^@fo}M1{_A4T?mP!|t0`GDGU>i{<*Q z&%PR8S-I7IV03m^4EVJU>zAWl2K?{;ek1@U2#Yy1pWt0$BYfq-{LdN~-iV{bhIGdO zSZxe@q%~8x3+vl59tWqZ;7;13#8>?cHI)N_U0ISUJeotJYY$JZQQz?Jz|A%`nZe`M z7GWZ_M(Nx8tMl)^?uM929%c<&yz8FlYr?8dMt%qL&Hm3*##!j6|PvarOjG} zix%ptl8UxzN~-K*QA|d3K5~TkinhYy zM!s0B0>#z7{D$-4yhK{lN9BBRLtZ0h(8Z!XZ%Q_!d{MJyL|DZUa71JbG*=vmOU*FrRU#Vj7SML-E-6kSxKU}cQm^vxRh4KcClfIZhK8qP_+k=H88AXa4U^OHG&ZJK zYa3#U1R29|)UY#+H_GU%5n6D!U}!oipdO3j)h&#*#+Y7@DS6+xZrp%6s!@1b6LR*$ ztpcw}i|fLFTd{CEwQYdg)^&m0Nruh`G)=WrGDzFu4(yR%;RE(8th&OSyPHx(Q7)@; z;T38rtzZ={xr9^6A6)9~#%pkdK@ZN7e5-3r(xJ7%wI|ib>p`hO*kVz&{38R$QmuP1|6ItP~Lh&mJ1>!5SKgt7M_q zn;^Uc+3r~J*lSe)``;_0O5*7CD9aT%Fw=m!l@~j2HU!;$y#&5?`sIRFzgqwDvG!^X zy=)Bl4H@+8ny-ovBWJ&Q{>6oFHqmNLtPMQd4pLE%ic|U(6xUPYphGGV6YEWZxom6# zu0F#l)Uwg5&t{h=PM;pG%s$&cogj$gy~CeYz=sc4UY9Wdz`c|Z(!zifczJfh`;fA~ z{+SKwjjYWZ8bMz@A(IiW4Jey6I#;9e0CqQ?E!7$lT`hRIP>H5OgBW|pIM0#jiXn8P zHoUhmPDV#|>q%8DNQ!l2LVWL*NV(m6g49vaD*Scie^K>g$_@_b^(KN|N2GRn`~C=EM=bRq5`0 zyP9WiHkI|EUI&6N73h}98U)7mOIe z1c$_rlRZ&Q8I6q!D+9Op3ONI1QyRS$-7)&pbZQ$o!EN@4Za4ch{N|KyI2#F(blAZG zZ0BzxGb3Y>eKb1QJhtAasYNbXtW&gjhoWvaw$hA~U-%X<;u>(HWG=stq1NeMLH!0W<7Z#Fuv9kqo>wBM-2l zEq)|yN2+BQg4|;GRb?T}w?C1%a2Z!HpP&7jIzk51hRK&0Pa8U4KEp3Kh^R{ASnmUX zxEbn07#~QP7jRv59O*e`gOL0mS?BiC=3$2M`jmbK>SBzi#BmAWKv`T49ySe*3{9G` zus}*elUbc2W4@8JkqGM6M!nz$sVWylVi9VQDuoMnTct!=q$Zixo9_SG`+MGxwapZc zpN~nv&-c9VbBJ+*#*l>R36)uiFi0$A;wet*WLFCmnT3J?@2~OSa7p90gd}>Rzv==} z`e{n+I3W#}T_;qxgJ#j1(t)*ckK1C7r=c@GCW*5EVA12ipf%VRwdThhgOaCeA)#jL zhMpQYQ^;1%6Q;SelK62>Q(YFY#P;HIqW=)@Fo<2kC6qHFoHpbf zq1QNFGJwAO!!Agg-yNarCZ*Oyqp-Ws))F?NoD5KEZ!(6B6Dp?ssegVIKzVqQz#ZGt0 z$D|u|RVtn=?Mzx+mAx_pZRwYt>}vE4MuXPsG_1&Gq{?7uc}3+$c2~=8VXCM+7(ujR zuMlQ?@JNNi!ueAkj5Ygw{m!dF91$VD{Lig{|CKQ~_)ZIFr^^~a{{n$s1#NFnGT$2R z9%QGcU9NRh>X4BnO5u;G8aC7kBj=DoA|KaiI#9kVzZt~Oa5id}U3f9Ey!gqtL(8*M z&kq-uho-MhMd&LOj*_rG^C-%%>||oXNw5sS%R~Bh=KSQ(?&dqcisFz8`kliaWlOUE zHI(z@4Mjg1)7xR?YEauEcd_Aq*PQ|HV<<{}WmHg+l*OpDs8~Ggb`!8qg)faevAlH2 zI|f}EjYa7mQCBxE9JvU)RXc09KD>bh8XR4)KkHYwnIab@z?v!6)_4ZBp@D-NZz_QU z4cFZL+_U)l_yTB7gTuo8^HWCN?OBz5vD|2^o!z+n`s;80?n7@p>b;kmTEk{V`ew1V zv%UTrA<>hU$D!VH=dayvQKdu|Fk~NNul=)>SIhX1YO)yvzP0ii4}kWpCTW;FN@Csy z!V1JHUU~6wBL^n3+#?vn;4}+ZGCsz65{op?3E^*Cxf;igU|=*1vhj?@$;!0K#Fp6Z zW@Q=`b4I!&xW%v(V~p%Az$yk_3Noq!=2%u>%Ii9xLjWDdm8B+FrAP+JZIU_+lL_RY z7C1KC&c@pMib&`Xzmi&nv$3Rsb24NrtjuUu#L1+SVZLnRS8`%Z6lMJ!o};m3)p&B> z@F>G(=F!7dQZ`1%>X?j@ePfb8kI_hoG;6qu+lYcf=G1Z`X%ua&c@G~jDIL{4vME*e zi&(45klGH4A{Pqioi~lXZn7}$^oAt8Z4M67KgeX-K)7mrSnz8Hz9*Oxdl3#}>6r_C z+Vu*HDN#~*N6(;9-LDO23-UHGN@lNn8a(dNVi>mDZwSkp_<=zzh|9XTyI=VnJtvfK zi45y>_q*7Tydwi3wiBw1Rto+j5%_L6upfmW`yV^HFZ#P529isoC|K%XB@y~6I8cXH z5GFiJT0t&Avcg>g1!$>1$uKp6`byM22D&WLQs$ga`dCY$HG`H`jqw2)`L-OS~GQ1Emf05!Ub=UC3A5e=>L>E_CA zuDOE6c_pWzaSBaWA{{Z>W+{QFYGs#Hk+g1Wl${{qT{K`p&YvIY*=g)q_BeN&dL~LI zK?QwEmLkK!S!cYWn;t1CYRm+>>r7Ncq*=27O01K)EqE-16;kV}UIb|P%aGY=?0i=Q zjILPbecn^1sonL5{Ui$ExT8VzosV}H4S3ZcJR8MH&v&_(msn>nN)$Y6i!8jF ztW2DJ*n2F2zVrWH=U!vL<(VB-^%BTIJ`{WpO1D-<99@I4JnWt}P zFm3F24sgA(HM2v$v7ucLyV9DnBnQP#gVJ{|bp++Mb_+?+@xe&+8u7m-Qo9* zMZJYfS(e2d3Ya#B-Oe&n;9lGI;m6+ zAeYQaX3?28*_Fw9J4r2}n}gfQbM!Qj^I`0Gtd4(}n5?XFpGRHnY)ISwX_%_Pu{!+r zoIJnPYF$~+!+Vr9^oT95Hp{KA(Wy7G7qRG30{t`n;78nO8uxItLXJE%K?h-!m?M0@5mx^H($GiWFI3qqNhgv$z)oQli51-pim_ z_m2j{2cLTe$7cL<39;^7L&DV+DXx5(tHK1gFzHK!=wp=^&;Liln;9GXwipo=^mz7+ zXI|-fbw%aET%eSXE_DHm|8lQzWeK#UqZV|}qN6_bZ2Xm=#$!1Cc=E~Cj-&2z2ZQ~& zP3h6ei7#FmK~qzB<@UtPd*2yW-#qL&jBfTKpAzW}qC5tEYRTPS@^U%_^2az=Rg=j+ zv9FP_#Nhb+%ZZ7zZ+DLzzC6-sdHREh0sDuy&Kv{qO#v|bU$j??>P4F6^Wt*x{mEA) z&_93whu*(!JgSN0&a6Rwi`4M725|pU(QClSgjtr~vR&MeV0pk}uuw`D%V!1N1bMW| zBxe<${X=a=?0~WKvgcj6b?esk>lZKn@#-7zp04&~R`T!t=HZuH2Tz_qT5AnR^wd!F z^uO*;Isx_-@JHY643t}|wbp9OMNZ|`^w6V?>*_6nCeN*3JwJ8w+1KlizhrBTUwwS7 zOd3Xwm}&)QOw})cs15L&n2;{dU3l^A>33V(+Z%8H5Rd)zr+bsGf+m}5;o{a?GZ>9( zT5w+hXf=EjA5ME+wyAF0?<^XFN)7$C7Z9AhW>d{|5+-MqESu)rY;$|g) zvX|H}_6=wo5LYGAnpLrG@Ah@*H9(9}+-r1IF%3YivEWdn<(-i~2hYS&p2vmM4Lj41jWH5!f?1*SQecN&$(>}cD*7*39z zOHz_lHJV%>vjc5fkcO*!kYKX0M$dt>Rp1!{ylEKRsU!}eG+Y)urg#BM(ipxX!XrCJ z2Rr-rDF1bZ7997Uo(Wc_DHtmWJdQKy0KK(VpS>OMct@Hb7>#*Xue_d(}b!)(COq`?!>{2{P zXmM6tftPe8c!R`U0;N+cN?d1cRG?EA)M|N&gy@4KZPgTzkm`qMFO{M+l^SUzQTEb4 zO?~Lg{+^xB_gvPrYKVyOy}l3``RjAe_k6xq@@^^N$SU3Eg~U4A_3N#peYbiXgJt!u zo&LNX+&a3Y(%H)3h=MY#w6*7_VQ-8Gs5G&&CnZh`B-w1riIv%7o15PU%yr3V0~1~& z?mDcucFNRBC!4-*4m3K}gq-C;AHids(xiPL&kfwsw6`e-=vp`9UMj?RT|$xVMJTGh zr6819p)8eB9B6$qP`Geh)iKM%%2EQP6<1neT3~?104(dy+HfXh&RHENe#CPe z9_dxBeVBC=eg=v$|F-Gx`&S~zFMK#IBE-4vnjq09yr?!Ete^d zsF+ebR|{=nlRoUNO=^Q!2oUPz#hkogRso~BiX)UgOKHHkqy_iT&zSRAVa!+ubKZh> zE7p_U=z%+(axoO&;*lj8vWi{_*M1(xa7tOhM~)>v`=;~7Z^qBu^9aMGd!ttK?)hXS z3^nmJ6i+URdM3Nxbo#LXj8VLy_o$l>ix>C*^siSs+npssk(NF@+ymA>FNQ7Xosb26 z(J>rKEb5DKz>V8G(gB5~&{!Yd(PODWYS2&A&%G+*LtQ>^* zOisg00phY%fNe1==kYLG@qC%=;PS}VAES=yHJcJIES%{Zs#cS!*FO4Ud%JV@&ZGMe zZ|__6e(b``?2E{53(yuGr$V{%X!*Ab>sJ@lfnHyq>$=Zoa)DNOn+m+VTAr@leGB;2 z)w2uhcFsoiet!D%%?%BWg^*sD+dGggOq*2DGo~L74h)zA3xs8r?#b7GzrK8ReVs7j zXI^^d(j~YcLSx!b`}7^4m+U;PwvpJ1)}Ur(M+1P>c8_(X+?GGfj$dxgR@!v4=fQKd zWUww*Dwjb?Ke+j;6?vI63ix%}Z^DExme9rt-Qf&<=>#$gZ~;qH#;V~&bdUNq)Y`OH z#|@7|GVP2?%F$T@6fzvn@bGHWzWB~wwi)8Wy=p3hAt~k+7tEwx$>}~PF;_(sP&cY{ zl?CXCsn8{S(5}JOQHG;-C6nD<%HitRnnacC!Zdy7s=&}0aiVvzLUTun{iM>E)xV`o zLYqp}2@;g-Dr*xNI9VcEmP~%xP+C)P!&tR6F>#z>F^fqgF;Mox))>5Q)iA+Ff?bU< z=e65YCX=iL|3l5?>q;v`d8b5gs|_`4#Tx z9v(M1c&pDI&?OROk16z5FtbjVRaSM7D-Di|K77eGsuDYsqt$vO+#Dy`Lwu%?eg2{G(Egu1G$d%Rf zF>%Ucl}KRdx66ea!oXH>OUGr-dN&?;pE~7R#NOPF1{x^$3xXenR<5K^ia9as7A!O@ z$0L+rqq)TFgftx{N#jKtdYzt)+q zhk*wkNhs`w_!o689ff;Gbg1hmyv^KObM$lFC%EC9*mr}qUL^KaPCzY|j5R7&eVub5 zl}*~YT9dklvos!ELfWnc@Ac+Bc#}wmD`!^4*iwJ`gwh15OzZV9H&EM9IbRM|GrKNx z^`uAs);)b8HyI+L1*5Kc`~q$*rT;qE!!w0zxy4>lsxNAFIH$p}I^Kw~mC6Sve_{-N zLZ@E7b7S5oz)E5WVUrpPFXq1gr8vUr{P^75#>VSiu@7lmPt$@qbKw0SL0?zi{|Sro+)Eob_pN9XPLbeyjL$+u`S#Ch-lGU-^a)*B zRj-<+ESt0@RTz?3g>8!sJu^FUcR6x6@TK2;Ci~67y?eKBpFjV>pGQXWGbY`n>S7^A z(JJt^E4XCaAovjzS>$U-b-rBiDGwQdG3$fAIul0@4UUf zzOZ1Tt=jny+k_Fe31}k1u#$i9*1%Jd2+0k&z|IatK8;+9M6Nw2I0#&jOE0@J+cn>O zl%H>vAw5@SXD{s)&SaBy>Tl%T&V zvf4C(Q%!2GYN}C_h@`#PGQ49-o8}Cemm5|L?KY59nUtx7_jFW)LYbMHc2B06NCB*Z zn_=1-b$V5Tf;hoSOB&KMrD-*t5OdOA=B*q)bUY^@K_kgvpA$5Y9mHW`nRXFIaGP9S z@X4xXz7)iq0=9#@U}BZHS~a~}rJAjV3rZ?>i4GRNGJ`J*gEQO0rSVc?%udj_7$jC{ zZERv}>RXOi;dqRVlc0nS4|yd_Z+S|%Xy(33LSiC3IK?d3wRXxhlP}3>=$RT4c5-kC zD74U5gHwuJpcKXcO#wW3{IBRHe?fAX{topWJ>EA&0Fn}bVPSRkTz48Y=|}dLRpCBS zvS>Z`psHQhyLxW1e004}Uqb2_#Nyo7w*@L|t4I4ugTSH5Yv3R3S3o%a`Mmv!;09o* z&Kx4T>+iGtPb@AgmObaBXC!E7#F}ykBsJ|#qrKeg(|^VmuB2(b!&k&ojO|~mbu;p7 zrNooAH-XAhN_$nyR9G3rDuGifsj+S);|;xjq0tglw3qV06CLn!DQ?(tGg>tcvN83v z2~kR|q_VMWT%^mu0}M?gwQ1b1=`e{&bp2>PCuvZ7_ORx}0c%NEt4$kM^cWn=h;{am z>@iH=x_f0s8%zP)zX2gP41T+_fr?~TOuEEWyjnq~k*t*_+RmKc?fvRN)UEE6pqo_V z@l^lc(CI*nRq}j$5Ji9B!HwPB>H`F+VTDj=>)CYql}@=g?7Y@<|8|TpfJ0bxEp#}$k?BOZkmL)){s4DYu`g72f`?t`;t+%1YpD^m zbAJOdj(pRrrQ%wc#-PODnjFs_?ogi$XUggvD-cOjU#TipvVs&e37%vOT~qFn=LTvD;a;Q#MoT6VzKyl$;T<}0XH;li8np%Z?Dxi^Zap_f)aA zC_mQB=F8`<{LEqYgbR9Ob6?F;5`;u&q^@I{*%pF%M&yllxouhlsv{4Eqs3XXVL)$Q z0@)V1v0Yxx7jB%yo*bHrub%u}M-WM^G?o85-vVnz;?gSLZnkCRHkT;03ajtrM?S*? zy?*lQ`WzkTH)8uUp)_MOE)?3+M^1ln#*tN&$jcj}x67B`S$x=7Ua*3g#2udEMIx7;GI1UlI2!`Eo;}EyTl0z+%vVkv1)^-{7GQc&_HZfJ3m?VjER|J9BFrBOH5i zV!%`F**Fk~#wd2jOY5i=4R}PECX|{iw2EdB(u8`*Wm1(L!eJct=P2795oIOMC6hDJ z=nfD703ZNKL_t)b@;#%xGs!6pn|EePkM-utB`qD*&Bs|q4PrmJMJ0w z79QR!WX94A{*CYIJ0Icv2qiibi9l5sA~uvS*<0X3;w&ryP#Yevu&jvhBi$mq65Tx< znOSw16qY!eyHI4`kyk2fMU_TCb5c5DPLKgYBf=6- z@+yUqS80dLEm}5v(;*vr0na8n)j%cVfZJQ^6g zvuI9nl*?W~I63KQlVYSY@5<;af%D{{7Z*;tgBYmG>)xJZ<%ldY$`{K)CNt`(<&yUW zmYy61e=ja-oh-%iAHRrp=e+$PKk7nMPf=;olbR)^a@x*RTmy6OG?rOOC_N{j*4|f! z-@FGs1FcHj$SbzX`Se_O^h{l{GT9F6+CJPl-+lhc+igLkT*|Xg4?Iod_{h~8a9~5= z{#!=i=Ib@_XlQ*LQhfYnY$NVPVKUR(k8KRNO?WtxK2$`fv_dtj)3B~Z&Pw9^znc9A zvCAKSJd^nJ6d@abzq0VgM{DQx2>QkjeZa`BkUsOrDJIg!hBuEL{o;S(uaBUAckFR( zliu4U)%q^MOG(_I%3ujwZ%2;WlZ>BLF(i;?Sxj4QZApO>#!iW+oL%pMOh{XbptBE4^I!e`~$9*`XPU-lbm0 zix?rjvzGH<55e@4^FxFGBzREh2z35hBJBSczNSQ@BMv<)yb z9_D@s6Yh*qjm?+xaLs6p(YF>jDsrNMzL4+CeiJQ|hiUWJV5>Y$2+2{Un< znj|z^Y>3MhFt%YBj7}Q+@03D2w#(%`#>R%Kbre~sv~d60%_5&DwTl+dBwg|P$%Jcnen8{uoR1>_9R1WF3%vL25n~y zcnjxd3dXGqh2*(F4qcd;xd%U1OW_ze8O2v-NE%H!&rPqmINc@lSk`{DZ)-fg!D1M) zYbW(~(iV}`Om#|Wi978LWW_LWBZN)ZMfb*&?NORpt83csmi8&L>`jRu<4WrwV#UCT*s9opE^MZRs@zB(TF(Vh#C8A0=7z* z6FO&}<8y;{XmDa;!o^-$BCn8)Y&n(CyGwMdBPU2{9Lo-_o++ zRx|2+KiCfUsj#2>ekka@b?c4FdcSb?+rREEE?)Nr!c(k(y_t|G%Kk6=fOndw76X2K z9jNBwjqBG>-FP_>4kh@-AlU%FK!`%uh_Vwl$dTJO9FE4*``G#rPlV!;eNJo>E2;4N zFZ=!X&R<)-x_tot&NYj#0r<+5g)6{gBKI$nJ1;_1f2uIpmGSXN3=kL}v|$qQJ+V5XvQ`_D#dlA1+@y z>TO3`q=K9|10EldDe34L1YIf=mSSv}dcuDLrvogujqejI>Fr3m8cEhSM%Z`B!?J%3 zyK%*Rv~Ve_tFdO(xJWTnr}M%Xa2o6kDfSVTYjoF`sZ_|Jc3LbLxC|pZPWfsV$}BcJ z2x+XWF?EW21E?DVE;3=J$Cm{$g}>Nw1+$Q4RVk=TfhweQ`;kV}kD@8#q3n3um5?k& z90(E|8nIiI9I@?%`Wg&-{A8MOvbMQ~slLxmgR@a(T#3@ci^YHWJ}FX9Z@>56XIQquQ1%i@FB8XPsmY^jeL9G+K4FHh|oX z>U?F|ZZob-KT@L(5w7oH4xX=1ZyO#@S4iDpS4=y@RECT2+zcVoBtn-TP8r0`7}&yt zrGieD5jmrTrUf{eF>;ImYrK%zR!mk>`Oc(pOry~n&rCT4&uI8;N6QrM`4ZTO@C;d4 zID`RQnUJQ`8*?1GZGEBsMIoQcRT)+5#Jw zCh`(}ml7|*wOBlxTT|vV5tgxuwTPC;>XwV;JZGAja@Iv)0Yqn!Wasp32Bxuypfom` zOA|aDa{``STf_4dk-bQz5=g)pGqdUyR_j&7;uH2P5pRyN!^CrOuTzdoCMNAS*6H6K z)V$F*KY6%Z8qJ^Q1Y_FNDoeQw-<1W)lQsy=S`NIp0H}1x%U&Mn(5k7gpqKQHuHBoR zEDKwgXt^Efb&7PUbogNF)~&Ixn}Db{Fno2y@a=xrrBr$G=Q&6BQr@M?vLlyVU+v9J zb4vUO>JEWeUX*CBj8U8~sN+cTXsB>s=-Z$4uq*Fg!pp>nT4jVhqgNtz0pMGKN9rx9 z@X@CS#YKVX4X3~oVcB2T7n^VIfSV(!wD31z%y!}Vgm!*$#n0H!dgkfmj` z^YQ#yr?w#JaP`_(CsoyTxv_adb|2!y+_;8;)B>#C%;OU9=`kR zKf4{yDtOY~ub+N=R>izQog8m%M`b^w!lAcXg6b^mt7))O0J@nMH@0 z^UWR{x7hjymoTRv#iARcQUho(zQQA|V+k`rk1MOvm z0O%m99wf=Jz}Py#JP+@U(#cSvfzT+hebyV*h5>iIYJl9PchKmpUC{>G2h60obpsJHBpti*k7$uq7yr;K zOSQFCuACT4X`@!s(xsUUPLONt6jozSg|fQT32D|aSZ)F%416(yi35iCqPy8e2n{qB zNy~bZU6%Yydq2xpCoacR?ABM?>@r%{+Ol<}g7dq-%bxQ9BYhyJ4 z*V~XrrbhIp>fM8Ej8#lHg^<>j7f;Hh>bpB&pj7s5m#I|w=+o9nUZPWkA>WR zFk)1EvIyJHMp{c>J2;)dl$MZW&wXhLWs*{4n9ZoOf!!7_=^Rx;jWv@NYPwqj5kC=O;~QQv`Mw=wHPafqol zNDIaFB03r)a{p2;=D^UaTxzdp2RG@J;QXITktx8NWR$(+Qssi2z}LUH`o_Zv1vgJBSYzUYZ?0awc_Vm=3ZZ*Rcu$yz z9+keDS0pV>hMEUVN6Nhl$uz?q%$96b9US_Wjd)?@X+(lQOyS)!CiP zJI4S#e+iM?=`4K0D-Xqf4MpEEvztKhwSzjyv1-&%3{v2 zErea51aU84JeDK_=pwowjEaAA|+&FlX?Fazk1)Dj_j{*h2u=3g?YDP}TI|HC`m{;h8- zOe3!(Fx}8{roP8Mnp~`AQ?_7opZki*GN>+Yp-eOKJ=dxCI}3RO;2bfI$Lu$Y1X&cP z2M9_i6-SyhMl#>((_m;rLt-Po4JWd=cr#gd`*>0Y8(ur%f#b6Lx=}e>$*_;jMh|p! zGR|u0%V0aomNhyyz$Guz5HFK;xiczg6&p2NidBKl8t?(p(E%~e6$a0X!bk0D4K3}K zxC)eJ!Q_fozft3$yl-crCMnj)I9iNq433Tb8v4ex5!yK-T)>e~nb*pqdV)!*6hPOM zh&7{|tMnrQwJ&Nok}9}><9!8XRc2~%tO5zx~?bSz6UG0LY1|IabLUdY#8az+m z@-{-ddE~wU@wEPo89_D_9%J}y*n8`iRM6A2r-0)3=nNh^p(h!WQ94TWaEJMmmPHVd z=p`d%tRxSRuM^A?Gl9-_CFsL-lt|jud$OA(M>u7JJ26VkfBo**_ z*ee}0ng*g$f@mt5QaL8e1F2jupen{CHL!|gLn6nMU^!|lz&M>69~zdXYe4dA?{&xp z)bqxs)Ud~3i~yTKnU+kH9sOZo4XM(sBPMOun%3P{+U!T2UR0qgev`RJwiK zAuL+mc7-$#z3r(U%(4|v@^tkWd-eVoeYpm}8|Uaanir=%7c|ferO*8Q+75W#+ZX0N zu0ujC-RF5One4Ll?RL|ttTw#qWbXk+gM=5pdNyx{*!^BIWi%$0lf1dp8)O&-eM{_d%7Mn(`VZhA}DP8$JyMXWx2G@zVq({S~q^Ywav-16g z`dqOyM_5OGui4)#HlIAao|YuJM`%Ts6)QVlK(=AOHH|Fx)*Cp_kr3KQ`+I+{PlT*O)YrT9!3QQY*d|jvt^k0~&J{qrn+jcbN{e%7wSW zQ)x4b;{!>U6{%4M%)!ydK^$roVvrZiZPd!~i?VTO(j^-Pqzz4&asDE(s*!dTlV}xd zFHH7EsTvuoz5rOu2A-9&(kf9rD-zoHv%w|fWZHvyJk^;pk}D(A#+Y9$D#hak@z6}H z5l@#E$>}f%CcTn84?ZS6O9N_>w2)BS8#cu_mMWF1YLiH^oT*kvFbtC~jdnU9^3?rO zX`iU*5-A%Mob7d&#^WQ89jx36iE~vCMV@yg^`H#0VwX0QfVC! z;%#>_jLS$+-+RDTIFsmt>Gq2zVg;5^a9YYBmr0zIpURCk3a!j6~SXQ zLhW&|^HbE=f1x`u%$tX0A{v)$%pmo@Ov?qiLqn>P?YfwZNRe?Kuaw|^^+3m+>g@(X z!Q;C}TLJJU)i>zQ-IY+xFv^m4MQyrjE>f^n+aYy@K0-i{5ixpXZ%Zfyx$~r_UloMe zVXaKuq(;hxf*0Qtvn55Mt@1qJcAwv|R;9N#)>VN!@?Ix~SGX}$RMo4;ZLCh_`>^Y0&`F%B?75JwS& zsTVN=!}zGzD+-rUBCBbhrlGq0!S($1cB^R&__s=_M1=IiXUl>)WnP`$z4rcDJA4i@ zZ8)vaXDOEK3pM*}n&~^pxBC6Qo%ZS4a=^sZ-Ob&#+fQV??Q9!L+gCr=yz_}js~vLj z;^tcENps(KM zV~bHb_x{6&cOE_Z@!9jkuQU=jh7ZX#`rE?gyVU||n+&vzA^TZb(7g2Ry5sY0{ZsAn zq4@Gbr&vdS{o}(wrW!KY0>hEF9kAVvT!M_`Sv(dvZ4kMfiBUBJuMK5SaVzs?(wH+Y zOwNREB6^D44g@eqWK`Lw6A`i}J7=6l;!Jjx8n+_F*A*eeHl&jh;6K`>zM7uVuS6(DECjE1>fF(PW8snldRswjuD;!0;N za54GD)fZ*0at&M;YlgSwnlM+K*A6UEX9#*KmJ)<6DYr6?X9&NdI9S0PB}UccW0h$l zL=9c4dbTtWY$#u=DKDBstN-Wg?0%a%%rK7a*z%mn!U;@H;@XLqxNS~-h&3CEkz=8< z)ajZoEJ{cvBFnhhN)^J=PKXO`kWhPJE*4cZ5)xdnU2IZCiBv91CVEqLSM_dx&)(nj zp0HM{hML45$HxIRdCv2`&xf0e*$dmN73@(ACyEq3lu4Q{%gj_&xODNB@oW1iGG*2n zdUT>Z?1c-4%##SECvQpQJgSK`2c(o(IW=myDm!p$_(m~xJe5*bbn0G8+N;sY$$P^$ zm`59IPfd+Z87d!RJ(1JGU)D2iBl;-aW3prKE2>4wW`3XwF+4RZ?zI}y4k*Y>4IBo) z1dC=N!`bw6V*xo5wOIc4?f*9lJlKDU62xPP{e&`GcqofDi-3=nG_{rS+Y#LN&V?fagtxb%c8BU8lCzO)KGFj30NsX`*=&Yipv68BV zzxx>}v!Rn-NIbTo#dAhM(}LBL8Lv}MN^m{qCB~8@XExMCEF{%r`&St@)TpP)sZv;m z`1DE5r;~dB*F29)v772ShAXGXya#GbAg&fDiLsUWr5!X1HO|IzTk~@;{I!Q`k_*?O zSgH|ui)tnBXYh%#q9&DAIqqSV9!sgifJL<!WDQj}X)m0;2Bg`sTNs($h01!a$zl@?p$gLFH zUh+obai1sK<-@A#Ab{2pt&dfIz#!Z@VHn#U7dc=P{?u+HDzD@=C?!C=Tt%`M9H+IgD?7eE061$6p^jJ$!Qi{`T&|D>E|- z2D9+taq>BH-aY7=<=3v5I1T+fJ%`iuZm@mdX_D}*%<%`tq|e%DI{wewX_RkK+|{){^p zc``=b@5+^->RhF257wDYOHUPk*QAOdi!rh zbK{U)=+K`6p6f-ZDn=vTMP^`CBguhOh85S#5bBCb2qPe7#$56EXi_Ufh%ILVd?^Zc zNmgB|=(cJXspy3gjfc?lTtgwlc!+86D)*pP>?j~vC#A}jGmz=*uEZn;m&Ny=Uy~P z`({Dmo^K#Hn`195;Q-yu5a1U8Zxggl_hX76O~+kppB8|#`i<+Q2DwP@cLlUafOk^`rhJlA% zO193N(85w^qhJ?R^<*Y4Xh`}S9O^^GBtai=qz)GalES-+v+VY4P@R1Db!~d>uzbd+YMxu9T-WRZW$U4{z0?w!Nn6%J0P3dYnL9jq}FQKkzLt>0vV6QmZ5s_tRd~yAJ|Ct__?`JLlB)+r0=n%Ya z0KD_ru8dOXr#hSYM-M7tF8T5G2X}5iJb3!-@X6lZ>8mXgt_LzlsR9{Ka^RsF({@SF z?FOA-%jvqIGL(O-fql6^{jV-nx?2jo3^qaFLZGZlrJ4i{yu`uu!S%OZC`qbmq=b>K zthh#BV=~?LG%aRAt7)TjQv3>zRTMd;p|eEC%`D_qu3P|8dtxNY#8mAgm&%FRh9K=6 z#5l}BSM4SJN*1pVc3(wRQAlK85IupFoZVhuQ8Z*zF&J=IyglG)!Y;zG{ z8S||(c2?_=M9p*ZBLTV9Ug#5O(ls{GsH&fN*2FE6EU65p&ye)1lxIVa z4yPv1Oy0ORI$9h}P2DgSJw*h^R|vJvFnwl!>J`dx&tdxJ+sq zbD+1AkYK2S*lH-3j`dx~PBdkVa2Ho;rGabdOBhur)RRT+CFAEDq}CxCdcA^@I@?F| z9E%WJ7U8I2SdQL4z-`naX|y@}JlB_^#W-|Kp_QtCAd177bGmOZlvALp_Q#N4JO6V< zM|N-?dzNXHqgv&^o#dtcAj63f&z}5RW2c{Q7J6U8=V$unxuaZOQ zO%fZKNECI_C)pV{6T#AXDOO%>pnc~Iv@4QpOcxH^VR1cnT3rs zD}KWxwMtPwrGT1^aa%*@5%Khze{zL(NhqukN)ON)QOWU0?O$!rg>J95#fK%;8m}Fk z`jPnR$8j9&fP=GZYZ#DR*xV8N=6P)Oe^k(hxN9;jMa2zX5c~~`U*-QQK)oLyBD)4d zDEV^xInU4UyJI9WZmxjMT;`s8w7R;Se|G!XKfnG9Tix37=I^fVZX5h=zqh@8_6UG) z{_y>uKV6!iRRlETmm0$5*|vmOAN=CP&kvwIh~pEfpz#?Yc(zXiS3n0UC2X(&$Y;5-U?N^Ms(|Z65 z&;R?u?-$qYW!KghFYf&2oy+GQVIjgE)abT?;PofZ?(d!6ef@)$q-Bl9fG-^bPUEx# z&65jkxjO}9%v>OJ8{O^zP%Uh2Ep+$>8x7;s9NN&M#CSTJesR0_kw}4sI6h~oP0yP4?!8nntZU~$+OUkGS^L-CoOZla9eIM4 z{fF{O+uN#m>qLb>4NOJlxsaK07^>c=7^;0CEJAt#RZhszIE2*Jdu2{3s%j8f^x?5G zvdZQE@O6HzZ5?J9ucRZPNv^hIHzhi8l<5$QMXDTomD*aJB-(~fE_I_IoZd7DSyN~_ zr-r43L46Y_xp6KQOcE$07r72;1MNlDU??p62)o>8+53CmqpTg<>Jl8Cqhp!add~B{ z&mTj508?{iCey9R&oHX%s0{Blo|}_738>yLs_C$)PQ!=;IWQa1bhK#j3iGAtFvd_! z-=R8}AjJ5MBO}r|Bi1Bh#Rjv)YEh%4#-r%YqSRIur@kk|gma6(vQJqbzofjBkbg7o z)I$ASi15lB&cGy4j(162ks&1*K2zaXn9A#ogBFLW-Lg#;P#LD|=Y+fd;c!|SJ|7-2 zg9|b#Ldi9I%cSKePA7FBDTP9pROvu)YRU!FOzTqKVO{X5YCxz|O8E@C;2fDsh)jAq zRbU6nT6q_ArBf1DXFT%H;}E=k#y7@O1rw=w*i*F9UfG&=xmU)g)1u0GL9cz1!U3h8 zM8nFZj7rp%qLr1lOSa;?;;S(YFUibQa8{gE105q|DY<-nE!p;x=Vq#iU7Xw%+}WfT zYROZ-vQmbrCMv6$Ix%4CZe%5$4Cw7yuRgfsiH>yi^*#4dor4lVJ7bj^3zv~}$I?e7 zErgx|S)Nm0&#hDfhet#sXHKA7Xw1BKKC^b=w5G=dUU>Ya0-^=oXt;pVXBQuMvx4^v zmy-#zb8as`>U;1rSCnOV~edHas_a zd*f-=elzZsyqbor1?+xy|EV(8f(H~1>7!8@DEYl9!(Iwo!*uGkA4dJ{8=stg`K#`z z&jfn3eR|gcc=!C7<2U~;!n%2L6Wj0BXyo}(n9lErRy_x@+^UOjs?LD&n|Ztdb#+S%#ay})4Y+w|3U-CB%n z>Yew#UOqjjLeCLY54NAC?A@#qJU{l<+k0Q#c>MiIQS5ei-0;%gHZRb4ES-V`Rf4T; z*s38kI_6o=r|AIj4hAWP0^U3blU}Y4#y$J4$8u#=cXkHLUJb18yebH<>H$Mw*2jZJ zd$9cd-XHUtCOh=9zn#eBBdd{M(k(-hPyv8}?^tCMGH49+rd$)%)kwO8SC&yUytjj~ zsHRNEiHx|bnj-6SBvIakU_|roL{ccJow4!;ipvPNSUtdOtI4xHp;qE>&3Cv4!hkI` zzIH-|oMx~YiIj&}8MMYsgy|7%X^b2*R9?j!6w9V-f5n|7iIt%ped9>YM|RXMWzSgE#5hid%CUC^%i9ZSjg8M5m)eg%N%lKXO=^567s4>_wk6K+<*za3d?w5fDbTzZDjEwWO!~Ne)x6q@mEA$z+mI#kk?J4P zDpFkH?Qu;?BotT=0g3?xJ&}0D1~?7UPN|W%oJf^79b(I}0wL<^Z+bI>WY(TynP`|7%E=L?zmM;e zY^gMA$)~~P5m0_=y)2K_*~xXY7GXt0|VIA`P&WMGow!5r^(N__rwS4~8*}1Pr zNE#?v%3!Ol=;s;g;i~$SP;ph0{jM>`@p$mjpI$#Zmr`B0c;SQlSE}uU16ht68@spO zQ2^zK?_a(6`GsqpCrpgh#oK824h9=no<4f^*4zqXgmzA)droJP+{5B?}YHt9UMrz$? zjJK5%J>xr~)bXG(s6N|!Ef3U%%$pVHs7R>^^j1@5aaP`S4S8z}Mr5>Au`VO%+Tkjg z$W!YbIdOxqRxbss9->S*6+Cr92?AY#HHYO%hwP};P!?czbfsdxulf{;csWm@Z>cHaRDe;s9 zi6fFuxm{QXjQ|G<{7|^%JtG7e88q+@=Y`avv|J&H1qG@a42=td>_Vm_LsNd3453TY zVFB|}W|$^vsF24DRXUQ>I3srx=N-{Kqph)&)MCZil3H51rULWRxQz2jjj@bN+6)T- z?`b?OomR4SP0UUOgT8{W)5AUNLaxCoc=-cy{8DGRz*@a?X-USss!5t^!(t<|3E{?< z?9^I@WSz65#kCL1m9<&${v1fS+9(9aL~$-(!7y9bv%+DdVh2CUmjH^cVv{y%^G znGH!ot(By!VV+z`Hgq9)o>xSmT27{6rKg_w4&uFH9ef4XYaxQTKE{DUQ&^<;IRgUGmtXF&@7$Ip+ZUp{zk4KmH3P ze+JdF!N&5VoZ<54*FJdp*TrU#e)aL~15CQJg9fpWOp<$Dd%3W8#aq&2tk_7-IxtQv zW;!tLYh0Jd8f~ZI)mc}sVkX&D8x^=hM(og_UG|ANJ08x75LA8`hGcw1I5kp-~EaL?TtIOHVb? zM=hvN!c|F~?QGeF!dmTapyK;gEq6P2YazK9O2rVJM)lk@Vyg#h^_E+6>yk``HF49r zYK!U^dEvaxj$Bog55S zxv?mz+I;Q$K<}Xh$}UXSvK9fd0ckUeL|MUHwGHwtrq30Ha&VcJNNy$e|JeqEx(>Lhnt3rO?3B1t6kRo%n!qSYGLDHMC+x}WqUXyv6~Sz4-Ar(V-|XBsNzih<}C@+W-HY1^iaya6pH%Fac-BGd6bKS)a)73 zIf5+1YGhl~TIxMWa7!U|IK!uu4>Y9Yw#yl zj;>+QOyyotW;{-hilN6&djolegTuViFd>`cAP|5)H9o$QCiDu1mBA&%i=I-4=;>Oj zaLVQnBYA&RrtW4XQR_T8Rr$!<*EKp;;57c-AV_MgNnL1GQ@Q5 zD94WilcgRe5kq6=k%vtwoywQR+SB?DxhP~m8dW^pqmniliuOv9rGYcMR?o#!Yr~cd zPg@ly)xyr>L3ElB;%!Fo?tw3xy}ZbCrq$sq50UafKwJJ1#lfWF3DG2Rcn|PVir!w~ zAbYSn8V0W08ccMy9sJFYe)rn1k6%c!PJMN&naZk8tJ~;U;B4%6@ZEQRd@YKSFB~^8 zoOPPa)cTvegop{QJVrV)ov_8xGRIdp>ZeJP18gX4S3(_VfBp2yWbowoUrnled!Gy@ zFx<)MZ3AEXz45E+=oJ9I{U-?ifE{qU3m#C+U`X8m;i><(0cHpM{@#ASFB33P81DaN zm|R7WWW08%Xy{#nkr_NQe(ukKWgopRcS&0|4!ql!FR8ho_XI3FwuZl-zO%3L;JMybBQ06;?JDt>uEB0r@78{H!_B->Eax7n)4+hbS{;6N|LyO6|IWQX-+%Pz>&M?d z*zYg9u2JqA?X(xXJ8br4*;PA2nmoN+w+jrFo5|!HE(?J684_QY7;M;e$MgC&kDJ$* z)$26+V&$#=t&82r$SkmK{~NwmZ+iNf$?Ra0^{(A4d zY?!WC4L1)$jdNMO)*Fyh(i<5~yB(K7a4em3T=$$ud;Y*4bzC^rW`r!SPtS8KDEvd6 z%<5J+3?3$MP^`b5p43#+X}b}(882&6?U9d-hC68@S@l-S5tT44|o<^6WIJYwTESj5WhSj5xgYvvWfRxgcot+7SW|8 zHGut@;Rt7o@qE^+$K-{g+LL69FjGy9L&nMsoHNpuq>-etdM{Nt$zu?5hTJ+(v0)|~ zdl#1>CFANuiCRV)41mX(pcjZL6T2l?&WsJw4LC{vSjl9(RtaZiHp*nBn9eJeI#4r2 z;L&~(WYM)6jDwYA?4ccU6|)eI)Jr2DF{@U4JOko`r?T8Kj9y`lOkZ~Pq_;O^d1RM0 z7z{KHjx@;j!8C1)C)wb7%%%3WS{-YT?3`61XF4S!^&;}(@*0fi)kqf^5%vlS>9bL9 zGsf17%fxPh%5u|@J*n(4Ezcz%|Hv5dzquyeHLQOjE%1T8VvKx!z7 zo3>nHHL9eNt>RV+ylXyPHkQhiTjhp&{-~H1C#|KGN}gF+sT`qDmaMAc6~b#Cuu*h* zm&?8Q##$R!H1l2?9MRrO?&R7Cltq}0PTD8ZavYI^rL=2YNrQoFsg=(Gqr)ef;(3`q8w$^2wt!*W;HOCnSz2-qlEcV;Xb!`7AMWg2xVN{zf9KwY z(c8&juywxsmviR~e>XO-zHmVy2OE*RF&XU8N2v9$LZR)P>N~G8;Ge%y#&GKWfA2F# zuA(5S;_(%C8*ZYHGQ{f7HOz(AQ6PvSi58^hQVm5_2)j=5WAzWB!ZHLih*f5l5z%J%;hD>J%BO$$;IALP^;W5~_k>r1 zGORyuZa%ns_rfQe=hl~-K;EXxmzF~siJFG8bEEIeE*4|>`cVF;d9^!VD#5DBn7Lo| z4kwXt*gp8L;-e)xGu;9-cbDkIV6)ZgHLOxyrCpKC!PeM#GR=tV+uA0>bW%3l`kTKR4T$YFp;22m99bN4z?a=6^!j~!aGh}a}NN!CJda?)^ayFjzNLTI% zckN??Pzx^4-n9hFr7EEg*Tury(telu@zf|Rbk>L~(`C{h;jL4xawSzZuwB#@)Qptb z4k_8WwP(OCdsahhEJ1CCwsHu;YfB4UL~Q~w43Z0Fp(&iT)eFJj$VerJjaX~DHQux@EE$fDDeFZIk^h#7pYZ^FWjU$xZ~&y)YcYuZh<8( z0Gkts_48IcUI8qe7L#2pa=9}Gy{ok^A-$>>wr{mike2-+l*1mZD$Wv}blJY=&751B za=F|Ikd`-wg9Dsq4VPg-dF}mS%8IHN7$cs>nog4uE&~|^I7klSfP1#sV@E@o+*FvQ z-LU;#AM=J1&kh24&!5XFESXklSeQ6$C&0G4sb}J=VVG4YU&O>%&D0b+WW;|#Un9d= znwGMOLhUp8jIm&YurapcC|xZpZC7!YS@Qq92t9IU>t%^C@+~_VskR|}-iw!HU1Eit zPYcx33S*<`QJTjEPnhD0(?!<}<(<6}8K* z!DInB@tc$A@^F=QOK_lvoWmSxvEIK6XD|CgK?mU9*N2v&_=>8oM(~$sV8`avd1*S4PWQfU5mJJs@~uYR2b?OYWcBqzB4PJP=P`cPqpR16dEhiqZ_YiuwGMQUH<#6;mc&_GzaUdJi+Jxb9DRms}%U` z>9Z+HzZ^vK*SCRk7^aH+)xBsS-=?w?3~)7_tSjNjem3mT-g9<)Nk~FJJK+7yFMiwk zNpk-&L+G8s&c*)b#zuc*bNlq|R{?kn6EHj9^Qro3AV5Al=>Ox?o4ofm0KW4}fO8We zGwIBRu28ypvxyTJ6ke*DufL1zcMj$lAntB@NabAo7iP)imU!fcfhmw*lc4ZXR9^NuE}!g_g_4QSFlb;kEtuO1&t1>CT;7_i^Yx*j(3wc&LFgBVjLZ z=&CxR>waZBk*zdU4^5m?9?m?kdalTl%&zt8K3q2BoI{a^>XB#ywTiFO2ktxU3FE?D zT)!G!8x(6wt+;DhqWjxSpzVc_G;Ltq?J}fa_XV;3Z-%-xF&N%O_WjSjOM$diQ?N1- zh_c?3HJ71rUG2E=8++8~30Lba3_bNws5+HpD8UAc^tnD|AY4y5wH=%on)aNtYJ)4) z69E}8TJ%yf^{N4|BlynhV3rVJCUbr$7L!9JE9oJ*?zp;rd9<=QGZOPyhkA#uUix^{?xClyIXZ&$%@{rbYbylNxOo>7z!aGQjJ|R7TQc_d^Y3~AQ1WOV&?5?~`-1jW> z{1&^1uiK}Q$D%Qd?!{Aufa~~~Zt-XK2BK+o-JYpq3pYL+&$5S+rf^KEDT_8#*JPTg z0zvUCI5bd3sGbVO=?ASr4^Gj*42}{rU<+g#ukKpT-lGT z9jt^x^(HX-MtQLy62oAA(RYTz8fXSxO8h4M7y9??`Fx*qQ`T-tNFw>}e1X{C`##V2 zhai##veaOj2D^W_^aK_iY-EdEM#h1BLzfh(Npe;GN!~ek)^LpGs-&BcZz`k5psNZ>hS+G+W4%-yX@Z8bU?YLQf)_Gs! z?7n-V)NR;MogwHdcIuGnxf!0`p*p07!|IL#D5aF{qx>QWdUD=(9rVtT(lYy5*OJ`G z7=|ZmMLNO{yp_deO~i-$M_CZZmo}tlAbjogPVB(j&XP4ekqr{Dhg z-o&06t{+_)@7a&hUTx>yuK@6SOq?eZ1xBO8G9+%J!a6z{fA?G80KFH4_*bv~;~v4s zaWo&Z%5BE+N~L?FGo!75anoyp0WFdnI`b6J5?&-)(t z+jsUTd7y3BYX{ZEuu`jGI@cuu{ZyY~{P#~k{_w*W@4azrkTWr*<^ff?y^j3Sz4a3qNt z;2qtJ_KXoL(rO$_4PJ|mSu0QN^QST;*~5f=s;PF+OsS9O-uR@sbUIDvpWXdlSfKY- z;ZX(GTl^z z4rSc!DHUU14x;_uVxVN@PN$m%N*TNk^fBhn!s3PgF3GWcLtSK4ScZC@)2?>1sI16e9<(->#(aD1 zP+_(8e_{%%YRufKt_{l&Rf(KRjI0H3RZWBU#d0b9RfnLGF+ff*8Gu}FN`u^D7_4{8 zfGV?NF1Re;7l*co0K%WivMK|UOS+MOT_dxDZ7>}Ei`5rc1%{33wiJ3*UNT;W@mA>x zUT!YAi{-XLqV4BZ^%R!LjpjO}MssJh1sekIg2CInyT*W}w_-TrVJ!&~EFRMo|IG*V zypCJgU^Ov(?F`lS9H`~l062gY=aK^7L5BA5?mf}OW+h>c*W+rZ;3<;ai- zh3KqAv0I5EJh+1(DdZ&UDxMhGg-Mh1VKi16E#NxH2Wl8em{l7O4UGWLNHH)3HwHY* z%TAdKXY7X6eV8ZoFK-{6iRa3+tn^HR{|sMXqEl3*#4>ylSCX*R6|Zb>I#>2-N^kavlc_ao*-eFOIyM`E7iPiDhB(dydMK6bqIX(EZV_X5kIw3XEZ zYX!{WnB^~5wLgpj|K`~U`l1yH3jFiaJ2it+xqI6eN-SPazh(pez~|0Jjh!zO;BkXR z@S}hkA$mkCniaRB^yKeEH&N**T0t0`@a3j*ny~O-NNDgYj}38eJ%04bomV#gIwIw2 za&#p!JR3E~(`OTCL*Vzc{ng}IV`%yq*Z|L8xOM6BFaD1T`qjJl#v+w2bZ&w+&DDyg z+d1XH(p{}YD`9yfNtZ_ofUMz}MF1U(pK1hMd-U41Km6=hwOLNbsl0LGi77Dje%v5*b<|7pYX)w)ZSZm$=rvg+2 z%LG6IoSm+3c9{_mm4*QxyQP;IG{awXSD>&qw1%Ob!C>hAUB=LcwPod9xFtwJV^q&; zd46P_T}uung%;d-jnIjF3j;ADwre%>vJ0+nv$ll^x5R)Hmta6 zo-y;{fl?^#WruiCC%)==#`rr_eM4ozy30GW5;>W$7Y!ds$CZRqR##xYuDbpleRQb2 zEd@#!?2vteJ%D;`l7nzoAWBR9OZX@A1(&oK2#FNa5P{Xw@YFE6Nd0P{ybs3G!HFc( zQ0FiodW2S@#V`O1frS|Zb)PfSHNtEkR#P$IStSU$sB)l8>tZfJOtn!$Ew&MAHk^dY zxg?ScW0MrrzOa>CIj7bLev0!d9|U*}pXAlPsEQ^Unok>GC4K2-N+k*WaM{v2FCT=s5$XY3rDllZ*Jz>MFWi$V}zH&MQ!!k1U)qVss zo}k8>NOEm_+1`8j{5Maa-}>FZPnKR_}%O6_J#hr?Z@l&jZd?9 z1y(Yl2oPUX545V0K}Aodnj-}~{PKmTCtl(a{`~J3vTk2Pe`B`(_r@`d>cax1@r;`=UV>nxY82X)1bgMU}m=-I1|Paws*1rA1iI4K@65ssx1b0sty zu4ul3C`V~D1=wRv&8I|h*rlR)HHET9&GcAP?YMT9#@++f^vQB9`T|m|dBCxe=VN7v za1Nw6HH3$!Gl`CG)}X-AnLc|n`rE^I{#aS4eXoTUdZ>_Pz}PUitI%cRllv8zDgaEd zvU=(-HnoHO0cjT<^$ZM%sWK95=My5;BFlpLb5Ho)L3-7zGL}|pkz7J{V#mXhd%dUh z)-zM?(An2%DR^o@Fa~(tLTk)ob^(5pR#oq=G528ats`#6haqgVy^7!C)~= zc+I?6gt(<0Zw{A_gUGlC7oIhG&mmU96~eT$?!s{qN{M*x~9i=p-l&0L(@*Z zwUmAe=xkNHWv95es}fCZGixquL|nKff|lBwd56+ zR$EJKz7z`*>kOw|qj%n=;}@8$g08zpWtl=VRlZFxFsE#9U)|L^R5CcMZ^MqSRtct* zYWn^r-AVU>T~#>9i&R#(Ftcbw^5-fA4-5rrI~djMIcpKBX+!EPfvzXG6lk(S4pWjH%Q zAv)tUHp9h$I$}y5f@&+({N$pLVBbQt&U7{)( zY8%K3%t|?@-%9>=kvq%Jj2dq^LMK{RQ`N4|X$PEWjct7QiPpeLHiQ?h+w%aFyy$W= zEL(`yesG#9{mQq$+Rh$ka$~VrWlt#=+SO04v2t&c$2#{jVtSa3roFO(3`j3RQmZfw z8zGjL2m7#^t#3b5K?BYr&F5Tn!aP{`=!@e%*xL62HMeo-8{3AALRs*%5;C{^p#W|@ z5#+*njYJwjl&G%(MJ_^C8mrTjP+5;61z$xRjLG% z+se_1Knt@5gJ9W14@PJQmD-g0(6Sh+OD@epC$p><0@*`vhLHG>g+fAnagY6<`u?7G zwq7S~){Z4hvm@;i?=#Q)J|D1Sg>*LMf2RG>V-&=q#VbKp<2EC92Nk*jo-2bg3G-mvhk3RX- zOBW)w9!-_<3`9n1CE#PVX}gk%2n+nJePJiC+4pfROt!tkceDS+{a^n1qu<^C{hj(Y z|LxE3U49CSeX&}_$fYAX4cl$^HKFCQGp#&QI*Qe7gig!jC5d%ZO|YCnD7ScVRL=HN zQ@yv!>3R&ex~FU+naV!IwOxc~g#t^8n+M-??2 zC}9~+%Q{%TpYHngI@GvWj@#k7v!1M#9|fx7w4J2dUboXz7IT*ktpYD5L@`UTO!S4%jm2`+WsjDa>GE*U-0JK` zSZiDK%gr-|N;NyLL2i&8#}MF1J_ZmcuB!E|)KrGI10icoTUef!Wwt4W^FX)@V$-Hz zfY?#RZpl5mkm#m1vLr>SfLF?5)g&;7u>Qw2P025q=+Z`$wJ zJ$toEz2qb70+|~$In+-}g>!m=$%&@EP}cILdk`}(I~OlaHu?wgr2NG@wZu! zn%oXZ@sjN@)=6T540!W_Y)x4WwW%1+W-e53ZHI>8a+#sj4eJr1SQ%Eqne0*{Z9AG` z2l2*0YO74(UgHc$7u9c^)4&>AkK?fKj74v0c~Vh&SoHDmg`7wLZAQ%yRJ<0`@vzp# zuJ%&o26m`mxtB}q*`V5!;mkPTgus zmT@mFq~bc#n);~fHe@(os-UTb(rWB=>u2Ab+Fb3PhmsKAw+1g zR=5$@yUdw}vH-FU40Ul!biVy@>+8j6!9e*aE%^nFN4H~RU&l9_AfC2(LNcr)qv8(? zfH4G*4(#YZ{q)@*EMxfWE)HFTsTHk%Ubhfap5VHo$R68BAM8RUmrbDqHiXn_6*OZ1 zYGk<|$1k6}|3qe?tE+#!eD>_oYU<~Vlv^3K=Zt~vy7eDMg zu%oe3+*G7b+-UMFe~`hlg#D4&C;ctj3E-*69;`$b4@oOrC%9 z-*M^Dq zmkv>kX=@N*4XI^{EN?E2LPK>EK%k+%0}p9*xw0|fPS05BP|bZ^-{wkR)j8{U;n2Vx zxqgEznQj7g3o#$AUFRp)1{xa=l>;f-YmZ451ppiQtqqKVYNtD7Uc0?s>`s{73Wp6( zVY`JITUo}+o%5}mY?&b&(Ih7lxGq&BwK90E7bc~G2SMsEJC)|Vh@}c5qIU}5IwGe! zM{aAC4s2K&WOyk^x)p>ocE+b$sllGnFoVC80hc;NNP?drbFFYnmNUnbOj)87sRSAR z(jH=(T@k?*oU0>P9l~@pXb)Vcp0HjQ1+JV^NC+dY+uM0ZqP)b=b*L)HZr)3(z)vAA z>1i_sKPw##vaBr@KSf~8_IQ@8@bGzNyBlM7&%rLke^g|f8*>9feC&H~p#Cc$95 zyr5Ar&}3R|#A-Z8z!e%}G-S+pRXWP1gkkeukh`!e0oKe*d6Jhda}M?r&9JF$DyHh> zoSjP(VWDY&FN!s?LE~~y3h7)Rj5R=oxRQpw6#M0c7*QJ_2YO3^azi?XVheM*niO9 z13qqFWys8Dc0>}PoPMM&1nbv%UFL>Em9nnAa`TUE!^)+CsenBU=+&{V< z(~WxrfS(?YM;bwE0X$M72fs(7#lh%V@IyY}_x|$9-S%!5MN=3oQYo;dt!U%bZnaY~ zqw!+{muR(#+P>^n#&TQR(*2W2{+_lGMm=@+?xRN^?Eg%zV*EoyMn!!GTmYUx%RU|? zVmPAxwi*zpl3DfVcHn+rl|$M(!--d$7ipb?;I?gmNdIu#owkg=8<>GkcDs3F=VCD4 zmzVTnFkYo^Sba?3^}gLa?5{SPc0AoEXwrY_XvlvIob$>$Nz5^G1%@b`gs_gtsI=ll z`gnn{53k}4rzh7kil>dui|KT?nSXWf!@RV@ot`n_uHh$h;xsq8HyQMNI=ohzlxpdr z!S>h;_KGEULNFD<7(Fdr`2|5XM12jto!Mt}{xdG|)KI=AzO@blQZi5MV6^&_}LC7VycG4 z1UBOI!F9`Cc6*M)s31vkZGyzuuuy~M4sxdw^I;&gK})3 z!VWwCvf%pTif|UZYhvyxY@5bnS>JNPdhL!JLCl6}4TQ29zyp{y?PzPHF>irp13@FJ zzY@izM4_NU1x`??*QLg)oPw2gLN(4yinF4Fu;kO^(?aDA$V)x2a-K`Z#uYnhFYb72 z*9F|SPthB$=y`+QIzVi=0)MsaBmj)oo= zlM4xq>8VLDDHUacVm7^G*qea4nI(3hfT?wn?K0^ei7Tu#%Kq@Kbs3BIq`^*D1!q(> zkxe7I$PWpMiD7Y)%U}ZzzvV?Qw9#FvqaE4{>gTXa<(Q|VvP#072I~ye;o_kfKRtHD zeTLcPk3Vimb}Yp7wxX7578HY}hFy)C$7zsN`MNIy4y5*kG^aTI#C5I*mkJ35?2A6hqn%1+wGTLZU2* zu;d^{%ZviM>~3L6m`}!O$FE{3kzKJE29-U^Lt$I?xkuQ8Q{Ajj zsqk+vFV(G}=&NHFIs5HzM&D<^X#vBv75G?xkFV?^6B~#UdR2h4rZy&+X$pi%XNT#IZ)wXm-JV=6T=eBOgjrvw$|b z)%966USHJCYGm}g0RSdI*}v{Xx=WN{{%{UA)+QM;ZEtw}>3bt&#Z>jVK%JL`7f&d~Jr3A%AW! zW^)_~84W~LngIIR@lqo;2#yVDVZ$e37-xpp4ZA8kE>dhHn6qR+Hb`u+OCyqGJc_hQ*E0R#f}3qY$Xbnra`;p$z$(xT>T;*Pj4x9DQP z8b{+~3<})9Geq-pXnWBtUH5YPxEztrL2ZX8b^yb{1pQTjw2C=3 zs7fH#ot=x?m>HX1Hlefix_~Je@34Jgm@PYUjaYj&%6NxmT*5=llX)Cw4VO}FQd0#S zjfhCG4WoCqCzAqfn9yr`_hgIokD^b3InS0jDL!Nt(V-Q?4bYh&8(=XA@gG{ zlR5T|`W1_l9VFbdEtJlAjZ@KitbzJBJDwc^0^4=W5H)j0fj6sWf4MD{T+rTFtbW7z zo$PEQ)@1n`)-#!}ZQDQ2Y(0DYJQXTRhkT)gXH^n;rsDx!e)Wp?>>g-XtUjU*lGQi0 zMyH>RuMgZD>@ian?_N+Sh95j|)O6jnmcbsPb$qN=BR|hYzUQrokRJFAKwYY^dS0fK z@1Nxh*3#L#1aSeM5hf{@vfM{7U)H;-1Xj)_!|E&WUcnn)&!Dhp#ZhWlu686mNPO;< zrqC4)sSVw}{%;2S0Ej<$`Fx(+dEvl^hu0fd@ag5h(H=jvAwAi9>r&cyfY0swzfX|d z^hs90!#UN@S3n_+{rJ4GTU}y(JL;T+`^t;br>+Lu$#1^666d9cLHK)CzcP{w+patS z|N5o!Hz)*tLIUL_Ig|u)0LZ_8{L^oR-^~d6FHf~39ZKSyDCsKI3Urugev3>QiPW;| zR$I~8gqg86qBIJQwO>uaw{)B+|50Up!lI#4nPn&Hf=}vCkTq$UkhoGrUH1TEz2b?XnvIx1*pw{J8+ zc74>~s7G~yh_0yYkx^?|ZVj9bVauv4P&ic29;hjI<;fY|=vP)}ffpS#d){(@2x_1S zGI>yC8Ej=9YWCf%843$$k zY)ghEU2#aNh73eak;xVMr^sQ@u#>YcKd+Ysz@1T}Br3wE->8!bf7h z1dej6j_SE{M{u|_@qy;i=(6~oF;aV0QE8*Wo!GEFQsXo3q7Ho4`z_TktrYSRnk)Jq z0=&WcGormv9WW%p1TIo3lJH?4UVzH75{CF14wFS)#aXN33CX-2E%oJA3o^@^i zo6KfA47pKCgZJpKN!FZHl}7C_U6>e6MP^ng%w#GqY%!3o$_QNb(#5T{DjFYe6>Brv z*I7x|Y6hs=|6(Lgn__LJVCS!MtJZgu4@NDzp+`D`s1s=)1!A zpSR$N7b-bAtN2!y&8xA`e_m|V%XO)cA-`w7D6Zr#VL5#at6u-%<6r&ouh8M~*Zj7eU`plHcYu1~Mu`hkJiCl6P!Z*55KQ@U0$;k8rXFN=6Um2RX~bAFhrYM#sY zIHUzu`9VXD1rW2~8v)p(>HA-RrpJh@0OBXoI@3_NcldAuU18en#P`s@(-`_tW~2|R zKlpz;;NSl3=~yInu6!yr0n4tNcrmcBPgV0{*>{I|pRZR3-6SpTLdQc9)%|1%AT1@2 zGNc+WwMt%+AJtkeyYDjR7WRRm23TWykc>@^)jcEwPs@3%9ZiN~K%FshOEclQM#v1s zhsdO9N=yWJh{w7vw6ar;@8|oj^76_fxTt|DZ?JbJG#7JnpD2sxFT1G|VnHyUlzxIg zSivFU_U8tz=li+gcbKH2!^ydQ-u$MOjEzW>5}h)^KbKTY4ym8K{P{0C{gqg4Pf5um zKoSFOAKjGE(~jzfR!o_xk6-nCQQMog@fWRDJ(b<6J!r5ZfP(V~DIu%v72+wwXu+q^ z;qMW1c*N}zKAFMXxix)n3rk7j30dJ!7Y$n`#qxa$xd+R zax9-$Psz?gvL(dzo)0pyq%cvd*7OKsI)xt>yywzYpCn$YPIyM`68qfuwB;( z|CkA0r>a}J^Fei>#1BI239k(9wgp2)MeG8Xfe*6{%Z)Z8;W9`I7(xfL>O@{ARl$)? zjTAd@6BC%qtFoVn%`Wm!iv^1Wo|Au&tC$#?Cb_RIW-? zR;bOk7EXe6Xy+FAc!nKcr0Oy7&23>aX4jcK`U% zSC#t9kAC*S=;^_SudgqT_fISJjTY;|rPO+)e5$(JdX-Z}(3Mc#KT{P8K4g}7*$~iU zI*y%P<3{qjCdF1(JaIz-(8sDjl7&|hAV|qneyDaq?VRE52VQ=p!UY9_TxsA8k5&)E znaoHs0=otpVHg1X>|6LRU)~V|zRpL_n8-Vg5jcQT4nEYs<8r~9L?C^+&NG|5&{R}l!kclCgM zUz}YXUS9f`T0tE8bD4krQ{j8xMSs-?{O8ZG=5)!3@;JufG9{BDA%p{M6seBD6BWTK zOTq)(!p4(yNw7$n1*gnw#|D@8t&}V%0-GW+-^#iuRi^8zm0rYz49z^r%=unIgN&#eM38f9aU%BRM;XVL5ejVkWMn&4__6+&dw~HZ&SE+u0%04A1w`I(g@Hj%R94QjnSh0r8D;F!5 zl~~c<_-u{N_B>0<;F;YoBjKn`M^M>Y`69r-bI-avf?cZlr#(IN;iYBTqv-a5E%mVMet2vq#a}zO+s^%{9k*2&wIQt z+L@AAALks|kUr;m-{%7XSUDLM?b~88Yo|$_hISDyZge;m+H0rwEEJfN<<4O&QtnEi z@(dZm{>2%klxMd>Sln^4^#vp9u+3 zC>_pt`Gc`$nVe!W4hOO)WxDKjC*!dpY!@;tpHtvs=$ObavGu?)yWnNKlg@?-n@&h) z9Se@#jJy-KQz&Q)r?9$<ZN4cNk$jW$nq$nvrS0`*U50KOz! zm1ku`lvx5ZBqzWm{#tO%fIdc!2`QUQ!})#1mZcmIj%B7s^!@tnlhT?}pwcdP7PECZ zmOygLDe0QqdF3{0dE~RtnA6_>`}E55l}ER0gQG95-nsW-bMKpvpQTHUdzJjrAGeRb zd3b4FfnRUum5mjpa%`#EFiQPUlve)bAPTkA8-UxFk~zz?l#aR{(puKG*D&KR30}b=ohLx_PoF-5w~)alpvao@s! zLF7@r$Ii7gVnR%rV7+H7c2xJ8K1qRxb>E5tnH|liy+W51OFPk_6w8t|jg*nxcWDzX zLVa}-_Bt@&^>wk-(YpLc>&8k^Ut>+~8KZnm4yCKEJ)aT@GUdg{lk1O%+SYQV(t#7{ zL%Wd}YBp^50*5jlDKiqmx9$gw;2r?=ENk`Ay*3HH&Ck?lu1)rHecywv`~>!ynLKk( za0njH7059h_U!8Yb+POIdgqaue3Pk#QBaYK2>geSh*n7Jp2F|?ZA3u^2$Qi^r9 zT5yzBApw|;tjarps?4b2zgU65)wVIzCKBO>BvJ~s*kDGzu@Rx@tU!$r<6i&J2q>vkvBDIRnI0uH#Kv2qaQ!v^GQXZ!wT`^K6x5`SuWH5*9sq7}*6s*z#mp3F0 z#KBMCoH4WykPFjPVM^*0i(CUaNsl#LE)-q;WSD96b*i0mGW7sJcObSqgW{~1wWEt% z!H_q!KZ*dc5!)h!7~ZP6bdF7M(P*uKbUEjr!_Zi)I^=W)@)Z6W$nqDj*jwy;2I13k zQHX6P%7*20;~E)flwKsN2%+tZ7;i15l*pnWG=t_>W38$n#7!pCHISHWamzXb5U2bTVtBa{b{2$<|L(S;M^KH5m# zK;D#5zcHy@YHij08mb#lcsQoy*4U?Hf66GbgBVPMYb4b2DrIC8I=`cR^CT|M)A2Ek z8>LsqW#7jWjlv1gA{!3sNA{nEIl~6@#5>BeY5t- zS9vzhgJA8_7Ry-@&2I=Z^#S=0x* zno7!PZ-Vf<2ghex7}V#h)MxKS)IK|}L`#9Lr&i{b5A9hTdAA?A=$To&PTlfihgQq@ zF{#k4mivIOf5#FS81R{h}7MdBxo^#Z;Z zX&eM+hjheOHp=xKc2M@T&^Nx|h3DCXA+?WjB8 zuJ`NnA%ktE+oMsPD~?|=3=yO;N7bmUzJpg>9``ShS5~opjH;E3(kB|JkRw@QV)_m z%jl%%aP9;9h!~{p=pGrB;P0@scj3vG?^fH5`wh`l#=>AIC3;wU+TJWLR}UcS4S862 z{#D1ATL0o?`#@4-#VRjc@> zwu<>?t5Qx$W4uuyg>i#HttUpUZpe&-p4mX0qe*i#9EG=H;W2hg)gI*nU@%n#cx=6d zUg~8P;sUgG#iC&@%u)zVD)P+0&%iln-?rJaVwYu23v|j$E8b}sH}yP6v{R|Fd_L%k zjWuhj%YxOen*s(McI}yhJt%7m4a?1;gZ78~7qb49XgQahrlv-bi(v>*LZ1zvL!fvn zs6}aIe}`H7E(D~DxvU+)Y3vG9Ahm2S0I0~b^p=#6*v<*fWeg1|&xS&3a5`5G?I^os zGK+*-A}nQwbGtrP-6Y#781N#a^_4=Rn_5j7_2mv8TLtne4CN~CfCy(IkMJ1OM1A54 z>aLYuRSD$nzSGf?MqBvXA}^U8H4W(ttXynPs~==`-y=n zwIqVvs(Luv4l`e#$eXO(KS{jQT-;R>KIZ{N6|aTM7%m!9cU(ech+3=$nQxbwg$Kf5 zX}e-ez->(G=nN4c6YZMe$Ktu&^MEe;shG@8ey;PexCCR%32|oBT3S1E6(x0PHqKHy zzyb{-cjJk;JX^};^zE;DD<-jJ)jisGh_eFSQ^dSVHuHm%br)2@2AMGDy~k*fjxZ}i z+%1pQ(8xLMs%Nje*8%w_SDxqdzx(hn)9L%6*M9xi!Qa2Q`f2*lzZ#W)c{519 zJ2?65o%cUpsvzb%y7$3zyuH48mi*Zhs6G2xPFzorrZvzz3B|Nqk*CN$EBY!{!-JM* zaI_*VvzwGu{hQag+0U!Dz2$*9v_BW!Gvi}C6%fIirMarrwH zSOD+|WegGNUD>a!?C-JvMFUmQinmf3c<@GK0A5+S^`h{3v;3RXGso)6{)=F>8Z??} zd#e!$-0o@@-0*(4YMU~gW+O3PG#sXh_Kkvqn>Qcr?p9jLfTj*uVH_-ZSJwY6g8tK* z=@{LWi_s+(@7A3^hy4x! zh#;!37KXm!8daWD_s#;vUX+MY#@VYl4ZwS@4Chf##fI9$&i(9K`*xJW)e$zkH(AJ7 zKLgDJx)M~2U{K!oTElr=oYj~+q0+EwC3%!ahKU`;SJn^eC8xfIibIyT+W!LUD(+>z z-tlG!nVk;mhkbNiLfMW%_TgyHz?4d)(tLOze^g(bc|@Yf-a5nY_4@o%WlNVd9VjX3 zs|N#qyXtlFD(_Q=UR$hIBvjP{pyzCr+Mv|NeRy#}lo(W<35MyEC(7bJq!deRN{1DI zX@erB!eXqXV9b~vug*Z{W=f^CDz=5+^1gPmfKO+Y9H}3`_)vt%1 zDm9a#7vl0(AOpT(5uCHj zha78%X3M#+fW4fLm7%4I!Z45xPl3v;tEHx=z+(|Qo#ZJay@g~sTh8WkSwLIk>M19g zhC)@=yi-Hc&y5Xd?TmKtDU_Hyf}BIJ;j188y6AG&_;Z*#4a0I4DsQiZ{9NahH);r} z;*1*oSv9IP8epwGnW!xgYBs8Y-ZrigDL;1g6xJkfkJdC=R9F%%mb$Rxrs3>@7!Ib? zs7w}G{mRSKb>9-08>P_mz~x)Pgu+7^kb}S{)?@9Nu>uRVfm26b^*bykn&6UdDTGe^ zldZFRZR;?@c%%r`t(?5{sL47_2C>7yNz zfX_(UDY5003xjaX!{ul4oR6Fs=Zp$j`{<0tKH<0*b-8_5xA?5U{@DH}+*Mg=N4ohZ0E3oh1FSHnP%3 zp^~aRz4qIaC^rQ_* zDru>+G_v;4>3PxGSsmC(8=eq#A+)NDD(W4C?P``il06B1wJIOJFT(oWYt@7wo}BEg zp7$?!2*>SoBAt4T41m#P?d&++ott}j=f21=?Vf@8w)xh8vUT-&PwYH~a+u3=<4U~kHJ8(eG2)3nD@`9NjA z6EW<8{JmsM*)76B3emd^spG+#ZW*{UaAIoQd}DW@hNK$#nW?UN62}K}J;gEQ5v@g^ zUJocFRA16WCTJ3(FKgZm6Xv#Iu;G=2X)>3AHKS_XsdY7nD6!Q01-{8Wi%zYl{kaEW(WmYRs42 zH-sao3r#H^p;OKqNY{mu3r7mGP%{vT%k~(FGBaO0048i`(?#q1RjCIf#durR3N0Dex^ZX&|HMeK5#wIz0?B16 z&0=oMJ$PGg#fH3zZNpC`jIy~JM@=KJhPTVju}e#uiVNp0_V34WQw1JqvzmQ5hZ_nO zpoYt^9Un&Sr4(8QY=i(sAndWo=~#?e0YTax+exIl67eMwqwg`)&_d{L-`C8J+6uZ1 z9GdNW%t>kIQX`^HaZIw7P&*jUJjyhT;Ra)*T{#q20p)LutFy3gWp!{erq44fYLe9$ zld_?7*2m76o^Uw@`%Jryh-S9}=dzL`XGM33%FL-$BDb&N31YtRHG8ngOy-ecF!^7E zfU(vM^m5Ke(is&nQy+_ln;QZWO4xDF=mz2uYAlJt>6OaC<~cU|&dFtxtE6Pwbl2~u zWK)}I>c+fGy9(Gy`EI(eou@%4l{U|x{@}sgKV19Kt!pHx0tDNN zvfNZ(QrdikR(j|e9Gh-7+T8S@EY&J0#!4Aq9)npK&Uz8>2wZlSuiFeRJ?wZLgjCZN z?rt=zx2R~4`^w|Y){mkbNje5^F6aOZh4(hjR8P}yb{mbW&u(_$zUl%VDeg*N zON;*l;J?h?bdVk?tV10Pkl`V}+kYPfZ@n5gzX8P8FMMnOjFDDT;#~vEH3L^NGWJ@Y zA+`9V_C&r~6h{+4Y(m6_Fql9_tV^wlXLQJ^Gtj8naB(8*Pb>p39w+5Ydw+dP@~K7g zFBfG`vhx~%rwmfSxr@Jdu(zlig9*#vn6MBO#uH7KW9gg`e{qjcdjdhHDv3tH4SF9m zCU+fIe4g8ZoDA0MAz2%W+_0MurBWj3=7%Iq+6g}&{s6Qe=tBu^!u&-&}rtM9ejGU8$&lC{>**eI#iu@uuz^L(c;$3oeA=hY2QbzfRm z;1N($_0KO91i2uvfOO%IAgY2R?Q}r~pgMg&5?rZf&--)XrmSPtJWn@InHm7~>oHgM z=AH$CrGNDl*XQ>bt5e(xN^32A9`*_3`^LihnUye`0f-%#t3^|h!9-9=a zM{HV?f>ftxflwIL*TpwZ-)Bz?C0tALW5|CI%fzk zEQ6|ekN{ontPo$(4$Zubpl~`on(ee4OA0LZ#tok{qb4C$&$x3=D`Q1+EE7-(%8n%i z6??{)BoGW5V-LXf=cU!^kF${n=7Oob+K@S!X*4wu!E)c}F5ugD5N0Sm26gG3175aZce}*{pGQHmc&!PLzQ=C0lzu7h6TYHCT+GSI)K12EFMT znD@`ETzUD{>)?C+doX$2;S8K649`+WM=iHK! zSnN0!@T<3%{vuw}Ek~?CjlF@Gv;8;>xMTVi>`#FE0T6YfjkTMZ*hbrD-T;qdt{(5$ zmGg7$`NFAc51+Sn6~;LX*zVtv3hG^pIz3Q z_346EwsjTsDa|6Ud`KqPMfKoPvsW)7j#3xUVObS4HIS)Bc@kj&tg9ZnBDk?lzkMYt$YqD4sC!rVNZ4KaU~0W0InqPFls74NjX7 z;`UhJE%@#Ow~+#*SpfHylI1njGAaS%xmQzZ1lh+_x6uX>8O)Cjrn7w|UWy>+occC` zz+u?Fj>oEK;*>$A5gp6zv=1wkqATi?lnHJl`^wqt0S(1X(2{AlZWt5~!Xh=3@g1@n zBS1B|i46zG+7z=Q&MLM`jZB(udyqAA>l~eo+D#LfDIgUw&IFIPaz0DXxPDm>Ooj;2 zB091BQru%8zhWxhkA&`95cEI`ayMZedl|FW#(E`l6#bX4vwLmpFvEE4DNdLbA*tzz zEMZ9|5=4qs3tLrvS{)HD42jfPJCT9X86yjgQIeJwqMQ20V93CQVS*h9R2Rk<3xp(v zx32vNaPD5;-}&a~#*2rE=O4W+^}qh?{>iQU z?((Bd{`}pM%eE$K&mFq+9x81gVckth-V8x5WZdme-P7Jc53!UsJDM#^F6G%-dDlNH zv$E@{m2s~`5(RbGt{Kn zSl^}=w|gT6YK^=o3CuR&yIhomsaot@&Ot=M^1ZEU%g%*A=Zap5s5jWGhL<%E4_nnv zt0)QeUMTh(wmQ7Ky>-KbHgcm5vuo{dPxZ=Sw66~LjF#@nAe<|1z|*;;(5Bih8p4iJ zw5qwi%bFQCMoh;!b!2}rstt>c%?1l?(RC!=Q2Grqa`4wm7n zVRG@xmpgV6`I zSu!jbDKjmGn9gF^Wudy@6qZ`r`R}&{qzIJ3MnqTh^NLGUid7VkXm5+Dr=Xx>7_Jt( zD6q!xS%WZat7#ep7&c3(JmW%Tk|}V{Vq=vZ$RLyk1$?nHtV`vm)pub$HmDo(N@Buk zG)m3pxPa)%F!y*obD+D-eR0Tw+DWwxjd2TcOw!It8aswZ&In_T!p@KW2?br9;~#@(4D{8fcf-lMg;aRH`E zh6Sy}TR~!bsyfs%7(%biEN?5+yjfw-5=1L~GA^5vGNAS1pjta$f8sWzuR!7VM$tr3 zjubulwv({qf-E=rc1o*DZG~i=22`>n-nsw!lj_c-!^GMSI|-DIuOz{rHHai|fofKz z94#uJ0i&o4Dz#u?aY3ExWFb|q9?65GkgHxDT8k-Zed$uM{mu?}-P;GD$)|}Ny~qb_ z59}w-{l)?O>({vpKVGRKy=piN6T{4~STdwNFXttA8Q~T7q!zi*loF0c46W58NL&={ z^z3Fg6~}DoD4`W+LISe3T3|nkk|MET3m0-r_MxistwBPg*+44CYal+tz3Zds(WY;H!Rrm7 zc=#C2b3;pFU0#efJ@3nCE$^&PvB5u4=q1TWx^hHMDwc!sL2)CeWXs%@$<+^Q$cE=u z3_uT}aO3$EBfqo0arM$5QBe>Q&C{Z~ebU50*&|ToES4YI4bqEq^I6?M3kA?poX2dL z>OHm7D*V{n0Mcr`#f!_JSWDaV0qIc`$-|usuvSGB&lScbWf)$ni-3fwdC*ddqqG+a z0Go5O|%?ZyK2WOvYm~6Ds{yf01!@SrS zuW&OB`awX`Gd`ka25t8VtpK&`dkpV1D4qckvtqJ3RZ?UFN=cdR?wGswYYg@^o41n^ zAcL9Nq|W3rp^zNw5b@xo3$%C_fq6t?!Ef+VaLOZ4Wq(nBqTfskZnI7CSuh(oE*u-b z*6pNVHmUWq&gmC)gkBWRd?qkFrEP;<6haWJi#4N+6@%J=tc&V=E-OZ0z(@^Pu907B zq&Nm920*w`Un~^{!m$DK=s;i_+QW&-Ne^GUFQjB(KwP-_ogcVxrhU`7Zd9ty)_l+8XK#&!JeJ= zbZZa~Ew&&Jv{h$ZY{*<2?=q&{>2eI?5ofVSR@(%OHW9dpJEjCpPwT>goNzOi8Y(nh z1~J8;2`xEH2&!W-6+hVrJ!Hl$vlT}wGh18U!*aq4Acu+A`9Q>50<+j47NvEwFb+O2 z2Ao$j!J9Y8f7^njy!wkWkr7B7SQSZLK!_W+?r80y*t*8a8K z3;#U1asOIteg0pMUj0dr z3`cDh6*7z_mr_~QsG#d7*T4Gh5?J?_CzEhBDqtwBzODN`P2;e~NU0*7#ix3+i7vI?dx7($XPo3M544MpR>Ih5grKP3)!TSLGJ`kU~asOsjX4s|>Yp@HN zfkLl8z)S=gm3#>+k4(BnB}<3Y8+o23`4)(_G<()a*$%wiQ2Z9l=Ul_<5vxe9J6s=V zfz0ICko~cm927FbU&|1cvLlSohN2D4p&`SPTyq^_;Ow=&+E@E>IE2_Tv_@R*;gwrn z@ZhD5Tbm7Vx}!|aB9%&HgIt+>dUi#P^4~A0duIWy6(zI}R3spp>y7d=>grPz_ST{4%EYNU9kR zO`gSI%R9}CW$KYx#-k`y0W_zoJQWeZAP;=`IxBUr#?CBfnfj&?B}4HJBrZn!EWuKN zsHo&I%4kp-sLx8Y#HN(6DDbl&%dEbPQl`m^GE_`!czj@QpyBQe;-#$Yv>^3ZQO&5S zv|I%;(@8^Jb#?-w@p>^0COPK|c`PPddCJi;`P6-Oo1r zh2*h40TBjRoBh7yuyoTBVI2ds&SLuosjHge#P&#^BLus4;m}XsE@<-X)Rz&pIJ;pt zfPAK0snHI-Xs~KO3}C5rca+73i3*6(NU3o$qUeFPzBQb}1Dc~NxP&XQ!-`$SlX#1p zLZKV74_Ayu*YGga6g9v}K&&RvOo|8PLpd|#WU_Np8gGk(OB$--b_HBHj1ia{i#YE< ztxOb0aLgb$d^?Y3kPQ?brW9damhFj9Oz?J~G)-VsYvzG>7N^LR4xID48ha`x%4}RU zkg`h=oLWo+l19&ESPs5`7f(f1QN)47hD^6*4NegynHma?ktqZ7hNwaC%MiW_qaBJ@ z^Y({2ZF&$%sscH-fPd|#r`6i7Av6LqdX!@>7iX=`9|Rt9xndU(!P%Xnr&Iy6b&rl7yh=RnR1l%oRPRnvuVW5UEEgDp>3~b@){(p&|G*>Nhoh{G>wjX za|0vm_`5+IfB%&P|3g{OJE8A&wdlR2C}=k#twuBHo_7TQkFT@)ZR#+?ctc&QYFyX$ zSQmfHu~F=8wqjxtV`3UxP_`wMfLfDP$0N#)kuS=MRPDo8xrr2wi*OU6_#zivATEZ4 z_>jUhAQCtHVS9hids4wVjZ)$G_?%-Sp~uhrJ|C3@&%IjOn0fs3!*h4TJ&|I2-BE15 zu~-9Tt2IR>C@;U^1+1h3&jYo1Hmmg0G^!HbRBOsg`r@_Z%&4n;xeF8S8Qj+29YHgi zUNfw%X!VN{YrzFrY=#&1rmp`Kc#kz%zrX(J&egJJxk`H^kr`%ZEVwXdv{8xA9syZy z(FG_`6Pe8Qx@OADDp^qCbGJob!$=~lvK&DLyd%w3eNop2w9# z^WM{aHPsS_ff9LotaA`j8K9Pwo{T)%?qwLa1=a!BD2tVroKZ90mfC(w6cyx!tow0k zk4v8VG>v8nYpn6)X`V%{q(~@`d0g5;2(_Ox#8L$E7DA@@w9BLHA?E>IW9GgABV34R zDP@3eFq&^`5NnT1V?%RUXB{U?;*D_%z~&(0vCO9d z;fE02Hfvq5Tku^f1;A;$6hV1gU@K7nHkIcB`P2Z=9t6kN5??kpJotd>NCQcfn6*W< zc6g;E``}oEF3TFwX?)g*a9V=t#su$Ct;Wmjf$`pO5=!ulNE*(}%W66|DUr2cqN7^O z22p&J9M-Cy;o&j4JX>vu%;HH7J&UUf8cmeE6*IQ&^jSV+Wret5S%4h#DRh-!%Wx_L z7X?vnT4I<@R}(5}!PivB$JHDSqdaOn$sPHQ)1Ims6TMW6lcdW?!*Jb74~0v2N~d(x z?_@um;1aHpig~hEOi|XdElo|GAW-wB7eDzL7yY%p@2N26C)g7=dCPQ9qqM-YoT?d@4yPt!!^WCJ@2HCDFO`q@(RM4Ldfzt*FSVB-3jVq3NUZI!VwG2A0Tw@X zqmPTU7$j$32M0>as(g5Q=kTlBuM#tZKm4gzxEy@atF&*-kn?f>(%!-8Z50V-v*)io za51%JyqY?5<(_gT#cQcC@*rweB6;g@vw8mHopYCOJ!w{cedgrJ-@TkY`|pFkN<`{?$((GuWl6n=hR1fxHwN)<`Z}I)cW0m?R%I!lH^; z8~08%)B{J2o2Jt0W`+8ad34X4Yfcr7DBF{9^f`?$4^Uq5fESb)O(R2Z;p*g_9k6n)-^+sjYUh{bZkMU-uA6!3vz2U0*&AZ5-60r+6KHd& zXv(_E6I3!-SDKUo)3W5s-enIhZ0&kLv*b?z)37jC7n%v~Q7H*E%Poi8x;QaK37))F zepG)Xzb-3gbpY1uyJ~IXP0>rF?gq$feOOrLZllp?IE?y-H=_-9cVlQ^xx3kFd7DDZ z7;?A8+8M*~NG{|k-g?(4{ZNt8pfv$s^%X-{khn#U@QA;qR^&_`7FN_`>_4{XDsB~q z%cPMIhrP~fy1sn>{KqJsjQ?&aWRYQRE?&$O<9RA@pMsNW7hoHUxEV_73)h_Mls$}i zE0>qaC!>U@_`a%qrsJoS?HGCa2P&UlA*BGI6TFO2b7Hg*jfw4Kh|`I=OpD7Xwxlk-M^8bwE zgv%iWBO{k!Acb4vJr=@9ZXHfyp%)PI6Yy9|d(v)f;?+!E$#m>Pwlj=_PEbd@sV2Ydb-8JpeQ-x4TPxRC=cdcBI#Ogqt(D}3h{|}i zdXB}hZ+1FL`ASCYT=FXR)5(Z#ljxyO#M{tJfV*!WtK)Ds@#U4h=CunCD~~U3y?%1xx7S|X-cBqeFMOY!`^$^MG}p-}N8UHuQ&_NtIqUg24sxAM$)&*mzTC~M}({+$%b2&4s_*3@|q z*7tbeMot}YIe4-1jP7ApF?imp&My|{zj)?Nz-XLl`i=0nw@`jhghlV~np0khpDSx# zh=d=he^9&r|3p}qcdm8m+AAz?3a|`kmxt^(yX9S|Dr~nqqIOXGS!xS5-O|G-SAwj< zNR>h@FG!M534&X9k&_ZONO0CDdu~JBhojL(mkOfpkPd|9I>TEfMz2ujyF5Z-Z6}Y^ zgtUqAXQ;{u;v=D!I;gx%d*>VU7!{z=jE?K>s#2{(dBdvF?7_hEi(>M`2i2xzQff)NGZ$JKv@+*``9T9 zYL43veQc{OYbv9ys#L=`fSjs=)IR^s2gm4HiuSVsl-X$MSeTb;KfIywZ$5%;gLEa`OE+qj<7kE`ZgE@g4fiI=pud@dnPCi+TyxKb-7h( z5S=qf3CQ_BK#lD`-rzv$gNA-B){tHrg4PUu?=gR#NSQT%s=BC*p0GxNCH2tQdwn`h zwWY!3+gepv3o_TpmakF0CK8O~O24bsNmYG@c4`=_QFW-LGW=KD;f`Fynrnv>d`-~h zq!+kVy|J9YE(6%4U3K20w(u$$3|1*&iq)jC5p|tJtFg)X5E4sA zJeBk%YD3#p<%&p%oJ=c0lSeVn5V@I-KsX&n#^b6YygHHfxD!DurB6Cft6aQ7X&RO% z2JKv0&sHF+7c9_wttHgoiRuSY#Y z@F3AY|Jmd0Lgv=TcXwW`ZQpv3*gpM&3Gm)G7tTUf@iGxgx$42so&}QiYz@h>6Fye< z)DOv*?_N6F>;3cVtGRz2^s>)y-MM=Ehqd9SC!b~a{<{5}D}Vp&%&p|i>)7XaUX~NR zS-1VFr%)bX1y9auzOD*}Sz&Hpm4kidVKoKNyxJvM+1}bJD`9U)I=b}V1L$KR^rgr5 zTkA3%`51b=;*zX&e8G}AFZCle)IZiEhtksK)tMLJpO>R#j`imu@%i_vi;Ko_->T6S zRTeP|IbeBFd4q~0T5Kp8so3y9ef#h82Uv-`R-rGKuQ~?b^8x?uKYU&9ZyNUE}Y7lnC+lRy!M=$L>qD?2oXD0w9Sgwb<=n=zp-Q~FX)R|R{SDT z{9@W0OP0r^L|T_>d6Rejr}}xG&lks=)2+>`P5m|0O1&xni8vX=XyE(ui)Hrz)| zI+J{aLrx~XJz-;RbFiXyxPn1}FvW=(>I$TD+nmwuDGD5HL`lP6i)6|STZ1+5S)OBT zB|3Z2!6dk^1-w|q%I}5)hHGR(Rvp4G#6I5g&>!)*32~I6UMMcK16Z8Z4h)9M24T5} z5HOdUg`wH@`rLazD*Hhw??yh5A0h(`7~5Qd65GxUMj;K)qlsJ#LMy>q;BzRa0XrVx zmIXH;P5EFq&Td@=@tps=I$w2~i}=RW98J3OoGc?KF|9dMNb#RrM&VtWxr|u^I*mC- zhNm_~3Tug*N3K53>uq0g4Fh;?ndh3$sv7n)vNr>SQS zvZuK`Iqw()Y|vVT%@ka-b-}`URV51!Vup*yn8Gs6f{Na>CP#7KI<}~H626$Wh`Sc4 zuqul!l3Z$p^F}93ZLo@=_>4s$m)isoM)~UHFYrq)WECjot4DH7qb~TRZgc^fy&1J7 znw}4c^?9YB@}NJ%U|j=Sx|y|to7H z0J|>ZY@@o5uq-E$VS|RYl#^lRB-VMCZdZGoX~Q~ z-z5&In~bLx;uk{1G`hK>4UdTHR19 zaxCF;QB4;$ao(Y~O5P?ql^Juw4~&_!8l~|sDkgU~5ytoO-{qaXAg+toIG3&%DQ}oS zs<^2hq@#z$ynsiTcj8FI$}PPn7H_oTuf6!pmqfjiklW6dK;7!un%DXEcbgwB{Lw$% zo^IUud7@|+aHs$PAOJ~3K~%F5Uwn7x8v-GV5pp`@_JF$`;Q0pWuig&CP0BOD6O&;9 z;HB0VA5TBNUR}!Fu)4v|{#<=_`{r@()%MH#ck<7Fnmn%Vf3k3GJ-%19-N%*e_e znH#znu6hQ5i*2oISUWv_{O?~T|Dlqtt;H9@YSvp~X22X4 z(!^pE@r)WO%#P=k z*n*8dg$|0dW8i7lnoDI7DU5yaSnzht!hz-Sn2y$Te#~&kzoj_$eTu9^=2fs|U`)+2 z;4^Ikic|AKRW&XV{MF)e7Y3d=YYaH;>e4i&3t2(iG55Jt0;ebvhJ)6^8W%cUd4Lsc z%3{r)MKv*4uso4A$Z1()3WT}7da z23BMA?XZE70&5J(vAG3TPf*51=@noSRP{)BbOR3MSc4{C;~e(g z_OiOyGsdTlSu!OD-no_rZzwy46f55P!{)R2O8)k%n@^Aw`QFZb$69-JyZ?J{@8(-@M-fi}zSGs2gE!g1LTX#Acl6ipVVrv9S4t3Cq)g zwAYazJ8ePfs<9#ck1_Q2*_p;b&w@5octumN{QYQ4Anx^S1g%L}TU&d_)9cUn&x&$P zxVRX;sMRR365@-_)+~!y5%DWXTcOjWP&h>4xkexzR*+Cw&|g$oM+hQo>Ie}`i6L{b zd2s|y(3Jy<#kOWp%3(zu#bxk=#Qz&XU-@+JOYIF5+!gA_{E4z1Xo(-3I&{$rs1E!U z+t!?8wH*16Sb6}}Rlop`ObEhAE3Q8Y>=Wvy1#-h6$OOWb2W(Qp8Jb|JVF*+mBC`W) z*A?UD1)-e`N9-GfggSFFAi8Q>uOQ*-v%oYW1p;%v?Vn&y?fZif9L#=3n}cy}wgwBy z%l|=rw7IeCC3is!tg3-zB4)@=&G{A3DwWIqrk@-WGL<$syr+_Vf`;oFNo}u zQBN2iz2Z0h5o?kds`cCByO)>Yr%jFL=F!>?QdvkNA(&k|$Vx`k1u9~RxA?Zqhzn|) zvs~jUQPtp!F+z{)h&yJv4&+mC*jkK<;&hmu18@VS42-5ZycV1me)tqQ5HRpS$AtC) zQsoq2l99;y9_=}B6XmsGfa<2P(fm?nJV&JxHBk^J2|pd{AejEv^jmz@QEr!OR23(K zGd>kkm{Wl%z(SIaW%!s{83)ruY(BV2mal~EAUzavVB8bd!W_b8KdouE#oP|^LR@=z6#LV zv-AuK!@c_X1iCvrO~2RG-}WxS3E>n_1s>IEt{@L10-{Q`;=&=p$}GVEtbPHza&!qK zRY0|-;0hv)E^**2QMZK9ERLuvP;`MC18N(rIYc~P#CdiDZeu19l%kSm@F}ox((KSz zEWq~$KcIj~JIfo`IWzu4>28#C5nBz94p^rkIv8%Flq_-R%=vYLK_Q^A7+O07&IBD% zn0G?~%mn z25*MV+&lxYIqQzdnFZ{%Kbf>1J8S)>EF7OYNy&IA(mM$ntI!)s3JmXc#P$ohUW_9G z!R#L#mk~3`Y%85G=O~WS28Io`4UyCWm4%%mL)rLlmrN(a5>BwB1Q^ilam~v>4J=<< zjJaBB#XEA);z2bY|N8LL&o;N;>mY5Kqvg2jt=O@orH7u<;+(c2@;urYaqCLsi^{_D zSL?_4aesaK&(GdJzSl@rzuI~5VCOog*!v6rinl)6Igld`qU{e?=|@u6u&#i?cH=}_ z&m?t#1?LzFP0f|3;%I!w);P{C;a2;_`osS)0YAL313nJvFd_%unuS1boqL1Vs@~fj zaFJ2b!{__^KmPoymx~6bPcd%R)Zc93aF>;E%TITO?h3=5ub_;khN{-uZfzd(>1^## zSn_U-Vf-Kb738-_NTt09agzvm9$l~@dDU4JLlI6S@?WH3acteH9=Lz{o<3mwS@^}1 z$21LTzplM9Xf^|=p3Be(`wWt5Y8Mf@kl1Bl{5f0`Q>isVD*?D;z?%AC5@eux&Y;z3 zAawGPoMQm}FgCDdq(lqGQV`9}GX1unm+j#YlW|)nV9SbNn2&7q0LsCCIs5gr z+!P)f4oGMxK4n`Wlv}>(lt4cMWL>%q_D5xZ)U?B)S?Nxwc!qJeNeR|>be+#{Q~4Fe z8OEYg<5G_`n#Qq9>?pRVjZGqKc`!q)qDXZ*4VA`#=e<7HvRl&*VnDQ#SJ^~DV&Pd7 zpZ~G7+A2O|5xwl+^<7AY6&FH%k#6t=Dc(7`B9jt4!AI%PNzNGSkqSP zvZm&W$np-tS`S@yO9@*wuOLG zgFRMVc;q*+(}kp>4))Gkl*)=5CdwG*N{f!1JZhL##>K3tPCky|u4$iIY7?uBE_bHz zMUO_Lf0ln4G1bf|4@F$cDi4Bmr^xdt+TbYr(-~mQs#fM5j7c+htOBhtX+SOSiBK*h za?1~{p8%d&rB7&}8 z8hD$kow@+9s`6pNKI&CZq=pAJf$OR}lil#fG?|a8JFju^x9c zqSvp_xSnAD5BJxJ;Ml<_tGTac&YK=gNqKMDSHMi3;fSkm?Yp--J8zLeE3q-u1tXmD za$ft?b#aw=wA9qH6^A;*T&`dK>gvN^hVns4l{fX;J4)jUVOXm!!0tL7r*;99y!4Ch z?ek~<@%_gy0m=Ofub-Yjxb*M4(ZxUgdikqcXRq(>baM}`JX`JVZ@=#L)0?#~w-3DI z(33V4*CEhV>(gpi9-~#XR%u`LDsroU%UrfKFRd3wQ*xv)*9HF`z)q?qVG$&I-7dKF(xX^HHs1f#-ubwC1BZgnCez`P+*Qh2o z;H_HkRkD5eSE#}462p?GP4ad|BT_<2t%*VVbgr1{Ldh*dpufU3=Y`SjnxkmQ&1$)7 zjPQ?;7G0x+7#ESdBFACE_z<)2Gz z+d3gKhXpHxiRjVkX-DtJ#ro_N)x}amK$j}<8BEI* zH3*KAcrpEjZ5H9T@e`SgGO%FCDYB*{PC!8eS6FG18N@sjFqat0<;bzmlr>jQV!viI z2-um3pz>UMy;!T<0qENnz;X!OjyWgdwPGQ0;#w=F%(1g#!Efxd>sU0ISB;?7ahOuu zp%Zn3I!qB@Y+a?LYfxFH#|FTS`q%?(I}IUeRV3MUTTSf4V|rc;!^yj?iapmKHN5`R zV3etK-M{JJW(uiW)O`Uh_dK+ixcR+4kHzwR{2q!z^Ce;syo{=2+8i4bAn|s^QsyyxJ|eW2k6S z&R)G5^kCsVfYzs#&P^(r57+BlNlq<(Ac1-6r~B)lITDOc_a@{V6e-Oa9FU)E$d zB)K3fo$jB#^5)gUa_->#zVXu4``fQy|L(iyr-wJ5wNEbJyYltvZw|{jJDTf$bL*A* z7e2dkpbRV(J#4BNILNF7=#po3ed68?8t8QJ6RQQuqbTJh&K+L3x!}J?60ARjD9V>T zxsWcF%jM-^&)bj!`r6-(i{;&Pz`@<+q1QFc4-eN{2iMC%F?~pLE4^_P+Av=Rc?G>| zs=`?@1g`I?-IY4lr89=sO-fu1oA*9@ru@nNZcsnNh54?0JcuJLZ5FFvao*jsr$TRR zl(iCmh6w97NAUY23ViLi`?pJS@EExC3Ufo#NliV2hIv%(s$Z9iAlix`qH~oGUPd`x z`n}j+iJ&Pqr={AuegtD4DWVa;8n)&R>|2EwtbdIp8tw{mQB4&TGFh8mR``Z&PA&xN zwWLdC6|7+B7hvV6_H_HNpTDu20swnja%+-dWs4MMT8+qIE`@4At(xasp%XY5tGF9b z??cG1EKQ~1(k@$a=7P$STHzci!R%IIs_n99yL+86M9nAD=|m6>Y||XkQuSeBYl@NS z>i#DuPt8C&FgFZ^1+X}9Bo@|#S)SMiEU=7ri%@2!)iSwycV0H@UoiN1t&XQQWuLo# z*pA{4QkRcC(Nm3~s2;K?I}k}sq$fIkRGUxU6~OI$gd|D_^A52*h%n0@lPzV1l6e<2 zNqiI{p4y%*5rxIA;54(a_ADmK@j^Zo`3lz6N_oRNM=Hm}#Q9~SO>Gjkvv!JGZKEgR zym2%@_++S8JOc7KD2>B-IP%8{NH@?D)&R4;5Fy9l-hiXvslD{T(A(fQ8AQ5#cr&q- zUYy0hB=$uxBWhSRSZ`l_@e5wZ@aZHP#5@-2YMLGM$LH3uQ)RuIftWBSM#%|8mt@6* zl87|x?;6bx`8@`hbxK=|5sx*Vwok6tLV9ICANT`eCB>$dNx2`SVd5sPcRFj{%EWU8N{!A!yG73%CgidA zKLAiwCfq=psBnr>VNGteX+@~b3fZ@`6$5GBBVerP%(39m$>`Xn)nsKO(o*sV%h<87 zPup$PGHOc9nzq91ni2WwDoK{`)0494N-$;IxzkXXHp^$p$(#~bw9l=inBW85j~ihX zOg$B{ab=k37dFb=7|V*Cq8-EjyHa)b<@WJ`L|C~HDXE#VGByCvw>wk~DlQV=uh{Xb z2RGB7kb9q#)s-zc{WiDYtPG|-?IP_YSI?EmE3LrEbcm1K$qB}tYwqlLcTqZYKX|<_ zA6=h?ul7IPen^bf`i&3!hRyfSAH4ed!RJq3-}wH{rQDyd{N&>ccdl+e`1#W}Km7g9 zWi|WWy>&ovm#o05KI%$my@L!(aUIJ3(x3jOM&i7eeqZl=b(a-zH|IvA?)x1uGOXj9 z;9D>ETMO6G(5nd5!?4K2!iKaEVeM{cOKha~&6oEt|F9lv43`g^$=sz(_SYvhUXVg-0iOP9BlbHzuGv9OUvnvx9prbFYBbMUrh+}7ZJWT@NnI$ajF zs#W45^SKO1rLED!+08#**x$nBL}deOVPUZL!|T1C!zSg1_6~a!Cf=g8Y=qsW%&}6d z)q62iJwdC${Rvr`R8`bG0L%WTJQKPwoEZAQP)gQ> z`oE`ZQ}Vi!J`8Ei5~j#aVD>^ugCirQ6(1@%$OzqFzZ>w&x0GbtzoifGLgX;`9#=`KR@P} z;h1K^uJ~OzXxqUw>#X?rRuzOz;HqeZef*jUqgX9f`FRuztJ_+O>L+c1lYJ-dy71{F zKCTAVB$e{fuja!syt5dE;c)C)COvX`nds#P3%Rio*GxNzjR$-K==qNZBBchb@xZY< z&OCwACiZXuiB3SyFYL>}P@LNUyZpdj>Pey~wkq`U$_#_v7&hx&{hn+mh5(nJGPC5Ww!DG$| zeFy2mckx~^=uFpeh@b#Md4SC*iWQSbCM{exQf8igF&Z21N50an8S`BuXFgWM-q?vS zLau2PxRD9@bGW4QDy;+9#<~;(&`x4w*fDA=P?UN$9va(Y9Ao$r7sQ&qwoL>P#aCOB zv7qL~ZbqXiFQ&ve7K%^9SduQ)uEu13K$Q`V0bijYPJ?mZ@*1GU({||o-cUVIZGS75 zW|MTyUN~N0Z9SGDh+7Akt2!jGR~5K3uroykU*Cq1Turitlx^SeLSv`KpV?k3!?P_5 zwZo}sIG$dGXpc1r=V^rGaBq+pt9C(wpvc#BNuExo$+MjTk1m!Qm*T(lDleO0|D)4yo!yfSsqyDqkF=eZm|5rw%+oO_IQGtAl?iJHJ^MX)ve!^G zu+-DonKli8bNTa?+<-Lu>D=BPva3tp2<&!X!`Q6@bMX4=X7%L`*bjJiIQ-Se?|#3& z;thrdz_)A0aPO|wR6|D*`r;9L;7C-%$*IVNISN>72GI|e6o^E=AdPcBeYn|R@Z3XV z#U_}P4Wq*Aoz4FRU^NiVDv^x&@+!@$S5_ao4e530d;P}w-z7W0SRO5Rw&~ZK)F-3L zqep@XU0X-fW+$2xIJ=Ylw4Pp0_**=Mhk0vpN9 zXR|}sGy8nm|G8R8;Hr(O@KD2AjcfIkJ&>idYZ6_~VcD)D$#TI{D@%Yu13+=mfur~Q z0I?Kk$QkoP4P=LzIB1p_zS>zb2jroHGD(FqqLCUq*+3j`NJVNMXXz#?I5n-5q#VoN)JVZ7?97c8n9%;jiB@ybXxcHFF zym%=j9xtlx$B|^51ohmaK8GJ-Zen39A_BD> zOD;Bc+>@v)EO=%}9C^0`M6&=*4N!QGh0QTurm2gm0aqP2j%8tn7ssxD7LyLN(Oz($ z)dEz0VOkK+WvLDEmzLUINF+&tTL;LjuZ{!V4&e3*7G~b*!c?&*K=(eV%isWknO5ga zxz(8y!R~vzYnNV0HM1B*^U9=USp%W zdwTa$`Pt2*z4a5H&);7?a`^JI>N~f-+=ONS?ahDx^R3FCYb#Dr8D2E=7=rug}fAab*1rtNmz|M`D#@MUFfYKy~3G<5PJ2c2G1VX$&N%y-7X;2aZ4^7Z=#;QJci2gtuvAm7(Wkq1!>hOBz>+l=|U1|Zg%t5 zg63$H*BUC_ax`-NRd@OAk@B#X9g0ClxN28#=Fw9mTTSRrxcHMBSFc_@z3at>T`hC_ z%l)oK#xg6DNZqFx(Y?TGX@ET&CEaFJ4j*oM?6Z1=xBcokq0!rBcWcD%x7qL7y@lmba%>Iv5`3X4zx8 z%{3P*Nx|I8$G54hw@NZ@4PSzsFJ_hGluvnmuIj)l&MGh}`6M?jxr&(quM^T%>Zun8 zN~kPzymbc1ZdW4XmXlea)0d_$&0=cH$qc|s3~h7l(n&$G3|`6?Ls}$KDY&Z-SZ6x) zC2dK7oas22?I6_&QrL3IAeE~VLuDLpPtO~4aw@@W!eg0;Y?A3bdSifDXG{`1TH|Pr zOC6py#O5re0q0EN&j!nh{b(l^hU54gwj8*{c0>}HW{R9luQa5k2-i`Of6L}?;z=gte5o`R{oU2a*j zC#Q_J#i1ehY}Q#|+x2N4fL@zFn-t_T(fD{OJC;wm?RUiQF=j$(Chv7>AJ zd+F?_JMZ6oUS56UROwRV@JAm$D*yJw-$P@2yXT&Nd->-*H6Rtw+`M1(wQf<_lf8|G z_c8Q50a~`@hBn^XHT!R-kD?UQRnPAL%=b=T&j-(rzAs16XZQB{avpi?RqjX9NE$5` ztKr^8{%2bC7>?updrzO;yZDdquq3UluWx;0KzkQ3orC5QhO}5y5jtC6;(Ql<_*^@- zrX#3MUsMgcVeos8So%VNwdd_A3Cpl`rT&T!xV%d0q~y^Geu$4v-XTcyWCr9qG! zHOx~dO0(AuORq?tT0UMzk2^E`$f6@5FriIfxsgYTrdFQa)OtA?KEUNnn46w-=@P{F zD~)&$VxI)Z`G9zs3z}L$l$66M80K@>Vdj7ZT}?Hmg#r%%ULY+=#4W)(;T=obOyKGy zS8^%m#~fmG5*Qp9TOAArTD3Avwu3V5gTZ88r}qIt2MGW^;Hy26B!j^`fDCkIx+Hse z9<($dP3Dc@a;5ezx@;Kj5P=s2mrq%0EZGiXs0~^hz$S?Za4Pa_m~5Zzy#^ecr1RWa z*qa_2gQjHT5t2tei&0yJ#m8Re!djTz+FIO3A#Gm+JGxzyMjBL&@hOpOD>+sSk8Vej zV}-(EI@cIWtA}lgJS|0Tjl-H@YAE%V;VK*&sBvF#TXb1d=`kB476u1-qGq6VDH~GxnPUyWeP7CQSiUQ1iNS6bvD^lPByMWh&Ehu% z8jar;rXt>B?U4h;hk(ayq}^VOcrA3D_K&^BLZQ}U2HB$13(DGrJL~=cbyz^CSHY!T zIx8=T#oE!5k11;=>JwLVpd?Q>gvGJ$Ik->Jolc<9LO4FUv%H~9Ndwy#Zj-G#+@d=E zFJ0&N+U9*mac>xBU5ajd4AP4wVWE&-n%wR0+4DKiSB^TU>$cVpzwayGocEmPJm-|w z(xLpcdim}z*4y^# z^Q9NLcVGXiWXFvq|M=)wbqcCiYOEn9lR`=Sm>L_3Y&2W-+%L{zj7?)v+;odh5-t)6wNk53iiO zEN3CKsnlVLIAFTbReCeEhx9zPw81aN^luN18Rb}d9seha~`(0Po2D?a}#*uqA z+=hhQOa!#&Rg#9K#4LDmu9!QX8X1P)-~HGHedErPdj^s~SdAh=?FWUOBXPibO{GJ) zeCG&U&NR2QHpG+@gjRvC$e|&j+|xu#&dGD-67Hg^3u<)_jaCzH6O_koWk<1-*7~8x zw<33zfu4#GD~y=kJjDfWv5oZW$6xUE^<~YtE}@dfe+gn1JKgfurgOCj)r{T&4J%JP%nR6V{?G&SM>7bN!F-ZUGCryhNfb3JHycDCngZ8Q`)F`ZZ$ zj9*tmM)69pAI-{}>zNd;?>btp4Cb&2k|m;R%aRTqGAL%Xj~ZOUQ7 zBb9Sl6wvu=FA_EFXdOo~uGHxh9nf&?qy=32Ftr0J1#gl)h8-r{x9radtP)*~QsI>j zo|1XN^%j~jGg`rRM-nyA=A0F5iy)dEU9J5Jim$!g5#DvWtrlnMwD`pq=xAR&9r^Ee zdqUs1&>tWd)`HZAy#~O*uwkr#wAb~+ipSayofF7#&tAs#6$$vcArR%(k-2jKZ-w@Z zjO}Uw=%_nVHU^x}69jMIN_4H^sY=o21MuR{VtGQqDKf0Iyu7-``K|myR^6t|i)j^y z2CH%nZx<6}FjsUf$lak|2~bv?M^;Xwywheqrvr*|FX%=9#L;ZI9Dbel#ByHgAoGUg zvR#uWt+$pnTdl&Uc>(xlXGs*BNRd$yWLb`lO_#&^6Ru_%!9c$S&0Vo>6|{$i@LRnp zZolo5U)ZaCBH6eWw!OYd`J0l)wZhCBlzp|};aqsi>@$qsT<}?PneA!m0-EiH0B(Iw zu6g^YdQ&$HxV;gc3+UH;=7NA-+P1c@tNc~CB`M7RY=4fKtq)~OvMz&>B{l1+7C{9J zKDMOR)o&4^jR55*g_wIlGdHG%L>C##95H_>$t52tC)EVpVD(AUUU+dyIIL@Fc>R)NFZT|?8x1zg1^r;i34M*hw=Yh2 z3~AW}&bb52FgUlNegMPjs2xeffwv~AX8J+R=z;k6}X~w!q6c;+O;H}yH$*zjcCXiG#Tx?#i=%e0 zcUV2w!qb%uh`z8od5b@tkiA&El_{)&rm)L? zkAJ#wNYJq5;7bPB^y2D%1=P|+yf;;0}mB-L&LfM}z#T`s&O{nuXT^n~l3c%0ja z6ZB=#)KIO z0PmTaLVv$x0qJ(tJ_L^Cf=k>-njhl~*A}wawYH>``n4@ZT6S**k%04%T)Xn4Q8$FK ztSkSSEZlkBe_*3_qCW5QTvyf$Qm41yRYltm=N*-GVfN~%7PDnIlT5%2U_0Ep7ytuj zyYg6Jch=&M1Zl-_lssx9HmFTli-kU;bYo4Ryg4&0K@V`42a=?(b`5^7uC9y^!-?O% z{oc+%ff5CS-ngJhW?%hn2x{d{*2Gs>&k}Lk+XX$3tE6bFWKyg+Rw_;=W4X)M$>bkW zpDx|FKfCqxw`a-CJJXY~MzX#5+3jT~)+KNCwI9}%fvMXI{8gT|sbO%t5o^mC-3Zyy z5~q0x3ziA%;e+7>4i};yJiPt#v|_NjDRVP>y&D7SyXt`)tGRY;um_Ae3mf$6+2!er zzf3j-(yNt=GBLp8>P;v4cS03%`&*S&vtQH8dO ziSlZKW^M7ACcDqnAjJ5#zLn|MD}DBQ4V(MKSY|5qzQpFb99TG{Bm?)G^~@aB;2H}$ zh}CmUcU1z+wk(o{tEBzj$!>Uv&`MZX22&Y1ITI z4fKG-MYSdXto9Mk4Hq$#^(A`?LM!SGR_df(?ws7rTb`RGdfT`6aQ3Eza_^Raus3J? zuE1_Al>1zv7rAdJZnq%);Ik&+OL1OM>*Xh(R6|ta%F4Am`z;XZDU1n^JWdR&#viKR zHG++txJH9$h+fx6p$S^^x}hqs>x0uycThAi+m%tM8+fnqspol49JS+_5l&`(sw*h& z2xO$;!lvzbF7|SRfUkJP)my2y1|c|%L{xhxGWTi%8)>|004HEd2x1LLLBNivD_D$D z9Pc<|g>!<6Jpn8eRX`Q=^k+nM{ojs(XjiPW6QpL|V&?&gdvOP8jenz#e+gWrNjq|L z0C=pyXsdV9byjPD3H>#ogb?=(ha+7X4_ff$4s11?%pf>AiFgz@fDX454%d7hJs-h_ zIhlRpcn^H;+FRpXP|ILim!;V;e*(L-5%9KbxCw}sv#LrXCw@vTYJ$zYYFvQVve%2F z2A2yGptFYs8K?8*DO_6$^^kaqD=TaNG0=WTS+E@_3k<7*tqe3mn&Hgl!n;Bi4;Ki? zxA9m7Y$;6(yjoarJC|%>RkUyAT`njhq*~CfvhO?PF=-WK-YRGt%JVXf#8&;V$m1|c zR?aCf6BDyat*_LOsGi#LhuUgU|e+nu1m8 zQM=L5@d7I*8+&w{S-CF{>!NT->pJZO+}#x1zg?{!0jY4?s`!3^a%GA9EQomyN;%6P z0C}HwJG+8E?f+6+xdStDsI(X9Rf1J1>HA3`SfdnTvOKfW;BRAV7=W)FfCs*;D~I8~ z*$<%b`>QMa>FWJ^`_>My0<^GyCDY+F__dg~z8zE;l{9L0QUv{;-j zCBOXU?BAC!+pm7O7mGdp{Ix;se&Vk;K7OMWBjejLSCPBbfc7>B+)~*QOTrD6Cm9BZ ziE~N)g~^bD*-&QY>C(f&5ct}G750EH_BU2NUSl=buKa6bW231p-&`?yJp*Q6cq7+5 zJF7I8_m9K+(&ojK`r;-grqmRN)oNlaCGWGs_m##^!Rq+Lo-%^RymD@Oe0nPT$*c7+ z_4P8s#ya|Pu{b%?I2g);ZY!d4T|L0WKZh#nypA1p< z)c^Q8pBK08D~cx&+=b`0s>#AL8D>VpGqh4AEF#tQz-TBz0W*mQ3#S_5TqcDX>iR`33Gjml4}bM3cB(<(-R8>HRaX*5f3|xU zlT~XuoTDKRe7eon*V)?JZ{4UbY3q##91a4)`%FjVB5Ki=sfRpzYvt>vEG$zNc^3?w z0M{2ozB)oUHiHEdg$ZfLoQ9dZ6%6=?t8SeDH(XGwl%!e}g_ICkt{hXhs%F(yKGUp% z;VQo&ZAvZgA6$~mF26>*)8 zYh$A#&{rqGVH%v0_NHrCxG7g{H<*$1Dvig&3+PoU;?~M!wX-CF@LkA;YpTLlf_cQ+2=D|h!BGH} z|3<7K#-o7UF&I4a1Vs_2<~T0IRed5(#Vyr}(o1uPL99jm;K&8I%IQ5(k2sW!WRx)(~RY(b!xRmJQ|7vF9M-@9NcmEu&?clHioO-o_)vdv%nx7*-cGZ z`|Zw!G1X^wDGB)6zAPOp!nSi(Q^!#0jQa@W1KV&YCFRaR#~s_B+P3(BkYL?@=8tql za?H~(e&h9SzMyZalZ9#J-u7E|Wz9oYas561I)AT5~{e_o#ap2AsctdiMBPRRE3+#b+QG%>C}M8vt

tdWvfGF2M=mIiIU(_sUBP($FblxMRH95DZ7W8156|De zWWe|Sod^vEzjuD#hyUIl-cB#{bvW={0^k4NwsDnVHXHI^;s&OrBSMs>4EWPXNojW-_i3!1X(4%kO{G##jf5PuapS&^o>O-daGJqHV z5_5j#hp}%ytP?^-BM%kT{*s2+`9Yu_P#eF)45=UyBl}|KSh#``&j=Qc zjE5#&3>lzcUvV{0So|j6qMigi6<}+&Ogj+7QJm}N?^XEw;NJLeH#Vyl+Hz7 z1oYw^vUyd)3B$`S*3wKU5Eoj?`GeD9Zc6zW_#DqTZ<>P9W_ibYEO$}$?bP6WH6XI2 z?WPFc8MuYnxTu^;<;tA|>Ut!&43v#kktfz%Cl-W@$*LYJOiNHj{ITM%KsOQp@EFIg znjCpt)prwnT_~_r0BuJiW+DFi!Kt{LGI8vj1uSzw5l6FBh)>OCBOp4q%W-uhg=Ab3 z9tXxH;}+q)aY!NX$Iel~!?Q++C$E9Xu{j;T(P=b-#%?ip(CIAkPx%H&49jicnrZ-@ zO(H1iK@w(rTTLd2J3CF`xdGYbjrP9kG~#g_4GV6&p|3RMla=WEmEBf5wS7q zMLZ7tnn%puXEU+w$#P|Ya*e}EueS+dEDkysXy|)cNRLNgS)wbt9ZQjR!%nPD!oU(<@i^U#;l!{qwCW zOe6<=uU!2ssP7d9wQgLyDlKMkYj9m?FT|Jeai7Q5BgV)*dgtoLuh5ZkK_9N8MDzcO z%n;n&-J7wzI9fZ-IY_nuA0`UNTTX3Y->WMR{|^KHQSs!D7^WB$h@;o4tYODY#3e4M#;I1OAGcJITm8jBop5P6<-u@H!*EM^Iq<4wm$B0m47gw# zaJ_GDQi~Bsv4iP`EyoJk0VNQh+LrYE#V0EOe(;+we+r8R51F+T_ts|-0qiYvdSYGt zR7D>Q2XJEII}nX&xiUkG+V3)_1rG=JTMji`P*z^l6VI#6O7_NjW6)A%re~`^+@xkr zWf~6Nk`d2+e1fR^{RJBK2T%WSLK0+I)mh7z;9(W1WP9tSwHOrCkc1ArGpi=%Och&a znOZ!nelQzX((yDYQ#P(X{FP88L zLSQdSY#~#`vEyb&oP;{E*j-4Ex#~2)n{B^L z3&O#G8N>p-_BvbfySG;{VyQ2KTN-<3!HnC&tybx+%S_ugL0O&VSIK^Jz8iIY16dSNad?sZJpyoa}kjzW?E!MDoFtBM5wM^TtCNYOouPUP* zC2Gbds>!x9BD15m+^Gy+y@rr@BI3eq?Md$B)WtpR#)e?q02V;$zl{uY-#fEk3b^fM z0h-39SYI?H*3G>$Z{DUU*9#}Hr4CfBseDb0FL`M!@*sijtsy^NB>lB99jj6I@ z=%`YP4N~qBiSZu*30)GePT{o0+70r=VTBUGXmyWkzuba}L z7=Ebr+R|^b^DgZ980=O!-p;_wLx(!7WqRbc5gTjU$D~kJAKSic3RaJnRm;EElL8+e zI((r^18`2b@%r5`{r^4>0KpZ(T2nk z=fAlB!7ulpSHqKH&sWT0-wA4q)V#5gI&;7=5KDINhKc;wu06W?IRkB&PP0QqFth5e z{N$A}l$l3~0oo*J$#9yic8|Nqwg96!)A@VoyoT6+b2pQ*j$iFO{IA?Me|}JWb)!BH zc+#`nM@F7659X&srvu6k2c|`#8=o3Hxnz3LqJF@1Trwta1m9iSf`m;NFK{6F9G%wu z$t6REN!qZ8ydeFVjOSLi9iP_iJ0j2{(0kx)LK3J1=ToI?yinA4Tbtj!e~G^j?v=0R zIFW;h&yA(lB-YA~V>Vh0F&vyaN5V!UXCM)772rw1_;iU{42`Am>r&&Cx_9*yLltNf zx8iBOUdrBWN**p3eRHql{jXaZs$tf{_~f#lnU|92MgQkdKW^7D^GK#iN!4Cb_m#6M zzNt(uDo#p!X9h&50o!q!T5&p!%jviloXOT239)6`afVn-vlpgnbD=(IydpeRaXAjd z`!t2Y3Cd$TbBgo`LuzelReMF#hQ1bnjK@eRDbj*%l1qp*_FibmC60l-s>Q#pkZK}}P1Lugs3ED^Y%FL`p|SW?Vma}#_ZFuWLf zi<5t`bw00c@ky?Z{OnP*$a- zFfoQ^V+hGYUDTNAA{Z}bx(N)Xg>Kp`vhg$TvutQ(v&P8^9x3u`J;U~9}tUzmRq zFOLE6>#7@t#1Ujv_&S9Ii(*RErG_XHvTA**|DeIuI9W1T#$4bgRx^ zmGz`IszcqZlY}hTw0GVTWmbE6>K!MFYRisPPKrcazM*N}aJ}9KJ zblu4^v|XN@@w8mI<#yQ=4z!P$+V3YuRbDSw@3E=yPdJr%WncRs{eQ5HQRP-tj;Hq` z?U9=Cw@?30iMhWb>tjv+GJC`vtdAdgBiI|Tp4hO3@fF7#>!bFSlb-(o03ZNKL_t(d z3Hn_*G?*Ls?+yN{0Zb`cZQyS3;*j?Rc3Z>{cNsqxE4LN(UxmJN08E!mxpP+73LvZs zmePo|R{FuvirFJ|jHz8Wh#)58m;8lBaPNXOH^g-@gSO}2cSuH=)gZ0Gy*l8fl@mx%PGwW3(= z^4jwDhU&~73Z7v-qWPnLiB+)c3d1hL)V`Aq1-eVB1qMk0Iob98+U zxQiJy&R8KA_~qK8uf;Ijfbi|?@{gN6L)}?tj^AW}kP?++vUm+_OXTv(vQcPPn&3BC zLQJguTU;>aiVt#|jgmUJD#X5!UQ1rhlY}sY8i|H>nYN+1Ypn?!A{~J#qMBe#ZP^_I zaf~1*cJoEDX=wbHKm6(jfPa7cS&(ffl%g4Vatldg?n2I)D&6kyj5mie611C`C|OYB zNGc@H*M0TVyZGkg~2M|%0|Ipc`qzok-i-$@im8}keXNO>)Ol6>z(rgBR4K+4IyH`9S#ctaD`x?sb9;0 zS8xT08jPly;p5nusi4wcYN3Tf;F*r0tiJH2F9BRl{g5--g0B(=Z7&96RyWA0aF&x` zdcbK$DS7DE9XMp$*EEo1PO$shuR>rPFg@UU%7YudFF>aQa%WIx5Z(@@AJNw>7e#9$ zE!JC%RD>?d z@I!cPupF1glBxQFw(1dU?8%NqV$Y!jjr|AN503BTMpWwV+a*m_#R)c@V^vSC5LA>l1$qTA1nXW~xX^zL$<(5HJ%`v(KgO5UeNbX*3nA>qt4+w)O! z_BwGKTEdzvl8Biya>YB($26^`y-Y7^`tTEH`4B;{*TkU?y5oi7ol;3fI;k<#dG^x_*3k!yHk~mruudY;YaJe z+0zfzAw_u(O0XgAyH;(mJ+y{jB_y^?K;<^kp5k0() zXO=Mf)jld|y1YKfjHQ*t%PV=kyaCAbKy-S8-A3PFX&ZVW5r8YBk9DAr6pzFEN`#<;<-;C*}r>a zG8p}p(~cag>P0%Ij*8F!ZWi`*z7oyCvG7r5*KW+v=MdDz}BsowmfmJBbR^GO9{yiZPN{ zc|z&gz_sH+O0zRu}>Udy^WvCNXDMM@w1!-(Nm>2Y?@}olRyrah~xqGE{0ku(Sfz#GxapYZH zRmtZw{k%sk0||&q4#xdT&oG})lG(%{nPFlh;AhW%5aY+7?kElpf;n(lh^39e?T>u5^6g1VzdaUP%2d+T3u81E#ZscZIF{T-%Ea$3;rYy1ch~A;-GWVIjYjj-=G5v(&*g2U>q4{asyLJAh&4 zj980L{rS^08|S<{UzR^nY5=VC(QK9jVxQwHzZUyCyL41s- z>rDgJG8i05U@dHQJ=QfZWziuySkuRl>1U&=)&j7;tU}Cn_BnnaDqPpA*I=fwy8`!h zQCA)1H!3KJrj$1kU)RG3m8PYHqfIrA#gohMX?w6LZec|QH9DCMt>Zd%fU4uW9-=D2 zn0mkE>k1>(URYKo8cuG{!}zl9OtU@KzM~R*`9RB3tK2nj>{09&DCwNH;=g;kASlQM zPncA=)~bv6m`e0YA7d-g9=ZjX4(Mz!E{fb`re5juPul z9s%s(e~6763^;i(6P6%dH>T{u#$9j?p+4yw62IbXf#iDl*up!*`-gZC^c?c+yZUDfW4F_(x^X$UQCA7`*^_9!MQC(%-h!StF zeXi)arDJ8g+RKeKW5wde$7|aji@x#0FLrI^-u+cc*-bX|(Ur-DfpBA8OBU4|TFP=*;3h4Rbq7Zdd@6P}?Ggsuy^gfPK5$e@CUa!Q zCGY++6x8XdYrBaS>ux@S6h1z_bf=F+&9jr{Mn~=9y;|>uhNi@VVep%^qeNBj&55CN z(rzoXnEYa8T+|c2opiV3rTxhRrnlNmD zaUOUJR`uipWLS0Ptl$HwoFd4!zw5dPcspjM=8zdxu#*}yZC7zmKobHu4lwH_T!hC3 z$e(B&V&K(bjv-?((lNxIZ2;pmA~`JN@Cv!5{F;KIqN(Do6rAmtbIhUiP|jHkp+;NC z-Y!9J4EQxbUIhjMc!p=Ga9<|~!Um4F@3B+JD$Uve!QljlbKeYnISBBYrU6P*O33eE z>oCnr)oEDhAO*q?e19NFW_P013_`itHz<6hzK}weQ|5FS)|ZBh6+SYIqn}HOxvnhm zb0fTE1*xeuOg^}P(#{Z6D$PZeX@-@`48ri@u^~v&m^9D;Yc(992z?%NaTTcz(iN{j zfjXjMEhLW}T!mV8cgCIS_<^YZDdO6!xUdT^5Kt%f8n;_z>U)j$#Ok(cTBjP70Xvyj ziys=R#yEtou5dM?;cOI=xu1NF8N%J1ig3D^i@9X=e^DlDiYlga3z|*?9d616tV)}< zd0k=o7&nZ=K#8@b#(LeDm1KuDFd?VK}^jING0%xs$!(AsOy#jt4e6!_4z|uq0G*%-Rf!6+dF3@5M z*qyMXg3e8_f(q+x5BT&d8SQ$kQLDAbKvK(telh2`b9Ddh9PoY%vyPWfuKx3{v)}9l zW6IW@%g;$^HJn}5XQA(gn!X##Ro|BI>XYLQ1=cNXYzTHY{?FF=ytb8JQM`*b(AuJ| z$-zV41#gYWrhiZG`P}c59VVV+q95P)eNPJHymRik=RR0@AWYVx(r?eh5JItF@}2QO z@Am4vX0L7zAj9>ZqqD(sU36Jdl#;9Kqx#$RXP>VBlErauSR9 ztV_&A*GPA)j$+$orpQW-M7UC4kMwRWo^;2Wdr&UFEj;-MfdBmCbEYF`6e8WX!trX1 z{)|6*Oh@xnO-QOw@96ie6*4tryi|(3QfPB**Jh|{A2U8~b*Hh~hQ(qPjAeHQVz^ym zNc`4g2Voj*TjIPX9+!pOWvbjett+hE-SV%$`Dt@4gfJcE>B2Ozr~{PbV-#08qcWO) zP?FV4yp)l8o z9naGw2);RFQI7>VZI4R_P6x~+$&pt3@gPkc+>#vMl4ObKUeX0R4fxZ9tpuOG#ZbWQ zZzh?8y?gOYz|o zUna?q3<8TU4IlNdIDuCyMVX;1l!a?6(w`f1TQjfJilV_ahM9^Ti_vOPMb7DlfVt@s zbPfBKo22!sC@_l~fV`|$dSswvj9WZUERJNYZNax~F6p+h?c#5fzNYArT@~IW)NQz~ zT4n*unrq%h8jBIEnu~zi%De3{w5(Hr<4FKkBcP3W)2U^ndEE>xJ)-XO$YVvC!D(Fc znyiSl_AuBi2Eg9lZp>|$oY51a-SpH9Bi}WQXph)ftFNUEknY*MzHY$jsZuxXtJlqf zMkyP?E!NNhw&%JQCPCWK6_@2}4FPV$o5t);rGnZpw{Q2fX@74gXI}-uS2iqHd>vZ% ze1rm?VpJtQU!h0d#S)#W1 zzQ=KJa{+Uv9k}N`Pd(&pDbdC+zrUZCeM1!Gk`90Q{l(+9+pZ)y%lm9BS6-}outXm$ zhcWmpq;}kX{CMK|(Ri>X7Y3xy*WZ*@){O{1-+!*W-sccvpN3Pqr-$pBqgr}b(j$h} z$(L1H|IK+A1iafD8Rk;qmHkRyXWEW-cUL_CTKz{DvqlUfR0#BFRNvh=sGpaf0l80Z z;rGcc4jTYJRPdv0Q4?V5%Etj4mP{CVzW$SUXx z(|o?)&a_*e#Zy&>!zd+{eHjVdolQyFQW_S~90u8~W5rD|a93~~x0ooTvMj~mhiCWy z`0>w||55JbxOMC`S$d%iu(?6dM-a)K(9G0TukqCG2{g2Kq9iMW%c@egC_$^Z8&AF0 zim;AW2WfoVnm#uAO#}3-E2CL=D*aj6BcjW3bu91JRATx=BkMwHS;puD*2jGP_n*|1 zMxm@>F;XQ5i)wzWWTlY8BxD>OqWmJC4&79|W`~h=NI4c?t-Fkcnul2+m}E6&xytILC3rHY3u045U_YXX}$3l#`FCt*<=daX%FfLuA!Kl;o?W z`huWok}MHZ4-D`5NeggR9nnt%6}8oAB8b(tg&c(Q!fAG@68i zi14AYO4bH<+ygd;WrFUKcq3A|Jgu6%OgN~zcZ9-j5^H*IG6y}9^ewA*6r4^?xOf!c z)Q@o6w&JF?X^EaUa6sXomMYL7SY#WC9RXPvqT=vew-wj0_6EH}iWAdmh3MOOzHw?J z8btXzzmD(0d*lZI9dC7lGn_0($>;^D6v7M{rP~)rO=e?z-Cav%t0k;G!6F zdK}O_A6UHEx=p>j*%gQ0yctjayZB&$-W%KV!Pa8Yd%yMK{a_?QJ%HzmSbN47(N;Y# zb+3{?sp@af{aJfBvFNu_BhRW2FWdrwB}dbfq(0y~2IwXH{^7~fi?iuQd-pL7yKbvQG3ks@f1o&ijiQ4g@4wqO zpx!SrXMKG?OmzLr`3SX{X-M@0yIVLI?a69|!Ys74&$_#}>w^eK%p~l&60HypnV?7K zKa`;Fwjm8KemR{ScRg&9YN*s-^%e<;TU~YM3eS#ZD#FV&>k>FAnRYDvJjS*K0vpX0 z?siChREnkeqPmM@VxmmUGHR;gzvYgxRBT!zz*oxbpcY&ncUu~$O8^!vwdL~b6(_*< zH%9axN+0$pWbiP-<%&lN?q9ARZ6>ibc zP{^O9mr3DPe@&dP3b%q_90Y4eLkGCNUN9i*8z3j3s+enjv5u3O;o8tKZV2EeewZHG zgXEtM-Cj@@iM`b2z?D;bpNq2Bc%iR@Qb)`_`lN4Lvc~TZxWqKL zwRDDn#>+d2%dmaQI{PsOtRdkQpAKGG2~H{?S)|Lb)==~w+_+Liuf~6MdJ0w5uOb4r z@vm)QHma>OBw+)SVR#{h+qq()qsHlp=yek$F9N@EPTAX)=Bc>xDfl->j@AzIns-GR z(wu`O?V;1ar zLlX`sb^S&TtqgyPaCSG*fTbT-95My{QL_kc3al#uOs{JO@(o>WQMV3r;I`@BGe~>w zMEkH_*sX7Pn+eUtl97nQF|hv{Hn^zr27{c}=%eUmMbuYvg?;P4IP0jHXfvOZfa2`) z7u1nU66GqLJw!r>vaLr}kSAy(zS*?1d@xdcvv;%c*?8Pq z9E=vD-irY@6mGqOO84A@wdGlp9y7f+vj4U~WLd&wh-PphX_O-wxP;NpfN$mJJ9Xfv z-<`#6ZvYNmMQuk`YQTcqgM-c7gw<}3HzQ*Mk^?g^;I=yWm{LQ&ot$4PCM$o)l5E> zei;ya>qVCMDwK=6cBGn>$Yzv=twvjcac73_nWSZUjE+4`vg}jt$#1Tb^0C95U1R98 z@16$p)nEI$8TxnsmbH4!P~ma4r4hfXIV(oeP03{xa(zBV4^EjTSZ*uzCU;8|to z7Ne2ux#6v`Z<4E~zW|Gqe#RLL zwo@G^q%;B=;1Oi(+mkc}x>MM(&XW3jDa1QT!xxtRpRDtFapOM2xDV<2APF2dl+~;} zvZm1%TN%ZoBX8}pqv|kNnn4a|*=}$x#4b_Nr0F4q8bNh2n8ctS8bmL_*@NASp_mqW zX7b;Lm(mwjuf*!v#8wEkNdg_d(&?Prd-*s+}qea$)*K zF0`uN%=8-<%YDX*`>m=*B(Pq$Z`u-+x>K3b@BDuNrdNvotLgG=I_)pZ{pG4Zr2&gw zDQ(rV;Lb>NRc)*o8deCL!n^2(^p^YO3q3zf0Z)y-%T=efT2)u&)ynX@T=vfS`~3bn zKJK5lx2Mba*0kF19MILw79S>X?UV6Ol*Igry!_ju`f!5dHR_=lx7Bj}F+bSU+2F!~Yu8zpO+u626?FYqgGSB@P3=6yFGOEg4jlr4zzZzsR#8-yXuJ&y^|A@`(vnV zHk z1J%s9?ho|WGRa#~co}UMU2HaIXNu@Dg0i$Y4~IWUfw}^j3m->mdLgbmRAyD6e6fk} z9+lDyInGVgSh7{wR%J&s7Qaf&4c*#eTFM-%AeU>w4BWP#$&r(#-AvrdphhzZ%TmtY zlq(6ArDVteG5?+t)8K3>y`50IVyRRbIMWO5lDsB)yI_8aGFnSM)x86P*j;g-_{82> zuFeV0MAx1Sv9>+U_}Vh;p1K@yraO&POvg24CFyk%+y0Q~`cu7JTv3{*m@fr^5!l4< z4FBLg-zylK(61H^vPfG`>X`I|T%KWT6C{SLrGU02NNy2^f?LgPA6o)PqR4XG)k}x?Ylnx;PArPb`OIwSm}kBf?Z7^LZdPd zlGjr|6xIgi& zpnIp&Y0oEz-txT`~CGq9a;^y^Zbp<6Ql2 z8gab3hE9#+6Lx*V)LTRA{9Ph+AN8;rSY(u%Fjd@WbE>Wp646}fS6H%4A?|a?eFK)I zw#M;7;>Ku=(MHdT2IXgru2wogt(Nn7g|HCE4L33v^hH08T5rNJfQHO}{9gQh|Lgnl z-`~2dCtv=n!3wDpe4}KDzNoQ+=yo#7*dBVYv+02V03ZNKL_t(>v?r!eCogMEMz?jF z(dN}4**oTZhLhfe<;=Cw+&CI@&{2(}9xy*~Ug?dE*gZQ3Tw#^o$(VlWcw`H)kqO5+ zApkw5m%D*7q#t|g27v~LY^<0UzNSZOd{Q6{hihX_o*1?7XLLaw4L9Z>HkClgR~}^6 zyX0~lo z9Wt3n6=(!QU@FP;sRXlQVM0hF1Di9Jrx4u|{t3Hsvw_r(OPH_))`;P*l(Z2uA?C1(2@^`HwB#MB#E1+xA%!%B8D`QYDS; zal$PwxSmK?V`;sJQZAkC=L>SXTS_ir{I?g*FrNj&*P|3gdeQUXkh0(KVFkurN?>5c zo-Qa@G11fujHw71d%oORGGO^w%Wn!B2wX>jtV0B_JXo+i8}b&E#Sx|SU*Px(A%qED z?xYr65etABmQ}WsZMm2fwIwkZQ7-OCo?+y5@ygz4qEi@pO|2OTsx(8fkXBN-xk~}* z!|F|McSN}yKwY8$3xg+`J|os1E0i~>Tia>DY&g$RY|3Z=&!3Wx&Umh(aPDUe%CHrw_KqlfzkrmGKD(}UHjb1+?X zOi>r1fL9$my$Rv-^N;NNiyQ6b@;(53dt1Gxnd2_A2S?QvHnUk)tEHBk2sLXKaG6nO zqPf#zTdne~(|6XAcWr`}BL3|36uqDC)JNN+dfgQkNeep$*VhVI!;kJ<`})D%pZqNS z>Hap&(sxF$cA#sGzZ~?+1n*xrb74*RKEkM+>w7y8#5)|%4pehS?B09N5jU6b$~fC0 zb*Xk4lLniM%=xP66$_BiuhKrY>vbiAzd!oJ4=q?Zj+Fy`c#2u|bCYd~u_ByINz8V~ zoKNH$Ues73jG~=(MRN-01ZF&*tIUU^>Gvlwkyl}VM`nOo(=%aMc`{)u$T8_>g439Z znD&XCZ30dC5^O|Q%o>B#FWVFJp@O6OSBg9T{Fk3rdW~;?BtzDv?`~k)QiDcodxdj# z(cEvGoFJXe;51645EgFq;*&!*4|ow|u0ukA-eadx9kg~r6WcU?%7EO=OQm@FyJnP*mC3>{IGug%kyB^Mqh z7f2{lr0evoi?uSM3&dmsbk-F+Gs#23GNG)+R{|nt#BL%2=3M4V-AqWrZVCNSi4vrl z1ZG!!1Jx)}LAT^Z#)A=e&elYvz)YkqheetDv+;s`lsuc4CKmgh20&1 zlO%hZC0!og#nCQW{i2(s!YJRSOu)~0Q-HI7DIu(z3tfgw6+>1#2=mN1N$T|eCBNV? zsEnV+iNe*$7m%BDZr1xz@|)<$75KXVJxyPvB1@L&qz=^$M1W@< zmaDCT>&gptJ3w`f66%0&>MjOW_@q8?%!>)3{uj8%;N>CbE{R>>>bRx_!vsLIg8K|v zN3hA^#>C!459wZZ?B+x4w_6Ac_QZed$u*Qz$BBEY`TYi#1Wlo*@ckUAq#|#ONRm z)9tX51~m{NOwtNbEh=;=duWzour7hn8nlNbq8EqwVCPV6mbACfZeej;VtcW7V!Ct- zjYD9`rGG`A@AvtQlcj!(^)jyke}3QR<@-zu0mIWfQ|+L!BN}q2SZW75Q>C4$WTzw$ zPFhIZ7TXv-h_ve*2QDC?Jf|sOQvh8uc9J=rR1D9L>gl+{Tp&VMwE9so7bL5d;3$W< z_UiF*j#HP8@hKla6!<~~AKmU4Z%W#0sMJQ8wE9Lr<+%QVEOg_{PMdSLBQrCxkCfP zrEL`fZ204L(bt2~2#C?LqL~Jic||g$q}$KeU=p=}WUCGZM7OXST*zD8Dn%>vx){jo zLJ14TTl*%qOk>Tb$V7HGF zZ+|lIyLq$YuB;peeVB>ps6$+dTvVslS?Jb#Tle0wuB^Q34rSA7R=pa2@v2qS)GC=G zo%mbj#H?w$(tK3_Ot{7?sT9>xV-0|&ur-n5rbck%w5(Xmiegh|tb9#nZmilbg{%>Z z@^ghR#R^?Mlj_STYNo+r;4Y$2j0}?%VX?j&Pz`wm9E8XbhRPQRM7Aj?ohH_N$XJH%4ufQv&M3*`C-xaTb)jLjhOP&UqtDFKI2dyWon zVicJnUfnf?G-SDISH`y&VeK^rvCF3+@eIdDP>rio7pQFmn!u-{xmU*0sj-LWsXoi* z2y8oMyxZe-mDjLe@EPH98}Wig7K&rnas^{OQy7Wai%NW~3C1>xxF~!bZQznqHLYMQ zCAS%l;E4=P<2C5YjDX$>NA9?+k;bedn!eIj2@2I_n6>qOTP@lVMWLJTY31(-1TQ+($=k`9$Qo z)o29FEZ2{xju4v$d@tjNyneYQFZ?#I2QNk;;+LzwMObm9o;y`eox zY-)mBZ#{hTv3HMb_P=dw_2wF);RUYZ;#|H=f3mM zM5((sp=O!a<@DE?X)_%bx!~WK8Fcc7>HE`X?@#N5ItXOw<7@N3-6*z978vPW)LsQN zrED3#7DUSzk@}@WR-sU6x6(lk>5PWYuD?{z{Ug+28?Fc)N1v*COt2ZfmFTQ)bijE?`cIoX8K;Vn_dbHC3 zc$vsXP}O$<+IWQ5U*jEd+w;?A(z@-d#Fj#sxnek+qg6WH5MMXZKhm4n}6 ztC7n5Qx3VD_RxUdv8noLu25Pktz%QmWEyU$!&HUFTJ>Y{t0oegMwMfn3^J}NeeEB@eI@-GrnauIC;+4a@K6+tiy&RC}fMOm=L83_SD;w^;t}CQi1ZoicSQ>Z8pq0 zYoM&-83Hfy-DTaLRZ8maRkk%;j*V?oH!KoTRuSB<>Si`vtwHz>SXSM0UYLMiB6 zSvk;E1Vb3d9t+WA%XfH&Hj1>knFhukW5Ze2+%97F9xl*ZV{sLVx)&GETaK;}hT7J} zP_>N^fMd)^Jala#m;j6uzm_*%Lev3QYGGZo#$V)r$gMzMgAm9)- zlqDKoq4kLRl;P$n7=xGRx~Xl%hOj8SiVXUa{%l-r?FEV-(NOk*ioxB zujA{Mzkge2E5PF!70$#itT=)|NGz0Xl>!E&i?pLOLxAO>LK$O`T3gfaz2<+FvNuf# zzj1Z*LY_kaUDh+#`|hZVwj*G&CYljR*@4zn`EHL^RrzxW(#muFx{e&o>&&9Ody50@ zX|Bwc9=L0bCJSu;@!_d~c}Ok>1#-S1L}tx+d!VjsVNmO#|F_>~$eU)%D6pz7Y|Wqt z>5ca{I2)-ixck}79}9thwXy+zvH}ZLQ6ryZuhN~_ryzFSD$Zpz;2>X2S9B4ab}^I? z#Dp7`4=GG%Yq#E2Q|CN^M6wv_Xb#RGvD@(ghj2G=+l94KTw znkNsGBIS)HUoJyTS?cOQ``m zN3*hJ#jGH9$Y&kZ%_QX*k8IAJ;PeSS2gbjhB}FtU(;Vj=udKip=?dN>Z@uVcwEo*M zDQeVZmm${)W%`rwFqEd~F0#Gzo*5yYEYA8!>{)~5%xabe|-1x!NH?DcXoHb*?sij&VvUJc6T4`9vmF( z?TIS>=ZnAHzC5{b+?kAyC&x+WxXrTU2Jx?zSn7(!UlB2er49K|%FUk{ zlrJ8%2UV08S1T$QW_vBuyR~kO9jsav)H&5mucI)TcB}#8%>{M2Omj*@jbn$qAb7T0 zp@R$~k8w%R;79?Z-v`6dXsO9IA$GrDkEY%2wt<6~)TIP4NATMAaQD;i_|%?L57W%d zB$VsAO(0=epJoZs0Agn7yh#)D(6H`YM+()ttp$M@NG&*lop_^ajU8GV&JaYACG7oj zNJY%-Czgl9h}*^zoRX_dlhWS=r74J!Swo}J&|yO&S0Yd(R1{i)Ss9jW!y(hWk#G$~ z=zb^dbTH7WPUe!-;CDpOM-9;!XUK(!Y8S8Ja)d-uH{y;6<489K@ni|R)iTn}QN0&Y zs75>z@d!CA_8LM(&?p|_dQDhIVlVYNcZLO>Q_t~NO6%qLcPvbW4Y+~L#5azsG z-k2~mZY%fr-bV2`@)lFVO#~zDn|J`Nm)xP6HH8(-C5ioc_m+_IB`b@@Y*O1c!I%XG zkA2TDz*^!Yr^4b4#bOX7@=^!;pe|M~=ak4qewn5s*0AOh_5eW`*w|xgIhO>0^Adg9 zB%6ml`6Q`YU^0RWbQyb4kBo3Qc!wJR);(p)uFnWW>VCPH;dV=<!r*{ZK*EUa*fG%=;8h+WEyq5_+4#Xa8qr@u*tPV@;IolXFK?u*=`{Td1dsWSy zod+wWsX{50A}w%1jg%QHUSGJd+1z;Azy9#q^YQp(^!%^K_W#)UYmZ|?@V%F#(UF07 zbae7ybOHq1_vp_rM+W8b__?WK#HYV`XYcK=^RBZrS;(7!Cw8=T^r{LGdS-c4DW(2Y zuwhp&OiP{m7&3p_49_+;QnyYQPE#S4`=|pp0H0krd(mPX+Tiwb zGh<;GL&^ED=>95&i*RI>G!8fWOaEE{BMXhyo4cP-(85$Dz|Lwk>09G>&lfo$~U6Z;H#(C&pjtl13JcbfJo@EHyF6_hq0uu9@~7n2bdMQMJ-qt6{D^%vdb}tcoFp*$SsL zAfq}cRMpc1&61HYO>4+71JZbzEjvtta@^p+u-mCJ6N{#oFju2LB$_b~IvtEJd`fS>2Aet5wdR|{NnNlmw&LQMv;)B-2&znb=A=d^}sNL0rJLI(vfN1LKnOR zH`Co}hxu$y8Km*MQ0rjyQ=#(+g-sQfD?{YNP|f5qi-b{|+(v-BGH9dESD{nkNJG>@ zSKVAjDC)b{-k6)2RO=vyshny3HeI{OPJ+n45?kxSDMPopj(|Uni}SLMFP6*e`m57_Z)x8RYzA{g1yGGvaPYeI}IL%`C|s3 zdENwR&vBXLj_i0lb)Nb#*8U>hDrlj{y}46}0dZWn8x~4PJ#@JN*IeNzUqZs%!XEQIGfmsXJUY6IZh#LrK*Zn&Xvx(E| zUoE-hEv#%sUR@?A&cVDE+_1YEyqBQ4j~Xqs{q(i2?`pDH@#XVgCGe1g_j5Ot1kNO7 z9|PW{h;brz&2#viUb}gf1xNHjDI?3q%5LCLievk@f@xqB?p~NTD)p~_WBeVDMq|^x z&z@8MJ|7>C@7)`peD)c@`{2Ro=>7;Y_=FHXB8=_9P&|HVD1P?Of3YPq%bC;#L@l@2 zs%l-+7+4zxEs7C?sY?2mYq@o+zi7N&Y^ItEO)B8^r~T7g{nJ$n;{I~W6!446ix*ue z;1bG^&cs&ww--uuei?(C9E6l=a!_GO-J%%)*W^RMn(1PLbTeF7CV*WE*r{I^hyKyw zp_97ofJN+Xq6hS9E6=eEuehM|YJIi$t?2tJ+dtV;zmC;>YZvb4^Rp^4qTy;=^yMJf zOHKsOlE4T*Z;8*B7=-=+5J2z0BYQzJ0No5jwBpbd25R0W`eKEPl)ufqrZaFZu!7dh z8}s(e>hc%c9~*lwU;h8iu--g>xR!$af~F<9OtZVMh?7^TpTvG#~$EGUKBrY=N{ zlKjHi^ja%T;f%q)m?XsELAnCO%GPO0# zl3=bFV!Vw+G;SJDrtu=R0!y4L6&JTgd>#Xm z5WTj06BIPJi2J>3Z`_$y#IiI+6)$qZ&N%EL8Xd`91VB2C97{1Zobi{su`#RzbuQ*v zr#hv4osnxwNm|656*z^&11)DH7y)JSj9UqD06GyI)g7PkoM7hGvBe&Cf@g=ZQ^kfb z>Q0bO5?PR&>>=6#Jtw;v;LN71v||{;@cIr974u>u9TIHs z^>9x>jN?6M2^@Um);ZSv`U(l7tZ2^uu6tepT9U3g z$X!4Hkj1Ze0(6Vcz{pHA_zYg>G9H4eIZ&ePGbl|w9F`Vu3gjkLYhz2gxY@G8Lgw1$_Ipq10bSP2DMo?J1lcQXwFs6MNNo|lEsbUCu zA6aRr>4YLVK%^VHK+3g@YYP}c&$xUr5uDS23T$F~Nf3xv&+B55k>;g+?78egxHIa` zej@>+;_URSAhuUV%aI^J6Ks5WJh;^JzV9dY3DD!_`DI4-%XV{9_NlOg8}^xeV((tU z2!4PW?*?Dnz#emRP{{V2SG;)zRYvOzEbrA!T?$}MDJZEK$09w@rV&k-R_DW~PoG@> zw*mO&$zQAMTyFN4e> z=Muu=%yw85-kPP9Vjehz89QVf4#1b=fl-ANaz0^LI(+?=`17?H`0K(7J``uu{2ta&}7* z=}WVi_DULW!v~F-bw7RBMCh4TXpKT5VmC_QD{;KA2wA+r8sR2g&@?k!onZ=# z_oHgC7ZIdtyRfh!v}Hn=I0!Ts4VWU>78)(Sv8cgzd!ahW4m2320U?LlzNk?`ORs`^ z5&D1hJkL3^Qm8JxpEL9B8us@-uaY?i001BWNkl%fGzTBSIvv8QJPOaG*W3 zWV3)VgX77XECSOQg5e}&PYwv{@dP1cjzJQ#3Mq%I8x9y&7T%8m(-3t<%vTXNiC>DD{nIj1>RizhQy%)6GYRQxizsTD1jQ>4GB zWp<>N!n3CiTS!;|*^b(Ty1gCn?}gj=>EBVuQ7gA4Q)M!&%b+oT_60b%HKrPyy+{MY zjHNQh+fvQiqK@qKls^pY#u~M?$Zn2GrKVyq#oJo|Z)=9QR70&jizowdg4P~k);py> zWj$${FdB`EDCP9bx}r-sc^4;7WL*h}*h+Aow3VJLC{`vX2FsK?fy9`c>Kl60$@yQ` zR-k}xB^1m0I#!T^yvpGi`q>nBPd{2Kk4ne-nKWpwN|{ICBt~la3KBUn2_NecQw>4O z?>vTud;B4XjCBRT-eS?ai&&@!nJZ)fx`-^_RkC{YOe=k<+VEC^8-(39s0gPPV%zj~ zF~m$s?IM-zgWcLcg5(G3T{hD~-g!!%dRa!|Q8q$G(+x%nYJ?dy7LGv^gUh_0_S2MQ z!f(Y~G$P(2emza3vY9oMv1ViIEU(4+(A@$!2F+bC)~gHfroPr@E$ZpzBvW2$3T)CO zUC&r6glQES5nY6gzQ$F!PUhpYxa#@xVQ*ub5tL9Zy4ln}>tO*-{Q|sgvKOI|++|uD z0f>w-0RLL%_(fd+yM_vNiypTzJ~Q>$HDwOJ9moCt)g_%q$XcTX&RQrddew%c9%<{& zEO;7LqrxfyeD`wz7~1zC==)@E@8RCw-u;_*ZYqKqf+lhW%DeaZ=)OLp8vdfs>AjqI z&_N+^hutr26mP^#bb%E@Xu&1RTl)j2DuKXHJ6l_Y^3l=!V68eC?DzK@hw^kM>SH=m zzfS}oBM@+{6$ZDC2cJb?(*cY&^-{ldxfFs&{2Msz%zNV>v3Xaz-%QKWh@0 zQRr3SbQP|w>b=Vs|3CZ7dL*dg=UzMbbrYhpwl4@8VwzycR#-t0R)(z4f%8{Q#=&63 zUX2yD+z?D5c&rU5(U}8Pwj8XWrYf|AY*)s^3FE$q(?Sb}XxUg9wNcL`50}tbi(RP3 z<2INjc%#bYY`<{Q1l1lSKY#mApN8;+u|HL$bLnYpOVZTXqU7quv-ogK*ibPG-x8IE`SZOrNsXJ7mFWy!3E-Xr zfqX+k4yUF*d9XZ4O`C$uX{?%)yMWond7_?io(dUI#u`&2Ca=)bBjZbn@!FQb&!N_8 z{bG55o+!mWAkD#_s`%FRsQ8tyCpi`17V0KMHG>79Jx+TjbG)K}vY2fb@v|82FoUt|!b~$3Du7LrE;QFVh5q4h1;AemfcGeX zp@T&N3xA*d{&Vp6CWFtnd7lyJT}uW7y!S00{g1DnJ$tqsMawJ7_Oha$B2?u!CogG* z6oTPFvtwhGwhp7}{QmxBXwj*b?}Pmk9kf$u;Nj80i!M(lj4 z_G&u3$bIceSs?r2f$p4g(puxg^Uwe2qgy{K(Iidl^atk%;B`^K5VnFL&!*av;@HI zrSsptIQJPkR91KpE)}AibEO@8`u?Stm)Nc{)OifpC!pEJC>Y3vLe6sFZU7%-G?I_k z#?6owy|vn4B5D_%urMzX>*Dmqp_V40vzENr#weu{rzf$+R-no9!4N)eRy!kKJV1W9 z)*c2GupNClYNcC0etu3}INjXnWX2_`Gd#INH!oC>d8hKMp;Ei6F5fuT%9l9aA#Ph1 zB+flTv!8zo+m@wcHIiy6SiNSiW#`v`vL;bgOB+Op6D2CeZH^ZbOBtC{Esamn26_&( zOcN7<@(FyDkXYeW}7PHaJXTuywPUrvzl zg?RQveqrW=v8Yy@^PfRx+XvXC5}rN3XgX8qaz9P%mbi||-ZbgT8U)BYsR{hlz7bi6 zo)({9mHJ6KI@O(r5bn(oujNQyO`*w0!Q_$Dpg?xWX ze&2N#FYwFod9Vv_7(xX8H5ZWw(6tCxc+tKShgNi1gOFIhUwIFANuFQ4CeIenB9ig? z)pyx%gLbI0jvZp?7wKTuCYcB>b6{b)+^j~AqQm#T`nv%5&Yywbhy44C@K^5t=HbKp zh&J!u*}ZAeXojG7HTYb5zxdZb|NEbJ|NW>M5rzeH1wkG<;!uVTJ7sY| zai<+_y=Q$d1-p+>MRO#quCCC=d{`*2t{wN$wdIj7FLPpJ}QwS^y1J)SylF=6hK$C4*0E8J+R(7 z6@-3q?x2b3e~73GW^3c2plpaP95tGaP(wS>BAu`~q!XCdCeezMFdQSt%kjYIS;-<; zunQw{g}i7s1*@|TA_^do1$s@ei={lMoV5xj(U(h1K!+-f+21mdeE}+%?p?mp{c8w_ zql*UnJht@&lc4nATjxIXIBifl$V_K$~g-?!&*m^U}H! zt83C|2G5wy4SPnk9y5q^&Wgm1lWtyRs*;e5o>`8_gPqv?z!Ybu&RS_V7p{DFs^vVb znVth(@ax|-#@cPFlFm-u%S}b9K>KF!?swmkTW7`2_mTtQo$^i(1WNPV~nDjU}GUL z$n7q4XqXTT9%F9_-7RiP6XTa{aUt!C+>+ggE$KD|qxhjQw5v5Kc?x8~?EW3S=bZ1z z+1mLbjYczHNubZ1d(XYsc8gNLMX~n50r2EFsylo~lGX|b*V98rEj;XS9r32LtV4Z_ z9UVX;u3k^%k+49=SV`eJcW&_&L8Z1D!taQ=TyqTN%!NgK&ti8b>gu}wcaZ06CEFuy zLqsCxLKf2Zq0Z|K+xLKH?5-$oSUBGx7mg3L9>AGV31@ z5zBf@2(FPl_}x~RQQPioGdnxM_fR*APswgQHZ@@A9+xZc*Y760;)i( z7y5);+c$Z9fN~&gFGJ6=H#KUBuuNOfHHNEgz56gKNkEpVsFn2w)$(foRX}&GeA(~@ zU$$Ph;_eRpW%UIE4ABrQFUJ_RB#g&jS706&E#-YxMkjfm5#Dg-uoD0jDdfDDu+-XT ze1OP?)(w2*fqgov@CN7k&e{b9J|Cutbxnkb|D+fAc1@I>G%6oJ9v}GL_YJ_9+&4!1 z@9~uD0Lig^PIPa3p6|nx_2qwGN}JA1X}*4`Tq2gR9T8|3W|QSF4zAMN(=tc^4?Gr5LS*7=%{pGS*K zj&;g#?gP~}EMas#b5@~C8M8iW@$mo3kVf+eH-30{*g>v0?L9eLR9|SOdzUfnsJM7x z!s66I+tz&V^T)sb`-j}MxctEiX{sPJrSIz6tySDyU0WMhVwhW@e;J4#zqz(%ShoFE ze)@5dV~*Gfnj#k+uNYu%QxLb?W6TnBTp^S&qtJ`4F(s!1fByE5(~$EUO`v7V+SvHc z<;NjZZ;rB;-X>^JG=@a=QBQU!4zsVon8l$-m2ka^?#az2t9VQ7#i0=l*kH&l(PZUn zaxeg)Z(?+v7GgGp?#irXfbGF)-DR4!6Y>Y0ui*dcg_N+R@WY?i|4J{GJWriwZm+2> z(RTj12TvdLP;iXoZ%(5Vd!d`n#Go_7&z*{Dk4h{UvQyg;fcTJ?0qQu7kTR0RRmRFg z?ur#xLN)5({NN@M%Dh@p`EjMkhL)95hvR@lyD;d=Gu`auK7IGQ<0PjLNhM1$+qf|@ z4=qq3xoX!xEsQ*~jWpJo#!*KRRk3)K^^8V}RJhe4=t+v|BcbTjSA&8tH6sy%v3t1T z;>u3$Mb1FvK${9)!p<>G+08h`T7w!<^rfVAf88=&h&rM)tVd2yw!pIOqakG)rRS*&x43IREv~E;rE1q*SAdcBSS0Z+j7JPmQ_*Xk zdZpgM|lL zAPMYCl6oXCCW>PN!_BZPGZIRLmS^zPAOm2)JmganBY{au+M!V#<5BZwfk1*XOQ(^1 zLwRb(E!T?LGz+2$?Aaz2Wt7CX7^DFW~vj%gZAc~uTD>% zJb!X>gr9Bb-Xmbw*t@%Xw2Rxn-L-qW&kV%(e}DhUiBz!&j7+fM_+e_uvd7NPPoMw$ zH7^91p+#A8Ept4@KGm8BJfEplH;*~oVe|MugRxAz-KjzBjAV7oSJuYu*R(IB@3;|pWqfUI^`_x>b=)Yu^1TO0{nq&FihWW0i*{IO&VkC{DHFs+ z2V9i`Qw4J>A=*I~|MB*>6tMKKO9*fL?48NSSD_oLbSfi+3INZsx`>vm?i|G4vWj+X z$30Bq3yCp~AVR9wXxy)8h9Rd6v4;nqfU;rRvW`Dhw3e!3mO&-#aB>4|UrlK3D%x6v zv`Kh_=-a>W{<)N^_SQ{_EH=E&JuZs0T)rXxD!_6T>(d%g3!8)ZLI#i<1C9PIX zH1o@r4VcQbS+JjZry{JiMtf_o8rB?p(>zhGM)l zCDl`3(gG8su4Bao6XJ%{u2Z#jrZq`P07mZNxUnEH#}H}!QL1DSC6(TkzQYa;2b_9} z4>60O;Z) zWyyj3Wo((e9DJg$eqzt|BN2=O2UNrX(y3sKrzEk@kSvt6hxjw3^*++bc{0;Bqrl89uNrJQ2=qoG~eb+5uzh9#+FVDgGv! zy9i;s#j6D$6<26Bf|dBv&vbx$Sr*rl&5IXbyn6lm>dSt=zuY&Ro%K5t)BRy( zw$nd5dwFIWc(!7yxM+fyla2{k8m=LSXPEr1!TXFR)FLtIYhu4$6NWiRn6RF43V7q& zDPZP+-$xk|Xxmw4S1bFU-JoYD(uS1N)48ilOYhzOT?o50*n1^+`@yGw`|QfB>zZ{> z-shED2HMqI$N;YzVZmbD#jkC-wF>{$trgx{xe0Ylo&1AGurt>d*@=Tf7^S~#dsSRy z|0_;Is<~N7MH-%I?mk?w)eGprE3^NV%fp6w8fz%`Q#SFdn1DWfM7N zR0D&!oM4bs6Ad(+YN~rjNnI+@-TC9g&kU%0nhCK7G1|q{Cb+@Yo6xKr{+H|Ramrw` zgUmG2uqI2Jy**q(}K+)eW__He){fPD+)BHJsi?xZG9wPQ*Um>fHKN< zZp5H(G^&bm0b6BA#nv0L>&Ds?M;|Fes;~A7{HEv>NnA=*VNlS4NQfN;(qyNitwJBw zDu_xZJB=vpL?AF9bVTJ^TA~{v&FE^&9fypH<*ACuB;uKimS~OK3nZGwQU_PuZ4p>R zDxn?g0rHemR!pnwOxmLrxx>`smc*`j4N|uR`IO0yk5Niq#RsU&`I2<@y1OpW*`rj^ zI^8V%^E0@(z=#zP;HTKaX>lBT{(>$x+*L$;iGgR-0+YZ6XyC+snL}b_Cw+Xse{y%y z_!3;E?1E`JFf?T0W(IMnT#d&bGsk{V03&>X!GLkVcrzVD*bS`lq}r&DJ!Det;W8Xw z36PH)TTrvul^I*YQkW*#66$jUzwr!%oDik9V-=V=MKBkhB_dscZco19eLAi|VaVZY zY>1gKwjMBZD^k*B?b$^|IiEc!r_QJUQFVQ= zVpu{Cp>kTUyVhjk%$h)(%>vuqiiRje!J0A7gK$|2dWnW%VK25rlEQ{5eK3}xu1sib z8r(g!>%ipy*yo(j_p4}jEZLIo4_!gd_ngo9oR3GY30my1J32)<_)hdK2Zxhqqil$B z0QR(G6T3-oNwn_}k9#gF$}B1OSY(&=PTS)uLoQa^B>-cjGFLfq>I&SOTyqq8fl+z1s;LJ;)>uMn7i~%6EnJ9ZnDwGt9#RLKo(8haW7!gmru{ z6y_`3w=>x5C=z!%gAegohdA63{M`@$7W~~l=&v6L5ck1{`wGR7ur;$|{}K?qe|ehG z!Y^YoB9Y4UAwn;=c5}O!@KBie?4q*!pKo9O_sbV&&rVKIZ0-;Hm(0BU>g>ho7vDbk z=Kc3Ba#?}n^W84T5uVp}YtOsSYv)rL_8?{Gz0$Br+Mc1c7g+l)XE^=00Mt$B3}W;r z^C47*Gm%+lLH~acmTJ(ydiU|8ikhtyTyr%YLP#CDhKCnsDy3Q_r#-@urvLSeYd3}E z_}42_wHXwR!GKpLt5pNDa9T|Y^Q}UIo}64+6gYleuo#u!$rU2<3Yf3}vOM?W2L+wL zz!)r$U^QBy>6d@aMiOWWE|h2FyP%VjX3Dd)KriTDpS<(7V(z#V%l`cCdy_j|0SsWL zAX=SeUtzX+q);F+DldpR7wabTutn3%#9_cxondj()a6)yt{&5<csP}b`Y-p7F(6r`y!L+*ys z4WAf?03+EFa(1?sPj;adr_<92Xmev4i)Ni{nFz);+1oskW z70SCV36PiSc__)Nben-1Yr;nfc^inDVd&xM+A53INYGlPVl6jMfBKu{aU7-Z zrg_71R!Y7Kn6?tD<P z>J*K7tTb#yDT{`u5+;d@MT1NR&s4HC^jDc@v#8*RlQ2LA^*9JDj|FB0VR39X(1eTR zfqX%;7>;mP0W#DZ-7*N2)^f8zIWI+J<=5eod|NWi9RPrf7CXUj4gMC*`%^$CV-2}? zz715Ml}vNnz^*a4aiH{HF*)G+V#KPsNC*toH{3eVw-qS->RS!%O30oL&iIPUFLW8< zKXqWHLv>U5F4(D(R7atrC2-&Y2q;UtaUb{!oNLiM6{ocd$Qu=81k8b5L!AbCz#7#i zZ>A9`$`&RFti(LX$#nTfiKb+)fM|^ZY16Y6)ta+|qN?kss4at@wjs^JCyWi*!Q-m? z%K?dod0Gy_(N5gJb+uzDO4}7{;5;sTOenfKnudWUTX1upEUn?J!}d~o#yG!}=?r2^ z5Z@)Zw3F)LDu9yfyJ(x0g^M0)lxpRod4Oy=WQ!hju69`Uy^7C3t`zQiDhW80;Gs=B zar4peWAf!gkWZooEXLAE9%;L8ZN6v1FwkiPrFlMLvL_>q$BNJf9f?dOI4CI+s~jF3 zP5k-gaDV%*rN97T`Pq|yP@Pqfh6KIQ>1@l_`oVS|40yfY`EVV-uH*MXzc0Yt2LZ;v zf>#!W^@982eo-)5e!o>kKX7$rIsh*h5;I!9q*fT?o!u z_A-^U7nz;N2=~IE{>_9s(3{ePa>>9a2&uY4_(C{pt)C-l7Sq0 zP>TV!fGfa;K!D?ew6#%wbWQgW`DNQ_c}@#dQMhPZsH37qH0}{(J#|mh8SMijQ*HFo zKeTv0VtVL2D zLor+=hIzovI2SBb^vnR@}nLuxGZSm zSR+B6c0kMJ8LuU42f4m2@7m^dmUhX0p+3*EARJ*=Qi95~&hSfQIG11|pZnnG=y2=n z&yRVO9B4itdzD*3&u_Zu4wVC))EQ#~lubnm0ZA`n%o;A`g$@>e_tq`1Ij}>$iX2 zy*NM5W^|-Nfwf>Axj^%@(0_t1&0pn0qM!*_UU&}waUslg^K^X6?%gb z*d2@tD!zqWCc8K99!WFYN zuh=dY2DMT>`{~cVQ#JNkwul;;QrN4KTXhS)qxz?Mb3?sX%Wcy-nwmwc6ssvnRZm-3 zBpbscftqjai)<;>l1}2JcDas2o02-KIukPjt-^+u7dC@2DhUo5+)zfR67V=41-dUw z_?q@Gf{a1aLap5yQA_TZ1Tja@{tDR)Ne%TyV>>g43JmsQFHLj0;gZ5(U|+}efZ{QZ zW3*&N^FUV%78>P2-5S3%jZ_^JUtP!0RHzlhalv{0ien3gU{rA)v1%i4Q;%1`56$-W zonG-;jwe)0=#~S*>pB1M!MNmq_f$(j!lSt-N{FE-3WALP_5lD;k6mu$(y2_KV6pO= zPsoWvL-yFf3gl2&iaI`kQwUoMf5uZDI-sDcD*qNF_5u1%n-Q5LvsQC;X_S@+p9qa? zQ!*CV?g>s3par`HRnZ*9B9@8~B0GVQcvH$E!)@;2Yxyv>R9^AS$sou>qhNxc|O z#PloHh50yy;fdH3s<2yM5BK|f%72CJ$_>8;DE$sl{T;xO)w#PNgjcW^h2Rdg=l(Xe zXsFQx26qeqz_{B#ehJH$nE)Y2&2?ON*5?-t z0I!WT02>(o!_Lms|G2uI*S4}Vnr_}KWKF|k7S?-0mdu!Gc~dHvQHvLns>P(wrCB_w zz9JqA!2^Y^1Vw`g)FBBCorRjxDTqRo22$#U;*e}QlujAaIFOFpE@si?Knp|vkACNT z_uePR`C{roYM>DQ?9Nq}uGK)6Uo z47C#9?vYex>sfj?|w^%gjwdX4u1{b zHfHLMV=voenY$oINkOCaAf`Zc_cO4crM+)Ubu%Y>>q5cIrrA2l_jLH;g2Jse%q8KO z;WNN;vi{3==y8(Q>SV;F<2gN70i%~AqO}}u z4r5tFHC_E`OSS|ti)1OE&ay@v<(lG{ay@pGx3owe5~I~j&OfrkiGj{bZZ01`1?ITK zg~>AD!Q~hsO7bD7E^ekIE2KX{Sg7Niv}VoUyZhZPP;ZM(IMAU1wj2Xw=P$4Wh|?Gl z#j(*ixUt*Z|L}j-gr&Iqm=A8!iA4~8Oc;hI3kZBqE5A^mVa8Gs`plMtAxxjkx6_yZ zpbS3HnME7jz449a;MI-i|HRaX)6>t-E%_A)zJD&e3j;1t_vF!o6PJ8>;p>4S@xPnu zFeBY(f6&}?QOMCie-3Is=?3jBQrFr)1tu$(;1S*s;d1wlwR8yy1Q5) zX9Hsv8UoFe)tH`RXtp}CegZvNIO7O~<_SjwRu|ZmA&(%mDV)ymo? z;e%#Aq?{$MwwYpuOH(_uz#Y_OLFHUCngPk^1cLh8;>?7cxs&J&YOr6Z3ilQaTC#cC zIlyJ69mHND@(Nv6jHTB0BnDL@bh6r7(b{ZB3CmTk8ti9cb~X*uNYJDz-pNy>jV#(| zfU0)>^3HFEbi&Shg&sSlT_nHFY$1}A zOaanMuLbY)z9I#K-qfk3*g>i2)MV={S;gGUi@BLYRZDoW7tqD%V!?Qd$$vAyx5rXm z8lcT6GP?sB2V9v0Mw1mtr9?6VK4xp;w8de4(b&7@@r-WI<4rT;*{d9ZtQhxh3KhIq z72q89(=Zleja!^#4zFkS3O(PJZD!L8KNi33v{=*_`vlUpE{-k*6pI19C4fj!7fMW$ z#quM`Eq?n8O9tT8!HI)V)0qewG-O5Fg2lDER(J(%g+A9*K3xi8;xKh>VhUNdWI3}G zJrkg1NfV+q-wEdEiVBY-?Mr6SRZe(pv6d7YD2&D_%TKA8!-^Dx!Ee(ejKmCAxE7)u z#TeVia1Cufj*pqCfh^^a?MJv`IdK5$9B#`(0fsNRBDU!|J2GK3#x-n*T!Yl0J0BCK zsjRDdj!TL3Q;QVe9rVH*^>|MnR@ShPdmC;dGm0Hd6H8vy(z zyODP(Ld)6q-rjgo+5g3hf1SVlN&uGp_e@i#Kfe#i)|n6FzmJpwKPsX>ep8?^x}LsZ z_%mip!2C=DmfYo*(p>gH!;VF??RG1JiiPPeXEE$D7OT>{^Y!&Xzy%Tu06+N?O1zue z1FXoZoxq!%bhNoA3|L9=o{kLGdZFne%I)vzaO$FxR5r?jq3Cx1OeIdI; z1!p`c_fZfYmXG?EzyC2uAT>FC0ho&(BrsmI10(UdIoKc2Z3WzI(yz61byJn-s|@G3 zN)wh2W3csKn?p$o{MO+U6g-ht!5Ks-=yn8D8Neu9uF--_ruZ%2sc~I=mPq zbObX@IpI)Ubo#&pOt%&YC=)n1b1>(8KK2SD4SLb;ux*%AlRBDJh1Ml1z)8}UeNqhD zWgc@Ym)-MDgQyLAS1UOH_NARPp9s3j@m3muHR0wXjg`zhlQC}PnvFDvuUpn22kM4Sm}M=mA+{q=p>WH+Lz9Mh zJx)@r9t42DHhf=mfhvvB55>H*wtLJ)MIY%Cbr>Z*rP2eL+=6E<~cV;oXvGY`21_tgDNf#(it{Zr+` z07}I|&r^-vT(^*mGCe)D@sLkU^>9)~3F~-=%1|iw= z=-C<`bJMA=4otz&ujmrU=%?fPxc?~R=_Tb^G3$x)+dQlhZi9IoQwkN@D!=TPYRqDl zF#s8!1G41rvw)~eVk>-XiFz{RY&P0Nv~K}p&^~({g|!&%tvG&Z$wDYx#cV^O*bUUI zkww=^!e~oT9YYUc`sH${MVOpn`&}Uw2=< z+8_W!f<8a9vD0T{!1pOZKeF`q^yKv9(>_tG&ff&`(1{O?9vLo!N@C) zKtzkuU<;NjytWG#S=ky?G#MIO3z@w0;}1S~ErrsKB>eW%hv{Al+tucX(~xW{Fed^N zj|J@%aYvejwWqqX@ZVe$J2vkgm4662D@Z#W>fa&hE*=7V!G8P0a=(96F5`cBU7q6M z@bKM_X~E+7K`78Wn#j?;I@p9e3mr%m1ai=A#lGMs{~>~d`t#0U=hNN~t~&I77W+Ec4Bu_ql_s#ND zW#Y^`doAB}I`JCx7S13~P>X(?EL$rynnG&LGEba6;q{_#<`K!tshOjinf-FI?FDSo zO&y3?=$I;?8G9MV!3i&>*xmA4!jRp|oy?xr=&Sm^e%V9FTUT@+ z?3oCSnLn8mnXzJUbXU*l)&y3B&O96wS+lj5h|5>90wbsP0*$>+qwo0L^aOTEg~Lz( z&(#&ZwsoJ;Fvi`3Y!>cQtgFgbC4zxAX2BHKutT8i6=yvC#usWEY=TV*F_f=;`C1=oNf&4lhj}Ag>_GJd z49Hheqom9lfRhGZ?jZDu6V??&>lVmitZ1wMd_{BeZP{;;0}AM#XEkex0Q`h}C5A|BA5rVNkk93$EsjEVTIcxJF;6QPaBxj1 zHBTy1HduqF{7v^;jPn%ea)KuvcOmF7POxCF?=RvVxgZRJMfntAa5nJX`}jhGfXe`6 zRz}hJTh$4H48f`*B??m#P$q7agaJ>MZ@xec7?&r8zPvv=I>PNpAb9I&i;-B@cZLAm z>%%)cLsOigKa&mB-5nuU~!p$#;9l)#YW*Hkz4P#oVRpGIB-;#|=h7SGDaI zrv)CgRi2HxWljRR;wx*dQd%AyoO9BZA8d4+Ma981P2M{j7SlFyP?+`AQ4il9PcL{-mW{BsXGG zA*L5?3+=26Q|$Kyq6NlEb%CVrMdT;3^HJtBRr^5C7H%{q;CaOqN%n1ZcD7!6DUe#14C0B%xfOnpBC zvn;if!l-jSInwsQ8*trDFxUMUq%he|#bi5{L5ih=sGU+fE6XMa5gF`c4#aklz->Zp z?RNrnkqWztn{7}-W2j1V^;g(}f}*`KGNg4p)QYyY&4g1YA5!0GxIRdp8>ZW0qN$4u zz5Y!AJ#xpD;HTnxdh~7mmtDFk7j+YaFqs-bT*_>O^r0bxz%H@|JLFfFDPvJ8F zCi071>#p)J2EqskklO{m>CdEaEJ6wx5R8E~p*KQ55R1K`uUfEhQs9kj4@l*)jTi-4 zR&&824-hXcbQ^?}mS76tfKE>%p46VSnJdPKr$*=m*fa15%}#NS%~N^s@;nU7o_7t& zj6`ucdMeaxq~h*q%qnUdvmA|e-_1Yt^`K|PnB!fnt3p>C!Z}B z(&7xMB2cq4-VEJYxNi(74mJZa=|%tTTkj)!f~n8PKmK@pY;lasoXNoOC>BpOvqGNN z%ae!4)erym^wHsX`q**b@%R+byCru-V0rY>(RlpPcxz`kyff6d46m#48SHgP1ZDAe zI(^F9@YM`Q63z?SLl0jnO&*pTH?N+c1pN2?sa+iH-kNR=W$V`ucaZL}OX90&`_D`% z_@2FN6PO-7dGh$#v#C9}%-6uuqA@pPSsU=2=>#O`0K%2gI83ID(sUy+VQr*A zlzRK^{V$dbN(rg0CC(z$SGoeoe& zf*$}}1zow40po@j`|`dBJxC?(p2dmOWiYHNYKw2N85!ci-Gb#)A{*DltW72Sj58Q|4N!sNOd zt^t#Km{!!lKagqSdO@@AMI<$r^K^+pQt85`bS@FSXPrCWnvJfEm)Z zkt;&p-hx4z%}TuofB5;V%X>=wIEfQC)kYl&R{r{v4xA`)BPDb-@f#V@;y1pUlN7SD z6#aD+oT3wCzxJpUn&q zCs3Q&US>_>77Dr_8qjnL`1@3Z=aa~UizrIgQ4v277_i`!eD9+l6$Qr-X%6`A$2Wcm zag|IgMDZ7}y9jnnsET1N_JY_qqn12GhwF&rg!yLA)NP-s9cmNe024s$zr-NAdpCu7 z#z9yNgW_oOz%PO{3&?C@VgtH}QCb%G83B;ufOL{X5Y<+gk@ET9ky4Wd2O%1!XzWrS zGXM@%ROXE2^YDA|agj+$!&RgUVs4_BHG z%tWml_31e9MMfEDfj2tK<|3?cVv6Pg2Pp)Qm)T@3OqZvbuZI*N zVp*lc*wWb$4}-I;{>DIG`IsQTa+bpIH@7ZSsWJ=Yd->%za(Vgk`|kyaA6iQ;`;iF2 zuqDk`>q`%3I1gADaDu+$Q?g$H-&46iJxVU8U&-zC_3PKCav8Gih<(DsfCY77gq|YK znhbtjr_s62Of6cydMz8Rz&FBcRau9a zUeLle>{hi!KF5<5Yf%Vvk zpvrIgJ`LA zp+vaJT_-1QU@HiPW_Kb?562#wQKklM3Omk;?mTjPDfp#oo zu>b^?jj_2l|F%iTa3kZ;;5=679VvtMb1DLa`g_l6wD`#6uOZI`%u&EZ8o>aNRK1C@ zT)`X!sG{pRk$sE+pCGz8?h)5DVThODr{bf44ZcEcgAl58>@Nz=hT)s>|Q6wI40IL|ol z)Aq0u-7LXKnkAkwSqSV!I&8Ow&TdNS+mRgwhD8&aW?8y)O)fJfGz>jBST#mHEH1>b zJyfPpDj#H=Uh+z?l$qtP@B$wNmt3Y8q)+%mVWC)$nS=44@6UwsNV;mvJ2**X( zA~p`-!rlty%$)rjVK!kr&?yoFEGXo_VZspk2%gjQ0D<3RYcv>)gvS$Z7$pdFCnH?k zSR1Sufo}idJ1<>!K2GV`kZfk-z8;@*4LyEKkvaW2m(lgQE^~sDzu_~d)l!cLM|0!R z==Ul-k28lw<@gz-WGS%Tr`Jc^;W*@rF9OumJ;5^6Y8+QsqVR_ZeU4^?ZRv&A&*=b}e;(>I1 zy|AAvZ)}{RE>zWfpu0Qimj-sLaRp{sk)Ny7Iy%Tsexr-fwN0l`V{qfBmI|rRW`I$p z8<3L>N%KLu%amuG@ladlTvm4L*Qz11$!sYKNOO6pnx+vlKe?RNr_hEW&|0B9B>(D~ zf@TG_D065|6`^&_hLY^^wNketT;NZ=&VnZNRLS#;vg?$Kfs!Pmbw&B9}F;jDX&t+6ihxV&v{c{i6&TLFvlH zoA1GC13kZM^8o(+KOYMQ*J;LqE}S)>7&Xe#(&6JZ3}di4;3rN3|LNq#iKXuI)6>)E z&jr2mT^=N`!|@Awe)8<(3CJsl@nOdqenmUX_1=O`?p=xx4i*l!A3uBen;kdtaLYXb zc#oikZ)mFd#xIVp!}9XhjzD-vo~hxb2B%pq&D8Mj{YQ81W9$7Vdu*;+?xXx0?$5}0 zWAflKZ76%3PQg;>-uhav-&^bV`ULR28>MXozWRgw!GqQS>XrkMHra8cjYgNW%Xg{2 zs^!j?7_dSYZYo(U7_hh*MT%~~n-TSnzEBE*bI zk5Sz<812zpGRB#4Z!lMsX}2{1UlX;Rj%eD9GZHy0d}n12aKPfY1u34iapw}OB81AHp8w%uF{>H&VDv#fxaf4BtY+>vuTvrsB?Az=zcD@Jp9Q)5zovEWK~%;mKlPZ)(Zqd()u1Dr-q_5Cs%VleimIncUAh2DwOU#py%@yi6gy4))K*@`5! z3ydPm=0IP#Fab846F^X2fiLo_UH}kivKR4CCN`(nNICjF)Dc##03^_YDCDI_2Ah>g zwQ9Yi*KVX0Ult6|g{8)4=$bT$atReb`@9`73{s38oVVRPYAn zZXeT-h+H-u^|byO1{`)KL$lemMObG;(4NLGmmhZ_5COax&A*(ZFdo5q0?Zl147!z| z1&3IY{RVJgl&xJlVZj)TPqil83FwJLz)b5=t zoX9%Ew>5-y=9IM6t01oZ2UN`Uqp>lU4d#<9RRGJel(KJRGe8=BLu2n9^=!p9F#3K0FH_sQRN?s^nK9t7t@Y}#))yN9tW6{IM3`>7; z`ga|JNDnIcwi&M<9QL;lo;|utK!1+0hxfqY4-~|7zC60OwRJ;eFkGfN_Tl>N+raMi z{r&5=_}GCc-iIK@^ZhSH7w_M{`}y92^@D~h2ReD9Q}^ z%mcnU`*!t>-#u{jy~H7eORm03hZJsJ+UP5qVHb@&u$E|P!xDGh{5jByBrlP==%IUA z)vi(*s#s&sU@sn5@Sk_S_2!1Q`GUXN0!*;N1*=KFNx2$pO3AT=$orxxSilRjtc|6O z=4apb-d8>YOd-rP_sgPyTVqUP5V<-*4i;TWXhwpe2C9!S8CWRU(15MLu**roZN_KE z?B<~bWI`n!(VZ%yWRB>@3_N#r`Ve|*y93ax5p%?@=**a7{X{tq=?;z0cIjuZZ-Ta` zWXNg1l-iAWIMN{uNXNnfdc@$*&LkCqG%M;QW3l19s zfEwQW^z~nUH=8SX^@`WAH*@tnzS1Zw=78#BoGwP1&J&<;P;t@YA~iFd7O7LLE>G$N zpwi9E@}nj_%SMMqN=D;rm5fGnjn#{wNp8`Y<*5~-4#LL8ksU)JRtYp?W-<^G)>!)G zmeQa26+$|rFF)3}vjLcK={zv^JE_{vjhPeVMv<%7HvYPEJ=@%h=hQ-+ZwXH7&&24G z!1(owaiM^j`nOUzpFPzOdXde}LWAJY;(AqiZUJrNv#_K%SAocq-~P3S$k>K3fi4j@ zX8linipcFQMO~#6u5kN*$vVH+w$3w-=VGWAa@av+#m*7+QHcnt3bSaHW0Tn`bNfz~ z6FSvIVJ(`Ns6tovdW^M)-IygIBo}I7Dd;9%3oR}*Zpa#lWkM5-Jr+A87lD-3URlWq z4vbv(AK3H#KJPhFG9}p3k#x?{5%}|dpC8``1z4;b5*Cv)sZ^L!cL*QmOhFW-9O@wS z&>@pvN}}8umh@^fO{AgWV83!tDCWDAtp`r|sFOlnn9peLQbxUzX%qsT&UEkJP(H0| zhAzvmw91LSvJRC(GHo1^SE8_6%|)===b-&Fp;kcSl=lZIEsIhMjQ#r|rV$5@AXV{c zebwNR&(wID>lU;DL7h|ZvQi3iI1H$7xth>QG+C-J#VZQ}e%LM$8iCvyw`@UAFO+Wp z+KSMXM=8&xcjadUwJWF(JTD9b>b80)(39^(O%QuXSP4%xGK^ zg)vEJpDj-|hHkCRym#^Tmjd9;4d;ZleDmfPM_%l0JI>x4Kl1!0!Amtv=x!(S`2NoQ z9c8j^S5$9r|C=tDDD^7CuWDjyZGCv{-1;T~e2UrPZ~`LSw@xj7 zv?_A z7+u2Xz$%}9|E*u2{C^RwIbi3$;oO}OTGoEwiHSU{IL5{r9EHS@NqqthY9{x)X!+tAMpB?<=%2Y{9yHJtcEHE41WIY(hH-P^++IS)STWZl}hvmiXc$ z(#^(kX=8XU24pgJaL3rDbTy`Db=`n)vh67{NqMrHmrc*E$D{B7)+%-96CrKmqt@g| zK(rj!nwXB(Nm~cpqqZMBceGWVYI#u0U&cLCAE@kd7`J#8u9VfU#`dG}TwL_r6_r!q zcVy$Gka7EwGuz`K6AAtyN2-NC@}tWbwET4!{wz^?`i#<|aVC`C9zev{E37A>?_3NO zDPsW-Rh@c82*A4fVz@h@bJ*APYrwQ`6ezRcRLPcOpB2E&gF=kr#UaK60m%UlnFb}( zh~Xk^9;q`F)4g5lb(dh3wFD2(^#uMcp;-ycO6h6hN9I}dy+IGK?6*eYqGDuO zRQghY;5Xh70k%PatBPfi;8(t@FoXaW)<%33r9Am1qF5L#pDYZYJOA4u)qcgN0DKFD zS8Pujp(FClD3i0f36Z5UmB22Q$ z;y4F0&kCYGb7u5>VQtk)=WOcJQYD+oH11Z_22 z8*66Om-zILw$`!P^8GPX3C}wDX_T5yzFLPh%l*_CX?FYIClEecljvA39W38~ zlRR2?XtqRK&8qC~=@P^CWwgsDgRgisPGCS{*LwU6vbkq;X9g6nC!poos&wZ0x)V++ zw+v6*Rer^R@0xK~*K5Oog1pr1i2x4ylb-QHh(Dl!jtQ zWQOz%HCCO{#Ylj1G(@q%XeZRl5)y_K(3nyb@SoPp@Phtw(G4QR6r|jxJb#JV7d7Fh6o+X79(TG3mJ$d7^7Z6`Q2FI&% ze&rwY^VPjCzxWk=p%drl5l&yo&y`*4FQ)}N^?Ph=cr1To{+*{~@4)S)^o>dQS~!GG ziEL|=Z@CI9lPiT-x(ZWr9oRQw;6k%Q!{$=9f;L_hI78*OQ7^?-VIgaCvJG=b#(!Dh zg~>!Ecu!8bpYV2WW!sIcv%t(|lTKq%wTODRCRu6SYzuoUq<0Cy?OdzXqC;d!x0Nm- zdaNGRlbxpQSq@df8sfmA33<`mho-UzzW!Pk4yQl9aAme;-`)4ut6#nL{;Ti){G~T9 zcH}c&efiaA&H~oCN(VZ*f>BKE4yenSgCr_SqM^cZWtdhjHFWwf8;vWiQm3KO^ad)i zK9pfJ|o5}g;3YsxF5=L$7z!s!=1B@X|ESFPET8^;hNF6x%0L49+wbU8E`wli9J+hA;P6T zg|KUbfk5>&_sP4cMFuHUugc$kfDdpJ{6-)`k`BI;HI~}r%IMD7__C|?{&2*z+shj3|y$r=<0J+NeHVvUzfkh}szAJHN z_s|j*K1#has@8c5gv@`7f`48%^9zTBkUkyQz&R`CqT3`(gsUz~x$lDWZ z#ajgM-?c7kIUWFfb9sZkz;J^epANSkefNkRM_)`I?5P^w*||49zV|NB`-6b@oBP}M z0Nw{b?C#3{-CI!GIx+$GCOV?Ehu&Lb2wDd|Y%Mqw4mwVs(E$)FgN6cz@>P>d*j=t- z+%TYfn_R|SK4f|Hr=M>fANe0!*Z11iVMfa+ZbNK(QB08{CB9l>>Q)_=NEO9ombTcr zD7KtdF;-@n5omKs0@n@{E`iNBX~O)VEL#{}!C5>=U6_qY+>ts{nh@N<+_JpwAKI5PTkWY{lGcAiEb!TEc z$5945+K|kF6}}Sy4ks~KYtckpU0D-0`bZ!SN_4MgMcdehV3}t))u z*;xb&m)gEk6T;XVd2Nbfc4eLD4IQBlOIm{k?0W0K_eOX4ldOJ9)}^Yml`A8P8Tps0 z5ld6^E}+BrBF$HEtm=n#SI_vF;+oJ{s^0p>fMt25rYzA{DAt21pkir70VzZ^PZlUgt|(+H%z8?8 z^$7Y%5TUJ}Y|Q}IHw#rY1X&)mD!YX!ttY$bh1+>;y!T95wk!60d(`pmTF9EoU46Y= zy{))uo8kS(C-GQ>oov=>o4)VW+W4%{?}sLF0I>WQz6iievbyNF1P=%4!a-8`Dtcgq ztPv_4(AdE3P^B6rNnvQo#g)aFp*5MOyE~?Fmhxc-_=)WVTwRN{6nvr2n6+ky$}f0e z%td1?jawAAY436aO5K8d1xT?7V+0+i$(b9l*c@nQ4|XDClkGY%YVk23X0kN&q8rbim7UcFSD@_6yDy@c7}z$Xg2-iGVA@f>>|| zO}nsAIk=GyZOa8kXsh4ir{E{-Wllqpo8?`n5S=yPRr#ur}L;eEC|EX82|_OgacPH3l5 zJX;=MS5lZr8PATR^s8eCZ7d-(Ig}>LX9kZ7x}N?}5f{Yv6!d0!GYYp=mx|Be#eiIj z&qQdfAL;t>50;=ckM))`?rN&_@@vcc`+Dhf9vh2;9{1QNLX>?ug8}5XmvbA~3>^RD zy@>suc^-m?_deh-KEasP#zFKOQ2`e4fHfHb8^Q>M!yZgwW-xIU#n~yH&8yMLz(piT zG5#XY)Qw`3nHJQS2lK@`im+1|mWop_cI7d~fO8R=WjeZ$^$7E`HV&l`0ge78Xvjr+ zu2A!30}*`EpuhZ3lZti*h3d3&=gh6U>sOXrhvh?`{H(wGP}l8W-~A)4cK`q&07*na zRGo3Jr*0qXZ)I9Pbe4Yg(ob3&*I!R0gq#Ze?*b*BkHMc=7 zBD%_F&57%^E0m#lX@YRLt?z|vL#zskSi~#abyx*YZ?mcruNM+Ql~EOj6_6ESeFHep zWN5rrlnm->-D1--m>!t?SX>7b_18C75ZrNZY9(=7ZK+ydKFUD8{&z9{5@bg{@QFHV6e#2t=uV}UXN zF1C&lQDP_>lgd&=b~!G9qXKqQmqtZYPzEs)0%0J_KzH`g5^;YXV-Z$CHy~N0(aA+Z z2;w$CKwWOGAr@eoq~I}TR#-AJPS!y_GIVfZg)XC{lF7vwL#B2MXpy4^9Ta)dkzCLx z57?WM0ZrD9z;`maHwZfDn8I;znT+cMr6%#mD#7NJfLgp0z@a9OEh->TCLlG(M#9+L z6&D=Vbpn?)Xd1`SIuuhu*#U>eolgqd#vCfnF|L8+4Cr-8cfoWWK(=7D0~E$0hlChA z5fWT*_by!TVV6b!k-Ue{JN~!(+d2;edp&d-nfROX%v0u8Ogy?Fb6QH0&M}* z_nxf6=$yl$PIRgSjduyoLGCFr{;IRoC{dAy6H6H66=p#{*9k0N)#V5Ifp{6k-Ch8z z#azY9mQN|17!veA7Si<8L^u*SK45q)Z}LY+!h-LJ(cUgFUDKLJLO70o0TAnN%z{RN zw*(I~ka*z!I}1y@W+$@DogD8SFJ*HH@Lin=tg>@-56 zQw)(rpft7UG;7FZxQJy#EGd_Z44SM1%<`C~1luuVrMYd&!mVIvLU}fmSuJuf;8dQ` zkjU1^U>zHg>(iL9u=K&X;o(a44`(xA~zIeFrl~;d? z7T*oOwvo@=Jols5i^9^+elWaHE~hxTDX)GrWMeX`3kq`+!t*rapW*i+57(hfoL$J_ zgaqJBu`vbP*EBk?K0ffq@sQqDwNKRwwKHC=ZA0?B$Q;C%svojnLq>x`)t8m=g{z_l z9W@yHwXpnZ1kjKEvp3GF%c`pKLcb*?4}nJaZP@3Vc3ksK6E<2{@prIQqGKD?Laa6H zt#~NP%Fl|Oh60oENy3vSxN9d+@xy~fd^-Y1-*4~P3s1-nf?xZ6Q@A4(HU`UU3@=5A zccr2#ww;x~WB2VJ?O&)?6Z>s}ogGPgzupbc9#!mLfKMO1l#1Tdit=ibXMISq#|rKQ z611={fzLt^C?Ny$a~D}Ah3N|Fvc4|}B-2*~DoX8_wjo6&PQwEkLpw3JB?&Uiv(&8t zqS_!t4oMOzpjlw2D|&2g9|2ulV3{2Sl4T$(hBojFsaV5?y}LkDF zc>ItXv;ypBb=X*K2k5%oI|sTkP0A?YQd~yiH&6l`z_`o;FK|_Et}t3?$sO_n#D=>n zN&bt0xTpgR`MCbYnNqEi8QM-WF36QIzNgK>r6hnq;U=A2dcE2qMA-Ek}CvSZlzawIe^)7P+!g!>!UuJMiF{2B)> z-Jl4qsH>9?3BIaAuTAx^uuJ1rsnZ>mgdC8plNnTiFO7u^_}!=tDf~tsa1?|! z!M>vb=54@oMQOT}9mvX}Y+OeY#>>6EYMIs~EWzs8E`wGgE>RZ%OTNo~BbctR8ZRGe z1Cnafqa&wZJBy6Tk`7o9XuWlGd1=q=v^k(*vO*hDwgk&Fn}AECz9{{wRa!Xk-I+7r zhP<|{d+$2jQ1zxzHq0eVk#9oxMNe=#UoWGhr-&9=vR^dKqRA+qM(Bo6+h$rrEgEni z3ntg8Z|W_}Rwr%0Y@P=au~nqrskH0Jtg7&FSN0-ch8->^!E8|6Ht z9PB&P2ZwZiqc*dVKm6jktMc$s&J4ahd?_st2dGl7{*SKndu{7H0e-{x!7H9!mjoY?D>A5_dPmFHz&4bonO*1`15|B=leVlx^gvYHGm!V zG~SI4%7Yt-Kx6o^ymWcHY*NxdL+W~?$im+u4310Wd-^sy56FO1X zv>=g(L7e8G<&SB)=ZLQ$Qk)TW11=`}8x_Ka=(W5hXN`rUG1z9@t1_`>b%)`|Y;UA1 z26yEs{o3qvBF!!3Q-=;-K@gMF?hJZHV}Eidf04&-LyF6h;r+aC;*^@lyD_P?g3W82 zG|JPr+~vtl+#Jb-OaXU62ewEcF+p=k`o|!LRl_203uTHs0#R(a#NF$|f`E!oS2DD9QI z)dge`PzK*a{Z0`~42NM?wJ(9J)+i_0r=}}HiNEIwo#K? z$!Q2WcepyWy|caj>wkUqHz$A5pbE}pMxgmkSls)q28Mfx1@}anUg0c4gsUGt6G95I zum9uJh24wZu~oHPV+LZSGLxHXf08>suVqNK;ns@l`>~&DIK2-DKSJ|M z^x~oiY;PBsMQZxa-pcNkuN1m8Mgzj~Z+HK8g{(h}!rvKISm6^RpvYe|sGR4_LYlzw zcpha)sX<6C2>k&XacnG%YKtrQoZW-Q=mI@fQ^)~B6E95IExHE-*3iqCl5`4arRo); zQtX~5Y#DpLNx^G#!Lx@n9t{YeorMlQgjSU5gRX$Y=Puv7d+mpx)m<;>a~OtnyaLrb z&pIT|L1Hs#P7g-6j)~3XU%ps@l=^t(*uxr7))rZbo{N6Hvm}bJs>6N!2JO5UU<6g# zZuuakAeDY6#+=KP&Mg3!RYQn1a|3&5_3K5QK_~~K#CJ)<&gdKs%?lG&%P;puTh~=T z`i)wrt-T;o28HqVI*qW{TA~iGveP7{_AV7~myuwuu_bgHEh^=>wb?VPlWP~wyu5Zk z-Vi?DcqjWHjMvxx$#+)!Rkd^> zwcKGQT;4~c#p0@>-{@c}Ly=1WbjHFMWUb7q_WR{VwccSTN{(uTiiR+Mc;v+CNJG3< zU&gKiXU+vaBOCp-A#2i85c85jlv;^I={wqthP1oA|IHDkH5o_ElLw;H78(1Lzvo$&$iVKSY(%9J%5z|% z3Q-Jf6(nNT@?{+AuYd|(FVCQA#v|I0;}luf)x0N!G-Wf8L4On&4hV|o%}^z0JzB9S zpOH1y_KR2-FvTnw0u2A`(HShNnEozwgbbm*DSB0%ldZ%&)U@hOwV8>;htrrYFwvgf zuBunfI+wEYGXlf3n}N$fp}YgTECE=tI_PpiQQ-d)Z<4Gn*pLcW4jCdqTwiv)#qhDJ zR{*wKTJ#WGz*VSWOU&&;=rXaZyAiUBo&r~PvidjVa~Chd08JkAYsh^IS0~YkL*(t) z^soY+78N=VFOu+?eV}s~OE~6_9?tC`2mH_LySATmZ-tiRUA054kidL^1{sJ8!t6iL8sNdlOW93~lBawmauG?bwHXD*q#srQqm;JA29AEG z?)&I;fvE(2z*u1a7)!F>rHe_+ajPbMfouyGN_YAYcB=PgZ@1 z@VdIJ+Cp453&A=8wNPpfms`+gL>}#+8>l}*kB~mR-(}V~%W?&oY|LF+=#)3#I<{WuIFy7(9?NVpp>{CNa0a5bG-gjHFLO&6WjBXpKO(rKDqfZ>4Im+DqRNAn z8EDH4Q^Va*doq@o9|pG6{575>N@;k)-a;=bdm62P(+ppCiMt?_ozeKPh)VX^C}kmP zL%bKrdG@{Vyjum-AaN>!hq!cJ5vti*xw9n(5kS(A0cY0iGHKi8eGUOl2AsoCn`?NK zydJw-$*X6$8T%+`OKibmlfSx+3Rs97Ui896FN0EB1zPu3`hAJvjXL_?<$&a zVk2<;oolo@3uXnTYad-bbz^<&?#~6vqa2YWPs(b7MZoA2J#U*upJOL1c%sn{YyJO( zpe=w;JoFh}W-_+wFV)!2SsPygudVVASk-&GjHXc3y|yCAZ_6>P*%e^c8=ZE8*;2NI z;*)YsoQhzKLmug27I0sV)kamS}{%>qTaP zIWkZP-T>uj@}gLWQm0NXm+zjAH>>51xb)ejlSf6ofB62T&DVk-ZJht<`0TwC%U>M5 zF!E9mcwhQ=&CkxfGV=1ZC2H)W<7ZYIRdljMpKIi&5n{Jx&aPRsU)FXUG^sKDi`G{N zNEbO`vBe1z2#3oO1={%DTR;Al4LUb1R@H}W)0j=C#-cLR*jSXb<8P4G=@clnt*kL5T=1#VMW9-3)Mq7_FS(7Rz+NIp|1{$l!57 zv4jvaa0b_~oV*L}GF^)*VY+}RptUn2ihC(ES&WM~G_^6kN_p3gqMI3q_y$o6v?gU} zhhmKq{7@l{+a+zhg(_WLdU%CU7Y>NThj@4RPy;f;(tHaAcE%{tvz6gWrC=>qz^eyf zE<(xTkWkdRr%kN10!cp$>SM-(MQULWhvn6xMatrmp8XJ_-U?Ol!g5vMS6H&-R2QxG zwJKPk4N#BM1)XCX3b>&E{rvg!uL3NSgcnSDzw z%G_}iQO9H@wj8kKBsWEwYYS&&sk|Dtv@YvNqevS{vZ64_2q~I6O+oM?4N{Xu8IcMr zG*JYTpc1@5qEbM-XeI>GUhyyNJkR;w8;7-nB#!Uzn@IWG=lpn1s+(QHVfO049i!Xs zSc3xo8eY)1$Xr@u2!O%eRe>&2vhshzgrG(Io)_?*ANMGHYhoPZ1M!yjRu?Fwg|1JT zYi{9GVEGIvfN$P=a`}SiInB@2yLazCd8mfd8^-xkfcwnYPWx1T?C}_D?wgs2YN)la z{;;F1G0#*lxC`qoDq@Ud;N)Y0a!X$BINz8`>2!uv-v3oyn!aTtFLrqn^cN zv=F7&GZMWW`93x%MZKzLytH=Ym<6UQW%*oFlW-Nh&48|2a0QV|*7o$Kd(uWBe*zvG z4UF}fo~AwRed>Xg60FXi=t-xK4OpMasbei;V`JTTbPDUJ1{y!NYOWXyqS}Ro9B}`) z(39LOvVP|?bhK-XNo(|otpeX|72-k zI&|Xj&sT1Iu{VDGT6O8@;lH-)AmcZ`xBm=ks+e82?HmrtQ51SZXzXQ^5hfSU;}L~} zB-k{KjCrT59)!0D;^h^ZRLX;e{n^f+q&HP&F`KQ=P1dWX7ldfh1fadmpj@k_uBTe` z7gn>^43)Be64d=>5z4D@UPx!^4vt%gTF0nMPvnw+eulK@7}_|#OeVveErDT$k?Z=r z)xb2t>UhFhiA%n1IiVudHIOC+&3=wq%y0Of7eWTRJRXnf_>T@`wBxFBcAUE0ud{ix zn@3j|>#0xv@QXN#?{N*}%$meLxrc@8yQNJT~rd1zM=VT>0{B6%$2X_?Xm zYns_)gYmY_h{6Un2aOOoI3Lk4Hju_;LU|meGh2Sx ze+){qiF2QEQIHTCr2E!`ZM)M6LLZnhx@j1csfYEQ)py{tvX|5eq%7*izQ zLHAw&e<$Qcz&p;t3F8waFQzEqg~9BFr@%GwO{?5NHFWjn|J-oVb z=g^63k2&i>KJI_@)%s&CtM+N^Sxyto4`|euk)t2NDKF*Q$d>0+ zqt2daY0IMn2?=5C!)j?g`&QjJ;N!j#w0!hmS}7Bw8dO%kM(H+L(6-;!Xd&0(nM7+L zw0sSCgqCj(_E60>QQA`DYD_u8Js6-(vr7zBL1U{P>QSuOb5qAF5bV z9VZ|q+2G2Ffi{Nqaa=+zX~&0ZT3l7Gi6*UJ+ApBoImAj}?uofY99Nixn^g_P&$$Y0 z86j44nB5mbEp>d?-uK!+=#0xfU7B2;?L>h3%Fn7@U8UKwv@ninLWcb z4qHO25-}I2OURHsBiLv=&dq+}E?&P_OfPNQaTbJ}85mw%sW$9sx_UOdv*$1Euk6`> zu5(_%exrKo%GFGDCB}hDul%%Yk}?*7PznxyU6%I-hD@0SSsf8{kR>ue?Oi!}B!oURGnX6s^?TmE*tKGuBd z874TJ6m++4?=#2sufyFEJ}w%8YXD*}N5;8`6Fc77$TmHVUWL+`!cs-8-l|hI?}1)( z$YIy8R9BhMGEU%e&|IhP01ZI$zwfA81#MjgxLys<1(lXUo&dOUOr} z%ZSXupMUlp$x>u#8UGDheps5g7`0d))ExN->5LW}gos%|Wi?pMY7N1psKrb!g0etf z0%lKIzofNCS{x-SN+{VvmKNZ*g4)Alp(dIVQiIPh$^h!PQ$z4$(d!Vgu+l;ymN1R& zK^orG{#>d}#)X3{(1s{g&nP}qXla(bEj55~ggt}55xwD267*v{3Yh$?R!w2K)r^9v zIfTR;c(JmZ=4jEo%kn4<856E7oI*)7%ckT|1Bsx~vq6wF;RTYlP{+a^>B1=en+pn%ba zL=P;jxPlnQA5Gqb_$ z42BscI+B*M|4#w$*tfh3tYb+Pg=SfZo7DM)sGO?VP`oi3OJH)aY?xyXRP^3Z9ODgC zFWW4Nu8DMnUsTKna?$lmV+-ikd4zA1v06OdK6_;L%-MtAdHKgTreAZ14?F$)ZU|nF z9LT1(_jY~%w}5I6oyfHiZ9qavjN3)#7};oyF2=B5I97|~4b7`%NIY4|A?tkQ)Q7{> zVdvB7x4YiJj?+#3*RS_9y&jpllx|2L-L-4`@JZ3qvDmV6ZT7vlyWZ_YHo5&qaR2Vb z*?4>&!EDre>ySgy;)AR*)5(d9)aTGDjUQG{ma4Utq4Ea`gDSsbgJ4c)e(6(O+RAt==DXQlMC$XVnd|KFtgPQB6_{W(FV5ks_n_kH zy*PR&{=G*+Z$IGW1U2dWl=JzEFUJ?wHkSirL)vAdIV{kMPM0~X& zq7iC_mj$u#oCvA~lU5#Eqng=dbuUY!8O;?YG29GyM^g}t{4O=C$kREp2sTmFwMe0k znnEXSa0*7|Fk=9pmeQG}TRb^SqhRqE(Oz0=QIeIl+ZLt;ag7x;y*>b%uT_O`qhxYI z1t#v?z#I8+mTX&mu+ZQ!Z;lCQWR*)`DYMh$IRgkmOTQEK<=FrLAOJ~3K~&cevM`+@ zT^>pBL!tJa11{M(grm$^UOE>=SP3n-Qilx_Q?940?qdMqy0uL}iUGhTF$E?wd zA0Yk95xg&WLANmQ%#jT0je**vR4lNzww53H`pdun6O)NHyK{lwg;h4_uConz^>6s{ zrv-tqu7!8=IFT#L_q>pp+IM2Yj2c{cy4Dy*w7Z3d9N~_4x^LfJ8yOP-Ur;M7^c&+` zpTB$J+QRxBF1mB*ciT7wg0q!Qp8M{TM>>6J!^5s|o!;0`>*);*PHzO@01dX%@T!HT zSIBs$;JfLyC81Rqt5ZCzMjaIjX3n6gjV=UQ`;0h7 zt(LlG4VnaTpd%*>a=(WF&NP9sJ;?4t|u%{J3M*t?j*7yEi&Gle_Qbm&@7I^esRB+xWH> zysL^ij5&+>#=zrT3Ps>fIm>daTCJd?mCOfFDVLE8E^yM5TN^_b8@Y3OU2{@mdg<+V zPHQ$cDn)8;dLftk8x>UYZ@rKl>suH%o)TVD?FNm^GqkUymZOyge1FP&yAFFXVbydX zAE_5M3d5QNGtsYCH@afIG!TqS=@l=ixZi7#Y#EVkF=|#V8X{s^DYgJxLR7sWSUsc- zu2M2IL6$+(0US&Xvoi)`^OBOcl^8B_!5IXpjd)df(N|h4uX*&0cpl@-uyB^pxSlK~ z<;6*HgJc+*3fSy2&!DlDsWF;tC6gNZmC`8gAc5`}bv~lKMd=udX?t z7Uix?A%yoNH7;~-8>*tm)E5i$7~ucRV(2c>z=d8>w}V2}L6N$+OA@R4?E{nfT;Gu1 z`ttew;K$Rf!5SWB7<%a+yH{LTK(~!FDPVRS?bG?cFv9|cA%VMT2)%Rp2Xnw3Tb3Pa zRJOb_xy$JY>?wk|MnwkLGi~d#$Oz$SqxmW><`)vmg=#_MAtwpuaz;QOIB<&XO{x0( zhtB+H`9O9yF`06f`p>SV>aAy%H@A3)KH5B0pDA`+pSg3br|*tab314DrVTGw>0+5m z)pB&7a?_0Vra3TzLwzBnt1>~UlBR_;oG;uemYc2*9iP0@X;l4W5UZOlr;bldpFGlk z`m;}F{&GBAa@~*OyJvTN-MevHx32Pc(NocEif z=*QsTG$RFc2Qln5s=iVw6flvnR$!%8AZ62 z2&i&}VkHp$ErHoYK=wkzcMOn*tD@1WsiM=UoIqU%vvQd?gSbKx7Q(hg<;igAn=v5>8gb9(dMe;^)s^9F?OM0 zB=Nb!YuZstK!FGh-fAI`)&awd5^>X3h1rBM$vn=`2_qp2Eh(l=F-BJtoTo?W$(EW{ zrgL%Jd2~D>=*zq^Rj8z#8K!0361Fv}+(_Ro$;`Y&l}S0)7t2WcnAk8TMWDv0R9l%t zW^Q#p#>Qd}R}lQ^WyJ(80ZMeXNV0KvUb5P(jD|92&Q{Bf6G%PBc#@2GQi+I#b7X5~ zUINS$8Wm0?O121WWvLWajR{lN^ zKPv4G;?L6uFWIe20_zs|Bfr(MWAUo(W8!V`#U40tw8QaZ*of|t^27D@^(!#qkhu>s z2$-hO40sFrZ}o2ar&Kr_B;V@Y|971|{Bq;y!Pc9S7k>8qyC;tyzvMl*PCqxd^Um_RrhxgY zpnlN%PMpB>1v{rux{qjGX@0O#S9Ql=pHx31=A7^A6ZQ@%YHiLppBFd_g!6-WNeKTU zOJB(o90c5!zQ5z`sXAJXMw|%1SCqe;Mz~LgBJmM)FswLkkN!{}aL1ARE|ea|B^ao5 z(E>T0EwK2AIEFJ;u3U5A*MXX;y;9|j5VY7ur^}oRYz|=PQ$X+1^wRI&_~6Z{de(LC zPZ+HmAD=sUwCAl0sq4S=mI`+-Z(IFM$L7vUr?SrUxt>|qT^k);t~uqJk-qm%Z>uA( zjKPR7mohq(y+(yJT8@ndMd246sR}Myfauu;kE)cDb<>rxbUh#3V9Qv0J4`W?NJNALT-Itb*jUk>@LKzCP}SQ7W>j)JHR$p4K?| zex!JP{YM@Z@Mv5#RDtFDepIjP=_|I@NCd9u`<5MA0~JP@)lgHYR@yampYPiUtQX}+ z6~}UXMN6o`RbRu)K_rv42Fi=V$@aI`fV72WV3BM=X~_h63N#AO{jhPY&_0R|X^z6& zttEdXf-NxvIgvfGA3;9!nx2jLYPGZH*(JzDitHKac|yIG(1nD0B2SiLqXQ9ZeFbk6 zs<+Vs-(IVjyRR`SYd}(*5bOU$F-glN$ijK;i-Cqin3btkDFsSKO{hX^?Q^9pP1uea z?UoTvqKzpzPn)b*QCucu&}~emuEKlLd#)BSaC_(g>o>BRktf2CKc5grda>OS*k+(eqC20+z(F*)07Y zkSif)WP$rEfa=zVdLSc$uptp^K8ITCxxncqQ>;J2O_ur+db84(&;AX%ELyf(t^{t@-sSF(F zIP!0y3PQs!D{a(jnWoQ2chAM+9UZ}zx?4ZebLPF?GcCKVgcRJsSf3VldI*w7mlezTj<_wisTpu@-#o{jgE zuJTzlZdKtRR!&thzQSy>wEgwdp6^Em#UyGFMogAaupdd;P=lSSFGDNxJk6il8ec2s zM84V(uU0-$zX?Xe2IRs9b;Aau6eNMy#74g%A{Ci|-6haJL6c0i!P}q#J-mg$v%3TW z!9aQUidMx-VW4<54+1Z+s|o~offq?ri}MJ$0Z%74OLax6EQOU-o)A62R*kTBv)J~% zp6C+be{5avZ&TM9MioWX8Y(Z1s!+R%U14dJ+c^<6myFtOOhHb$p@oQ`YiyiJ^Stl#KCiEg+&!cpO%Qi7bPa@?Y!vi;{isby#+%BR+kt6)D!-{y z^|PCj8V2>q;Z*WtHv)i`WOW&v?go@dx>Iz#!Vzf?L77!jxTqJ`XtLl_;3)=E>dews z9xC>UL~bDP7P?Cj+&maMcQedO)aH7C#l`}u>>7bd*kil9W4bhe6IDzj)s?t}fjNHK zP9VU#B95?lQuNYv)r?EMEdiafDv?47qH7pDDWyV5ZF&$8z(w+$&T9+b|WB*nqE)FgQ|>TP#icAZwBYJ8(vVwp5O@iaph33 z#R71j7(f<70RE2vFv77~eS{9VU3Bco94;m6|wf;VUj)z^vBB8%)uwVgr=}Z?w&~%$-!gz(5=ZT4n z6BF(J4|tuOeDA%7bL&PNV6D24-^Ob1|ZKupQJu|VQou)u&J~7$Yp?!9X)Yw!8QJsK(nQ`>A@Ni znEj9j`(6D}Ev+sby^biWC)RF}R59*61pEcUTBrrb9U3AyBianuwV->-4h`WwN4M^J z6J@|y)6-G8b&)jv|pwE=j9rdOj1!QxN}2Q2Zz>hE1_KA87yZyi0>^Ym?a zHVd=>N8$5WPQjyjJKNh9#tZE93tvXN)hK`sLKihn(H1;15>kCrNR;cjaw4Bkd|K*> zfA{sQIeC1lIkuR1X7S+I)Izp8_u1yLeUI!sx9`;hn|mHljpwEdbCn&l)5kBAp1g!a za;Ep#o~yCp5X+A<8MJ-CDgk=xGIY}D!FxP|#)sFCw@suzJCVI^ zNpd;A{btZ(vM(L^bbC2*>$%4-l`|ht{r;&`=KYzOoyQCB+dI_D4f|j<1mE!(6pLM> z+N=SyN*H!!$~DH7%d`eVmkG$d%MDaU7gB7y2yI#_Q$tif1*2&6g#dJ02(K?%0QN&W z30427rdIy=Hl2)DGls_TD}iGXMmZpmIBC-bIR*dxD1kK5@U4krO&G>i(ug~SN1HYQ zd;pw$zhj{J;BI$*C$9R6jcrs6XQh}b=w^HcMK^Wdof6^~kGHhgnD&K?G2wy$^ili3O?@4->zrwDKsU0{Cq4 zJi$uwdUAeGv9`+-%`K8Ng#z%MPDq%cbI(F(*;*CPuFipN9? zMt-Y}gv4Hou8o?UwJ*eRQB_-w@v1I5oYcbFm@X;eNr7fb>!P+;$S`xsfy4mI`huI);Bg*@6XHYS0B#L-?*`H zS^Sy>iiyM%#M%i_NVh^O=e1VInQ`Pq>n^eTtFCRs;{Jg)NcgM=LO%DeAQoW1ySlpLR(yvRNbmoKke-TgWM_#O&?*PeJbY3cCS{JOVi z*SGI1v%@inJ@A%#Gf4uY4?_`62)AKl7@_IDzR}TvZT(Z59x&ig6h3yWIW=38Mo7%? zLXIVJtF&{39vNY)q_lG2vY14(3b;3o{P5sg7Gj6?i{Kfc3IrZv{F$s*c7g&6^x_L) z>HR+$I(2I6_h-=S2%V2Cx&8Ch3!8uB?LTzx@Mv#agf+|;@Ymrmf24aCvTyu< z^2^bl=dKqrHH$RUXnvFvw+-=iLN8#bkkKu$k%8^TIGglAY*a%LZ@s}zMWm$DXn2(2 ziMhn5*@L&9dHb~;r!W1k^xE6wxu+i4@z^KLgEwzJdg$QuJ5M&R9{6U@bF)(yZZ>vS zvoB6PJXZSYc3fsWGq-o|?E-?&78q0IdO-{>3aRNvBM(V5EGScWdu>{*G3=56&^KNK za86%KBxS1+blYISWTle0%o`-SB%nZ9duon~hP814swS<=k_%xmvKwrpZ26Ocq zy}FR!pp?M^Wwv?F_GRlvf6a9 zUPo8k+1IGXSCvKz+71W#$GaK9x~5*sZ_9}MtWzaLnV#{Z@#dx<;d4Uc1P*l;in9um z;X&CpQX0pEvmviFnmaX0WQ~d9dj!XPQ&M7VnvtCfZ^jSr5Z)k)?ncS1uRBck0aBb* z_%%(_0qh}BHj(v$QKD^{k<067DROt;JP_*6hWOsO$Z#_<8f;)HJ>2i>Cu)pQoNvna zCTEJla#gjSh-qe$m8@`-0>paay(AiAfgj1rQsdh#2u>{YVh*`^DJfox3sMuUv8N(& zSZxQy1%T?A1F~cZ7RM!C%ca3-N|h=5^+<|^XePxG+0*LXm`I={MJ!q3n0jgiv6zCk z%u^U{L^CBIDY9i*iG)5Er?u{uPas$LNIwPA;24)Df!JJO4PYTM8HkF??shf1dOWhZ zn2=WyEXJ&v%Z+J$5p-37u;IWdvA81?VpRaX)oP_`Poorz6uFZ8VCOdU8$^aT1YlZG zE_YcnXrTvbU`As}g9pmJ=k4pAe|)jFZYl8U>bwKtD_7>PU}JUFA~AK*t(L~89S$?( ztibD7@LlKbe7E)0FjzKHvTXlQ&M%$Wwk!a=qKzLW&YtB}XumZ9?kk?t7s-I7-QeV; z^cCuSEVt(z8EvvT3Vut{+5$Y|ODwAgfr{%X+G4G-p@5RxmAX36n_;*$Oj z5sQbohr<|s*|OkMLwxQ3)`8I?QoEyU^xL0#<FX~y7Z$eu^5yughxRQVfAx)? z9WM=?duDFy8>OBf?AZKqhS$!&IQGyCTs3l*U{8xA4CY#8bV;)KJ}CYEXxZFAe3$`Y zX(Gt3y@}k;4^GZZqkmzlo_S?v?#-MOH=}7nLtvGc#B8y|5LaiqX0nL{CNYg#W3(VF z%Z&<9W=+=#vnc#c!9ug%pc_d!MaekbNuYEwON{)`JC z8^;E-kzlmmGs1ldZpL&FNZo;BO1zvY8Rer<{49mHH%f^KTP6%-n-CIpM+kk{kN}4_ zEa?O^5UsCL1mQ~^({rm2zx~j{#7j}kk1&6oT^Kia1l|wfwsR2?-b!QSn-H0eu|m}o zXbsri?orQ$nUx2|r5CM~8!5$$J9i1@N0Z`)A?Ao)H{gWIu8)*cCP87zVR1GJiaY>i z5E>!3>t4eUt^m4dm6*+CZ~AyV8H*Yr3wtFQ<#6D2OA1yM(4Ja!uw)0>T%EtxF9k_u z|IY9cfpcZcw0MlXJO`p)o7H+jOpmD&XHn)W#|o1bjg{2t5~?NO93agr_?isdO+b1> zz?E&DTm`!Frw8#B{vEOV4^R2=~$ps{??M1Ew~sC=zLOYv}7k8Pa)? z^n8Bp(jRYs`KPOE8yoil!ygide~teHidV^rS3(1gyT55~g9EQ&NJuc=v@8SeVxZen zZWuC`x1U)WSvs?{wmJ{_l{kK^Fbf>2xI|ygcEA&8w(#C%X$Ne#Z`l7PFT4J~D{E`( z>wjTO#PyZ6XZJk0zMRH`q3#HFla}W~a8;Cb22$Q#qeY~Ku{0U&qdz5#IMe~U6QzzG z+c&#_(qD--izQ|GzieIaYg^|T&4(1W)GK#wDGt_ZX^Tcvm0p`7Yg!W-Uu5^%mMM-< z%rz1sY8}?Q+Ual-{AJjo!7eEI;Ege`9Yfq0=EMXWT(%`?yf`C2po~Jt0%Ki1gzoRy zd(QK|@4a$k66s31y7x*3pZA>SJm>KlvmuVGN_!bL=!%(`l-6h*1y-j0Ukm|vfv|*O zlHef{UInxLeN)t%MRi8~m-mEdVDVcYv%ZVy=iaVzesOE9r@f*GajhP;AxY$hU@p@r zIT5MM8$j^t!0CO+8{dBQ_jl0f3w)DNMA*m{&_R??oG(k|cLM3ha6|hwOeCmtJ}=BT$QZO4u~ zX-k>WZK<`ySSo!_3odEf?j-frQe3em!Lk(2P(;nlN`h9F8$Sn=4aeQb7X>CJEua__ z2`y9+B>`TB?|LHch6Z&*qXt{R4ntcJwl4sIHITY)3tU@B6@>L%fogq#QWz(|p5Dn| zeza=vEO3WL9Cstc4vj=z(w8R$J~W>>PI$F$%@dcxh~kH_GPh^X6IuX|eLl085CNcM zepLr7pVcYE67UpJJ%KJ0EaBKkIo*7tU~W7xO*e)R>L>|Th()0VCj=1=w9Qw@vDTus zi@HOL;4;@IN8?jcPa;Tavs0iuWw{DqAz4e=qMj!WJ|?a0*~rvRhjDM^4AYd2AQH*d zYvYbhf&>h+IVjf=bp`3evPf%WWtywxYal&6uf0@MxFI0tOeI&48E7d{Rw(0+bH|(` z5GyQ~_GV&rutM3HHQr#n%0q(rLYoE*SMmBdUUQ&KpI_+d?A~qT5Q0_!e$ZX+?qvvv zwkRad@mKWl#!7cQ6o`>&_pee?C#4<9~`5#k%`S8rUsy1xFoBF6WhEu)cFA>Vb0 zw31Y-hXTY3ejkzuKY7YTuHHdrPIq@=9N~k(`I)a20Aq^MZ#j4g)n0nGICn{Y_7wi^ z&0W6yx67cwGH!5LCKB$=5`^cFLcO;)H;XFr^7TKxd+Kg`r__2`=Iy2QjC${3Bw(Qu z+{=7Q8qnHcj_&Opxe~dcPun0Yg4F2dj_>EiPNlt76$WmkQ40pdDu6@aGe#v5lYP+R zbR}O)w@W}}<+UMV?y$z$;eL&_cm$*!HmEx!IE;Uq0QU|3x`*;JWazGu_B*FeIL;pz zmPSVMu^Mn!IgLq39>-+ zs2(!@8KVajEVE&$&Z$F^iQxk{;SyFz)|BD&*@=z%jyrYx$l^=kp-p#sZ6eb=exW#U z>y_e}4~ABMIJz)AbZha=19!KUdX6?0tHmojQ>6=VeKitmZ@aI(&xw8je7KGilCz8{ z5Lr%1$TYJBmS7W7xvouQkb>nW&?(_q;cNf^AOJ~3K~#+0QHq9xjJR1($oRr+og_Gg z;N}#PBIV5pre<{)hO$fr?YpGI>KOGph7L1K6Sk~u1|gVD16yc~UZPna5OzH;CVtE5 zbP3rOpi9y3$SgY|Jl1-_0cxflQpFTrDehy(R9}sltFSK@h(F1=b{%OOc5<=4R*rTM z7q3kz?yzHgG*;#;nt>7m_yX+@h8Y=Pk~5`WQeXjcZIUvP$qrprj@5+)Q%%XW0}!Wy zllpm5G-!P&BVWrA0@1)VW6f2CD?8>JaRhP$QyOMyq%lzCOvSwD^ma8PWf&8e4iuF2Ufm0oG2*~O!D^=jT;Bj(c5!4nPv8@vH zzcC33uB$c%Q?wzBLjhxVz6=GL*n2hx#b?jnD{p-JpMQMw&#!>Q&+fPI;q~>E&qSPl ztU&Y;@%NFT#ZRtlGuBfiE+cLWfmnxo^FJB9*VYXHUMKXz_B_YR?{$s6Uw&ybFV)@U zSxC^By)>(~X6FRDU|?TiA_bbd>6R8Q9&}IMyjbjC#4$JBzO^$0FTK8U>r(iG{_{&8{ruIp zjv%dKX{@+<U_!3tSe$8oJSwP-*aF^+)ixOwPBU021Q<;l1(9L9}JB`vg; z;#Q=%?MawrD=Tb4S>AY2B{gorl08aVgLPx_vD+fl0wN8X#@-pWsJ})-_N<;8hE{C0 zyw-K&1e4eq5z&&Cgk1~KVQ6o>I4m0~YC%wc1kdB1aw%Ty^aA2uM2Cf$V{b2vqrM2! zvh9TtJCEIy+uLj8UY=QEc%E5q#02ozBF2l3fqPG@1s3Toi0kk8fD^L_>9*9I?eqaE zUF#rXXsuPcXXt#s#`axMIE{x%)00D>>agvv4vo%9c|NHjENN=M3WGXCo0SX(2BfVQHxxj>Lsy*fq-8q8N*R#2KX zZ4QX7;K5?KQasl@gKMa+s0U+e3-#aXnA*Z!b^PTkizv8)adz*k0e4e_#=zWirvji( zx~1_{=b-wTnc3alRW~y;^Ya49!imq$Ke+ec+wX|PkDfgy5U;Edg>R4#e}3cYjo;mW zhC=Zk5m@~rC4Ta>6Z3!>f&m>mpBmil+MSQeli>LiFXVp8l}>WP?)}dwZFF1(lt1fH8J~#cxQ{ZG4O&!FYNw zedSza!a8kk2~SfOcF1@sDEsL6g#)?cK?_d zn(46u(rSzI)U@Wo25qOO`G9*&>sN+<#$gO_LYI5Hwhn%>w)NKwtGByG{DKAGPS$

X_suugRzAK*EZm_xw+(3{;Mlu%_iQ{k~1%y5a@>2XQOkir@ z@dAinA*JvcG=ZF#O}C&8h123q9|D z5Wai7kxFIOK6~e8;?C&FRdwnQS4-Y6j~#r2D*{e&Age^UB}%vo?MTW43rXAD*< zbKEa9)tj4Y!J!y>vj*W^9hnOeECu`q%gHIljuU=uLZ(L)I0dR%=P1L~L&*U*vKob^ zJ{lvlQOQ(`#UfpXrTyKlw%Qtot@YBl2dQNDuvQ=vxrpW(8992lh`IaaWnr!Iju!0F zknFi`j2xORBPT~yVhd27I-chW4r*ZY zRHX6Z0ahqY(K0C&PdK0g1}%2z{#j;CY92@bFr-??R$fiH7CNf-8$~5rVTDO)6N(_J zL)Uz9(yExHM4U#Bqt-l=U-=Fs<$E@DBB%gc|rH{|^^?JUZudQLuq73`$6+v36Y8}1RUPAchG<~ho zt&=Lnty!Ty15VN-jRxh3-JA_|)COp-3^PCl?)nHhGcXihDzG70D#|3FxfzV!Y`hka z9+bqbuLp{lyFT1jBy>}O9`E%7*1tutYLwN^kwHp`x5c%yhG2~)ZtaT3c3v!zn3w3>_&h*wwF=ua;~Vq)>y z?BL(fVfZ{88G-gt<;OR*9sVI{NK`g5hy>e}1$ z_a0rAAZYEU*1=m?xpYYc@cTCqK7En{wtg=XSd$pSmzNJqP5LH(brXva9}J*uQCsGH zPoi|kC3rG9UdrmpB$bc1o5^BM+vbp=`jw+l(kz-6(^Q%K!z^bVaavAVNs&l?Lw-f}^*p#S>k zmD%zb>DofM?(`xhXo=pCI4s=@M*kPTCMPC_`_{F7M~qlowy!kO>Ar+M!qkL-N%*YN zd8a>UI?fDYv52^NmxG`xXaz%)=26ncwgoTGxmh4LAr0Q*#8CY@6MtsusB^V*=&I|s z`adhax?_c2&+|vG?>RL0%Kn8Hi@(@EwXpcpMF4o=J3F5`>g3OFe(SAbacAe;OcO{4 zGt-GilWWbG@8NNvW`kD~qUhaf&3N!!(|3bLnpZVQptZXVc+O+ZF$8j&Hyt-YQA{$C zu5Egd@Lq)t?S$O|T^W}2HRt@~HoEGNtxsqjH~Ss}LHH4^It zSZAE)7%Z?I@5=D;)PZpLwY_g-SjA|heItEK@jBa%p-k?KmW@Lp8*QD28qA%gm}B0hPH$nP<@| zG;$v1QG(mH$Xxq$3}2=6@ieVfCOlt*Z$`U{Tq&5R)Yky|dCl3|H%VTD((kc(aS<<8 z+m`25Tfgh3%pTR>ILHQHj{r+0Hf{x^FqL6>A;sP-G4R%Wokn3KvbOqyDw~OMTgCNc zfSn8dN&#nYh=k@i4Jbhrw`+ccX(iXor%x3*RoIkK0yrDq51xu{ux1 zXX%jLAC1Bk9>Tn zk_;vh{0`=TWz<&`@K;6w-{#dout6tFSzcLK8qb!-*)xqrNwPGslq3w7#!E3B@CR6LGY_MtAuw%QGR?!b}<+y zHRov&d$H@`eG`0niT%(gNf?tHKJo6mCwTqRP3U1r;G2k^zKbO4GrWN5!L(SOF#w$` zNgfuz3q1bJ{;OC_lDW!Uh0YdGg8s3!KU+i{K5}UI32#)8Hn2u2#*Fm(g|V^8Nho3t zpkz)%{jwRFB{EUldtsN9oV(ioEavA9Yu>H_Fn#KDLmAv<9HSWht3@Izonir6cI5|4 zmC0Go+^9rc(6eO>AWh6lw-~X|6S9|ZRs)#Fkc`9IG`jV|i6h1BE8tAO<<|R&hTC8< z386>~Bz1@$sv`qAX?K7QD!0?melU+%Trj+Tbo;&alGYt z`<#2esye3x0CwyLs91e*V1!2cO-(>D;nA{|ZXIQg5W#Q`te!NUW|)1-dnGS%AAWinorm;o5vm)q z!w}74GN)y(5HhMg z@|q%-8hCa3Oy#9XwL84n2%lTtPG#PmNbOzssWXk8nk|8lw>e{C4n*3@G5O7q z@gbd^p#wDZV+FlAbas8|_7Y=B%la&GiO(`pRISzG2kEX=_E`B<)SF4~LN(X43A$zq z&-ey(CI-jPEnwFVLC2V|zWwjFqJUvY=AUy^WfBG@LL)2ULQFfQ#6JxXBf^S63@IHm z_37R^N!+`=_OEX~{}P(`j{;&6#B9_;v-s9$Jdey8I2kL9*VC)3*|quJ-~V#)3_d(G$`F z9%Ba61GsNYZ1%p(zN=l`ylh56~k56&BWPv-p=QnL! z*@34lmz%Z(on^^eC_u| zNH?MA8d&t}^yz+Sm&B>(HuJ4!pLh4UeKbj-M-yyXuDj^D4(GbpAQID48(;ot@q?*X z+Iy}h7IJUR4HL(TW7uxSak=02gm&bBDg$9)7yqesjYX`pvN%!F=ky7lQ+rOpc?%NUF< zCrfm3cE2}1(JJ)H^Yi!bNB=#~kL|}aQY)R8C4^YVK#2F4@D7he!vaocMb`lhRKEua zukIrFD$g_0aH#Ph(!h0wkNI=a0a1fN6$;jf7`5i%wzc6JvMJkGRT&kLyAe1<_#IJW zrXw0@sH&05a>lA>Wp!#uJB#bg2z4#wjLI}bi{h4^s%Q_`&L~sZwM>kX*79~ZT&~J!^4>83@-qb;T_*vWQZ$sL_ufBXmdxt5C{=n)M!`s%~eGW^NcN?^Th-B zt%~hvXyu=#js@4Ze)Lrc9|fGz+ETR+w^eHV9eBEKP-B74g&s(*jMI z;T^MrPbOe<;Ti!gHKp2{8*RNBr*ZgG+0F;1zZ3T(rCePr*4z2y%OEs7)dCZ8v6cJN zGR(tk4*VbtodU`=jsxG=tOB`)NJS=(=zhK=U5&(91%l)p0WyGimFtoqe3^kDzE+hd z5b+*xeg;mp#yJ}BRIv_*w5{>2uv`Ub_r{61nDoVOqHz_sRDpSb7C%NEx{3-kI80hN zIEaFD>fAz%9nK}QjNw0j&;TCC3@kB~{vX79`QX$laBKzXUIaA4n1wY4S-rFY#p5J2 za+bTqrDT#Jj5hH)60fe^{^sH5Uw(1#9)_6CUgq-jt!rWiLpv7uoBn5PZF03Ye(%vm zmcIns2bZG6mEh?=JqQ6D*+vY<)(ty>{2Q@QLkORd=;;TyIeCMZ5GD)by!9BBXxN`o zi7sF)iPV0XP0}37F?;Ix|Lc$*<|xW5*oK4@EU`iJ=n-O`xd=TyJy|C1lF+Tl2yjJP zrYFptus7|#u~(qG*YLL6!Mu^MSo*-7u5eh7AdxcebWnxvzWMr5p6lfugR^6&pLq7A z*M2!XR-UZqZ4d{ri#15I69p2%W84Lv74-`(JO%(8_8zfU85+pyrIkGK1`BXGbpxy; z2&cVDg6V=uAD6e=a-W#JMQ(GD$m51YBk$xJB77SIDMSwvPIIYvV9_OT^_@?4Z~5V= zpX^q@d(JtwX+!5)B7J)9qviaz_cnj{*z^A*>-t{Y%Ij#cxKF9%q2h!|$pj}z$wMY+ zHWZnJUNdW=PD>NA;oeEe8a4$(cXXYR4GUd%K&Ha1U>6Zwy0g2ZMY@%;i2LB~4xufS z78^zod{FU45Ty7&_&MkE{S|GeGr76<=H6tW=X=iQe9q_VdpEBgeR5t9bQKv~#RJY; zK+q#(=8>?_5oQ68)+@t`4g-`;+!t-j!ZBCTAeDtf3OzuSpcxXG&0t%Ekd$ulTlG)9_>WxJ(Pg zHs-QF7o}Ug`5x8#MCr12BJ~pvROqSuIiUqB(GM!tl5d)17qnQB76?tI+>Wsc%%!pKY#{_h(O^+KE%_nGZe!=Szw*6J9jzeHT3>s0?{s`-W96Q3 z@_aZCm~FqD$xufumi%3!Bn>89FC3QK(qij>Xs~RZ{qDz=tma**MX5%M(N3~k^ z@N3_Hb(lT6C%bCrFWp>y`Q>%N?P5)kOwNRyyw03SboU%&4^U~Y!EKyH%vCWv9t+0i z*(`-=!Ik_-(=&>e^;RGp7n_3tTyh0jl5|csPdX>}Pcrk?bUr_sYmIlF63UCO{mo8m zT88akp0r-W-QB@8jo>KeyJ&Al`qu#*RbyFeVAcZa&jR;|uavtR7Mr#4h{8Sm)I->$ z$I#;|#cp=>@bl?c!WP)56qaj^mg{xNQWQ$XQRFzQS3^sS_8$)>6JK(bmuZ;);DfSe zG+D&U$bm_~W(})sgi>-qYVAE3V2do{^t>~2d@__@^(qFi^%53a8y5J@r6aw(L+Z%r z!zwTPg#u4)_)V`!^UmzMDcPfVuDg=GhMrh*0PP8OBVgyYoNV4%$%3%EivJwU9pX3H zPzhmDYM2#4De~8u7=mqnho_7y*cy=7@3OMIFzUT;B|ET;+s zM$HoqN2~$=^>_b%?V0HVW;C;o2ZSUHN}I~nb2_m;MXMCTD$B4Fw~$r=VVd+6m0})% zS%xi+dcYGxi~+^7eKk*qNIbj$kIQQ~SM}$X0N_$>cE2;*Pd$C|5Du<~Z$Cutv?hBT zlMwshX>MpRhek}}5DsoQMs}qIU*>RW2W;k#l^E24P{p zxpF4g!7wCQRjl3k(N@?69K=@a9Db&y-mXp`ya1?enieCJgqJ{p2VIT}?!y0!KBcZD z$|xDHe%aWYcT`&D)|DMrfK_}}D3(8XZhM>mE&_iAk$-p&`ZMS+@~t|9n;(7lwB9qwKvG+eZgulx!={?>+ac=iWW4 zH7moP-8^3dO3}Yn1mcgGeOXh@8LYNh84aN^W2Dl!+te5g7MmHsQ9+L|Y}w-h+o9Op zTN_~_LVm1s0xzu9>rgxjos*Nf{R4#EpVv z;cAXi>upxl7mhMHooW!ki+4D-n1GEOO4*4S#qv4fgv)!UdoN6)pi;YFy*1je<6@=2 z_B)9jCtTpQmK_GHv*gQ*k)yMdMZ67orxQdCO^%{K^({3VueEg3bHho%{u)szHHT_$ z!-10HyzWuMp|O1;I5pCkN}Hm+*9lOuXe@PzY2E5A;R=P9l(yCQGmx{kwVs`kKY4CGwahzz-* zWoo=^6pCH@uc6l~x7g2XnvtD$?ouwyTEhT*qREd+Wm#s`8z)%Ot&Gp7m!^8Gfy}Wv zn>|74TMWq{j)KG{#9D$fn~3^2xv#I@?sJ&09Mxv!HdYC`f6Fu@3B&EFRGn1u5Q7E{ z-~xxicF&+WxSu{l;kg&%s2*C7(2cZw<9WtWWRw9vd++`CU;EFqXJo+4p-}A^4_Y~e zV&G|+Q-WCk&1AG}+M*E)4r!no!5Y8}nHtm>I(8X!Sq>5upUtN9YlZT3Da3!#9NiqX`N58{qSq9LE87Tok2azJW=2`|!6*1v3W;qkg+)GBAG(;EJx- zIVM;WD3{P7EU+sKj6mEKGMxXSE$qq<0apXJl$p1;mHqPj#Vdedda=lWvGZHsxYj`m z7WpsJD4|5JZ5FzGs>SC2k@ z=N#x`9*w+Ar^*Vz7xRNW4aI_*wWe_vbM#-4gB@x}bSw_?7>b~@m%GQD$~(&5DGss& z%uJ$L`T+9~gdYnlUP=L74eZWY;B{N`I(YBy+&l@@X8&Zqt7}HPaGX}o!Qy3eHsRwM z3aDZ@p&%>^<)a$&!Q^h3ztzl+hIx`-Bx~_T8@JU&F(aU~*52d#XrrKn z>Nu6Jn?{!Jni6CPu1dOP%kAm_03ZNKL_t(6&@G^@BXZtStnlfd@Bkcn_*eiyBFO@l zP8rx_BU zSqBw)V$ydO=eQcDoukUYuThe9V1W&mB3>p*;*D5+b#k-Fsx~U^#_eg=2B_;Y(=d4N z{R9S~5I-$C(R5)RaaGYpnBw#Z+(^uq91H0Qio|yPyl{W{t#_ER(Gpq<0RH*wZ+!EO*MIp; z09fz`@f0acBS20^ro}+03^S9M%9H$-*4oY_QK8!M4aM~IP$e@0Id z-aiAea%(rfwB@rXw|oV7>*~eB-&^IGPH3iGHFf4up$l!gfCvu2Z&STk*j>-+5#= zp@OzpJPsx3ReC}1GBp^}N{k|`2_tSd+r8Qcb2S$6ARM~fmo9(%?7bF4=ApSF=1_(O zqFZjaG+hB>t`^}Ce9%B`8dI>{4h*6bmVjIIgcJ)3rUu>IhHM&91sE&F^seQo=jqsC z@w!FQ+e)ShsV@@`EbGQ_ljV|d#Y|^#V=gg>#8NN%u^qcY0P)>tYD70_$cY^bi!ha> z(Z;k>6Q~W3L;SfW9QdT?wg%33=F`JauaV#B&k?-@wZ--Pfp!>(2Jr;^j<{R(LJ6M3)fI)oXdO=|@T?<3Z3NjCtwl+-FW#oK4>! zZsL>dRg6NeKW)CukmZ#H7X@4u9F5-@aMj5DlNK9KnmxuEPq9sWqhakJ5-_8?OjvT5 z=n&b**TGj4KH|QvO#IQVZ|&C`>;dQAc##!ZuYSrkuGV#1wRL(f&tqp~jSNuZsKOax zIN~WX;Ucil&D;&nx~6Lsf~#{zo4F3`6r9DW=9_-_r+x&cjZW#;Z?OWCwfU*+0@NYE3SHI<`22}WQdeX z0tB-RL%nui21_d`E3=17FrT3IoQo2gvqr%73E_6QlCc4-#}11j`o8!HCk-b<^nzEi zbJuTH=sZ!89`Kj{|LV8TpFgJv3jiqzfprc7BQ0o^lfjT#QF8^4ETArlF~)?E+c0o5 zw74oO&#T<3Q`PhUSiCCNL+-*lw+7U0NxK={WqU$xTbS{K?^>EeM>Bu zU>cw1U(>LHELCIU$g%MV?7msv@l4e2HOTl%NOngd`|g2H0k9FqrQ8U_fp=AO(gN3pou` zY_T5Ac4~#gOBQ{>u2I1TgNA&IrEH-1s`Q3Yw`NIufL1HR|LkiHR%_kE`2V}Z!@swG z@!9|W{lP!~fha`a@H_8_yVf0!GFfKKFeVsXary|_=_eM1A3yxv-6tN19}5aUJ05_+ ziwh+kIb=Zq(u-xq`Uoajl8w|GS(ZQQHLss>gGWIeERPIxz+38dr6CLOofLmcRG~+^ z7L+;SG9GILL$f(9w@84|25!8feP33cwe!1ku&2^zf!;l#zji}m`am8#@7>(Bm}{{Y zt=-1Ef4F&m)Pkz`j{GviaI1NH?t9ypE}b3-zP$0%j}}l^rF3j; zarnn_yv5W)V?w>rblYOl420IAUCD^T1*UW{h`XI|m!*e`29grGVx`O}9LTi*kd_zE zAWgDBoR*DoYWHzw*fLtc7GAMo;S@7GI2HRkGqPG>pv?B9F0n{rk8q1=YVkKo(o_g4 zZ75s&ji$iwwG*|~Q0VnPoSgVAQD4PwZ)CvZpDa4Cl5TN+c!8q2W#zNfu0KG>8~aHK zh;3o~2=`OcFFL`j=rINgvt7N$la!FGRtP3Wh%bqwt@?4=T z*YRwO&*n7Lz&aw_axNmNi8APdON`tl-V3hYk|!xf*3xkm`GYM9S*A;07jXaG?ye=#(yPr5QxhTu=IkJ4Fi!^ z+>T*3tlpp#7K*~70Kim146!{Mes}m3+R{_UB6oAY;8q2GZ^x^ zbXmpb0^`N&J&LOd&FceT`ha@rdgTEon^u_$+#U~JYCCNQ{KDhYH|A?t1Te~0s@Lcu#Ke&Fcg*d|1z<}G#KcWXEgBWT(&i_gv@NVsD z-!*(Md7YUygQ0?c^&{Xcunmzuo$XX22pY`JZA?*QwwOZ=bgQxGipMe7>H^ZE7QG>P z3{v~-#_VW@?1TLU=xrs7?w7FRqRsQPOV)|0;Dk;g;&;`sl(RKUn#-S%|fqG zn}2IB)`vs6GQ!Pyq#%AlaywTRXFRgH*&MC6o~|Ls-Pl-#qr5L?Ju!!?8 z01*W(vOIT29z?(%@0>GZE;?VOioS_DA>bFz!lKabZU~^)hA-HyT4&_BD*!vyw0K6T zuE|1^6I99c4~B1Zl{wS5f;JhfI#V_#Vq{6wRi6yeZjqdFchz-l$=EY@WdPx=styUU z7t2y{E(w8|P+yTyPXL`3d2@7W^IV$6B5y|PH=F2iQKkeolh_5Ssw}9&R3l%>=yrvJ z2-58M4yE7>KAo+&^0VC>7AQmKH*OMk2CM6%Q)5UpMINB#TOUx`++$A{ytP7i4rvji zZ(C>E6o894U{K^b(YgX8g{g9dDrgW}Y5byS4Wr8uy3cj~!7b=DD(m8f0RXQPs~@Of zOQBe$FvrIiJ_iyzhb@b{C{4c=Lop;BY#a$bP2FEZ0@gN(PmyM>xF&^9G3mug2z2u=aO z(%q%BN}%}4&J|_8>F1}f7cM@Ml zsPEE)lA0?jpGA8m357Mg$uXojaMAI6K4-r5F+01^PR(YC#lfVp-vj zTWDCQ32ge1vNRhAS-1I7VvJyEA2!?ePw749yZ6o=Maeq$NE%6g*fZyR=R2pnO8c~6 zJK)@(PIJYnTfklQ`@)19mil>P+MG?Xn1rUlI9@$cuZ>QluJ2=>tT4VQw3i-f3|+AY z6yq)R=l-dTfdzn1j0;OE(Yq%V1-#;XJ~`P{fV?yVp65GVOsw%ix^jN@7Gll0HO*)A zqqU}Rs;N({E-jiUB4l!>qRZ2k`b^9wfeyWT`)k$ng`HSON@xIfIAg(hqtMlQWjb8& zJ;RwJXPO$7-NN<>#sAzR8B2!6#B^H&f#XGv92?ZO!*91O9$D!*bdR_WsVFKBV(~h{ zF1HJ&Y3Qe+vn7-^JTxqTG%Dd^Xh7D1SPS6_(j%7!N6x5NzrDyo^fLH6*9h(vL}afD z?7Oiqi6^v+v)Xqgzw35b7SyBi*WwBWCq0vzF|06CU2O*gF*bU$BKE4LLyS|M^u&}V z=(Gk~HHHbJ{r1L&0pqiFl}NUM<#@IsASk-B$!<(ZR#R(dCdQ9#8!o|4mT6N>YHfwz zYjMhl+E<+l&=Rr7Wa)U%8>ysXC~yQ(%?!tdU71XmbYF(Irlu%m?9?H3=9&g)3}W@P zw?=RsCODfG!O3(JNp2Q~Ee}!HtZ=i&EUN^W&Oqrg5OrKlsL;2{|~t~xLjxE%sy zlWKKLzB^P822?9N=C=uEz(7%mzAH;fSQQr4vmF=QG+;^<=A%J{;Twodt~ZFkq{UFH z8D~Ltd7ZHq91+ulwZb%MtPhhC;}lZv0G5msuXB`49LL?g6((=3^L!`+4EkiFPl3gI z^YTFM@xT6a;nhDM{rly!=l`H%`eUt3fBZ*_#2+4idW9^uV4Suw`#w7v--hW5U&<4 zXbyj2!ov6$SgoU>>jK8!t_Ub-e2IiapkS zS)a~P>gai=-s#*(BEh+LCizjTyXpG`L9|4)&=(9XTbg=vMpcrZYbO{|L?%sd-T?s5 zjRz|@>2Vr-Vl-!R-(9_XG~er$6=-!V-L*}i(c)y?K4-old66eYl@Wx{0v zIC{Jp@6-1@Y2^sWQoJ~BstXaHM7i6&^=5M3k&z4Z6icw)TPd4%3x81PSdYyXOSJ9S zc?#7yvL+#oRPtgaWjHE^v<3+ab+$m%5|$LyI4Y^IkwrfNCcspl6Ct_wu!7nu zjtT8e$c)E0Si60|NMr!*QXjA+QuU;gPYRQe9mUKjP*z%*dkAqPuEI_%ytTpkFR)bt zEU|_JnYyPlIG!r{Yv^h^Vde<${7IJSUO*?bC!GvlelvW(FkM}CFj!1jZ#)!F5rUnY-7exUKdr3D(51ZWIIV-nCTj`LZrzOZ)4^KdES z)#I&P-A)&s#bROoPbly5*1NCuaY5 zPa*G~)|+>6U{`!sWXI&YrEGJ3Xr5mokZv;g8sN%?Lv@L<4?!Lur7PXP(3)q)HV(jL zlT-}IR=-Zj*5_`1Gc)1BMt*hXwARuTZI?Gs?F@67{f2IagyGSJkJq&XMb@+Il110* zR1m+?(@7KJ!_L3gnw(qL^ltKXq0H=j%nLJNC zN@ol8I5kEqPFbP7rg{xnFY1g90nUtx3!6SQNo?X;EpwoNt}41VSqcQ~f3 zoB(lADmdiU5x>97#b0`x39#s1P+(iFR>6GL(cv&vN7VP~r(ve}?+}QbeQ?m=^tQ27 zN2maJWksrw07~MRf_equT+p$Cc;5dcS76vBj;>r`Le{f@Z=cD>puReQ( ztjp)e_wRkk+-U{Gcda)4?5H6hd?c+40W+|8Ik7Il%!n-63r=Dzwxdd7cy`ap%bEm=<6i5WUs$yKgIi9SHDp`-omEhYxGsJGiF7 z7w{_t_}Y6HfBJh5(a%@|R!DsCN_)^?Sas3^ClK@Cb1%_e!k@+Mcbo_u(ozOVz$`kxqM5}%DDUPVsUPvps(Tbz+d{mf=U#Fr=l5kiyN)Rk?1u@E#%xN3d`t7l##gcH5l*J1^+|q;b>GUo!)?zA9H+whwiY zxh)@6f6{j3((bm)al>VNFMqn%nQ#gF9iVk5(aYB(=CNlaT|%6|;x7X0t650oyi=56 zx}&7mhca-YGb-4Vz_2F;fJv%r{b(tYCR-!#QWh3knaQ*?W5uovW^vb9X{Bc=khq{~ zVpmFKDYjPASSU1`ZYK_qGtFOXOpU4uH>JSLogiKk5Z>gXAd!$rvg1R&F{FiN&S=FD z4Ui;@Plbqz@2bX8twriIp%6YErX1d8T<6seDe&WjZYsbscaLOkm!oEIMt`x(w)eFSyg%&_LPo<&5 zFIO1j!CoTCi{vr&eGgkhcvsS~=c&6M>oKvlZ0+qn-h1MGb@0CjpWJ-;{KftISR}qn z9(?b4&i(~j$O2A!SqEGh1j^Iw>+VAg^%z23ib=Ca$=ceTLa?4w5rex|hww_Ge% zUe0PHR1i{vwsT^}RCY`c1AdO1-%xOS@y5W_myPvmAW%HG=1hJE?-6?k1muf9c~_BN z{23`c{p@=;E@rnM{os@On%{Kl2N4bG(mFVMb02vd&3vL^7ZnJ|tppH*B{O3KvB_~O&J{K(eBDA;r-EE> z0`I3zh zw^kJ_ujY6!@lliO$(#RY>v~?>$nR*_(wnrX5U4~IRBxjeGcA!Al%Os4kf|0%S!A!J zN`odERMbpKj7c%ug06w!i*o6y5S*TR3GJn2bLb`@LZD?^gqZ6>+r9Un==Z(PcfRu- zIcBkC{hE;%^5(tI`@BczHi{$?XLM08Ju`D-Ig-^R%Mx8I_R53m$0hg<)Y3lW=hQ{V{pa`oLvy8iw>+N$2h0srymYat(8|%igS{B zS{SC9$Blir*XtD=$y&&EdzR>&v9nVfoXzz0G}nABA-Ml^=u^7q_KdO8AiJ94$$Fu*WHCxoAnl{u|7_IFdWSl-BYsMt9MoqJ(?|j$ zMP81~ZZ2u0QTRHCjJ zsS!elE_35399|-AQs}M1T8x}A^DP6L)mJnG^(_kkm&;-0#dDx3T+X|Fz*LhPQixRR zdu%OK7)k=$rXCHtC_ZT|GIMGyPGW7624nT0DHEX;Wp1!MNw_ksuxb~ULt@X!RLuti-m=uX4}BfeOd{{HX(euGZLufBTs z?%kh`$(Gpw03ZNKL_t*k(Ji6uMp7na514^qicuqMqy$ObV=*B@u;|umKKt$c`&WI? zz~N7ye1U;3=e}KCI!KUZ{G?)a)zM(A%NQ6^*_Fp(%NnC?w%T<*)~mjH(FhAjT74Fo z`DAip^yrhvlL^_c{<{0)IjmIemWO2LS3mgnpMNqefAqIjE4C$QuPLC5W?PmJDze$k z3W8hJr#)kVHX^k7`K#XVzpRVOi%vmWkN3FHGneSAj%lxZION_giWgAvx8l-} zB7TPl9DYKRt}hm=WL%Z5zwWrT?P9br+NRsIlk)3Py1Lovj?*+aJ5Ci`Et237A9#?S zZ!G{m0Ifvp0{4s@iO}lK75XBQY7bk;F`I~;1&e|inF$;BC|@`t`>k!-%TZ&re!JP! zmKXj0vesB`mKbyFFkpe@-z+bJeRW=k3UbkZG-osLTt0aWTUoHcArX~Dv_&QulR?;a z=*XXNQKthuIDY!Uy<5Jq2Im=tzLgSX7FZ43S$NwM8ZBBg}NJe650%lSl5CSWsInSLjr=}ZW;&XNKgGb&Pw{VMDj ziiD}M-H)&+g@BRl1L3ZUAhSr%!mFoK04D|Ip>zg@;6i*>M#yn-M~m?L0nno!Kk<-?rD*oJ>nZzY-Paf zi7lEgXlT%!0k`QuF3Cigj4&jiydcXWq z@w|Gnz(Nq3{pvTtZsWO=BnhLY5~fFX6t7*OmH<&zD}{9|P6`+Zz3Qxx!m(l(eYI6< zSGNOztfIE7!DhQnZ+6p1=V^M>-KOL8=;m0#Zs+VMT_`G?5S1Z7=Ky@+o!?*%RU9nX zJlMgQwVu$B3>mz`-r-f9*oV{Gn=_qxUJnKt@!f3u3Tc;{wzpYs8l}<3^VB6=X}Rf_ zM(fhsrME`EW}cXOL77F}5gZ?`2&6$$Phw|*1tSMeti6|u7}n+lhHPlmFo-FxFGjOY zAjy>VMR0fsk93kK2K@0Sw>14bE!u_)3#UDaMY8bo)E+_d?$aHwP|lzH;>hyKPv0J9 z7I>e(8fNMR=en0;TL-x%v`6}N&i=LZ7ykBJS*{y3#jv#1pkCltDrYl}_ zWV1CZ85O#+mMb%nrn!ibkdTe=`xR|{B03`mSwvmzv`$eZq;=^E-Am$Bp6aeX*-M&5 zdi{vVJY|ak;d98*EU=XtcElrxdN~)aCk&4TeWlOu4rw{fQK1A*i8@`G0^1bfu9UNd zAl|}6{5?CMrgi-L6qf)b6yUE0kV9nS@{wxM+$ne^IMkp2kTXL5PI=U>;V&K z(QC9LK?@WScd;j16NfWU5(2Q!lJrQ6q2AWkZ5iUy7u}{P-ES~a3h~d}xz$276R>KU zY1U+WiM70a4f-Xs_MoX6mzfc`2vz2zbVzAPC6(}#sm;_0Lg^+}sAe*PZviysf~J$WOpW|{NC|4eH$ z{6n&p)FR(xWs>?W(34*#W~sa4X7vCjtjCkbC!g!V@5zY~qOFx?6*TK#%fF@Af7a`4uPNFb}B-5eENOa$h%wt!3itu7d7As5vJCgVwdvO)mcO0a* zQ~Z}UH=|~%81ONEZI078-B*7gg~MlOXx7XAyUh!G#==MZmU2huV5wHm;!0)19Th=E2KEmYY{~2hK5d z8t`lCA?O_p%dmcgD=-4K>!wpxd`kz;$;o zMtbfwnW-Wj5i~OM5knm%(u&zwX0dc2>+Zae{8tL%L4BtciI@mOf+wxNLT>31mc{|S zbc7xPinbieN@D>DE>RmCc_zc%EH9GPxFOepaKu@Zamyi9avZsmv1b_;OIC&WrYKc2 z)=>@=N>-JI^{H+f8bb4>WIWS}RlFB)TA}lp@QBWYkhde@#_IisjFlv(1u9SJh2nXD zESK49gk7R=8tU{aaO^S|t2m&^aYJz9awxrm{7K)HByEIzDwOCl0Jp53IJ{RD?#nxg z#5488=-G4fNBkor0Q~j;{+jgx1A@4w!#X7KCH0Z+%+L&-KPh}w0TftlzpqoZ+EkkX zte686=d^L!V@Crl&}?l$8kOF6>NgtF_`s1e%wI%Z=+6y_tOUq1Dw=+VF=dnU*eIa#m(b`ww z?!+%?xkAEp;vgy-iCqcCvIzHBbeKO0fS#*g{!iESytr}SQMV+Qb`%8FK>{s8U{PFM zBnHJ+!8`4shLMZ1Sc6tbp6OCimECq}6WYUG3&wkpFTSMEuH7E1Qhds#si~L-?54z> zEDk*cmlR6Q{TKRu@ALi6d`EH?@2)hOUy_aA_r1^iyiaezh>)N&9AaIzQLDhw*+#9e z!bJVsNf4kKD!8qA&L(j}FX<$WS|?NwCQ0IWo3r6P4AyL%-5a*A*6WhIMFn16RDC4s zT8m&2b6#<8y<%^aT0F$P{RuKinnwzW5%+~QV60W3CoFnzpTBYICsv$8ZYQ<`XiPk`mdj%Ql?;uUhRd>%hZ!uvu>$n@ z%D@6C;tIS0fGI^^*B&b-K+Sb85b5=FrpL@v^NzHT%+Ul9Bcteh0!fYNT+*K7smR&c z6ng?(By$xE&>QfbQ|hK8N~Rx3491M97-P!a=+ytVRbdvT zX^nzynL_$>dNJoOD#8R*^^hwGp}ZHo5L<+1sN6DnV=P>{gniLO#6f~3MmX~#K0ZYMM_7lTv1vD7%;dOY zjiS$*LN_C)Y493yml_E-?kAdV+h7J>URfB_veeZ3`M$#*nT+a(<@}+c+P_ z;Dmx8bu-745MtKfC*tYkR0e{dxap4Ab`G# z%H~S_s4rKDeqOc(m=r9c4$L6wU<3wynWhR?-$rkd^L%u9`8>XS7f&Xat62T)_XBLe z$23{)!G#44`tqJOBmc5>auX3#D@Ar!0N8qS+3W4!Z0{?Ax#S?g^{R>dsePH=5JRJG zHsfA>((&l5_rf$mNhEPluy~#{hDk^L)hD&?sGBNKcEU96RBK)*dHVF}I#Dbba`fhG zv)KfvZ8SY2t-2i}QL;Z#P}_{bw9(-lunP&7h3buUfcmjecd%I0_d%GK@Pjc!()Or0^)E$f4-NHT=6EkpD!0|8ra{U6D&B2g*XS%3Wzy4V%&`TL^wg?jFCuc+h=f?87P&jn8njV>^P^-x-e( z0#9)}n#t&0n5(Cp%PWLdT}|7MBbihbl@t$Vxmvo7F36`#B-K-{1{844W(?B6VfZuF zCESQMDh06k4B1&U2dJX>TY|VuoSjl=X8MM-BaQhGAS`Sc-}8qLF#4c|DYzPde=h)> z0Ee8e){;?c4ZECHz>Xvi6@)d}VX_9rTsG>G4YR`Q!QIr*?yQ;&59UwIDy(h9J6&sp zU1B^VD;t19hGU42y588#8CEz5G={+%>@Q+# zk$M-N2d}U&jZ7^K$_3v2j2j=U{w1h6F7MlR+Ot z2KzGUh$UdUvBFT7eW5&a{85XufC5FOHrg}H?60v<7#QoYu{>lS>^^7scP z_uBu;2b?Te4{pj#KscG&t0RTGFl5Dw3Qvw8y2dNmu8{T&V#q`)n3Io=kb)I7=@eFb z#T^B}9RTpPQ&_87-t&;iiz0Bf4?7k=tc3zx^@%Nm{wXb3*Dg=vGh>IU9$Z~=SVQ~h z2!N{?_IeTQx10Nl=Po%4ShwCTF%1Gv=^mU?&E>MXNm4IOyd+Fg^)FlfQb4SprlT|s zJL+kiK21|^vR+S49=v?{&lfK~{q)6uzWCzbq0=}UZj!S``v9foAYS$-z5ax{eydMP z94{B@*J`yyhca4#+xU1GOWEWELI!@ZIjYy(pY+-%4}W;e-)*k7LDaYYtM|7UZXs{6 zz%zY+7jb=eV0W5s*Kb{`PU&x7U^zt-XaPO za!#6|t>LW}zpWS!>t{P;z-&mT4Wt#}vHDV#?7daYNwU{mvv@EEWWa3EVhd%n!}7&~ zwN9|;zJA4b?L|iZ8RH3Rz*FJ4b2HMfJf|tRtovf;0*?|*S*D}7EZ7)HFx5;48&74b zu2hQIv=f!JG|aXi7Jdnkv?ND5FiLVfBrIx1$8ni$!)!AmHo_XkK3PT}3v{!=mLyi< zl!2IIpgagHn|bDVKBb5(k&gn%fX53)S45m9kfn(BJ$kyZOMa0T3 zP0l2_RHDJ2$09gS1#-0j%^)mww%Pp$B$Xg}8i0TIS(bz)HCRf=x&@fsu>#EEdX|Z~ z4myKsHEob)m=wKKv{BKgJk+mBD-!#P==`ebgpDo-FfiD1DCb2>FoUsbOt^Gtkye1* z6(9A`YslD!8d-8p7mZQS!W%AM^3u!3X!j_$rshciuB>_wVL0}?neNN#lmP!6g(mV?z_1;MNZPgorO z*Be0GUr<}7tgLIkhX7#N1O|La$_w+=p$13|mibJo@JO{fG6=s1>(u z0EXh+VgFI5CHxmPEE4qBKIk!OvbU$Has7Y8`Ml++tNx z+m@og>WZT@^hRkX4Z{@P@VHuCPu3@&zx*7i`^nu;KK|q1pZ)El|9<%4Z$EnW?Bjnt zczLjXnk1X%UcDcv8&vBW&pE?1uVG)k;YAEfHd8qe{@jbzooM?v#x_VYNWHg=R}xba zsEsG*-~N8)RJOfRwv6oiyR@~Cl{grD3A5dz&O4-Z%arTxnx|~Q%tchi?<$th*tHZ{ zUrM=^K~_U`EyQ#!HaRHbk3lZ;c#wfzUZiz-=8S;m_268QeDy~$FzN~Lr&RfZl z*OYwCm*L78GUxiVA=~;S6X(V}Qf^Dk{xq`8qy#}m);OcPwvS6HZ~QCZh^Iirv0PRB5eSS;Jh z@cPI^O~D2|HahfdOn8)Y!&Vi|gy+H)HD+^>+y?J&riT@$B!97#(3~FY#Ow ztN{7&Vd;s1IHn{;-LZsQL8%5Z6HMu_LK_lrH!4Z;hL)S=H)+>*ViI^cWX7f8=rvh2gpO2tyO;&s z;2J>I5iA(9A&CJa+7Qj7SPyQ=IKpG2KOY+!e0*Gb^giYeBIruG#lx34UM-VF-zT7IPdMlw+=N99}=E#zolM!=S@U#DE12# z`ZtfCy!Q29KSGf=$N>1B6Jq?J*AgSvNE}&w#&N}?s#OCnAhC8q|DUhxdu{8!qkGt1 zhAwm1rC6XK1ond`7#5e?p$+RYqq&lY7a}1GU8IR=b(^U{| z2uyQ5Ht1^F20}12c9v8TE89!j6vFbW!5a zuMvzlV1;4?vw=M%bfKlmH*X?0KQ_o|P`Edq9~-WVbEnbh7q9N`|Kp=CzkK@i@xzl7 z1G+DckB;{cK<6x(V^~(i*ZiO}`nnotTKE+6_a_uG*)r!h7aJtE%@NUt+6@hSaEk1tww84J4)3Uda(~IWD zDX2}jx4q)VVs-SEri5v)nz~c!jD!-jz)N9Ka23sP=qWw7qbMs9;I^Ht+O|G8fW=v9 zgqC@^6WZKnnyT$$F2H%lqM-7ZVO`##X{#$>wHrVVuKbAgdo*{oNzBa?QMFYkAOMv+ zK{774wG*Wi1X-D(UbnGP%Y&#M%kSDi?R?%uqm*={|bnUa_Y_xVNny1R%*rEBL*ZMN zK4+3lmH-pVXj7Kn!tXLv}01ZI$zY_-LS_YDyS^l8h4b~p%KX`aEtHckEo%wh8zcO5RDoF&O zH`*}Zlm+Vw0hn-nyYs!X4EUGHk2jVtd}c5WtF#3*0Q!AjUH4dR?H7k^Rp`^;R72)5gy%l02f;zn z+Y763&amPN9MntxB4@yc1Os(14WBfhERL^DT9d(K+%i14WiGL_HC~!v06g#qJ*)`h zXs#hKka>P{iS35II(at=6rOu99~X+ql z@yMX=`+t6TdUE;#scCyk6W=>9-+O@G1AQMKAKyMbK6-JAqOFsM=Ii9-^yK8>e@4H3 z??KQUUS#c4&L0iT`3E{Y!fL_TMvjlj@5vxXD1MtX5$2XSN$vXGp>U%~*>#-|i8CkMI--%Re9vL<;6 z^-E@?3F#B8d6BNn!%`^ey2)GeES+`JqgEU;MRDz=o4BiDAvwX;=$s((WZ^G*CO7pc zUUeF;69BhQuBUe89P<*+uLpB^ni9W$p0=crKc@N7Ndwl9I$US93$B!5yEG_qV%wFu zN^7$;QgJc39oo(XW>I2VD$f**Msg(6u4LDDL*_$vwet&P+YzyD$W2Uv+V%lq80`@8 zpmo#o+-Y>|3^$Z58#hqS1#0hfwRO~H)xA3JHG{>$)Q&^WY9UM;Cq5~aJ$a)gx z_6xGBl_D+z^Ctine#4%x-Lg z%I4pr!kn$sy^QVLd_GFn$Y*WUFHs#?7XUPRr6Kzo)=S!nDXtcG^QuZ>)+N`0vMLBh zor58v^^8#Kpm&sF-Ey|TGbp5(b4#=r&;IRhRqSlT<81W%f4+z9q3t;MzRwQ_5-48a^2yf#}a zw~AOz@(l|f8UVhbLWKF>RM-q$k^dTn4~W}hCNoFBBOkvQC>}5s8n4cr8(0`879=}jn>F(Cn;nv4nw!~xiuEAe}!REHx2YYvk#kY@;C4O{tdUSkh{=L{c zG)EtwKK}YfW|Nu>wMhxl8Z=_W^3V z001BWNkl2EC6R?p69&%2AJ48v!)f8rsrn{xJgX_wNnmmbQdEKSuIFTFHd zPQW(7)v9+ElA{~kly}K44JG?MF~fAdYD&2E+%#=XF(!H!tfFBcI zfSV%SV8C|%YG8oFT`dL!8yQDQRTgWiWWBT-(bY><%&9B;gRo76{|yulbh_$^CrFw* z@7PD3F=!OpZUeZDMSwfNNe3qa4tI;8Kezc(8l4^LzY17p{v(5t8=+1YG}8^0wXF2z zP&rqybpczujIxO0GU#%i+3E06qSc?aGB`jl;qrFW@u!*tYt(`q+}$DW!WVk^Zdpr4pUh#M?mi3>+?FqFmycfpWKioq6fwoDWmFrYS4K zbPZ-w<56`3ft6EVNZ=5c^CiYjnl}?DSR`m>7=wj-Wfd6RY-VSb1uf(S^y&-OyT9ie zQmZ##PKYq0IMlRIE;pMkWmFn~?(y#iS^Sor6&pOB`!TnCWp|Dc_Hvr?;`&NVdRHz- zzpkvWT)nx8Cg4D6l((+`ZTqkHDh6FkwO%pV(}uvqk+iydif04lHfP0 z-}%&Fo8hoNTWrx)R6vs+RMlK$UioJ^J7>Y{;bTt^*84{F`8Qo)TL9w=o zBBGW7U{c^=_DK-$AdMHzPjg{D^d~{teE1^+yrVKhvWAoK16xOQaea0e5}OlMXkEOsQh-G~R&ko7YnK_eUou$Hz0aO?07hge0f*!Jqc__6!u?r4oH`8xV}|BlGj_TU%QP2dDr1`o{g{;^+PxV@Fu|TN&tm zvT-5Dlb4z~@i3p+0H5Cgag>^)*9Nz4{_yIV+{NkKrD_~|7|F6z!nAkJ6cr~NdtP-q zX3Ut6h;aR&#~6@b0xa67e9<}yz0j2=|=eMPCu|~QC}}5 zIxKm3ynZj1)pc9S3uezmVwbc&(Qnbhq^U0b%nUQ`5Lmjb8R)P|-kOy{ZU9MehUH2D z7itjFT2a@6BdKo3*4&aG0$s73Lw4u@e0LhL&l!VR+J}*R(NH=@N4vM&BkGvj(XW6P z;)GIy6)V+X^8s&Z@UK|PMY9k$Y*E`6(t6dlLUPz?Fw8O3#t#n)fxn8j0L~K*I|kZ1 zuu{QD1wamUICwH1!P(KaaYK!O0A?mLBOWqz91-q@sC8S?v)HfGUUk~>1UDplwuPgS zE6Zu@2(V?fN@473TafJtht0*R1?JVp&&}2FC)*j3)7S;Q8}$L_W1|ujT1d_CJ!3%1 zb>OT7>;m#;6BI?vB`@&XT|}O2{+pc ztv%MUU@}}b(yC_Qhd=^N9{O+Wch2|y?!9uD>N>WiD_!a3+;hJ3og)~0N9lRBgaZ_I#GK5QBA_y683v$_WW zY;g=0B8zduI;bt8Hb{Zd`GW^EODlCku=Wx8!!niVGD?7orP%KxcR4&()79~~@>OWT z_}uaFZvnvZaXcR9LwlO}?(N&{{Lv_mPev!hRebx~&4x@Xyj%$Gd@YmAG(lV59 z))I9^8;AQCv*;CKVsWM9vp!-uu79%&yuH8q*!?2_EVtc#Krbn1>XDjmoI<+{@PSZmGY_yMbtiaAr_Aoyew( zvd-R=I)Qn(G1Y3i%#-fyq~tLOGC1l0(KsR~(ar*NS&le4OiqwdVJs!iM&O)x2y1oh zmFHs|K&L0fg9Alw+;2|3tVv%ny#{d4V~pS?50o>K^V`=#&|6(ApB0t z#8q<|F^i3~wh!$Gntu$ev<$Q(Dl*rM<%!8qIZy4$%TKG7S(M_A&T-ZKO#hSQXY@F% zmL7X7QgM|BHmXivH10kLG#ykq-QWeOS4K?I%NQzN4)87T$3E0#w)5g(hA(4!E5TOM zl>kt^+DUpo!RYU||o5 zWr&LMQe(({C#GJ4%o6CCR88(3azss&HBpvh;)Z>fQh!{bnY*ByOPnm*|Gc&Lo%!n8 zwX0bT`daJm=jy!jx`;RKQiMi0Wi21afacK4OYBuF2^@LpLdr{Ymc13fr^YMsIVS{I zoY3@MUAL$U#d$%rXZ{8dURb#C?yPkCT0+~d{rN|q{ow7l?m%NMCuIz)GYs8m^Kmlu zol_qc)1kfET_bGwYU+OeAcf%I>=#n5P)EDauvjlK(}Ey7ASDLTrS@B1;nEFrv0zFn z4eJABK*9zL1eYMK&@$k$j~Ot+DC2fJEW~8M!`K_coi#qrkG*mJI2^~dvAwQ28Fgd( zbIjqOKZz^|X(TU`v>M<=uP&0-_D z1dTb4S;-VP%YIxcE=vjWpoC1y0nZgDhI3l}=|}I}QnzphEUVdA25OV@F0Z&6Oge2- zp*PvFsb+&7++4J({-4aywwjDW=O@;UG7ckUcG(?RC7fAn@O)-a>W-=kQ_OmUO#*wT zEl*i(xO$o|I@#7t&{LC;%VbcTO2tMws5@0hm;(oEc!UY63I4swf{jw@Qx9;6s*pW- znc&1}N5F-cyDNeq)v}F|CkTuh!JHEertF>66K3$=b zEhrB3m1Mrwp1gg3NcNj%wfbU~wTXsv>_8FN_7LMEhd(Tm01BgSAg z#240}JT3RpLDmp9ToBlwd+`3R1$M9M==YjaqFZ-9bu|otRl(G5O~WZ6GZ)%IhRJ~Q zGB2*7qR<6We)ub8z3(MXX8~Y*7vrNN_GZB%f!MogENijDSIa51>F3 zdk>y&yxx1degBbVz^|XZT%9>QnmhTh?iaiGT*@oV-$L_5H^%TAF_eSiU@-KHBU~Gx z6uD`CKu1J*eeLI0<}+xS*`ukZ1}5e+%x8R0$vD?c%F019Ma(RqW-=-iywdom)A*ec zopnCzG9ojYa8ON7@C(rxphZB{jwv<7lqjD=3*hq?+8vsjR%NF+uvA38U5bW!xWA+U(v%pf9Lo zSYJ4Bqh`TqqtrNg33;kB!UkEkz||ls(liS%NuZ>&4NC~5K(Ww6<|HC5S+H}9aU6=S zJxSGw7)(K2w2#b*bln$SxhG_qDzohP^m|(!?iC3o-%|Njf+st=OT^~+7N^h=#bF53 z;H21w+QJKQ>Z>+nhDcIcCi3w<2gn`HbH&cwQ#rW>5{#HEO`PJr9W_07q_C(It?XXi?in`eiD_6D=0()NCWFnIO+Ua zb`RJ=FcA2cOLsr*dfix&Hx~O9D+#+4o13*cw90$hz<`dVTCM3x8xmUy<8yC227HCw zb|D@2?knlN0<6WzcL8kpI=Qb<;2S@lMZ#n|FS;43N?!-I@fV4n>K#bv)4qkL}`NF4h# zW3jWo>9dyCmyE_{vDnRjH8a(Y4=v(a;%iYi?1u3e%5yySyETis_GkM+0gLm#=lOBX z!tk+oaWrl`c>?-tzvbbA9$E;l4`3|D?hm$}5b|g*3z|iH#)CnO>1!OvC*>C}UOfEz zKmYyXH_yKO=bn&W`Fgy`5%A+p6{5HIxA(z;w<$z#!w0>yL+1O31Kge-yrvmzZ)5Y( zeG9;Uc{W;|svI3%yj-?d1m&2>-z3+E%Xvkn!ovZAq6dfptK$zoKQ?>c%KFWBZp~*l zVuOi%r<9QhzUP*2Ky#b8Iv`gH|1cHnupb2WK!pn z8-SX`fowALHyN>}Q&xwN86b9OncAUE<{%M_lS6rQU^41+id_lPRs{h~W_l}nuK;hL zcx;r$>JD)N((uXTQ4G#eB4&0Jhqyv+JCRfs z^u@hIqY^s?$+Ua@o{n(|xl!M({gD46-cfu`(@|%MVlbX?E0R-*q~Acsy2QaKatHAA zae0wrI}wdeimr56XABY?H*0c?R((__RQ9D;YScsguue@evjQE8@##iSl5X{6bmhb5YD80FP6P+>PI# zW)2wME1f{X<$y5YM%;)R@IU9+$$^>;xvrpiF_*(CLf`Bwg!P$lj9Kx?U!HRG=eIQi z>n{OZ0Ixu=LSgV=4bx+cmx=FU z&WG&GBCI)CN|>ATZ+QQQ{?Y~gtp|gJSh6(P2)1W9i3a&7tMIq8Am*!fAfsM+Ogi6) zWd0ds(G#iIaXT1w^9yb1qm0G3oDZb&aX!WjINqJeMSX$+39*7=xg*ZSlejc#Z&Xq&v#ai7?D}Gy&pp<%Hd5;6^;m!Z>i_e}(w)gRqCr`wA zb@h%wtx(=8LWA$B?{|U4S5J@x-?|F+3+&zAUSD5dUG1+9)z`z}aJVigydwa-wR7ta z0>C?upI;p39@VplJMtk!=}3`r_2H=Vk!T^^NvAvV2}N+GA&(?csg9usmmAY}jq$D24=_uulEfTr4u+=vbMGh8YYnU`DPk;mmUw@FbLYkW9~r7FFwt;$QNhiuVRg^{uj>54YY zT|js#-nNv&o?8TeA@}NjNuk#@&ZE&)ky0EP^JPSA(ND!WZmmh7xCK9!e226wC@tP7 zxpC<_^GjIyC#Y`mu|-^M5_hZOf3AVKE}JxOii6=4kJQ2j1Ubi$fo@8JYK`R`)Rmir zMfG}B-4UrD!Ye6@tELM}r-;O$1u|Qc;Vwa#*Q(X(am0T~d5_m9OdEO(R6bsa{L<6Ft1ZvH9_`LOLFQ8*3IFX; zgT~Kyzh9aI_yUFNZ{1sY@GBn!U(uJ`K8#FqfO;CV*mfZFeMKt3X&iKR?=4Kjwo#-8$MmeEITZk^}sX)wlTMA;m8x z_#0r}+Q6y^Si#Z@K{tymQa3pF+0(~6GR7sdHJ7_)@GHoBMP0jc0u-3YyS25o-XHc? zH`Z1kuC88C|5i61_7xDXuMUU(;ZQj6_6KCZ3V?rCSbS7pD2d-HKZr2z?TG!XAtwN` z9U==cKz(!~&j(RwprBbyZR%?G+RAHZ!(zCHf4aYh7KDqAJvcEW*@>v@QVQ+(aJo2g zDt(hAZAn&Lzf_p`oIL&Fp4EvxI+yI|QZv3{aheaiVlpLF2UT^{*3LyeCt&2dskESr z!{I2Fff}H-RMw!X=dje!;jQ}*Wz-namPF-!$Nfh zua}YI!90`fFet$yj&Kbqqxr%_b6ad;<^}`|byF?vq!R10F4fS; zX&85k5;crfjOw=NqLN(+&8lg%YBG5wiQZ<-BB<$=Oc8noXsb;P(n-+aTV|+rn3g~*>sbC{)*sC#wNm0z%9MrcLWHhBVTSNLQzthj=|y;0 z!EB`>H5r0*G;*ONtAgQi1qLa3oVwt4v|Cj;;N@xsoz$&>pI4Yw!oCL(an?OUQZDe+ zq0HS86%3vc40ypLCY0+Zk@s425O>XNYFkv10#s!&*#5>$`)-1 zxjpKnju`e;Kzm9s_vncpe)J$i3l#U>edD0?JcIu(&K-W^z=@@sCF#7b^Jc|%%LVOw zp7SvT7Iy5$UJ{(|K9oy=i2Gsx9?-2ynsks!nBG^1%5| zK7IMYovR<=pUisouvg&sbv+2a`VswBfBMU|f?nag8|#9;7uGJUs{b1bcsGW9g}bZ$ zet)MwT;J|*57!j}-@5buojW_9{`cae`b_!xK`G@_1i!?x4|P#&yxVEWn7Z5P1dX^8 z$hk^B-R`!<6&*z-bpo?_={slNoT@dp8JN%+v4*c`Yx2UxNbJOT>_n9@9CBf&8p^tV zLnl~k9&LE3Q|0J-rb5q_UwG5+$lz6&h^$`1U)_X{W`zlGg$bUSyIh4=v)9m2*o(RZ0TF;KeIN+HOLr0fzal10H@0-I)9 zsD{`t7R+OJE($P^&26y_QX7!qoT>)W)okxdf|#voY0x7JJ$wrX8gCU}I`V%|s?HPO0S)kZAbew@#% zHdn5(B!em3!c6*O=*>nPCS=JZRsn5gR-2vB&PZQVMt3(#Mks^s4%Rs9BCL$=az>wW zhWmg;6GlrkIBy2i+X}ZW6;R-THHU1V=7wQGX|8PG;>0r7KG5vUM@s=mft{2j$Fqz# zqx?gi1dLhVRp2X^!Q{DI0%_k2P`J$2%QEa>0^HJoJqR}|(Nr5~Ik^A&BGK4g0n`x(f$UI$Fra1MwNjirXOWrWeGc z6-(WdbYetV*)^~5S%J;MNWqR`qCuzK?LaG5&r`1)Pezm7(jkSvyYc*BG&lqo^q1=D zX!rTK&0k-;e;akoPyda^sV5@*4xc>y&$AaVz8p2iRs4IAz9jNn_ zY!`NLbs8d{i~8s`SN`~usiiwf=WytSQ^8tCL{7X@#?KSFnHi%cdr8@1=wyCe53`r} zy*vxguF;u!S}(NO)uQ97IM~Vrf^{fvnA)U@^xFYe9J&Ho=UR#L7WgOlxZwTCES8(4)!1t`vj8VGTHLU>ChH zc0&jQ*I~(W6U(#eY~JdqDGMakmRxwYSe+~(Bdp}64H<;~ANxJe`<^eko4+KV=+hT@ z&hx&{2m5ZPndgkfDe{uxLlQWgq6vwQhtI>B^jOz;NYOb1BVoJ+>xGP1D*V70DbdzN zwdP##H8e4Dl*+X?~(^IW%yM|GOei4qIx--%xcya_Qb%dWt?!Nse*RduRDMq!;hbBUM({{u|^OMSW`2henN5;*SaXBzPfBvU~$iNbnb9&>=4}SFf_dbc?*D5B{ z7&2$`c}lGWs5zb1SZGP7Ovk=i1uZyy=IpueKFBl;mmQT3+#)1b+bFxuG3|MTbLT`; zdXaMQ<<1eR6Pei*au{baDZ>s^&?_@cIu{%M*YLBE;b+eb>^?UboIA4e?81e?lUEH$+mm^DFDHoq0kR)_0iJa!@aOT* z23*4Y8X4zdOjWt0jnY`eSc+*i-cF0LM)br?h|*pnO>&+Rrw_9q8>G3@(@_b#s*7D% zLN6NfjlpwWJWP%@)=y2Bsi~f#|CWYil4g)iNt{Ax6d1Y$TacVe)?;0gFoat=;z!0t zJ31v2=LYA|s+HnsS}KRcz$9_cbvaJGRg`w2DOFQBk`_sb=Btlto`(CBLXNc(p&^VJ za5^1zBb&_w0xTVgd=^Su_M$W#{Z`F0ZeI@SoBh#qxh#rlU~NVCZ@E&&w7Oz`)Ljs+ zf4Jr-VpWG zTbw-4kGn`b?){j5`@IoSU=8IbCMG^v*!a%I!lfeC!Rfqo09PYPu7JUHC)^w?wjfC_ z(!@{>Bj_^$8MJQ#K6B=sv*&*Dms)X_5fWf>WO$hjQlr1XeDSr^T3zPla_i!vp}+XPf)TX&G(Wq`tA+%dJHZUx zH4n1cX}5b%wl9|=ySvXvkamS+kY)xREd+;|D@F4na5fsVq`4?%xdQ!6a&xj~M}i*7nqfe~;P`M| z2EBxC;vZmhU6^WJ8i=CIZf2-OUBWW-F~vcQ!7WKJpj+8F2Io-@kwMiZjhUz_`BY9_ z7qxn*q1A$%6gwJ|A$wUzaxw_5>jw7A5>QnaC0f*lbB1nc9M!apvnBM|QBtd=32x+- zq(`c=$PbRJE6O_2N&s>Jr7C|`He7c>*ihbzaAUx3nJZvn#-zr-s5odt%2u;+H&ywA zN(PJ)L){NQ6)KC$f-L!GDOt)Q(J?L=SU}5?q(vubu|>Eek&n5{ac*SI|NJ`kmoj-i>(8D^fXBuT zU%E$YQ7nz1$zi5%Xy9{^R;1zTP>rizZiWp;7X_gi)j<-xa!mQJz%6yp-0))h{FY08 z=Z||#n3g2HcK&-a%+xS^*Kpc9_k?*V%ufyQ{c)mmM}?77z^1@5)muO4q-u718d zGBqew#}j3+QJXc`{DheA|6-A zWch9$9oSmFb<_*Xuzc5#%W18!8^;QUL@d^wY`Fek_!M`g|Ng3qe^ z80-Iir~{nY8aTLYJ`v*Jc9@YLc#Z)AuzGc-R2_^xF4e)5LnG7z;On@om-|)>s0Eaw zhqYD!u!sHXl*5^eDXEjL8@#9XR|n0#?ZkymjXEJea~DI%(i6paR< zx)k~fmbxAz38w-rcFIzr;DIP#pD(Jys#err9`HIr^|CNqA<|`8_EvP~TX6(t1z{bL zM3-F#tSKF3!D5b}-&jl1*TaV1NWA*yxvN<*@Z>LD;s#V5J<{4sNX#>5BU@!M7Dmc| zFzFP=KsQT|5t%EEM3IQ%b5cgm9Ck-!3mkc0!n5M)8j7%ym+c5~sV^$&w0b9!RBI3= zV2FM$iE5b&ZAO7)spOKAh7uRPs`f(IMu{F{YMk@P2T6*+8K)HS64t&@JgXr}VxuX- zV!;xvSWLn?>rS7?-0`!)-?93}omx#oHi)k<_R2=MM*DA!J75(&6PVKstBiT=NW-Up zC}JxST1|@1Syj&SBDR`T;nn!O&w+9M`25>%0Dujy=3z2AdGGGg`nRwH9?DlG0D2;w zja1=Knn;T-S~IYq$pSGpzZ6d$639IhaszV!Z5Z(J*Kf|TVgX@J=6h6B&`g_Lp*_i5 z%QO=pzKG;7S7zY%P0gg}UCPa-3__z0sJN0y)DnYFAOF>$?kj4O-QDbQT61sw+5Fme zN5$OIwl$jhM*AaF6B!0;Sa1)Skljwl+~>2c4hj)=%)3fmNHKnSF0+y=Qn;PDvp#-Z zax^xHy>bZz1_ZB?1Gl=+HZL0jjCJo4CeBOC7Z=UP9t6wng^bLo!GE z#;Yg8mrMDf-PB+PB@92#H4_LTF;8AA&LASQh_&!ss>ptZOsYshIL=RIaV&Ln;pn6$ zGFYChsu0o>_r*m8Cdj^;*z#7l1<8c+4J?wa?DAO4qn`!a?$i6Y&l%W!28=bn=e8d< z?9iyx4r7V3(SCuk$C3TDYiJtmJ9aJW8-!5*aW#&~jv*cjbu3HZX!F&{c;9ToxhB8f}&C{DYXQDl6HR zuv*e&y?PC#!OMNs$WM_loEDgwk?0Y3U67y!rvZ{gBJR8t$1|n0Yhd5{%>2ozql@tiIniZxr zMo&%2;+N>lz$^V%aCb`fzv>P>!8i9r4JGgz_x?4$ozw&Ao1fdhT}+pRVlvuF=T32I zi~+L3EiWzy2zqj1YV=Ty)!^>8k}M&ELy{oXX%Ifgk@hT=gv7;4Tz1Evl==#Aiw9Xl zEIdn|lnTf7wwNRCbkaz*D8%L?ZAwZ?r()cb>j+*c(AkW`aTyUeHYa{^$fC6{jNlCJ z%S#G+l}0ZQE&e3RfHnS3er5Slel+YpYNS~-2(M8=VkrxS>6|VDF6bIy%%ep$jk)#c z=sT~{<2zyGRfgQo$da9UpRzJ&0>#K{-G*I|%53Uxbw&2|93osP+;(tg}~ckY?lv2G|r zCs9{XS)d;#$y-~UPUkVws6PJn@L~EebuI%P^1OmM^$Ax}`Gw3!yE~oD`-=K*5qr0u z5QM>BiN5P=P&MCD0DQ2tbf5rsY4z&*!RpfL6-9p^0D~3&{_ZN&Sn6eLg4dT2$)Qd{ zBy@Lcv-|w;di-#I`1J8azOhoK4|onzaBiX%`$dEa*59y5Wne?fH1ZNn!pnraufH~P zriVg)M3fxsnQ?pb++K)exOg28{iJ%SYv(5#Nv=NEW~1Q}HEPcB{l599J@WM<2<0D{ z9QPrJYmbIqd&3%wS?Bsu5mhXL@*%GJM5O4JJ(%ldx=z9Z@kG7KlDx43Xbpb3#Dvb3ok|cxzLKRN+7g=LmQJ-gHCC83?2! z)P*&*h6=G4)j(5We%zL9SaIDTVkwqA=qdv$u28}&R6UrLeCEIsC1WeyG#pi2N|F@W z3Y;EFOSXpyqXjElax|Wsm0S)ibX$%oD&m$`-H1yFchBlBBORN;m}dl7h3_LqU^9%K zGBRftEjTi9p3>SY37-@k4mglT6y>SyICC(-6ie|+VdTQYVabn*-#l}v_Ga}9|6sMQ zbneEb{g=5G9PuW(_@!hC6X1&EcEsxvH90J&hMH$slXTLghGrH6dSdJ4$k)T(wIUBt z_sbmUN*xYhVb$QVb!=zxpj4ODZd~NeOw1zDW$7Wi28HzwC-+$c?CDHPxf)2aj{%nu z>~EqN4Mr#yF~~)P$De|Iv8ND<&^x(kjh_j_lV4r_C(v~c8(pfL8=}D?+#*o1kxLiK zB*l{aoCZrS>u!d^+~{24^dDws#M>**qKS|Kljqh9@9o{xvbfFSiSwrl@EHlIO{Y(O zuzmaeM{GZ$(n?|Tbi5?Lh_dt|`)LN{-BcX#VA>Kw*Fetdm6SE!%tNt( zPd4v#U!5|7fJx^b?`kfWGPkrb7 zxNpyh`v=9A!zRoT_I*2~(MXNM%;Vld)hg%<4L&i0+&w*!#YrQ(%U;w)-@elCNs4Uy zj0GV65f%J?3ke8o)`%%sAMMl1V?Rx$*}QN!JZ0!$*f-WI1gDDF>d4+c8n=jxUv+j?=_?8P<>_ctrTPiRl{@x z$BNa^aUA+fw#3z{={^$bTNM@bS%(x^QaPpoz`|*z?Qi}~cUe3M>q!MOZVr_)S(5)nN zRvvf79`#w6L)ViG{lbR2ME4N~<#oug(toZLmB z2r*#Zdu6uuw_pA7gEYe_>oEJ~a+SDbLFe!gtqi5O*D|n1nSFbKTpw(^7(eV%#6xJ`RPc z=|^lh)}q&s7-=+E$85uEZ@25aeXG_evF+PyTBB>%CtZzhY2874&#^un8#s^ldoQ{c zt@T6d>$-y(ZEVntdCUe!_p=Cbgj(A~dcfNa^%3qd3%>Odeei`s@5dYikZq7?&SG^- zwGwLq38><*bqJ&M&}a>EE7T85XP*?}(wRgujUnr-7DKgk21ZNvwN0*pd-=*(3#)_P z5Y1N5lFz^(j;4UuEK`?Tl9tRBFOgBV7KsvBB*e0yH5CTL$(9pRPU3mh7<@So7ng36 zgj%3dCqA|`xCcQml^J_#^JJh6M|_8>&aSG4C4*$YO~*iYV3xdQk}bznL*#9S-XpAd z$#AP8x>787N=lDJ_l(;q*$RU?^L8rKVO5>W+XP9vZWWf+Upe!THXnsTH8Dg^|L|Z$;t1&{fJby&?d0XY1HLYWe%KkIfXr2D{V@6xmbjX#3z*#|E{iJ~KW0^hI0KwUxpMSSlF9BamrRmZ1 zpQ|Iz*`bNIZmY+Vy`ivq*rOPl$yWlqGJ?iTn)2wz>#k)3)^{#m)M&hz{pKE3O-P)~ zz~hUVvSN8F`T05QgcaDdQ>PQy2^Z1y({5w+TZ9-oh3eaeB8H88=95o;dhXLtKm6!F zFa8Gt+z|pS7_6hIc4Q3Q5e&Y=P{_v|L2qIHytdU{Ln8u(RJ$-J?VLd&LRT^1-==ei zC(a=VdJZU@C)sRgK3qq#m6R#qEYMc|>8?|Q#hos)CJzp-9$ZE8)he{l3V@#~*nRp` zeZNKw#_Lz`jZ%~`5IL*Mj=3`1fz@S4aV4?9sOr>0k-xe5 zb_y)`y*y&UR#JDr_3A{3eSlfrrx31XtvrfecEfn|p`C;nN|}0=RXb72w`R+Beq;Eu z??>D>zGaUMLDG$o^{9_1_A((+pLEKPNQHZmRFTJk!VulZqbItYKEDLAVy>AJyZ`6w zYG2#B&uBhPA0~0bFiZlqp1KOQso-1*hlXO`y~K?y*)0GKK=QwnNVEvK0)b2$mS!-< z23v62h4zEzt{5{`r<-eMsavNlDczb4YTU$-q-#GEGMbK*ZZO)vW509Gb6+GoRaM!# zzLswM<>)-md5Q4OOJICC-mczr>g+|oo20-VS+SRZQQ>>p^UC1Wdrrqcq8zhcacXa$ zORo&Q@krtmh5PP+q{SVPTaeC7H0SV&KYQKlnr z(n%SYIAqrJn0{O}3K4P}(sOkrbZW`3#A;o>KHl&o#nR#MmX07un+4j4i!#G)Ta^e( zgjC)X}(6}hqCO7WCw#VT`goF?b=HEO2#%2(YH+XLB~ zkhbDryb(s!a_o{ekM7VvBuw_T-SyRVl+LM+fvFwo5J8z-nNA}UdNfcJHN&IvxnKt+ zhye|~KAA45bQ4d>hN)}zeZEAX^{_v^!)joB{-7#b6KM>lo198>?2Z+&?+3+4sDhps z@M-`}6n^s9x1N6+o+E=@h@0`Xc-$7i?nqEXSMU*%U_^GXqd}@HQRRtW3t&z1JVTT3 z43T$C%y%qdKN{m59M~NnJN<))OFptSW}87VIP}-&|90iQ`~ULiz5`$YEO>FTnZwjM zU=qh6p)ZiPc*M#Hi*pYjFt(f61d9Ma0RaBVMqa|9IW!+EB7=Fnw}?3^3^t&8CH4Pd zuv$ezWg(A+aDHyCbo`UU|M~2*+qeI9{-c|JzjX_O=Syz_bUA#U!PiaFU>sNxEQgNW zHMH@*;s`6Yt|Y5V^Z@NT4!jP((xsJO3V34hG#>BeOWodLq0n_)^o#4D zzd+yh%S+t-F5@-iKZ2%t0bd=gp1Z!ajoa4N*>h)~J-hwevs>F+d;k(VD!c^{b`<#B z2bw|SlCG{h27JT4_qE``#U69M+{5dbKUW>;troBZhB=G;7k({=&RvJk?k`g)U|F4C z{n6J?SK<_>I3zfhDaZP(fw6F?7xpT9{5mn39vz6YsD#*4NyK67Cl?wX9ghsd@jm9- zJ>uX><=#K9++*$P?Xw`=56ivizfiwC_yS&%j@li&)^JO!L#cRD?2SaPhc78(;GP%p z>lB`ar=$ko2$ztGNpJ+X(PelsAeW;z2|v-4y}_&Z5?AF#|BM4223$4R9&dYEvOSX4 zM#FZ&bO|f7!l0A#Dygj0z$?E{hUc`kd~HjV++p>ty86Ue8|LISF>-@i>x_DRTeeo! zyUDoQ);hXDS5T&-fpex2W-zxRJ(ZB)vpIz0V5yTTLCAz-W$nH7av761Tc1%z zpG6EbTbV{|A|l|l3Z>Z@aVJb3=S<2Fu~zPYHC@R4v2?2s-Cq6<{kcv`#SVpzs- z{PFK8V&k+nzTxKg^vu|!0N-%o3(5;v2Jf|}?sft;B;qO_RhtI#!b*M{@i`t{W z51JG{7cGB-5m*>KBN>`WSdXNryo!g=l3|Gp&!77J26fN6%$~s zt*^iG%JRaikVU<~JM2LV*wrq5u;6$s=Ewlxl}+R^fBvhT*+Vxb?xPyJS77@RH_`vR zjvC)(yIsZLc?lA#3xHqnSwu`;xDFD$edo@{U%J~ncL2nH+_oFP0U0I^Bb&pW4)Ddp z+Dp41ItCovXukMh3E>|OUKu#q?Ly<+ud1uKKfZ`?=<&H~wTd9D0yo4^u$5N7|C^^r zMq>6?NmKzGjc3k#Xr|%e(aLbbQbIO-G>L_SNseCP#L7T+aYUepN$?(E-h-)?VFA$| zVe+t`s~&Q%mlV zU~gm?ucKEj^F+P6e$UQM!a2@Mpldn$3=n=mD31(mkG*IW?HI5F-jlMwc3P4q5jtyD z)5~Z`aL$YZAiv!t7|ULNVcX#~5fsnqUz_yi23~ zvPDj1%n&5vP4s4ZGB3oM`xF8V>MKi>)ho2(IID))gF{GcH4-6^Vd;>CSP6D*K^&`- zqndQ$)MXO0f|?tdS`;K%v)8R9Ft||x)rw`|37Mi|t=9#xQx>h!1or0!W25X%5 zO`DukpO6p`0w)}jFpC+Lv$2ebUhP*s))r4JoU#->d;E8-J~S5F==1bf_%JcEO6l$`%ozl|B5x zX|dhN=WE~0*y5LRs~M`Hg}lOEcbge|`k@KOZv*jLv;xl-S0AU`Ia_4d)uCcDJqr`C zf}xp?H7jE<+Zo(<)z?zt!q;ZcHiYJF{?xZuRmM=7oX8_$62Z>&){HaUDPPEU3x!E! zTowA&{6y(^shf8cw6{3fKYaV;Tk z{0oP>&q98@z%a-Qq^%H8X_UOa_R`w=+NIqOKYwngn7;POPrD8Q3uxQzmwJ)?$99Q}btZNf(0wcrOPlIU|(cKHD)85Ee%#$no`eFAwQW=hgstn9oziRL4 zg_5Y`;Z%9x^}SS5Km}N<49StbaH*RbG!qdmy#(MHFsC9UcE3OMTbg=Pq2Iadv zt=6J9HluchhU~+trDu~thst8&T8m=oPROLyS0H>O(n?olaZ>G&#bW*33WF^=Hs+Ne zx?|0N8LR6ByH;9qSjwAeTOgGTx!mXCjFv%Ui`wLd?PQ^w>L_mmuxWGhI4dKx8g&G% z+DfyOs5NDPDy-IQxFH11ggr*Y*p{5Ubz{vIqoMG~D11X)xAn3@ue9G4AGSesy>8>@ zhK|)Q*3EuYo3fwOr|PYTHwXpqG*$$!(7XL0E}y~7S(`i)3w8Of2GR-12N=^W&@IYn+v%QuW7 z;ZY8-M`s)NnN=pGR=|hGU;C!*d!Nwe*Z8lHcz*0V8z{I3uyj#s zTk7RYlVHHmWK|2j{KQ;gu`vER>I(DuK5{1ddD6W6%77?pnqt|9gvGU*uOUW7NF0g+Vfg$k#7y3374&Qr{7M@813Qr=PmV zyY2x8w(qZjcoYZr>i?4e9is2JlGVqc*yCbRF_C7mSK zj7lUTsXT+hp@ev49fiDf$wp}(G(&6hk~XxBv!*nrkUXSa86$NJP78f7bj%JO>!9Gj zW8ZVm=X-xRUT+l3`Yrk8=$y~_oRfag*eGFP4r^dqAIUH9#-3n$q>`{JjaZN@s0#|) zK%sQ!RD8}my~6y^6|fuf$lx|CqP!pGrob86D{#2oZb~5IN*x}{&S4j z>pBuX;z)J&M#G_!R)OS7W*Q^w_^^`1NT|LCzH>dFx!5;!?E94;Wk-=Mm-?1)!MKV( zkz5@^D%Vy16)Cc1Oi}1n0TLx=4rUpC(NlD?1zD6j>Fe`CPr`Hmy0s7yr>|Q8WXDR4 zY>8K`L)M>NNz9Jv+Ju8I&Fj8PMU+!rudvu-qcsc#AY9rQL;+G zPCoCdokDcUZxofxVx^mBKyH=sOtE>Uow}VhAO;PV7g`J%67(H5)H62{82tJ(0|it$ zU>&bj-@g0vdxo(rNunrBl&pA`N$y&KC99=mM>>p$)uY6&z+sY8xS?AVn;obDP`RFz z=+Ru=W#R@MRSciR=v8@>E&Ng;jKV&x%;pLUnyj~B*h&S>%cbhU7F(C}j8P~1J2hD0ioU@C;-S6~MKgtDh2z!6)*MS`a{@Xh+HR--cDw(9usR8(CYG#1JYtp8%y#-YufudZGFFRLOVVTk9akz!kIRhj;hmDDD>dIQ!qm> zt{ysirk>xp$>mGrFteUzVdVV6sm@&gJ|g=4%#+Hq>xdOyF(oA z1NJyiMDxo*aXO@p3nH^+K!!zuI>YiH8}1h7sX?j%7gveHAg@Ko#MI0rCHRfgd9wrM z*uP$oW8+k;^?>ZNm~d>XNkCYSyy?%BJjaINLBJ;ovJtntg4YFno}m)U5YF1rl{-MB z#Apd-BGlQwJX1ZE>M`r8q$G`V@)q~bnuXY#rUZ1B>1gHloGV`k<0Xgm9SG(sR@$`s z{k*jpc4@>Cd|^rZ0!l6+#MQ>iSY!x>m8p8SxVEDOSvju z+XK${F9h*Yn!{YmvYQdP!R)G@Z&666zkY1&A>6CR86FF7{Zi2>#%*{ko>Bb9OsXum z+cyFF~M4e>ydV)F}2GwXpE>-U-G%axrL3 zrl*QTT$!9eL`gdlBxS`4+5xJlsi@`2CO2%8XCKgdLM>qD&_p%VI@sz@>P-$ z(GzlP##bVUBYe?Mehq^Capd)TMAJFsZq&GNR7+VdyjPzYXV?*Ov({m`}mb0OMy;>XwQYuKl{_wa(U30ju2=JKlFSQIp`g5*QknU zXi&Upun?684vgo^OoK$?({$tBcMP{u>EDM`nbE6&R7kAkQf)>m)fb-;TREI{80_$t z446TXS1$kgvWkjSMzky!^xCbB6-0AfySC;4xU#;!K6Md&LxcJG#p%W(r>%`|0k^jw z&_DIy%ZI?P*Y2#hTfN#7H z27GDk{_No==gNzY=wb&7dOcL;0dlg-5Dql;GS@?2*&0u$|9(v-r$5NMaARO)s zbu6S=6m;G&L+h|u0gyNR){A>P`!SXR?qm9LjvI#ujeq0+8|;){5sHf&L61EkG_~0b z%whg*<}buKzMO}<%yJbNkbzLwO#%*#U&i^+j4;rQme}ei!J!R({oEIi4^m)tced9L z3%kQH?&2|;=xNW7=L-s(QX;$#yYZfk>FP&89LIefDhD=<9xC;f^vrHQs~a%0F!W=U z`VcbD%A5s}SEWKWn`H)N$#2+-FVB#s!iyy(TJesuF?D*zi7nQd-MsCdB~h7low}qt zC7%stK-uf3)L1YpjMQq8*_5?2rHm>qE$IX4yhoaA0NUx~#AYl0quGo5O6^is*elt) zUCKfCId5Bi`vtmR@-tD@yyO?4*-rS>(TMa~L>?4Itvdn*ZpwOEHl zTNjPl6KZfslus$T4JuxlFbd2!KpnZ#Qj#W16lKS1aqo!PU!4Eq6S;32MBs@rO@wg^ zfES&@B*GI)!uoY8KEIl3(61h08N+C89Pt}m@U6LYiJIhy6fH*vIfPTfdd z_5ZpX#wL&xO_x@egJ0jtz%mARcKWFyGeKt>^o!~F`DcH*TAr&mo{XTcR;L%Z3Jg4U z+zyDl&{XzS17TMYhM>5B4u(eb_l;{;Kcc1T20Dm7SOaD{-g*nhEh2;eXy(U*D{~b&)9;%mzVlrh~qJ z?_#b?iTUC7KLEd5+k0DkyF35f5w+blyan6UiFmv7hzj)fRtmzmPu531`V9DcC5_@( zS^IF~&CNHu>%*H4Es?34-pn*S46E%$0MtN?2&_F@NAevrWL|gIne6!h{ zf9F>}SSoVfedeT-BZXC?15z04g$6Rg<1Q{mkA(oDGyA`5Ik~^IJs% zcOW6~JIGt39g@c0r{(9oq^u6R&Gj5;$PCsh%1T%V%*K$ENBER+s%Xc0Lfe(XefiBH z9?^*~?LQh{YlygGdqQ$Lb(AgDv)p6K&+djcIpjG;YFzKj-rVsaj=XGsDJ44kz(x6* zs7Z6FNrYF!WUIIDak7iZjZVpz?D8^jx_!ORIcn#e*`3%fXdOf(qq(932Z(*IEPHPh z33t2GPDN%vAI9+5F9)?d8C~^o>c#Aowf55Q0(g_gd^Pgzw5_Pu7IwYr>@{aq3Yxb{ z!Ok5Gg)`Dydd897o4{4S@0+e6&FHt843bZgHai>^2Df<)Cd(&QD^zxehsTeE^$TZ? zEnO63wz_ZMd#6#Wy?GqrkQJ*pvUDr;9aM~!a=z+NEm3!{rn$0R@mHNxKRBi>riyG( zw#8dv(_u?R3M?fYR*F?caUR5DRRLSbWt#Ls(u+rcw#xEF(-*rR=+SO5ngaqk*mjqN zhDh>Y#ULQJ(#4Y{DiKZ)Bcd6$+K$KZ-2@;!HVFXEq-Pv|G!xd5H}8ts5_##r;_z3S zNTbar${3_QgD2yrxyeaWt>=K$r{DhT(h?n2;=GL75b-557UqijlJs8iC;T{bXgYzn z+5JlrqUtzn85F(Ym~VG>Y^+vGs61m5430c1{3TI#DBL*ysvK9T^~%C1dH&MUE30%l zMhXihhp4(qB-?7PlK%vYR(SIa>$hrm%e`h4S~t5$zet8$Ucrj(GM9}U7$YFV0q|=MfSCkI6V?N`ml;B}va-g2tCbJbNOUP#-z;BL z1ut+9T6DD;eY@lE)*X9ZO5WZAB5&<}v$OM!VJ@I}$7rukqP^dJ`ogC-A8zmM@`^8q zhJuqT@L+L-%st}I+-q-*UP?CCXMgrqbs^&S5BGne5zR%2q;&8L3)aUGZkStif0t%? z4ifo14Ovk%ediZHUfLJSe}IRnDEgj!jADklqMrI=^*cpWt%nD*?SqBu@Ug_i1I$wg zQR<)=&*;&sp6%9zxj-lnmT{bVntb{d@zA|%Z-nwFn~rQH*Mz)rl5Jk! zICa6U{DA^?=$}z)iBMmUU-4VG|);*$dk)UFK-Ch5D-B zs4foL-CdRI(UuM*`%wE6At=X$X;pLf4~Na_lJrL`Lgh+|!5$(T!-V z++#knx9WDO%gjhw*Vc*K4I8Inxv)e{0)~b5j>u5}a8tpTD6F66_DDmi@W_av!6OEM z$HjE?VBl!!)3?4i{N5xrQmIt%(YeyQjfs&vHDQ?nO-Vp03YNuVlo97pj^P(M4SwV@ zx5hBXT3I7BWM?c?lbs8|(3+4|+h-`Ro6?bWDyO(B)9MtXn}MlvJ(*mK$W0MfPKt>6 z?40d!VD>Z09Vi8Bag9wyRSlDGrM>|*V}XQUvO=lM0FI38iMd{GF`6w30H*M^WrxW zxs`PrmB@lm3;6~3iU{l6xeGta2cs=A*;XqcqT+8$a-P9>&5zI3uYfbdD0y3y(xAbe zAI`j=Ai(ecw8x8dw)Ep0$MZ!49Z(L1MIc9*4YOG&vZlkTL16>H#RX|QD(0sQ2ke+5 zn6g&?xnKJHFYBxEpB3{V!5CVLAmXbb=^QL3wp23&Le?p-h9F(gfEak%^L2B zKn-02udXhwZ=j4}do%dMF;04mXdx~l2XmqL;<2c!z;T}_+V1_!4w|2u`}Vl(-Q$>f z=d1mjJ7mMSbNMyLxy$N9VD?vIV+MfnRzUdgy{#?ofFBQDc~IWmJl>zLhSTAAwuAQ{ zXhIAP11>JW5LGn4w4rJ>kKK5FdNPCz`Zz;7i^b1=#u4;EOze$_@D6kjRN@t`kXuV7 zlgBj(x#A~uNNMk&f;lO7@_IE;=|eIjyof$~y`PsL^dVEWl!*$1lK2X#$jK1afH#)gM3*73-9*$gtSbb3Eg_>h5^fR zmsRsXTRM4N5in6hJfR9IcVc3>S#QgBR`{dJnyI^D?T|Q>Ak3<3_q?kaQ(DB!0B9nz zpye4Qn%WOU-!0>?;=Czy)&{1>MBKWdzP9^WX_TaDadV8(a&x(^+N-wPjMus5z6PT; zn)NuW8RWOEIZ|$0lv9nS-RI)qvz&26r_Lm|LV*dp!;$0)$AP`(>&S>0gD>7@x}(9x(eJ(+27P@)8I>jF zrvCQD)o*I9n=99t$E?9r zC>Z7#JCl->=@ttgG7O$%YBVO+EL*a48!s9V%XzvKdkIqT`F1R}efJFkW1o-C)!KY6B_VQoFb|l^- z&|aoOj}LZ2QAP&^$%h^fwStgk43uDnlw|e4&h>9>Eh-7&JssUH3F@9#-YfT<76$w& z`hc+l2JaoE%z0Fr2uC??HVhcjXgq=gXf^**iUs;>zAe5zmY6%o1|*@xXG^c%0GOb{ zHV+9j_L}0RF$jm-3kFPpJB9`iF@o7Z%+Q~KfYq<}KmK@WWo31JeIOK_^enQSmAl`lS=n+}(6Z5%Ks#GdlUHE}<{O*i1 zwnW`@x4YBb_}y#HJFABO&R&yB;A>lpi+9)e9~Z9Fwu9i=@oaT6zkrU$Ec{03VXRI~ zVsd~U27od~;%up?a+WZORI#DkuYP#)P$g4BPV`PfFID-!rk%>6QHci$bmcIKm2>b- zfSP0@*m#@v5aw5NwLZP5ouMJiiv7;kn!OnQ2>yT%ewknQ#P8zRf|zQ&V>|cjm1-97;4%fwL4+WoQhvhPOA$cDDIfuG)(l;skc#dWvT{TwM=~fwxNX2?tyN+n z7y~d@)@Thu+ze?md25cnM3i&!+@!DMzU(Mu{gR|Yvs@4_Q>OHa^$e7EQ3XbEws7=- zDRotmidVaSJMga@2LoV&5c(+ z`f{*O+XhiYC}qIoT1be01_or_JkG!@-YiH4R-prL@Zblpmt@?0ntNYJu1bo>I%&Vmi2hUohIrTH!+BIoDOmcaQhN&y!^ zfj1VnPzi_;bg;cy=sz|M`O{Pfq!T$I#p=KR`ZN(ojTPjD1FKJwo}0oi3~5*{vsHp4+Oys!Pk!np|h3ud+kuhV2%#Yh2e& z)F?FKO)+7Z;wgE^NZl@fZT5yzTs~y2ZimeVeTS)>9_F_MWkZ37@g@L49EiCn*9zbH zNhq0+8R_!Ny!qwZm;V@u6A0Xrut;GOJv?BeDQ)hRtto1MQ`)@$)+B?2 z`CI{YSh^slQY&aNJUXZ0np8lS18qLepp}8Sm93QYB4K!)8o289NS`r$mK#ToUcS>8 z>PQ*Diy^cGVX4z7G-x;|yqD`=l3o~-WMplg@r#=$x$w1+D{!kqXalo$3T>hI902%) z?toAJvMQP@_>EelbRg-5w*^B|86lO3-oTi;&n|vPg&iv)&i;NZVE|4zf%$p%{10xh zUcg}5kfFarMHK%6Px8}Y-XLur;TJ<9!>Wb|i$)SvwmQ^V$bP-QWEgO?1KzlWp)sI$ z(Kht57vUasS12Sh;0nv{L)wq#(1I{O$48?EDl~!SLMXUx4jCc}}#&ka>6iPdAqz?dk6K>4h1`xzH8+@7~@&(uT3DcJFs7 z*SdfAl$Tzbn?o9Ow|oE6C)do|fJ+cSV`q(A%Pm9f8AaLJ-0ts31ZH-+YJNSOI#;Xa zw-dssRpp?b>0!kz*5%b9@Z$xPRfM;{{b5N#)9W4kN+FJ4=`GCbsmZBW@O-%iw{kF} zF+y4IB|v_uPA@XI`UfD}kF-NvCC8b@GH>;~-VBZZ5q5R2ZQWsT~h7jbfJO$|Dqv-MDmxE@d_B!f{#2jMv3xqZezl zt~0?h^n-=btEG@_y(shFvETDN@9#)zyH1T#+4?xgx$twI_kBLXcqET;FeQ(vTnc?h zL8emn%+;8)#?3((4vV%p;+1XITYK;c_?G+Bz$VC?A;*CpU~3zY)&ect-+L0qjaw)EY1HfhIzfJzj1u>t(=@4%T^BsOPUeXD?u8KdR@K(nP zc*$Xx1Ywvh!UHat<1spgY<|pgAnOVO_`HS;3)T86s>ml-iWR{;RzsHzM9vGjLBG9U-OgLa zm1sK$&kdi%JhT?h4P3l7aYpvCWiq!kOE+q26Zb}z*xbl+tO&3>g9xjJ7cw_9nU#sD zWIsZL^G?n(uyWb@SM3UzB+n9`a}rj$x4qPy-2ryb&f417J>DVsLIjNsFo>~(=2P#E zQ<+pOPW}AJlkyO;E4P^Zx|xNGr$AyXSpH!fQxD;CQ*mrnMquA`hoLm zbtqZ`12{DqI4>9st8ql8Y_z#u&O25Jt_)!pK$n*R?s41RL!z7{%%iT1Pjd&n;y1s; zNPOQf-f?)F(%`EGByM_395FMGa;~J_BTBEP7r7pukP~=<;;hF`T*5}z60Us0#u==8 zGw9_E`t-6#U*pE^zq6NL2JB9h9Qry23^8;`_&UdwD|d5O6Q%Z?stD(#d)CsJLud!f zwTC*M^m_Ymrh;|=eE#>Zrs!cnmk*|><;hwvW$Lj*76-+Jo8>MFf(w&fWK)(WUv@AI zyy*W^V$f(Ckj_oYuiI=pf?et7sR z{F_wIl~bforaiPomFd#zK@V1~b{U*ajToZCFqkf*U+T@TedE%IZ8i8m;ZR?6i@*Ho zAp9(~jX$&J9V*_7qtQ6zfu}cv=aF{~QXD;W$3x1hU}(pxCkN`NF!UK1B8XYsqd=Kp zM|G4RIR{FuP@G2S?MD6qHnDLKcnOzbawuVP6hiV8bc~`4af6`a{l21{dRt_;N}LaM zd@^GaQyV4AAvBOTN8-e>4WMH^9ogzQFjTkC^b-Kni;1ZNt^Fm0J~)a4uY`7w#-vPM zP&}i2J8TP-2--kYB(~*)F{qiATUQAjO0&3d!SL?2dD9|iGhN@XtK{db9#^Z}Rzr#` znttXzwr4FyjJxtU3gtC0xRHZ%Ny$?~uH6h>=Vbu0akh6SIWSvj%r}NgiL6*~kPPWt zg|fM`A}2lS+LKMMU)F@V$rla$y(Y1;2H%{8XxLP{;SEOSKaxYZ;ooXO&lc@WL$H

=D1#Iv{qg`tAxTGbKF6K89ZODQ2E|Hl)*Ej;$ZiR*1)q`X9Va@wTM z+3@)7A|fm?Q%)+CdeQnB2*=~}?f_5|rb&b6(%XcfEnua2mL%sICpV_-iX0~uE41Ag+u?p@jEf&&$_Dw2<@;K?OuwF^kUaA3F8t)`#c z`}FNc&wQF?Ykc5-+kN+g<9n8LwKX=@dBYu+$35PAF=CeL|p7F>#P=TYzX|-aun!9x&!B0D>JOx1BgJD3tgr;uEnXTS8|-tX&LfKHaey zcch1miViv*klsi?NX*mlTV7slbRs)+U>6=SrUmpm1!G{I3udsfq$#Fpcu>nGxfYh3 z%Zdwf%3s#DmWk1N%|gqU3~8`!^wrp^l^&=lu;p_zvd!~?ac0}sE@;j?;N9Nigji_* zZjeX8q|K6BSzl4M_w^HKd~nl(tXkd}Qiqj zzN(VUoj9KYL8(1*5Y>MEPq!T!o%&6_T~T3@@+Gk&<<6D1BBn!g9m_ne+eM*uo>Z2* z)&%jCfU!#5vNJSbW}PpiH7cA`2#l^P{>qE3wb;eU0q^Td{=kx%7@Amw7OoJm zZbH9v6N6-LYsi42f zK45Hr4SvOHCl)7ClV(+>eF#TMQfW(xwteu#^bhVgY1OjO)0-H8_)i~^8~Z8)qyv~K94rRB zb#!eF8mB#!-LvSvfA{WzA|WvXJ~##s-B{h&*xNu9Gcb5>eGi?yA8xad7aQaoTNGg> z?Zc^uf9CMlomT-9@Lt;Ob_@Ty_qO{@wtxKbFaU4%-DhL!e7x&^iEdrn?ys${ul5i6 zn1ef*z52@P)s5Aw?!K|Qw;>ExD2U_0up%=K6BHOWB(@>Fce3V~Z4Ej#Or9A?i7h$s zwu?dZQd)R9ohjp)Ld~7uO-u>gi~jQCUtby!(?K%v|17Qz2P@S~eHDDZOecz?@N>0x z;c$D;a8P5G95KXeqs(g)j#`ICoI8;uPL?)-nQv^_ki#BbJsoEm$${aQSz&#=WN3jI zfnU)Ep%$qf6C#rxl5fVb&@#3kBMvRHLL@koK@pTYg7VPT$B~fNBw_^Vj?It-pMD=~ z0E$!Xh||WMj?f&ZAn={YPT8@=oD0#E-)!Zyq${v%!k!KB}xzAM!rF*&Z zIhy7#(h!MR|3dCn6wK#Ild&vL@+w2ban!j)2^FT+zHfw9sS809y$QGu>Jl01W5_Sq1CeMB>$lT%y8v)K?y}yJ5z>y?590neQDd z|B*K^;tjB3lHhf;A@tWlfq{faH~s(-)|K0(Qt5{eGipm z%R1)}CtCCocT_rwy47k%K&1pqDJ;;8W%+2y0$ELyyVPM@YJA}Yw)A2xA%qYaoCd}S z?7}M^bT{$evG;kN-}~yQ>D)Nc=h3k*`kd$Ydp@{~M(8AdL+iui(5ktUt3cG|E?th@ z{_d{bU!#wjV7c*EwzeUwV$X!rHuUy@XYk*k;d>*^i1IZDW%wk-d(^%6_O_2zp_otQ`8rvDhjlPf;Xw zaq1!5FOi8~Df5*Dst!K2bsdA9abuebN8YPMG)~jlqo+PdL|n6Hn^qU6+_9$$R9Nv$ zQx3ADaMfUPX;Nui5=5RflXs{30P%a!UVd~jjqJ)HjpzejV(gR$BOK=I}Uv2p0-2% z^r{EwPUsONSPES8stwHB#M!H>8Vy_d=B0NwQY$ACxGx}f|3wO|#EF$p$>B8dx3Sv5 zm&vqNfyRygPd+A0q5kK0M_;CA*BbuHfBNHMIVpeg%~=*LB-AalxB#S**v2r8IdNe| zI|J7!h{gn&dt!jGWk8!xY0fe_5I33Qac0z5)MBRtQ<}>HN7Fnj0tB=i1L<;40UYu{ zC1pC6q#FZqh5r~?)6iD6m>b>Fsfh;9QSYTkk=>D#^*7f`B#X|?^r-uWFpaZqptS&h zFGkQOwFC|hVE+02_us!wGq3s;rj@fXJ!?=4R8FdysA!Aem_{}h-iJx_i~X_Ec|3Jq z@XU8Sc3!Z13%o%TUU=oDI!ci6ov7%jM@1Hf(ds)|bojeyWrQ#U_t-_q;j}5SYEPZa z`j0X$B#xkWzwq&~L5U@U5EPZ_s2za4rj9(U+Ohhe?tlehSlASo81w|sjYI17$0Ncn z*S;GY8!Mv`a+nbf$v7!@??LE6@WlxDk`tGc;vFI}dyDR#Mkye(s34sN{$9DhcJ<0X zHZQa`@6SE=j^m&e#DF+TJ}ey@4x3+Yf9n3IRgSw0ltHt3e7$t%*DLHy-TUr8cRInj%Eb1B&P@$Ce24lW9^gBOM zBo)}lLSf^{GB6W}J^M|`hV8U)aiJYBQ>T1GfuUjFM9DJgE(tbCZTspcRF0KAvwbg) z?)&sfx_*CY46J*bb~@ult`amX zNF(29*z(u+Ett5utSY(Fh>!p3VzJN?%5cxDWXT^M%zx~(s>36>Ie!`eZ))UYMgjA^+(TLx zp4G%lYE6SJ34})e&mG%%TOlkJP8c5i;m=*(fS62FTW1?G=NCplD~v)%O^e+bT?sgFjbLz!0}(*)p?Co>vouwVT3 z({q1k2o~#qfv8Yfsd|9{9Y>}YXPdME;{{EIaJUDX*#8a)%Y&DH>8H!U)x%>cG~Gs` zzK0P#Nyz2wdBNRX;Eh)f45~f=x~D1htVpoh31^eVq}Ma=ud=Z$CVF~yuiU`Z+OJQ& z=4Z}<28TfCH{bf+WrrA!-fa`)p&{)O7hO=+@ z&n>1fvq2Z}k|O~w5}84IZv_0^_Q{Yt){gLnr9*C0u&gJx?ji~jg+ym;2Yhn_D(FX> z7jpME7oVPI{ced>yO{en=fB)uEB^N2)tkV~6?72N^@K=iL~g-tyzGD#AbfU&$d6?z zy@0>Vj{Dwy@ATaf2r#@*9)DGZuJ!Aa$GvPvUoDezrLBPhyPn6AYLnKTs3|Y?=V)1P$lQoBq#y@f- z4=jh&VNNbPZNX64q{Ln#Wfa$NRP*9uTJ#8NIw`vd(BX?pumZhIi*X7V6xqa4QX{Hy zY?z!n;;ibu_G*phJbdAA1ZqZOU5?IE#3b18!!OOO!tw#2h6+A@aFAB#L%V9`c z;0PP>9>Vh}T|Y!q{Y>7X*lb(*RSdFHGjBdL`$?&#vR(fUPdf7Wy=gF(0 z;9B+O`3-4v+fSl7ai%bOKc4{M?O+Q`Sa!GfI}q;w>{d?7sF~jLN9&e1rFMek-2VJC z`5(WCEhyP#B5G{=)0`@i$}>l#e5TeaAw-uI1WnYWq#9Wl3Wao}7ZPN&Au%J8f-68L z$TZio;Rwv=LJzfX69|>0=2?5xl?x`?&K6z+LDE$1n+wk-5wJ=JO+yPRa?+JqeI^*7%7;bpWiG|{Wqtkeescl#2E zU4?Z602x5$zt9^G*O`(vYirl9 zQ>}I7%4cM+08o5^0b~6;V$jwyw!auPJ1%_w?0Lt1xdL|Ir&&UXTc$L>V4y&%~Le$Ly&13E6Zs_SYH$$C)>>>4!i8!H@ZcGDjPi`*`0_!4iuj zvn)lvDVM@0u2^M+E&6cff=|uRyxFoV;vlLj+9)?FSZIc2Rq%MJWh`shES9TZhaizN zZaaj*oh4aB{*D)L6>a-kR7i8=SH*M+6{m_KwwgGL_8JMDN@D@Kkk(@|Foyk+JJSVFKa}#HR}W6u6p39ibTEQZUg1bg!w2!0K@Ybxe`) zdZ>Qh522SVuQDjL!oQZLjBW#?)=NHys_)^|Pn<<+m-?Z%-V^8vX>vQ;USy`;VE1iz zg}tF?sOt;w#e2Kv>Ft=)m!Q}WVHtT-HyfqptKk(2Gv|((d&z3u>0j*HNZGQmI^9(t z6=_i#jl8L|Fi|!cm5G`8IG4a}^&YX|R}`BU&YiHbP*xY)*J{+*@ zj(6Y|3k{N_JpHYsAHx5tAPfTTowtAV(nm~8mO?nE88Wjvh-ljRmL=U%EHq@%4rN;^ z`6J0~u~Cpv+rq$@j-s5)7y-IqR*f{z z&Q4e7Up+MGL7IT!H-3KLBg&evwnWpyx?^^vxQ@adr!}e0;j;rDY&`eX*h4>P9vcoz z|9Q0K0e8!8lJxFuA&uGab|+LK;QL>`nCOe`?Hdn1fB0YvF9HVdtid$|%v|w_&>Np! zXCCu~WV5hFqyL+?=d3k+`_&d2gwdQ_W zm$7(+&8T)4^WpJ?MMw^c$5Y7RfLW{g_wRjwKIAWkgvH`oZr;h`Yl04yAtZUkqiM^D zg8fxEYpKQ|(<&+EIhXwdW#3hh*YC-$q?RBX&sJ>`>nF}qZ>>;BPZ$hVEo7ov44{fL z%iACf*|LqX)I>VFSt$SjAOJ~3K~&1L0+a12ffVddvAvb0JSKLAvd`2=v;rLF!FW;G zyO=osE&EgC{-;<*s-#SvxGI@hgKMr6`6C6InP4!{&M!zfPpcuWdzx1gC9FH~X*jRK zr9gN~quz-ymRft}K|Y2>+W4>Fn3H9S(YzWc4V9+s8*tSt6x|#K_mpK+oQ@>-`UELf zA*~8q`#u$V)u^dnWNSskJdVmXp3Ks$&0F6wG%SeKe(6YaV0+R;<6z+82)G||u+(#J zPAqris%3nH9^NPlW%q+Xb4Md-+XJ#&+X&8O>o69EI;{K-hC>1;KS3sB)Hi#xk!Et= zn=0}hSYD)`NyAAs8bsFKEA)*lX;N7m)@g*AUu_NFRL&&NwP^K6i$3>RksR(0v}dqm z2hq{{_eeM~zKz3n3l$D=4TZ%>`=D0hTz^#&k{U%pygGn)WHI`n0X0_8>`4Y z;ytZf0%kIHW^bV-V#WQ_Q!GJaFW7y=v}XfqQe*ZOvXhWOU@MJrm;t+6DR*GGJ3m1k zVG9!Tn3#J~)eJ3EGAIJN-U2lqw@8U0P9v^zJXRnybn0uPg1dQx>%MYb;mf?t&eKMK z-ECoh+5zu0omlhpr>=~(eKbS;IYk&&Yew17GqgW1H&Si3(;2VS4^c3uFH7;N=&a4uDlm zxJ^)feElw6(5xf;>a8QQ?b~hUUBD9N80PG^k5C_cUAY}sAG3Jr{QYe@z|NoNS`p~) zh2LLz^oa0F%KPx68?b%dxCjyYBl@7_!*a)BVVUbwSFa-r`sv=K4}0lOdgNV(VZ&P0 z?XJ7uju5Xm-46nLNRvr(Y08macU`i!HUUU?F#`rr=-yKQ*cVf zNwKuf=C^SO(I^M8IPCH!aV{h0@ygXuS|8iDi4jr0j0`gi>qo}E%Z1L|VEB@@?3Zgb ze>S(V3{!9(`4O&WxV$)stvw;6V!(cs805v`ko;7PTxQOOxT#>XY_hjdRb$g6iH#(e zJq<4_T1p>)BCq+F32>SCY?gU|Bw%O6TrU!rOPNAFAR_COe7sc6%+y>B18DwbC(HC+ z2GV+yIQKsry^W3K+Mn3H8Gb^gOfSf!hr2f`S@=fSA&TI%@8fk`RKgaEdT@XJ(n{qLV`5cDsg$JW%&`K6Pc4CimkWH04j-#% z`U}cmx3weEV2z|Z64@*AO|vGLyjd>kdhJT}j6>g&AN+dsEuGl>!^eN~dNZcHKvj-* zPx|7)lPeUY0nzTErCMvO1z=`o)t1J!lkdLyj$$@wtR? zvp@U1eYxqVT(j-)w(S6grSlFz)*a!zeViFtC?R0plY^I|*uHT9-JM$h=QD3}-g~+4 zu=ZOeK|0*s^D?vh{@Z;LUkAZ2Zhi2JyI;GbnGSidbs{cLZ?nty&Ye3?zHt8?ZC$-^ z9y&05$ak?+y!Gc7d$%v8GrKcKe}fRNH3n6~i9Md0diLnLcTB-~_4q!6oVTxXBD}rL z;V-!@mYg2mq1zg_8}1iwA6>lo=nj{VanvL1D`5v}d;2kc-M8+(*xS9-+ud!wbrja` zHGnT*xH~&Ra`tie({dQ>P`J&OrnT{eTUt$gO!s4J&OUhkwT)^L$N#Gum#hC*5Fc_n z%GJEmprBOS5Vo4wa!)?^jg4UXEn5TCq*|=#vjc6t=wwwj$Q`rxQGx?wmqhk}4GkL0F)2t;ndx2ZvY`7k0hV6D# zR*gML4(QLU5IiWF>~(E}ZM>>P<#|<2zkb@w)g#YlBUSxUgtkHjMm9#OJu2)J=^&u= z>L^TgNBxlXm}f1^y+v9$^mAN3#YN!0uh8ue3#T{!+V3lcI%H4{^Q6b2fRXuKQ5eV? zr46OLQOJoT_zwHN{b*o=;G2F-YwZeAVYO(W2BW?)QlvRYmeCyf1gw5Rtrj5beQ!_I;vzU&=GKRmP}W6MaHlm*QEg4 z+*eX8bVZB4Onm0lx~?Q@^fRz|B1Hotnid=N+K=Cs32XDvt@Orb_N$NoBE!{~5_9WV z&2p~F5Xe%VjhvII&~sIfJCZB=%w>5X|m+ocB@NV~AHupzAF+!w;LgX4v1 zV)DYm!u-$w*hRSWjO1iyK(D}zg^eVw9j&A()Ms`iIU3wTNpP#R(n^)q;edGdmCg4K z-+o#6{><5PpLUUe<=CwQnI>m1ugutPf=*iblpML#P(NqTqFF$er)0};ZN%0emhriq`#aqb9U?sx#Ru)&c*w(-# z==+~x#dzyakDvVG((dl=%8}!*MYO znH;DkUPpu&0zBczLJ(GSYU(ngDp4Udo_g^5>G|06({dbC;9L#X+N!6&zVl9FR0CTZ z$i{Kbkn`*epKg4puHH|5$)A(M)eFAnKzqH?eZ8_Q<5f8j=0tWXtE9IvvD$xZ+-s4@ ziP)_VTI5y`KSE+8HiRX|8iztxw)jT95oO-YRARnuZ2sV~$I+ykg!Niu)E4wC95h4^ z)7x_3xiUTnM6L$*t0yzc!!|S4!zTW+v6|Wg^lB^_|Hzr_SAMMisDRpiGjH{6ZJ5bY zk)QVVeKfP3VHkxu@6etUlbr)F4t>xDD~zH!^%e2%z^7dS69)rDI0r=TE3*pD=E!d+ zk>twEMPD;NoBDkti?~AZ(Lfu)ju+37`T~aMm_SL@8E=h8=N5H~etOU9`x>0<(hpTv zm_}MVUZ1%(Q=wK|Nh^wz>ToHif;!!fT6_tp4Ih8Lp^5o5yONcNZWz8v-v7pxyn24L-=* zsVnW7@V=X&6eDu{5hnA0u!O#wXPo4Xe z!fJD!oktFdyAuZ~lV*2}$O%^OVz;%8`XjXcj2*jM`!88n{MyESN3X2gjUjOpJ0gZH+@*3Dr1| zO<;$t?%S_%~ zn5Kd3<-)Nz4ULoX;L2X3Fw>JmBgl~skjZ4#M$H9RO})^TA9Az0ZQm%MS~o$YExdF~ zV^OEhk^%aVH1UblIL-8BKxADRGoURp2XbV)vmo55WjBMqDq;nQROXmjfl^j^#a~5a zM1}{}gX&5$l|&o3Qq@keMx^d)x#Bd{akbnU>%~(;81nsKpGb#L9}ayNF2}Y}KXUJZ%-d z(^>SS>A$wEB(#vimbLO}&fogOD9ODEau#a+tFc}vhpB({0W zGBsMUPmLtt#<6cp;2IMQS}jj;^Lg_~Bma?M90^O6C?_k6?GldjJ_Z`8RxKlX*>c z06xvAYOGh~df5AwHD`$h!&|7KAW1A|4HK89`KN&?^p${Y296-3Cl*m=SLRIU)7`{4caRwo0O)Ta*t47A;2;N zUcAjv$sRY4dXpf#?x4q7hRT^-4IZo>c(8_Xa1#j-JXAS-OoD!a3jgel3yZ%;474!X zd53GIx$?N9w=(l|Xg6M-E0x=GtL5?jc*!A5Nkr<=Sx1)LgHJs>BJGv7Kd|3Nf0>xL z{^fIH!4EH7j>5Z$-$3TZ#;?-w*4nZ|+a2MZ?-y?Ucw02$D`-VJZ~zDo)DnzUh_&36 zHl%%NL%M(No3eydZKLt8G&NowAAhp6%K@;spB-`@9O$<1m4lrf2f(5`%gx^47o(v6 zIe1E-8V{8?4#~o#6>DSjv(NXh4mb9PPMs>1+QPeMZXuR6eW z2t0qgFUmcP;%)aq;UC{Pao(p=Y3EOU(73tr#P} zbWekz)-3=la=7GPS%lew(ptWPTC8&Pla>!Pm(ZG|2s!&Jw$IPhUs z!jgk9e9_1p`5~?!_40wg%(P~LIcT$iDY&jl&Up5>^+&~KO3z@ypwg+nkqpgc4M{D` zT`Iy>3#3_8dW%5GX{*B3vcH+Gd5z;4O=8Z^aNVYx4RSsB9q$gzuozh!-R`lbK>rKJ z2E5*i1jMQc}4q6J4f@y)lgAjvG@iWR>t9SviIt6pZNO}4nEgt6}gl;;@SH=Y3dg%~}7 zr)o_=fEGF~C-UF@P|65|=^>u622?^lQt?0ETKW68|MazY5#cOT(+=8&U>HV?U=da( zgm(-Z)h*_9WtTaXIe}-L|8hcH>}Z}9Hi?9hN;XvoU`O@g#fr$AX6_|y zX^lpIv3b$!&N2!lDclM5pNT$rzbyga~(W|I>1nB-7aWa+m@=Q9E+8=%92v6ICj znhBA=fpiXcwt;FSbwsaz<+T?G@Zi@QmmC8|+aSW7W&s{BMbFNI<~qKIgE{f_&X;8m zcC{+qdk$!x9X);U>8HPY02lLP2f7dMIwrDx2)_ID=;&}HNW;650lkMTjt%#}`Hl4( zOE;F5#S68zzIJnIS)!PinF4*l2`nXG;O_^L$J~=W;QQrs^RQo)rbgRy=>3~}BFzmF zo^c?Gvm?F^fu-C*zDdlq%y;(yz&nIlgIguQ{>DA{Py#t5L*ziN=D`}jubx;)tpT=P*I}bd1(YzY8PRas6wDBu}aqRQ(zaH%Aq}R znhvPgzGMlY96@Csbbpzuou>Xl1D_K3Ey(+5tLZHJ*(^{4s`N}ZI|c-5s5AKO3?{lB zxixt?=GJZ&V)cj2I2HTtBd+>b{$w2I2gbfhw&Lp}G7{fNWc$5IoGtdMC0Ro>C=Tam zw0)N#tclJ_W=)FDt2a5(U@E*^O94_7G`NNv+kjZ{G#~4duG*L-9ZN-K>dA?=`_jA4wZQO2 zH_r5jbTL?K3mL{SCG~|e5&lJ<36w&7HEg4)an>gu!SU9i1E_7+tpqrN#$Dlb^ z*ah6{O|oV|Cc!wGtkfE3%yotE$w~gezp@=Q`pRqnhrQY1#S4q?mgdCxEM2#bUrO*~ zX;rFx%JZ{mn0H_^U!D_kTpmXofsBRAju7{seQ~(GaCYI#r&@<_bhr>i(Z=3$T|GM7 z2%_-4b+JP2NDJWR#`gC54Uu`5mv2Y_#xkl9mKj7PS-uH47hRs zx2MZ}WKGFBE`i6(rynlPn=lN1n6;kus)dvmmoT}?bLSeHOO>*Mte4ADRvuRj}FFf?6Ly2%t~ zTfL$FtdrJ)r76}Uw(u1!i_(%SH9S!*SE1&3kOUXF0$Z1cUE6h)EJ)Ryks%pUx=yqG zU7aXLnW8%oi4h)~k%qdin|h5G{FK)Yr!js@j9Qt`N%xaH&IA5{vSg$-B~GJ2{aE0- zDVb?x4yiz2GYvD}a++qWJV=$0rvrwoD5T3-8MD`<)jA!8UbHq`4gkPj&1GPuKa1W$CFEFh zs}glUCj+s~LNxur*ie&h={WXzlU?6Xq`%_{a1!g}x0UE((pEn4z;DgGp5?EO~tzGOWwRCU4sezU)ObExTV^(!g~wZ8{&1I zcvHr~K;9OQTC$NOmB6q5xxvgT0bjwQA{z!BuB}|_edkW@Z!0zJE|N7}`OeaNoAl=H zApxsH@P?&X0yU)4LGTx$7c4Hs+E9o3HRv(|DjNuN?tl;1=-PssTmwaBQ4(;qh>pWy z4gDa9ON*fZFFqb zYV1d6MS%_iQK8j;by8qBh`uL#z%2XK+c9%tRnUvn?}^o!OG)a3#@&4h>F7Hc9(%nz z;&*&U=y_H^ZerjIri(w#=2`s-04xWWe)GCeURgh?G#n9b5RMT#DV{8MzQ(o&giiu? z@rR8J|KscWUfa5_xab&nl&jqru|%LC%&J0Am@OHt@q;B~tVOzaW>mVa*@z|((-?-5 zhb7D|1bbsR0Z*X~dQl8Bp7B)6G^`IxNZA%_gOluG1X>m{mNsb~`fu!eKIfe8y(x4i zzKO1{epnCr=yT5J2ax#}|G4lC0xaGEpS!i$A=Puf-szI6h<2=~A0#}P;7X(t&0i_z ziAsLj^=^jF=kuRGe=upt$T3A*0fV0`UoimOUq2e71@Or*H5zT-B~U$DGrV_ejqE{v zLf|#boec!9Qxp{fsyI1vt>0%?FTwA@&YiuNPflnI+XiUc5F$T)uzfTy2|1RiDKLYi=3h@u=2g%Zl2wAi<52aUr=EMU_1lqh5sKE2TpukMbO=S@xh>)>;NfEwCwR&*i8q&Hq>W z%d6F*`g$E33$4*oy!K_v?Qv0(qnVD_+Old(waku}iV_wj_ff+aIjoU!8#~{kr*X^7 z%w>8k4S))^A-i+{m~6cTc1fTXAXWj448)G?REu)TQ=s%jkQ^%t3~^e@6s&ER3AzD5 zg+m5XA->FKy@Z^kmy?K5S0S+P3HDlvvw0o3l2fMjXCZ)ApxXT3B6p{!4gtWh;VN;B zF<(rjL1F!5WGa&3Gy~d_a@?h4G6sg~2fBz2Y%D)n12ohcEPn@0F(wf|y_k&8p0#z? z25|VQlX_)H?eFpjf$v7rJK-eFjM`aB@eQ`y3jagM~+9 zgk(si*TP}W4axCph&34UY1oPzT-4xVtt*uiC|82`i>K!F0VB)nU%IX$Rfa@`-I+g3 zllS)&LGS9R3s=m?SMzOPcr|?U+C9Nr9WJAcaFMVV2^^|ebDM_Gb$EprIS7kJ z(7r5t=cQ-?i(jU>%y#LpJg+0@`MG(SK%0YMzzgIrTBu0DLQBG)xdCaRQkilqQkIlk zXo(pZVrXoDX*oRmonQU@o4#3ISnIEuFU)nkCg`)7&#_DY=|?Vl&iYn**P2L2u~4AVm( z%yNttCLHOL05;AF!pw;2KrH#lydvT>7rweZMpKbz_0^8uIWsIq`5c~fC4`RZu{=-L$y&dl zxm?mqq`A+`c*WXVT{hTy zq17{osW28zX@$mux|D7~DO0PugC#oZS>g(koQlY_KxRnS$Ifs+A=`8n)gy4%1#yB; zhA}yHY_F?#iw4grJQfB4A#a?S7!w1Qkc=feeolUE8H;r;>!p0gWm`+sjHN7#Myd^Q zDeM3MAOJ~3K~xzp)LM$oL53L*)! zjhhU_iW_Z?lbZV|z#K@CpyX}Hvemzyv?YljALLE<#&z1XoVaU;w>1g9~$#i^c5?G=#pDT;?&edX2<%1fn|$ zn3X@~ds>lq8nk%s-Sh1Q;WQ)y|mvWKTtbU zfA;jrocV8jXfSi_2=sEt@W-A0F`}INH>q8SI4@@`6TRiAiyH*MG=Qd1NTR}ARdgi1 zg?_57PIDYWp@uy#`T;AB&sGK!C z*L>nIzdogJ)L}%PMe{;F-|fPpg?}%04DGFF%sW96`m3lL*LgJv z+S3GPwcl!Vl#GPMo$G}f)|`^CC{{xiZ7+i4O{H`M%_iKGsHTb{!&cZA7jM+zhpZ?b zYID>@u~;l>hLxk`xzcY`L=to4l1(@^xRKYnPD)dwu+O#O7V*$z9usp~l&3sXm#YeR z#b`DiDp&QwSPWGd4V+cC4E#>TroFgZ>XbF=@?`+hRlBDJu~xbohIahSf@m;VVde=L zE$gGv`A8_H_mtobyFlhAWG?LC9tj=_Q@?_hN7-2ACVF|9{RR<-H7A258CW-e7Awb% zHomacN;gqckWO2Yd|z!$sw{W*HXo-72>XG60jyw}w;?J^??l&w}VG*C(+D$uQw6jiIZ_@BN8PHgF&v zo*bfOq2jWjx%a_eZ=Zkjt=|?3x)V*aG73Z9O16~-(@g^f5nv^~3-=8+x(yaf!R&({ zRiJ<_$c7k{m7POCcWG^K5eN;Q+@MAy{xp!~z(|}FzK)1!1HTWeTW~ag_l7f41-kxMZoMYuCz%7O}Lx5f@zQ;z)r$& z-~>ciq_;XP17@-J=5myV#dcqg+(7yUu0d&`7?TVIt}p&1APW*O7dotEyWwT6)%2X; zFG2G(X3^%pz{d9d@>kKtYKy*jja@sKB$P zRrUeL!l1PYFy-i~R)EwIWfeahDXojVJeEPV=V_}@N;~WY@5x;&7ea^Sh`icii6d`e78j#)+||7(d0KSH4cTurtGI5LUtGgeax~%YvNdi4uuW?-5#) zkx=b0JS8%$m=~D|wFlBkK%E+$BytF=Ju34M@Tu>hM3s=vlanhsTnpqWVvK{f#V31}X{&zJvs@#4joUww6w z=I%ZYNuHVlLv+bRL=X)6Sdbj(ihExoFw$Icgk38U5zc6FbS7t-~aJ-eXniZ zcl34-yL-^>WgxHxHwcYtkZDj$MrGP&32Ra#>Ee~zS2K(VgFquQ8+l2HT?h?na12UI z67rH}#bm)Xw$`zRvapt6oPg?dVJ`_TGg+264F4PZem>{(`Cj>9QKCrEPs_wP_ngo9 zoI_vYb~=xB;uJncLfm7RDkl)ug|LylG$2><+iaw+a3EIcbnOHQ&|?mTZ;XvahW+|9 z5suuSUj7@5&)h`VVP_TQ!EA|cm&WI^+3_qQvMBz!(`a`Zh6`uM0nVlNwOMHwguYy@ zk@p#=N%1--0l|}mz&r{zmy@-mx%T$ywsbF4IFNEev}a1h8lPavIgy&nvLVZm;u0dE z=~UrI{qcKMw|v;>5m+(+H|{Y`K9i`T(6re2Nc#}pxGcb z<#zn{+pPiG5aKvyszvzlIu#NjlM3`#2=IlA47{X4e{_*eQ&dF6<|#5`kyd@{eN+K+ z&Eah-W1vQ&($389-sl+KTkZy#saywQ_`itp-ru?ayd@xp9)14)?)|N=Q4m3~(hrDA zuigBNH0J7!8|OAQ&Jo`w%4^u}+WPAHgO?9?zkXzJ_nSZd`)X-uc<-6`w33+O;}C+} z9CtNRM@5%cf@v4HzYz3_y?_M*Dg-9$+7vP3h0nitvRZIO;bp8#Dn?3uPXTa=4O(_u zA=X$r>!Bn^WJ`|g16`4t3s~bt!GZd=lm;tu7i>$ttJ%$(A1$l6QgZ~=TBfpy*brXq zy6TzsH8+Irbdq9R#*>xyy4u_4#-Wg|j&6mH^Ewhi(|gHLv#`3GG)2R=kgIMj1MZP~ z6vszWrJR^%iYdy8Q9FvPKN?qAVTQd~bz%UfBST^FU%|_z@a+iB$~&pT5Wu@xry2#Sg;V=Gz0dK0ZbFgntcg^{LyX=urk)NqlkRipRTLxS1 zM@Zxmv5a1WJo}-b`clCH7JoR!8T^t_I8WKkXf)#74;s>@VYW*1{t!KdC&$~MtCd7r z$F@9xW|Es=0~ed588n-+^-GNsT!uuRYR29KA3B)hg#2~_AAo}>Y1<0r3ykPw&PquF zbzXGqv~(JBf;5Ecbm>a%#0mQ8IqNudUS4*_q)^tFXvamrvuk5eWH zSaXK)=JxjXf}X+J;sTklx&~}I)IHxTHM*Pq2KjvZC_}hyesd?V?M1l9o4NN4lxoEv zGMNqP-a7x0L104P4-EQpDX;m1N$^EVg48a;dxXD(!GP9~c9s&uotdj;4x;2*2s$Ka z1bff7P+%x@S4P11X`jgeuX*ZhEniY>NeFxtAF%DZO?8~${KmS>C@DcEeK5UBmRqXXKA>`nG=h|O*k9ohF$uaH>esUPWp7aZ5h*AZUE`k+}Zckq(S%PuEeNA`^)b$9{z9ao?0*rN`4Zsh!7 ze!g|m6Pn0%1B9R_#Xk&FvBz;$C#}0`UKHc`SrwnP#lRBi*hLiwaB#XuOZDkcih|-A z-j=1qF;CVMN%9ECfmJr7O6*OZ#z1-_PZSPHz&xwO)qIfpEJLVQAL#`QTX#GWr9;~| zT@D&*Xq^nX|cjdK&0!uC0cxAAiXO3pA1)4i66x4i5J3zDQtJ%Cpcbm$E=0 z>L%jlAfk`#vr3_3m&T;zB4%fCnq!)q;FM{^Me?vXfubV{!l2xZL{rnN67W*dT(=^+ zGT)z4nL5ROX}X;a&uKAj=h4@Y;H0c39}jTW1{<)Mh8qBHrqPE;z`V`N$LLn#&@3@K zV|A)22L&lqD&@Hbi9Sh%a!BadVf+fsfE_~Jv*gAwKMf8avO4~EFMU};&<5mX7NXn8 zyh21)D$7;DJp1iX6N3TfP8(`8?<;*A){wUWv-6u(#9tw8gD)4wh-IiSA@d|4nh?19 z_T>gE(7fb3qX}4ZFhY~WOnty)&?3tfH0K$_V9jt22f=aqwNw8$h>`&K%3G8g(eL-W z-G%|(XU`7lpUVq69nu9d=bCXmiAjnFxAg>QTy*^l5fB9r{WoK@C_|7rfy)|D= zvE9#+Q7qVe{Ox%`-G|J4A2ROVUR!6jyYc3tp}OY`;#LF9U%*|`-iJ!Tnx;p|?rH;6`SXSa7kMDHqG# z4m-k&{o)%zkxb+PeajkM1J*(Cr|)|;UrO|n$`Ba`eQ6v*0<%D`@5*0&?!eV7tODDk z=?+Kxk6c;v1u(~^u7U(!h%HM-!v&-?f*#90FZ-$hss%X|AnwhNRAJke{xUm`5dGwf z>TC<;aTLL>sVK7kDW>zR_eODTkZ-R?aiIZvc4PAsr9Qjrb&8N&VJF6sm6d%g5IH09 zR8C~e7IgUPtB(tlR(=@<)F>L^!b)VL5&slXTBybjbZETFm|aiO7!JkQ2!7@Wnlk3Z zjvPt=%t^HNqgble`{+UQI`nOg1Y5LVhngP|f(-!9>qag^r#P;pn~ zQ@VAuIAJzMYzET#QSDml{A8`yyjjS`s?du$veH@|6RYVMb-K14LEO!{AIx{nic^_O zi|(|rhGe~3g222aGz*TawyHW>doktpx-^A@ZK5ISIPO!IPZ8LBSk6`o)sU2jqodW`*YJHWv=UDusGoR0K0DHj%1K9lvaVYRY41bX#G%n~?TG4x3Cc zrCs92U}+o#FgH<9OfS%6(V5nmFj*!~Ra26-IOB>aZIeq8@j3=Hw-dbA#QrTbEW+E2 zh)Q;anGc_?PzV@DWTjIx%*OLnfkf#eoU%#ro2d#((3CtmM#$@oopt2L$#MN3UHS^R zn;jRH%Q#DGzCwB{82PrD^HLrqdXU&LP0p>xwYuyS@z_^(jts!^#!)S{Uoqq5OFma? zg~{6FyO(p7IrI*iUlqO}1D4vY<|eXKF`+1Iqq#{6#fTWuUoNtj2i!|d8*$530`m@!Se;%IM*%@Zb$J%UzBIxUL zJ>b>nTNlJpWnlOA`uduoyEoWQMJltQyo(z&+`V~o?XT;rg9i_HcYk*I$@9lguRYrw zVY`I826mUWw}%ti&GAlVZ*S`A@u~9h<5N@R@BEZUNxyvnZ~iQjt~?sqxrJBEmVc zff_t5E)@JDzAE3^rg&_OIs(;}9o40i5?o;|QlO*0^yP|ISmo$ATI0RgoVAQ(t4KF; zeHD=H@~*>lmdU0cYt(>E0(h}W1C|{c?ph180I}>DIg!O}61SJFnyfKdjJQ5V$c7TT z?ijruP+PrM?y|37@5Ej&XH*r|Sjkz@lQkU@wyD{8OG#FjJiTTCT=#*I7j-1fO6!P_ zDQSbTq#)4nYpV)}s5qD%Nt2ZNp)lsAI@cBM9$L$@7uOWs}2{v7^~uj_kl>pa7!yU{MBiZQWRpiBrXMy9d&$f)3DmL?M|`VrS)N%SVdprIR+ zwS_Irz6k4RaR#cP4Pg-6FjkYLuDh)(-MTdiA}+Wyj8a(eMM$$IFhUt)|H8iKdEfUt z$Au*#wtOTXB_Y;xp7(uzsN<+D92m}BrP?}zrop$~mJP3Xj2uv==XP6AR{Vo^8Eqy0o#g(b zd-opgGa5OYoH@*f#ih}dSdS2XMQL%E>_W;U?L$QAq=26+j>$sv#wn#EFfYO_!Y>0R zTZBc{ERdomrJF%zRG~_(vm&0BwxqlSc4Q?)S`15|#S#XR&sx4li*sidJHVe*6ARLW z<|p?bhiX7>iEY?))hubi-+%7Z!Wjv{k{uF09pg_(`P;92Xzt&s zesgX{X)YNtMOUyPaY5YYoO)2CGOMXjjoglB+hQ}apbatkBJp|FzMka`2t2#sZW(t6 zzh`GppM0@j>@L=3D1Tnm42~HJq6x1Kcf*<eF^m6Z}wsB+^bI&TM`?|t-J!ASt|F4b3Hah`n1qT1!+}b=~A;aYlsDefs)qZh$-r-!eS)~@a z!sYATt;@R(cQH?PpnKzIS3q|$YIYcW#n`T+yWH-6a{t7Gop56#0$t+nWRk4y&+Rk^ zg~DNB`nBn$`RU`w9q%m=df__WaTgqw6%4;o(uh1vbVm(y+zO8|u%9n5q0`~AdlC{$ zaMc1~+pVvjTTlhEf@!8F8YL<51&xy|$f%@O!jseUpQ=@5*MG zF%?>wq_s;KqoHzI6)koY7A9;m#g;OpqGxQu0XN0>cVszcukg{4-1HzM<__d6Q^v}>vJAt>9GKcS^b^9n+Evi!Q>Nv(>dJsURF)|VE^0{U9`Cv6EfBKFkR zTXl6vylg(+7^)g)_T9bKYY^e!a-^#|XSt7UBi>S!)X^odxqMS*>BUIg0xra7M5?>p zjy3ICV{bd)Z9z_isu81Ci+QLq~tJ9OJqpH(w}ruRZ^*0qsP2EM&9N&Byt2Hmka2 z20&{E5;nBSymTr^-i9SV=VfP%{jH>6Wu;_+rwZxr&9c2WpVU-m37l+EGTjnd9FqLD zB-x6W4U!B^y))u9T6r-iQ`SW#bdBjAa-aLeNU)|&v*b|B!dbN_)i_0mx|?og z66XO#SiNH;z?>3^bOS$PPhIJJYv?*c7<6~h&{+By!jRR!Mc-K{5m@vr zaT|R8$qe|1*PcbaeRDW^d@q9De+vNT9LZ}s?uT?N7=h71;2?O2I-pUm@cB#J{_c_j zixg{F>)7#CRKg7|vXxHKbTuTbDOCxdy)e%Y(aj z)@pa|%*Y6u6nI!F3`^BY^_AVLS5KZ?y>jx#>MA|FH?ZCP^L1os92~s$@uzoheRBV^ z2ZxUCu0`A3pKh#8+^t)iE6%~wTs?7kxb)h22cy+oH8-BmRnY((K;yrAm>X3J)xiid zD|`uWFLEaF`tD-I{pH8dMURnsRYm%WvMYpODkYG;~6u9JQC)p^<55voYphX#L9%mS8;63Zoo1}%a}fkJgcl^JE3%2 zz*-xKGV!Wi(=M|)LCSqH8tj;kw+<;AwneLz9mM=a>4YcLJxP^BT2`;8759p#|>diOXcX!Y)lm6~nwlFZL=?LZqOhWN-w27u*xbj>4aN z>+%jE7YM--^>c7c^<0Xx>j^{Pz%CXD!tz@3Rukw21ly2wJ?mxA%h3+D{hTj6uqNMS z<&$hah?cIRfnL^S@N&x5%AI(1FWByL9UnubdtiHxG2o-#BWp)UofG?yJ|Z*eBbi!W z?(B<+I;n=`adaB0WtIk`hV62<)!FOWX`?QBX?+Q;?qwRYtbsWXPNfnzd&Bh@+c z`%QthO-d}Sz8WW~eP)ZR()FQ$b?!8N8FKES*2MBuERuoo7E%J`4pfQRxtpC==iFVm?OD24>J$ zGD{>E9l&`Re$y!|B@8VSfF-2|ky#sIjjhHl#(^Ov8kL1%R&qF!$b_ziC}X%lvjOCa z$5aRjw?O(wm;Oo{FgCvfj-gRJXoX0SJu3juX=Tz}5nzqIa9@2&&nz3*E*ReOjv%s# zofnJ;XK*+(3-D#k@2b02Lh^GL(yQ(weMU2k!nrXc=Jd&k!Ok4xS;qg6dgH z02%Dee91kSblC~`(%V4Ym$jkjqAv*KF?RAgAVw7A9%^}iE`c1E5k>jY-N{B+tW6z1 zUSSUAs8VfKhAWO{R{ze>Do1wDp8eg`tJi=1#vcy;_7?}cfBeV&&;I#fe=sq=YjpQc zt=8?%3`+fGrF1wyJ-xJ4b?g;$=IXdK7%>7nhuWuM6Qzp`wi=H{Bgm@U>%j^DVYJixmQtq9n&z&~mu!yKKR$Snhu&O#vYe;2+ zRMe!>8DBnRI%FZs!g$NRKS@Pb0^CHqjGS3SS)#5^h#5&*4LL_HXB3HL16)=ck#yUq z%gQQXhk~AOC8ARg4DrM3U?vxSa65TSd4Sk(GUL z&%X^StG6za>hU)I}o{4&v4jQyU~(ZX3=umKo19z zk4Zn{jl`D3Jr2RwBbSmr)7^LPIONE2gKxC8wJfaE5dpF;gWqU(q6x36raL}3npqo` zP|3Bhj*H_$Xn)quvVVP;i8|hL#Fef$5orO@vSl%MJpbh~Ru;${X6x~kj(9mx-cB*r zS%%6Elee|(ud^+RY5{A!64$P}+f~_B2MR5V;81QXjlB(X7In1dsH19;MLx;^03ZNK zL_t(7|7Az&jDX=hvA{5yY&(vu9nF}O8is~|Hgh|~fW+?u-G$w^v#lHBx+V;Cg> z`x`e2G7vRAdhgz&{r&wU>wojv?pwFQQ@>jI{nw#X%F1e28;?S5;Drw;->TJw;;Jb) zL|=l4nKe0@+GiFQ94Nwzh??3?PTEPcO8Sr0P{D`}!@Dx=zJHCI|7|$TZMak zaO(7h3-%MnpdGykPp7|j=})rCRc1?k6~fyWk#ns$kjSfke}Hm^D3)Ui-3)`N*Xsn> zRUf#q8sogMBF&26D#M3og(}ZF40gyo`{Ne|;J!07B1zy?7dv4?wKbs;QFO!N~Im(S{#7?`vn;=Xdl!@4q4EA%ke8Rs8AqWsLne8-rQsd zAcf9b{S6%G!zHX*`7Bhh58 zJGV4lBJP)%!c}spIR5lE*RSvH?nWM>f4#Z1v%j&i5nJwJyPI_XJr^C_?KkJA=L;w1 z3)9nuYN1dWkKKpqY7Qpo%BWPRG@EnS-&RokgxVwIeKf}_$d;@OR*;vig;2vGo`7Na z00On9ySWn}y2PEa;2?aQLnzk!Pp1}0LNmS-S1GMlACz@3tQGR*vc^Pf?3Iw%jP6(^ zD^fzWxGB~#wsi<5RKq1-nrA5Cldyz9O9P@Aj+A?=RZ4RysaP)ip>sK^8}K7)OQ#~= zRS?c3BGGa>5v#KIJp>}}O8Y_tHSVO->8LM3Mat_quJ&1jJx^zenLex8B+dq{vWrdk zVm2Xh2$Q)69!#nE@NpeIW5I!alVEWWh>a-d1;)y`x%KnxC=m;<9wYF=mDhdHhhxa= zMvnts8wb2ZI2Hs#E&-FejP;SpQ7A^kXJh!F%H^2%*OD&0xN6zzhW^Lb^}V)rp5Zen z=tk;+A&>_k%QuwoJ2Sk&{TKL>#35v@yN!-e$7P*{-ZyN(Qdm5C)3my1XXT?>=+ z1;0ABZ{@!jEt~6C@soYa-XK}Wa(J}g2QuSZ0WiI>4wjz6f&?${vugR+QOYa7seS!M z`J=BvN}Mlmg9zriaJ764N}~yIRg0q1vbb!?9SKcFKwrmKHSa}eq{CbiSSr2pRq;++ z|KjbKR$SiFQ{Z$0Og)xQD6!rI!{~(OC5)G4KCV{BOxI}Qpe8;;Yh}o;s^T&;w0a2> zG@xP3Bbc-t!nipM3>?7NyJnFDWw1Lj1zJ_bdWSWekqhI#{hw zDR9OfxZb2NnyP2Gf0OBG8iTyM#J1HNbu^* zZ!2ALg&OEykCSKRYxv^9o-|p^=P(tPvEUVb_j~{b14g^;L3{XR0RGIuE%UG(`GXS{ z{Lrz%16q|FHh*#F@!?y)<~uMLSM-A-*@sU6HKwDUF&+H&_YR}!rX?&Zd9$MzkR!gti3 zJDi;{1=}67V7~&|86ma8ARb=nHY=nYaf#pmDlU>3S7((Msl3cn}-NSt_$S zg?wLv+`_q5>=D{$H(RffYK!DdYMIxzC0SIzi%$5|ow8Q^8c68tFpOO+bN;wUib7mIisZofBmS`FPteoXdx^`d9oI{(z9ki5A z1x|c{IaX>**i1Kkrn86BbmRrkmUS_(M6A$r6fo86whS<{bd3RNbb4e9*+Lo&yV=`@ z*0VnE`6vx~YU1ah;NvMdAs%6U>+xKfR0CgDM9@778{E_&d60@<8Q-uOY5(u&ZN2O8th{RZHj3z z-qFR2V8v*gIwJ%G3s!q&e(b@0$8tAwd^od>TO{yGM1(&wM8 zGU=+gp6z_O>P6;8@hliG#?R~Mk9F5TgH|QK#$qNF!mNC0&IEAwj}l- zSq$Zv5@}4N0mi@l)^mNpgLmI)!_M0HDh7PJ-G%X|GTcH`hvRtj17tE{FS<4CcK>(( z;UN~jY!mz)>JSbs(;4X)4>3_@)q?UMca0CT17Vl(%=h)Rd#C>S@Y=Pzw{G1+X2#3c zY1h5^!RL?vy}h@ce^5XDn&X@^hrC+{4m&%5;I&7O_D)!LvEALSCho~kr|ow4v}5Uw z-=8|&>DD^#)UJE=P+35}?4DD1AzioQsauP!E+RD0HVkc71#L#CqNr>QD|3g%TaY@p zx7fqb#+cfHv_t554U`-PCHI?|F}`!*ev=1{ZmqFEbXMih-zltxC5b1qU} zBz$I7p^bw{f^%^wD9ptcv#iXFT%4skTfvZq*@~)Si9*o|4_ekfAZ1o7SM(mIxaj+h zQsh)o#;o`&W}UiO*p+n&1|;{(SA}`xg2~AK?sk?< zM}oSE_tDZ~wBrkovYbdyfFrBk^*CuPGs-606SgY^2M}(`M#WMkN205xaJP0Z{xs7@ z>or4E3Tt4|b;>w%MAgWHwduWLofj~@q^+=n?&yRfIrRG)aW!{vkVgyC0`1-OX5lnc zHH1QkbZL>i>^{nJBdMPnq=n^Pg>*R!EA`ROL2acevgqz0vN9_q9JhvP5Ujm(`W9&w;W0M@oIBgNP1h zDYW|gfejxC#z*9>qpwz4nb;Qi7lBTpLd9C!y^!+z9TL#*$g6L9brSFUDMM5sX7N83S zv_t4(3>h?t@VTpGz+-Bh$JAQY4QT23b;z5H&*(bZkGTESXZV%y^^bo1JQ3C_{j1*w zpPLRBUjpF&JZ%qe&m7i3f(6wtL`djGssX3kjkW_|USKq`6souG*albuks*qC*FGK^ z5K9>C4mx~%c=x?)@7=t4>-t~*zzb!}$f<&!>VwB0|7-hFa-6Tf-oejA>T;Vc#qQEH z*xftcJ}x&=(YUsPGUM(+=QYQ7Pjwx-&Ks3^w>E27lruES?HW?P+$)Pl1LEcx2z6z? zIH)Wdi)m$uvlf6~p|Ga#?)cl4d3!dSVG>_sFcu8bTMdrI-NV9adhST_R%HufX*iM` z1KwP>$!|-cld;7|s;yq>&z9&I3L2EF(JE$rM=jZeZ9y9npZT4p)~x{4v86QUywHor zq=`+W$%DzSL#9^F>K8H;HlZK}Kv=;Z}%< zG7`L05FApHvjMX4SL3vklEqn_sQfk3%Xx3f0GQ+9F!c2a&UQm?l7(kQlMJ3CFI@IB zX${azLhgu?W%sdz$04ni?RkAIfEZ`6f;$t_^}4IHWBz z!I^;^1s{WD^++Mv**lc{$hi=Vyjj-Ore#5A60gux#9MIcNHCs`g3l=P6e-(TG}!#S zMq%Am8$SE0kd-aSkW>iy%xUV|d9er9tQkQdgAhO|R}fHA18qyR8Vm}38zhq~J02^e zF5)Nq;=uiZHv*$c&^Et)iM95b5?LsOR--iJNfJG|#ywIZM=Gz8tiWWy1mM&(R{ShU zR^R->{n5x@H?lZr-1tWNgL_qujA7fsTaOkavc$FVY@9#;*B@%kT=u-SOhFX4woOZt z6wX2!EketjWhG}JUXoHNdXN&<93}al;b9`hbJceNCrW-+S@3aQks4K|TM|@dDXt>d z67-j)O!5#Xy?kCjme@|)RK6*$i_vwDD`EH0*sWAmO(EsiI;KaV7>Wy(rvMe(9gZouk}7&A<~y7Mu+^T+7gWj`S7z`KuknN;=LKhZ;U6BeRhF(A@i&eFSk?z+1gQsz%k zh=5)0_W0CG4aYCLLq|d#elq>y%=Y&2gXW|0+6w06wfXICr_()MsZ}~i@T%b83IMV; zb!Xre#BApNnbi=lf#>A7tmC$GU~RiLt2p?awP)CL!&HRK>qXnqT)2B1H3e)S`FY5> zHD=6U#vS*qJICFx`)O!VKA2S;mZLLx@zRYKUtP5*N8134?OH@eQJSoYht!-8UAD*$ z^9Z-p)@$)s+#9zzL=MdhIo~qWD*C)EDW&3;HThZHZ!ttg+8Hv=`gixxd}p8E>T1MY zJh=dlC%F@Ke=PyCC%x_gL{^4N?~#w_hzY$AKQHZwgSAb!sCzR!=0O>lJj=;#??mXvrtFe4!daGUDRmFK*u=3Lx;(AW78`}THfd6Vt9L_}gb`U9taX8*&BU_k z+*bDzqm~JNk?mnfEK8xpLuZ^pn3yJ(;U>k*8YbCRL{_;~Th_gTmV(7?J9rPZw#d-i zOlZ|tw!BF7RZXXImIz8o;t)Hq^6F5I3hQk$7fYAMglgK5B%=e*xe)%~7IjtVQ!v!` z-o1Ugj10w1&u^c5vr!Pk&{P_B3;*1_e(`v|PYITkD=-#v%E@$BLM5xE#)OMknM=!u za8=at%KRFS=SeiX(i;e_ONbZVOCNAaH_W_JL#EIA-KyxEp`XHUn2d3R@XA56WOazr zniUKbO`C&Lu`ibzC;%q!6)Clhpat5ijKl)d2e4Q1&tXm&Zm*ou1RrmpX@U4JYkoX_ z<;q>z<&N@FiL_Lq$Qc?e=3eC+8V$`)X-a}+IEn4p5dfyU2qS2!uBdfxt&;-_{l(WS zR6gf|7DYEe<2OzkRIM^|l1txJgg~!K@MK@YI7&>T1{ym77QSYI1AM}jZ#{Pe{o@l? zelkR`v0oGbK0G{p^5m%%VPODUgw( zP)ozr&D{V;;(k7lRdl&{{5UbSNP6u1b-z9aT`xljRfCteL%NF*bJ1|(QEYA=kmKAj zOm{1eM`c6ox4>UJamPILYvXZ^o+nJ1I{@Hf-8bi96cEDd{Oq<$@t4$B|1}n}A{M!J50A)kH|!R-X%$(&pUhYCv+TX_oNj1e&!M zA+RH58vsH#Qp#2$36W(ahtv;QWEJsqPFev61Z)eeI(5!!lviLgt7y*+1gN>M_FPAx zmMNTXdUBw;b@Ws^c9jcC?RqSQ=EGv4wU_q3EsoP>|thFx!lLF?0Jb1w#2 zwJ#-NE0-Ec+KRz&D(iVOh9cp}o;oFTr)%?ih`Y$nJC&OA67J12yg4;Cy6eb}SeW&k znw5BE=4eD2mnRv`45OXL7I$%Cs{HU5=!mHO}5$?!LvaU*HU^RD$Kk+w>okVIU8>bLoH z9saWL0CCV9OWU$voAW#q2@O{g4>xu1i$BcscFA^k37AZmY-(IH%|~=Ig%Y7b^Kpc8 zRb3ScAaf!u$WCZ)A_V$^E{5A;8gA;MSTZOjs)OJD?j1^|pbGx%-FGR%di+0j<(8H= zkKG)m(S#u8*lMZ&Vrt=yU;X^gKRWl1TNn58)xKn2ab67I)A{e!V|fEtixRb5(#0;# z!{&_B>>TWN#j6Ce*|q4*&jMNoWk1}Vf>k$!Ka1YPI_EaYIgH`jZKNv3Xy0AN;lKj|63F1W?S*$MrZKL&IDKyy7oq03F(^(Gb|Z zY$!4bGZL*u9!Odi8S_AVy)Yhm zS%y4jH9=r<(9w!+kF#s4z%ii;K~K%SKvKU zm@BN2={Qlov~vx9WW293)oWywWrvOmpjA3wbFII?i}A3(|Z|+hI1)$&_q`xt zl+CsniP;WJ%#Ca+B^^rUVdjT-q;c0k(PO3yg3uI%PcH4eedJDs0agWOWA%R-thdaa z;i+t{^=kCBw>NLz-YLfohB}wn`Uh#&>XFxOm8Lg;Hs8%}{&aYqh+5Dz=&o9UMMqV# zny#)bWni%aE~bryGzBZ93Qrb;5^Ia-N0z9`lH^5;5UixBmwbL&X62IA!L&)4hRfxc z8j?;+t`?TRWaAA+P&Xu6y1*5=xxmOUVEJ#!J=?(6m71SWUp;@v0BI+$0<6lAQCHFg zJf!k!z9Ng?VTaLJ6hRxF+_Cx4OSew6)`7h1xt3;MQQy3UqgJWtU#KVJm`7Q-v$QK>`THKi_hNyzjfu! zBDbm>K_43Iefq^0Pl&$;fPqs;$zrZkG42d&BV=H~9&Dfx04%FsgR^H3Y%zjuLqJZ| zJAb`)iMVSpw*}ypc;=NAmfl}`XZMBw{_Fn92M-^9@CXT!t5ay0ou71J3pL^);4b#rdn%yWW3Y*Ex$=GSaT9u?l2_mzIJBiM+G0wBo=$W!1jgnMvlB1ihS7C<7O0b5P zSak;pJyn5K%I0^Vlhjiiv4W+e!?M#=G=<<3-1*WfUCB($|34no~?N~hT&AZ88!B|#Hin*-A+&AaMW~KmCBK=rgK6Q`)(4E|v~5-;scTz|OBY=3b7;9H zMb&Q1Os%mZY$%T3wnb6|Q8leRE24s0kX8|z%?Z+(5Y8x`3FILkHk*pN5naP-K#~Bg zOxUyxmy&3)AT^s}Zld#u{R;{2Z8oh=s~LUgE*t1qfj|5EtYi4>u>qVuv8i(B#go_j zjkL~w8(&|)d-wLaU%%W7*B5dSBIQ<2^uGPa?W?yJm**+dGPH5|``rfG5NI%!pv>S*aZIxXm9gk$2?O0oRW=S%BVE!eVChmsLKdx21x7}LJr^1c{H?0f{C4Y< z%ARqr&YvH=XV2x1Y~L2wFUQT|{}sNQXWYhUSXjdRcS(;Me6C}Wjps&9rTi*qZ zoLs?-nJZxgPnvHGIBkaUmx5@Zv!THTna$6M|vO(w-!iz3I88g5C{@)GVJ@@d#M|VH{_)qiu zrRj{8`8U6xPESwM`~CestC#aj9Rqno%ziO7hW{4BU{1zsol%T5W)NCKemekOKp;?* zsEUnlQGm6MEK9#u#}QCpbSoL6TQAqm+3~1cTLw6f{1}NGBfqn3u-2T~DN=uCUZ`B# z13se-k*Os03I1tdkw!*zXN;hb{}Xn-uWj6SSY@R*HVL`QZIU)M7qKd9Dn=xEO7Xx_ zWuoqMiVLw$HG>K-+QcAqFd*gM9M6N51SDVuV$;&8m$C_1)#h zmMDzj^@`4kcUgg?$r_52nO-ItL+^H!NJfzs9S~o6{WgWl8AfJgxSy3B>n@YB?C!YN zv4&uK0-O#Is#YZuTNrkcts!tK=~$rFvR)=r26M*T3S+4N03ZNKL_t)jnwwn~00U(+ z;I=(Y*}y8e4SAO+vslFtS;H`dUQgW%C^5n|RkXj$&^57`J{{zzpWAMV69=FB%-KmH zT@IE9i<7sfx4-lG=)#hp^HOzh{_@3Bm)586Ow4)i%x#~jb*Eog4!-y8JLQw>{kP_} z5I~imKC*r_eIw|LIX4hPFjl|?)mLHp%!#%XAyKu3bumTJ!f1tN-%wKAlDV}A!Q@5{ zY6aaggC0Y}EEDDfkXa;3YYU=)eHxV#1=bJNpcV_PytWO}X@o$^vY=}SOH!eXQ8e^dbpH+%vWJvJ?_3n5h3e`&Vm1Ve>*fQ2 zT`YQq`_{9D44*%rHNUQ3_Mw=?Hu%D;qiVm;qz&X>p%u7gO9%VqYE8Vs{A-n;QNpaT z(B<+=Pk$-{?%doGv>JvL0PuhQJ(C6fuTrTZ9em>vDhMQ*Vk8kz4TEDtgNYCRdY`jq zY2E$VuYU^%k*JtCUzTiUnK&;Yn)!FX#CG?+*Z=bVhaY~h^U+@Q@Zg4Z?uyK+D^XR4 zg~O_3h#fVC2FpZ8Wq{t`+i-DQ8B5cjOqs)>1aXC-)HDh3iUp`CpeU6Ijgo=T5=wcY zRBn{QK?S2_h^1ukJi^yfG6;+Y-y+PwV{@evvNVL;k4u$sZBw?#6%MA&&6GscC4ET4 z%5V+tEKxu=#zW}>7Cp4Nx4nje{{=a?SPD0%k4E#>psSIQNrSEG+cdm{6yj z3fo{$cgOrwSMICnS={i>D5khqw%v!mZ!JZtb+&NtW5V+$7IDloGofIrE z*V3j=!o5>hNtO3WK^>Gcs=+t*UE{9nFUnf_tJ7YX4-)-V?9C{gv_!~DQXQR-*JgLP zfXS5RI14y#c+T7FNHkzIt5F*%i@ye&bBV*(jh-3Em2<;vtAo~Rh7AwRY36%{u#OFi zu+kwwiD{%O#a!^B4XBrmZ@O4hw=vap@UBJpSL7h82>*jTN80sKC zwowL`-HmR|+Kf7ymO&ShLORhHK3j$H$li^{bf{LDSJer0q~TSOw)?7~$6_yr(>BwJ zBB|N#L8pfnBFdb}Hn^{qLhtr$lojX38TJV(^)*0v3t$fT76F$aYnz*2Kz@fole8*f zl?z>T2W+}yNpnvVH_UBZqc@50st#d9VacKFAY@OlL}K+i*JQCA^`5$0K!;#U%}6!$ z_61VGm*09~ty)`X?w>2LN1>4Z#n}nwyKwauTGhqLAbkr-C1u0!6aWj>X*geRJc*Ivt_ETsNd>p z7e|zpl!mkGcIT%B_b}<0A|Ruk*+1tnXN+MK*|iE!!Fp?VT`1OG;4^6 z7@3d(Ez@>7mSLc3i9xH7ZY|ti;?I>7ocW{!KE`wY2?M}HTm!acN}y5n%j`)5u#$u& z;T-wKfXF+P&&w2gI7B4Y)s{HLFBp!wd9-J)DnjN`rP*v0n`_19XwP7p>~fKYX&wgl z#E~nd_wel+fZQ`ww#bf#ai!TXd{lsex{H&in&N7f{|_B_tg8&hJfY&hlyHmgc!&y9w?SdB_fYpi)#zFqkG-UbKASyzx7 zv;D~CX4G}ktU52IRe5fjoOpYcDU0d-&IaW%JIbN1KygnnoN^w-3auhk`^jwf*2{V=*@ajzZ zq^(s*5*?#seF_Ndh-Q#j!>!b<6wL-dXEMoiOg_S>Nmm}LqXVk)B~ zlagM7Fe5Y2CkT$bi&V_EI)mDgCUUe9FKsiN+v*!~&dOVZ`}Oi$rqpddf6Pby)`#!O;4B8XEHm%6RThAZDFLmaO(Td@64^I@2#He zmM`tUz4G+4H{U2S1DYYtUCr2l@wg@-(FMB!w*Mxkp)L}#m=G(SPc(z7pc+eErtY4E&;`s*rX)in#yiT;egMoeEahCn35I^ywCc&{`&0p zJtg?wwFJSa<0mJ6qp=;%Q{3^A!L=XZLXHzVfxGD$G!%=0>K_94B> z0*!Nq6{}L!_v8A~D+>a&k^$XcZVCJC=ljcy&>G@uKLWo1@SmqU3AH7i54~jvQl4ENNAurNRQ) zV6$QTV^KyMqHNf-!TYuGron6^aLDv|vr(k|cQ^p|AA>kc7lZ7U8^yIoXfRzWq6}3= zTZ6f%xsseymd4|eY>=DN$9tN(VVPytx`xpIXU)3?Eb;KC80@J?%d6`+y6*O^bxn@s zcv{k%J)0*SJ4~;5s=_f^SC2FHn>aNolj|O~^oz%vp1f17UkSnK8053_E70(KWU&kRyZl zGWWTy@y`%s(K?J(?==gy3cYQsy+({Qmci!eXQdC=pf9`VQFYKtW1|{e-CuwFRP@~T zGTRjlZR~$@X;PqXNKj5-3@}Bta5>*Rw-|J*D_?r+E7RKa$K}GA=w8s;UixVj`l`vT zJ3)H?*15YY#h^d;%Fgc}^Dka`GmT^nxr3m~rLU-;x-4a2zBAg8FtXMXB-)>(`$3L} zjk#<6PRO}L4hVP4)_j}>zJl-+AG`d|lsb zTlXEkD`WRXLhTSp0u5IzD(NmImRzL^!`779aHU(ft1S}>xo8OVu&hnlJcE_DL0AIn zi`i4mk_VeTn0kBaVDSPbjHTNi`jWTMG^8-{u#Wx<`<`1-n&f>q7k*x z>~lcfL^w1JO4TZx7?^~`f%FG&zF35HhQ5^7cWvb|xb0WsST&(QRy_>DVM)B&p6r&Mi@Or? zdLHZ*W5an?Tw;tI6TkfEmbV5aFMtZIypQ*l635@OFYRP{$$tzlc*{xawEgUJS^k)2Bki-vS>*dnZjA4o7Ar1+71xPh`ASbko(nBB6RZgLS)8QR z_L9!_WHU;pUm^I_YGp2&(A2+D(>-0dQW zqXvV{vu+C&1*hs+Kq;R?iM@BRG^J5?q4v_-`vrwMlD2Z@+b^(UcY&!Dj%4m#z1q9- z)AirHy1oDg+&^ADCc`Xzx-l*k_AcK$N#cd(TX$-;lMnyAzgVzx1uc3dPc9UE$Q3>+ z;z}S~v(5$ijm-0l?Jn5(Zl9-ZPr?On7VF_|Mn!}UgbItao4e&M1=KA^t(*OVx`=Da zwPuYHKDWB=y@MTa3Ee36r?F(F#<2W-?0_Mzq6+Im)09;V+yK_04JoEk2|3Zt3#k~e zjzSx7H9go~y|P3Pu#{E~bQwMg{3QwIT6h(3e~nCdDOeho+e;TKjt_r$9i(@YU4v*M z1nO@3fiomni|d6hu@(Tmj=Ze(rlKjERb^u}fBwb`ZAi(-9}woE*o&~-+kZ_3%@!c= z$Y^ERaX;|Dv_7uaF@>H?mLLA@)~!Fd{|-OFm>CwLhyVKg$>XD=_1(F?d$rx~?iSp2 z#Qm)cX>$vd@u)FFP-KK?NJMKzgw$w^J*)%485XrMqb)issbk?IcOJ{!{;oi4g`T36 z&*K1dd4iUvi95j&80@Tpuxf0oW899}@Hkp=_r>FhW7TnI)_{B1(OF=9iff4xOCIVR zWlJjUkT*WlNeSc)*oQk4{2m;l*I5G02aJH+vlVwTjRwcjB-MeXWCU6kUm%XJ2+mrHgv?WgS(VI@G|ZO0!#r#< z3vSF=aOUjIKAIO;5FN|~O?uguf2>7IdG4L1ESs0e+(x-P*|f-0=0FOWy-F*XPJ{Wz zz={_tmogGdzRFp4kS~cVp7Bn(0G=A_^&DD?X+I9nSviBE17>vv0e~?v*t?twlhqfP zVPPH-`G1{8gE>bqCdHRLoj!yk*q&j{?{f2!LX&DGv>nY6*qc__>*vX9O2_gKI2;Iw zP3~;^t75jqm2Ha4-YjTi;5|si%n6)iT54-0R0;3EVw@8QrzOtH`isPowc+KsSgnKu za~>g%xu*y#tMly%sSho`3Uv5TI%aa?9+6tvlH$+~uWuqtGSSp|O;v*fab6Z4B}RPJ zv<=b2#>&mKJhq&@iReu2F~(cR7N-lzMV<*KE(`>QK^P$+e| zVm+;$c3XXlk8z_l64j2sbAJEE`^$g&ZnJ;Bc+jtY``pjElrA0(MgMdG19|)oHeoz&F&^YJ{*hzArJ*k?4^{U@8v4rZ zzcL8A8K(@JWZ^;;L090!TkgAllLxSqFwP?=t)HRVY#!XC^{A}2g|Y=uI?@|*>r3G? zn6P_AgipG^zWjuqx24j#+cBvx(T-n8I>(jMZv=g0{o)45drRyo8$<)?03C z(Q%N%g^MKS$Q^_}gz>13{cwY2MiWeh(WW4D#!MPAsXB_mdH3C{GQy$2I9eR(XvukT`;1u#{lh-dj%$Uz$QJ4 zM`!N5(pxo-+vd7oUAE=6QmZn!%=#KiC9?pRe1%fGG?!GRBe?Y~2R<63%_4=e-xKrwo)c-*zL!_pIA;b{yI|W!#=|i0IO1Vtb0Nw8J1m76>iO}ph;SCs>;oz_ zq7AYN-u5sjxLILQIQK+>*HkH~GO&b7!%8Jl`Y6cfh0C@s77WfCh;sn+@+xBFwQz21 zoRtbzhE_=Eo@MIyyA?loM!scbDDzPT@skx#Yn6ND_;1B4r+s9{ln5Q}cwKhI&SC1l zsNfruDGw}6!+UdmC4+hv20q+5^DJfNV9W7Haysmb66OOsL}$&6l=ua$UN2{~#NiFr z3>8_faG2S7%`i;Y@0!{Y5?^w72{|E@9qR-v?m3Zl7YtdRVgq-DXeG%_?=hxox<_yD zA$u2;jHO;d8j=nZG#4_jlDcKmXl;ot!pgmG+w@qQY#$YAIaVaO;>;>ikabrJUN5nt z8Vk#B261d#wg%&|6oQ3AZ}vQ`9td*vFjC;&p!kcE7W)w#>OFn*06v^&kDe{CMez7+ z+V3~X0=N|R`<~bW@OQ^M2Mzznj$Rr48rug zO2&&GB=~^a*#EZM7nkrCa!DbA#uzf2SiX2H6X&zU)9cE9AsR&(9`LXe(ZchI^58*gJ=Z){N-)tMo}qK>sL^veWD z!lt`*)B$=&{Mk>byQ|bs0O()PwJ4l^@ z-a7OiBk>AA9$`-GKCZCa5Nllb(~Y882L*%fq$8FOuHcFz8oSGdt%#>hvu_G2tnVXs zDK{qLaec&qOb6vN1cYqi{J(eSwO;NY%HY+$r>0q<8D>rrZwyRarFk=fR2VK5H0~N2 zdYAJW11hH5ek)7ou)T;layv`Y&_JBvRPsU8rj@oXq@nluDhfIedd{pw!;CPO^2A7} zq)KKC8kXlGHjKLxxQE#&*`PYKVXxgB`l9=xjjp|?Xqeai&h`6d*!!G3+M9oTsUWd+ z8U%hf9av|uaoM3ILk5{{YbWpwSD!;$+5*?77AIM8&$crcdj(k4kb8K|dyVi4l5YvU zHNYm~s*Axdode&5kjzoqf#<=T@@@z?&8kEWdWltk8(AE*g=Tr=KAyK0Enbo% zU@EZI)Ha+XnP*r{gQ^m=kc}d3#K28J>OlFDO7bvaRdQ(A7+Mlj?wt6jN-3t8($O>W zs)T2SW9dt2uGB)PkV_F@uYKO`Stypwzyr&uq#yXlCz~zx+24Qq^nZk%&ubg`8OEou z>Ck1g6SivQ0d2LSnJ(?LjU=Ppb&E$RNJT$L+C-zKgbZqDt3yl^vlK(po&u&0$k3Ql z76Qq^J{dyTg`{9-!T8ck554t}TXN~4?Eld3^StkOMxl_hN!Gt)i5&9ydEe*#JXFKK zzjzs-dv~()#CtY6{&=Uu&+~W(AuJ&{(^w8=!3yE!+7@5a`Rs}3y?6cT{nGBG?T@0# zJD;_$Z!?&DbagSTt)G2*RElepuRro?`~3&Bqm#Y3F+u;5nA6}k#r(D)GH7uFQCPdt zC4XZm!({#*lD6duTvArYLpf%`FuM~-Rg-6nm$2|zalSK*Z3*)=GL1F^DF?>*^Xa3n)O#tL7`ZOnBT8dfVqUl zd>XLEcG^y-^Qw`ibC964S`YtJwA~|Cb#iL{qQegV#!|qjV0aN_s*|N`WH1`wq{mpv zdB!ST+%#2F43!7bTnJJa=SBl*UqT@O4M6h0QPtQ|pq~j~2Ir!hVi&t;M^mhJqZq<# zz94P$&ghV&suUUK0j_r2EKW2wx0=n2J_90>QsGhgi=@{qN?C%0jB~_iGA?;=nBn*+ zn&M@*=a6)njN|o2(-e7W@;uCQ&Ee6Z=<_(Of`es#E=W`3?c;xK|D@l`$0|JOQU0^* z+74h1BTF5yenD`RebeZfS^ezv7iEFzeF4PX0|Mm;#< z7cFrnU0ajj+dgbg%0=ImwbA06P9hBqxlevAA)TKRiAnaCD3e7ZI>`@qi&8*|LgSZH zwCdU>1UF}4IIo=#vr*Sw4mnv`q<)oxA6XS>E0AQOe8+jcs3E`7y^{x}WX0W<$-BbHRzzZWaChJ{ae^-{C6O1$2_^E$Y)__=(TQXoJXlFVv9PfW94zarWSh( zxYU&cdt5voTe$Q{wR5D63JjEK)q$8=89+<9g7B&GdtqjmWxort(>CC4Zf-@J1=37v zH1zi#4f;KaDVOxJNb!?$FwAlV`DkB5%@*xEQVO(%Zs;_+D>TaSJ*qU+cPv|EV~6du zx~o8}?;c_L3_E!G;*~LaMxkE5JjGPHv-`C3!LKLB-x8cMGEd%_oBM1-Iw90by8R%Q zvSk&p^NoKRL3{Yb+r512{BH34;JCT@mk5@5@9a^nws+;|^K0u~cKykTw}0z~H$15Y zU;ORnyWjis_Ot!_ai}D$Aswy9e6wIX1i(R8%2q_)>M|hRl-8pmiy26S4k*WhqV}Xm zDPS7fvz#rYvYH*3-KL;9JZ*!(nG(C8n$2NTdZ3JB9tM+OvbK4_aVt0mX_XUOGlT!F zmcO?9T$0TQVv#p#&yhk5qs<#$BVDnV!c1zx|H{mosp;^j+hYLB=0Zb7s z;(GiZcBJk4eOS?yFb{y4SzC_A`?q6!?jNa1VY@9zo&h+k-Tf2jPOr{7hh87^dk{^S!=r9B{9d zLn7toNRE4%eJa~blm@Nz3Rk=@^;2sGc^6!6xvH_M$P7nI9YbE<=NAZQUJ<#rny4(O zRo`)~`szb`qASZSd%epkOk(RCa(hfz7Ats_h?VF!kzujB1jVxNhzqtIfywe0BsPha zxWyJYFBWu*CGnC-Gw^$ z$dNtk9os}RR8|X;h}am7^53Pr)>mqOj-EuJ001BWNklPxSv3k^{%vYYD7H?~XT8@pbh^*5->sVQOisZd<$+q{(b4l8YGiDN-`^6O# znH+s$x0I2kh-L*#Y6mbrcF>o-?@05=BeAje5~-g*n5Rq-@2--z#)7)CG)ai7ES!a0 zso*O~cZud&3yin#NrKA~E62J7HlqH)aR3Oiks#xMPl=>_`Qnu6;iqSwU;WbCf14?2 zFrjOmZ`|C&0Qh8x)u<=MgMlqb5W?gMN4Jwkt?_L0Q6qTt&f4(7=m;7a{@@oY7w=v> zw_p0Ows!WBH{9z!prC%)bGEj&Dt>RH`_U&mkDu+;(@95$%A&v!`Uca`Luou@G+Jqt zH73aLWgTR}hKi;3YSOa+|0*+boG;7cG#HRSSFjIW(D3!gG<@;Hgv zEb1*L(Ru?cbLbC$^nV2S=j}m;81bwBZ9}5DtRm4=O;bT&K_-Ex02E^d&y7HH3PNR_ zn^**xjdhKUOwUNdh%m%PiYepfI5QuO@vd>l2nyE+RUGgRvUC>B7YnFpm2yhV24uM& zXVrMllOu>_yr^e~$VJsNx$`xeM?huFSn{0NX-<`4-cjZRVaIrw6iPJwns1c>@Ihu3 zZ8E<%eq@Lw8Eu|=Hb|$i)kcalWSpzhwyi?WB%%#|Co^2EaHwWrNFxcI;Tese9<1N} zalfY-WLF9pRP$VcSjpZO39FWyN1jQ}VkpaA_9Bv%wDgF$tmnOMONm*&wk9~b*cECA zn359eYRN^DakpjdZqP;~;d@}RT+SE2D&sABQ9sW+CoMleArfF54}_V#P6YIkSh3A7 zck>?rFq!73D~?+%iv@FKZ+nUkU)S+-buN-wMKr78D*xFkWMZrC6LHIK-s)S_3l>?Z zB?hI6^O9wz*WOYYmRz*Nlq>l_n)>PHu`c~yZvK|zSldk6l`pDZ5ep4%cI@p@MITNp ztqs2@QMhVH$0d8ji@TzJJ}WLQD{4t96Ri5$yI#dg9*o2_k8__o%IkecN=8=at5RL? zu~gF!^irs=&n`qr9Zds(rI9P^l8b!yxDVilo&fXdEF@B6R=Owdi?~w^54x5~X*a`t zX=1RfN-lFXN!?YhGm92DSLR+=?}Dh)_h_D_HV~s~lr!LtNIa`BCPg`AEZvoYB#x`~ zG|BFN$3on=HD=SH+$Qx$7FKERm-@0-F8%6Qs^^W^ynOL*h^!G}2wTwn?O%WPe!KSg zW2CT}l8pM@7ZWj%HCelA%b?Mx6KVe)(wlNzJ;XY87>2{z#Yab+S|9hn`NQtFz4_J0 zoxRetVeR?v_c;%qez~*xo9ma)ue!8x--cE<11__hq+!WvlgB)lP^ziT#tb)C zetO9TlZT&6888>TMrj6E1{(`JW!Bjk+yJH+K`atDG$6eqscE1o z*YaP0A7ti_3u(A>jdTpGvmRbVK1@M_s zD4mf1m$2)3apS(D1EHM|q{xR!B~ei^G}{E!kd?M$>>5eccGXClDrt5{HIxoZM0KzW z2_Y<4r5D3O0?MJj8r*~T6bQzY*azTlQi~|A~Izd!O%&(nGo!@2;fzVITDL zKA-m^Fzxkj(xhML`j9LOku0^<-UICG?eT4$734Rg7&t6Dd&3>@6_nPrdo2nDEe105 z`BH0nmdY`8f#CM|x-b$2KDjbjuN`Dtv?Lb1Mx!-#4(jWmNZ6=TEagj$!d>*$!In80 z1Z%S$8(7nn3_sG&g4!n7>ylv4c0|dxujNGgcvkfFl`X-*MT^-GDLpQ2#Afm-+JDR3 z4TVPvCy&itR1`O)yG4Yl#d7&2anTxhtcVWV7c*|Mm{6ClVhfN={e0WIj%~SXeZAIj z#4Ag$@^=L z&FVsqrBMOR)-z~98(`j}i=DzG1wu>2HBu)-T9}l6^Ms0L#}Rm za`f68vs=^V!}lMP%0h)aY~;7Te02V!pI-UhVHCU-I3PZJ^ZlD|Jlz3X-2}m37otAP z-PRo%mZW`dTXjPdL6@pBEOx^%Jhz)l{h$FDo8Jm=O~IF4g@AOMGDb5t8q66XT9w2x zV8t1T`PORk2-Tvamp}cAvS-P#P<5nsLXMj0HR|qDf@Q*I2iCAE<%`AyYAq1qhwpOQ zOy%=o&9UFx^!*Bhds*+G*JDCf#0KDu?#~0=OO_p-H}>WyY#>DJv#G827>uQatdrp! z%izYGs5@6`mK4+MW@zl+`{6dE(fNn1&IV-l`7Qwe$AUO=)q-E$+!qBJ$%BZ-N zygKO&CVli2w2}db!63%cYb9{-Bot8t6JcT^^eyuVyNWvfcmYdO(t<6?!E}!L14x)B zr%Q0l<TiI>m#!wq z&RIuD<57G{Uc3OUmBAPSZMvLV{S}mAlMVj$4yQ4db~nQR5=Wck4L$+jmT}g6kR$!$ z6rVqspp`E-dFw6!*u={{^WoMMvl7;PEfOCldP)+-ESR1}H1~WmTh!YbRO5xr;E2k2 zXBGEab5Z1@Ea?%7!crBbyD>pk+2HGSS>{Ko8Ia;bX<$NT5Zan2%8Zlltp&NN5UyoA zB@9_9kJc~7uh(=7`+UkU+s%cxqoa&>C*m4@Kk&lv&=00V+wa<_xURFU*K4JF1l;=y z-4$2G^>W#P5bl&L0N*(h4%hX-i?gGYNBQ!)0F6jKNw3Tcnn$uWScAd*!QXWvf7n?&Y&*-=PxeITxtS>CjQb z`MseWvnsKdXQxt8LbGI7Z8aPyiP=x0Nm)5Ywhc0w<)%M$a2LOxj=mU9rw`Nn?XF&m zr7I4b?+udsU*7%gdsjwp9!25V*$3WJgpdD zuVeV^JAVbTl3Pg!eS%Fe;y3oVCf?gyIyBCO)O!H$`y*iQ;n5*dux#^t)Z-f1{a8EV zHkeM4z((KT-h9KVhrhqOn5zevZ46lON)WBT0mRL@3K~viM#8!nBkGd|=g^J)#?_zw zAOo(Rze7Y@wsrvc->PJ|1WGmF^5LWxxW-^gO?Mr2b!^hHVn=(y5c`W3iv9pct2mxG zhR88-pAfZh&^AaG?j=~6s?K1tVmK95%-H*4X1&P)v&jZsMohXQKV8u?gf(q~@i3wu zq03%4kpGM=49RIrGO5Wa(wrxp5Cd`hiDTvyhtjJ7p%#~oNwg=YjLm>7OnJ~aHC$F| zH*DqDD6hcg<7Eu3b|+pfk($LSL|hHgmdvYOE%31f|4{dl#Qhb=(10zI{`s#*2O+IQ zMI5w)w4P_8QCMPUxgr=B3a* z-@cG}dR$X#hvk5T%|?!LP!f5Odp8oN{&Tl}8Wn5B9B7sj1Ha#M*ZE ztDMw@1Lp&2{*KL2U}I~RG3_muSyeUd~0CD>@Xam*cAj%I_Nz?1H%b_ z0OSuV&E&>mCh8mg&)2~VpFU;-66mj5kQT~=zRr=f1K|@&vgS6ZrbG)*%Z~(TzW2w2 z==PCiU8xaCS(Fh=8HDx+4v(`V3R@43R2l1@3hTG8DS2|}4M;TlB5#A0!1%2)-1m+o zfiecu*2chf@V&qP5CE^o53V}Y%pLCS0Pw$5iFDZ+Y#du%CKwANa?#s170~mJ^V<62n?*wH??s}W+Xc2Vi*k1slV~|k9UUBT*Z><2;1BbVZeDxVF z7PnUL8cm8k=}tdCg(u1#I8a%zWH|!kj!EIa~<+ zz()Z`q&M%Jzc-2$JXPx%@)?juHjy?pb7Zos2&Uf1Iu}AKQu5IoYH=|1R?vk{jf}jk zsuy`iU95j`zFy5|Nk#}7x7TE4p&)~^_?pZkuFtjbUBJ9>V02d2p<1b{%KYONQuV!_ z-*6|_IUva`ce|P-7oCDyEt^|M>61Yamho6V32SW$Ac4oowKXRd&A~#~x|Je{?ADEt zq8IoqD}+%p=GKJaUY(^YofTv4wcT$$D7;Jl+CFO9T9E4Xa$$T{8ktJ$mLR&0G547U z)q$lsdkJ&3TJ!*$0oW|T$G+#cP+yr($h&yCL!KG@nq{c?Gb=S(#gtj6KCXJ@lZW%P z>U~H%0W!ml*zFYv#P$4VQlRToJxN}PcSJg7rP@uGmS#tzss%%iJ`4e5J!9h zzDuvKy?!K&mE3vc{Yc`-sZFU9&n#LQb5wZP846Z-JOB1SCq+%ey6HGMTwDZElCkn{3}U;N2C$?@qf=JTtkHHfN5trJsf}O-3Y2xwvMY z+;}tKd*FeZ-i-bN7+-ww_&V}7kU+Wb@KpM$9I`9sax5GGFBaxI!kjuM>@pCG#^FW& z)#!*hSOnigP~n;*y^%0jQY@hD0WW;y-XH(w-c*^46deTbo?EX1byk!*lMpvBWj=>8bdu8rcB2yveGzxzV9%jB%5sy{rbE*(?6HzMCGZ+`7_EUL829LantmW?it`Tb zL=OB|%$q~jwOZv#jH+IwXC$mc#H%|S+JF}h<0pu!iXF>#;0>)-j61|vJV7)DE{-Nc zWH+C-29EQt+zqTmcZul(jLrYc*ZI7*m0wZ(k(RzJ^!)ncwX&#MRq1HbRD@XaD8#gu zkg+DxQyYls}PkaKShESJg& zbJkMm{MEMfp>JK(op@j^)mb+~-!ZvjSEeAhXCsx4mk|)4p<{QaV<}f;WNBT3j?ALE z9KE?+=4*EX8$k;C_Q5e%zqkPhv3j=pc03o8bF6}!`JXxA?g&b{Eqz9P9ZzF5U1<@L zgpLlSO;C#mztK!+z=g%-Eie5@JFPns*T{WpEsudI=$$M=on!Dvw|eA&Nx1_?WE3-& z2Vsrh97upN35dN@>hG}_f{TSS5Tzo}Q?8(0CM z;>=>6DT;inxU$BMLbr|)vY^+Rl*j-dYB=m zlzt_I%S79jG7?r|y;pwd4!NPH8)*BHiBRuk1j(YI^Lh!Ux_ZgGPjjFTi=O13S5rok zw$&Ln@8Z7dfHvO&6m^rAU3ac^_zq65^1`CIGQs8(%bJuwsHJ)`rU8ptVaff|3xMhCid<|S8Ewxd^E>tR;yhk>~-31C()bu@LogV~nuMTL`S4cO;9n7E2I`AS~{|wWW}r>vsI#^=JfPUq4&+%8BJNW zt^JwvKWQERswHHLT<_}O!>RU5u^B^oX9N*RNaTiucS}8sku;CrC@G*y1X!98%r5|_ zm>A-aT+oBD489xk5P4qjDEXu&UjhNA)tkRNI5>Iy;Bx=I5#sUn>t0e{xIegXe(SFJ z^wi%v$ED*zdplRU`_s$8YN>bQ;dbq*zt_s8pB{uVr9(iH7uw6m>Z%Zv# zFkQ{GkU6SIJFuB}v4YN;8e|N%9%x2_|M9)|39uJDz62wb1#!GP0mF6FERHyxg7$=- zTNr77}Y_>K$=UwS|Ml28VWE(!{}`wi613Qr%iofYi~5QY=m>Z5fnS zLCp_q-S3W?sZfZ>;ao*kv%libl2{W0NMh8A)iSM2tTs=~{fjRoo?`^??9}`^d;Qj^ zF#XO?f4<*&o_p~l3X{>l+(~@3`}sQd%sd7cul@MHPhZ>+8i&(fnz3F%NngoQxyJji z=&VMHUctJI-|1quwk@7zDZMrEH}`TU5pKXGef9aZo0p)GOO@5*XZw5S?mWD*=;yCr zA4ezV$v^n+oyWPOA9l<)_!uEUz(=vYDWB3+7Mi8DWzjZ=vUJW4&yPErD?{HF8t|z0^HgD06XU5u={@m7&~BG zHI25E2~I}YU!%AJJvILfQ!uSY5JccN8lx3X%wREB8SQ~78i*^{sZ#S|=mDHJl8Ffz zCsgyyvU60P0LNto{N}!S6BqW6Yyx10_iayNu^7KVdex zv5R_OqpM{ecvFy>DgAIk!&8O7;hjKn1+>T&fI)!XYVh0(=%)FO*)`F`fQ{hiWVr1TZK=C<|^OlXb5zTHx*XK+W^9NtuzPvUo<7QMBLo@y_Rw>_-Hhi63BMtQW zLblT9MS|q;E$lh8o+##z1gn*e!IqyPL}&e1yTkVFgdJ%Nipy?24%c;A?73l`=x3Uz zL(dU3>avKALg&HCdJx`aVmUSzjAxU8tVGGq$pnBSboE0MTnd1EfccYcX05@#opR;CD+BRZt= zZc8EwnjZY}MM+T5x!jx6v$NATZ~lGywnQSu^tqeYTDk4LmZWS;rLP9NrN_Un$b?$! zrC*y#^xjACHE$@cf{rMtjHvhaHS(|&OD-I36yp-y`jD=eCT9$9iwyM z75!3;_WiP0w(wgkw={on@YNR=F9e-uxx&&vKm5;B<&!_$-l`S0g5%rUh2GtVMv)iq zZNjR5Z*%&}HbTaYR!M&hJP)<#;Ht4-7MTp^2cnv(lJzOL`Jjr59YVcThogeW^j z5}BfEiL>3Ewy`88MO$oDsV9syxW=~Rkb+Pb*#t^p+dpF8yf6JX`kiy{_l*i6j&U@yW@Nwk%(?gcU?CwMFe>Z3$HlM8py>s+ zdC(|DGEm%FV>vKJ(CzXX_Q8f0n?GA^&wu#&h!f}aW$8QGrXXv3NwX+HehoWbUjji! zP=^6r>l0=f5=ijd8SwtS;~yhTq7eme7(ru7j3{Twg%jpOjwvxR*pmgPXg(N4RA}M5 zonQ)iaxzL1IA>v2Lf!@Uy+OkeSnN?zlS__jt_0at26`MNl5f?ZzFFKt*z{(oKETkJ zUSf066?3g=IG&EtN}Q}tnN`(5|8K*v=}GX^+y#J@M&!&$C($Y7%VP?u zPQz$KQ8lLD3HQ)Z!n6<2$xx8l=8!}w1`qd@|&yIdwwv{{(ey$^E zjm#=o4m@lP7xi7PPFHG;%DI5bmHUz+t0!#uC>d z7NmJBVU)4hjI`xb`2H%$_#|<}7uB&*e55<*%(E~nT zv*YG|@qloBP?Sz1{iu_43QevX2K*OIqXaf@Ji7CtXuz02EsV9^tVSE#2leU?KR$Z@ z)~8=w`&E7E?>|_6_tWM2#_niqbV-*k$<|6R3K|LyaO z@a)ya`GbyBKB4xv2CFbTk!uI6SOh8VV#yrt-RECKZey(h39@B>?Y+GV3b2rYg=j0d zi$)`DWMD(X_A-bs<AqZ+{Q~*YkFbgt+Fv%ohNpOTIFKQE3%@M;PiDTIPBCdnIe^Q!& z01V2fIkFY`aU7psUDgzt_ zz;+<*siLc*?qHc#^H#xTQ1Uu|%}v4PPQvr{vXx_edorLk56h8Y6-XPo|R^#x;#D~Y~J~7 zL*~Wuif+xJu|!56^fg7RsQX`C_!ezql?bs!+T5>Sw!e?FYf?QJ?(PN#$EAa~FYSZo zvIo3+^Ly`}Z#}zqk)G6^Y<}m(UT;=>&^zj%ee!JQY@>9{dxqk(oiA$j>hsN6_q}*r zti9a1Jn!AVd9(M?*|Pa%Aj2Z{WknLySrBRAunT|ic<jN1X`Of2)fL8o7 zBzHvOTh)Cpg;v!rC0A5rjSc8xNxVeyRi{HWR_9{ivkr-$ZK-1*1NIFT`+~ye&}&IY z@LG#T6nw+5;X9uj!n?jCif0mEdVIUvbR|_Gg|5+r)TJQHaAS$TS{DxzZAi0wZ`}cJ z9c^H=Yxv+B81Pdx{}~v~*ofPhqKXKNcx)&kdhHG9tR@ne+z?e0#>gX#tTP5+iBdR} zz~uyXTHr6!sSJ0V5VZ_&J`Kkc)FMENg|`5I4ucVD5I|!gqJlIEPhuw>HUP7ctaD{2 zOr;ldAd$536x|X0i4Der_eL3xz^H>&+zDiG9)nmXtT<-l;#e$6VbEbF2WdKfz#th% zE9TUo!I^U?x-4^JFv+G&zdW5H=W4JpZ5%zZA2lPK2Cz=2JI9!Niu zO=VUtyO_@G%u8Gc->kWy_L3snx=%h4Kv9RLxVqVhgz?JJgmCN_}^3W(7J$8YL!RF&C?eSV|vK ztxb}oO_EXx?~o>6P3+JnK@#Nw#LlT2mPBJE=fuLJCGDB(U!7bJgfjOu5X)w9P<|z? z3?IDEG|4VX7>eJ1^SUnP*jn+{wfOGr^!SVwet5QfwA0&~_4_(z1~UF(k66ttjOMR@ zIeYQb4I#c5-(Ft6nEkDPfS{@aYc1lnw8dAzmoh8@^S}Bkj;`B!!OQmZdY$?%VE*;q z=5;x-Db6D4E)>M?e)jK;(jRZE-h14CcKhMOo2^&MfPrbPIskiS)Uxp1{3orMr#0do!MB?rE39^L1WMPr{7 z82(_IlUnVz`HPB(Xam7J$Iv;G)UL00x7Vw102^>cKcP9U8feB2xW=jTI*76%!BtrZ zBdW4$9?$;qHUJ*pJ=$PFU-%{w7AC=yQG)J15LE$4`I>Rd85opgR&;1kHR=E-4d_K# zX5b9cDCA@WtSnfCRysUQm>LyC6fnV|1f-ixlQF7&CGaC->o1};LPlfJhYLU(3**Gn zIGbkZKbj(bD$7OzOM4S@TDXFM5LP#^yV#I&hG<2sa{$&(F`fo#9Y@)i-MtCOcxLe1 z+!T!292_*zuVj$E1JxGjF=3wg&d3gge?g-)nsDh&XEB&~DA6Ac3D4R91Ex9GZ~2z% zYM0Sai?_6WA)grQD_S(B50#Tj{-p2HnXRC?>^w-4W$8P^lIWb>Hn%0NW4n%3{IsI2 z;ZUhCcf3AhKMF$|H|g2DD?P8EI87J@M*23_ipLhCwOp{Qxmvbr!OP7|HW16!8x=e| z{PhkQ^jyZ!mtt&DGcTlKDZ|tpDh-=dEwlzxxl!`r|5hT4!Nnz}oZi=TVm_xWKP7P!~7{lP)>t%eecV%Rk6o4>sC+ zOIwF`zi4i-ps;$=Q0RE$R`727XU+2lfbSkTPW8dk)@;7WTZk;vz9c#%EA0$ufpVT< z4&5~XtQj1FyKG8eaK;-Cj=K`5fw;-8?IpB@zvihbfSFTjrN-1`&2~e>(n)Xe0w9=w zu?eOUdf_7ZuXus63>GX-r54N=ZA%<7UU=BOMzY%mxz!#*NxstRg|-t%@>QGl42;Uk z#g_|+@RfDH~IM49Q#V2O-zHvF+mZi}5N`-%*X z4c)RVRcEE7uRLU}f%ye1bg>6!W->4vZNCPe1|*8J93T4(nKWe5@0Jm@)$dneZ-T~& zP>Lb7H|UqUjG^-3`JJ#~$pE)Gc7j}K=4qf?(CtDig=H~PDo5pkhl}~{2nk(ST;~S< z1bb`H`hI2L(wS_Ym>}&^(w$XYMT0N2*F$zA<#Lmo$ z<6!O(-rxMiQVP4Jhqj zL;Q|hNw#z_5@Cr>T9&m*+x#o**7Qt-+S-)BV2!o4*mV7`O}vso44DHPU<(mjyh$C~ z@Ee+mBV`pcqGR8>9LL6MS|_YeP_UeiayZgy1>~`+q`CMFI}bYw+8v?72BXJ>U>t5o z)3y~U5vE^Ed39~JWYZ>Y$Z|Acn}HKiBBd&or`^4F7LB>IfrM5wXzBX69tCGHSklHw zC$z`c=4)A*b0Xx>Ha<&K&}7(k{v!yY^>c{Ob+z`YQHU|p28nk9+c<2|HX(tMb!&G5 z_iTMTJF8~UH6gwq;O@>2Q!%;nO)y7ehf?SIj?Sn#@>cn?5M{~EtVxmwAzM_;#8I1M zWg#`ePNn*N;kGv7OSmw$!Q2DOG+MGfIEfBpDVu*fj)PF5o&J>nnIeud%M`1<2hPcr zv)fG8z(BV8>AUT7@BK92SdFV~x3PbwB8(LY90&CS&At*zm0Nqbzqzj)-lB-0W~

-4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. - The progress is shown in the progress bar, next to the _Autotune_ button. +4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates reached during the maneuvers are 75% of the maximum configured roll (`FW_R_RMAX`), pitch (`FW_P_RMAX_NEG`, `FW_P_RMAX_POS`) and yaw (`FW_Y_RMAX`) rates. The progress is shown in the progress bar, next to the _Autotune_ button.
@@ -194,7 +193,7 @@ Increase the [MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_S
-By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification. The target rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. +By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification, corresponding to 75% of the configured maximum roll (`FW_R_RMAX`), pitch (`FW_P_RMAX_NEG`, `FW_P_RMAX_POS`) and yaw (`FW_Y_RMAX`) rates. If the signal-to-noise ratio of the vehicle is low, the system identification algorithm might have issues finding the correct coefficients. Ensure that there is no excessive noise and/or platform vibration. From 73ee098a2571865757ecda0be6090d2a6477e17c Mon Sep 17 00:00:00 2001 From: mahima-yoga Date: Tue, 28 Oct 2025 09:27:37 +0100 Subject: [PATCH 231/812] fw_autotune: continue to next axis in case of convergence timeout --- .../fw_autotune_attitude_control.cpp | 43 ++++++++++++++++--- 1 file changed, 37 insertions(+), 6 deletions(-) diff --git a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp index bfcd857092..48633f3e73 100644 --- a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp +++ b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp @@ -548,16 +548,47 @@ void FwAutotuneAttitudeControl::updateStateMachine(hrt_abstime now) } // In case of convergence timeout - // the identification sequence is aborted immediately + // the identification sequence is aborted and the FSM moves on to the next axis if (_state != state::wait_for_disarm && _state != state::idle && _state != state::fail && _state != state::complete) { - if (now - _state_start_time > 30_s - || (_param_fw_at_man_aux.get() && !_aux_switch_en) - || _start_flight_mode != _nav_state) { - orb_advert_t mavlink_log_pub = nullptr; + + const bool timeout = (now - _state_start_time) > 30_s; + const bool mode_changed = (_start_flight_mode != _nav_state); + const bool aux_switched_off = (_param_fw_at_man_aux.get() && !_aux_switch_en); + + orb_advert_t mavlink_log_pub = nullptr; + + if (mode_changed || aux_switched_off) { + // Abort mavlink_log_critical(&mavlink_log_pub, "Autotune aborted before finishing"); _state = state::fail; - _state_start_time = now; + + } else if (timeout) { + // Skip to next axis + mavlink_log_critical(&mavlink_log_pub, "Autotune axis timeout, skipping to next axis"); + + switch (_state) { + case state::roll_amp_detection: + case state::roll: + _state = state::roll_pause; // proceed to pitch + break; + + case state::pitch_amp_detection: + case state::pitch: + _state = state::pitch_pause; // proceed to yaw + break; + + case state::yaw_amp_detection: + case state::yaw: + _state = state::yaw_pause; // proceed to verification + break; + + default: + _state = state::fail; // safety fallback + break; + } } + + _state_start_time = now; } } From c536120e3d368c8d1ffa7482916e6b1a71caa21e Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Wed, 29 Oct 2025 09:16:54 +1100 Subject: [PATCH 232/812] New Crowdin translations - ko (#25811) Co-authored-by: Crowdin Bot --- docs/ko/SUMMARY.md | 1 + docs/ko/config/_autotune.md | 5 +- .../autopilot_manufacturer_supported.md | 1 + docs/ko/flight_controller/svehicle_e2.md | 177 ++++++++++++++++++ 4 files changed, 181 insertions(+), 3 deletions(-) create mode 100644 docs/ko/flight_controller/svehicle_e2.md diff --git a/docs/ko/SUMMARY.md b/docs/ko/SUMMARY.md index 3f6edca6b1..fc556f5949 100644 --- a/docs/ko/SUMMARY.md +++ b/docs/ko/SUMMARY.md @@ -187,6 +187,7 @@ - [Radiolink PIX6](flight_controller/radiolink_pix6.md) - [Sky-Drones AIRLink](flight_controller/airlink.md) - [SPRacing SPRacingH7EXTREME](flight_controller/spracingh7extreme.md) + - [SVehicle E2](flight_controller/svehicle_e2.md) - [ThePeach FCC-K1](flight_controller/thepeach_k1.md) - [ThePeach FCC-R1](flight_controller/thepeach_r1.md) - [Experimental Autopilots](flight_controller/autopilot_experimental.md) diff --git a/docs/ko/config/_autotune.md b/docs/ko/config/_autotune.md index 5c35b38bfe..ec9ec69753 100644 --- a/docs/ko/config/_autotune.md +++ b/docs/ko/config/_autotune.md @@ -102,8 +102,7 @@ The test steps are:
-4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. - The progress is shown in the progress bar, next to the _Autotune_ button. +4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates reached during the maneuvers are 75% of the maximum configured roll (`FW_R_RMAX`), pitch (`FW_P_RMAX_NEG`, `FW_P_RMAX_POS`) and yaw (`FW_Y_RMAX`) rates. The progress is shown in the progress bar, next to the _Autotune_ button.
@@ -198,7 +197,7 @@ Increase the [MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_S
-By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification. The target rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. +By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification, corresponding to 75% of the configured maximum roll (`FW_R_RMAX`), pitch (`FW_P_RMAX_NEG`, `FW_P_RMAX_POS`) and yaw (`FW_Y_RMAX`) rates. If the signal-to-noise ratio of the vehicle is low, the system identification algorithm might have issues finding the correct coefficients. Ensure that there is no excessive noise and/or platform vibration. diff --git a/docs/ko/flight_controller/autopilot_manufacturer_supported.md b/docs/ko/flight_controller/autopilot_manufacturer_supported.md index e4d997d783..a1b565877e 100644 --- a/docs/ko/flight_controller/autopilot_manufacturer_supported.md +++ b/docs/ko/flight_controller/autopilot_manufacturer_supported.md @@ -35,5 +35,6 @@ This category includes boards that are not fully compliant with the pixhawk stan - [Radiolink PIX6](../flight_controller/radiolink_pix6.md) - [Sky-Drones AIRLink](../flight_controller/airlink.md) - [SPRacing SPRacingH7EXTREME](../flight_controller/spracingh7extreme.md) +- [Svehicle E2](../flight_controller/svehicle_e2.md) - [ThePeach FCC-K1](../flight_controller/thepeach_k1.md) - [ThePeach FCC-R1](../flight_controller/thepeach_r1.md) diff --git a/docs/ko/flight_controller/svehicle_e2.md b/docs/ko/flight_controller/svehicle_e2.md new file mode 100644 index 0000000000..1e010d1aa5 --- /dev/null +++ b/docs/ko/flight_controller/svehicle_e2.md @@ -0,0 +1,177 @@ +# S-Vehicle E2 + +:::warning +PX4 does not manufacture this (or any) autopilot. +::: + +The _E2_ is an advanced autopilot manufactured by S-Vehicle®. + +The autopilot is recommended for commercial system integration, but is also suitable for academic research and any other applications. +It brings you ultimate performance, stability, and reliability in every aspect. + +![SVehicle-E2](../../assets/flight_controller/svehicle_e2/main.png) + +:::info +이 비행 컨트롤러는 [제조업체에서 지원](../flight_controller/autopilot_manufacturer_supported.md)합니다. +::: + +### Processors & Sensors + +- FMU Processor: STM32H753IIK6 + - 32 Bit Arm® Cortex®-M7, 480MHz, 2MB flash memory, 1MB RAM +- IO Processor: STM32F103 + - 32 Bit Arm® Cortex®-M3, 72MHz, 20KB SRAM +- 내장 센서 : + - Accel/Gyro: BMI088 + - Accel/Gyro: ICM-42688-P + - Accel/Gyro: ICM-20649 + - Mag: RM3100 + - Barometer: 2x ICP-20100 + +### 인터페이스 + +- 14x PWM Servo Outputs +- 1x Dedicated R/C Input for Spektrum / DSM and S.Bus +- 1x Analog/PWM RSSI Input +- 2x TELEM Ports (with full flow control) +- 1x UART4 Port +- 2x GPS Ports + - 1x Full GPS plus Safety Switch Port (GPS1) + - 1x Basic GPS Port (with I2C, GPS2) +- 1x USB Port (TYPE-C) +- 1x Ethernet Port + - Transformerless application + - 100Mbps +- 3x I2C Bus Ports +- 1x SPI Bus + - 1x Chip Select Line + - 1x Data Ready Line + - 1x SPI Reset Line +- 2x CAN Ports +- 3x Power Input Ports + - ADC Power Input + - I2C Power Input + - DroneCAN/UAVCAN Power Input +- 2x AD Ports + - Analog Input (3.3V) + - Analog Input (6.6V - not supported by PX4) +- 1x Dedicated Debug Port + - FMU Debug + +## Purchase Channels + +Order from [S-Vehicle](https://svehicle.cn/). + +## 무선 조종 + +A Radio Control (RC) system is required if you want to manually control your vehicle (PX4 does not require a radio system for autonomous flight modes). + +기체와 조종자가 통신하기 위하여 송신기와 수신기를 바인딩하여야 합니다. +송신기와 수신기의 매뉴얼을 참고하십시오. + +Spektrum/DSM receivers connect to the DSM/SBUS RC input. +PPM or SBUS receivers connect to the RC IN input port. +CRSF receiver must be wired to a spare port (UART) on the Flight Controller. Then you can bind the transmitter and receiver together. + +## 시리얼 포트 매핑 + +| UART | 장치 | 포트 | +| ------ | ---------- | -------- | +| USART1 | /dev/ttyS0 | GPS | +| USART2 | /dev/ttyS1 | TELEM3 | +| USART3 | /dev/ttyS2 | 디버그 콘솔 | +| UART4 | /dev/ttyS3 | UART4 | +| UART5 | /dev/ttyS4 | TELEM2 | +| USART6 | /dev/ttyS5 | PX4IO/RC | +| UART7 | /dev/ttyS6 | TELEM1 | +| UART8 | /dev/ttyS7 | GPS2 | + +## PWM Output + +The E2-Plus flight controller supports up to 14 PWM outputs. +The first 8 outputs (labelled M1 to M8) are controlled by a dedicated STM32F103 IOMCU controller. +The remaining 6 outputs (labelled 9 to 14) are the "auxiliary" outputs. +These are directly attached to the STM32H753 FMU controller . + +The 14 PWM outputs are: + +M1 - M8 are connected to the IOMCU +A1 - A6 are connected to the FMU + +M1 - M8 support DShot and are in 3 groups: + +- M1, M2 in group 1 +- M3, M4 in group 2 +- M5, M6, M7, M8 in group 3 + +The 6 FMU PWM outputs are in 2 groups: + +A1 - A4 are in one group. +A5, A6 are in a 2nd group. + +Channels within the same group need to use the same output rate. +If any channel in a group uses DShot then all channels in the group need to use DShot. + +### Electrical data + +- Voltage Ratings: + - Max input voltage: 5.7V + - USB Power Input: 4.75\~5.25V + - Servo Rail Input: 0\~9.9V +- Current Ratings: + - TELEM1 and GPS2 combined output current limiter: 1.5A + - All other port combined output current limiter: 1.5A + +## Battery Monitoring + +The board has connectors for 3 power monitors. + +- POWER1 -- ADC +- POWER2 -- DroneCAN +- POWER3 -- I2C + +The board is configure by default for a analog power monitor, and also has DroneCAN power monitor and I2C defaults configured which is enabled. + +The default PDB included with the E2+ is analog and must be connected to `POWER1`. + +## 펌웨어 빌드 + +To [build PX4](../dev_setup/building_px4.md) for this target, execute: + +```sh +make svehicle_e2_default +``` + +## 디버그 포트 + +The [PX4 System Console](../debug/system_console.md) and [SWD Interface](../debug/swd_debug.md) operate on the **FMU Debug** port. + +| 핀 | 신호 | 전압 | +| ------------------------- | ------------------------------- | --------------------- | +| 1(red) | 5V+ | +5V | +| 2 (흑) | DEBUG TX(출력) | +3.3V | +| 3 (흑) | DEBUG TX(입력) | +3.3V | +| 4 (흑) | FMU_SWDIO | +3.3V | +| 5 (흑) | FMU_SWCLK | +3.3V | +| 6 (흑) | GND | GND | + +For information about using this port see: + +- [SWD Debug Port](../debug/swd_debug.md) +- [PX4 System Console](../debug/system_console.md) (Note, the FMU console maps to USART3). +- All ports use GH1.25 ,power ports use ports on E2 uses the 6 circuit [2.00mm Pitch CLIK-Mate Wire-to-Board PCB Receptacle](https://www.molex.com/en-us/products/part-detail/5024430670). + +## 핀배열 + +![SVehicle-E2 Top Down Photo](../../assets/flight_controller/svehicle_e2/top.png) + +![SVehicle-E2 Bottom Photo](../../assets/flight_controller/svehicle_e2/back.jpeg) + +![SVehicle-E2 left Photo](../../assets/flight_controller/svehicle_e2/left.png) + +![SVehicle-E2 right Photo](../../assets/flight_controller/svehicle_e2/right.png) + +## 지원 플랫폼 및 기체 + +Any multirotor/airplane/rover or boat that can be controlled using normal RC servos or Futaba S-Bus servos. +The complete set of supported configurations can be found in the [Airframe Reference](../airframes/airframe_reference.md). From 99965337f1d666fe9273eb5c59d57eeb8bf0d433 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Wed, 29 Oct 2025 09:22:59 +1100 Subject: [PATCH 233/812] New Crowdin translations - zh-CN (#25813) Co-authored-by: Crowdin Bot --- docs/zh/SUMMARY.md | 1 + docs/zh/config/_autotune.md | 5 +- .../autopilot_manufacturer_supported.md | 1 + docs/zh/flight_controller/svehicle_e2.md | 176 ++++++++++++++++++ 4 files changed, 180 insertions(+), 3 deletions(-) create mode 100644 docs/zh/flight_controller/svehicle_e2.md diff --git a/docs/zh/SUMMARY.md b/docs/zh/SUMMARY.md index 44eb72121e..570c6aa5db 100644 --- a/docs/zh/SUMMARY.md +++ b/docs/zh/SUMMARY.md @@ -187,6 +187,7 @@ - [Radiolink PIX6](flight_controller/radiolink_pix6.md) - [Sky-Drones AIRLink](flight_controller/airlink.md) - [SPRacing SPRacingH7EXTREME](flight_controller/spracingh7extreme.md) + - [SVehicle E2](flight_controller/svehicle_e2.md) - [ThePeach FCC-K1](flight_controller/thepeach_k1.md) - [ThePeach FCC-R1](flight_controller/thepeach_r1.md) - [Experimental Autopilots](flight_controller/autopilot_experimental.md) diff --git a/docs/zh/config/_autotune.md b/docs/zh/config/_autotune.md index 6a75da6380..c9e2b5bfee 100644 --- a/docs/zh/config/_autotune.md +++ b/docs/zh/config/_autotune.md @@ -102,8 +102,7 @@ The test steps are:
-4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. - The progress is shown in the progress bar, next to the _Autotune_ button. +4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates reached during the maneuvers are 75% of the maximum configured roll (`FW_R_RMAX`), pitch (`FW_P_RMAX_NEG`, `FW_P_RMAX_POS`) and yaw (`FW_Y_RMAX`) rates. The progress is shown in the progress bar, next to the _Autotune_ button.
@@ -198,7 +197,7 @@ Increase the [MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_S
-By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification. The target rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. +By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification, corresponding to 75% of the configured maximum roll (`FW_R_RMAX`), pitch (`FW_P_RMAX_NEG`, `FW_P_RMAX_POS`) and yaw (`FW_Y_RMAX`) rates. If the signal-to-noise ratio of the vehicle is low, the system identification algorithm might have issues finding the correct coefficients. Ensure that there is no excessive noise and/or platform vibration. diff --git a/docs/zh/flight_controller/autopilot_manufacturer_supported.md b/docs/zh/flight_controller/autopilot_manufacturer_supported.md index 54ba3a753c..d6f07a44fb 100644 --- a/docs/zh/flight_controller/autopilot_manufacturer_supported.md +++ b/docs/zh/flight_controller/autopilot_manufacturer_supported.md @@ -35,5 +35,6 @@ The boards in this category are: - [Radiolink PIX6](../flight_controller/radiolink_pix6.md) - [Sky-Drones AIRLink](../flight_controller/airlink.md) - [SPRacing SPRacingH7EXTREME](../flight_controller/spracingh7extreme.md) +- [Svehicle E2](../flight_controller/svehicle_e2.md) - [ThePeach FCC-K1](../flight_controller/thepeach_k1.md) - [ThePeach FCC-R1](../flight_controller/thepeach_r1.md) diff --git a/docs/zh/flight_controller/svehicle_e2.md b/docs/zh/flight_controller/svehicle_e2.md new file mode 100644 index 0000000000..d34e22e553 --- /dev/null +++ b/docs/zh/flight_controller/svehicle_e2.md @@ -0,0 +1,176 @@ +# S-Vehicle E2 + +:::warning +PX4 does not manufacture this (or any) autopilot. +::: + +The _E2_ is an advanced autopilot manufactured by S-Vehicle®. + +The autopilot is recommended for commercial system integration, but is also suitable for academic research and any other applications. +It brings you ultimate performance, stability, and reliability in every aspect. + +![SVehicle-E2](../../assets/flight_controller/svehicle_e2/main.png) + +:::info +These flight controllers are [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md). +::: + +### Processors & Sensors + +- FMU Processor: STM32H753IIK6 + - 32 Bit Arm® Cortex®-M7, 480MHz, 2MB flash memory, 1MB RAM +- IO Processor: STM32F103 + - 32 Bit Arm® Cortex®-M3, 72MHz, 20KB SRAM +- On-board sensors + - Accel/Gyro: BMI088 + - Accel/Gyro: ICM-42688-P + - Accel/Gyro: ICM-20649 + - Mag: RM3100 + - Barometer: 2x ICP-20100 + +### 接口 + +- 14x PWM Servo Outputs +- 1x Dedicated R/C Input for Spektrum / DSM and S.Bus +- 1x Analog/PWM RSSI Input +- 2x TELEM Ports (with full flow control) +- 1x UART4 Port +- 2x GPS Ports + - 1x Full GPS plus Safety Switch Port (GPS1) + - 1x Basic GPS Port (with I2C, GPS2) +- 1x USB Port (TYPE-C) +- 1x Ethernet Port + - Transformerless application + - 100Mbps +- 3x I2C Bus Ports +- 1x SPI Bus + - 1x Chip Select Line + - 1x Data Ready Line + - 1x SPI Reset Line +- 2x CAN Ports +- 3x Power Input Ports + - ADC Power Input + - I2C Power Input + - DroneCAN/UAVCAN Power Input +- 2x AD Ports + - Analog Input (3.3V) + - Analog Input (6.6V - not supported by PX4) +- 1x Dedicated Debug Port + - FMU Debug + +## Purchase Channels + +Order from [S-Vehicle](https://svehicle.cn/). + +## 遥控器 + +A Radio Control (RC) system is required if you want to manually control your vehicle (PX4 does not require a radio system for autonomous flight modes). + +将 HW\\u PM 模块的6针连接器连接到飞控的电源接口。 + +Spektrum/DSM receivers connect to the DSM/SBUS RC input. +PPM or SBUS receivers connect to the RC IN input port. +CRSF receiver must be wired to a spare port (UART) on the Flight Controller. Then you can bind the transmitter and receiver together. + +## 串口映射 + +| UART | 设备 | Port | +| ------ | ---------- | ------------- | +| USART1 | /dev/ttyS0 | GPS | +| USART2 | /dev/ttyS1 | TELEM3 | +| USART3 | /dev/ttyS2 | Debug Console | +| UART4 | /dev/ttyS3 | UART4 | +| UART5 | /dev/ttyS4 | TELEM2 | +| USART6 | /dev/ttyS5 | PX4IO/RC | +| UART7 | /dev/ttyS6 | TELEM1 | +| UART8 | /dev/ttyS7 | GPS2 | + +## PWM Output + +The E2-Plus flight controller supports up to 14 PWM outputs. +The first 8 outputs (labelled M1 to M8) are controlled by a dedicated STM32F103 IOMCU controller. +The remaining 6 outputs (labelled 9 to 14) are the "auxiliary" outputs. +These are directly attached to the STM32H753 FMU controller . + +The 14 PWM outputs are: + +M1 - M8 are connected to the IOMCU +A1 - A6 are connected to the FMU + +M1 - M8 support DShot and are in 3 groups: + +- M1, M2 in group 1 +- M3, M4 in group 2 +- M5, M6, M7, M8 in group 3 + +The 6 FMU PWM outputs are in 2 groups: + +A1 - A4 are in one group. +A5, A6 are in a 2nd group. + +Channels within the same group need to use the same output rate. +If any channel in a group uses DShot then all channels in the group need to use DShot. + +### Electrical data + +- Voltage Ratings: + - Max input voltage: 5.7V + - USB Power Input: 4.75\~5.25V + - Servo Rail Input: 0\~9.9V +- Current Ratings: + - TELEM1 and GPS2 combined output current limiter: 1.5A + - All other port combined output current limiter: 1.5A + +## Battery Monitoring + +The board has connectors for 3 power monitors. + +- POWER1 -- ADC +- POWER2 -- DroneCAN +- POWER3 -- I2C + +The board is configure by default for a analog power monitor, and also has DroneCAN power monitor and I2C defaults configured which is enabled. + +The default PDB included with the E2+ is analog and must be connected to `POWER1`. + +## 编译固件 + +To [build PX4](../dev_setup/building_px4.md) for this target, execute: + +```sh +make svehicle_e2_default +``` + +## 调试接口 + +The [PX4 System Console](../debug/system_console.md) and [SWD Interface](../debug/swd_debug.md) operate on the **FMU Debug** port. + +| 针脚 | 信号 | 电压 | +| ---- | --------------------------------- | --------------------- | +| 1(红) | 5V+ | +5V | +| 2 | DEBUG TX (OUT) | +3.3V | +| 3 | DEBUG RX (IN) | +3.3V | +| 4(黑) | FMU_SWDIO | +3.3V | +| 6 | FMU_SWCLK | +3.3V | +| 6 | GND | GND | + +For information about using this port see: + +- [SWD Debug Port](../debug/swd_debug.md) +- [PX4 System Console](../debug/system_console.md) (Note, the FMU console maps to USART3). +- All ports use GH1.25 ,power ports use ports on E2 uses the 6 circuit [2.00mm Pitch CLIK-Mate Wire-to-Board PCB Receptacle](https://www.molex.com/en-us/products/part-detail/5024430670). + +## 针脚定义 + +![SVehicle-E2 Top Down Photo](../../assets/flight_controller/svehicle_e2/top.png) + +![SVehicle-E2 Bottom Photo](../../assets/flight_controller/svehicle_e2/back.jpeg) + +![SVehicle-E2 left Photo](../../assets/flight_controller/svehicle_e2/left.png) + +![SVehicle-E2 right Photo](../../assets/flight_controller/svehicle_e2/right.png) + +## 支持的平台/机身 + +Any multirotor/airplane/rover or boat that can be controlled using normal RC servos or Futaba S-Bus servos. +The complete set of supported configurations can be found in the [Airframe Reference](../airframes/airframe_reference.md). From a1e5a959b558fd9d9e75c9ba49fe59f0a8691c14 Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Wed, 29 Oct 2025 09:23:08 +1100 Subject: [PATCH 234/812] New Crowdin translations - uk (#25812) Co-authored-by: Crowdin Bot --- docs/uk/SUMMARY.md | 1 + docs/uk/config/_autotune.md | 5 +- .../autopilot_manufacturer_supported.md | 1 + docs/uk/flight_controller/svehicle_e2.md | 176 ++++++++++++++++++ 4 files changed, 180 insertions(+), 3 deletions(-) create mode 100644 docs/uk/flight_controller/svehicle_e2.md diff --git a/docs/uk/SUMMARY.md b/docs/uk/SUMMARY.md index 779440e3bf..4066b1dece 100644 --- a/docs/uk/SUMMARY.md +++ b/docs/uk/SUMMARY.md @@ -187,6 +187,7 @@ - [Radiolink PIX6](flight_controller/radiolink_pix6.md) - [Sky-Drones AIRLink](flight_controller/airlink.md) - [SPRacing SPRacingH7EXTREME](flight_controller/spracingh7extreme.md) + - [SVehicle E2](flight_controller/svehicle_e2.md) - [ThePeach FCC-K1](flight_controller/thepeach_k1.md) - [ThePeach FCC-R1](flight_controller/thepeach_r1.md) - [Калібрування рівня горизонту](flight_controller/autopilot_experimental.md) diff --git a/docs/uk/config/_autotune.md b/docs/uk/config/_autotune.md index 7c31b3604b..a76a63832b 100644 --- a/docs/uk/config/_autotune.md +++ b/docs/uk/config/_autotune.md @@ -102,8 +102,7 @@ The RC sticks cannot be used during autotuning (moving the sticks will stop the
-4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. - The progress is shown in the progress bar, next to the _Autotune_ button. +4. The drone will first start to perform quick roll motions followed by pitch and yaw motions. When [`FW_AT_SYSID_TYPE`](../advanced_config/parameter_reference.md#FW_AT_SYSID_TYPE) is set to linear/logarithmic sine sweep (recommended), the max rates reached during the maneuvers are 75% of the maximum configured roll (`FW_R_RMAX`), pitch (`FW_P_RMAX_NEG`, `FW_P_RMAX_POS`) and yaw (`FW_Y_RMAX`) rates. The progress is shown in the progress bar, next to the _Autotune_ button.
@@ -198,7 +197,7 @@ Increase the [MC_AT_SYSID_AMP](../advanced_config/parameter_reference.md#MC_AT_S
-By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification. The target rates are approximately 45 deg/s for roll and 30 deg/s for pitch and yaw. +By default, the autotune maneuvers ensure that a sufficient angular rate is reached for system identification, corresponding to 75% of the configured maximum roll (`FW_R_RMAX`), pitch (`FW_P_RMAX_NEG`, `FW_P_RMAX_POS`) and yaw (`FW_Y_RMAX`) rates. If the signal-to-noise ratio of the vehicle is low, the system identification algorithm might have issues finding the correct coefficients. Ensure that there is no excessive noise and/or platform vibration. diff --git a/docs/uk/flight_controller/autopilot_manufacturer_supported.md b/docs/uk/flight_controller/autopilot_manufacturer_supported.md index 7892d5c8a1..7945545734 100644 --- a/docs/uk/flight_controller/autopilot_manufacturer_supported.md +++ b/docs/uk/flight_controller/autopilot_manufacturer_supported.md @@ -35,5 +35,6 @@ This category includes boards that are not fully compliant with the pixhawk stan - [Radiolink PIX6](../flight_controller/radiolink_pix6.md) - [Sky-Drones AIRLink](../flight_controller/airlink.md) - [SPRacing SPRacingH7EXTREME](../flight_controller/spracingh7extreme.md) +- [Svehicle E2](../flight_controller/svehicle_e2.md) - [ThePeach FCC-K1](../flight_controller/thepeach_k1.md) - [ThePeach FCC-R1](../flight_controller/thepeach_r1.md) diff --git a/docs/uk/flight_controller/svehicle_e2.md b/docs/uk/flight_controller/svehicle_e2.md new file mode 100644 index 0000000000..5d3a4aa9a1 --- /dev/null +++ b/docs/uk/flight_controller/svehicle_e2.md @@ -0,0 +1,176 @@ +# S-Vehicle E2 + +:::warning +PX4 не розробляє цей (або будь-який інший) автопілот. +::: + +The _E2_ is an advanced autopilot manufactured by S-Vehicle®. + +The autopilot is recommended for commercial system integration, but is also suitable for academic research and any other applications. +It brings you ultimate performance, stability, and reliability in every aspect. + +![SVehicle-E2](../../assets/flight_controller/svehicle_e2/main.png) + +:::info +These flight controllers are [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md). +::: + +### Processors & Sensors + +- FMU Processor: STM32H753IIK6 + - 32 Bit Arm® Cortex®-M7, 480MHz, 2MB flash memory, 1MB RAM +- IO Processor: STM32F103 + - 32 Bit Arm® Cortex®-M3, 72MHz, 20KB SRAM +- Сенсори на платі + - Акселератор/гіроскоп: BMI088 + - Accel/Gyro: ICM-42688-P + - Accel/Gyro: ICM-20649 + - Mag: RM3100 + - Барометр: 2x ICP-20100 + +### Інтерфейси + +- 14x PWM Servo Outputs +- 1x Dedicated R/C Input for Spektrum / DSM and S.Bus +- 1x Analog/PWM RSSI Input +- 2x TELEM Ports (with full flow control) +- 1x UART4 Port +- 2x GPS Ports + - 1x Full GPS plus Safety Switch Port (GPS1) + - 1x Basic GPS Port (with I2C, GPS2) +- 1x USB Port (TYPE-C) +- 1x Ethernet Port + - Transformerless application + - 100Mbps +- 3x I2C Bus Ports +- 1x SPI Bus + - 1x Chip Select Line + - 1x Data Ready Line + - 1x SPI Reset Line +- 2x CAN Ports +- 3x Power Input Ports + - ADC Power Input + - I2C Power Input + - DroneCAN/UAVCAN Power Input +- 2x AD Ports + - Analog Input (3.3V) + - Analog Input (6.6V - not supported by PX4) +- 1x Dedicated Debug Port + - FMU Debug + +## Purchase Channels + +Order from [S-Vehicle](https://svehicle.cn/). + +## Радіоуправління + +A Radio Control (RC) system is required if you want to manually control your vehicle (PX4 does not require a radio system for autonomous flight modes). + +Вам буде потрібно вибрати сумісний передавач/приймач та потім зв'язати їх, щоб вони взаємодіяли (прочитайте інструкції, що додаються до вашого конкретного передавача/приймача). + +Spektrum/DSM receivers connect to the DSM/SBUS RC input. +PPM or SBUS receivers connect to the RC IN input port. +CRSF receiver must be wired to a spare port (UART) on the Flight Controller. Then you can bind the transmitter and receiver together. + +## Налаштування послідовного порту + +| UART | Пристрій | Порт | +| ------ | ---------- | ------------- | +| USART1 | /dev/ttyS0 | GPS | +| USART2 | /dev/ttyS1 | TELEM3 | +| USART3 | /dev/ttyS2 | Debug Console | +| UART4 | /dev/ttyS3 | UART4 | +| UART5 | /dev/ttyS4 | TELEM2 | +| USART6 | /dev/ttyS5 | PX4IO/RC | +| UART7 | /dev/ttyS6 | TELEM1 | +| UART8 | /dev/ttyS7 | GPS2 | + +## PWM Output + +The E2-Plus flight controller supports up to 14 PWM outputs. +The first 8 outputs (labelled M1 to M8) are controlled by a dedicated STM32F103 IOMCU controller. +The remaining 6 outputs (labelled 9 to 14) are the "auxiliary" outputs. +These are directly attached to the STM32H753 FMU controller . + +The 14 PWM outputs are: + +M1 - M8 are connected to the IOMCU +A1 - A6 are connected to the FMU + +M1 - M8 support DShot and are in 3 groups: + +- M1, M2 in group 1 +- M3, M4 in group 2 +- M5, M6, M7, M8 in group 3 + +The 6 FMU PWM outputs are in 2 groups: + +A1 - A4 are in one group. +A5, A6 are in a 2nd group. + +Channels within the same group need to use the same output rate. +If any channel in a group uses DShot then all channels in the group need to use DShot. + +### Електричні дані + +- Номінальна напруга: + - Максимальна вхідна напруга: 5,7 В + - Вхід USB Power: 4.75~5.25V + - Вхід на серворейку: 0\~9.9В +- Номінальний струм: + - Комбінований обмежувач вихідного струму TELEM1 і GPS2: 1,5 А + - Комбінований обмежувач вихідного струму всіх інших портів: 1.5A + +## Battery Monitoring + +The board has connectors for 3 power monitors. + +- POWER1 -- ADC +- POWER2 -- DroneCAN +- POWER3 -- I2C + +The board is configure by default for a analog power monitor, and also has DroneCAN power monitor and I2C defaults configured which is enabled. + +The default PDB included with the E2+ is analog and must be connected to `POWER1`. + +## Збірка прошивки + +To [build PX4](../dev_setup/building_px4.md) for this target, execute: + +```sh +make svehicle_e2_default +``` + +## Відладочний порт + +The [PX4 System Console](../debug/system_console.md) and [SWD Interface](../debug/swd_debug.md) operate on the **FMU Debug** port. + +| Pin | Сигнал | Вольтаж | +| -------------------------- | --------------------------------- | --------------------- | +| 1 (red) | 5V+ | +5V | +| 2 (blk) | DEBUG TX (OUT) | +3.3V | +| 3 (blk) | DEBUG RX (IN) | +3.3V | +| 4 (blk) | FMU_SWDIO | +3.3V | +| 5 (blk) | FMU_SWCLK | +3.3V | +| 6 (blk) | GND | GND | + +Інформацію про використання цього порту див: + +- [SWD Debug Port](../debug/swd_debug.md) +- [PX4 System Console](../debug/system_console.md) (Note, the FMU console maps to USART3). +- All ports use GH1.25 ,power ports use ports on E2 uses the 6 circuit [2.00mm Pitch CLIK-Mate Wire-to-Board PCB Receptacle](https://www.molex.com/en-us/products/part-detail/5024430670). + +## Схема розташування виводів + +![SVehicle-E2 Top Down Photo](../../assets/flight_controller/svehicle_e2/top.png) + +![SVehicle-E2 Bottom Photo](../../assets/flight_controller/svehicle_e2/back.jpeg) + +![SVehicle-E2 left Photo](../../assets/flight_controller/svehicle_e2/left.png) + +![SVehicle-E2 right Photo](../../assets/flight_controller/svehicle_e2/right.png) + +## Підтримувані платформи / Конструкції + +Any multirotor/airplane/rover or boat that can be controlled using normal RC servos or Futaba S-Bus servos. +The complete set of supported configurations can be found in the [Airframe Reference](../airframes/airframe_reference.md). From 37398248aa04809467def87cde7a2835b1d99b98 Mon Sep 17 00:00:00 2001 From: cuav-liu1 Date: Tue, 21 Oct 2025 10:28:17 +0800 Subject: [PATCH 235/812] BMM350: Fix BMM350 temperature calculation --- src/drivers/magnetometer/bosch/bmm350/BMM350.cpp | 14 ++------------ 1 file changed, 2 insertions(+), 12 deletions(-) diff --git a/src/drivers/magnetometer/bosch/bmm350/BMM350.cpp b/src/drivers/magnetometer/bosch/bmm350/BMM350.cpp index 83f43a962b..65b2299268 100755 --- a/src/drivers/magnetometer/bosch/bmm350/BMM350.cpp +++ b/src/drivers/magnetometer/bosch/bmm350/BMM350.cpp @@ -590,13 +590,13 @@ int BMM350::ReadOutRawData(float *out_data) return -1; } - float temp = 0.0; struct BMM350::raw_mag_data raw_data = {0}; // --- Start read_uncomp_mag_temp_data uint8_t mag_data[14] = {0}; uint32_t raw_mag_x, raw_mag_y, raw_mag_z, raw_temp; + uint8_t cmd = static_cast(Register::DATAX_XLSB); uint8_t res = transfer(&cmd, 1, (uint8_t *)&mag_data, sizeof(mag_data)); @@ -623,17 +623,7 @@ int BMM350::ReadOutRawData(float *out_data) out_data[3] = (float)raw_data.raw_t * lsb_to_utc_degc[3]; // Adjust temperature - if (out_data[3] > 0.0f) { - temp = (float)(out_data[3] - (1 * 25.49f)); - - } else if (out_data[3] < 0.0f) { - temp = (float)(out_data[3] - (-1 * 25.49f)); - - } else { - temp = (float)(out_data[3]); - } - - out_data[3] = temp; + out_data[3] = (float)(out_data[3] - (1 * 25.49f)); return res; } From 6846af119d3944c2ffb7b1886ff662d76bcb6439 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 29 Oct 2025 12:32:15 +1100 Subject: [PATCH 236/812] Update docs metadata (#25828) --- .../en/advanced_config/parameter_reference.md | 30 ++++++++++++++----- docs/en/msg_docs/DifferentialPressure.md | 21 ++++++++----- docs/en/msg_docs/SensorBaro.md | 21 ++++++++----- docs/en/msg_docs/VehicleStatus.md | 14 ++++----- docs/en/msg_docs/index.md | 4 +-- 5 files changed, 55 insertions(+), 35 deletions(-) diff --git a/docs/en/advanced_config/parameter_reference.md b/docs/en/advanced_config/parameter_reference.md index 41db8563d2..7eca46d3f3 100644 --- a/docs/en/advanced_config/parameter_reference.md +++ b/docs/en/advanced_config/parameter_reference.md @@ -25550,12 +25550,16 @@ Used below MPC_LAND_ALT3 if distance sensor data is availabe. User assisted landing radius. -When nudging is enabled (see MPC_LAND_RC_HELP), this controls -the maximum allowed horizontal displacement from the original landing point. +When nudging is enabled (see MPC_LAND_RC_HELP), this defines the maximum +allowed horizontal displacement from the original landing point. + +- If inside of the radius, only allow nudging inputs that do not move the vehicle outside of it. +- If outside of the radius, only allow nudging inputs that move the vehicle back towards it. + Set it to -1 for infinite radius. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | | 1 | 1000. | m | +|   | -1 | | 1 | -1.0 | m | ### MPC_LAND_RC_HELP (`INT32`) {#MPC_LAND_RC_HELP} @@ -38833,6 +38837,14 @@ UAVCAN CAN bus bitrate. | ------ | -------- | -------- | --------- | ------- | ---- | |   | 20000 | 1000000 | | 1000000 | +### CANNODE_NODE_ID (`INT32`) {#CANNODE_NODE_ID} + +UAVCAN CAN node ID (0 for dynamic allocation). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 127 | | 0 | + ### CANNODE_PUB_IMU (`INT32`) {#CANNODE_PUB_IMU} Enable RawIMU pub. @@ -40859,13 +40871,15 @@ The encoder angle at which theta is zero. Adjust this number to change the locat ### ZENOH_ENABLE (`INT32`) {#ZENOH_ENABLE} -Zenoh Enable. +Enable Zenoh. -Zenoh +Set true (1) to start the Zenoh driver module (a.k.a the "Zenoh-Pico Node"). +See https://docs.px4.io/main/en/middleware/zenoh and +https://docs.px4.io/main/en/modules/modules_driver.html#zenoh -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | ## Miscellaneous diff --git a/docs/en/msg_docs/DifferentialPressure.md b/docs/en/msg_docs/DifferentialPressure.md index a6f10625c6..83adb2d03e 100644 --- a/docs/en/msg_docs/DifferentialPressure.md +++ b/docs/en/msg_docs/DifferentialPressure.md @@ -1,19 +1,24 @@ # DifferentialPressure (UORB message) +Differential-pressure (airspeed) sensor +This is populated by airspeed sensor drivers and used by the sensor module to calculate airspeed. +The information is published in the `SCALED_PRESSURE_n` MAVLink messages (along with information from a corresponding `SensorBaro` instance). [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DifferentialPressure.msg) ```c -uint64 timestamp # time since system start (microseconds) -uint64 timestamp_sample +# Differential-pressure (airspeed) sensor +# +# This is populated by airspeed sensor drivers and used by the sensor module to calculate airspeed. +# The information is published in the `SCALED_PRESSURE_n` MAVLink messages (along with information from a corresponding `SensorBaro` instance). -uint32 device_id # unique device ID for the sensor that does not change between power cycles +uint64 timestamp # [us] Time of publication (since system start) +uint64 timestamp_sample # [us] Time of raw data capture -float32 differential_pressure_pa # differential pressure reading in Pascals (may be negative) - -float32 temperature # Temperature provided by sensor in degrees Celsius, NAN if unknown - -uint32 error_count # Number of errors detected by driver +uint32 device_id # [-] Unique device ID for the sensor that does not change between power cycles +float32 differential_pressure_pa # [Pa] Differential pressure reading (may be negative) +float32 temperature # [degC] [@invalid NaN if unknown] Temperature +uint32 error_count # [-] Number of errors detected by driver ``` diff --git a/docs/en/msg_docs/SensorBaro.md b/docs/en/msg_docs/SensorBaro.md index 8a3c364f60..ef4d7a8f28 100644 --- a/docs/en/msg_docs/SensorBaro.md +++ b/docs/en/msg_docs/SensorBaro.md @@ -1,20 +1,25 @@ # SensorBaro (UORB message) +Barometer sensor +This is populated by barometer drivers and used by the EKF2 estimator. +The information is published in the `SCALED_PRESSURE_n` MAVLink messages (along with information from a corresponding `DifferentialPressure` instance). [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorBaro.msg) ```c -uint64 timestamp # time since system start (microseconds) -uint64 timestamp_sample +# Barometer sensor +# +# This is populated by barometer drivers and used by the EKF2 estimator. +# The information is published in the `SCALED_PRESSURE_n` MAVLink messages (along with information from a corresponding `DifferentialPressure` instance). -uint32 device_id # unique device ID for the sensor that does not change between power cycles +uint64 timestamp # [us] Time of publication (since system start) +uint64 timestamp_sample # [us] Time of raw data capture -float32 pressure # static pressure measurement in Pascals - -float32 temperature # temperature in degrees Celsius - -uint32 error_count +uint32 device_id # [-] Unique device ID for the sensor that does not change between power cycles +float32 pressure # [Pa] Static pressure measurement +float32 temperature # [degC] Temperature. +uint32 error_count # [-] Number of errors detected by driver. uint8 ORB_QUEUE_LENGTH = 4 diff --git a/docs/en/msg_docs/VehicleStatus.md b/docs/en/msg_docs/VehicleStatus.md index 9d46e42cb3..05e3f98bbb 100644 --- a/docs/en/msg_docs/VehicleStatus.md +++ b/docs/en/msg_docs/VehicleStatus.md @@ -20,20 +20,16 @@ uint8 ARMING_STATE_ARMED = 2 uint8 latest_arming_reason uint8 latest_disarming_reason -uint8 ARM_DISARM_REASON_TRANSITION_TO_STANDBY = 0 uint8 ARM_DISARM_REASON_STICK_GESTURE = 1 uint8 ARM_DISARM_REASON_RC_SWITCH = 2 uint8 ARM_DISARM_REASON_COMMAND_INTERNAL = 3 uint8 ARM_DISARM_REASON_COMMAND_EXTERNAL = 4 uint8 ARM_DISARM_REASON_MISSION_START = 5 -uint8 ARM_DISARM_REASON_SAFETY_BUTTON = 6 -uint8 ARM_DISARM_REASON_AUTO_DISARM_LAND = 7 -uint8 ARM_DISARM_REASON_AUTO_DISARM_PREFLIGHT = 8 -uint8 ARM_DISARM_REASON_KILL_SWITCH = 9 -uint8 ARM_DISARM_REASON_LOCKDOWN = 10 -uint8 ARM_DISARM_REASON_FAILURE_DETECTOR = 11 -uint8 ARM_DISARM_REASON_SHUTDOWN = 12 -uint8 ARM_DISARM_REASON_UNIT_TEST = 13 +uint8 ARM_DISARM_REASON_LANDING = 6 +uint8 ARM_DISARM_REASON_PREFLIGHT_INACTION = 7 +uint8 ARM_DISARM_REASON_KILL_SWITCH = 8 +uint8 ARM_DISARM_REASON_RC_BUTTON = 13 +uint8 ARM_DISARM_REASON_FAILSAFE = 14 uint64 nav_state_timestamp # time when current nav_state activated diff --git a/docs/en/msg_docs/index.md b/docs/en/msg_docs/index.md index 44ab566a6b..a70fa245f5 100644 --- a/docs/en/msg_docs/index.md +++ b/docs/en/msg_docs/index.md @@ -105,7 +105,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [DebugKeyValue](DebugKeyValue.md) - [DebugValue](DebugValue.md) - [DebugVect](DebugVect.md) -- [DifferentialPressure](DifferentialPressure.md) +- [DifferentialPressure](DifferentialPressure.md) — Differential-pressure (airspeed) sensor - [DistanceSensor](DistanceSensor.md) — DISTANCE_SENSOR message data - [DistanceSensorModeChangeRequest](DistanceSensorModeChangeRequest.md) - [DronecanNodeStatus](DronecanNodeStatus.md) @@ -240,7 +240,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [SensorAccel](SensorAccel.md) - [SensorAccelFifo](SensorAccelFifo.md) - [SensorAirflow](SensorAirflow.md) -- [SensorBaro](SensorBaro.md) +- [SensorBaro](SensorBaro.md) — Barometer sensor - [SensorCombined](SensorCombined.md) — Sensor readings in SI-unit form. These fields are scaled and offset-compensated where possible and do not change with board revisions and sensor updates. From 7d509d832acb61e8928ce19c2c73c87c67ea67eb Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 29 Oct 2025 12:43:10 +1100 Subject: [PATCH 237/812] Update to latest mavlink that includes support for WIP warnings (#25804) * Update to latest mavlink that includes support for WIP warnings * mavsdk_tests: pass build for now We need this until the figure eight stuff has moved to common. --------- Co-authored-by: Julian Oes --- src/modules/mavlink/mavlink | 2 +- test/mavsdk_tests/autopilot_tester_figure_eight.cpp | 4 ++++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink b/src/modules/mavlink/mavlink index 342530b83c..b401fe0238 160000 --- a/src/modules/mavlink/mavlink +++ b/src/modules/mavlink/mavlink @@ -1 +1 @@ -Subproject commit 342530b83c215654f12988ab682111281d2e71f0 +Subproject commit b401fe0238b9647f8ea18d58d9e968b79b347916 diff --git a/test/mavsdk_tests/autopilot_tester_figure_eight.cpp b/test/mavsdk_tests/autopilot_tester_figure_eight.cpp index 2d6e8f0b85..45142f579d 100644 --- a/test/mavsdk_tests/autopilot_tester_figure_eight.cpp +++ b/test/mavsdk_tests/autopilot_tester_figure_eight.cpp @@ -39,7 +39,11 @@ #include #include + #include + +// Fix build until this is moved to common.xml +#define MAVLINK_WIP #include using namespace mavsdk::geometry; From ddc173249a78073467e9554d039ce1ff1a2a1798 Mon Sep 17 00:00:00 2001 From: GC2020 Date: Wed, 22 Oct 2025 23:13:59 +0800 Subject: [PATCH 238/812] Complete missing modules for svehicle_e2 --- boards/svehicle/e2/default.px4board | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/boards/svehicle/e2/default.px4board b/boards/svehicle/e2/default.px4board index eecdbb4293..be198b4f2b 100644 --- a/boards/svehicle/e2/default.px4board +++ b/boards/svehicle/e2/default.px4board @@ -27,6 +27,7 @@ CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=y CONFIG_DRIVERS_GNSS_SEPTENTRIO=y CONFIG_COMMON_LIGHT=y CONFIG_COMMON_MAGNETOMETER=y +CONFIG_DRIVERS_OSD_MSP_OSD=y CONFIG_DRIVERS_POWER_MONITOR_INA226=y CONFIG_DRIVERS_POWER_MONITOR_INA228=y CONFIG_DRIVERS_POWER_MONITOR_INA238=y @@ -74,7 +75,7 @@ CONFIG_MODULES_RC_UPDATE=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y CONFIG_MODULES_UXRCE_DDS_CLIENT=y -#CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y CONFIG_SYSTEMCMDS_BSONDUMP=y CONFIG_SYSTEMCMDS_DMESG=y From 05c529359652ae42e959d50e3adc1b8a4b5424fb Mon Sep 17 00:00:00 2001 From: Jacob Dahl Date: Wed, 29 Oct 2025 08:15:22 -0800 Subject: [PATCH 239/812] gz: init submodule before configuring build --- src/modules/simulation/gz_bridge/CMakeLists.txt | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/modules/simulation/gz_bridge/CMakeLists.txt b/src/modules/simulation/gz_bridge/CMakeLists.txt index aa4b1be37e..c639b4c679 100644 --- a/src/modules/simulation/gz_bridge/CMakeLists.txt +++ b/src/modules/simulation/gz_bridge/CMakeLists.txt @@ -37,10 +37,11 @@ else() find_package(gz-transport NAMES gz-transport13) endif() -file(GLOB gz_worlds ${PX4_SOURCE_DIR}/Tools/simulation/gz/worlds/*.sdf) -file(GLOB gz_airframes ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes/*_gz_*) - if (gz-transport_FOUND) + px4_add_git_submodule(TARGET git_gz PATH "${PX4_SOURCE_DIR}/Tools/simulation/gz") + + file(GLOB gz_worlds ${PX4_SOURCE_DIR}/Tools/simulation/gz/worlds/*.sdf) + file(GLOB gz_airframes ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes/*_gz_*) if (gz-transport_VERSION VERSION_LESS "15") set(GZ_TRANSPORT_TARGET "gz-transport${gz-transport_VERSION_MAJOR}::core") else() @@ -78,7 +79,6 @@ if (gz-transport_FOUND) target_include_directories(modules__simulation__gz_bridge PUBLIC px4_gz_msgs) target_link_libraries(modules__simulation__gz_bridge PUBLIC px4_gz_msgs) - px4_add_git_submodule(TARGET git_gz PATH "${PX4_SOURCE_DIR}/Tools/simulation/gz") include(ExternalProject) ExternalProject_Add(gz SOURCE_DIR ${PX4_SOURCE_DIR}/Tools/simulation/gz From f9595319b88ee414025d871859991ebdd7d730df Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Wed, 22 Oct 2025 14:23:14 +0200 Subject: [PATCH 240/812] mavlink: remove ODOMETRY stream from ONBOARD_LOW_BANDWIDTH mode It's not used in our setups and it reduces the TX rate from 11.8 KB/s to 4.4 KB/s on a bench setup. --- src/modules/mavlink/mavlink_main.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 0d5b771761..479fa5a0a9 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1746,7 +1746,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("DISTANCE_SENSOR", 10.0f); configure_stream_local("MOUNT_ORIENTATION", 10.0f); configure_stream_local("OBSTACLE_DISTANCE", 10.0f); - configure_stream_local("ODOMETRY", 30.0f); configure_stream_local("GIMBAL_DEVICE_ATTITUDE_STATUS", 1.0f); configure_stream_local("GIMBAL_MANAGER_STATUS", 0.5f); configure_stream_local("GIMBAL_DEVICE_SET_ATTITUDE", 5.0f); From 6ec106a0edfebf737308592ef82ddfe1b0223f3f Mon Sep 17 00:00:00 2001 From: Niklas Hauser <121870655+niklaut@users.noreply.github.com> Date: Fri, 31 Oct 2025 13:19:10 +0100 Subject: [PATCH 241/812] INA2xx: Debounce battery connection state (#25786) To prevent critical low battery messages on a single I2C issue. --- src/drivers/power_monitor/ina220/ina220.cpp | 2 - src/drivers/power_monitor/ina226/ina226.cpp | 42 +++++++++++++------ src/drivers/power_monitor/ina226/ina226.h | 4 ++ src/drivers/power_monitor/ina228/ina228.cpp | 46 ++++++++++++++------- src/drivers/power_monitor/ina228/ina228.h | 3 ++ src/drivers/power_monitor/ina238/ina238.cpp | 45 +++++++++++++------- src/drivers/power_monitor/ina238/ina238.h | 3 ++ 7 files changed, 100 insertions(+), 45 deletions(-) diff --git a/src/drivers/power_monitor/ina220/ina220.cpp b/src/drivers/power_monitor/ina220/ina220.cpp index c8f52bf71c..bde68ce875 100644 --- a/src/drivers/power_monitor/ina220/ina220.cpp +++ b/src/drivers/power_monitor/ina220/ina220.cpp @@ -329,8 +329,6 @@ INA220::RunImpl() if (_ch_type == PM_CH_TYPE_VBATT) { _battery.setConnected(false); - _battery.updateVoltage(0.f); - _battery.updateCurrent(0.f); _battery.updateAndPublishBatteryStatus(hrt_absolute_time()); } diff --git a/src/drivers/power_monitor/ina226/ina226.cpp b/src/drivers/power_monitor/ina226/ina226.cpp index f61a7c7b79..60fb333699 100644 --- a/src/drivers/power_monitor/ina226/ina226.cpp +++ b/src/drivers/power_monitor/ina226/ina226.cpp @@ -83,10 +83,10 @@ INA226::INA226(const I2CSPIDriverConfig &config, int battery_index) : _power_lsb = 25 * _current_lsb; // We need to publish immediately, to guarantee that the first instance of the driver publishes to uORB instance 0 - _battery.setConnected(false); - _battery.updateVoltage(0.f); - _battery.updateCurrent(0.f); + setConnected(false); _battery.updateAndPublishBatteryStatus(hrt_absolute_time()); + + I2C::_retries = 5; } INA226::~INA226() @@ -226,14 +226,11 @@ INA226::collect() success = success && (read(INA226_REG_CURRENT, _current) == PX4_OK); // success = success && (read(INA226_REG_SHUNTVOLTAGE, _shunt) == PX4_OK); - if (!success) { - PX4_DEBUG("error reading from sensor"); - _bus_voltage = _power = _current = _shunt = 0; + if (setConnected(success)) { + _battery.updateVoltage(static_cast(_bus_voltage * INA226_VSCALE)); + _battery.updateCurrent(static_cast(_current * _current_lsb)); } - _battery.setConnected(success); - _battery.updateVoltage(static_cast(_bus_voltage * INA226_VSCALE)); - _battery.updateCurrent(static_cast(_current * _current_lsb)); _battery.updateAndPublishBatteryStatus(hrt_absolute_time()); perf_end(_sample_perf); @@ -246,6 +243,7 @@ INA226::collect() } } + void INA226::start() { @@ -297,9 +295,7 @@ INA226::RunImpl() ScheduleDelayed(INA226_CONVERSION_INTERVAL); } else { - _battery.setConnected(false); - _battery.updateVoltage(0.f); - _battery.updateCurrent(0.f); + setConnected(false); _battery.updateAndPublishBatteryStatus(hrt_absolute_time()); if (init() != PX4_OK) { @@ -308,6 +304,28 @@ INA226::RunImpl() } } +bool INA226::setConnected(bool state) +{ + // Filter out brief I2C failures for 2s + if (state) { + _connected = INA226_SAMPLE_FREQUENCY_HZ * 2; + + } else if (_connected > 0) { + _connected--; + } + + if (_connected > 0) { + _battery.setConnected(true); + + } else { + _battery.setConnected(false); + _battery.updateVoltage(0); + _battery.updateCurrent(0); + } + + return state; +} + void INA226::print_status() { diff --git a/src/drivers/power_monitor/ina226/ina226.h b/src/drivers/power_monitor/ina226/ina226.h index a402a079ab..a69695a1cc 100644 --- a/src/drivers/power_monitor/ina226/ina226.h +++ b/src/drivers/power_monitor/ina226/ina226.h @@ -206,6 +206,10 @@ private: int read(uint8_t address, int16_t &data); int write(uint8_t address, uint16_t data); + uint8_t _connected{0}; + // returns state unchanged + bool setConnected(bool state); + /** * Initialise the automatic measurement state machine and start it. * diff --git a/src/drivers/power_monitor/ina228/ina228.cpp b/src/drivers/power_monitor/ina228/ina228.cpp index e586590470..fd7494d3f3 100644 --- a/src/drivers/power_monitor/ina228/ina228.cpp +++ b/src/drivers/power_monitor/ina228/ina228.cpp @@ -98,11 +98,10 @@ INA228::INA228(const I2CSPIDriverConfig &config, int battery_index) : _power_lsb = 3.2f * _current_lsb; // We need to publish immediately, to guarantee that the first instance of the driver publishes to uORB instance 0 - _battery.setConnected(false); - _battery.updateVoltage(0.f); - _battery.updateCurrent(0.f); - _battery.updateTemperature(0.f); + setConnected(false); _battery.updateAndPublishBatteryStatus(hrt_absolute_time()); + + I2C::_retries = 5; } INA228::~INA228() @@ -322,15 +321,12 @@ INA228::collect() //success = success && (read(INA228_REG_VSHUNT, _shunt) == PX4_OK); success = success && (read(INA228_REG_DIETEMP, _temperature) == PX4_OK); - if (!success) { - PX4_DEBUG("error reading from sensor"); - _bus_voltage = _power = _current = _shunt = 0; + if (setConnected(success)) { + _battery.updateVoltage(static_cast(_bus_voltage * INA228_VSCALE)); + _battery.updateCurrent(static_cast(_current * _current_lsb)); + _battery.updateTemperature(static_cast(_temperature * INA228_TSCALE)); } - _battery.setConnected(success); - _battery.updateVoltage(static_cast(_bus_voltage * INA228_VSCALE)); - _battery.updateCurrent(static_cast(_current * _current_lsb)); - _battery.updateTemperature(static_cast(_temperature * INA228_TSCALE)); _battery.updateAndPublishBatteryStatus(hrt_absolute_time()); perf_end(_sample_perf); @@ -394,10 +390,7 @@ INA228::RunImpl() ScheduleDelayed(INA228_CONVERSION_INTERVAL); } else { - _battery.setConnected(false); - _battery.updateVoltage(0.f); - _battery.updateCurrent(0.f); - _battery.updateTemperature(0.f); + setConnected(false); _battery.updateAndPublishBatteryStatus(hrt_absolute_time()); if (init() != PX4_OK) { @@ -406,6 +399,29 @@ INA228::RunImpl() } } +bool INA228::setConnected(bool state) +{ + // Filter out brief I2C failures for 2s + if (state) { + _connected = INA228_SAMPLE_FREQUENCY_HZ * 2; + + } else if (_connected > 0) { + _connected--; + } + + if (_connected > 0) { + _battery.setConnected(true); + + } else { + _battery.setConnected(false); + _battery.updateVoltage(0); + _battery.updateCurrent(0); + _battery.updateTemperature(0); + } + + return state; +} + void INA228::print_status() { diff --git a/src/drivers/power_monitor/ina228/ina228.h b/src/drivers/power_monitor/ina228/ina228.h index 46e152ff00..72a89e6dcb 100644 --- a/src/drivers/power_monitor/ina228/ina228.h +++ b/src/drivers/power_monitor/ina228/ina228.h @@ -356,6 +356,9 @@ private: Battery _battery; uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uint8_t _connected{0}; + // returns state unchanged + bool setConnected(bool state); int read(uint8_t address, int16_t &data); int write(uint8_t address, int16_t data); diff --git a/src/drivers/power_monitor/ina238/ina238.cpp b/src/drivers/power_monitor/ina238/ina238.cpp index a55f71b893..f42ae87764 100644 --- a/src/drivers/power_monitor/ina238/ina238.cpp +++ b/src/drivers/power_monitor/ina238/ina238.cpp @@ -90,11 +90,10 @@ INA238::INA238(const I2CSPIDriverConfig &config, int battery_index) : _register_cfg[2].clear_bits = ~_shunt_calibration; // We need to publish immediately, to guarantee that the first instance of the driver publishes to uORB instance 0 - _battery.setConnected(false); - _battery.updateVoltage(0.f); - _battery.updateCurrent(0.f); - _battery.updateTemperature(0.f); + setConnected(false); _battery.updateAndPublishBatteryStatus(hrt_absolute_time()); + + I2C::_retries = 5; } INA238::~INA238() @@ -178,11 +177,8 @@ int INA238::probe() int INA238::Reset() { - int ret = PX4_ERROR; - _retries = 3; - if (RegisterWrite(Register::CONFIG, (uint16_t)(ADC_RESET_BIT)) != PX4_OK) { return ret; } @@ -254,13 +250,11 @@ int INA238::collect() success = success && (RegisterRead(Register::CURRENT, (uint16_t &)current) == PX4_OK); success = success && (RegisterRead(Register::DIETEMP, (uint16_t &)temperature) == PX4_OK); - if (success) { + if (setConnected(success)) { _battery.updateVoltage(static_cast(bus_voltage * INA238_VSCALE)); _battery.updateCurrent(static_cast(current * _current_lsb)); _battery.updateTemperature(static_cast(temperature * INA238_TSCALE)); - _battery.setConnected(success); - _battery.updateAndPublishBatteryStatus(hrt_absolute_time()); } @@ -276,8 +270,7 @@ int INA238::collect() perf_count(_bad_register_perf); success = false; - _battery.setConnected(success); - + setConnected(false); _battery.updateAndPublishBatteryStatus(hrt_absolute_time()); } } @@ -338,10 +331,7 @@ void INA238::RunImpl() ScheduleDelayed(INA238_CONVERSION_INTERVAL); } else { - _battery.setConnected(false); - _battery.updateVoltage(0.f); - _battery.updateCurrent(0.f); - _battery.updateTemperature(0.f); + setConnected(false); _battery.updateAndPublishBatteryStatus(hrt_absolute_time()); if (init() != PX4_OK) { @@ -354,6 +344,29 @@ void INA238::RunImpl() } } +bool INA238::setConnected(bool state) +{ + // Filter out brief I2C failures for 2s + if (state) { + _connected = INA238_SAMPLE_FREQUENCY_HZ * 2; + + } else if (_connected > 0) { + _connected--; + } + + if (_connected > 0) { + _battery.setConnected(true); + + } else { + _battery.setConnected(false); + _battery.updateVoltage(0); + _battery.updateCurrent(0); + _battery.updateTemperature(0); + } + + return state; +} + void INA238::print_status() { I2CSPIDriverBase::print_status(); diff --git a/src/drivers/power_monitor/ina238/ina238.h b/src/drivers/power_monitor/ina238/ina238.h index 7d888aef54..62750c44c4 100644 --- a/src/drivers/power_monitor/ina238/ina238.h +++ b/src/drivers/power_monitor/ina238/ina238.h @@ -154,6 +154,9 @@ private: Battery _battery; uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; + uint8_t _connected{0}; + // returns state unchanged + bool setConnected(bool state); int read(uint8_t address, uint16_t &data); int write(uint8_t address, uint16_t data); From b320ace4d11ae830a1866d91d680722daf69808f Mon Sep 17 00:00:00 2001 From: Niklas Hauser Date: Fri, 31 Oct 2025 11:45:44 +0100 Subject: [PATCH 242/812] [ARK FMUv6x] Fix the timer assignments for input capture --- boards/ark/fmu-v6x/default.px4board | 1 + boards/ark/fmu-v6x/src/CMakeLists.txt | 2 - boards/ark/fmu-v6x/src/board_config.h | 4 +- boards/ark/fmu-v6x/src/init.c | 5 - boards/ark/fmu-v6x/src/spix_sync.c | 309 ------------------------ boards/ark/fmu-v6x/src/spix_sync.h | 42 ---- boards/ark/fmu-v6x/src/timer_config.cpp | 15 +- 7 files changed, 5 insertions(+), 373 deletions(-) delete mode 100644 boards/ark/fmu-v6x/src/spix_sync.c delete mode 100644 boards/ark/fmu-v6x/src/spix_sync.h diff --git a/boards/ark/fmu-v6x/default.px4board b/boards/ark/fmu-v6x/default.px4board index a4b5c42f18..d67f3a6db1 100644 --- a/boards/ark/fmu-v6x/default.px4board +++ b/boards/ark/fmu-v6x/default.px4board @@ -19,6 +19,7 @@ CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_AUAV=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_PPS_CAPTURE=y CONFIG_DRIVERS_HEATER=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16507=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y diff --git a/boards/ark/fmu-v6x/src/CMakeLists.txt b/boards/ark/fmu-v6x/src/CMakeLists.txt index 78b8222f19..a120ebe336 100644 --- a/boards/ark/fmu-v6x/src/CMakeLists.txt +++ b/boards/ark/fmu-v6x/src/CMakeLists.txt @@ -57,8 +57,6 @@ else() mtd.cpp sdio.c spi.cpp - spix_sync.c - spix_sync.h timer_config.cpp usb.c ) diff --git a/boards/ark/fmu-v6x/src/board_config.h b/boards/ark/fmu-v6x/src/board_config.h index 302fbc22d9..16d0aa9300 100644 --- a/boards/ark/fmu-v6x/src/board_config.h +++ b/boards/ark/fmu-v6x/src/board_config.h @@ -241,7 +241,7 @@ /* PWM */ -#define DIRECT_PWM_OUTPUT_CHANNELS 8 +#define DIRECT_PWM_OUTPUT_CHANNELS 9 #define GPIO_FMU_CH1 /* PI0 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTI|GPIO_PIN0) #define GPIO_FMU_CH2 /* PH12 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_PORTH|GPIO_PIN12) @@ -482,7 +482,7 @@ #define PX4_I2C_BUS_MTD 4,5 -#define BOARD_NUM_IO_TIMERS 3 +#define BOARD_NUM_IO_TIMERS 4 #define BOARD_SPIX_SYNC_FREQ 32000 __BEGIN_DECLS diff --git a/boards/ark/fmu-v6x/src/init.c b/boards/ark/fmu-v6x/src/init.c index 6c1c2257ed..c60f700af1 100644 --- a/boards/ark/fmu-v6x/src/init.c +++ b/boards/ark/fmu-v6x/src/init.c @@ -46,7 +46,6 @@ ****************************************************************************/ #include "board_config.h" -#include "spix_sync.h" #include #include @@ -290,9 +289,5 @@ __EXPORT int board_app_initialize(uintptr_t arg) #endif /* CONFIG_MMCSD */ - /* Configure the SPIX_SYNC output */ - spix_sync_servo_init(BOARD_SPIX_SYNC_FREQ); - spix_sync_servo_set(0, 150); - return OK; } diff --git a/boards/ark/fmu-v6x/src/spix_sync.c b/boards/ark/fmu-v6x/src/spix_sync.c deleted file mode 100644 index 056e38e75f..0000000000 --- a/boards/ark/fmu-v6x/src/spix_sync.c +++ /dev/null @@ -1,309 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2023 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name Airmind nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** -* @file spix_sync.c -* -* -*/ - -#include - -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - - -#include -#include -#include - -#include - -#include "spix_sync.h" - -#define REG(_tmr, _reg) (*(volatile uint32_t *)(spix_sync_timers[_tmr].base + _reg)) - -#define rCR1(_tmr) REG(_tmr, STM32_GTIM_CR1_OFFSET) -#define rCR2(_tmr) REG(_tmr, STM32_GTIM_CR2_OFFSET) -#define rSMCR(_tmr) REG(_tmr, STM32_GTIM_SMCR_OFFSET) -#define rDIER(_tmr) REG(_tmr, STM32_GTIM_DIER_OFFSET) -#define rSR(_tmr) REG(_tmr, STM32_GTIM_SR_OFFSET) -#define rEGR(_tmr) REG(_tmr, STM32_GTIM_EGR_OFFSET) -#define rCCMR1(_tmr) REG(_tmr, STM32_GTIM_CCMR1_OFFSET) -#define rCCMR2(_tmr) REG(_tmr, STM32_GTIM_CCMR2_OFFSET) -#define rCCER(_tmr) REG(_tmr, STM32_GTIM_CCER_OFFSET) -#define rCNT(_tmr) REG(_tmr, STM32_GTIM_CNT_OFFSET) -#define rPSC(_tmr) REG(_tmr, STM32_GTIM_PSC_OFFSET) -#define rARR(_tmr) REG(_tmr, STM32_GTIM_ARR_OFFSET) -#define rCCR1(_tmr) REG(_tmr, STM32_GTIM_CCR1_OFFSET) -#define rCCR2(_tmr) REG(_tmr, STM32_GTIM_CCR2_OFFSET) -#define rCCR3(_tmr) REG(_tmr, STM32_GTIM_CCR3_OFFSET) -#define rCCR4(_tmr) REG(_tmr, STM32_GTIM_CCR4_OFFSET) -#define rDCR(_tmr) REG(_tmr, STM32_GTIM_DCR_OFFSET) -#define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET) -#define rBDTR(_tmr) REG(_tmr, STM32_ATIM_BDTR_OFFSET) - -#define BOARD_SPIX_SYNC_PWM_FREQ 1024000 - -unsigned -spix_sync_timer_get_period(unsigned timer) -{ - return (rARR(timer)); -} - -static void spix_sync_timer_init_timer(unsigned timer, unsigned rate) -{ - if (spix_sync_timers[timer].base) { - - irqstate_t flags = px4_enter_critical_section(); - - /* enable the timer clock before we try to talk to it */ - - modifyreg32(spix_sync_timers[timer].clock_register, 0, spix_sync_timers[timer].clock_bit); - - /* disable and configure the timer */ - rCR1(timer) = 0; - rCR2(timer) = 0; - rSMCR(timer) = 0; - rDIER(timer) = 0; - rCCER(timer) = 0; - rCCMR1(timer) = 0; - rCCMR2(timer) = 0; - rCCR1(timer) = 0; - rCCR2(timer) = 0; - rCCR3(timer) = 0; - rCCR4(timer) = 0; - rCCER(timer) = 0; - rDCR(timer) = 0; - - if ((spix_sync_timers[timer].base == STM32_TIM1_BASE) || (spix_sync_timers[timer].base == STM32_TIM8_BASE)) { - - /* master output enable = on */ - - rBDTR(timer) = ATIM_BDTR_MOE; - } - - /* If the timer clock source provided as clock_freq is the STM32_APBx_TIMx_CLKIN - * then configure the timer to free-run at 1MHz. - * Otherwise, other frequencies are attainable by adjusting .clock_freq accordingly. - */ - - rPSC(timer) = (spix_sync_timers[timer].clock_freq / BOARD_SPIX_SYNC_PWM_FREQ) - 1; - - /* configure the timer to update at the desired rate */ - - rARR(timer) = (BOARD_SPIX_SYNC_PWM_FREQ / rate) - 1; - - /* generate an update event; reloads the counter and all registers */ - rEGR(timer) = GTIM_EGR_UG; - - px4_leave_critical_section(flags); - } - -} - -void spix_sync_channel_init(unsigned channel) -{ - /* Only initialize used channels */ - - if (spix_sync_channels[channel].timer_channel) { - - unsigned timer = spix_sync_channels[channel].timer_index; - - /* configure the GPIO first */ - px4_arch_configgpio(spix_sync_channels[channel].gpio_out); - - uint16_t polarity = spix_sync_channels[channel].masks; - - /* configure the channel */ - switch (spix_sync_channels[channel].timer_channel) { - case 1: - rCCMR1(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR1_OC1M_SHIFT) | GTIM_CCMR1_OC1PE; - rCCER(timer) |= polarity | GTIM_CCER_CC1E; - break; - - case 2: - rCCMR1(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR1_OC2M_SHIFT) | GTIM_CCMR1_OC2PE; - rCCER(timer) |= polarity | GTIM_CCER_CC2E; - break; - - case 3: - rCCMR2(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR2_OC3M_SHIFT) | GTIM_CCMR2_OC3PE; - rCCER(timer) |= polarity | GTIM_CCER_CC3E; - break; - - case 4: - rCCMR2(timer) |= (GTIM_CCMR_MODE_PWM1 << GTIM_CCMR2_OC4M_SHIFT) | GTIM_CCMR2_OC4PE; - rCCER(timer) |= polarity | GTIM_CCER_CC4E; - break; - } - } -} - -int -spix_sync_servo_set(unsigned channel, uint8_t cvalue) -{ - if (channel >= arraySize(spix_sync_channels)) { - return -1; - } - - unsigned timer = spix_sync_channels[channel].timer_index; - - /* test timer for validity */ - if ((spix_sync_timers[timer].base == 0) || - (spix_sync_channels[channel].gpio_out == 0)) { - return -1; - } - - unsigned period = spix_sync_timer_get_period(timer); - - unsigned value = (unsigned)cvalue * period / 255; - - /* configure the channel */ - if (value > 0) { - value--; - } - - - switch (spix_sync_channels[channel].timer_channel) { - case 1: - rCCR1(timer) = value; - break; - - case 2: - rCCR2(timer) = value; - break; - - case 3: - rCCR3(timer) = value; - break; - - case 4: - rCCR4(timer) = value; - break; - - default: - return -1; - } - - return 0; -} - -unsigned spix_sync_servo_get(unsigned channel) -{ - if (channel >= 3) { - return 0; - } - - unsigned timer = spix_sync_channels[channel].timer_index; - uint16_t value = 0; - - /* test timer for validity */ - if ((spix_sync_timers[timer].base == 0) || - (spix_sync_channels[channel].timer_channel == 0)) { - return 0; - } - - /* configure the channel */ - switch (spix_sync_channels[channel].timer_channel) { - case 1: - value = rCCR1(timer); - break; - - case 2: - value = rCCR2(timer); - break; - - case 3: - value = rCCR3(timer); - break; - - case 4: - value = rCCR4(timer); - break; - } - - unsigned period = spix_sync_timer_get_period(timer); - return ((value + 1) * 255 / period); -} - -int spix_sync_servo_init(unsigned rate) -{ - /* do basic timer initialisation first */ - for (unsigned i = 0; i < arraySize(spix_sync_timers); i++) { - spix_sync_timer_init_timer(i, rate); - } - - /* now init channels */ - for (unsigned i = 0; i < arraySize(spix_sync_channels); i++) { - spix_sync_channel_init(i); - } - - spix_sync_servo_arm(true); - return OK; -} - -void -spix_sync_servo_deinit(void) -{ - /* disable the timers */ - spix_sync_servo_arm(false); -} -void -spix_sync_servo_arm(bool armed) -{ - /* iterate timers and arm/disarm appropriately */ - for (unsigned i = 0; i < arraySize(spix_sync_timers); i++) { - if (spix_sync_timers[i].base != 0) { - if (armed) { - /* force an update to preload all registers */ - rEGR(i) = GTIM_EGR_UG; - - /* arm requires the timer be enabled */ - rCR1(i) |= GTIM_CR1_CEN | GTIM_CR1_ARPE; - - } else { - rCR1(i) = 0; - } - } - } -} diff --git a/boards/ark/fmu-v6x/src/spix_sync.h b/boards/ark/fmu-v6x/src/spix_sync.h deleted file mode 100644 index 2e37c89086..0000000000 --- a/boards/ark/fmu-v6x/src/spix_sync.h +++ /dev/null @@ -1,42 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2023 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -__BEGIN_DECLS -void spix_sync_channel_init(unsigned channel); -int spix_sync_servo_set(unsigned channel, uint8_t value); -unsigned spix_sync_servo_get(unsigned channel); -int spix_sync_servo_init(unsigned rate); -void spix_sync_servo_deinit(void); -void spix_sync_servo_arm(bool armed); -unsigned spix_sync_timer_get_period(unsigned timer); -__END_DECLS diff --git a/boards/ark/fmu-v6x/src/timer_config.cpp b/boards/ark/fmu-v6x/src/timer_config.cpp index 3504c3569d..75d67bac99 100644 --- a/boards/ark/fmu-v6x/src/timer_config.cpp +++ b/boards/ark/fmu-v6x/src/timer_config.cpp @@ -60,8 +60,7 @@ constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { initIOTimer(Timer::Timer5, DMA{DMA::Index1}), initIOTimer(Timer::Timer4, DMA{DMA::Index1}), initIOTimer(Timer::Timer12), - //initIOTimer(Timer::Timer1), - //initIOTimer(Timer::Timer2), + initIOTimer(Timer::Timer1), }; constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { @@ -73,18 +72,8 @@ constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel3}, {GPIO::PortD, GPIO::Pin14}), initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel1}, {GPIO::PortH, GPIO::Pin6}), initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel2}, {GPIO::PortH, GPIO::Pin9}), - //initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), - //initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), + initIOTimerChannelCapture(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), }; constexpr io_timers_channel_mapping_t io_timers_channel_mapping = initIOTimerChannelMapping(io_timers, timer_io_channels); - - -constexpr io_timers_t spix_sync_timers[MAX_SPIX_SYNC_TIMERS] = { - initIOTimer(Timer::Timer1), -}; - -constexpr timer_io_channels_t spix_sync_channels[MAX_SPIX_SYNC_TIMERS] = { - initIOTimerChannel(spix_sync_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), -}; From be9fa620fd182e74aa7d3271b439809b2b795f8b Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Mon, 27 Oct 2025 14:46:05 -0600 Subject: [PATCH 243/812] drivers: rm3100 add i2c/spi ifdefs --- src/drivers/magnetometer/rm3100/rm3100.h | 4 ++++ src/drivers/magnetometer/rm3100/rm3100_i2c.cpp | 4 ++++ src/drivers/magnetometer/rm3100/rm3100_main.cpp | 16 +++++++++++++--- src/drivers/magnetometer/rm3100/rm3100_spi.cpp | 4 ++++ 4 files changed, 25 insertions(+), 3 deletions(-) diff --git a/src/drivers/magnetometer/rm3100/rm3100.h b/src/drivers/magnetometer/rm3100/rm3100.h index 7e4737d48b..3057d98c27 100644 --- a/src/drivers/magnetometer/rm3100/rm3100.h +++ b/src/drivers/magnetometer/rm3100/rm3100.h @@ -91,8 +91,12 @@ #define RM3100_REVID 0x22 /* interface factories */ +#if defined(CONFIG_SPI) extern device::Device *RM3100_SPI_interface(int bus, uint32_t devid, int bus_frequency, spi_mode_e spi_mode); +#endif // CONFIG_SPI +#if defined(CONFIG_I2C) extern device::Device *RM3100_I2C_interface(int bus, int bus_frequency); +#endif // CONFIG_I2C #define RM3100_ADDRESS 0x20 diff --git a/src/drivers/magnetometer/rm3100/rm3100_i2c.cpp b/src/drivers/magnetometer/rm3100/rm3100_i2c.cpp index 3aeba5d57e..9a7826c314 100644 --- a/src/drivers/magnetometer/rm3100/rm3100_i2c.cpp +++ b/src/drivers/magnetometer/rm3100/rm3100_i2c.cpp @@ -39,6 +39,8 @@ #include +#if defined(CONFIG_I2C) + #include #include #include @@ -129,3 +131,5 @@ int RM3100_I2C::write(unsigned address, void *data, unsigned count) return transfer(&buf[0], count + 1, nullptr, 0); } + +#endif // CONFIG_I2C diff --git a/src/drivers/magnetometer/rm3100/rm3100_main.cpp b/src/drivers/magnetometer/rm3100/rm3100_main.cpp index be8571cced..3c3b51060f 100644 --- a/src/drivers/magnetometer/rm3100/rm3100_main.cpp +++ b/src/drivers/magnetometer/rm3100/rm3100_main.cpp @@ -45,12 +45,16 @@ I2CSPIDriverBase *RM3100::instantiate(const I2CSPIDriverConfig &config, int runt { device::Device *interface = nullptr; +#if defined(CONFIG_I2C) + if (config.bus_type == BOARD_I2C_BUS) { interface = RM3100_I2C_interface(config.bus, config.bus_frequency); - } else if (config.bus_type == BOARD_SPI_BUS) { - interface = RM3100_SPI_interface(config.bus, config.spi_devid, config.bus_frequency, config.spi_mode); - } + } else +#endif // CONFIG_I2C + if (config.bus_type == BOARD_SPI_BUS) { + interface = RM3100_SPI_interface(config.bus, config.spi_devid, config.bus_frequency, config.spi_mode); + } if (interface == nullptr) { PX4_ERR("alloc failed"); @@ -93,8 +97,12 @@ extern "C" int rm3100_main(int argc, char *argv[]) using ThisDriver = RM3100; int ch; BusCLIArguments cli{true, true}; +#if defined(CONFIG_I2C) cli.default_i2c_frequency = 400000; +#endif // CONFIG_I2C +#if defined(CONFIG_SPI) cli.default_spi_frequency = 1 * 1000 * 1000; +#endif // CONFIG_SPI while ((ch = cli.getOpt(argc, argv, "R:")) != EOF) { switch (ch) { @@ -111,7 +119,9 @@ extern "C" int rm3100_main(int argc, char *argv[]) return -1; } +#if defined(CONFIG_I2C) cli.i2c_address = RM3100_ADDRESS; +#endif // CONFIG_I2C BusInstanceIterator iterator(MODULE_NAME, cli, DRV_MAG_DEVTYPE_RM3100); diff --git a/src/drivers/magnetometer/rm3100/rm3100_spi.cpp b/src/drivers/magnetometer/rm3100/rm3100_spi.cpp index 3d8f84498a..b9da9f5493 100644 --- a/src/drivers/magnetometer/rm3100/rm3100_spi.cpp +++ b/src/drivers/magnetometer/rm3100/rm3100_spi.cpp @@ -39,6 +39,8 @@ #include +#if defined(CONFIG_SPI) + #include #include #include @@ -135,3 +137,5 @@ int RM3100_SPI::write(unsigned address, void *data, unsigned count) return transfer(&buf[0], &buf[0], count + 1); } + +#endif // CONFIG_SPI From 0c9ebc432185fd37afc544abeb7f560b6e04cb8f Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Mon, 27 Oct 2025 14:46:40 -0600 Subject: [PATCH 244/812] boards: add ARK MAG --- .vscode/cmake-variants.yaml | 10 + boards/ark/mag/canbootloader.px4board | 5 + boards/ark/mag/default.px4board | 22 ++ boards/ark/mag/firmware.prototype | 13 ++ boards/ark/mag/init/rc.board_sensors | 6 + .../mag/nuttx-config/canbootloader/defconfig | 57 ++++++ boards/ark/mag/nuttx-config/include/board.h | 132 ++++++++++++ .../mag/nuttx-config/include/board_dma_map.h | 42 ++++ boards/ark/mag/nuttx-config/nsh/defconfig | 149 ++++++++++++++ .../scripts/canbootloader_script.ld | 134 +++++++++++++ boards/ark/mag/nuttx-config/scripts/script.ld | 146 ++++++++++++++ boards/ark/mag/src/CMakeLists.txt | 65 ++++++ boards/ark/mag/src/board_config.h | 88 ++++++++ boards/ark/mag/src/boot.c | 188 ++++++++++++++++++ boards/ark/mag/src/boot_config.h | 130 ++++++++++++ boards/ark/mag/src/can.c | 130 ++++++++++++ boards/ark/mag/src/init.c | 147 ++++++++++++++ boards/ark/mag/src/led.c | 124 ++++++++++++ boards/ark/mag/src/led.h | 37 ++++ boards/ark/mag/src/spi.cpp | 44 ++++ boards/ark/mag/uavcan_board_identity | 17 ++ 21 files changed, 1686 insertions(+) create mode 100644 boards/ark/mag/canbootloader.px4board create mode 100644 boards/ark/mag/default.px4board create mode 100644 boards/ark/mag/firmware.prototype create mode 100644 boards/ark/mag/init/rc.board_sensors create mode 100644 boards/ark/mag/nuttx-config/canbootloader/defconfig create mode 100644 boards/ark/mag/nuttx-config/include/board.h create mode 100644 boards/ark/mag/nuttx-config/include/board_dma_map.h create mode 100644 boards/ark/mag/nuttx-config/nsh/defconfig create mode 100644 boards/ark/mag/nuttx-config/scripts/canbootloader_script.ld create mode 100644 boards/ark/mag/nuttx-config/scripts/script.ld create mode 100644 boards/ark/mag/src/CMakeLists.txt create mode 100644 boards/ark/mag/src/board_config.h create mode 100644 boards/ark/mag/src/boot.c create mode 100644 boards/ark/mag/src/boot_config.h create mode 100644 boards/ark/mag/src/can.c create mode 100644 boards/ark/mag/src/init.c create mode 100644 boards/ark/mag/src/led.c create mode 100644 boards/ark/mag/src/led.h create mode 100644 boards/ark/mag/src/spi.cpp create mode 100644 boards/ark/mag/uavcan_board_identity diff --git a/.vscode/cmake-variants.yaml b/.vscode/cmake-variants.yaml index b40113f5da..504c38b2d3 100644 --- a/.vscode/cmake-variants.yaml +++ b/.vscode/cmake-variants.yaml @@ -241,6 +241,16 @@ CONFIG: buildType: MinSizeRel settings: CONFIG: ark_fpv_default + ark_mag_canbootloader: + short: ark_mag_canbootloader + buildType: MiniSizeRel + settings: + CONFIG: ark_mag_canbootloader + ark_mag_default: + short: ark_mag_default + buildType: MiniSizeRel + settings: + CONFIG: ark_mag_default ark_pi6x_bootloader: short: ark_pi6x_bootloader buildType: MinSizeRel diff --git a/boards/ark/mag/canbootloader.px4board b/boards/ark/mag/canbootloader.px4board new file mode 100644 index 0000000000..46917280f6 --- /dev/null +++ b/boards/ark/mag/canbootloader.px4board @@ -0,0 +1,5 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m4" +CONFIG_BOARD_ROMFSROOT="" +CONFIG_BOARD_CONSTRAINED_MEMORY=y +CONFIG_DRIVERS_BOOTLOADERS=y diff --git a/boards/ark/mag/default.px4board b/boards/ark/mag/default.px4board new file mode 100644 index 0000000000..53f391b7e8 --- /dev/null +++ b/boards/ark/mag/default.px4board @@ -0,0 +1,22 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m4" +CONFIG_BOARD_ROMFSROOT="cannode" +CONFIG_BOARD_CONSTRAINED_MEMORY=y +CONFIG_DRIVERS_BOOTLOADERS=y +CONFIG_DRIVERS_MAGNETOMETER_RM3100=y +CONFIG_BOARD_UAVCAN_INTERFACES=1 +CONFIG_DRIVERS_UAVCANNODE=y +CONFIG_UAVCANNODE_MAGNETIC_FIELD_STRENGTH=y +CONFIG_MODULES_SENSORS=y +# CONFIG_SENSORS_VEHICLE_AIRSPEED is not set +# CONFIG_SENSORS_VEHICLE_AIR_DATA is not set +# CONFIG_SENSORS_VEHICLE_GPS_POSITION is not set +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/ark/mag/firmware.prototype b/boards/ark/mag/firmware.prototype new file mode 100644 index 0000000000..35ba6379fb --- /dev/null +++ b/boards/ark/mag/firmware.prototype @@ -0,0 +1,13 @@ +{ + "board_id": 93, + "magic": "PX4FWv1", + "description": "Firmware for the ARK MAG board", + "image": "", + "build_time": 0, + "summary": "ARKMAG", + "version": "0.1", + "image_size": 0, + "image_maxsize": 2080768, + "git_identity": "", + "board_revision": 0 +} diff --git a/boards/ark/mag/init/rc.board_sensors b/boards/ark/mag/init/rc.board_sensors new file mode 100644 index 0000000000..29163fabc9 --- /dev/null +++ b/boards/ark/mag/init/rc.board_sensors @@ -0,0 +1,6 @@ +#!/bin/sh +# +# board sensors init +#------------------------------------------------------------------------------ + +rm3100 -s -b 2 start diff --git a/boards/ark/mag/nuttx-config/canbootloader/defconfig b/boards/ark/mag/nuttx-config/canbootloader/defconfig new file mode 100644 index 0000000000..11b948472f --- /dev/null +++ b/boards/ark/mag/nuttx-config/canbootloader/defconfig @@ -0,0 +1,57 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/mag/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F412CE=y +CONFIG_ARCH_INTERRUPTSTACK=4096 +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BINFMT_DISABLE=y +CONFIG_BOARDCTL=y +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DISABLE_MOUNTPOINT=y +CONFIG_EXPERIMENTAL=y +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=4096 +CONFIG_INIT_STACKSIZE=4096 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_STRERROR=y +CONFIG_MM_REGIONS=2 +CONFIG_NAME_MAX=0 +CONFIG_NUNGET_CHARS=0 +CONFIG_PREALLOC_TIMERS=0 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=262144 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_DISABLE_BUFFERING=y +CONFIG_STM32_FLASH_CONFIG_G=y +CONFIG_STM32_NOEXT_VECTORS=y +CONFIG_STM32_TIM8=y +CONFIG_TASK_NAME_SIZE=0 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/ark/mag/nuttx-config/include/board.h b/boards/ark/mag/nuttx-config/include/board.h new file mode 100644 index 0000000000..18079b86e1 --- /dev/null +++ b/boards/ark/mag/nuttx-config/include/board.h @@ -0,0 +1,132 @@ +/************************************************************************************ + * configs/px4fmu/include/board.h + * include/arch/board/board.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ +#include "board_dma_map.h" + +#ifndef __ARCH_BOARD_BOARD_H +#define __ARCH_BOARD_BOARD_H + +#include +#ifndef __ASSEMBLY__ +# include +#endif + +#include + +/* HSI - 8 MHz RC factory-trimmed + * LSI - 32 KHz RC + * HSE - 8 MHz Crystal + * LSE - not installed + */ +#define STM32_BOARD_USEHSE 1 +#define STM32_BOARD_XTAL 8000000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 + +/* Main PLL Configuration */ +#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8) +#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(384) +#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_4 +#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(8) +#define STM32_PLLCFG_PLLR RCC_PLLCFG_PLLR(2) + +#define STM32_RCC_PLLI2SCFGR_PLLI2SM RCC_PLLI2SCFGR_PLLI2SM(16) +#define STM32_RCC_PLLI2SCFGR_PLLI2SN RCC_PLLI2SCFGR_PLLI2SN(192) +#define STM32_RCC_PLLI2SCFGR_PLLI2SQ RCC_PLLI2SCFGR_PLLI2SQ(2) +#define STM32_RCC_PLLI2SCFGR_PLLI2SR RCC_PLLI2SCFGR_PLLI2SR(2) +#define STM32_RCC_PLLI2SCFGR_PLLI2SSRC RCC_PLLI2SCFGR_PLLI2SSRC(0) /* HSE or HSI depending on PLLSRC of PLLCFGR*/ + +#define STM32_RCC_DCKCFGR2_CK48MSEL RCC_DCKCFGR2_CK48MSEL_PLL +#define STM32_RCC_DCKCFGR2_FMPI2C1SEL RCC_DCKCFGR2_FMPI2C1SEL_APB +#define STM32_RCC_DCKCFGR2_SDIOSEL RCC_DCKCFGR2_SDIOSEL_48MHZ + +#define STM32_SYSCLK_FREQUENCY 96000000ul + +/* AHB clock (HCLK) is SYSCLK (96MHz) */ +#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* Same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (48MHz) */ +#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timers driven from APB1 will be twice PCLK1 (see page 112 of reference manual) */ +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* APB2 clock (PCLK2) is HCLK (96MHz) */ +#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK /* PCLK2 = HCLK */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY) + +/* Timers driven from APB2 will be PCLK2 since no prescale division */ +#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM9_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM10_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM11_CLKIN (STM32_PCLK2_FREQUENCY) + +/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx otherwise frequency is 2xAPBx. */ +#define BOARD_TIM2_FREQUENCY (2 * STM32_PCLK1_FREQUENCY) +#define BOARD_TIM3_FREQUENCY (2 * STM32_PCLK1_FREQUENCY) +#define BOARD_TIM4_FREQUENCY (2 * STM32_PCLK1_FREQUENCY) +#define BOARD_TIM5_FREQUENCY (2 * STM32_PCLK1_FREQUENCY) +#define BOARD_TIM6_FREQUENCY (2 * STM32_PCLK1_FREQUENCY) +#define BOARD_TIM7_FREQUENCY (2 * STM32_PCLK1_FREQUENCY) +#define BOARD_TIM8_FREQUENCY (2 * STM32_PCLK2_FREQUENCY) + +/* Alternate function pin selections ************************************************/ + +/* UARTs */ +#define GPIO_USART2_RX GPIO_USART2_RX_1 +#define GPIO_USART2_TX GPIO_USART2_TX_1 + +/* CAN */ +#define GPIO_CAN1_RX GPIO_CAN1_RX_1 +#define GPIO_CAN1_TX GPIO_CAN1_TX_1 + +/* SPI */ +#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 /* PB14 */ +#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 /* PB15 */ +#define GPIO_SPI2_SCK GPIO_SPI2_SCK_1 /* PB10 */ + +#endif /* __ARCH_BOARD_BOARD_H */ diff --git a/boards/ark/mag/nuttx-config/include/board_dma_map.h b/boards/ark/mag/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..773b49fc34 --- /dev/null +++ b/boards/ark/mag/nuttx-config/include/board_dma_map.h @@ -0,0 +1,42 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +// DMA1 Channel/Stream Selections +//--------------------------------------------//---------------------------//---------------- +#define DMACHAN_SPI2_RX DMAMAP_SPI2_RX // DMA1, Stream 3, Channel 0 +#define DMACHAN_SPI2_TX DMAMAP_SPI2_TX // DMA1, Stream 4, Channel 0 + +// DMA2 Channel/Stream Selections +//--------------------------------------------//---------------------------//---------------- diff --git a/boards/ark/mag/nuttx-config/nsh/defconfig b/boards/ark/mag/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..665ad0c1c3 --- /dev/null +++ b/boards/ark/mag/nuttx-config/nsh/defconfig @@ -0,0 +1,149 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/ark/mag/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32=y +CONFIG_ARCH_CHIP_STM32F412CE=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_LOOPSPERMSEC=16717 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_CROMFS=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=2624 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MM_REGIONS=2 +CONFIG_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_VARS=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=262144 +CONFIG_RAM_START=0x20000000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=254 +CONFIG_SCHED_HPWORKSTACKSIZE=3000 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_WAITPID=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STM32_ADC1=y +CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y +CONFIG_STM32_DMA1=y +CONFIG_STM32_DMA2=y +CONFIG_STM32_FLASH_CONFIG_G=y +CONFIG_STM32_FLASH_PREFETCH=y +CONFIG_STM32_FLOWCONTROL_BROKEN=y +CONFIG_STM32_JTAG_SW_ENABLE=y +CONFIG_STM32_PWR=y +CONFIG_STM32_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32_SPI2=y +CONFIG_STM32_SPI2_DMA=y +CONFIG_STM32_SPI2_DMA_BUFFER=2048 +CONFIG_STM32_TIM8=y +CONFIG_STM32_USART2=y +CONFIG_STM32_USART_BREAKS=y +CONFIG_STM32_WWDG=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_SERIAL_CONSOLE=y +CONFIG_USART2_TXBUFSIZE=1100 +CONFIG_USEC_PER_TICK=1000 diff --git a/boards/ark/mag/nuttx-config/scripts/canbootloader_script.ld b/boards/ark/mag/nuttx-config/scripts/canbootloader_script.ld new file mode 100644 index 0000000000..48a59fe92d --- /dev/null +++ b/boards/ark/mag/nuttx-config/scripts/canbootloader_script.ld @@ -0,0 +1,134 @@ +/**************************************************************************** + * nuttx-config/scripts/canbootloader_script.ld + * + * Copyright (C) 2015 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The STM32F412 has 1M of FLASH beginning at address 0x0800:0000 and + * 256Kb of SRAM. SRAM is split up into three blocks: + * + * 1) 112Kb of SRAM beginning at address 0x2000:0000 + * 2) 16Kb of SRAM beginning at address 0x2001:c000 + * 3) 64Kb of SRAM beginning at address 0x2002:0000 + * 4) 64Kb of TCM SRAM beginning at address 0x1000:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The first 0x10000 of flash is reserved for the bootloader. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08000000, LENGTH = 32K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K +} + +OUTPUT_ARCH(arm) + +ENTRY(__start) /* treat __start as the anchor for dead code stripping */ +EXTERN(_vectors) /* force the vectors to be included in the output */ + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/ark/mag/nuttx-config/scripts/script.ld b/boards/ark/mag/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..2f4769b8f5 --- /dev/null +++ b/boards/ark/mag/nuttx-config/scripts/script.ld @@ -0,0 +1,146 @@ +/**************************************************************************** + * scripts/ld.script + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The STM32F412 has 1M of FLASH beginning at address 0x0800:0000 and + * 256Kb of SRAM. SRAM is split up into three blocks: + * + * 1) 112Kb of SRAM beginning at address 0x2000:0000 + * 2) 16Kb of SRAM beginning at address 0x2001:c000 + * 3) 64Kb of SRAM beginning at address 0x2002:0000 + * 4) 64Kb of TCM SRAM beginning at address 0x1000:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The first 0x10000 of flash is reserved for the bootloader. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08010000, LENGTH = 928K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K +} + +OUTPUT_ARCH(arm) + +ENTRY(__start) /* treat __start as the anchor for dead code stripping */ +EXTERN(_vectors) /* force the vectors to be included in the output */ + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(8); + /* + * This section positions the app_descriptor_t used + * by the make_can_boot_descriptor.py tool to set + * the application image's descriptor so that the + * uavcan bootloader has the ability to validate the + * image crc, size etc + */ + KEEP(*(.app_descriptor)) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/ark/mag/src/CMakeLists.txt b/boards/ark/mag/src/CMakeLists.txt new file mode 100644 index 0000000000..4fae41fc0e --- /dev/null +++ b/boards/ark/mag/src/CMakeLists.txt @@ -0,0 +1,65 @@ +############################################################################ +# +# Copyright (c) 2020 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +if("${PX4_BOARD_LABEL}" STREQUAL "canbootloader") + + add_library(drivers_board + boot_config.h + boot.c + led.c + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch + nuttx_drivers + canbootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/canbootloader) + +else() + add_library(drivers_board + can.c + init.c + led.c + spi.cpp + ) + + target_link_libraries(drivers_board + PRIVATE + arch_spi + drivers__led # drv_led_start + nuttx_arch + nuttx_drivers + px4_layer + ) +endif() diff --git a/boards/ark/mag/src/board_config.h b/boards/ark/mag/src/board_config.h new file mode 100644 index 0000000000..ca6e5bb094 --- /dev/null +++ b/boards/ark/mag/src/board_config.h @@ -0,0 +1,88 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * board internal definitions + */ + +#pragma once + +#include +#include +#include + +/* CAN Silent mode control */ +#define GPIO_CAN1_SILENT_S0 /* PB11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN11) + +/* CAN termination software control */ +#define GPIO_CAN1_TERMINATION /* PB13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN13) +#define GPIO_CAN_TERM GPIO_CAN1_TERMINATION + +/* Boot config */ +#define GPIO_BOOT_CONFIG /* PC15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN15|GPIO_EXTI) + +/* LEDs are driven with open drain to support Anode to 5V or 3.3V */ +#define GPIO_TIM1_CH1 /* PA8 */ (GPIO_TIM1_CH1_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz) +#define GPIO_TIM1_CH2 /* PA9 */ (GPIO_TIM1_CH2_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz) +#define GPIO_TIM1_CH3 /* PA10 */ (GPIO_TIM1_CH3_1|GPIO_OPENDRAIN|GPIO_SPEED_2MHz) + +#define FLASH_BASED_PARAMS + +/* High-resolution timer */ +#define HRT_TIMER 3 /* use timer 3 for the HRT */ +#define HRT_TIMER_CHANNEL 4 /* use capture/compare channel 4 */ + +#define PX4_GPIO_INIT_LIST { \ + GPIO_BOOT_CONFIG, \ + GPIO_CAN1_TX, \ + GPIO_CAN1_RX, \ + GPIO_CAN1_SILENT_S0, \ + GPIO_CAN1_TERMINATION, \ + } + +__BEGIN_DECLS + +#define BOARD_HAS_N_S_RGB_LED 1 +#define BOARD_MAX_LEDS BOARD_HAS_N_S_RGB_LED + +#ifndef __ASSEMBLY__ + +extern void stm32_spiinitialize(void); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/ark/mag/src/boot.c b/boards/ark/mag/src/boot.c new file mode 100644 index 0000000000..a26034e254 --- /dev/null +++ b/boards/ark/mag/src/boot.c @@ -0,0 +1,188 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * Author: Ben Dyer + * Pavel Kirienko + * David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include "boot_config.h" +#include "board.h" + +#include +#include +#include + +#include +#include "led.h" + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +__EXPORT void stm32_boardinitialize(void) +{ + putreg32(getreg32(STM32_RCC_APB1ENR) | RCC_APB1ENR_CAN1EN, STM32_RCC_APB1ENR); + stm32_configgpio(GPIO_CAN1_RX); + stm32_configgpio(GPIO_CAN1_TX); + stm32_configgpio(GPIO_CAN1_SILENT_S0); + stm32_configgpio(GPIO_CAN1_TERMINATION); + putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR); + putreg32(getreg32(STM32_RCC_APB1RSTR) & ~RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR); + +#if defined(OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO) + stm32_configgpio(GPIO_GETNODEINFO_JUMPER); +#endif + +} + +/************************************************************************************ + * Name: board_deinitialize + * + * Description: + * This function is called by the bootloader code prior to booting + * the application. Is should place the HW into an benign initialized state. + * + ************************************************************************************/ + +void board_deinitialize(void) +{ + putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST, STM32_RCC_APB1RSTR); +} + +/**************************************************************************** + * Name: board_get_product_name + * + * Description: + * Called to retrieve the product name. The returned value is a assumed + * to be written to a pascal style string that will be length prefixed + * and not null terminated + * + * Input Parameters: + * product_name - A pointer to a buffer to write the name. + * maxlen - The maximum number of charter that can be written + * + * Returned Value: + * The length of characters written to the buffer. + * + ****************************************************************************/ + +uint8_t board_get_product_name(uint8_t *product_name, size_t maxlen) +{ + DEBUGASSERT(maxlen > UAVCAN_STRLEN(HW_UAVCAN_NAME)); + memcpy(product_name, HW_UAVCAN_NAME, UAVCAN_STRLEN(HW_UAVCAN_NAME)); + return UAVCAN_STRLEN(HW_UAVCAN_NAME); +} + +/**************************************************************************** + * Name: board_get_hardware_version + * + * Description: + * Called to retrieve the hardware version information. The function + * will first initialize the the callers struct to all zeros. + * + * Input Parameters: + * hw_version - A pointer to a uavcan_hardwareversion_t. + * + * Returned Value: + * Length of the unique_id + * + ****************************************************************************/ + +size_t board_get_hardware_version(uavcan_HardwareVersion_t *hw_version) +{ + memset(hw_version, 0, sizeof(uavcan_HardwareVersion_t)); + + hw_version->major = HW_VERSION_MAJOR; + hw_version->minor = HW_VERSION_MINOR; + + return board_get_mfguid(*(mfguid_t *) hw_version->unique_id); +} + +/**************************************************************************** + * Name: board_indicate + * + * Description: + * Provides User feedback to indicate the state of the bootloader + * on board specific hardware. + * + * Input Parameters: + * indication - A member of the uiindication_t + * + * Returned Value: + * None + * + ****************************************************************************/ +#define led(n, code, r , g , b, h) {.red = (r),.green = (g), .blue = (b),.hz = (h)} + +typedef begin_packed_struct struct led_t { + uint8_t red; + uint8_t green; + uint8_t blue; + uint8_t hz; +} end_packed_struct led_t; + +static const led_t i2l[] = { + + led(0, off, 0, 0, 0, 0), + led(1, reset, 128, 128, 128, 30), + led(2, autobaud_start, 0, 128, 0, 1), + led(3, autobaud_end, 0, 128, 0, 2), + led(4, allocation_start, 0, 0, 64, 2), + led(5, allocation_end, 0, 128, 64, 3), + led(6, fw_update_start, 32, 128, 64, 3), + led(7, fw_update_erase_fail, 32, 128, 32, 3), + led(8, fw_update_invalid_response, 64, 0, 0, 1), + led(9, fw_update_timeout, 64, 0, 0, 2), + led(a, fw_update_invalid_crc, 64, 0, 0, 4), + led(b, jump_to_app, 0, 128, 0, 10), + +}; + +void board_indicate(uiindication_t indication) +{ + rgb_led(i2l[indication].red, + i2l[indication].green, + i2l[indication].blue, + i2l[indication].hz); +} diff --git a/boards/ark/mag/src/boot_config.h b/boards/ark/mag/src/boot_config.h new file mode 100644 index 0000000000..76782f9a93 --- /dev/null +++ b/boards/ark/mag/src/boot_config.h @@ -0,0 +1,130 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* + * @file boot_config.h + * + * bootloader definitions that configures the behavior and options + * of the Boot loader + * This file is relies on the parent folder's boot_config.h file and defines + * different usages of the hardware for bootloading + */ + +#pragma once + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +/* Bring in the board_config.h definitions + * todo:make this be pulled in from a targed's build + * files in nuttx*/ + +#include "board_config.h" +#include "uavcan.h" +#include + +#include + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define OPT_PREFERRED_NODE_ID ANY_NODE_ID + +//todo:wrap OPT_x in in ifdefs for command line definitions +#define OPT_TBOOT_MS 3000 +#define OPT_NODE_STATUS_RATE_MS 800 +#define OPT_NODE_INFO_RATE_MS 50 +#define OPT_BL_NUMBER_TIMERS 7 + +/* + * This Option set is set to 1 ensure a provider of firmware has an + * opportunity update the node's firmware. + * This Option is the default policy and can be overridden by + * a jumper + * When this Policy is set, the node will ignore tboot and + * wait indefinitely for a GetNodeInfo request before booting. + * + * OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT is used to allow + * the polarity of the jumper to be True Active + * + * wait OPT_WAIT_FOR_GETNODEINFO OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO + * Jumper + * yes 1 0 x + * yes 1 1 Active + * no 1 1 Not Active + * no 0 0 X + * yes 0 1 Active + * no 0 1 Not Active + * + */ +#define OPT_WAIT_FOR_GETNODEINFO 0 +#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO 1 +#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 1 + +#define OPT_ENABLE_WD 1 + +#define OPT_RESTART_TIMEOUT_MS 20000 + +/* Reserved for the Booloader */ +#define OPT_BOOTLOADER_SIZE_IN_K (1024*64) + +/* Reserved for the application out of the total + * system flash minus the BOOTLOADER_SIZE_IN_K + */ +#define OPT_APPLICATION_RESERVER_IN_K 0 + +#define OPT_APPLICATION_IMAGE_OFFSET OPT_BOOTLOADER_SIZE_IN_K +#define OPT_APPLICATION_IMAGE_LENGTH (FLASH_SIZE-(OPT_BOOTLOADER_SIZE_IN_K+OPT_APPLICATION_RESERVER_IN_K)) + + +#define FLASH_BASE STM32_FLASH_BASE +#define FLASH_SIZE STM32_FLASH_SIZE + +#define APPLICATION_LOAD_ADDRESS (FLASH_BASE + OPT_APPLICATION_IMAGE_OFFSET) +#define APPLICATION_SIZE (FLASH_SIZE-OPT_APPLICATION_IMAGE_OFFSET) +#define APPLICATION_LAST_8BIT_ADDRRESS ((uint8_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint8_t))) +#define APPLICATION_LAST_32BIT_ADDRRESS ((uint32_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint32_t))) +#define APPLICATION_LAST_64BIT_ADDRRESS ((uint64_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint64_t))) + +/* If this board uses big flash that have large sectors */ + +#define OPT_USE_YIELD + +/* Bootloader Option***************************************************************** + * + */ +#define GPIO_GETNODEINFO_JUMPER (GPIO_BOOT_CONFIG & ~GPIO_EXTI) diff --git a/boards/ark/mag/src/can.c b/boards/ark/mag/src/can.c new file mode 100644 index 0000000000..7737965dc6 --- /dev/null +++ b/boards/ark/mag/src/can.c @@ -0,0 +1,130 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file can.c + * + * Board-specific CAN functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "chip.h" +#include "arm_internal.h" + +#include "stm32.h" +#include "stm32_can.h" +#include "board_config.h" + +#ifdef CONFIG_CAN + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Configuration ********************************************************************/ + +#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) +# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." +# undef CONFIG_STM32_CAN2 +#endif + +#ifdef CONFIG_STM32_CAN1 +# define CAN_PORT 1 +#else +# define CAN_PORT 2 +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int can_devinit(void); + +/************************************************************************************ + * Name: can_devinit + * + * Description: + * All STM32 architectures must provide the following interface to work with + * examples/can. + * + ************************************************************************************/ + +int can_devinit(void) +{ + static bool initialized = false; + struct can_dev_s *can; + int ret; + + /* Check if we have already initialized */ + + if (!initialized) { + /* Call stm32_caninitialize() to get an instance of the CAN interface */ + + can = stm32_caninitialize(CAN_PORT); + + if (can == NULL) { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } + + /* Register the CAN driver at "/dev/can0" */ + + ret = can_register("/dev/can0", can); + + if (ret < 0) { + canerr("ERROR: can_register failed: %d\n", ret); + return ret; + } + + /* Now we are initialized */ + + initialized = true; + } + + return OK; +} + +#endif diff --git a/boards/ark/mag/src/init.c b/boards/ark/mag/src/init.c new file mode 100644 index 0000000000..a6290bdc7a --- /dev/null +++ b/boards/ark/mag/src/init.c @@ -0,0 +1,147 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * board specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialization. + */ + +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include "board_config.h" +#include "led.h" +#include + +#include + +#include +#include +#include + +#include + +#include +#include + +# if defined(FLASH_BASED_PARAMS) +# include +#endif + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +__EXPORT void stm32_boardinitialize(void) +{ + watchdog_init(); + + /* configure pins */ + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + // Configure SPI all interfaces GPIO & enable power. + stm32_spiinitialize(); +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + px4_platform_init(); + +#if defined(FLASH_BASED_PARAMS) + static sector_descriptor_t params_sector_map[] = { + {2, 16 * 1024, 0x08008000}, + {3, 16 * 1024, 0x0800C000}, + {0, 0, 0}, + }; + + /* Initialize the flashfs layer to use heap allocated memory */ + int result = parameter_flashfs_init(params_sector_map, NULL, 0); + + if (result != OK) { + syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result); + } + +#endif // FLASH_BASED_PARAMS + + /* Configure the HW based on the manifest */ + //px4_platform_configure(); + + return OK; +} diff --git a/boards/ark/mag/src/led.c b/boards/ark/mag/src/led.c new file mode 100644 index 0000000000..24c3c42bf4 --- /dev/null +++ b/boards/ark/mag/src/led.c @@ -0,0 +1,124 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +#include "led.h" + +#define TMR_BASE STM32_TIM1_BASE +#define TMR_FREQUENCY STM32_APB2_TIM1_CLKIN +#define TMR_REG(o) (TMR_BASE+(o)) + +void rgb_led(int r, int g, int b, int freqs) +{ + + long fosc = TMR_FREQUENCY; + long prescale = 2048; + long p1s = fosc / prescale; + long p0p5s = p1s / 2; + uint16_t val; + static bool once = 0; + + if (!once) { + once = 1; + + /* Enable Clock to Block */ + modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_TIM1EN); + + /* Reload */ + + val = getreg16(TMR_REG(STM32_BTIM_EGR_OFFSET)); + val |= ATIM_EGR_UG; + putreg16(val, TMR_REG(STM32_BTIM_EGR_OFFSET)); + + /* Set Prescaler STM32_TIM_SETCLOCK */ + + putreg16(prescale, TMR_REG(STM32_BTIM_PSC_OFFSET)); + + /* Enable STM32_TIM_SETMODE*/ + + putreg16(ATIM_CR1_CEN | ATIM_CR1_ARPE, TMR_REG(STM32_BTIM_CR1_OFFSET)); + + + putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC1M_SHIFT) | ATIM_CCMR1_OC1PE | + (ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC2M_SHIFT) | ATIM_CCMR1_OC2PE, TMR_REG(STM32_GTIM_CCMR1_OFFSET)); + putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC3M_SHIFT) | ATIM_CCMR2_OC3PE, TMR_REG(STM32_GTIM_CCMR2_OFFSET)); + putreg16(ATIM_CCER_CC3E | ATIM_CCER_CC3P | + ATIM_CCER_CC2E | ATIM_CCER_CC2P | + ATIM_CCER_CC1E | ATIM_CCER_CC1P, TMR_REG(STM32_GTIM_CCER_OFFSET)); + + + stm32_configgpio(GPIO_TIM1_CH1); + stm32_configgpio(GPIO_TIM1_CH2); + stm32_configgpio(GPIO_TIM1_CH3); + + /* master output enable = on */ + putreg16(ATIM_BDTR_MOE, (TMR_REG(STM32_ATIM_BDTR_OFFSET))); + } + + long p = freqs == 0 ? p1s : p1s / freqs; + putreg32(p, TMR_REG(STM32_BTIM_ARR_OFFSET)); + + p = freqs == 0 ? p1s + 1 : p0p5s / freqs; + + putreg32((r * p) / 255, TMR_REG(STM32_GTIM_CCR1_OFFSET)); + putreg32((g * p) / 255, TMR_REG(STM32_GTIM_CCR2_OFFSET)); + putreg32((b * p) / 255, TMR_REG(STM32_GTIM_CCR3_OFFSET)); + + val = getreg16(TMR_REG(STM32_BTIM_CR1_OFFSET)); + + if (freqs == 0) { + val &= ~ATIM_CR1_CEN; + + } else { + val |= ATIM_CR1_CEN; + } + + putreg16(val, TMR_REG(STM32_BTIM_CR1_OFFSET)); + +} diff --git a/boards/ark/mag/src/led.h b/boards/ark/mag/src/led.h new file mode 100644 index 0000000000..b68e4aa70d --- /dev/null +++ b/boards/ark/mag/src/led.h @@ -0,0 +1,37 @@ +/**************************************************************************** + * + * Copyright (C) 2015 PX4 Development Team. All rights reserved. + * Author: David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +__BEGIN_DECLS +void rgb_led(int r, int g, int b, int freqs); +__END_DECLS diff --git a/boards/ark/mag/src/spi.cpp b/boards/ark/mag/src/spi.cpp new file mode 100644 index 0000000000..b32d42b514 --- /dev/null +++ b/boards/ark/mag/src/spi.cpp @@ -0,0 +1,44 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_MAG_DEVTYPE_RM3100, SPI::CS{GPIO::PortB, GPIO::Pin12}, SPI::DRDY{GPIO::PortB, GPIO::Pin4}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/ark/mag/uavcan_board_identity b/boards/ark/mag/uavcan_board_identity new file mode 100644 index 0000000000..1e30c3d822 --- /dev/null +++ b/boards/ark/mag/uavcan_board_identity @@ -0,0 +1,17 @@ +# UAVCAN boot loadable Module ID +set(uavcanblid_sw_version_major ${PX4_VERSION_MAJOR}) +set(uavcanblid_sw_version_minor ${PX4_VERSION_MINOR}) +add_definitions( + -DAPP_VERSION_MAJOR=${uavcanblid_sw_version_major} + -DAPP_VERSION_MINOR=${uavcanblid_sw_version_minor} +) + +set(uavcanblid_hw_version_major 0) +set(uavcanblid_hw_version_minor 93) +set(uavcanblid_name "\"org.ark.mag\"") + +add_definitions( + -DHW_UAVCAN_NAME=${uavcanblid_name} + -DHW_VERSION_MAJOR=${uavcanblid_hw_version_major} + -DHW_VERSION_MINOR=${uavcanblid_hw_version_minor} +) From d5eea0dd924b8581e3d4216d41106c36c71b48c1 Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Mon, 8 Sep 2025 11:49:27 +0300 Subject: [PATCH 245/812] sensors/VehicleImu: Don't set _backup_schedule_timeout_us shorter than normal scheduling interval With IMUs of higher report rate (e.g. ADIS16470), setting backup schedule timeout simply to half of the ORB queue length may cause the backup firing before required updates are received. Set backup schedule to queue length - 1 instead. Additionally, double-check that the backup doesn't get too short after finding the largest integer multiple of gyro_integral_samples. Signed-off-by: Jukka Laitinen --- src/modules/sensors/vehicle_imu/VehicleIMU.cpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/src/modules/sensors/vehicle_imu/VehicleIMU.cpp b/src/modules/sensors/vehicle_imu/VehicleIMU.cpp index b8c0a9547e..7ba258a66b 100644 --- a/src/modules/sensors/vehicle_imu/VehicleIMU.cpp +++ b/src/modules/sensors/vehicle_imu/VehicleIMU.cpp @@ -706,8 +706,8 @@ void VehicleIMU::UpdateIntegratorConfiguration() _gyro_integrator.set_reset_interval(roundf((gyro_integral_samples - 0.5f) * gyro_interval_us)); _gyro_integrator.set_reset_samples(gyro_integral_samples); - _backup_schedule_timeout_us = math::constrain((int)math::min(sensor_accel_s::ORB_QUEUE_LENGTH * accel_interval_us, - sensor_gyro_s::ORB_QUEUE_LENGTH * gyro_interval_us) / 2, 1000, 20000); + _backup_schedule_timeout_us = math::constrain((int)math::min((sensor_accel_s::ORB_QUEUE_LENGTH - 1) * accel_interval_us, + (sensor_gyro_s::ORB_QUEUE_LENGTH - 1) * gyro_interval_us), 1000, 20000); // gyro: find largest integer multiple of gyro_integral_samples for (int n = sensor_gyro_s::ORB_QUEUE_LENGTH; n > 0; n--) { @@ -716,6 +716,12 @@ void VehicleIMU::UpdateIntegratorConfiguration() } if (gyro_integral_samples % n == 0) { + // Make sure _backup_schedule_timeout_us is not smaller than normal scheduling interval + + if (_backup_schedule_timeout_us < n * gyro_interval_us) { + _backup_schedule_timeout_us = (n + 1) * gyro_interval_us; + } + _sensor_gyro_sub.set_required_updates(n); _sensor_gyro_sub.registerCallback(); From f3ee45b1735325176693e4a31d53653772ada97d Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Sat, 1 Nov 2025 09:38:02 -0800 Subject: [PATCH 246/812] ark: fmuv6x: fix imu start after spi sync removal (#25851) --- boards/ark/fmu-v6x/init/rc.board_sensors | 23 ++++++++++------------- 1 file changed, 10 insertions(+), 13 deletions(-) diff --git a/boards/ark/fmu-v6x/init/rc.board_sensors b/boards/ark/fmu-v6x/init/rc.board_sensors index aacbc22db0..c16ed31f69 100644 --- a/boards/ark/fmu-v6x/init/rc.board_sensors +++ b/boards/ark/fmu-v6x/init/rc.board_sensors @@ -1,6 +1,6 @@ #!/bin/sh # -# ARK FMUARKV6X specific board sensors init +# ARK FMU V6X specific board sensors init #------------------------------------------------------------------------------ set HAVE_PM2 yes set HAVE_PM3 yes @@ -69,28 +69,25 @@ fi if ver hwtypecmp ARKV6X000 then - # Internal SPI bus IIM42652 with SPIX measured frequency of 32.051kHz - iim42652 -R 3 -s -b 1 -C 32051 start + # Internal SPI bus IIM42652 + iim42652 -R 3 -s -b 1 start - # Internal SPI bus ICM42688p with SPIX measured frequency of 32.051kHz - icm42688p -R 9 -s -b 2 -C 32051 start + # Internal SPI bus ICM42688p + icm42688p -R 9 -s -b 2 start - # Internal SPI bus ICM42688p with SPIX measured frequency of 32.051kHz - icm42688p -R 6 -s -b 3 -C 32051 start + # Internal SPI bus ICM42688p + icm42688p -R 6 -s -b 3 start fi if ver hwtypecmp ARKV6X001 then - # Internal SPI bus IIM42653 with SPIX measured frequency of 32.051kHz - #iim42653 -R 3 -s -b 1 -C 32051 start + # Internal SPI bus IIM42653 iim42653 -R 3 -s -b 1 start - # Internal SPI bus IIM42653 with SPIX measured frequency of 32.051kHz - #iim42653 -R 9 -s -b 2 -C 32051 start + # Internal SPI bus IIM42653 iim42653 -R 9 -s -b 2 start - # Internal SPI bus IIM42653 with SPIX measured frequency of 32.051kHz - #iim42653 -R 6 -s -b 3 -C 32051 start + # Internal SPI bus IIM42653 iim42653 -R 6 -s -b 3 start fi From cfe4cc82eae25d25bb1382b2e392d2bcfb164f13 Mon Sep 17 00:00:00 2001 From: Claudio Chies <61051109+Claudio-Chies@users.noreply.github.com> Date: Mon, 3 Nov 2025 09:34:54 +0100 Subject: [PATCH 247/812] UAVCAN: fix message definition issues (#25809) --- .../uavcannode/Publishers/BatteryInfo.hpp | 61 ++++++++++++++----- 1 file changed, 46 insertions(+), 15 deletions(-) diff --git a/src/drivers/uavcannode/Publishers/BatteryInfo.hpp b/src/drivers/uavcannode/Publishers/BatteryInfo.hpp index 686dc05086..7cd45d6f2a 100644 --- a/src/drivers/uavcannode/Publishers/BatteryInfo.hpp +++ b/src/drivers/uavcannode/Publishers/BatteryInfo.hpp @@ -36,6 +36,7 @@ #include "UavcanPublisherBase.hpp" #include +#include #include #include @@ -47,15 +48,18 @@ namespace uavcannode class BatteryInfo : public UavcanPublisherBase, private uORB::SubscriptionCallbackWorkItem, - private uavcan::Publisher + private uavcan::Publisher, + private uavcan::Publisher { public: BatteryInfo(px4::WorkItem *work_item, uavcan::INode &node) : UavcanPublisherBase(uavcan::equipment::power::BatteryInfo::DefaultDataTypeID), uORB::SubscriptionCallbackWorkItem(work_item, ORB_ID(battery_status)), - uavcan::Publisher(node) + uavcan::Publisher(node), + uavcan::Publisher(node) { - this->setPriority(uavcan::TransferPriority::MiddleLower); + uavcan::Publisher::setPriority(uavcan::TransferPriority::MiddleLower); + uavcan::Publisher::setPriority(uavcan::TransferPriority::MiddleLower); } void PrintInfo() override @@ -65,36 +69,63 @@ public: uORB::SubscriptionCallbackWorkItem::get_topic()->o_name, uavcan::equipment::power::BatteryInfo::getDataTypeFullName(), uavcan::equipment::power::BatteryInfo::DefaultDataTypeID); + printf("\t%s -> %s:%d\n", + uORB::SubscriptionCallbackWorkItem::get_topic()->o_name, + ardupilot::equipment::power::BatteryInfoAux::getDataTypeFullName(), + ardupilot::equipment::power::BatteryInfoAux::DefaultDataTypeID); } } void BroadcastAnyUpdates() override { - // battery_status -> uavcan::equipment::power::BatteryInfo + // battery_status -> uavcan::equipment::power::BatteryInfo & ardupilot::equipment::power::BatteryInfoAux battery_status_s battery; if (uORB::SubscriptionCallbackWorkItem::update(&battery)) { + ardupilot::equipment::power::BatteryInfoAux battery_info_aux{}; + + battery_info_aux.timestamp.usec = battery.timestamp; + + for (uint8_t i = 0; i < battery.cell_count && i < battery.voltage_cell_v.size(); i++) { + battery_info_aux.voltage_cell.push_back(battery.voltage_cell_v[i]); + } + + battery_info_aux.cycle_count = battery.cycle_count; + battery_info_aux.over_discharge_count = battery.over_discharge_count; + battery_info_aux.max_current = battery.current_a; + battery_info_aux.nominal_voltage = battery.nominal_voltage; + battery_info_aux.is_powering_off = battery.is_powering_off; + battery_info_aux.battery_id = battery.id; + + uavcan::Publisher::broadcast(battery_info_aux); + uavcan::equipment::power::BatteryInfo battery_info{}; battery_info.voltage = battery.voltage_v; - battery_info.current = fabs(battery.current_a); + battery_info.current = battery.current_a; battery_info.temperature = battery.temperature - atmosphere::kAbsoluteNullCelsius; // convert from C to K - battery_info.full_charge_capacity_wh = battery.capacity; - battery_info.remaining_capacity_wh = battery.remaining * battery.capacity; - battery_info.state_of_charge_pct = battery.remaining * 100; + battery_info.full_charge_capacity_wh = battery.full_charge_capacity_wh; + battery_info.remaining_capacity_wh = battery.remaining_capacity_wh; + battery_info.state_of_charge_pct = battery.remaining * 100.0f; battery_info.state_of_charge_pct_stdev = battery.max_error; + battery_info.battery_id = battery.id; battery_info.model_instance_id = 0; // TODO: what goes here? - battery_info.model_name = "ARK BMS Rev 0.2"; - battery_info.battery_id = battery.serial_number; - battery_info.hours_to_full_charge = 0; // TODO: Read BQ40Z80_TIME_TO_FULL + battery_info.model_name = "PX4 CAN Battery"; + + // State of health battery_info.state_of_health_pct = battery.state_of_health; - if (battery.current_a > 0.0f) { - battery_info.status_flags = uavcan::equipment::power::BatteryInfo::STATUS_FLAG_CHARGING; + uint8_t status_flags = 0; - } else { - battery_info.status_flags = uavcan::equipment::power::BatteryInfo::STATUS_FLAG_IN_USE; + if (battery.connected) { + status_flags |= uavcan::equipment::power::BatteryInfo::STATUS_FLAG_IN_USE; } + if (battery.warning == battery_status_s::STATE_CHARGING) { + status_flags |= uavcan::equipment::power::BatteryInfo::STATUS_FLAG_CHARGING; + } + + battery_info.status_flags = status_flags; + uavcan::Publisher::broadcast(battery_info); // ensure callback is registered From 9702a2a899c9a48a3f22444d8ee49e066fdbfe83 Mon Sep 17 00:00:00 2001 From: Matthew Berk <8104397+msberk@users.noreply.github.com> Date: Mon, 3 Nov 2025 10:52:26 -0600 Subject: [PATCH 248/812] Navigator: Fix mission RTL for fixed-wing by setting previous waypoint correctly (#25600) This aligns setActiveMissionItems() in rtl_direct_mission_land.cpp and in rtl_mission_fast.cpp with what was already in mission.cpp. It probably was on oversight when the RTL restructure happened. The FW landing requires the previous waypoint to be correctly set, that's why it was only noticeable there. * Fix position setpoint update logic in Mission RTL Currently, when proceeding to the landing point the previous setpoint is not updated, which results in an unexpected and off course landing pattern in fixed wing. (see #25436) * Change to work more like `mission.cpp` * Fix rtl_direct_misssion_land formatting for style guide * rtl_mission_fast: fix FW landing by setting previous wp in landing Signed-off-by: Silvan --------- Signed-off-by: Silvan Co-authored-by: Silvan --- src/modules/navigator/rtl_direct_mission_land.cpp | 9 +++++++-- src/modules/navigator/rtl_mission_fast.cpp | 10 +++++++--- 2 files changed, 14 insertions(+), 5 deletions(-) diff --git a/src/modules/navigator/rtl_direct_mission_land.cpp b/src/modules/navigator/rtl_direct_mission_land.cpp index 7e8b3d4aa4..7fdbe1add5 100644 --- a/src/modules/navigator/rtl_direct_mission_land.cpp +++ b/src/modules/navigator/rtl_direct_mission_land.cpp @@ -122,6 +122,7 @@ void RtlDirectMissionLand::setActiveMissionItems() { WorkItemType new_work_item_type{WorkItemType::WORK_ITEM_TYPE_DEFAULT}; position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); + const position_setpoint_s current_setpoint_copy = pos_sp_triplet->current; // Climb to altitude if (_needs_climbing && _work_item_type == WorkItemType::WORK_ITEM_TYPE_DEFAULT) { @@ -203,8 +204,6 @@ void RtlDirectMissionLand::setActiveMissionItems() _mission_item.autocontinue = true; _mission_item.time_inside = 0.0f; - - pos_sp_triplet->previous = pos_sp_triplet->current; } if (num_found_items > 0) { @@ -213,6 +212,12 @@ void RtlDirectMissionLand::setActiveMissionItems() mission_item_to_position_setpoint(_mission_item, &pos_sp_triplet->current); + // Only set the previous position item if the current one really changed + if ((_work_item_type != WorkItemType::WORK_ITEM_TYPE_MOVE_TO_LAND) && + !position_setpoint_equal(&pos_sp_triplet->current, ¤t_setpoint_copy)) { + pos_sp_triplet->previous = current_setpoint_copy; + } + // prevent lateral guidance from loitering at a waypoint as part of a mission landing if the altitude // is not achieved. const bool fw_on_mission_landing = _vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING diff --git a/src/modules/navigator/rtl_mission_fast.cpp b/src/modules/navigator/rtl_mission_fast.cpp index a8a7809549..bb73fd6952 100644 --- a/src/modules/navigator/rtl_mission_fast.cpp +++ b/src/modules/navigator/rtl_mission_fast.cpp @@ -108,6 +108,7 @@ void RtlMissionFast::setActiveMissionItems() { WorkItemType new_work_item_type{WorkItemType::WORK_ITEM_TYPE_DEFAULT}; position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); + const position_setpoint_s current_setpoint_copy = pos_sp_triplet->current; /* Skip VTOL/FW Takeoff item if in air, fixed-wing and didn't start the takeoff already*/ if ((_mission_item.nav_cmd == NAV_CMD_VTOL_TAKEOFF || _mission_item.nav_cmd == NAV_CMD_TAKEOFF) && @@ -175,17 +176,20 @@ void RtlMissionFast::setActiveMissionItems() _mission_item.autocontinue = true; _mission_item.time_inside = 0.0f; - pos_sp_triplet->previous = pos_sp_triplet->current; } - - if (num_found_items > 0) { mission_item_to_position_setpoint(next_mission_items[0u], &pos_sp_triplet->next); } mission_item_to_position_setpoint(_mission_item, &pos_sp_triplet->current); + // Only set the previous position item if the current one really changed + if ((_work_item_type != WorkItemType::WORK_ITEM_TYPE_MOVE_TO_LAND) && + !position_setpoint_equal(&pos_sp_triplet->current, ¤t_setpoint_copy)) { + pos_sp_triplet->previous = current_setpoint_copy; + } + if (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING && isLanding() && _mission_item.nav_cmd == NAV_CMD_WAYPOINT) { pos_sp_triplet->current.alt_acceptance_radius = FLT_MAX; From c44e0be18ae58fc2850da472e41dee4a3dbe1398 Mon Sep 17 00:00:00 2001 From: Thijs Hof Date: Sat, 1 Nov 2025 15:18:36 +0100 Subject: [PATCH 249/812] fix bidir dshot for nxp xrt boards --- platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c b/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c index 233d4fc288..d0558592a5 100644 --- a/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c +++ b/platforms/nuttx/src/px4/nxp/imxrt/dshot/dshot.c @@ -425,7 +425,7 @@ int up_bdshot_num_erpm_ready(void) for (unsigned i = 0; i < DSHOT_TIMERS; ++i) { // We only check that data has been received, rather than if it's valid. // This ensures data is published even if one channel has bit errors. - if (bdshot_recv_mask & (1 << i)) { + if (bdshot_parsed_recv_mask & (1 << i)) { ++num_ready; } } From ae03630570254b2e3037039569a38d13885e8e9d Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 28 Oct 2025 16:03:55 +0100 Subject: [PATCH 250/812] uavcan: more efficient calculation of esc.RawCommand.cmd array size --- src/drivers/uavcan/actuators/esc.cpp | 29 +++------------------------- src/drivers/uavcan/actuators/esc.hpp | 7 ++----- src/drivers/uavcan/uavcan_main.cpp | 16 +++++++++++++-- 3 files changed, 19 insertions(+), 33 deletions(-) diff --git a/src/drivers/uavcan/actuators/esc.cpp b/src/drivers/uavcan/actuators/esc.cpp index cefc5b276d..15b5504c45 100644 --- a/src/drivers/uavcan/actuators/esc.cpp +++ b/src/drivers/uavcan/actuators/esc.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2014 PX4 Development Team. All rights reserved. + * Copyright (C) 2014-2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -74,20 +74,13 @@ UavcanEscController::init() _uavcan_pub_raw_cmd.getTransferSender().setIfaceMask(iface_mask); } - char param_name[17]; - - for (unsigned i = 0; i < MAX_ACTUATORS; ++i) { - snprintf(param_name, sizeof(param_name), "UAVCAN_EC_FUNC%d", i + 1); - _param_handles[i] = param_find(param_name); - } - _initialized = true; return res; } void -UavcanEscController::update_outputs(uint16_t outputs[MAX_ACTUATORS], unsigned total_outputs) +UavcanEscController::update_outputs(uint16_t outputs[MAX_ACTUATORS], uint8_t output_array_size) { // TODO: configurable rate limit const auto timestamp = _node.getMonotonicTime(); @@ -100,26 +93,10 @@ UavcanEscController::update_outputs(uint16_t outputs[MAX_ACTUATORS], unsigned to uavcan::equipment::esc::RawCommand msg = {}; - // directly output values from mixer - for (unsigned i = 0; i < total_outputs; i++) { + for (unsigned i = 0; i < output_array_size; i++) { msg.cmd.push_back(static_cast(outputs[i])); } - // but only output as many channels as are configured - uint8_t min_size = 0; - - for (int i = 0; i < MAX_ACTUATORS; i++) { - int32_t val = 0; - - if (param_get(_param_handles[i], &val) == 0) { - if (val > 0) { - min_size = i + 1; - } - } - } - - msg.cmd.resize(min_size); - _uavcan_pub_raw_cmd.broadcast(msg); } diff --git a/src/drivers/uavcan/actuators/esc.hpp b/src/drivers/uavcan/actuators/esc.hpp index e758bb1030..e488cf823a 100644 --- a/src/drivers/uavcan/actuators/esc.hpp +++ b/src/drivers/uavcan/actuators/esc.hpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2014 PX4 Development Team. All rights reserved. + * Copyright (C) 2014-2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -71,7 +71,7 @@ public: bool initialized() { return _initialized; }; - void update_outputs(uint16_t outputs[MAX_ACTUATORS], unsigned total_outputs); + void update_outputs(uint16_t outputs[MAX_ACTUATORS], uint8_t output_array_size); /** * Sets the number of rotors and enable timer @@ -114,7 +114,4 @@ private: uavcan::INode &_node; uavcan::Publisher _uavcan_pub_raw_cmd; uavcan::Subscriber _uavcan_sub_status; - - - param_t _param_handles[MAX_ACTUATORS] {PARAM_INVALID}; }; diff --git a/src/drivers/uavcan/uavcan_main.cpp b/src/drivers/uavcan/uavcan_main.cpp index 37e36c2217..28f64049db 100644 --- a/src/drivers/uavcan/uavcan_main.cpp +++ b/src/drivers/uavcan/uavcan_main.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2014-2022 PX4 Development Team. All rights reserved. + * Copyright (c) 2014-2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -1082,7 +1082,19 @@ bool UavcanMixingInterfaceESC::updateOutputs(uint16_t outputs[MAX_ACTUATORS], un unsigned num_control_groups_updated) { if (_esc_controller.initialized()) { - _esc_controller.update_outputs(outputs, num_outputs); + // num_outputs is the maximum possible number of outputs (8) + // output_array_size adapts to the highest output index that is mapped (4 for a quad) + // this allows for sending less CAN frames depending on what output indices are mapped + uint8_t output_array_size = 0; + + for (int i = MAX_ACTUATORS - 1; i >= 0; i--) { + if (mixingOutput().isFunctionSet(i)) { + output_array_size = i + 1; + break; + } + } + + _esc_controller.update_outputs(outputs, output_array_size); } return true; From b010fe904c5b7ee19edcec8a0ffb10e275fd986d Mon Sep 17 00:00:00 2001 From: Vincello <58676585+holydust@users.noreply.github.com> Date: Tue, 4 Nov 2025 11:25:40 +0800 Subject: [PATCH 251/812] fix board_id --- .../743v1/extras/corvon_743v1_bootloader.bin | Bin 41044 -> 41172 bytes boards/corvon/743v1/firmware.prototype | 2 +- boards/corvon/743v1/src/hw_config.h | 2 +- 3 files changed, 2 insertions(+), 2 deletions(-) diff --git a/boards/corvon/743v1/extras/corvon_743v1_bootloader.bin b/boards/corvon/743v1/extras/corvon_743v1_bootloader.bin index a9209278330a4ab0132e5db7161ac06841e6dce4..0875784c2cc2581783805b47f15c0ca74f715813 100644 GIT binary patch delta 22009 zcma&Odwdhswm81`%p{pMrAZ%@(w26TDbO|)(iWtENJ!e{*o?BZyR8a?7&>b3>Nt0&2pPjHX@Q>}dzbV~h{%`>4ISSGk7r{%je_k`*RRlA)z z-vO)(0X%yI;5$Rz!!<8-53hS6xjIGUF{D$3<+1y6;YJC-LImI|A%Oo7aj8sZue?lU zj4qWi_R5t>Aa@S{xd4FN%7cJ?7J%G6zk`80-P>C;L~GFNu{wj^;tb)oYPc6Rg90$z z;)N~1<`{m-yQF$)Rf@<5>+5)IqFtD!Qv{>P2M6k0*g+d_JO{mXMu8AlPm}K{g7n|d zlCaS2tj?R)eBZ+AjJk!@&2`jOP@HkUqq^_D4AF@XFY{yw8RA|T>B$hyFw#?8og%&r zB0Y1eQ$!cm(<#DicZTQ;I-D^$CekyrDqh^fM0!f9;zcK>sCc0`_5`VTf{BUr%y3(+ z8NzgThG@kG%86-;)TMAKm0mF7&#x+|B%N?9cLl+6qer00%LZ2vY@mf)QYkp#bOyc4 zNF{4<;5vUO(TWG0PV8Mq3Gt#e=ty=3K{9F5iXF=`1gf>ZB13$UUT}5wQP>RU*2Rd7D8Sl;zGlb(_ky4#<-cbO!Lj6bFpzo~49xC`Uz~t!qOmgz<7k4?i#GwCsmm{ zGNo_W37!e=303KfCJHs!TQqUCMRisUK%4AB;us_KStVvZyE<*r# z-3YLns%Q@2hemjj#~zmp54d;%^Q2Gr{ngwBx|snm;QbK{u$RFA0D#RR_n*PQJ{sh{ z7zfz9;{cn|;pHKFWDR1FrYw~niJLlkzQ%Q$ru}dc6j47+6sT5nSB4nx$`C?weFfVQ z=gt)4+?i5C?u4ZGEOaHnH-)BM1_ODQ!9e4&AL3R~^H0SA))xm@wgcidVaNf@sE}hj z00t_#&JWjD0L&f-Tzv(wun1!I1cSMguoB|iCEd6j4~^dl(|o#hb``(Lj%K@O*L-?W zSEA?7@1XIo;aOE2x<#PztDzD%d|N~%w`K_xZ>xvcF!IAi04e;M#_%OVi3n}wKiEYt zpzvR{0(ZJlA~FJ3`I-md`0ybyyRu)rSAh7gNMV?b^x19B@FkUNtBxm78E9sVO=d*U<6;DB6B zSt%_@oTz(G0_-K}?!+A3igAFANDYZo;cL>{i9A)5DE%Yx7II58af~l&XpxFde}L~v zubFb-i_*uYeAC0xJfv@}@8ZxeBEVaukm-TtuY{QFx&3)ak7+%?eIX`0q5rA2WoQn{ zLlD0=!es0E^ANyWLriu`-<@sb`EbZGP>hzwApRL*vVZG)XDzS=d_}P@3#2ylq$#hf zOm=^)rYFQ9sFOso|u?b=U~z4#2_`@pw0!4CmP#OI3ak9NLlC z82~1`{~s!FXzjlUU#VaTf&Xduwe|z5-Ar?!#fs}Fh-o-wW8La_7xc7Lp$9h}TK&@w zCQwEJyd%V+oodz|h;JLwl)ptMRB?#Hk7$h5x=B<15v@ct>CFpp7PP-7r-+GFt3ZkX ztVXd{1%Mvv z_!pIHJ0$jtv;a7B7eN)4>pS$QCir|kgwny_5K(xuWSqFXrZ%i=>A$}G`bO;tU`zO*TwkGG(z(qY zS)!)=*9ajcIn;H*?9h~f6GVpC4$2L=Oi@z~hQ{8#B4?-Yfb`zP8B|`2^skAxz`sb7 zGV*PYg)g`78cu2?BLcefT4H3o{v?82^Wqvz#c?+sM7vt;h{8`u>oY7xHDNfDon@Rh z=m(sRbYlmpW9~S;n?aen@n`0Cdd0jp*Avi2`KQ?_{HSy~WA?Z!Due88&JW?h$8uI6KR0|F2!XP!d_{1)+2C>^k!C(C!*<4Wg7?xhG~!G zq4Zfrh{BDbqfW&ya1dYC7*tD2b=1@ew@!VGL+LXK#HP@jPQ~xwAU=B?!l46G&9_e7 zz#(%C;=%uh`0BqQsHyD#g1DVPNViX#wYoG!Y%*eO9E=0GL^8&sJF0W?cC~)1f>r}c zMExpzkokTc9uHz{ePLne9JB-h+^I6?fzGs(fV(0CThMP5p)KIkl*^+a@3Q|_c@C;Y znsQdUIBAyW+^7!i>IBn#J`TkP%#gyr#isVl+TUeh9fSO4^s;=Z^Y`JT-Cir;e;+pQ zc=WH^hm#t244WILR8n|IWzfANyN8K+a7;We z?3b5t5NBx&`n>J;;iTFfu=)34^V4GppB^?hg1{1rLn~0~%x^AIJcSRaR5RVO&l&WO z3H9&8NjoSBw){S9ZhZ8wq{+r%b7L){@L`o|VbB;)j&X=Vj<%?B zP0L-A+Qx5v$4UF6ilz|>&K0l9+NET-xg%3_wIx+jc#S&HX|5!bgTi&kC7hX-VyOJN zox-=NWJK~h(>aKnq^EL9V5)R7rwHCHUCyb zo(k;Gsgwi0MB~#Dn9cN6ISrK*&Q^bw^_3LPP&xFI47z=BAlKUh*h4LV{YML6$L*JH zwWLuyo23UW1+L2dvB_GYi(}BKVS2)N%<3HYJMTm80!vj*ta<_4vj|n*Y?A8u$y3NTwu8nO!!(w|H2x(#&Ydo%cP6+q#Y}NSC*Ta&6_VcPv#F9!=^uRB z_*X~a%M7w3O(~6zBT#KR{I(S0E8sk7VeSg*`KYu%_onoRP7o*l_mAHD7XSd1cEm55 zEb4I4s5F>67k(^Fo;-trc$+5GPA;Y1j7WPY-$XTdq%S8QWFQ`nN`IJg6B&?ypE4!x zjCCU7gs37*JyT}D|CDr7d1}oRsbFe*(#&Hi=zf@5^UI3q%=k0!)5+51sfF{{Dmq}M zAfF&g4&G%HaF+$~=$|s^21eEa)L|`)WgP<@d(`w(DYw=PE}GD_!p2NE^A2s6R^%1k zq^sWH09=x2bfpLbT_BFsDT$Ce?k(|KzS!&>q^+)P#FFdR!yZlfv|Cf2@0L#G-B$Tj zdUWd-ZTfs`FXZVF7$|c1+u-DPQNoCBc%t(aWcE!NOw|9}9^FW$Nfy7>Wo;8m(#vpH z5xOYTSNCpEWjM=FDBYEhJn7=8;c>)C>1J8hL2q3>ypX0h61U~|;Uq8Mz1IJ)o-tIX zh;!O_OwlRA>DcN%&BOEe!X_x9dq}I#{o~?cQ#GZI}rr2+Y?}@ur$ITSW zFr;%aWJ&~xJJgxibp_z+yT`y$F`xu=Pp5I)4C(vAId`^p)opt( zW8LtdQb1wd3rJzy>;7G>fbqYoXBt->qw7d9Wz-; zZ<{M!D#+5;cj!<8k~S9PQhB3Nb3q17kU9$NhM2sYjncnQUs*mHwWDEKQ(n*p<#pHu zE)!JXX^n{mtH7fqc9d+0^bm0)EH3SEZDUZser^xFZD!RfxTbKP zsUcTNy681TdUn?m5!=0l+vbIu;v2PAaoeEPC~kM~gA{EP*5OAWk&L0yF|`l4(k`hr zGtHwZZ)w!Fl&W}c8C+h=2Z76l_qdiX8CBLs_-%>Rlw}n(R=&LC^{WdXC2ajb*PQ8LF_GS98%4hAJ5!LBKp(YmdS^}b<4O5MgWiw=Bb zuI?Z~hX*xkTRazEMM!XAuget#DTIWAh`t(dH<~5G$I^9=lSPO$Kse;wMx$@_@QkMP zN%z|4dtQo+g^0{un$n}Gvblp=!ys#?YukOp+i4f6YtfY6aNV|b!`tb)$5$Dyp0OY* zwu)-X^B_7tU0HC>IGA3uoho~ zv*ONgpfRX(dQ~SNZ9?k3SNgdX-eX#F0h%_UETkfA@C{S%ShSeGB&`mD>rA& zw&F$9%6d%+N7imJOy}_;dhPl?{{#{oDh8I+$_$|f!{n8Mkx!{k5u7S>^D;H{WH~JFNUOV}VwN=C@P4$Umwn{|q~bBL}e%iKZ&@gr3AZ^*F zrtNVKCR$A+PpQUs)5!K{XCT3p*K4}M#IIEIvEL5Z*NOlu+W{N8es3uT><`y}zZ3(O zE&=QcJIE#%_IEpA_o?PnS(q{Dd{hDLPs3gl@a0IJqVb-+Rjc62S`u?zxn!TZ#ZDw> zr@F->4}sMgaeYdXIf9QlZB=dN{qvM@=8+1Jl3rgM7dL>tT@c^{^x1 zwM~l#T?sqYNvFmS(AY!kZKr!r51ppt^);BHY6f@Ei@JppvWD1lp2!xOAII);0}wd$h;dlN9~7j+AE zaCL7zSEebZFqzBN=q?#d_XJCi!Wo|6tfMr#Zlt+7rw<>Y1_NTGr9Jtu!{#lx;yU?I=&SAA-?3*I+_Qiom(8 z&!jj$3;+}Kxq{m_@Y}b^!+KAUI@?of0oXha+~TdHO+DM(p6ej*wSz(jj%y%5TdP~zfz5$`@`7pRzAe?z zvSo3Kn1{x+$*3|tazW(UC~?`E__lnsr^2F(?^$2gSpT8Scmaw9>)*(iT0(vk@ROc7n;?8mcT;8B5Q%3}L*4OFSDy+uv3+x)Z#V_LA8{8KA6<;O^iI=?6d zGtl7Il;=kX$m(H3%5F8u-f5tED4tZDYcTeZk{bjQ&+?8@Hdgiss}Df^$NmZOnBboG zla7E^GTk(#Ez&QaGk~5kf>Y&Gz&bqXfOW)2T2-P+$%01~JEBQ%Xju-h4q)~IqG5@q zt-*q^1_Smt!-k$ms%r)-GahlDQ%}8^DW-|gx>Aj+r$*Q-#ZIs{z1xMobdF;JhBTCJ z_JNjrM;aqpmMMd@{$6*s0QqV)&SSsF4Z{gV>1gFvp@>YV8b5_GwWJ`?uPJLr?sQA) z7A_exQ190i-NT6M>w#l1 z(fqXvz{HKs8|NCR9+os`59@Ah`_Wx>iuevUvo?y@WIb*v`bt%F>e$8CWT6BT&KvQZ*UJ8x316zE5foEvj@fTQb*z6d%;;cx;I6IDVoAOTSgs*{&Hu?}krQ zb#`pia=9ybYI%w<^vg_^b(pU&nlYb+Se>yUmL4zV;yzTNg=pa>>DAJF_@eYhY2lR3 zDzK1#i7MbO2*kS}1~XZ8>pSumUl7?gP5E4t>L;XmKrXQ4R9lq&TxZrY=x%2L&W ztmrXrRB0N~_=(juL9dV^aK)df14SvqCn_lBivQp4#CC{xX9;%+cineZXcjc3MAejX zb?w&shiQ84#y<@wc^d1x2wkK@q?2mLzSzbmc+`o#F*|fAjP&fOj4BtxFH}aAUt-sv z!q3-e%8T0b?wVlmQD8|&w;+ILkM6Fb5RGbZR$>iyBsf(e6C$S&wSKaZdJI?-!&GWk z$-Vbae1HjT*6mZbILfdzcdiAVlJ1&Y>RD4o`mBUN9^Kbsh~FAu51dE*sED#Ex}rLD%xo-4 z5dc1|-ceml-tj3qMIc*cU^y`}c>&}C5B@-{aT8`|35Twps>=`$T{*kK8a%b^w0d^x zck0=xWGk3FJFY-$hCp52ORW^DichNp9J&4+yIzQ0FU77nb`5e-WvLcb>a;mAV@|VV z3An_iURvZ*zh2~0FHDzT7z3DYjCU6iZv?5)nKKCY+29=K&Jd!? zuTf385_*gyyp1T@N1!{QlBzYn%YuY=SrGqz9N4)ZutXTd{eZo_1h6b%9SMMS-0(z8 zi82H1QU^#Jla>MEgc(`Kz?hroAS#i$t`W_p31E9G;Nz-*1e&)y;df+@8%nVG87KWc zXokgL?-dy~!(zBss=ql49+aNDc?MiBb=|xvJ*liF`1+&isJ`Rt3}Bgr=&P?k4)7CU zY0>_eha|L! zK}h;=etOP<&iV?n@mboTL#&v903NS8vvfnitQ(?|cN`m@p9AO4^@ABV`3!*xy2;q2 zJLgN7O2Q#gs$MXqW~NprvNMTX zmZ{9mq$;m*NbQ;|T96%0Lz?2&PRhyL*K!v6Mo#H~FKWsw8u86xGq3=RM#zR4@y^LM z>8DcHf}Vs2$(E-1U`0fUi%PFJ-dI43{0Iy{3;_u$)mNB4$m!6(vs`5|;fu6H<5Z1q zUSfwY1H47mwcf2VLriOZMSTZ@?8gA^l{^dc;aAez3+EM{QXgIuY5Q%>2Tp^Z?1cQ6 zdTGs?HTP!_l5G#|cTVx&lv#`{NEB&&MM`p}7(b6P;{8qndqSGwT;TaiB|-YlYCeL^ z^kINs4CxU0^1Pad;#%!pY{#h579o>cQ=W?g(cxsfN;{yHLBKN2t|?Hf!P+dqGXXnz zpzhO)b+F>1< zlK&CgMR-Kx&6*CK7n_{PJ|@8G?TE%(qI9;QPg5pH9v6St3XOjT+7kVQY8LR@3C{BZ zjSodZp001qxgG9;^Z4!NE@%O3G)4W0P(2P=))3B(jzT-_J1@eL^8$(7{4h$3j1Bu# zS-T`fTzLtzT!1Zf0rtrnz)C9aI>nlh{_qN5C z8BscdC6bf&1D>y^QQSa^3KJL=8bMybUz-6-&0R*6qCy+Nb4{jE27)C?n?e4F-<(lj zL6yNdG%|NcPJ=H=g*CJa-C&yHmz==wF?W&Iket&2IQTY=OGiQ8yWLb1*(teOWy0E} z!i#ue{35I9?2KO=f2*TBT!{$%euUo>m5d$v>z+f(ec0nle_msz-F57OYJ=o;7s#;Cjz|b z7T=M8o$hasv(@yb2fd!;ZYpe;U5ULc71rNm7&s9qG z$T;Ia5-6uB+veW*02f~w1hw~$JTpSju-*EpCjt+cLhTOxj29MF2ECPEv;*tzfl5rV zm6&1saffz#_!wfd>lTQT1SgCj2jZ(0Atkf%dcF89K^(Lx2FUW~Es%)2! z1RkI%TjTd90(B;U-)o4+=ji1&2kve79=+;bp)&6f9N6odpyt}yAgJ9?lY&{(26uXQ4tjIQ5FbBe&`nTbre{s(Y(yNXFSgGr z`wCGlUBA}g!uZp24YtLfl8?tcT5ir4?Yu~uIWM1X|3T$ip|si!o6`qrQ-(hUv2Qaa z#xnTw#I_U_PPFIe`!WNJ$<{BG=l7iq02AQ>)el=*%5(dS0ce0N=Q2$rjl;l3d!)a1 z+Xja==y+H{Xa_!6@>bguSt(`5oF8;w%K%f-ahxgBUxHEx;LDZSAGgC7zm#Fiz1jbg z!PK*IIyRfqyJ3ke6FxA~o(iS~&a;ZZcFjMlEF1mb{2;tb@V6soAU>eYwOc%-SG-8T zNQFBP-2!ZP_7Rer5iKRYv#Km*o=$paD4vGRTbz>f=I$>8fYvpW>eIUI{C9Ufl=VzG zv)3x-_R%kEF1iWMIqvN3HX%Zq!M7z#=bvuj5G14>fGsD>O5~DwqSEauI(~es4cu-`o$_xAy}U zoYJ%d>SQyAit@9&$%ymVOg~5NVp9c}!He^Mpk~!z7*FstRoq$5i+o>t5Zud)9uB2; zms=jNG*yt1V)~2y1VO)kde2t@U@WwZjl11)G7x8)a(3*E7mWcs|~tA`&*H2fDLG+H>A9xT>0)J=f4jb=$YNXnt@IS0A1P* z`0-`gW${A>_LFkxpI_GWDIBU!)Bwt&*5|jy{lFaErdBEyTh45uZQvFbS@c$G{C35 z;{qHT&pQ#ob3zA)SoYqLMwP&PqcUEAJG?dww=}Iq;!6*LbqU?+?X~S6PuL@q9%uN8 zBD&GxJghf*P6TRAq<_eFB(RR|YmY0a>W#Bi^q#vw<0VrNLTCa)vq=NS029}*0swu$ z@}o?e7`fhrxBXOmP|m|?#(4e)uV~){!YgXJk8oUFc3ZBj~MxepmtqsFMD6L0))8Ph|{JrUk)OM~4XxG8JbvRTzhKbbtFX zr{`+_4MmfI&8A!*FWO_1gdj@x!&xVguiV!E)({Jhmw(<3I9(ahiTQrmVk?`39{8mK z&66{N;9gyT((z(ycdcb}to~1=X*y$&HvQnsz?4ZBfU$C$g|lP?z4xYf7g`2o-Vc7e`%M8k`znyyW)yrjTKllwj8TI{@0*AUTs5{!# zGJA_befd7CgS|7V%-2YpBvaSiSoxfl2QM+>q>CQ{2`XqmSx=mZ+k3$9kF%{Qy6F62|Ud zpCpO206!n@y1+UBj{mTiNVkV@NQ}T(i|9;?p~S+yQM8lOKz_3 zh+CvXiO9N{Dj@jQhxyIWrt_2R%dQLc4uE@4l9t|g2u=-0b5H?fem1BJK!{Bsixnf zZvnO|{iHlW)wfvY<=8It!q=CnJOlK;f4*nl23U&Il<^wK1K7G<*FyY%mrhze zP!oKjUQ>pny6jU|(zX*IItFCkE@m@%;7Y>wa~A-njfqLAfU!JSsVU(osZP=7WX2*$ zKQ5o($=4VQyN5ljDL+T26$bsk$Z#^j)DtDm{nVgqp)pO2@3hXql z*J%8Gv=-5LD9WJ9ldm9-yoPVLpTfLs@5=%-cS&`Dpatm6hY*pj)K?FLga zJ)H~OusL&cO8vqs$uwnQ55K2!c1?LDYLUU@6LKxeN5%j&(zrYNg-oQ$ABA=YUf00P z{7Nq7G-Yk9`_DIw$28@@&otO3_NuITw-a31+0b#->j7814d>MTtt-$GXR7~mPE*8K z*B)!g?XdLAHeG~mM z)eKc=gvI}q`&D2jL^VXob!T*y%GmZe9hhriX7ob8|GOf;-K`tnq=iibw$H)Gqsd}mSapyi{lv-}j^%N~qnR#tj zy&l=m9tIY(3g^M19fL-i$?tDprt4?Vh(G`f@L&6~^NA>>~s(mq3|MCBes(F-Pddo|-G#ecFke9WAD+j#_&kXKI(#7o!3KFlKONN}#$woGIIJlTkLDvH z-6DYwdN(YJL9ZAEc@O$H>zt}_lgABFAga6>Wh{onhL<#D`Slt#u^M1Q$*=cwno>ae zzqtRi_UyvyUP2QIQk45@g1&khKQX!k)dat-r}1N>Q`{}(bNrLtP0pMA=hS_z1fqP< zXk3A4ER2r9-#1!Yz99JU`wOomr)>IlY#N(Kaodww$G)AEWH)ux#n z6ux#GbO#Rr_M)_6Wlj>{jSb#EREeh>zw**z=9+YA)5?YLQK@q!Kkn!Wa)8AvLVVxh$#xDQ?wcD;N75SK>-uc0S;9Trrfq?Bspxa5{(^cEFtbzOS|Me+zt5GpM9=9xm|MF{D+>+Y?qvR{|BKd zW@zOQoCEM$b$lC#AU>=fDbMb$L{Vi(E%L;&&t8h^&=>Lp&zecz>P}^} z!;<@UwzQMx#v1sCe58D+Hv|2rT=Mj!vRMu5aHj5z+Gw}6@kn3&xy6Af914vc`5@K} zerg>y=`PFedjMP7u~TH%{63tt>wl-ZOQ-HD@aVJ~xkO%dshL=$ zxQ0QyT1jTFcM2ulNHHdv@+8IBr{2GZ=xh4VovPk0*h;$v9!h6aub22j1-@RD5$xjc z!%5H3BrAB=SXS^Zl1ps)KutUKLc4XhY2?{Ra{IpWO#hFbXRN#9+LPN~bTa;*9s(8) z?R{uZ#e_BzTtBXnpusc4NsZ?^0e3)U?Igi?EV~-EoOBL+KXvy{YZkPBd$;p8>+TOi z8TGI@x&1Fr>kfGK4K=+L7X3|T0$wnxe5LJEtGFUmiQwFwY83~qiuZ4-*;~9m@p~0; z$!qphfV=~~Z)EA~`*W*z5okLs*{N39Nw+&f@pitG*pBrMO%b~5yB4;AwVymg?@n&d zY;Sf#pQha2O|~9LYIAMd(l%CP+eVesqf+Z#R*F@nGk4v>04!@#+TC-hMWfQPyPv;l zRFR_#MUXH1gg7L^3|6B>!t9Ju7a4%qIcQ9x?Vo?TKg8&cktP!dB z-s$jtY4yDx55S)2f5hzjHPK@vaaY$WlZwPAF`>OGb86|9KW|wy2&ehC_*B-rSEcu$ zK{#d4=A_Mz!MN$Y>cdNtu)vr`o{xI`%QxqYJRj80)7ik4Z@eU8K!4?$`@o{k0A-ru z>kQDQX}-XrVv}0QWz<9NKV_J|)!(F6+M#W;zgOL7-(ODoV9EaS^?opIouAbEakNRT zG?S+s4RC*z8}jR7HGu8j|6RjWe!Cw`Tkf}sS@qw_+%(C&I>WQS+~u!Tm(4J6HZemu zt}K$CmmPWPK-mBha2ewWh z;F>D_DqHfiuD6)(PsDU0DQ#324FKC=ALK5}mi&b4<*a|Krft8E;(nCZVGfA$I(!d! zAa-ITwn@;MYb6e&?l7>7D%YY?-UC)oT9`qlo$IhsXK1@wxDgVl305s5Kt0iM0doSF z!UXo{cB*dghZjuX(~I1LpI)>+X!?x2nLgWpfd(}}r)yI6t_w7HLtSQP`A^l`4w@}H z)mnQ^Fm1z5l|IN^ty+10Cv$b@hMnr-RuLV#&v|X2uFkWAxmvs7{A!c?(~HKLCigQc zv*$|{*jf^I{j%Co8t9g~}s@u*Wk({PcMFeqNm_wt=bE+;-55mg4NFEwh_KeKcwc5J~g8GgG#N^p} ziMKJ{LQl#8;};W)*-A8~YO=dGh%|=uBp1ZrNo{LO zV5juU+LGMKA&_^?uM4EcFF_D53o+Rl{X?5+tU>oN^5uolMVXwPkd{6CJe()}_;87? zU)5z#lJ0GoAlV<8kmm-4IpWJ`S|6bThQ?N+^AC~ikDV$!*z!sbmTfrG8k3f zP=TcsL40=vSnLSm6%iigp)m`k>jGW~aQ{d9rG zM)oDm;7~olyR>WVL{Zmwk!?a?Nwfp}H;oWw1^|DoK?@T|1pt2-d*T4V|DiE~WB@HB z8~|`@cYVhWQ5PGB1U(6>AdN&E^xwmId_8%;O^c<4Th2ekA&Ydf{_fh{A(CEBlFuLP z1lZZBcI?(z6D@zBrRYzUGtMK5#@`>FC?T?^Mjgqun|o_laL+(>>F)B0KX~yxV{j+A(Bj!`|rZJ;oxf5+yIq0^?!K4L4Lf0T!Ll3_y*TQI6a0BfVt^bL6sNOx|? z_e7La8rj>GN6Cbq8Twf^cWBCKjmg&a-S3Pj>qf^6QNkO5?>b)J0dQy3|Bd8IS{U0KXKC z=PK!^p)J7=c)EdXN4o@o2S&%Xqgh8pu}hg7EmTWbx@F@{RKkAg@r`#tm-NlX9q>P; zrH}nZN33g~bosFy=#s`gemBgQ);?~bl(6*t<6B{yWZX16?(m4dNoY?NO3J1RxIkL4*#gH&t2Zx%1&hOn}czo3^aZx;tb?5#@x+q57_aBHIS=Z6OYU+=$YuO2I8pz*nSoPw)^( z(i0W7CQTH^RsQWFr33hw$|0gI61a%sP-(QJ4ekNCI^nR`Bmn$|qu`c@Sf-|* zQQ18uKP=+Hil#BB^;leBT0A+w_IgN{P4{sqten@*$=|E#MMG^_!V>g_n!XU=??W7l zc$A_r6Ue2>>EZ{4y4C!BZ>VM7PcQ2E1b(NA?60R!8g)qpnq+kA`I2u`70)pT zkw1JmebK`_(AS_TKZiM_YsFn8^F>oS!#56guT@F1kLZHE2qE3=2^+pSNksQ(=%7?*AY$ zlwfyvo`1SuZ|u>O*QCy^nNX5?w(@YY6xx~zd1?F~ml{SsB6FfjdgPA_l6zFh1CAUu z(^qk5MEORQKKi5G^M(reJj8D*?E;gp%H-rH?ntQuT*@M93O&^-8pX^`qu>^BSF+gN zCaLCAJ_?-$)oxTVr&+mlXav^OKFXU{>Ky~O>*(NL(vNx&na#8yi=yot; z$MGq5rr0D-vy(#@q#eecDe}@I+iXe(7B+ky zOLI(I#Eb5>W^pnCQ{dcYffrNST0~$2Kh$>-l2%4}F|(~%Y!Ktingy4Lgi~Tu#gGiT zrPA#;Q=dkq$G7KE%!qVwdpf)*b#5<8di^*#6g<~mcu{fb(Kz&?6y843V-PtMQf?V7 zb=*7BsK7m~ZSZhN`9y_?e1BLiY@^UJm04gDmWyiz{g#mOCzbpefPL%)|Be#z(EVgb zr^NTY%GiM=yOIgyvfry<;8glKb@Qpr>V-q+*8~1iI1vK;TZBgtO{gYTb6=E0dXFWf zY}Onor0g2qr`}}-d`|wM`;&X^D6H6`jcxnXy97}9H{WgQT?=eNow!ywCF?DOw7a!m z<#jk-|GT^n)A~y>Szh2Y0f*BB?%n}d@MZJ7vCRP#A#n+|gRM4ktedUM5P)^1pej2f zdbh`5HE|gN**#E|vJ=`e14tbJ1D>6LH4lIRlE;*Y%CpC-&}44gka^Y#{PkU$@||{7 zrrhxeA`E*yH^7Axe+FH;OG8o@Hf5p;%x=2Zo?ts6?a*V*h2hzET-3to%n~-7a%bCUAaVzAEK!Zv24_0VS{jkloUdW{iJ*| zIw?Cv3PUQz>Yg{**b(gm?}3^bLll0(B(rA0z5Ke7XVi; zb^U1tJSa_gs&L%XQA0Bwswvm0Fy7tBR+>y zm5KcjRu)O$J+&NKrKycesnCe@MB}?KL7Mt>dH(lL1NQBw$I{eJi?HOhP+vj2X@Pd{ z5CBi!K=;IF0Q;o$($kM5{}_Sxu=1wLAafghIjnRyz$AeGPZh@k z+(vPIdpb#L`w%fsV%ZM%NwQ;^*p5?&#wnr5C+SeE6gy!GZbDlTppi*KN@%AL%1HSz z39&siIYQzzY0Q*Q0%Qio^;Av>0@~2h0F_Lcu_mQthJtE2>6{cNd(yeO&Ym%M(0a%iVZy10jAH~tDt}M5f`f-4B^5VH1*U=fKF}N5mq%6Px z<+%A2I{AHt-3$i{q+ez0O&94pMu(|;b8*Y2k|k2j(7i44aT=X#^jAbQvQ^Q@c%J^~ z2zfFFvD{Ns6-5L8RB~7v8CroZN{OMWx~Je}W}6(a9u zcxcRnyx(=mX2*!& z$}Zf&eD^lbhT0cTkEx1`)p?zsw7~&h~r9Zc6Mk1K6* zy*OiGVe!q8zq`P3ej41%bhR8aq5YE*1-JAiF4Xm=tM6*a?@`d=F|{yf<1Ff;&hE6K z8>`&aLBX7S!pdc|4rY?tf2PB`#rJD}cRHdLWQ#hl(w#;gtb#J?HJ6BBCP%#?$R@*9 z@x>X;y3(90mKqewlF$ZnBn*qsPXp=@i-e5jcU_0}p2VQQe7sYDY&5*P_Wl_ILi~^j zZ71UAr(w-YsdqEHfzKPRA9A5QBU5sdt`4_>i>L+4ImMzbq=dLlD$a}uY@P|tme{u{ zEDwh%`}T#4?AvjAtVp^3grMTm6GBE?_1NT~@Mx0hTIsn^>q?u%$5ZcRc+QYF&D!(a z)kSVT&k>Y2UF}WJzsr{AG7awAC<(cS{BFgf)=(0<%T%1-=M6D=Qx@{3t2lYTwJf7` z_$K#x#pKBhQ)ctLFjJ0VUor5`G`bU1tVF%$WQxAUW$lwuZ)=k2YWBF&Wv*9duz6Hv zp6T_zC$1K2Kdz4dFfuk{VK&VmvpLVrWnF913`1P!r=b}Z7rELV5}jg2$|O#IX%+wb zrQ7?(WORnH49u_yb$yn?;$$iy4ySgA6RDqwzesh6J*n3-47bu#m7?pWF$FRDM_}fu zuPWy88ijnQ^~&&ohj#=N@@Gxt74jzy9EKi8pejJ^&*4&fFg(ukAcx+_nf%lQb1~TO z2KiVHM?)at7oN&LF>4zZp%wWpO?i>z#!T>I&elzhMd8CznmxB1OA9$euGGx8vbGk-?Xv5Li~AsxknPJ zC+90@YroWcU}Zh>zum9T_wP&tax!to$;PSagYhZk4{u4Y9;jztc}x21fkm|nc~%R{ z2;Mnu@)h?d&%R~!DP*^HK;lE4J(LZ~cvTP@m)%uNjJC+$;a{}vzHLXg{bQR#!i6@U zLY~sk+Y5*%WMz&QZw(T1Yp%tAOmHO--z*Z+p5w*k0YYxcHTpoVQjMa+2l9=o!+%(? zB${N6vH6b(Wr-`N>)T9Ibp1fH_a67_LRYL+#JobXUMkBa}T3m>mUd z@YeGXA(4CI;rs@A#N4qe@WVNP0kAc zk>F0jFvVO8-?URGpTc?_m+C_?t4LR$kpg*jt|+H!Z8qDh*0-iwH|>`()`BCS1CgZ?6IJ~W1o zN)3l!YGhX%{pCSs_R_{GcZHsTu#n=ez$F&)MyFk~<%#8-bop>AS}E0x4Enmp=lglN zfiVVu5Zo`+#*+{46BZ7%Fm$d=D*aG;I7QiQ40l(G)IMP10@aPI;0PV8Wf2^_c zq4j_V))&XnvPBv`R=xVv{eY(ffKNUE_=N!A6&nCIZvdQF5BT%-fWKG|c=#c}=Qb2a zp8Zh~_Lks^K(Rh8T{*UN-4_o7u6q>lsR6)G|Fnpy+zNPNbMgAMM*-7=&i|VdYhuo+#o6w*%hv#MmRhU56_9|7alu09vWMDJ70OZkVD9^HO<9LZeld T%2B{~06-rLP(Lc!N5AzyMgj29 delta 21698 zcmagFdw3JY`ZzwbyGb@}A?XDOZ7G{3X~7~QX;P+_0Oh7~@e(L%kfT&VMMaVV zY7spmi=IM7Q9S41m9|i&U@clyyq%K({hUJOSVdW&UM4hkCr#7+J(KD=pXdAiKF{xu zY<6efd1vOG_nmofbM_Gy~>51OgqW`?{_4yYUtZ! zwcu)IsGh?6h5uC`SQk{Z6PvZNqMbMr&mt?+2d1_Yr*&>cJDFrXLx9zV4=!paAo0Ev z#yV(ODvWi^_RzOofR?1#Tv*GrlN8$-VzRj+PFFiICEj;(v5rE|8N%6~=VBda{3K$n z#0|wR%rNaFVhxc=Ru_iMM~Ti%wq0DTV@id^oa#M8j8+TQF)qw9?ZjvmJ+y?uMT}`; zG<1e6v05U|MXm@~)J~RI&yc0``vF%3JkU;-TF;OLlrk3Mnw<0}6bScsYO{C8~l4&yvnUHwINhh&l_;l5Yx6l5YynlCy;;$=SlQq`T0K z1B>1G74{_QE<8&v7oH@S3(u0D3Qv-s3eOT;c#`14v*d@u@h8a-g=a~m@Fa;88e4~E z0Rmv*-MrRqo z_@KHJIHmd8Y(ZBZBA|#?endbKFms;Kfiq28dsAywhKt0N1@)kqaLGGdu@HqYmA4aq zOeGHFw-eKtc9K1&od{zV!}JO^>~*t!tKBZbWl64B$mjtUV|lWW=>@o{A6SN$vjV{H z^jG3;%W0B5OT>P+8+W@uCfT#_WRXsK)q8wv;5*O_0N}w7pnEq9tl#MY->3(CdUHU8 zZ>~WcQk6=nSf4IU(r3V#Qn7wa%Fqla<((n6S<;8%Nc}rzSO)OaC^-DAeg$JOCIMbZ z0zBUg@qri=0Okl3_-23sq0g-`X{URuEi}3sc7utrP<3f_DZu)pK&UPSW*$KtYvJ%) z$JC!-8N{X1xRkMeRoSDmqRDbyx%jXHUFW&3^5hjwfmXb@mBs$pv~mI6=w-!G zvM%2pUWn%pWR(FN?$0a(I5T#@r;*xI(*5s6vpva;08fo&d6FBoIHYDKzN=M;pNT?z zUyQ?9gPf=@vscr08j=3bAlk(LAp-H}fdRR|w*oZDplv@3tT%ALYT66<)M0?HV}W%p z2dqmtU@hW+wTuJSLJnBRWdMHdL5|1Ac?_ z>aYoLh4lF_kx4a3zYM#P{!Jb(aJ7T}z0#uL_rX`BkA{zhk4WDQ&owL=v>|Onb*q4W z^a1>^G}>_I;+LXa&h=e3q{XZj;La$QlhXB6<03Qz*$~99^m93yE*k>)(I}Ube*Tt5 z`u?}5xqB*Fn1DDH<#K*G|JGVy4+rxTCHYdwFlOR@!sT=&T0R~X5Yy0l89xQuhNS~O z?}}2%q2UPb+Jk=WO?^u0-jd-T*#9jV2%INi0T4O~aKLFr6{)^j*RU?5?*w3Qd%Unh zgMe*LNNswmH??*hP6ji&VP2~5Xd4^{XXH8;6LSOGQ#1T{7#OC6{y~6KZTivs1px~v zJgon%X&-S2%MdG!-@ss&xogA8E1DS>cZj%(P4~OGa0zp9E5KW$0@_Bh8z3(0SCvzP zqsj%u;G0xV6dzWV;NVik(z!ebr$NWNa;mQqgOp*Oa**oH^mP&dn4Z%Qe9*JXz;!Wr zS^N|M3wFy3$Rv;whAEl8k9_d@Bs5U{@t zu~--7P(w*Mf`tnZi@zaDN;;)iQcanrn}`(vTQJDtp9pk3wpLs6vTNjNSXd&3Qb$?O zks1W|2uL4>dKSM+=9UEIb$B`GkSWPe%YWGmcxh+0iG}z^X+oMi{mB97sCE4sf&!5t zvLOclMS47KjA09*jBRW-nK=aUIq8kGF}bw^9NO6k@PU{nhdWORyKcaSs$03R6&&$u z@OOg(0^=CGR{Aw<_OOozDa73>ecmX|Odrda9INJlHPs-kN_Pz_CjwHHw-eQ@)R;a7 zmPr3hFNOtDYDVse;qgEHiSp_X13$PqC%fC)qAD3uWyWZxCobKSVS#A(mxKR*s_IKng3^4e*xVO>n6VSyw*ZRb}fOudv!1E>D$c6f~147G^G6vr*tsH5G`O>o^#e&%b zPxhwP0$WGOC@^?iKd>DLLXlnnwX7hYXm%Ax!2RECEk+FXN>faWE1fY-eb?_NYB26V0FQ|6m+7&m@fe%4eX4S< zpLU%VZM|%Cs>=7rC};4^j0Xx?K2=#B9r_OV1P6mpNg>k|X8&G^8GR%4OU0vejkm>q zZhE3OwN^kyt)OlHUg^=%nQ)c#!f12Gbun1TPfMP3H3S3=70j*s_ex)k&W6h*dGvL| zz9AfPG(rn7Gx$r%o;lX>-chRq;5&~2QP<2MxD%R9NQ1*F+zUjl844QQqXH4`)tVVW zgMU<|M>8MIUeV8qIboWvH4j4^ayF_8N33fy8pTa-x!91Z3?r1utiC>3{VC03 zY|iqz8&k^|d>iR*F_uyOW$-OW6Z&gIj&@iXp>(&km;{LbEVbtpFg)2cVloTyVkviQ zX%@s06$oDMA1q@+S-vYWR|fIFr5$7Q&EKm1vUM-uH6F%qY+g*J8tGFkMZn zbYbiYe=dOn+u&$5lrdN&&TBAz4XXStrTQHL9M2NQ3149G>;ag=oiBIk${3tVF3H+5 z2GhxWFN3zA9$3jiF&|uo-7~hZ4Vn4vwc8J_EwjIwt+o>XS9`9jp-?8 zsd}odSVTl&s`S1v!hNDXu{o4#^c*_T%Z?g>d5sgF4&38eOeT22WPra4fQVBB*uWp| z15*HQ3>@xrP67B(;Ba4HiW9#h8O-D0OVTv+ZOQiqxrnpia9?2dT4|qovCbWA?sKkl zNs2i)bxP-7HF+JZ8|JR}rUx%-Ql)&$=(1Ow=Bof2+$RaY;dIj$x(5nWr(n#>WY&C( zoQrOffv{NyVx0`d7iDJL$1*$age+bK>_277`Sip+Q7`SXOdU@r!#A_|&KQfUVk}-6 z8|E?jOf4y%EMJyyeG3qDcpsr^?khaGav1cwBz=3gUWCH(wpO^GXs01@5hbT3*NJq(P&V4M@k((1->8^j~AJ|3DRBT zn^H>-r=!(yMCFgmCUYaszRRXdxfAkc>&w}&k%3}}WS2=!(ftw0F2b#5B%-s_qD1UN0t`CthIPU6j%@0j|8>rM|n>}tzqqo3Rf?IRZ6`AeZwVueZKxdbB+mQbZ;rSE2 z!>D-xcqhAQWp6RdZlLDEuf3^TfEW;d?KN(F;JrX^YVB4k-(^9<6%{v%m|;&4u4u@{ zqwsFbuzhs?fOk?u!_#7HrUF|T<&de-WC7+u#Tpfmu~q%4y7|}M)F*)$kV=aTCG4j2 z+SHEZxn~Jq)TK-5I7_&t8etBG>^KZHCka;sag>}S+|u8g6341g-Aa3@ZuV@}pcJ%1 zmvUB`Jjpud?!g}UVr|;|+sYqX`@uaT#Tnjtk%>EE7#FZ}+ojZrI zz=;K*snB|iD^u5O|6dR-)FcOd0;Z^$UBjVa$ld7P+@;lafXxA@D&MQ(nyj>zqE=P; zT8+xNh$>lM#UoN`)@bSD+_aI^&F;+{`nUFm4tDd6L;d`N~yr|N1 zo|2KOO8znPItW+fj)3)_5Uz;6XX#=cmd#1RsPf;M7Qw|!#Rzb_@lN;R1#v};i<{Fb z81o7!pgjwQS_Z0UOUvdCl3m1vjSyO%cG9kBx1W&gB2`(EP>4RD{GsQaJmq!3JE^Sj zo@CyMn>CxqR^AJHma!PPcOCw;c1ccQ$&uJ^5wtnoO|2&P)st>GdDMKq&3(0Geb2%< zo4L&z%xYFcn0H_qA4;3oLHMOo!^DY|%s03dTK_38B!Uwk@oj{pT=emc^#^9 zSmi8Ln^yJe(yKNMX-pq}2rQ{cReotB&BNE|Pzt)eC3&+$(%WaOc=Lm*&F^Hc>wPjE zfox601p-I9q>lgZQ96rYUov&j{F07wIzsUW3zAWz1k5dBmX&p9G1e!*f~T zy6ow-e)5PzRSbi5WLCZ|j~3UGS@{=2BRo_?2j&rF)Js^2VOl%Mwk2EINrtVR7;R?= zuvsF5tJ(>$IW6MTVx+oC#2hPbVMOr(Rhd5Ev;ecNOjTmB*2}n5Ro?ntY|iR|wJ-@- zDVLC>mB3omoHma`L#+0HGigdWWl=W{xZM$uPFeKc7=;Cb`*+5q%fqu(4^h4L54Lk{ zX3=RaJgX`}>AA_X{HX&&UNB>;s&uGC&bxw(-J3YXV$2G5C*BeOeY+l9hY_?PRryn# zzHwnMP?fvlyUDElb-nHEHZm)JH+jS{^!|uLe44IGmL_YMJK|g{ZmD`a9eWL$AQv71 zslb=VW^^ARqpFXP(SG9*k|h}WpBmgvMxNlCMmBvAPBDz{G+g8PrDPHYZTIH`-aZxZ zHTi(w`uo4R0PuJI{=2sT@H+|sug@R)ZO;e1unFn74rU?~%F%+3QHRA%)cq)K5I1${ zMt1Bb8yzgCeK4Okw(saognd+ZRH=#OkXG=w`X1g6ZI5gI~0qx1ib_^ZLw z@`~ed3L8S$s2#uIOPQG>hQ4e{J}%9lYJne1_fIwZ^L75d{6oE$&TIXVyh97FYFU3I z_mF?e?BB*8s@g==H^x3YA{??*eE0b2ga>r6%6%24QKfP;yT5Zx*Bss@6x+2U2mM!03azz3U^vi#2b1|%{3RYEWYCh5MEoo@# zA{ovuViH^tXMsE7TrWB^oFcwbB}TeMG4l9&%Bx?J3f)m&GRl>+Qeyf1JUo7V9n4QVVrL$YlnoNqS4U0|XUPpUbSfZSP8-$WtP zYQUtl^E)b_`I&iiv$CN-HmkT&F>u)@G%~(LYmyps(aut{CaGg<`KiPPmbHfUH`bK` zv%f5^Odt4OyR73;&zO5O*r0C-YYmIO(L``sQ$h=Vv8E}Z1@EtE>I+Pn6Z)h#X#~hC z4t`5c)MSs>#`I7A4=KDKOmX5r)x1b@xRbprI*na$3;QIQmH$}c1bJ)&-1B#G zyHQmR$FoH?rmv;D<+|Q2iM?`xC))+^ni^F(Kk&Q#{9LCFb{KuB-W9wsb*T&{pn1Kz z;trRm@@nbmWrP*FNJbHJmG$!`3=Lz0P@GvY3ad%wgmJ9hePrV<1Fx8&rj2g6tNetG`9aqQkGFlLMs{gH-uhjd^XaRl~*mqyRy z&6@BC;8T^yqAx^8IDnn+Y9?6@d*j+o&_cDQwHsczw009?A@Tvv-*@Jn+;4F5@4otyPfdpikDh6)vch7Hmq*8OV^v zL2;$Ne~d>JsFw0uQ#;}H?SxNmCpLXMu_d>YGJQKKOKvAVeLL|bx070ZJE=`>CkOTI znIO$H?f^ zo~t0ur%6hYh{1X{rUXbSqTkD4tYdqbbHbop^B}OK#F&iig47f}#{;Ki^ zg}4%l0vmh2^)hj)N@3d_a|7ZX^A30~`sk8e^s>T$GGS0$1MIL1&Qe0+nuJQQ@@CIX zb1iF5>;ABFz_qfZNad z2`HlU5+f%TpCq8@ECEGs%+la!k@Ff9t5&gnyVwJ($_q{sE}uU6#4{!FG$x)IiKi)F zRSaZMiK~@ZEjUSxOI7nplCgAh#Ys}Q^dvDA<#|q$?4>53PylR4+A1;c1i~mc5mMa5 zc&nS3vLzP|jq?DDDp;k^^<({`JQ-zsS5jtJ?p?Mfv%-x1#pcK+XpU?uHe(egxq*54 z$`KWNSJqhedIy#7236(R=z{{KOSK1<%lEG~5O2cevPdpdJ6#4d zVF8q+6Em}+NxCp|3aplf-SDufx_ODogeoJiJpjyO&<~kx-)j#IC{L-_PRIoqc}a~t6s0KXZ9b-;GE4G2T-EDk>v1-6tf8{+UO0&K7gQa2$-`%lM z`OL_HCLvXst9~G-317?E=pS-=Gd*x$QK{1a?gi!nWeE*XG#FcHeDfhGb#_OJssF+i zVBB9ipmfEhYqMY10N*JmkoGx8Gmi~QN1fU5tkmJmg`Y{Pb7txXaA(!YD{~3} zzJYMzP2eO6EC6^q;liiDN%GZ#*2_gsfF~cN;f+a-xbn&X5Kl^O*OV$%d0(Xjet+Pi zOifpT2Au|ht-s6I%HsJS^3A|Zg#=o72dr^>Ri$b0zayIbA>UfvOs$xUgBoPRHvhlefd8i(@SaM* zyK+(qoXHS48`z_v>QWXNn|C!PmGFo|(6Q6ShJZytnbrDkBY|^S0zF_-IONQPMaEVh z83~*T?6J^qGK(@1EJ)o5a{EKZ%<58OGgHDLPtHykA5153EFdroVbL%<_-5F_b~Wkkm7U$1`E5*$FDk(Sj*026({&#U=Nat5 zWB#zi&=V@bkYno834Du@=pg;$-&TpW{IT$z zhCBLe!_@kP`6ZD+$>&YLvbDPeGh7MgxK6nQ^IV5qf{om1`A8q|x12c^e$+5Acr3iZ zFd=v>e2>8#vPJ@{{jWEbM1<8R1gxegDMqm2FY>Xl&!7)^|5F1t z(3-&Nr{!beY6H_|jR>n>_a}gBRZCVz_;x|lnP}iqpcWKVl^M&=>q{&_uaAZT?T(-^PwbE5&9xZ#}$T-@|K71ZJ&ixdDMmPJDFBjV0$0nmNA9FxW|%Wf?%FkH(s{}`boNXa ztlvAwc0MT#d02m-hv&s6U}vTG+9qDTx?Ur~0y=CEgat>#eqb0Cu=mYlO zLN}I-MgJ#FL|w|+7Q}Vy!|Du2f_`=%g`v=ue#F)T`=av`uU>uRR2Z;t_UIW-qFS{& zgWI#$bzK|(RwZ`uXG{{&1lDJ7pTkOaU-tPQwAzlAusWL!O-`U>U;biFa%dkJ=a^;} zI<+CX5b4-xpz@N>!|8S(RpIMOi)H$+*;Q9cTWj|Eb)m!A6oqCNMO;^^*$bz#FMlZ0 zW*6mgF9CkcOMo}O1bA>lRrir`MjOh{&1s_@h}g(JORNss?r0bo?7mqSnCX=m>W2n( zYL4A!KA#Z*chCjRXq#ic(_B|dmx=4jPYm&#Uz^wQMHnRInTOWgVLlet8^(Pz^uXq|ci|@|UO*Lw;CT(61oe%x8(<@LP0-4t)>L&7CtWgh~!yg0uhN z^3pl4_vp00b^a=UFq+78K%)uFsw)LkE(hW4OY*VsY6BM$s+i!h@EXI$(BVE|T~&w* zUM|+@zeMK?%!thp4%!&Dnb*-`RU26*M`U zcFA1dPXAbrjr!5pXn?`;NTA#(ej{Jh!jAIDiSo(_x4uL6 z({&wZrpz*Q*433B{gD?xmrIaK7SR{z7Fk3$$(fNrB@Dp=(9INdHQgZ>U(+&~R~f_X z$nrzI@({<+{ZHScWxJY=yZXBR*iGnySb}!nkmOT5#t@wT5qfn_?l%W}I6v4w=V%)c zv?X(o!}@}f9JJxb{b-h)83A`_!;IGM%V=9_-k6Z_A85C1=2h14Z7>rv25lH7>g{I1 zoEZt+VQR}WUzLZtqWec(=~r@9&hR&FXi@*xYu_~4eQCs$U03?~9|OLjuJo=Oe{>*2 zBBd$s3UQ}Lz$4j6iwr2cO^kpIRF+4e%Bw$Ybf6i?g4~G18lsA!JIeSMCG zK>PY0p8e^x4Ygh-Tj}lwgV#+B%ePGZRaSrcc$ZW+Pq;fZWWM^{0~&|JOwZ|pr4foIT4&^2s`Nf$W{>9kO{EMF9Kg$ijoOtY&pWSPZ{DK}!lwY7H{CDyz zKReeR`Q_6D>}?&+a$YoygTgC6-yr4ApW%0S*q%>W>1Xhm;}>1>D?d+s?8q;lC1AO( zreC(~F`30rsp~MuZbx8eR~F5ac9*>D+I3+OT7f`a zIb!i0DhNALmeK5qU3*ZH1&BO>U$S_yx&`e(m*n)JapVfm|7?6r_(k{FkzYPd44dl$ z{p>))FQv(MmcW_(jKg7d_D`V$vSh3@<&u{G?|2FD4Ro6geERz4XIXGva}s)%=m6DZ zhlO#Mu0_D;=@H?2T|Lm_$OROk*ou%m6Z=k;v7e zDrQoN)k3|ukwM#0osx73Z(p4#1na^a!rAZ5f^m7E*BIm!BOVIVmoM>Mv-LYWoxbQ&l8c#{@ z%3l%|f}>?nd0YLxKZmi^y{5NORUVQKEXdPuj&{q`!}6$fZo$kIU-v@?O_MdX0ij2B zt(n@`kQg!30nMs%S0Zba$%P?+tB%9OfBW(3Qfh}i5o^87I{}6ts6Q1o8|HDyzA+ug z4f@c>I$a0AHPXEc$HK7m?7}Sgtn|jh0{{AE4#9W9xYdHHbg96m>w?p?1SWHNeIZy6 z1kuYhR3}2i`uTJ%3N|u!+VkRA!A5A;glLGg^>Vcn;A6+BpXKvpn)a4DSMp-CuRN%-_+FL8`6@M`{-#oNMkj~wK5A?Q zfZ9>Co;1}Kmc*D(rpLH|fAHNy!@tXnv%FTfP z`ewkdxCQWc{~rziH%Yrocfdl_Ihd3b6D;LLZHsfs#Cn=|aUGG|^Tg%^+VUmoPl+MU{i zs&aX7QeGtVqYTGUOrIn$eNw~LvzTRByA!w7K(P{oWJcIdfP=+TRTl4|`K0*GK@K^O zC&~efr>mWWcN}ny?_}$N)lGLJ0-UV$1znx`8!LwJrElch!1#23%WO~9#`NmqYiTTF z)*gI^m>jBdV9+9iamVGQC>JG%VKR&TgI~y$yPh9}4kun*!xerdPZd<<*2Lr=s2PD- z#)pIUWFO&mYAt=#lIhLG535lvnsZZg~c!OK;s|^-rBkxS36T0lys59t0L@uEVKYuO_qH#IB}= zM09Munq}_|anmUM-*SD~$(gkWzb2*zRrx7S=VfHSx@1Ev?v87Bek21?b5J9x$`^59 zbK;K!bi5zLDgS&B(A2T`U-3UUb7T+A-iYg!tuv0F+mR9gzNl1+Yk(K`ZqoJWS z=`wx}v;~ua)hX$hj+vPf9ab)QS!{}?ctE3xo`F-7=ef-$-$XCOzo@{b>9TnRAN7C@ zD#gc&TDR2${<0BRZiM)X6=u&@paK8i^? zwp8$^9i^ADay-?|z{aJqVa>J{I>72jUy(VKk_G+EN+$u23_t zOQ!#w*)nLO^>3V=EXUZ6S_9$rE zun+KSqg*a^YF?!!4;Dh+NV?+vNj@D`KGnNc0HPRg`9=xqG=)9&c z*yFl8=)9&Y*y9=(T!&3S-~H-u%t9uY?fmvK#M(3y`1npBB<}c3d>|MkiyZ0R26D4Q z3hX3H9n$?+1{3cJ?j&;^>E5eyfXovdAE?TcQr@i}WjrBQCsIF`HZE-BeSBkFxu#0D zdo9eKsIafbaLe+xJe4HoX6+~CFd#|6NyXrtg>>0%7aAOwQ6e4 zBg+B5whHiHuLk^e%^Vtmc$A6OARq$#SxowV)ns@`O0DwW4sj}ZKcN@hGkBP0F=`rQ z+K~DL4JdVEknn+2>`hrx+e!YkU}x?B)IJtkyiq$-V+Ys13Q$9f{i1kARmGW&jNKY! z?e-v~CsAOM58zob$++6(r|xF?Jar`I`gU#v_+S0M$spH>{~Y+P$%#~Dq56v)$aUf; z19o2>DHAfQq3}-`<~|;(BV`U~eLiNM#OQ)H2_xAq{pS*U-cmMnF2l3N|Xel!S#y3%IZ zoSXf7pQaFpS&r7$lDSS`|9cP$Kg;Ial;7+5P@-j?y*|hY-^uH+0PdF8;oHG#8HmX> zf&0pR?X_P9SYOr}Q)$9CTgoAtNACyWYJC}sDNx-_7CL}^ad0=ObO3v0hzr*yoh7vk z@>=fbuO+p;skJn5^&X#nyU{mlyQ$I0N8HGP036{Bit!S61f&6u(LN=ipGX-U0QL{J!glb9X&s zB+Lmo_0@Z(H$kF3F}evBtlU=LMA7U>bn>-q-=0%4x#ldXbpU%qP()0{DRUWuxKw>Z zzPk$W(y`ko8Xr*qNI(jZg+?Mv^KYNXd>4}*y*+1AD3Jr>Qh$*_-cKPKQ=`{s<~da5 zWNaI$T=2cDDg|vt&D(tZnnaGE@%A)*Trmw&U4N8hzdg&Z4q|!ePSEdp<4I5g;!twu z)4wNo2FdEcQKEHt?L}=~5lClApnBcme-W;sivaLzZ|e46dyP*#kbr-JCWxDlkdY_; z++^8d=znG)t!eihCJ5>eyD~e!d)l%?-;~z$yo(Ece-AJVezfbJouxz693H2hkL|sw zwV$@^BbV)m$M5)l&Ge>Sx4D*Bb{vUjdg0WxrWak7t;{!-7_j12nE$EFg##e2 zoQUrx<-#)LMDY4;q+EcOw}{sJB{5d-ARN8hB&4m`Sqg0Xf?vzUjbLrs$4|36(wefG z_PStDRUT`rE|u^d)}nhU9tSL-dkqcYHb;{jV#|=Jp(;z;s#~i|hg|qp3pMmK2Z6a? z*%OmqztiG>JI0}+mUTE;qiejuYx~{6=iaT1lrI8iF1%CIuRIvrMmzz-KMbGH-;0-7 z@UfUv@x)~oY$J;uyl6E0&^EHvQ5hMzejAzBaB&;gw{874vSj~(Rj%KxNtw%yQYskyJfSBRz}J4i^#iPNWl5|_=K9K) z2q>;NqZ;&<{Q5q?f3OemyY~U!(fmZi6TajMqxl8mad60o7v_)}L6Rrj^ z<>G)1#g)l1O@pJAwySPVL7dIr>8E;owvDxp2P5WD5Q7Rt3mT1nxfK?Ks+p;Eu94N` z8(^!v>SR0H7_ly!6;Cu(RSVVHZdT+3Pqkj;t9MkNs;+L;%)21dV^lNmTq2L0rVS~ch4(ux%BsY z=D`A~?;a0aEETU^Iqcv4^a?ifjj#sdZ0XS2G4M0#>$Q2XTZ*kUn}3W_Vf-q(>X`%2 zl%XLe$!S~fV=-jMxFPP4X8oxE9+&R_Q-O6t6xeL4#H{q)y`y1+6uWl{zaTo( zcc4elN>lHXdeuqf|bb*1n z2tmAf0GJ&J;>rOL+0c-#(0Umc1AO7bZ0YO!#=^&?pYIzB?>#(h-EruDPCc;E-bllK zMsT1S;HT7~EbHo48g2yU;SPXLsdP|A0C2ks&0IJG0Q_O%O#lG5s9ZP=Kr^+c0d8um zZrX5JTuNwoxfO0rqO2&ce7C7s`#(gf$`64u+?1`_#BSBL4Eo2-RP zs%<099C~6SoTWSM^$jSG#S>l_XTLJ7^$@5YU*+pu<|r}V2yjmS$gt7yTZonnD0jzy zOeh%_h;4r@8imFnEduy-yaoaMcj?{-^5Ea3`Ue)nP13IqtR1m5u0^;J%2;PKMB^`dR!AdPCT!#ww!ybdREicH@lGH!mNfkOaKifa(Sa8Nq7-Ub=z;`&^F zR9QPfgQr*GRC1?Ae~^vMs?x4_>8SL=yUFrWnFG>4HcV%>)l1q3Z-y78+aBBsKa;+D z@Glyw4Jw-@WrVem9`Y!4O zIltY4rMEW?_jktxq-nsdG$%w=-jDrpJ9#akch;#gQq)Rg{|g#bEsY8dc?q7_h~9*aT|2=p44 zwp>8{%KE5;HaqUVF$zQ*5+5#V1>^c;dZh?Ar_TdI`dnuGL?1gr^kub(-YPF{P4hK1 zO2l{~b<;C*$hn2SGX$JyzXHrNTA;AlJMv+>ckIKNs0v+@lf8?*IS&(gu}}RsXrnlt z(uK`#rfN{K_%}0m^h>Y#r*Z>IA(1-$-eLWUg#b}N;_80oJ84cJcf@7&ztUXYOmD6b zHr{XSrZ>FO zy7%~AcD>dEnb&(5?$sU+?(zN{(v;JU%+de0cj)SP;@;S-np1k3S~P5~=yNyj^?`Bl z`n_J!m)=xNYdfmP`-V?sM(jHklx#b4Nt4hpP8`B?^ zCT%srZ>2d~^D`=1=(X1wp1do)r8+bW?LyhUgms|x2`H*uiaVUt27o*FH^PHa<)J7< zv|NaeX>|MS-mSj1UhN}M<%TG=5*)wF&`jTf)ih>W5Ij#f2N$;LbLO8Lb)J9|FOSYH z8&g3w(Bd$FKgGaGdWy*dB7(?NQAV$B4hl$X?)NKZQih_+2|^;DC}0Lnnak+~(61}`dON^xsiOHBEG zz|_rzN3kL{Brl%>t~CW-4fC3qvSr|A!oT$8oRm)P^m3GooCx^w-$)^HqL@-QkT`pv zyP0s=njU?U8AC|Px+e3yuFN;L4NSO+=&Rdxx*k2dq>c9hfh}1v=l(NCU2pa1S^jjL zYtiWgJs_Dy1uZL3AriY^am7w|WgSPMD~xNmH>L3l-}l}+*I#>Bjq_ZR?{uc8B+2Wy zdsBQg$>mSp^MnHcLtt`$K{!B%bjyGy%yTQynZ~3Z9XNl5NqgR#+IXI%2w!+7`d)Em zmQ3{8&&4v|Fuk>4qOZbR>eFGUo9T9YY3rf^`pg?R;@TB_Bg`}TNI*onrGE#_RY-nY zw)^xw>;h)3kGj1lde_ncIH&@dP6y!lNOmXG$xOG)dtRof_yKc*QacAY1Z=Y-zC-zl zA|^^+e?D>|w+yVeN&Y9@@EfW9$#Qr|8unDyw59GcFO5f0z9?#T`%;j`$5)&i^<#|5 zHzA!zS8>Ah2crT!&@Xs_P$b><)G|n<_n*oe_T8XvFPv&ba92!uLkd4N3jR~l*Ludn z0ZSr21)Q5&Ms$O5Kgs<;r;Er`ABZW}r1iCn;VJ2}+J($3F)4HV+i;uo+4ecPGqwX> zzkMjHtKA0++P&4KtcUfoo~>RW(l5~V2(6cOHkDf6NnGB(0JF=cpMI`VYG zu#GPRJ_$Lm!Bl{slkVS~ES-BcH*@!YVexo!fpFayt}r6kP+cks|6dbV1Kh-Mh2P$t zq_r)C3@O3Jpp*Plx!7QS3QAIfe3BOhCpEY;8P|cvHqh9#G~lGu5N0YlO(squFmQH= zAr+8N2rZqd@HnZ>7#A8k{h7%~CY{>TrsI}28YG&WEStU4Ilj(H3eC=(-o1TqZ{NH- z-R;}A`yCAgj}lnRC@DAt$Uu21kjvu;TZNQIMSNuD>SjJlBG=oyf_(`7x}qr3c1m7c#csH+Or?d$vr z-VeHkUd(C>0;G&}A*HaU=c44Dw)E`wa~^NP?EUvLs9GNR$P48+?|^R&VN)!JrGiPQ z1?4k2c+3&hLNAxLCwU%;VFI;N(VKVRn;*xyVdEdne6~I0MCe@7ikcE-TO64q^QcO+ zMs%9C=!=WJ2~=;>d8JpvlVwSS*kT}VyjOzhKZkszp!EEeh)xxYZZGyHkl&`m{DlUl znKgF}H-4c3g40(+n4C}A1aE@(z7_v{O0*1mT^Y;V;|bm>W-K!(V@{X(H0H6#AY)EP zbWIhl%#;FsY1Ra++mv33%b2H&vS#3v@o-4#4fRUi=~qJUra0X0&l#gB1vz8tLAT8x zZNQU3W;dja_1_;q+OT($^R)ZD3G6+qbA9KMHgrz<1Gzw+y!EZ<&d6XAbL~kRLKzEn zWz6Z6*WtT)2M$10&aXF8B0u3}x7eBC)5pEY_l3^}b6(g`Wc4M?KG1FV!jh2TX7FTL zFv;_fGCZrt!&2=e=h@{yz3jCsgF3xu(U+{NPw@3--IhL_cd$8Sc$SPGmL8bo9&Pvk zv6Li$c;c(r(xteW-2P-KQ9o&HxHLYT>%SFFFY}{QK%;K3b zFtRVu&YCUyUl{0=J&S$jQr>NL&DdQ`YPye(=9&p*YZ#mr*TN9A7>X3MfwCdfq@cE3 z2X!N?>uY*WvgAt=`v@o>jxg{h^Y2u=VE-1m;)EF7GQtK#Y`(xg3MpuVS*Qc$S66>x zF~$DR|K}=up|iudiyD`9W;Y<)VMlqRGE~|r5Le@kbdhzfm*RDyX z7!s|OCLPwbbS{6fewyb`Nn%u*M*JyhMO0$^BB?A|pRK@St(6@siilsnb)vxqDPtSV z9sQQy+^cZom?@yq8dW|bi(L#Ft7!)6_79D#y_=w7%@e+v{rnBJcT<^bbz@og zj_y<4fA3alrBNGDsmrJdsMKK~k<#;;NLKBm^sMG?3`_MfBvuhh2Q-n??4h(@s|bLy zNH>x404O%yB`@qNeX^>-cUkg`)etPI^p;^FZNuM*=+u?H-~nwxqkU@)ag)+Lln z*$XYmEf74!#lXqNdm^Fqo({^tzaZ=;=Hz@e^n^RD4`2oUmkhQ=Wfw3`F^( zeis^%X@4aem6yNq;4`C!iEN9^)3G^Wg^-Qt-ZtjxhjT0zd{$W`Wa6G7gZ{!Wk(S6j zy*!tT84Y^VaFcmD@+G}r&xSVRA)XYD!)yq=h<$Cju2ARcQb_vb({Ff#4IL9KWc;pS zCiApwjwM4`0N!g@2)G+#?3@@v`NPEOH0VAf-Pts=zr*UhU0O$$as15GE`xR$p{$(g z?l9PImm!dCS9v11tl8S_Mmfo~W74fzo$W>)nWxLiT+LNxK$U?9O|wQFOdEECI*e$< zO-%BSPBtJ-9zE$mpUEGeEJ1&g>B&J9mVf!?&)rSRl+)B0Q?0e!%v8r>-*wfxiQ(JL z$6-u>jLGdXoRq#lEI&U`gT5}G8#o+zV5?_HR2=;FPE+TAR2q%#JuH1ChRWR)zfHdc zg-$`|E0E6feG;GI_-3_yn>lK63o$me-*1SK|N2w#1t}QFo z@`CV#kA1!q@FP0`Yfl4C?*RPIR=}}Vz=v7^zupS?SS#SgdjLQ4RIcUqjvUqV^!?pA zUY7TTS2urqFW_VQ0Xw?@Yv0RBUiksw+WfiW0AO~o{ukzH<#Vemp9AA=$sxc)2LY#F z$oFs%@LyjT{50H*is4fuhycLImv6}1&z3J}3FkCfIWPB|U2Hpk2JmJ8*d_pk&&Y3| GUHd Date: Mon, 3 Nov 2025 21:47:35 -0600 Subject: [PATCH 252/812] flight_modes_fw/return.md: remove warning about now-fixed bug in mission RTLs in FW --- docs/en/flight_modes_fw/return.md | 5 ----- 1 file changed, 5 deletions(-) diff --git a/docs/en/flight_modes_fw/return.md b/docs/en/flight_modes_fw/return.md index 01ceafe6a4..393d1c6a13 100644 --- a/docs/en/flight_modes_fw/return.md +++ b/docs/en/flight_modes_fw/return.md @@ -25,11 +25,6 @@ The default type is recommended. ::: -::: warning -There is a known issue ([PX4-Autopilot#25436](https://github.com/PX4/PX4-Autopilot/issues/25436)) with fixed-wing approaches and landings while in RTL mode. -Please review the issue and verify in simulation that the behavior you get is safe in an RTL landing scenario (if not, consider using rally points). -::: - ## Technical Summary Fixed-wing vehicles use the _mission landing/rally point_ return type by default. From 8cb1c31f46775b0994f76e1849978fd0d760dc67 Mon Sep 17 00:00:00 2001 From: Hubert <1701213518@sz.pku.edu.cn> Date: Wed, 5 Nov 2025 00:16:38 +0800 Subject: [PATCH 253/812] boards: add new board micoair743-lite (#25777) Authored-by: Minderring <1701213518@sz.edu.pku.cn> Manufacturer supported board. --- .vscode/cmake-variants.yaml | 10 + Makefile | 1 + boards/micoair/h743-lite/bootloader.px4board | 3 + boards/micoair/h743-lite/default.px4board | 108 +++++ .../extras/micoair_h743-lite_bootloader.bin | Bin 0 -> 41032 bytes boards/micoair/h743-lite/firmware.prototype | 13 + .../micoair/h743-lite/init/rc.board_defaults | 28 ++ boards/micoair/h743-lite/init/rc.board_extras | 7 + .../micoair/h743-lite/init/rc.board_sensors | 13 + .../nuttx-config/bootloader/defconfig | 85 ++++ .../h743-lite/nuttx-config/include/board.h | 414 ++++++++++++++++++ .../nuttx-config/include/board_dma_map.h | 36 ++ .../h743-lite/nuttx-config/nsh/defconfig | 244 +++++++++++ .../nuttx-config/scripts/bootloader_script.ld | 213 +++++++++ .../h743-lite/nuttx-config/scripts/script.ld | 228 ++++++++++ boards/micoair/h743-lite/src/CMakeLists.txt | 68 +++ boards/micoair/h743-lite/src/board_config.h | 199 +++++++++ .../micoair/h743-lite/src/bootloader_main.c | 75 ++++ boards/micoair/h743-lite/src/hw_config.h | 135 ++++++ boards/micoair/h743-lite/src/i2c.cpp | 39 ++ boards/micoair/h743-lite/src/init.c | 208 +++++++++ boards/micoair/h743-lite/src/led.c | 114 +++++ boards/micoair/h743-lite/src/sdio.c | 177 ++++++++ boards/micoair/h743-lite/src/spi.cpp | 45 ++ boards/micoair/h743-lite/src/timer_config.cpp | 63 +++ boards/micoair/h743-lite/src/usb.c | 78 ++++ 26 files changed, 2604 insertions(+) create mode 100644 boards/micoair/h743-lite/bootloader.px4board create mode 100644 boards/micoair/h743-lite/default.px4board create mode 100755 boards/micoair/h743-lite/extras/micoair_h743-lite_bootloader.bin create mode 100644 boards/micoair/h743-lite/firmware.prototype create mode 100644 boards/micoair/h743-lite/init/rc.board_defaults create mode 100644 boards/micoair/h743-lite/init/rc.board_extras create mode 100644 boards/micoair/h743-lite/init/rc.board_sensors create mode 100644 boards/micoair/h743-lite/nuttx-config/bootloader/defconfig create mode 100644 boards/micoair/h743-lite/nuttx-config/include/board.h create mode 100644 boards/micoair/h743-lite/nuttx-config/include/board_dma_map.h create mode 100644 boards/micoair/h743-lite/nuttx-config/nsh/defconfig create mode 100644 boards/micoair/h743-lite/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/micoair/h743-lite/nuttx-config/scripts/script.ld create mode 100644 boards/micoair/h743-lite/src/CMakeLists.txt create mode 100644 boards/micoair/h743-lite/src/board_config.h create mode 100644 boards/micoair/h743-lite/src/bootloader_main.c create mode 100644 boards/micoair/h743-lite/src/hw_config.h create mode 100644 boards/micoair/h743-lite/src/i2c.cpp create mode 100644 boards/micoair/h743-lite/src/init.c create mode 100644 boards/micoair/h743-lite/src/led.c create mode 100644 boards/micoair/h743-lite/src/sdio.c create mode 100644 boards/micoair/h743-lite/src/spi.cpp create mode 100644 boards/micoair/h743-lite/src/timer_config.cpp create mode 100644 boards/micoair/h743-lite/src/usb.c diff --git a/.vscode/cmake-variants.yaml b/.vscode/cmake-variants.yaml index 504c38b2d3..b80cdb73c8 100644 --- a/.vscode/cmake-variants.yaml +++ b/.vscode/cmake-variants.yaml @@ -421,6 +421,16 @@ CONFIG: buildType: MinSizeRel settings: CONFIG: micoair_h743-v2_default + micoair_h743-lite_bootloader: + short: micoair_h743-lite_bootloader + buildType: MinSizeRel + settings: + CONFIG: micoair_h743-lite_bootloader + micoair_h743-lite_default: + short: micoair_h743-lite + buildType: MinSizeRel + settings: + CONFIG: micoair_h743-lite_default modalai_fc-v1_default: short: modalai_fc-v1 buildType: MinSizeRel diff --git a/Makefile b/Makefile index 80e0ee1f64..3639bbdee4 100644 --- a/Makefile +++ b/Makefile @@ -346,6 +346,7 @@ bootloaders_update: \ micoair_h743_bootloader \ micoair_h743-aio_bootloader \ micoair_h743-v2_bootloader \ + micoair_h743-lite_bootloader \ modalai_fc-v2_bootloader \ mro_ctrl-zero-classic_bootloader \ mro_ctrl-zero-h7_bootloader \ diff --git a/boards/micoair/h743-lite/bootloader.px4board b/boards/micoair/h743-lite/bootloader.px4board new file mode 100644 index 0000000000..19b6e662be --- /dev/null +++ b/boards/micoair/h743-lite/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/micoair/h743-lite/default.px4board b/boards/micoair/h743-lite/default.px4board new file mode 100644 index 0000000000..68a87e863c --- /dev/null +++ b/boards/micoair/h743-lite/default.px4board @@ -0,0 +1,108 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_SERIAL_URT6="/dev/ttyS6" +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2" +CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS4" +CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS7" +CONFIG_BOARD_SERIAL_RC="/dev/ttyS5" +CONFIG_BOARD_PARAM_FILE="/fs/microsd/params" +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_GOERTEK_SPA06=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ASP5033=y +CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ETS=y +CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_MS4515=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GNSS_SEPTENTRIO=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_DRIVERS_POWER_MONITOR_INA220=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_POWER_MONITOR_INA228=y +CONFIG_DRIVERS_POWER_MONITOR_INA238=y +CONFIG_DRIVERS_POWER_MONITOR_PM_SELECTOR_AUTERION=y +CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y +CONFIG_DRIVERS_PPS_CAPTURE=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_COMMON_RC=y +CONFIG_DRIVERS_RC_INPUT=y +CONFIG_COMMON_RPM=y +CONFIG_DRIVERS_SMART_BATTERY_BATMON=y +CONFIG_DRIVERS_TAP_ESC=y +CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_COMMON_UWB=y +CONFIG_COMMON_WIND_SENSOR=y +CONFIG_MODULES_AIRSHIP_ATT_CONTROL=y +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_POS_CONTROL=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_GYRO_FFT=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODULES_PAYLOAD_DELIVERER=y +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BL_UPDATE=y +CONFIG_SYSTEMCMDS_BSONDUMP=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_DUMPFILE=y +CONFIG_SYSTEMCMDS_FAILURE=y +CONFIG_SYSTEMCMDS_GPIO=y +CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SD_BENCH=y +CONFIG_SYSTEMCMDS_SD_STRESS=y +CONFIG_SYSTEMCMDS_SERIAL_PASSTHRU=y +CONFIG_SYSTEMCMDS_SERIAL_TEST=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TESTS=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_USB_CONNECTED=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/micoair/h743-lite/extras/micoair_h743-lite_bootloader.bin b/boards/micoair/h743-lite/extras/micoair_h743-lite_bootloader.bin new file mode 100755 index 0000000000000000000000000000000000000000..e9bf775cde0f8803b1ef1dca130071b8a3c8d2cc GIT binary patch literal 41032 zcmeFZdwdgB+Bp84nMpEf3rT6w(iWIxiiW00pjC_L8j^5&30f|?FPB{n6y2$~QUMi} zZ39Iu;=YUE?jqF{WiPBZno4#pSX*s%y{zvh(C%BQELGH@Ey@W=$?0`|pOb*QtM2dj z`TqC&8T7v>@gcP^S!RuP)g`-l$PU|zs_ijztVf0X60F9)oZN8#JPybwbQJ;<1{zV8tYx-B2KQI=Kk|J=3kS1&dRfr zYA#vM;H7_gmhu*tw^LhQMR_}QB(BAI+#t+tr_Q`ZL1#7dg1JokHS%7aHke z@6ypo*Nt9ww;R}-G@Fa)xptanJ5IA~u9(x+PO}pCyM&RhBJXi3*q#&^WGt_OG%j!v zj%%l}yf7`ua}mV7mFO$Wwp$qKnq6+Sr2CFjbDotLI2Yl$c52R(z3dG~in*-(q405f zOP)36T&|>EHwvbE&>TzJ1G>o3F12_6wUCqQ_<2v%|f2HlR{pG(@o5Y5{tKk78Eg9 zMgt7CgZcy@4^b^n#ye?uk()qevYqatPWnkv2mPd|lXez$(9WVx+FRr%{$+0R9N$5E zi#q9Y!(fIw>jYprojieqPi;KQHQ}v7!zdD>Anv=Ky|K@{@Dp{Qw%O zF44|94xfvrZwJ|LJr_0CZTQo+XnK8J)LhRf`ZDk3<;N)$r`Pi_|9zVSXimC+QvH2_ zw*w%v^3R*LN7L(%1_a6R29TRyUlKs`zEUCoT*w{sZ#0y@O`#aceJafQG9<_R8@a@r zUe)nNbqT{K=uUhLga7N$_l>bymv7%YN!ivM^M<7zGb`@~wXx{lz* zvCl}>e&k|pUXl9|I^C4w=6tM0e2 zkFr%qyHUeV7k6_1;6v4YDr!K5XwRUUe2Y%5E&k%-y9;jD@DZPzA6)HD^&y!b7Gjw`kaBx(ED*bM7deV^J!y&eK+L}L z>g@$Wch;iCiMLU;wm|5fyr??ybXNUk0rznQ(H!QM^hLW8?>Q2{4m_cNfwNr6w1@X^mr&&|mY3|f^DotI6GRl+l zTTz3 z6jSDuX|fGk4@JQbL39|1K+zk}l6)5OeLX<<;ZeL(v3w$L~Kwd6C^2_Mf2! zp52-DpP{CfGh{kPcn$)BqSJ9j|K%l0bb3iee^zN#bb4t;|CF-3qSMPN`m@W| zMW>fn^yhf*j!yTo@mKWcE|MtsVG?H_onZ43@_*gK@O7y#_WMFa;Et%5=J)@$8bZEy zVe=tYpRHR(e};Uio#Z+S+*c}qIR!*11w=83$bk_gC1^qtgFt|?YuyOsyF+GzOgx?! zLf7#W<)HlHk4bPrKbr9y!z)ep5O$z>Afy@c zGrB($*As)mFv7X6ck=nNXM3w~9fLsm+{elKTwqEyX?b~oGl<6(-fJs5`gDbQ`E(smYDcavlkg9GJb7fO(2M@4 z;KG}8eVlBsMr3H{WFH`o?9c?c&{wD+`@)kB#Sa|$jh64t@)atAPbz)B7Kk`{1}vBL@_nHG2bCr+c$~ylk%q(nj^<@KCNdH2`GpNRBr(peKLR zvJ=nM8X`{&A#%@%Kqik1vayua$R5!pYR;qj#P1=B$du7hwNP0FO)9kR=OOQU0rE2U zftWr4#JxP^EfOH_76I~#1;{HEAg@S(ycwAw{^VyM26CBPgFG$1LeqJj7anr0wZKzC zDUgq;gqd7}R?8j`efyGdI&Vb`){I|->HP*~-b4_q_ks93TXj%}({Oh8xoG;M-_`WF z&02ibm=zlqiKQ2sob+lZ47>v_-=op=dXTDH)|1IFqC#uB3B+mv@_uI%gK6Ey@}<<_ zSQX#~+PJ04-V(hxThV*7ePRn(b>0hVHfD7g{H3|F`XaLzzDK5BV?m`_yng)QeIV+* zIf^}?E1#rHYR-NF&CTAPpsQBa4wL;EUUM*8c{?!4o1?tc%mNh5sB#_K4XnsRe#&)m|hR>;pJU1LsFSY9wAg?<3Xrm54Ax*>|^$Bx1^5D3D zLjkb7TgN|{_B8io>eJ}Sl&4Sj33K7enHWeR)lJi#kT6GX8Mk45V|9y!zfgcYFceqU zlT=+yogUOb1G`i3M}4RW{_^g`RP=-^= zZ5Vz9B!ddmKI=)_w*a%c`>8OkC(+{1h8QKboFR`v>x2vtXZ6J^1UwO=-B06l(e%f@ zt2Iy2(fz0BsQ(0o#UOQ4aGYfX5YD~n zXaVMmim`rRJ3{1vAw90>-!6j96M_LTDL6=E*1Y z7EkxWoG?h`R7g9b98-SiOU}u89%bE1^8jq25KqohZMo5>*klVUGNIoF@2Iz+e@FpEvPd3(itldlE)u8)ZCg4rW;djF{9698h`` z-pBZ#jd?_^4(f45?7yoyQa>u-T>&5mMs(AJ1ShW_wc+X(A(97&eL8Y#T*5GeBkQzi zf}@EV>f`2S`;c|zhU${y;C4laivpDoA-nJ~nqRpAV&J>S>Kda46!LZ)upknjh$Ma}ixRp}xAs>~3&Dl>f7-4-Rq4S9F1?MZlq zK+>reFC3FFZLuhK-Oa4-bE;MON?lJT3uo1&?9TE!f>V`88nyVuvAgeP^5pZ;&)tHP ze=4t8i)W5WSl8%i;SU0-rtVyX%^|dlKgf}RG4wQp&Y%Kz1khA=-#{5|ucCYd*uMyC z@xf6fox0dhaj;G~7fpWztbXZSl+D2(O;5}Lq-Ux&1*{J~?$U?(NEUK5in-TI}H$q-7S1-ZWbc9B<}w) zTHIVgw7DI9>1-v*Z$`gTfi#Q~HCe-)fckLM)|^$u=1#mV z9s!#-v{7;Unv`w6sM4SpI%jT1@=j-lyUu4<+I{O3e)aeFDMS__*6ZgZ)-pz`m++*; zpBp*HEUWL#MXuG`#qhWB`w_DXYYp~uVf$v$em2bB{AuWn%50`fboa|FrmIQCV~qml$P**HQbGJiA+jh1?GYlk zh=+%)4sH*V0Q__3qUOgo{Aoutz5cPNx&E`A{I5?nO^U&Wln~Rl9Qo-8YT$ibL*;fu zLSHV%y4|cz-9CoHv!PFS>UJ-P!M&f>Ex;V{jdW5^V^Hz->vVUlWi4z}^pP~A+vj+A zZwc#B*r(f*7|7(2{VMY_bY62XSJC1h4>K%G8e$x%#Xmd3^nw`VyhzGXwD`)Qpk z{`7jD1IQgmKsE$9jCLVQ7S@q-8rlc4-hw0@>C-?)`}7u0(vi~|NPOdusW76Q<(aj) z^}CWjrQEFe0$`umV=SMfpzE@oi>Vc|0&gq(Tv@FkeVEW&)g>SesZ19#JB`WE?_UAF zR+!J*Q@eqz8Wv=OMZ%Tafh-tKu1ax>!2;yMNL>9-RuGV*-)IX*fUnOHP$!akKl5vt zcU4_t4r=l9nlMdwVy%lKZ9{@DsSC_4-yfajYjt*g7~P#(j|y{|QvD$FYm=Iv*(3>V zWKGx#+cqR(vIz}dtIIcrb$932qq&os^8H|4u$@~Al^3t?_JM~zBl4xD!=(X;_zVU2*>Kj?b1+A$hYq>oVV{J^|7rqW&PsLMm6zXq z<$V&)Dq;|~5B<&+4?879-n|In)WMbJo3Gp`VRHiF=5HW^-#~CzivI#}Ljr=f>^DN* zK_lcf8viNV{uB23GRAGv5aTxHJF~jX3ZIM@mru7D@G%OF6LAj}_X{7h)ks>(3!3NQ z#Tdw|RKRyMUv?Cv^D5Y5;Zz0LBOxvR^%&T`3V*52!^^Q2KRMaK99lnjq z0pDxNY2S0|VhNEHEwfC(Z3zqST-3ZH*~*TnxgH{mISFSLeZN1qF^)97sy=~1|5+eUSE(Vay-)C-Ny6_U+n1lS!{x*l`+Um-DP@SnG?0A0OVT9^=O}%uP>RSu zwDZiOhKQP@X#aRGVMnH6gI9-_(K%**po7nOu*bl60hvq-9w=@>cmLFiez{0y3Kz=0L)(3@e^#LHs+`{zkwZTa@6(|LXwVFwh#MawX$`P45&!dbgTyY_- z`V|U}pHt3>e#w)0qiC9NqReF|x*9;-+5n>9 z%~5z?d&Inq9|SqoS6u?F^l1<|eMP@HBdwF|Q0U8-QdycC0Ad0pPYLkDKz6OJE-^cX z)HfOuy0b)Q6mVOVzkD(gbxv~3f0uU|z0wC)0r{&RVon)|NqlV(W&;WMUmJAJ26D*% z+Ms{7lf2?@i-JXqzpEk3_glK$OecB9pBbyJ=!o);%R{oEf|!in)`Jm|cjF3@msUZf zva{CBRemugHRU;F;SxQ!O znm0$uQ8qS%WFQA{R66g@3q2iD@n z;}ckW0UbeOlDng+D3IdKR`LVGcjha{?#cG?jikk{7$SGW$M+<(j1$Q3UT5vG*dvoo z#lgCDX;_ETaYHln-{*`TtUS1`F@UC=sk9ISGG;%aj^Di5yD{gVGJK#DS z0 z6zvxM*lh~aC&EtfVvR*^T_F)a?HQ%bREbYeG>~SD_N|_FsE*v zfGxzJdpO`;_mXSk$L;I#F<7$jczo-~XX|*J@A<59&AO#IYbvvFaSO;JD$nAm(iD7Y zCfZpR`A%JQg`&l4#%x$e#zroU^ZdneR=3EC{^B^Rom%|lH*x0bVBI=Bo`5s49C&Ld zB0SRK&uax98_pvJVRg>CeG_lJw-N|XS(IEmyDQi+wXTts!67StuzB9pW|ysX9-9L{ zCEMV&5FS}PkGq6$+O;isR}1n)R2LQI53110@X6$7aS&#_r3iT8osZo4&Yi29v%Fb~ z^ZeKH{_|f;m6aWR6Ml8d5e`QEk_(&(0?VD6CEA4c<>Ix>z6~P?@7Yz%UQn+p7nhCp3lFDz0bOm`BD?SxeAegcTaNH zxAGndCq2XO@+8PMTzRJ!KQNw*Efoh-Fsc&p%z(FwU(GkWSA*<{qDVS1Yxp0wa+6(KT}KUe}b{)D`R zWrE0?m@ZpS1h}ATXGu_~@w}FS*P_W4U#z%FnB4g)pK)_(>q6qc<0@yN+ugs_jYtJb z!KBhwmdTUtbJwhow)5`$lX5oEW-5~twTN7b34beQ`DoVQmiGhtnbvNW z`G6ubo#6nIpTTLve0-kkO>7R$=%1+jylHR~v*2!3n0 zB15!;3d=7vUD}^x{Z$9OHEfS>l_9OuTD7uSuE{Q4g{CZDKw$Nh#g#Q{qTBe&`>R{R z^;4Re5C4<#0rhnKq?=bxOZQl70wdALQsi~-TH)@0%bi*V#OLJQdzQ#GtI*2jE+V*A zF0QO$c`lXr%Qav>5ni`NZ(S2LWUSlNsj~GpGkUdcYt)|vnJ*IxQ)ST?6UGRycMONCQh8Y|cuIDKKqxPs_VSCh2$x-e{97We>;68>&v*^@$ z_2uo01Uvz|1MZq0y}k=-{78#`rpZ+~&BZNjzivpKi5b@Z zIu`qnKK^?0Q}lV07Vp*=-Laj9>Y%$u!2i%+-^JJbpllUdwS1~j)b;%l2Cil)TDDw{ zf!j@XxtA?2Eaz)hAa1~&k)`+zqg^|ff7Qh3Yv*DqF}gjPRAVng)-cU2-sY6B+|Th$ zg0N9&@n2~y8p^cN_fy%_o4Tk_?2f_4cc@Uz?sE(yUDlcu>GHA*P5(ZUvA8@Y*Gwws zEUS=&pI)4->91rptuWU>ZCC!-ZH zRdkY|u4a10Ptm{%o`8GzYwy!;P-G{ARJ$-S62ruw-G4 zP@^NfZY@Hy4y+KvlWyvw;_|O_x3ng6@nD%u{BC}(n+WdR<^xNZjLqTsh~Lc*B6*vO z`-HThyuYbSsN_VBT;HH-W@EZIE@qSX99sM}O|VvOVU%6DDH$_-^G&d(V=ex5D-BMp zGT=0PTXSlSqb$i8u!eEQoeA!uEz$a%W^av~IC<~=b9W5ZzvvQ=SJtf1>pCS2mXqq63e?Df${GhkNb{V69;*T3X4e3BI|On7dL%ba}W{g#?3-g0zo`9SXOrlx@d zrj!$xl_U8WEfRM+dH372sQ54HR6L*-?#Rb;6bVo9Xz^RMfAXl@{O}fCf{w*20tR{nq{M2w}m3Q^^ z&Fo3gzuhOK8$%N2dly$NSe=EJtWJ8Y)h!vsETm&Tq{Z*h95||K@k3+%>Uv@VmTLyE zLn|r=X;vR8IYx!zxr>sPicqY@uN?1HvI4wf!9B{}l5x4<=2;amqk?ED6(rYqdXs#g zaYR?@z<;5zpV8Z2D7=8K*5Xsg_tFO)`bY;PsE{n;rE7DqsizM*w76+}FTG)oVHSH^ zPj8rWGCbMKc2U4Gxs>J1RuD9)o#xt7t?e|^)=tf~;}mSx*!Y@u3O1)zeq4@KSIR`- zPJ1@aiZ(-daUPr6CKNuK#Gx22Ua zUUL(_+Z}_9WsAq+KOJGP3EMuwVQfW3zVd#yZ+D4*Ts1sCrbnGxJk-k7=u4NP^yLd; zkeBEzk7_`2@xM?@jJ(!qBqQ8dVf2;Va`+ZK}YibL5KV}Tgx0>&IEVNxlGUD0hiFN(`)0fE+g z=YVLR3*y!}Al6;{wG@JQ$Ho7j7J|655JcmgnXa~VZ%=(c{c`=RxV~^XBgg|pcI>S30{l8Jqq$~>1__S)54SKJhJD9ID1+M z?44nlc`V!(g^aeS6P|y-+3yD51Cx6Zspa+dce>jL+If?{f^b|#e;vQ5)mO-D7TL3k z*`j>q10WxGK!{9D;G=ykp#J26KRj?jWh4JX7v%pg%zESOmxp0?ZLIPTBDJ8m-FV@) zLu~_XFi~I8?}tULJ_ii$u9iGn{HhU#*H^}Vu7bTb<~@XF*TzZ@@pw&C$dES?^@=Uk zhT6f04?%uyZ1bUH+mpgD`-X6`<$2xT-|k<>kEyGUqS<^H6SMw`O&_Y))me$U{+m)}Ne`%V z47G!E4n@B_p|6e2I<&Z7&)3Fg9;%&vKX9L|1YOgdyO|MX|a5_!numF|9& z!Sb1>d99CUIE?{!Y}-b8TdmrouZ^W1`sho`mI_1dp#IQ5^tCbm&~5#|*T%G0QGRV~ z^wl@Nv~F2qs2z;I%6g2wn(UFhdWkN_hQL-EJNv5TajnTvp5mMyaK*R{)@`4C>5BO` z46B#)#0b%}IMFn=hxSP0Dcac7Lo=N{G)r>DoQ3X~bEE9cbjqZ!QjYb?a_nat89#hT zGaW!)^3UK+T|G2Q>7lvB)123&ImyfZ9-39GS@xFaq=DT@p7r0!PwM&=J9)7DIL)<9 zcD~qzc0<0C6l^`7fZSEy(8M4oZH0nKCw7)2%M&*-DQd%)r07_@eDsVW1vq7CRZ3tc z-c@4JrF7Mmy_b-zIaPdMZwXjxOUL5ZjDDtH(e;pb>RmcwGB!u_rlp_gVq{WNBJ%aC ztxbu@*Z!?dgZ|kI!|y~>Cc~@+p;NSNYwi{L5#ytOr$zU|Y$v&U>#ykb&mW0^$w}61 z{X2Es`|uVfMa*_5S-I6Y>m_W6OofB36~vi3eRyXCJ*mYn4F7H*6}0&0!@r_8%;BuX z_^#+S{!x0voQD(o_u)2a!aw5p8%!D92EU0U2vSsB{P zu*33W7=#ud9C}$jX@IUIMn3=NL5?AEQMIvaX^j)!eZ0{9G5eJB!&|{B-B#1o8Zy;taGJm6Nqu_PqSE!z zg_B;|5~4yDPfQb;>_DU%E$E+^-bRJ2{7o-yy3W9Li85<_M6d5+*=bsQ_J}$0rdU6* zi*N8Ya}Df08&k2DjYo@58}TO~Py@?l5+k|dDiQ5@G`!-=B;JoFMwdGBH!G*5 zEZ#9*KVP{fJInK`>tO3uc>3_8bU~u*V2&1lbZFj=de0xI=>OA~Qu)#?93h-Jzc$wR zYSLd}CxXC!@XIMTi56XCGHCIKhkiLU*#UO3CrEP~_Q1L=OmZ?m>X%=x+rn9?dO)Zh zJpM{*`7sLfoeb-c~|PDPGYFLTG*mL2yU`GT$MzuF$f!PG^) zJ`3iR9A$5b4rc{GKJByN;+FfQvG`_+5_z}(O_@CtRiTyDt-iSb>AwQxqzBDBOy)sr z@hdOxKu^3$!m=_GuTm0`neE?(yifYPX)Inu!NM?j8x?V%kNHE@EtmSR-*iS116uq& z?fZQbuvkmA_yT&Ll!j++7>iG&_emCP#bfb?;i+CtVwT&5rgkbC+o_n^PHo0^YD;aW zrN(wzn%YhkV>?w++iAVAoz|ze(}Tu#dN8$}zGrNw@1<76{JwT-E^ViorR}t+w4LTA zY(OpEPqlbAUAJXzl;_uNVl%%qW`^5el+)lbnpP|m*ytu~1=5Py^9nT5wWHK|<#@bv zq`q`K9!^~UXXLS)wfGM0F>ggIwt>Yg$KqEGZ7<_6k1I%Snv42!5O(>-t#5DQ?gMMu z2$z{#c-z`3cL&7MWYK3R04UC%F0~HP1<|9o{^E{F(*YJb8`2%ap3OlGUhh4?QH7#*9C$5=^Yt|esZldGyF|C4V zg&owqT(fl0%;i^=chI8c9W<+WmbZiEF3(b=La-fftstTkBsZ1P+|>LdH_gi3<09c1 zUa)FXURf@KDo8+iAkR&uMQ&;?aMP@`oh}l-+?!dtZ#AR6mA(~K+2s~eyTB6Lf-JEu z3oJxKDQ>W=Ts^sb-|DT_eZKMdr{h}u=R@~N48NoCwl~>XtJIf8NPAg?lvj;F8$e_{ z_eleY9~XkiXpF@xdN28;siLztRdl9|Hd1qO8nCld#xmFq4RtPb{GTVK_>Z9h6~dnL z7f(CIRA^=Aol-Eud?`CAu#|G%ES8nsn)wWfZ=^yV=S7KJ$-le~t^fL*)BNwx)fb;> zVvqJR3}hwMMW*wsl^3UoGh|}o(G~1ux}4$mdF5u`fryCQR7`sz zBEn6+UY~?rRQ%C0DqjDYQs`dh19E#J|ARV#EPWkCO#BOjFKl3~RtIm%%EA?~7dC)p zD*im1AAI5d(fDH;k0By)Fu4ET7b0fZx7s|{T-d$(aaTOdG6D_MhOKxG*5ZHASpFu< zJOT1_vv$_(y*8Mu=DX)M% z`bk`saDO6)iu2|usm%h>Uau}m?$zk9sHCy1BkIc44RDim12FleDmgGkNe@WMR+sMh zQ@)NqZZ04A#8=#sjT;oAHV*nthGV=DBxHx~>JsEwB@U^Rr0SAnmi`|DTKxCg-o%do zce60NsMFHZWc9s6oeNl$yt?HUDqR2Dh=`c==b^&&w@~r=53&|3?;0{XKU{vSkJD#( z8hv8m@5;NrNy;r$Of!2tR7_i`a0GFjd!;WMvo=1=Uaqtm%$>*kIP+GYG0?5N=bMs% z7d=_NB?=-4A@>sBl!UI`s@ZT$V!vclD-G(giDk}w&v?NaqRs_9O>NX^VdI5@d107+ zb;uC8TsMQ5bcbBCyV=g!EG;<$&^{Yv%FKls&%Gz-P({ zpR6p;G1<~SmOZPd_?Fz{o8h}O4+mc9)8bcam5P`+0m^W}TF%p0R_YAJf*rU3Yw<S|y!m@N5%`J>`?jIHdnGUf9N=MbURF>nw`%;yR zX3S-xR4RpIc?fIm>@62sX_imzPR=Q4&t_WG(z>;blOzsEHk29o-EbqTN7 z1KA4aUma{&+irbf>OuE=_mTyD_ z+3ibJcwa^{+k3ArVSDw}C80i;JGVL2SJ+(c1DWm2SC?e?;_6CYTr~s*jGlzuK(dBU z_JMhS$!NT1%n@iBgbM!Hq$ciPa*@Q~zrPn-wD<$sWirolk{of>7O({PdXRFO*#7%J z^OvF*^Ov-^Py1*7()5|nwI<{IyprnP*UGZ6lXd>JWaqz?uvs(gOrQB|D=6|1` zj_L69p#G(0RLDV3@_Tsl;5ff;u>(B~ZLNAdOBqo0_$!qL z-HHyIFxY?4)0lw0t_#Q;^zN$Bz}HoWU511tI!@14RaLFcW^`x2>lxP-;cIf{VhdIj zo-7*y+k_Lpq}aitxsOon(Bkip3(8s->+w(Yb5-zMlWhvXRbPCvuIdWU!0N-U&d@;B z%H00dnH1Txt1qaKcSc=LMB#r_M{q|Yi(DhjA4I!>yqn01-b80&w2$RcdxmtF&F*n( z!^TEOix?b>e=wTV`=V2eKk=s6QXE890fVK$p~X3-Nv{T3h&bSm%8tH;g+Q*SLSzec zQ2$~e*H9ty9(2&ZE>7<0UiCW5b186)#h)7mxr1iS>7WxjgJ#ar;(yi{zyEpkw94YI66T3+9Bjiq<`$kTdQ%L7g=uzV6&+}+ z+o#2w#{W6?tKJk_*gEs%({UX>t?YG83JDQW@4!6yY>b~~IHARJ$9YAt4~CwwM?Zw*A3#|+#tFuKy*!GX9zipZUp;KxVnVL=HTu?ibuo(Mvh%B zJ`7d~XIC40%@i%-De^)=B<##a#pV_fo7rhl`$+hL%HwQ|3ez{k%;B&(o8=dB9szr& z?Q)5s42q@$ML94t9-fpv8b2|@_N1l~GOs$BW65&HQ*N>=?&g$5 zDL1E9oT3H(!!ACIWV??=$8Mp*{G+bHM&e!lKOV-p|GDt5P%HS9f`~^i6KOHLHS`{d%reK-fc&z%^u0^b)s+jp6U%7b6RK&c2~LB_gGG zVsOjt!;cSV#{9KnYX#AZMB+9uGd32!9xV0TlEl8=u(*# ze@s0*2(`_}k3=3a<%f<$Hkqyr9f{m!vV`+u{!#9%bd6c5fMhE!Xt$#V28mkMOg$g?!h!4o5g@?D`94DQa%#1}(Y?4g24#tf2X za)($?nXQ7%%ST;lCoG0P4DbeH=j+(6NERF3Tk?7Yi8TBJ4_wJ0g^*n-V<*?H*;~R| z7h-VBz2zB1G~Me>Yu$zS;@=O5M&p2}&!Q-&s`+{h1x|8!+YdY+W3Hj&%L+2f__kU> z?8a6#Eg;Q%zsat!UcOM21HSA0z1FwPp$d={Tp>MDrBRE5Gs5<0;bDD zVgzv+o};eAty(r*nMsVM-0*xnxfeZMI_<3{^yFVu)WAoy;vSVzd$;b$u znSYYIrh*`2a!l_nv@4bqnK8JXt!8HHLdzYNy(Mgogr3=n5q_+#H?+O*w*v$2){Nc ztzQ#n+%}UKj345UsbF43#nil*e+A5(Nz6w538$+p=3lXTU;&ywyklre%wMYyF`V(? z#r=o}@|ItGIYqXzv#dix&gV@G0zC!f&;FSNrFa%jAAWq;fBrSU=e(J_eYieq?B_Uh zJ|CV*(v8!HcMN9}vkAy6{)sPIJ(K8^0!O}+{KlUjYb(zu<`h;tn}{ZsHi5l;=#57r%S~*C3qvnP*7GNtjQJ(qM*G6BHL-n9?OM#W75A1tIa}bt>18v-yYi zlrY!8w3A!ORt&q5!mOD89_{*~jF^p6h}ncfWifx5S^h*ltw&vDv9_{`n6R-cv7$39 zj7pMvZEwlZFGTr$)q~xtj6cB3RT=+K&5rpiP#6_LFIU*pbi2CXyq?SM=S(-oRvwC~ zNm^m@&N!gwdzy~A274~a54IMTkX=dgI%~%iM%TQBpI>PEp8KaA%mpp2h5=Kgk}jw1WU0g*p@jCr55 zj>$3a*bk zs+RaWR|`;d#o)R$H~4$6eXxCjn>+)e?HLdcGP&)4_qR1a=i%C53jR4Y0JE7VL=1o| z%pU`r@JaHF3yZ>}6by%%SG3A-A>n;#@v0? zn0DsGdDV=y_{T%+{MgNu`DYB0#SXq6f`aZ7zq;tHJxZ}7tp2@Ezj#)*Gz*2N&(7^` zaV@~M)*Em>{=7kGXmt#^T4j6=y_~2-?%Ik@){yO0$Ihx1gjoQWe zILs~Xs%SuqKQtuWwWey9DM2@c&dHW=N1wq8))m>?X^DiaKqgS;J+a;5Z9}~( z`>h!Q>7<&4dsHCsI`gI`;LETU|4;)P$FSgF-!lMWreKTrfIJt^#6D#^Epc$-6UZ9 z<_t1sGKSwa7`lMej)0BtN%3;l>}sLcz8Tq*UpOjmIbay>0&;EyY!`YsFS35EzMl$t zAv4P<78m(^Jb6-MxeQG%kB>T8Vmfu?)G~UcGRJfV5vw1BUDcp?g zx-iQPW3ezGuODT525d~`VEQ6iL4{L8YZQ}rpKHp;CU1knN1&1)gu;EU^kY0}(0K9_ zO^e^B@#J2OCs%9C1Ab9Uo~0AWy4TGu0Gz04NGt}{CdjFaZlSVd4X`V^&cm*Sf;|@2 zdvi7yHXl&rW=;}_gU*!?_}KXlHs|*eG2d?A2?g>;!__719rL|j_Wq&~W*G1(+PH0M zHUGnKR(?zq8Z7gt+s|~P7nV|)Kr+mkoHk zlf1bV$rS`rIcWz42T!iic=9a!_5^u#T)mkV>y^RC^-2& zA5hVGeR;;_jOH7?Ih!-87o4BOa~AzUxbhX6<$FEdjMw_}E&%~(_l**I(@xQ5z z!uE|Lhm$PXDinp)xsn!Noxs8UTPG8qbCL~P?Nhp`Xx{09^LK9z4*F~1yt4HaeWq~* ze$kZ~eoxZkwrH6uuIqr zwzl)`t-@Y-8tp?ArJ}iiS9>U!*_g`5+4ZLJRaCI=aybdNRVeCK8Rl$>zOLK~GiGCF zFXOG!XCc84*8}7^A<6$C6Xac@b(l3Td~fcxA^op@URJKW-TVa3z@o$xG;x*qW&})z zP#yWHyDnDD*Tr~u9g%ocd@hXUE~3Kxra^zL8rB~KD~qL|xeq&q{GO&IRCd($Uw&mQ zEL_c2<0aQ$y9JB>p#IldJT}JWYvwz@v|*l{9nS3%Yt)a}vY$Hu_sB=7s#JUYf0 zb+!9-dwFtt>=Ko9{Xc!Z3tSY}*+2fwWp@WyVFfP;h_kz37FTo?j3jEZ40u4%Vl++g zl4c2N22EtuTu9QsE|D}Swy|nk#F%JIQ*&v{qO@)d!Nl6yr1^DMn^r*+qD>}x9m*+f}?=zI~P3q%%>Q+7VZ}ik}`3z0Zn%weXALoF+ zU-=k0{hRT1Ot06?G<|`k|6EVM$H&OWzA5|HdI}%&yq=<7PqEc!e0>bh$ZrlA2x~R$ zG#u8H-9tG9N9+rjzTdaGMo<695IEKcdE2}Nqq2>Mhm}u;S*zi&;pdw2%t-nt_4Kg$ z{x5LlylV&?%eqdrX67zAhb>w(gtqhL{Xs7yR}O6@<^5;8jJ#@SO4+{ocZYJynuNKb zPt{jjFva{U2?@&yBbN-t(k~dQn16Tw&fgaHC8yw+j*aNMhu-}>HfuA7WdG)jQ6U`j z#>2EV7C(JxHLp{c<(l$*JI=IpCfykqnn8ePJkSKr@N(3Vt|vy_Go>qeaW!#z7&)TS`>aGH_Wom=i)0r=?`Gt`sp|+>9U>!tt-1);f_vex z^4CCl|7ZDz#a$AH=OpOBKEU^90kXcgA8k%z@1Osz_s6)nGE-Zs2#$oV*!xlPR*iD7 z`rE}ghu9Ml3Dc@=EFr1o{ZBt0SAJCBLTWo@vyuXll3&6+L24f0E}k#rYV`Pko`)gj zH`z@b*)3SwQiA0-&6{=$$-(lQ)TZ6S!9d_Ur6v1qsE zXT*J?uE)i5?PkQbMfqU~vwpW)>H?>^qek8Wv1j-npDzH$u}4QYK=}wGqGi)Qv8jY5 z9{(wygA6NC)j)WUBakOr$yDOfHE?<2ZTE>g)lyfApR!VN)7yyf<`XG-_uJU_->uDV z++ZmlR-PXyJ+en#;5uldZ=>eas|#F(VuG0FR=cXB2=qy=qg%y_YWGcc*|l+Y3US>BZ_@YBIgGBeXiQFp_tyZgqo7XN z6b!0MT`8Ux^*+~b-%ho{wR@v1!IZVZo$4Z2isy>tQy25DcQob49U~UU|ACcSx1(rB zTx)vkUV*z%w4-iEdTU(k%Cwku$|q9Yj`=&{T3aHMUAe6b()$qQ0Z}3TqYSF?^EC`pLK3U{TjQtvf7R)Mb=w2 zqoko;97SO2f*_tx-qvRFLrR@y-H_u)ZWy)z?Dn;vZLs=95pe^-etGR=!iHTY`9d0tLq(urv$dQ7c4VrSlhGRT7zCV$2d(?7#10SheT_(D%FM6<@CBxlo!SPh^ zt}@DY(&HdbagX|{B~xVVg|d%oDdE?;0yT0nn?u}0Q+}vbcGr6-8@}-#^{^#Vq({c3pb0MXa~?3Lx9;nf&jyYeUys~ zE6=EV)CK&51C7_Inf2-d9_9Mn?cbZ<6>^HJsx$m3Jv~qYS^6pbg&H}5-6cJ`0=NgO zfO~H>aAg+{9)8CP9fDKT||378`HpIrwr)sh9MGuag_f)eF$2G1y2I39uQ5U+*w^MoV3iawj*HPG@wd?hC=xdqYk!!+S=0C(I|^6Ixo!-^ol_eD2dP zX?YBtJMUml$w-c(&^dJ}Z{nR|n&+5$AK&b2QY-l8jn7NgoLM2$v^-45?-Ztoiu`Hf zX>}>z+;CXEkKgxHgIeJ_r>=5=^H>o0rjju zZV4GuJ|2!)rXA8wOMejlb$;y*i%OrMW*%I3dn=_HPfTc~@+#~1wPGoadL180&TW~+ z)9U`NHn_mq60{R~;c06r+AC_WODn68E`#;ojjXZUzf--(l@g%rKJ^}#rfkw~VPyE! zdn_uVkgdlZdyo1(3nSBpdUXjO_CM{PuUkv<1kc{Mk88?jQOaJgmb><-bXqU6Ua9YUtZBe~i|v(s+t=4E&u!AvKZn>V)}!jU6F+UWH6{)07));6 zGoKE^z9T}~xzD!S8sl1%TYo07p-bx!3wPJLoh7kvoIHeb5k$iJQ((W!x^R_^A=6B5 zyi|RA>#hfcdu@$JBWWH)^ZA8f+e%+3mw~ZwrDps|V#7WdQvNiAEA?{XCe)p{Qd71! zRio!a)#7bbS;XMvldE@@fMb8~BdO32>)+qbG$yyEw>Aq@P*a}iKuU2G8R_Hi*xL`L z-fSIGHe)R=Di0|<+}GP8@h*EH#uL+&iVknPwd%4WS zBlo|!Z?*R$)#5Ym{-}q0{iB}v?L$gylqCfL#8EZ+^F59c`9X1C#WP@K!#fQt$bj-p zbX3@4u2;*v?|hjANvC4}U;L7R_wAVrpZk)5dUctLvsMMB95QOr>kF@(JkRX!hdkRintMHEELhg22oaGpaxREC4enhawXV~Wul z*llD2xweYR3wi08O~N>@dI22eSKQ3G4%*(7!Prl`S&UqWXr@h{G z!{Un)p2-Z0&+GIc+ADvxAGjx82CjQQaG&o74obZxL;HcF9G14^AnlkG6px$ihO7kd zBJa}b(v1(vTj=dx#`b~NZHwO+Z`;1n+m0t=L`Fr@gV< zm=j|u+ouxPua4jnvIKb~&-=j2PR_cmTxK|qXi8Y~*(ob+E0^OE4|p$cgyaGHYa6@0 z<+8>6+9m^EuR`}jUfagXjrL9TYFzhvv0fc}qFgqbFK+_-fycghyk1Q^Q7)Uz-A~l3 znLhjG%FVBAzO>o;Sk+_FWA?`nK7QL14?S_)la)`_i1jLeBB{7uwSx3yO?AC$_m#`> z+{5w~Q@xt)s#hob>Q$T9eOtYHTX(&h<*ip8o(*EXI>nV(T(3I$dUdL=Ud{2;tGTXv zb(*VQo$jhvT_@_*8E~z-Ud`j{)tR1pHQ!sW&T`eOw_EDf*(d7N0ytdlk+(p-dI!|2 zck=b>9B;ik*Hy31v)qLkDRn7rEV;anC)Cfn)-{z-d%>Xu@qXnx#NoBLQ%i8&I<=i8 zcwT5Axvhv7MeU+yy(ygQfNXnXdh44)eDL!2+}2CgsJ%z4jPLVjV`~cfJaGlTzCL<; zjOIghDMbB?<;o0Qs- zLkXf{Zug-r#PgeekL$0FgSZZNTzt=6)jLZncf7JAwt{DeF6piN-%sfv_C~XGsdiU@ z4O^gIrCTU@h2BTtpt~;Dg0nG*|9={)kr~5J^uGC8();k6w|!cwk(U^@VDA}zsLz$H z;t#5gVY30xR(S(#roHQWEjVuv<<(MoDY9nD4^q=}vHjmcv*bO66v_I)^>r?S)*)=B zsT1)fv8-hSxNggJ7^iawGOw>=I#-G=(o}L)+E-0k@d{JV_I`nFWiLxL@_4peQrZ#; zg!4@hE;ih+vSmB`RpKjRk(|opxl@V`dCL6M>wNW)(mjAC-f zyscs)8B1^^By(;;$$yTRGRwOlcS(>9=hI+cs`*Deu|>(BNA&R(!Ld_HVxuRsW3$M}6f?1i zl0S}IuHEgQFQ*z}G}SM(QQatAc|Qd98ac_dxzf=6xM+}B!^b*Rf^9q=DbQt&o2$Wj zGdR)nc;$8d42a_z<&qCn-&K|_+Woz?Z~C#fvb!nywg@H(w6L zY@+@(^o4}`yr1;0bC73cH@9!y>Fd5!)WU%zDwIzWyY>9XKMV+DxvtyYHN<94?DWs4 z&b-ze$6nd)9H9x=VDCCS+wEJ|RD$iC7kO7Y9*$4C6cR|R)^~^4%&yMQB-9D`f4a^* z(#{Yb!yz^}_SZ$#kU6pIyAi@KV;>ln9l5+6=em7s3HxL|ziW$nd7XiPb>BKXMMCbUU6;1oM_Mk0&PnAm70-qfK^p@$ z%)^kfV&vKkL(07ouoVzCY%z`|L(1X^Y8T*D=}4MnKq>*O1vuXZQ7TNy<%4$OATgd_ z`^?nB}J4>c%Q>bdkp?cg;Qv9O{jw5OwmCK&H zyqzcZt(sD*UDt6#e<|@q=(B7@zLlo@^mW{DO9<*7?o%2Kjj{#+8a`ErT`D1@dVPN1p{i zKB=Kj`xpTEUHys&kOLYUP6p(yAuelc2aW`TzPg%?sOeCu*=s4M@jNxh?#282G{g%5 zE6xS07x!4FxYEe}y}bYFN<1~C4S)AJ3)3T3gZ-)WfKHEyO(n7O73O+bKXLs^`$)31 zjUgNvO(^*}9Rmjua#jaG76NM9)>>R28U_2A4?%O<&TRv?NXb8nn26~ARjrR7RN970 z)NJqusCkEK_X~#30y3!V8>*4VL45c9YBmfidxm6*n$;#qXCL;w<^>-4#N#0<;T#=Q zws#=6`ng(ap6QH798`WZq;sd-1Iq07-+^~>m3VHstJrcE$e9D{V&kv5xq#iTaDBQD`J_7pNJfL{omI zv6)O~Df(R)c64`!fr*z*?0JVD`zrX@-VZSq zzpR2Oe$aDXWnC*PnBtedxhf?WJs|&ZIL2c;OS&W~-!hY%dNGs`rsABY>sSqV6{`WSE_x10Y8%+m-XXyQa>bC5$bQJ3 z)U~y?t@mV7dMC(}huO@euFc{Vi$OLSmZ>&?Uc=aVo;SrjzmvGg91qA-hS3fJ?Gf6)9H8KZ=7P;L{HsC62N)@@hWh$F7lN=YA_s5Z&A&U*q(h=p+LCn!Jgr~Kck$*{u zvU_sGN@Y+PHT-WY6_8gPD`-nv1oGR%22v$932ex|4R|WgUKd02KQ;soQ|F-4Hv}T< zxDnjpxE^#1;P^U3+1GgNb-j`WP`3o+y~FXP%r?qt4uPGi!_}b31M*o2_ zizj-ZNc5E8c`f^rbV$EH;JGR39C^p(;H+=bK$gpM@tYL*?JX?&jTp=RL!xRKLKDh0 z!#_Po4W$rj=7iemIRino{88H&(LmB_r%&O6w=Epwx@`d^|5;sM4bH-#)01815Hm!k zcDi$32qw=aivl)MBU8+j%2PeSp6a2WNF{1J8y-&;p*_XlQdDaCJ7Gvl3dQ@UPZ=N5 zl=n2I_PGD@HnjU@oMVEA#K{D*61r{v=~L+7p81Bem(D{LmT4nrr7H0@l0iO{X!4On z6R>}Po*@N=(Qj9uxmkX8(=dhbkQ&0LkbA;-`UJj zU1|MLbE*ek!>?rt8gvg2Z|joR(Vbu~Aa8m=erv$kB>D%H*9PLdqa)wS5}H$;A?62+ zO$P!fV?cSc{Cv(8j#)~ulmjIfB+3~Vnp2%Fg0nY>y60!5L8X2`l4@iFi@r<7vX}II z`Nu7&?*{TB%}N+Dh0urL7n;(jp&uQvvrVwuud|AJ>muab6|~w?XLvFOmFI`RZuh<^ zrd7}McjD37V)^7J|ieu<4u}XZ?lj3jQM$K%l)0Dy?v{q^%hc`nQ)WZ`&WmzxTj> zy(8^T3^}XQ*B|nurw){r<9<>Zagjk~RRrhp0g>~AToK_3WDP1yBiE!1qI0u~jHIz; z8yQbvN@*ylntjFSJ7~$Ra{16f!QAPr-nZTvsF9yzd6J-G@y{hOYl+)PU_N^RtyRKZ zk9oe9oYmAD7=!)CW=dVu>}%3N;q8v!h-1h(m0O}I2L?y^56(|QE{6BC$}Jh|e{&m^ z_hy}@v<<@a&LFPuY~&vjmH(*NBT-Y#9mOKfg!d$+?Ku%Ov2V3)LdaQdKXPH+m?JCK zGe@X5a89wA30>5_i5_Y{ma|h6J)=th)I%FU{)3ACFy(eLKd4+%8M4Gr?Sw3Y=djr1 z0r{}{Ij&ahRa`OI9w`GL>!i3`)RaGVpie7f<~A~hG?53ok^|_QiY4^4)Qi;Xs405_ z`Kw*jz9!KfsF5iHS}n{Ag8j4#t~z7WBf52I{2i$U*DYduw!_J>|o zi+BF9$7na(>s8{yTE_$-`?Lz~5gFw3e^$p7UXT`Lu~Fk=uKZ7tqA~nV_YU-yG@tb9 zv<-5)ClXv6&PLhH#SGY8qsxGvP?>)aOeD@@TRd)PIdb(+#0MIShFJNi)2 zls`mo`R`h)O?fT~j%e4>h#CDZZR;{7e5@(^qexZasiF87H7C6l zoQLYblrN3svG$|1uAv z`a&Mk5mDtm4OeVSJKMb5)2FX8=QPpZ5;42;{qJuRWDEU%9pc1U+Ces`JQcaQL_d-l`yFXQI8Su&OIByC1Cc)=aS*my|4eGC zIrM6QmTnD9Sj$UqWqgKg$yq>hJKE!ZeiJ)HbEJ?iLK8Sp7Bf zb|`3PbYB^aFV@n;3+A#6ah2cx$W~!g2z_)7C|N4ld17BZpj;mD?SXuYEU{N_>)(BT%60M9Pjx*bxB zjzON_*OZRoEYU$&t9=KRXRoL2c63UpQPwX-kSC~&-TtI~2Q|lDkJy4ZUT|y~%2Gv_ zpV@*t=Lr$167<^{i}$uA{uh0(h%#r0C1153@Y7q&W$0xfsvL`9kXm^%lSGui4Sv>$ zc;*a+Jd=pBJAk@edg<*k{{;WNUOdT|$vDzP&^zEAL6|Z-2syL<3m36SOz=mPyR}IR zsQe9{MDdhr_GJbfB&tl(rgpnX9s%24acL^`@dR;3;1yxag$ZI#;MKI01y`k1l0ams zL8OagSBVSJ$7AV$r5mZDT z(%*MZP!K1TH4C$EdGGuWp75vY>YXCF*?L|DUsQQWLyUAB9|fuj9#vmH=Z@sHVj>JNCZ(Q5~kMFGSvzoQIybQ2jxb`gD@_zu~FQN(lkmqRW$${?tn z2mI9Gh*BFt>3c-6MJD=-M5kw~xZY!YDx%yKK}mya#M9&)@z84Iw&VpnRo2CZv*I$p zcYb`Q3MXEgkWo5uAxggs!$4h)LM5KLq(M9CzAi-m$Hifu7_9?}T`eUM#WlP~U1b6L zq?|*mN1rPoQRRbSpMQ_K$^*Hlf|nn4dh8q4drnA3EA9nxDxMtTjj~iDGsds;59*cq$QY7Htbx%eaVU=}MeWIf zsPeDD)NVRFp0UeG2`lD9U#st6m@`C``oa5D?!^!1o6oUlRuI%I1Nk*IpSVd>X&#L6 zjqX#~3`1{Ryj7+s?9=MBPE)D4r~_{Mz8dE}X)^W3G523`vxiRpnP;@WQ#JD+c&3Oi3u(nu zJkImcwAWMLTrx#m=qV9RGG&@mROG?jcMjtJ>4QgwUBTDG96f{ZL{*j#G@{jX!dsG4 zjO%6S^&;w@O!2J8`dujXNx}ME?@2|v3@EKg@N`O8Qv9G*@26dZD3QLqU;Nz+g5|2p z^nn?~O^PJQdO(ton#BZSB%>x&i+?dq_b4`-piH)k| z1Mc-)JL0`Cfl?jmh0!^w$zrmO8$*SnivJx%mPz&CJS^{jdehF4JtM(GmsJ#@?-p-K zY@a9+&BP#b3(t@LJW9_hU4^fh+&0s zQzNqEZTo4<7&3|&3455?h3Rc1hp>mE%H?5GGd0sfFz1^CsH;p7s+l_svZ^x8IfOeL zRYJr0p2QY!J8FdwNbx%E6C9h}W+v25*tPQrbr@u4gxUwq6KivGsh~4AIYi}AyRC$3 z0y$gF%}olmgrPj{d{kiuZMvl(xPKTJ+YQ-QrGcPZP$lHuMV0<2#@5K-p6j3Gw~Hw% zHT4aF3Q=?H9@JYzuWZk?B$6>$vtvmRYrdvZ`zF=qPN#y->8X0X)a!UoC8{AaxihMK z5QQwn*4c1mwx2=_im7kwC88B)p2yY=w|#*Ug#ySr7QLYwqFkirN?aVZk9i}9q}GDm zq*nNg=QHP+eU{MP`H7uTy*0qAo;?97**5$N@s%qC}F!HBNg>zzvCKl^~T98+($NY4@g`ev2wp$!=Axx=; zs%m5Du7~LSu(UNZ)p_kaeut}4Jl`Yb6OR8vKarde*H@>f?G_vzDFmDuB>tka+D1}~ zRprNOuQ;U|toGtwPv~Ae;h5Se+fP)J1#KHNrCW>X{A*W@Wz?OF$5s%y* zIE_%VT(ux?Q^BEzCVRZ?DQ(ows4{nmazz!y|F`(5y-~$76hoKNu2Ks@W{yEe|A>sS zfs7+8u>?Nwj}hPTXOpR9tV*T7?#ESotcvpDoZ9JxnstZ%#EegZV4vfiPK^H9y1lDh zXC?!P`%;@qsJ!h09fT=r2<;3K%fRMpJKF>I?hxWarz*FK=xqg&)+Q9yd4PAdzb??B z_bROMjrIe=bmDS+99GppRNh@_Zfq1)rrfBmcvLRY?_Dgoz%|s--Sk&*Ux*^%I zKdQpgEe_-P;0#g_n=fvVXC9kV4bHy>vE;u7sW;qx=6iGrvm@Bm9x=P}e8>mp;4f0* z(I?wXzoB0LzRIqLpARdZD4S{QnnGp}s!3B`7~!TxmC!fd{g5K_>KwutqR?ObmH_9~ zS6@+6ZfM|$bfJe+q}O=$fXD|fZKLHRnwj!dh}G%Nu{v!s7Cx7tWA)2uAA;U`H03E( zQ#uCF;zU*MJO&+){s?Ie^biqM!qLi1XX_;*~sH5+yDqflP zYU`1xDsxdwUhx&C7@{WS*LrG}g|L?AljG}tEx7wkb*qc%0{0c8`(NoWd7}UCZe6BO zG(*>jXcXekLoUc)`(W~^9-v$#_Wa1e)|)VGVW?4{&psZ;RGH>=rmFuQx%4qi$sxUFi$PEH_KBJeS z5SfNP(;z_KhrS{bm-cF_KdQ*4sAY8V6{$CUbe%%IP_HXr(q`#ADyZzAiy z!nj|Q{uJg-N8Gjn)8L{jjF}%W^-}}J>lsB6?8yZ%V7%^+MpWL6Es2Y!>Mh`+iE@KL z4;cFr^j2_T?M|QE;A;@veb4z0hiR^|IM$Yk92aX#Aw(00f2y~Iq9Cm0KXT@$^VglH z3o47-%AzIp@YNZyjK+|IAGl-RiL;u|Bvx!CZ93SOn3;n=c9M0Nsy0!7vck3Z|cVNyt4< z7gQDROW)RdB&ysrMaSh8USSH2(ZuVGBfV=3YX#%ZGzw$R(|1)C|0RuF0a74MLlhm! zNG^YoO4KjP=D&U>&`Wcxd(DYd!6Au|D-uukNNy66g5(*Ao>N&oQ*x0w3CE5g;W#(( zhzG{;af>3#Q);;kRmJ=tRbPHY*`x}5M5$2`%gvYnNA+Aj+K?l5Dc8pGAionamZ1e^ zmsn8*^6L?h&qrcbZ5;vVKpSsX`WB zFEvF!2HQ#1qTku%!%J=b78}MI7M@h6#-8^3^e5gDYzKfwac$)?ct9=~D3>Wuto)g8 zW6keGV=<}Uib;MOlNu_- zcZG>hJA*H8dsi@oDBhfHh(cb4IPvMiK89%)_@K~7G0j3|P|)u)f`$4$*Rdk|q09tQ zoEcxdTNr<4j7rs1Wc*KHYSyzthL<|ul<|PqohG*f|FN_@yGN?XmZbZ#KbIH+D)q?c zQY!gc_n`x;O3^+rtSx~XFIa*qo>jH0l!Fe^4mOC^d~~U*JlFwNs&qgqj$=WHV}Wu| z1XD0UZwbbicToQk&$VHELXc~ZD~%|#Ri8}3d#%RO*q$@H!%!Mgrj9(NOA%xGR@sPC zx%E2NU?~}v%H?hwehqKi8MR?v{^Fv3FY~_IFmGmA-omr0uYkF+C55^1Kg;&fyFIF6 z)25ZG$|U`NhDPyEPVQl$YjEkscRJFXOZkukj+s8$tnez zi`vVYgv3y`tkJeIMC$yiH8agQTrdl(iAcno=57UKpmW$)!=HaTw)4QRQAOs?eG$74|jcQrommU3;1GA)9ofvvex*Ei^fZh9oG z^_#S`o_E5?J?n^33MuEXFI!Y5H?FK)1~7MI$r=ULWoou-LXn|t!Wu<6s3Nt3J8@Jx zfOvmysGuAy;o9gBddWPm@kCMND9D|WB9RGOsCe;=Y4Goz;u(|SV`kwB4;^lpStPFT zcuVZm!}GZ^n(P(pgt&9m4H#V~7|t6?>%^Z44IL1JlQiNe zen4ecD$22AlpSnltEPlI5L?7RIsw4Brq zD(_iA4W$y4tB!)Gq_!nF;D&E4OUkbh@&g?)cb#S+!^)aLa4gW<+Mt;TI7)N``-K{7 zzms4;JgW7I<^A4=%+||k4w6nY{oPfX@{s1!z^?&JfmS)}P*^*-0!P zrdg<`xkrCbVbFXWrE^oXFa5?FFbm_ev}69?3g!?@9n*mx@^D6@&JW98l4Ae!MD}(n zFSUcpM?XNL0CgBxKuM`ujxAjfWCKqZ%klr_)?k$=sV^cRuK1P zO&4mFC2Kx{$O>=xc*4)tlrzIFd$v3&!E8+<0ir2=!$*n*(n4svS;x7*GJJ0S%pi`1 zj_WlqELZutC_`MXX3RaUvaaQ7>fF;R=UT3gnR{9_yOyh#xu;c&Yq@Hkds-diTCQ?) zPphe}Q%f+wH5+Z5deu+6l9U-{@cIx41rA4P_zKoJ;q2Ka^7Ro@${U-2MYrRhfT98N+4iqGc3aXP&78|08P2B(PdR0OS`IL9nc(vIf}P&Z79K;J;*z_ z4&;<-S0^sy(fgvJuolRB)0 zr3?>bU6Zg~{AkD;v#_8ITX2tP5cdjc!O*%!VXWSQ6W5=Gcq=BqS%`8>z zON>F2gAHMwKi7EwS4Ajy1^XAeJ!q|_NYH_0-#!MiDmOj)#O&Nhr&n%z^g*$5)9SUA zk3aI*v?^Gz`jIvKy_K8SgLXA`&HzB!3k3iuhcSFBoXYB05rA?hj2B1lD@MYHYHA*P zq^5H9noSQrT3NjT3cX%oQ}u?2zwd?WO&h0IZ`%0a;~Uo0de>Avwq|wp=1tS8VD5&R z4V90sxeKtopHBde9toL|&`1G1H32vi#6pe&czgnI@gwnZR4iY@$h~EB653L}-(kE~hEKUTw6ZCX?L*c$#Zan1k9y5@=Msx^1=+25*Z z+2d7JYc_9Q`}iY|JjHJssTK?Rj_e~f1JD(~(iOnb6=0?-z=HJW$S;Ggh&X_&&H?UV z4sa8u0O!vEu02P`yoJ{tzzsQp({g}|-IFnO6C`sy?F5Y~O^)?3|hBo?~2#6nmw5{_{<@5Nu>?q|mQw&b&?>+jAj z%ILjxd)nQ1?r>fD=~MIXdS~0YU$&lkac(D)NOzPt2G$W7f3%he5lFb7Cq?U%lpu>5o13)G}A>68jFcSe*c4 zR{%F*MXdkvH*w_pR<6RL#o4PtyBdA~xaki7_tk^INvnYScm;5$RsdJC0=T*rz-?Ut zoM{bkD_6$KYI`UaemxStxjJ_L{0iWN#~)b_i>s?@3adBW3TNl%aG3jn_W0PN4x0AR#^r2ufQSJ0pr z+`%MFNoaC z0>B?MfdTJ7;J}EXB@s*(h{+f5e$Qx#vjBK5kArv%;P{0E3&4Tw$zZksocL2NjIsc9 zKRgQ(F@4-TNU{J-|KvZIO~C0 zz1xr;r@_<$z_m=iGp@yaP1}NNV+`X^(_AkB$3blU#b + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ +#ifndef __NUTTX_CONFIG_MICOAIR743_LITE_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_MICOAIR743_LITE_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include "board_dma_map.h" + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdmmc.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The MicoAir743-Lite board provides the following clock sources: + * + * X1: 8 MHz crystal for HSE + * + * So we have these clock source available within the STM32 + * + * HSI: 64 MHz RC factory-trimmed + * HSE: 8 MHz crystal for HSE + */ + +#define STM32_BOARD_XTAL 8000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE = 8,000,000 + * + * PLL_VCOx = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * Subject to: + * + * 1 <= PLLM <= 63 + * 4 <= PLLN <= 512 + * 150 MHz <= PLL_VCOL <= 420MHz + * 192 MHz <= PLL_VCOH <= 836MHz + * + * SYSCLK = PLL_VCO / PLLP + * CPUCLK = SYSCLK / D1CPRE + * Subject to + * + * PLLP1 = {2, 4, 6, 8, ..., 128} + * PLLP2,3 = {2, 3, 4, ..., 128} + * CPUCLK <= 480 MHz + */ + +#define STM32_BOARD_USEHSE + +#define STM32_PLLCFG_PLLSRC RCC_PLLCKSELR_PLLSRC_HSE + +/* PLL1, wide 4 - 8 MHz input, enable DIVP, DIVQ, DIVR + * + * PLL1_VCO = (8,000,000 / 1) * 120 = 960 MHz + * + * PLL1P = PLL1_VCO/2 = 960 MHz / 2 = 480 MHz + * PLL1Q = PLL1_VCO/4 = 960 MHz / 4 = 240 MHz + * PLL1R = PLL1_VCO/8 = 960 MHz / 8 = 120 MHz + */ + +#define STM32_PLLCFG_PLL1CFG (RCC_PLLCFGR_PLL1VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL1RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP1EN | \ + RCC_PLLCFGR_DIVQ1EN | \ + RCC_PLLCFGR_DIVR1EN) +#define STM32_PLLCFG_PLL1M RCC_PLLCKSELR_DIVM1(1) +#define STM32_PLLCFG_PLL1N RCC_PLL1DIVR_N1(120) +#define STM32_PLLCFG_PLL1P RCC_PLL1DIVR_P1(2) +#define STM32_PLLCFG_PLL1Q RCC_PLL1DIVR_Q1(4) +#define STM32_PLLCFG_PLL1R RCC_PLL1DIVR_R1(8) + +#define STM32_VCO1_FREQUENCY ((STM32_HSE_FREQUENCY / 1) * 120) +#define STM32_PLL1P_FREQUENCY (STM32_VCO1_FREQUENCY / 2) +#define STM32_PLL1Q_FREQUENCY (STM32_VCO1_FREQUENCY / 4) +#define STM32_PLL1R_FREQUENCY (STM32_VCO1_FREQUENCY / 8) + +/* PLL2 */ + +#define STM32_PLLCFG_PLL2CFG (RCC_PLLCFGR_PLL2VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL2RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVP2EN | \ + RCC_PLLCFGR_DIVQ2EN | \ + RCC_PLLCFGR_DIVR2EN) +#define STM32_PLLCFG_PLL2M RCC_PLLCKSELR_DIVM2(2) +#define STM32_PLLCFG_PLL2N RCC_PLL2DIVR_N2(48) +#define STM32_PLLCFG_PLL2P RCC_PLL2DIVR_P2(2) +#define STM32_PLLCFG_PLL2Q RCC_PLL2DIVR_Q2(2) +#define STM32_PLLCFG_PLL2R RCC_PLL2DIVR_R2(2) + +#define STM32_VCO2_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 48) +#define STM32_PLL2P_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2Q_FREQUENCY (STM32_VCO2_FREQUENCY / 2) +#define STM32_PLL2R_FREQUENCY (STM32_VCO2_FREQUENCY / 2) + +/* PLL3 */ + +#define STM32_PLLCFG_PLL3CFG (RCC_PLLCFGR_PLL3VCOSEL_WIDE | \ + RCC_PLLCFGR_PLL3RGE_4_8_MHZ | \ + RCC_PLLCFGR_DIVQ3EN) +#define STM32_PLLCFG_PLL3M RCC_PLLCKSELR_DIVM3(2) +#define STM32_PLLCFG_PLL3N RCC_PLL3DIVR_N3(48) +#define STM32_PLLCFG_PLL3P RCC_PLL3DIVR_P3(2) +#define STM32_PLLCFG_PLL3Q RCC_PLL3DIVR_Q3(4) +#define STM32_PLLCFG_PLL3R RCC_PLL3DIVR_R3(2) + +#define STM32_VCO3_FREQUENCY ((STM32_HSE_FREQUENCY / 2) * 48) +#define STM32_PLL3P_FREQUENCY (STM32_VCO3_FREQUENCY / 2) +#define STM32_PLL3Q_FREQUENCY (STM32_VCO3_FREQUENCY / 4) +#define STM32_PLL3R_FREQUENCY (STM32_VCO3_FREQUENCY / 2) + +/* SYSCLK = PLL1P = 480MHz + * CPUCLK = SYSCLK / 1 = 480 MHz + */ + +#define STM32_RCC_D1CFGR_D1CPRE (RCC_D1CFGR_D1CPRE_SYSCLK) +#define STM32_SYSCLK_FREQUENCY (STM32_PLL1P_FREQUENCY) +#define STM32_CPUCLK_FREQUENCY (STM32_SYSCLK_FREQUENCY / 1) + +/* Configure Clock Assignments */ + +/* AHB clock (HCLK) is SYSCLK/2 (240 MHz max) + * HCLK1 = HCLK2 = HCLK3 = HCLK4 = 240 + */ + +#define STM32_RCC_D1CFGR_HPRE RCC_D1CFGR_HPRE_SYSCLKd2 /* HCLK = SYSCLK / 2 */ +#define STM32_ACLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* ACLK in D1, HCLK3 in D1 */ +#define STM32_HCLK_FREQUENCY (STM32_CPUCLK_FREQUENCY / 2) /* HCLK in D2, HCLK4 in D3 */ +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE1 RCC_D2CFGR_D2PPRE1_HCLKd2 /* PCLK1 = HCLK / 2 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB2 clock (PCLK2) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D2CFGR_D2PPRE2 RCC_D2CFGR_D2PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB3 clock (PCLK3) is HCLK/2 (120 MHz) */ + +#define STM32_RCC_D1CFGR_D1PPRE RCC_D1CFGR_D1PPRE_HCLKd2 /* PCLK3 = HCLK / 2 */ +#define STM32_PCLK3_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* APB4 clock (PCLK4) is HCLK/4 (120 MHz) */ + +#define STM32_RCC_D3CFGR_D3PPRE RCC_D3CFGR_D3PPRE_HCLKd2 /* PCLK4 = HCLK / 2 */ +#define STM32_PCLK4_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timer clock frequencies */ + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM15_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM16_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM17_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Kernel Clock Configuration + * + * Note: look at Table 54 in ST Manual + */ + +/* I2C123 clock source */ + +#define STM32_RCC_D2CCIP2R_I2C123SRC RCC_D2CCIP2R_I2C123SEL_HSI + +/* I2C4 clock source */ + +#define STM32_RCC_D3CCIPR_I2C4SRC RCC_D3CCIPR_I2C4SEL_HSI + +/* SPI123 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI123SRC RCC_D2CCIP1R_SPI123SEL_PLL2 + +/* SPI45 clock source */ + +#define STM32_RCC_D2CCIP1R_SPI45SRC RCC_D2CCIP1R_SPI45SEL_PLL2 + +/* SPI6 clock source */ + +#define STM32_RCC_D3CCIPR_SPI6SRC RCC_D3CCIPR_SPI6SEL_PLL2 + +/* USB 1 and 2 clock source */ + +#define STM32_RCC_D2CCIP2R_USBSRC RCC_D2CCIP2R_USBSEL_PLL3 + +/* ADC 1 2 3 clock source */ + +#define STM32_RCC_D3CCIPR_ADCSEL RCC_D3CCIPR_ADCSEL_PLL2 + +/* FDCAN 1 clock source */ + +#define STM32_RCC_D2CCIP1R_FDCANSEL RCC_D2CCIP1R_FDCANSEL_HSE /* FDCAN 1 2 clock source */ + +#define STM32_FDCANCLK STM32_HSE_FREQUENCY + +/* FLASH wait states + * + * ------------ ---------- ----------- + * Vcore MAX ACLK WAIT STATES + * ------------ ---------- ----------- + * 1.15-1.26 V 70 MHz 0 + * (VOS1 level) 140 MHz 1 + * 210 MHz 2 + * 1.05-1.15 V 55 MHz 0 + * (VOS2 level) 110 MHz 1 + * 165 MHz 2 + * 220 MHz 3 + * 0.95-1.05 V 45 MHz 0 + * (VOS3 level) 90 MHz 1 + * 135 MHz 2 + * 180 MHz 3 + * 225 MHz 4 + * ------------ ---------- ----------- + */ + +#define BOARD_FLASH_WAITSTATES 2 + +/* SDMMC definitions ********************************************************/ + +/* Init 480kHz, freq = PLL1Q/(2*div) div = PLL1Q/(2*freq) */ + +#define STM32_SDMMC_INIT_CLKDIV (300 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) + +/* 20 MHz Max for now - more reliable on some boards than 25 MHz + * 20 MHz = PLL1Q/(2*div), div = PLL1Q/(2*freq), div = 6 = 240 / 40 + */ + +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_MMCXFR_CLKDIV (6 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_MMCXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif +#if defined(CONFIG_STM32H7_SDMMC_XDMA) || defined(CONFIG_STM32H7_SDMMC_IDMA) +# define STM32_SDMMC_SDXFR_CLKDIV (6 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#else +# define STM32_SDMMC_SDXFR_CLKDIV (100 << STM32_SDMMC_CLKCR_CLKDIV_SHIFT) +#endif + +#define STM32_SDMMC_CLKCR_EDGE STM32_SDMMC_CLKCR_NEGEDGE + +/* LED definitions ******************************************************************/ +/* The board has two, LED_GREEN a Green LED and LED_BLUE a Blue LED, + * that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_GREEN BOARD_LED2 +#define BOARD_LED_BLUE BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* Alternate function pin selections ************************************************/ + +#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PA10 */ +#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PA9 */ + +#define GPIO_USART2_RX GPIO_USART2_RX_1 /* PA3 */ +#define GPIO_USART2_TX GPIO_USART2_TX_1 /* PA2 */ + +#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */ +#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */ + +#define GPIO_UART4_RX GPIO_UART4_RX_2 /* PA1 */ +#define GPIO_UART4_TX GPIO_UART4_TX_2 /* PA0 */ + +#define GPIO_UART5_RX GPIO_UART5_RX_2 /* PB5 */ +#define GPIO_UART5_TX GPIO_UART5_TX_2 /* PB6 */ + +#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */ +#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */ + +#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */ +#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */ + +#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */ +#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */ + + +/* SPI + * + + */ + +#define ADJ_SLEW_RATE(p) (((p) & ~GPIO_SPEED_MASK) | (GPIO_SPEED_2MHz)) + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_1 /* PB4 */ +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_1 /* PD6 */ +#define GPIO_SPI3_SCK ADJ_SLEW_RATE(GPIO_SPI3_SCK_1) /* PB3 */ + +/* I2C + * + + * + */ + +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 /* PB8 */ +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 /* PB9 */ + +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN9) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 /* PB10 */ +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 /* PB11 */ + +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN10) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT | GPIO_OPENDRAIN | GPIO_SPEED_50MHz | GPIO_OUTPUT_SET | GPIO_PORTB | GPIO_PIN11) + +# define PROBE_INIT(mask) +# define PROBE(n,s) +# define PROBE_MARK(n) + +#endif /*__NUTTX_CONFIG_MICOAIR743_LITE_INCLUDE_BOARD_H */ diff --git a/boards/micoair/h743-lite/nuttx-config/include/board_dma_map.h b/boards/micoair/h743-lite/nuttx-config/include/board_dma_map.h new file mode 100644 index 0000000000..fd6a97722a --- /dev/null +++ b/boards/micoair/h743-lite/nuttx-config/include/board_dma_map.h @@ -0,0 +1,36 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once +#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_0 +#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_0 diff --git a/boards/micoair/h743-lite/nuttx-config/nsh/defconfig b/boards/micoair/h743-lite/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..c5f981cbd4 --- /dev/null +++ b/boards/micoair/h743-lite/nuttx-config/nsh/defconfig @@ -0,0 +1,244 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_DEV_CONSOLE is not set +# CONFIG_DISABLE_ENVIRON is not set +# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_MMCSD_HAVE_CARDDETECT is not set +# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_SPI is not set +# CONFIG_NSH_DISABLEBG is not set +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DATE is not set +# CONFIG_NSH_DISABLE_DF is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_ENV is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_EXPORT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_ITEF is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOOPS is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MV is not set +# CONFIG_NSH_DISABLE_PRINTF is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SEMICOLON is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_SOURCE is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_TIME is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/micoair/h743-lite/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="stm32h7" +CONFIG_ARCH_CHIP_STM32H743VI=y +CONFIG_ARCH_CHIP_STM32H7=y +CONFIG_ARCH_INTERRUPTSTACK=768 +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_BASEPRI_WAR=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_CRASHDUMP=y +CONFIG_BOARD_LOOPSPERMSEC=95150 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_IFLOWCONTROL=y +CONFIG_CDCACM_PRODUCTID=0x0036 +CONFIG_CDCACM_PRODUCTSTR="MicoAir743-Lite" +CONFIG_CDCACM_RXBUFSIZE=6000 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x1B8C +CONFIG_CDCACM_VENDORSTR="MicoAir" +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEFAULT_SMALL=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_MAXSIZE=1024 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_EXPERIMENTAL=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=750 +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=3194 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_NCHAINS=24 +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIBC_LONG_LONG=y +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y +CONFIG_MM_IOB=y +CONFIG_MM_REGIONS=4 +CONFIG_NAME_MAX=40 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_ARGCAT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CMDPARMS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_QUOTE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_VARS=y +CONFIG_OTG_ID_GPIO_DISABLE=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_ROBUST=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=245760 +CONFIG_RAM_START=0x20010000 +CONFIG_RAW_BINARY=y +CONFIG_RTC_DATETIME=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1280 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=1632 +CONFIG_SCHED_WAITPID=y +CONFIG_SDMMC1_SDIO_PULLUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STM32H7_ADC1=y +CONFIG_STM32H7_ADC3=y +CONFIG_STM32H7_BBSRAM=y +CONFIG_STM32H7_BBSRAM_FILES=5 +CONFIG_STM32H7_BDMA=y +CONFIG_STM32H7_BKPSRAM=y +CONFIG_STM32H7_DMA1=y +CONFIG_STM32H7_DMA2=y +CONFIG_STM32H7_DMACAPABLE=y +CONFIG_STM32H7_FLASH_OVERRIDE_I=y +CONFIG_STM32H7_I2C1=y +CONFIG_STM32H7_I2C2=y +CONFIG_STM32H7_I2C_DYNTIMEO=y +CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10 +CONFIG_STM32H7_OTGFS=y +CONFIG_STM32H7_PROGMEM=y +CONFIG_STM32H7_RTC=y +CONFIG_STM32H7_RTC_HSECLOCK=y +CONFIG_STM32H7_RTC_MAGIC_REG=1 +CONFIG_STM32H7_SAVE_CRASHDUMP=y +CONFIG_STM32H7_SDMMC1=y +CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y +CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y +CONFIG_STM32H7_SPI3=y +CONFIG_STM32H7_SPI3_DMA=y +CONFIG_STM32H7_SPI3_DMA_BUFFER=2048 +CONFIG_STM32H7_SPI_DMATHRESHOLD=8 +CONFIG_STM32H7_TIM15=y +CONFIG_STM32H7_TIM12=y +CONFIG_STM32H7_TIM1=y +CONFIG_STM32H7_TIM3=y +CONFIG_STM32H7_TIM4=y +CONFIG_STM32H7_TIM8=y +CONFIG_STM32H7_UART4=y +CONFIG_STM32H7_UART5=y +CONFIG_STM32H7_UART7=y +CONFIG_STM32H7_UART8=y +CONFIG_STM32H7_USART1=y +CONFIG_STM32H7_USART2=y +CONFIG_STM32H7_USART3=y +CONFIG_STM32H7_USART6=y +CONFIG_STM32H7_USART_BREAKS=y +CONFIG_STM32H7_USART_INVERT=y +CONFIG_STM32H7_USART_SINGLEWIRE=y +CONFIG_STM32H7_USART_SWAP=y +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_NSH=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_UART4_RXBUFSIZE=600 +CONFIG_UART4_TXBUFSIZE=800 +CONFIG_UART5_RXBUFSIZE=600 +CONFIG_UART5_TXBUFSIZE=800 +CONFIG_UART7_RXBUFSIZE=600 +CONFIG_UART7_TXBUFSIZE=800 +CONFIG_UART8_RXBUFSIZE=600 +CONFIG_UART8_TXBUFSIZE=800 +CONFIG_USART1_RXBUFSIZE=1200 +CONFIG_USART1_TXBUFSIZE=1500 +CONFIG_USART2_RXBUFSIZE=600 +CONFIG_USART2_TXBUFSIZE=800 +CONFIG_USART3_RXBUFSIZE=600 +CONFIG_USART3_TXBUFSIZE=800 +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_RXBUFSIZE=600 +CONFIG_USART6_TXBUFSIZE=800 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_WATCHDOG=y diff --git a/boards/micoair/h743-lite/nuttx-config/scripts/bootloader_script.ld b/boards/micoair/h743-lite/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 0000000000..fb877cc443 --- /dev/null +++ b/boards/micoair/h743-lite/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,213 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2016, 2019 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The Durandal-v1 uses an STM32H743II has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * The Durandal has a Switch on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the swiutch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + flash (rx) : ORIGIN = 0x08000000, LENGTH = 2048K + dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K + sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K + sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K + sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K + sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K + bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/micoair/h743-lite/nuttx-config/scripts/script.ld b/boards/micoair/h743-lite/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..85f4990724 --- /dev/null +++ b/boards/micoair/h743-lite/nuttx-config/scripts/script.ld @@ -0,0 +1,228 @@ +/**************************************************************************** + * scripts/script.ld + * + * Copyright (C) 2020 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* The board uses an STM32H743II and has 2048Kb of main FLASH memory. + * The flash memory is partitioned into a User Flash memory and a System + * Flash memory. Each of these memories has two banks: + * + * 1) User Flash memory: + * + * Bank 1: Start address 0x0800:0000 to 0x080F:FFFF with 8 sectors, 128Kb each + * Bank 2: Start address 0x0810:0000 to 0x081F:FFFF with 8 sectors, 128Kb each + * + * 2) System Flash memory: + * + * Bank 1: Start address 0x1FF0:0000 to 0x1FF1:FFFF with 1 x 128Kb sector + * Bank 1: Start address 0x1FF4:0000 to 0x1FF5:FFFF with 1 x 128Kb sector + * + * 3) User option bytes for user configuration, only in Bank 1. + * + * In the STM32H743II, two different boot spaces can be selected through + * the BOOT pin and the boot base address programmed in the BOOT_ADD0 and + * BOOT_ADD1 option bytes: + * + * 1) BOOT=0: Boot address defined by user option byte BOOT_ADD0[15:0]. + * ST programmed value: Flash memory at 0x0800:0000 + * 2) BOOT=1: Boot address defined by user option byte BOOT_ADD1[15:0]. + * ST programmed value: System bootloader at 0x1FF0:0000 + * + * There's a switch on board, the BOOT0 pin is at ground so by default, + * the STM32 will boot to address 0x0800:0000 in FLASH unless the switch is + * drepresed, then the boot will be from 0x1FF0:0000 + * + * The STM32H743ZI also has 1024Kb of data SRAM. + * SRAM is split up into several blocks and into three power domains: + * + * 1) TCM SRAMs are dedicated to the Cortex-M7 and are accessible with + * 0 wait states by the Cortex-M7 and by MDMA through AHBS slave bus + * + * 1.1) 128Kb of DTCM-RAM beginning at address 0x2000:0000 + * + * The DTCM-RAM is organized as 2 x 64Kb DTCM-RAMs on 2 x 32 bit + * DTCM ports. The DTCM-RAM could be used for critical real-time + * data, such as interrupt service routines or stack / heap memory. + * Both DTCM-RAMs can be used in parallel (for load/store operations) + * thanks to the Cortex-M7 dual issue capability. + * + * 1.2) 64Kb of ITCM-RAM beginning at address 0x0000:0000 + * + * This RAM is connected to ITCM 64-bit interface designed for + * execution of critical real-times routines by the CPU. + * + * 2) AXI SRAM (D1 domain) accessible by all system masters except BDMA + * through D1 domain AXI bus matrix + * + * 2.1) 512Kb of SRAM beginning at address 0x2400:0000 + * + * 3) AHB SRAM (D2 domain) accessible by all system masters except BDMA + * through D2 domain AHB bus matrix + * + * 3.1) 128Kb of SRAM1 beginning at address 0x3000:0000 + * 3.2) 128Kb of SRAM2 beginning at address 0x3002:0000 + * 3.3) 32Kb of SRAM3 beginning at address 0x3004:0000 + * + * SRAM1 - SRAM3 are one contiguous block: 288Kb at address 0x3000:0000 + * + * 4) AHB SRAM (D3 domain) accessible by most of system masters + * through D3 domain AHB bus matrix + * + * 4.1) 64Kb of SRAM4 beginning at address 0x3800:0000 + * 4.1) 4Kb of backup RAM beginning at address 0x3880:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + */ + +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1920K + + DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K + AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */ + SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */ + SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */ + SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */ + BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +ENTRY(_stext) + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) +EXTERN(_bootdelay_signature) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + } > FLASH + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > FLASH + + + .ARM.extab : { + *(.ARM.extab*) + } > FLASH + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > FLASH + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + + /* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */ + . = ALIGN(16); + FILL(0xffff) + . += 16; + } > AXI_SRAM AT > FLASH = 0xffff + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > AXI_SRAM + + /* Emit the the D3 power domain section for locating BDMA data */ + + .sram4_reserve (NOLOAD) : + { + *(.sram4) + . = ALIGN(4); + _sram4_heap_start = ABSOLUTE(.); + } > SRAM4 + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/boards/micoair/h743-lite/src/CMakeLists.txt b/boards/micoair/h743-lite/src/CMakeLists.txt new file mode 100644 index 0000000000..c47215375d --- /dev/null +++ b/boards/micoair/h743-lite/src/CMakeLists.txt @@ -0,0 +1,68 @@ +############################################################################ +# +# Copyright (c) 2021 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_library(drivers_board + bootloader_main.c + usb.c + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch + nuttx_drivers + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + add_library(drivers_board + i2c.cpp + init.c + led.c + sdio.c + spi.cpp + timer_config.cpp + usb.c + ) + add_dependencies(drivers_board arch_board_hw_info) + + target_link_libraries(drivers_board + PRIVATE + arch_io_pins + arch_spi + arch_board_hw_info + drivers__led + nuttx_arch + nuttx_drivers + px4_layer + ) +endif() diff --git a/boards/micoair/h743-lite/src/board_config.h b/boards/micoair/h743-lite/src/board_config.h new file mode 100644 index 0000000000..2eef26d59b --- /dev/null +++ b/boards/micoair/h743-lite/src/board_config.h @@ -0,0 +1,199 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * Board internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include + +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + + + +/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */ + +# define GPIO_nLED_RED /* PE3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3) +# define GPIO_nLED_GREEN /* PE2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2) +# define GPIO_nLED_BLUE /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) + +# define BOARD_HAS_CONTROL_STATUS_LEDS 1 +# define BOARD_OVERLOAD_LED LED_RED +# define BOARD_ARMED_STATE_LED LED_BLUE + + +/* + * ADC channels + * + * These are the channel numbers of the ADCs of the microcontroller that + * can be used by the Px4 Firmware in the adc driver + */ + +/* ADC defines to be used in sensors.cpp to read from a particular channel */ +#define SYSTEM_ADC_BASE STM32_ADC1_BASE +#define ADC1_CH(n) (n) + +/* Define GPIO pins used as ADC N.B. Channel numbers must match below */ +#define PX4_ADC_GPIO \ + /* PC0 */ GPIO_ADC123_INP10, \ + /* PC1 */ GPIO_ADC123_INP11 + + +/* Define Channel numbers must match above GPIO pin IN(n)*/ +#define ADC_BATTERY_VOLTAGE_CHANNEL /* PC0 */ ADC1_CH(10) +#define ADC_BATTERY_CURRENT_CHANNEL /* PC1 */ ADC1_CH(11) + + +#define ADC_CHANNELS \ + ((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \ + (1 << ADC_BATTERY_CURRENT_CHANNEL)) + + +/* Define Battery 1 Voltage Divider and A per V + */ + +// #define BOARD_BATTERY1_V_DIV (11.0f) /* measured with the provided PM board */ +// #define BOARD_BATTERY1_A_PER_V (40.0f) +// #define BOARD_BATTERY2_V_DIV (11.0f) /* measured with the provided PM board */ + + +/* PWM + */ +#define DIRECT_PWM_OUTPUT_CHANNELS 14 +#define DIRECT_INPUT_TIMER_CHANNELS 14 + +#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS + +#define GPIO_TONE_ALARM_IDLE /* PD15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN15) +#define GPIO_TONE_ALARM_GPIO /* PD15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN15) + +/* USB OTG FS + * + * PA8 OTG_FS_VBUS VBUS sensing + */ + +#define GPIO_OTGFS_VBUS /* PA8 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTA|GPIO_PIN8) + + +/* High-resolution timer */ +#define HRT_TIMER 8 /* use timer8 for the HRT */ +#define HRT_TIMER_CHANNEL 3 /* use capture/compare channel 3 */ + + +/* RC Serial port */ +#define RC_SERIAL_PORT "/dev/ttyS5" +#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT + +//#define GPIO_I2C2_DRDY1_SPA06 /* PD0 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN0) + + +/* SD Card */ +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ +#define BOARD_HAS_ON_RESET 1 + +#define PX4_GPIO_INIT_LIST { \ + PX4_ADC_GPIO, \ + GPIO_TONE_ALARM_IDLE, \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + + +#define BOARD_NUM_IO_TIMERS 6 + + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void); + +/**************************************************************************************************** + * Name: stm32_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the board. + * + ****************************************************************************************************/ + +extern void stm32_spiinitialize(void); + +extern void stm32_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +#include + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/micoair/h743-lite/src/bootloader_main.c b/boards/micoair/h743-lite/src/bootloader_main.c new file mode 100644 index 0000000000..5670308a29 --- /dev/null +++ b/boards/micoair/h743-lite/src/bootloader_main.c @@ -0,0 +1,75 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file bootloader_main.c + * + * FMU-specific early startup code for bootloader +*/ + +#include "board_config.h" +#include "bl.h" + +#include +#include +#include +#include +#include +#include "arm_internal.h" +#include + +extern int sercon_main(int c, char **argv); + +__EXPORT void board_on_reset(int status) {} + +__EXPORT void stm32_boardinitialize(void) +{ + /* configure USB interfaces */ + stm32_usbinitialize(); +} + +__EXPORT int board_app_initialize(uintptr_t arg) +{ + return 0; +} + +void board_late_initialize(void) +{ + sercon_main(0, NULL); +} + +extern void sys_tick_handler(void); +void board_timerhook(void) +{ + sys_tick_handler(); +} diff --git a/boards/micoair/h743-lite/src/hw_config.h b/boards/micoair/h743-lite/src/hw_config.h new file mode 100644 index 0000000000..ac210d78d4 --- /dev/null +++ b/boards/micoair/h743-lite/src/hw_config.h @@ -0,0 +1,135 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x08020000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" +#define BOARD_VBUS MK_GPIO_INPUT(GPIO_OTGFS_VBUS) + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS0,115200" +#define BOOT_DELAY_ADDRESS 0x000001a0 +#define BOARD_TYPE 1202 +#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) +#define BOARD_FLASH_SECTORS (15) +#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) + +#define OSC_FREQ 8 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif diff --git a/boards/micoair/h743-lite/src/i2c.cpp b/boards/micoair/h743-lite/src/i2c.cpp new file mode 100644 index 0000000000..bea7532cc3 --- /dev/null +++ b/boards/micoair/h743-lite/src/i2c.cpp @@ -0,0 +1,39 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusExternal(2), +}; diff --git a/boards/micoair/h743-lite/src/init.c b/boards/micoair/h743-lite/src/init.c new file mode 100644 index 0000000000..c0e1f9776c --- /dev/null +++ b/boards/micoair/h743-lite/src/init.c @@ -0,0 +1,208 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * FMU-specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialisation. + */ + +#include "board_config.h" + +#include + +#include +#include +#include +#include +#include +#include "arm_internal.h" + +#include +#include +#include +#include +#include +#include +#include + +# if defined(FLASH_BASED_PARAMS) +# include +#endif + +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + UNUSED(ms); +} + +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_as_pwm_input(i))); + } + + /* + * On resets invoked from system (not boot) ensure we establish a low + * output state on PWM pins to disarm the ESC and prevent the reset from potentially + * spinning up the motors. + */ + if (status >= 0) { + up_mdelay(100); + } +} + +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the initialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ +__EXPORT void stm32_boardinitialize(void) +{ + /* Reset PWM first thing */ + board_on_reset(-1); + + /* configure LEDs */ + board_autoled_initialize(); + + /* configure pins */ + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + /* configure SPI interfaces */ + stm32_spiinitialize(); + + /* configure USB interfaces */ + stm32_usbinitialize(); + +} + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ +__EXPORT int board_app_initialize(uintptr_t arg) +{ + /* Need hrt running before using the ADC */ + px4_platform_init(); + + /* configure the DMA allocator */ + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + + /* initial LED state */ + drv_led_start(); + led_off(LED_RED); + led_off(LED_BLUE); + + if (board_hardfault_init(2, true) != 0) { + led_on(LED_BLUE); + } + +#ifdef CONFIG_MMCSD + int ret = stm32_sdio_initialize(); + + if (ret != OK) { + led_on(LED_BLUE); + return ret; + } + +#endif + +// TODO:internal flash store parameters +#if defined(FLASH_BASED_PARAMS) + static sector_descriptor_t params_sector_map[] = { + {15, 128 * 1024, 0x081E0000}, + {0, 0, 0}, + }; + + /* Initialize the flashfs layer to use heap allocated memory */ + int result = parameter_flashfs_init(params_sector_map, NULL, 0); + + if (result != OK) { + syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result); + led_on(LED_RED); + } + +#endif + + /* Configure the HW based on the manifest */ + px4_platform_configure(); + + return OK; +} diff --git a/boards/micoair/h743-lite/src/led.c b/boards/micoair/h743-lite/src/led.c new file mode 100644 index 0000000000..d7794392db --- /dev/null +++ b/boards/micoair/h743-lite/src/led.c @@ -0,0 +1,114 @@ +/**************************************************************************** + * + * Copyright (c) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file led.c + * + * LED backend. + */ + +#include + +#include + +#include "chip.h" +#include "stm32_gpio.h" +#include "board_config.h" + +#include +#include + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); +extern void led_toggle(int led); +__END_DECLS + +# define xlat(p) (p) +static uint32_t g_ledmap[] = { + GPIO_nLED_GREEN, // Indexed by BOARD_LED_GREEN + GPIO_nLED_BLUE, // Indexed by BOARD_LED_BLUE + GPIO_nLED_RED, // Indexed by BOARD_LED_RED +}; + +__EXPORT void led_init(void) +{ + /* Configure LED GPIOs for output */ + for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) { + if (g_ledmap[l] != 0) { + stm32_configgpio(g_ledmap[l]); + } + } +} + +static void phy_set_led(int led, bool state) +{ + /* Drive Low to switch on */ + if (g_ledmap[led] != 0) { + stm32_gpiowrite(g_ledmap[led], !state); + } +} + +static bool phy_get_led(int led) +{ + /* If Low it is on */ + if (g_ledmap[led] != 0) { + return !stm32_gpioread(g_ledmap[led]); + } + + return false; +} + + +__EXPORT void led_on(int led) +{ + phy_set_led(xlat(led), true); +} + +__EXPORT void led_off(int led) +{ + phy_set_led(xlat(led), false); +} + +__EXPORT void led_toggle(int led) +{ + phy_set_led(xlat(led), !phy_get_led(xlat(led))); +} diff --git a/boards/micoair/h743-lite/src/sdio.c b/boards/micoair/h743-lite/src/sdio.c new file mode 100644 index 0000000000..869d757756 --- /dev/null +++ b/boards/micoair/h743-lite/src/sdio.c @@ -0,0 +1,177 @@ +/**************************************************************************** + * + * Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "board_config.h" +#include "stm32_gpio.h" +#include "stm32_sdmmc.h" + +#ifdef CONFIG_MMCSD + + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Card detections requires card support and a card detection GPIO */ + +#define HAVE_NCD 1 +#if !defined(GPIO_SDMMC1_NCD) +# undef HAVE_NCD +#endif + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static FAR struct sdio_dev_s *sdio_dev; +#ifdef HAVE_NCD +static bool g_sd_inserted = 0xff; /* Impossible value */ +#endif + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_ncd_interrupt + * + * Description: + * Card detect interrupt handler. + * + ****************************************************************************/ + +#ifdef HAVE_NCD +static int stm32_ncd_interrupt(int irq, FAR void *context) +{ + bool present; + + present = !stm32_gpioread(GPIO_SDMMC1_NCD); + + if (sdio_dev && present != g_sd_inserted) { + sdio_mediachange(sdio_dev, present); + g_sd_inserted = present; + } + + return OK; +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: stm32_sdio_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int stm32_sdio_initialize(void) +{ + int ret; + +#ifdef HAVE_NCD + /* Card detect */ + + bool cd_status; + + /* Configure the card detect GPIO */ + + stm32_configgpio(GPIO_SDMMC1_NCD); + + /* Register an interrupt handler for the card detect pin */ + + stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt); +#endif + + /* Mount the SDIO-based MMC/SD block driver */ + /* First, get an instance of the SDIO interface */ + + finfo("Initializing SDIO slot %d\n", SDIO_SLOTNO); + + sdio_dev = sdio_initialize(SDIO_SLOTNO); + + if (!sdio_dev) { + syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", SDIO_SLOTNO); + return -ENODEV; + } + + /* Now bind the SDIO interface to the MMC/SD driver */ + + finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", SDIO_MINOR); + + ret = mmcsd_slotinitialize(SDIO_MINOR, sdio_dev); + + if (ret != OK) { + syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + return ret; + } + + finfo("Successfully bound SDIO to the MMC/SD driver\n"); + +#ifdef HAVE_NCD + /* Use SD card detect pin to check if a card is g_sd_inserted */ + + cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD); + finfo("Card detect : %d\n", cd_status); + + sdio_mediachange(sdio_dev, cd_status); +#else + /* Assume that the SD card is inserted. What choice do we have? */ + + sdio_mediachange(sdio_dev, true); +#endif + + return OK; +} + +#endif /* CONFIG_MMCSD */ diff --git a/boards/micoair/h743-lite/src/spi.cpp b/boards/micoair/h743-lite/src/spi.cpp new file mode 100644 index 0000000000..148534ff85 --- /dev/null +++ b/boards/micoair/h743-lite/src/spi.cpp @@ -0,0 +1,45 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + + +constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = { + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::PortD, GPIO::Pin4}, SPI::DRDY{GPIO::PortD, GPIO::Pin5}), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses); diff --git a/boards/micoair/h743-lite/src/timer_config.cpp b/boards/micoair/h743-lite/src/timer_config.cpp new file mode 100644 index 0000000000..050d3b0dc4 --- /dev/null +++ b/boards/micoair/h743-lite/src/timer_config.cpp @@ -0,0 +1,63 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOTimer(Timer::Timer1, DMA{DMA::Index1}), + initIOTimer(Timer::Timer3, DMA{DMA::Index1}), + initIOTimer(Timer::Timer4, DMA{DMA::Index1}), + initIOTimer(Timer::Timer12), + initIOTimer(Timer::Timer15), +}; + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel4}, {GPIO::PortE, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel3}, {GPIO::PortE, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel2}, {GPIO::PortE, GPIO::Pin11}), + initIOTimerChannel(io_timers, {Timer::Timer1, Timer::Channel1}, {GPIO::PortE, GPIO::Pin9}), + initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel4}, {GPIO::PortB, GPIO::Pin1}), + initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel3}, {GPIO::PortB, GPIO::Pin0}), + initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel2}, {GPIO::PortA, GPIO::Pin7}), + initIOTimerChannel(io_timers, {Timer::Timer3, Timer::Channel1}, {GPIO::PortA, GPIO::Pin6}), + initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel1}, {GPIO::PortE, GPIO::Pin5}), + initIOTimerChannel(io_timers, {Timer::Timer15, Timer::Channel2}, {GPIO::PortE, GPIO::Pin6}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel1}, {GPIO::PortD, GPIO::Pin12}), + initIOTimerChannel(io_timers, {Timer::Timer4, Timer::Channel2}, {GPIO::PortD, GPIO::Pin13}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel1}, {GPIO::PortB, GPIO::Pin14}), + initIOTimerChannel(io_timers, {Timer::Timer12, Timer::Channel2}, {GPIO::PortB, GPIO::Pin15}), + +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); diff --git a/boards/micoair/h743-lite/src/usb.c b/boards/micoair/h743-lite/src/usb.c new file mode 100644 index 0000000000..9591784866 --- /dev/null +++ b/boards/micoair/h743-lite/src/usb.c @@ -0,0 +1,78 @@ +/**************************************************************************** + * + * Copyright (C) 2021 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file usb.c + * + * Board-specific USB functions. + */ + +#include "board_config.h" +#include +#include +#include +#include + +/************************************************************************************ + * Name: stm32_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the board. + * + ************************************************************************************/ + +__EXPORT void stm32_usbinitialize(void) +{ + /* The OTG FS has an internal soft pull-up */ + + /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ + +#ifdef CONFIG_STM32H7_OTGFS + stm32_configgpio(GPIO_OTGFS_VBUS); +#endif +} + +/************************************************************************************ + * Name: stm32_usbsuspend + * + * Description: + * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ +__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} From fb13b880cef55f653f08c71920ae3a4046cc5334 Mon Sep 17 00:00:00 2001 From: Phil-Engljaehringer Date: Tue, 4 Nov 2025 17:22:10 +0100 Subject: [PATCH 254/812] sensors: add ads7953 adc * sensors: add ads7953 adc * Update src/drivers/adc/ads7953/ADS7953.h Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> * Implemented changes suggested by review * Implemented suggested changes * removed unused variables and moved scope of ch_id * Activated distance sensor again * Update msg/AdcReport.msg Co-authored-by: Hamish Willee * Update ADC report message field comments * Update ADC msg - fix layout * update comments * changed group to Sensors in module.yaml * created new module subcategory "adc" * reverted group change in module.yaml * added module descrption to modules_driver.md * removed module description in modules_driver.md (autogenerated) * removed unused variable, changed board_adc publication method to "multi" * added static assert --------- Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Co-authored-by: Hamish Willee --- ROMFS/px4fmu_common/init.d/rc.sensors | 6 ++ Tools/px4moduledoc/srcparser.py | 2 +- msg/AdcReport.msg | 16 +-- src/drivers/adc/ads7953/ADS7953.cpp | 122 +++++++++++++++++++++++ src/drivers/adc/ads7953/ADS7953.h | 43 ++++++++ src/drivers/adc/ads7953/CMakeLists.txt | 46 +++++++++ src/drivers/adc/ads7953/Kconfig | 5 + src/drivers/adc/ads7953/ads7953_main.cpp | 77 ++++++++++++++ src/drivers/adc/ads7953/module.yaml | 29 ++++++ src/drivers/adc/board_adc/ADC.hpp | 3 +- src/drivers/drv_sensor.h | 2 + 11 files changed, 343 insertions(+), 8 deletions(-) create mode 100644 src/drivers/adc/ads7953/ADS7953.cpp create mode 100644 src/drivers/adc/ads7953/ADS7953.h create mode 100644 src/drivers/adc/ads7953/CMakeLists.txt create mode 100644 src/drivers/adc/ads7953/Kconfig create mode 100644 src/drivers/adc/ads7953/ads7953_main.cpp create mode 100644 src/drivers/adc/ads7953/module.yaml diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index 759acb3b51..d558d381b1 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -219,6 +219,12 @@ then pcf8583 start -X -a 0x51 fi +# ADC sensor ADS7953 external SPI +if param compare -s ADC_ADS7953_EN 1 +then + ads7953 start -S +fi + # probe for optional external I2C devices if param compare SENS_EXT_I2C_PRB 1 then diff --git a/Tools/px4moduledoc/srcparser.py b/Tools/px4moduledoc/srcparser.py index 8b56e7bb08..749acef762 100644 --- a/Tools/px4moduledoc/srcparser.py +++ b/Tools/px4moduledoc/srcparser.py @@ -15,7 +15,7 @@ class ModuleDocumentation(object): # TOC in https://github.com/PX4/PX4-Autopilot/blob/main/docs/en/SUMMARY.md valid_categories = ['driver', 'estimator', 'controller', 'system', 'communication', 'command', 'template', 'simulation', 'autotune'] - valid_subcategories = ['', 'camera', 'distance_sensor', 'imu', 'ins', 'airspeed_sensor', + valid_subcategories = ['', 'adc', 'camera', 'distance_sensor', 'imu', 'ins', 'airspeed_sensor', 'magnetometer', 'baro', 'optical_flow', 'radio_control','rpm_sensor', 'transponder'] max_line_length = 80 # wrap lines that are longer than this diff --git a/msg/AdcReport.msg b/msg/AdcReport.msg index 1ae72b6d6c..4a56bc2875 100644 --- a/msg/AdcReport.msg +++ b/msg/AdcReport.msg @@ -1,6 +1,10 @@ -uint64 timestamp # time since system start (microseconds) -uint32 device_id # unique device ID for the sensor that does not change between power cycles -int16[12] channel_id # ADC channel IDs, negative for non-existent, TODO: should be kept same as array index -int32[12] raw_data # ADC channel raw value, accept negative value, valid if channel ID is positive -uint32 resolution # ADC channel resolution -float32 v_ref # ADC channel voltage reference, use to calculate LSB voltage(lsb=scale/resolution) +# ADC raw data. +# +# Communicates raw data from an analog-to-digital converter (ADC) to other modules, such as battery status. + +uint64 timestamp # [us] Time since system start +uint32 device_id # [-] unique device ID for the sensor that does not change between power cycles +int16[16] channel_id # [-] ADC channel IDs, negative for non-existent, TODO: should be kept same as array index +int32[16] raw_data # [-] ADC channel raw value, accept negative value, valid if channel ID is positive +uint32 resolution # [-] ADC channel resolution +float32 v_ref # [V] ADC channel voltage reference, use to calculate LSB voltage(lsb=scale/resolution) diff --git a/src/drivers/adc/ads7953/ADS7953.cpp b/src/drivers/adc/ads7953/ADS7953.cpp new file mode 100644 index 0000000000..e2076ef115 --- /dev/null +++ b/src/drivers/adc/ads7953/ADS7953.cpp @@ -0,0 +1,122 @@ + +#include "ADS7953.h" +#include +#include +#include +#include + +ADS7953::ADS7953(const I2CSPIDriverConfig &config) : + SPI(config), + I2CSPIDriver(config), + ModuleParams(nullptr) +{ + static_assert(arraySize(adc_report_s::channel_id) >= NUM_CHANNELS, "ADS7953 reports 16 channels"); +} + +int ADS7953::init() +{ + int ret = SPI::init(); + + if (ret != PX4_OK) { + PX4_DEBUG("SPI::init failed (%i)", ret); + return ret; + } + + _adc_report.device_id = this->get_device_id(); + _adc_report.v_ref = _adc_ads7953_refv.get(); + _adc_report.resolution = 4096; + + for (unsigned i = 0; i < PX4_MAX_ADC_CHANNELS; ++i) { + _adc_report.channel_id[i] = -1; + } + + ScheduleOnInterval(10_ms); + return PX4_OK; +} + +int ADS7953::probe() +{ + // The ADS7953 has no ID register which we can check, so we verify the device via the returned channel ID. + // We set the mode to "manual mode" and the channel to measure to 1. + // If the returned channel ID on the third message is 1, we assume the ADS7953 is connected. + uint8_t recv_data[2]; + + int ret = rw_msg(&recv_data[0], 1, true); + + if (ret != PX4_OK) { + PX4_DEBUG("ADS7953 probing failed (%i)", ret); + return ret; + } + + ret |= rw_msg(&recv_data[0], 0, false); + ret |= rw_msg(&recv_data[0], 0, true); + + if (ret != PX4_OK || (recv_data[0] >> 4) != 1U) { + PX4_DEBUG("ADS7953 probing failed (%i)", ret); + return PX4_ERROR; + } + + PX4_INFO("ADS7953 was found"); + return PX4_OK; +} + +int ADS7953::rw_msg(uint8_t *recv_data, uint8_t ch, bool change_channel) +{ + uint8_t send_data[2]; + + if (change_channel) { + send_data[0] = 0x10 | (ch >> 1); + send_data[1] = 0x00 | (ch << 7); + + } else { + send_data[0] = 0x00; + send_data[1] = 0x00; + } + + return transfer(&send_data[0], &recv_data[0], 2); +} + +int ADS7953::get_measurements() +{ + uint8_t recv_data[2]; + int count = 0; + uint16_t mask = 0x00; + uint8_t idx = 0; + + while (count < NUM_CHANNELS) { + if (rw_msg(&recv_data[0], idx, true) == PX4_OK) { + uint8_t ch_id = (recv_data[0] >> 4); + + //check if we already have a measurement for the returned channel + if (!(mask & (1U << ch_id))) { + mask |= (1U << ch_id); + count++; + _adc_report.channel_id[ch_id] = ch_id; + _adc_report.raw_data[ch_id] = ((((uint16_t) recv_data[0]) & 0x0F) << 8) | recv_data[1]; + } + } + + // Find index to measure next + for (int i = 1; i <= NUM_CHANNELS; i++) { + uint8_t candidate_id = (idx + i) % NUM_CHANNELS; + + if (!(mask & (1U << candidate_id))) { + idx = candidate_id; + break; + } + } + } + + return 0; +} + +void ADS7953::RunImpl() +{ + get_measurements(); + _adc_report.timestamp = hrt_absolute_time(); + _adc_report_pub.publish(_adc_report); + + for (unsigned i = 0; i < PX4_MAX_ADC_CHANNELS; ++i) { + _adc_report.channel_id[i] = -1; + } +} diff --git a/src/drivers/adc/ads7953/ADS7953.h b/src/drivers/adc/ads7953/ADS7953.h new file mode 100644 index 0000000000..03ffcb7b81 --- /dev/null +++ b/src/drivers/adc/ads7953/ADS7953.h @@ -0,0 +1,43 @@ +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace time_literals; + + +class ADS7953 : public device::SPI, public I2CSPIDriver, public ModuleParams +{ +public: + ADS7953(const I2CSPIDriverConfig &config); + virtual ~ADS7953() = default; + static void print_usage(); + + int init() override; + void RunImpl(); + int probe() override; + + +private: + static constexpr int NUM_CHANNELS = 16; + uORB::PublicationMulti _adc_report_pub{ORB_ID(adc_report)}; + + static const hrt_abstime SAMPLE_INTERVAL{50_ms}; + + DEFINE_PARAMETERS( + (ParamFloat) _adc_ads7953_refv + ) + adc_report_s _adc_report{}; + + int get_measurements(); + int rw_msg(uint8_t *recv_data, uint8_t ch, bool change_channel); +}; diff --git a/src/drivers/adc/ads7953/CMakeLists.txt b/src/drivers/adc/ads7953/CMakeLists.txt new file mode 100644 index 0000000000..fbb25e5f5d --- /dev/null +++ b/src/drivers/adc/ads7953/CMakeLists.txt @@ -0,0 +1,46 @@ +############################################################################ +# +# Copyright (c) 2025 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +px4_add_module( + MODULE drivers__adc__ads7953 + MAIN ads7953 + COMPILE_FLAGS + SRCS + ADS7953.cpp + ADS7953.h + ads7953_main.cpp + MODULE_CONFIG + module.yaml + DEPENDS + px4_work_queue + ) diff --git a/src/drivers/adc/ads7953/Kconfig b/src/drivers/adc/ads7953/Kconfig new file mode 100644 index 0000000000..a50f4c8b26 --- /dev/null +++ b/src/drivers/adc/ads7953/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_ADC_ADS7953 + bool "ADS7953 driver" + default n + ---help--- + Enable support for ADS7953 diff --git a/src/drivers/adc/ads7953/ads7953_main.cpp b/src/drivers/adc/ads7953/ads7953_main.cpp new file mode 100644 index 0000000000..9c9de10faf --- /dev/null +++ b/src/drivers/adc/ads7953/ads7953_main.cpp @@ -0,0 +1,77 @@ +/**************************************************************************** + * + * Copyright (c) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include "ADS7953.h" + +void ADS7953::print_usage() +{ + PRINT_MODULE_USAGE_NAME("ads7953", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("adc"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(false, true); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); +} + +extern "C" int ads7953_main(int argc, char *argv[]) +{ + using ThisDriver = ADS7953; + BusCLIArguments cli{false, true}; + cli.spi_mode = SPIDEV_MODE0; + cli.default_spi_frequency = 10 * 1000 * 1000; + const char *name = MODULE_NAME; + const char *verb = cli.parseDefaultArguments(argc, argv); + + if (!verb) { + ThisDriver::print_usage(); + return -1; + } + + BusInstanceIterator iterator(name, cli, DRV_ADC_DEVTYPE_ADS7953); + + if (!strcmp(verb, "start")) { + return ThisDriver::module_start(cli, iterator); + } + + if (!strcmp(verb, "stop")) { + return ThisDriver::module_stop(iterator); + } + + if (!strcmp(verb, "status")) { + return ThisDriver::module_status(iterator); + } + + ThisDriver::print_usage(); + return -1; +} diff --git a/src/drivers/adc/ads7953/module.yaml b/src/drivers/adc/ads7953/module.yaml new file mode 100644 index 0000000000..9097daeb08 --- /dev/null +++ b/src/drivers/adc/ads7953/module.yaml @@ -0,0 +1,29 @@ +__max_num_config_instances: &max_num_config_instances 1 + +module_name: ADS7953 + +parameters: + - group: ADC + definitions: + ADC_ADS7953_EN: + description: + short: Enable ADS7953 + long: | + Enable the driver for the ADS7953 board + type: boolean + reboot_required: true + default: 0 + + ADC_ADS7953_REFV: + description: + short: Applied reference Voltage. + long: | + The voltage applied to the ADS7953 board as reference + type: float + unit: V + min: 2.0 + max: 3.0 + decimal: 2 + increment: 0.01 + reboot_required: true + default: 2.5 diff --git a/src/drivers/adc/board_adc/ADC.hpp b/src/drivers/adc/board_adc/ADC.hpp index 47f9538814..c765d596b4 100644 --- a/src/drivers/adc/board_adc/ADC.hpp +++ b/src/drivers/adc/board_adc/ADC.hpp @@ -50,6 +50,7 @@ #include #include #include +#include #include #include @@ -110,7 +111,7 @@ private: const uint32_t _base_address; px4_adc_msg_t *_samples{nullptr}; /**< sample buffer */ - uORB::Publication _to_adc_report{ORB_ID(adc_report)}; + uORB::PublicationMulti _to_adc_report{ORB_ID(adc_report)}; uORB::Publication _to_system_power{ORB_ID(system_power)}; #ifdef BOARD_GPIO_VDD_5V_COMP_VALID diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h index 1f74122014..eeafc722cf 100644 --- a/src/drivers/drv_sensor.h +++ b/src/drivers/drv_sensor.h @@ -260,6 +260,8 @@ #define DRV_INS_DEVTYPE_SBG 0xEC +#define DRV_ADC_DEVTYPE_ADS7953 0xED + #define DRV_DEVTYPE_UNUSED 0xff #endif /* _DRV_SENSOR_H */ From e7609ad5b5e98b2f582f9557455d4cc2734622bc Mon Sep 17 00:00:00 2001 From: PX4 Build Bot Date: Wed, 5 Nov 2025 17:10:09 +1100 Subject: [PATCH 255/812] New Crowdin translations - zh-CN (#25858) Co-authored-by: Crowdin Bot --- docs/zh/msg_docs/DifferentialPressure.md | 23 +++++++++++++++-------- docs/zh/msg_docs/SensorBaro.md | 23 +++++++++++++++-------- docs/zh/msg_docs/VehicleStatus.md | 14 +++++--------- docs/zh/msg_docs/index.md | 4 ++-- 4 files changed, 37 insertions(+), 27 deletions(-) diff --git a/docs/zh/msg_docs/DifferentialPressure.md b/docs/zh/msg_docs/DifferentialPressure.md index f5fd908df9..83adb2d03e 100644 --- a/docs/zh/msg_docs/DifferentialPressure.md +++ b/docs/zh/msg_docs/DifferentialPressure.md @@ -1,17 +1,24 @@ # DifferentialPressure (UORB message) +Differential-pressure (airspeed) sensor + +This is populated by airspeed sensor drivers and used by the sensor module to calculate airspeed. +The information is published in the `SCALED_PRESSURE_n` MAVLink messages (along with information from a corresponding `SensorBaro` instance). + [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DifferentialPressure.msg) ```c -uint64 timestamp # time since system start (microseconds) -uint64 timestamp_sample +# Differential-pressure (airspeed) sensor +# +# This is populated by airspeed sensor drivers and used by the sensor module to calculate airspeed. +# The information is published in the `SCALED_PRESSURE_n` MAVLink messages (along with information from a corresponding `SensorBaro` instance). -uint32 device_id # unique device ID for the sensor that does not change between power cycles +uint64 timestamp # [us] Time of publication (since system start) +uint64 timestamp_sample # [us] Time of raw data capture -float32 differential_pressure_pa # differential pressure reading in Pascals (may be negative) - -float32 temperature # Temperature provided by sensor in degrees Celsius, NAN if unknown - -uint32 error_count # Number of errors detected by driver +uint32 device_id # [-] Unique device ID for the sensor that does not change between power cycles +float32 differential_pressure_pa # [Pa] Differential pressure reading (may be negative) +float32 temperature # [degC] [@invalid NaN if unknown] Temperature +uint32 error_count # [-] Number of errors detected by driver ``` diff --git a/docs/zh/msg_docs/SensorBaro.md b/docs/zh/msg_docs/SensorBaro.md index cf834ccf36..ef4d7a8f28 100644 --- a/docs/zh/msg_docs/SensorBaro.md +++ b/docs/zh/msg_docs/SensorBaro.md @@ -1,18 +1,25 @@ # SensorBaro (UORB message) +Barometer sensor + +This is populated by barometer drivers and used by the EKF2 estimator. +The information is published in the `SCALED_PRESSURE_n` MAVLink messages (along with information from a corresponding `DifferentialPressure` instance). + [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorBaro.msg) ```c -uint64 timestamp # time since system start (microseconds) -uint64 timestamp_sample +# Barometer sensor +# +# This is populated by barometer drivers and used by the EKF2 estimator. +# The information is published in the `SCALED_PRESSURE_n` MAVLink messages (along with information from a corresponding `DifferentialPressure` instance). -uint32 device_id # unique device ID for the sensor that does not change between power cycles +uint64 timestamp # [us] Time of publication (since system start) +uint64 timestamp_sample # [us] Time of raw data capture -float32 pressure # static pressure measurement in Pascals - -float32 temperature # temperature in degrees Celsius - -uint32 error_count +uint32 device_id # [-] Unique device ID for the sensor that does not change between power cycles +float32 pressure # [Pa] Static pressure measurement +float32 temperature # [degC] Temperature. +uint32 error_count # [-] Number of errors detected by driver. uint8 ORB_QUEUE_LENGTH = 4 diff --git a/docs/zh/msg_docs/VehicleStatus.md b/docs/zh/msg_docs/VehicleStatus.md index 9d46e42cb3..05e3f98bbb 100644 --- a/docs/zh/msg_docs/VehicleStatus.md +++ b/docs/zh/msg_docs/VehicleStatus.md @@ -20,20 +20,16 @@ uint8 ARMING_STATE_ARMED = 2 uint8 latest_arming_reason uint8 latest_disarming_reason -uint8 ARM_DISARM_REASON_TRANSITION_TO_STANDBY = 0 uint8 ARM_DISARM_REASON_STICK_GESTURE = 1 uint8 ARM_DISARM_REASON_RC_SWITCH = 2 uint8 ARM_DISARM_REASON_COMMAND_INTERNAL = 3 uint8 ARM_DISARM_REASON_COMMAND_EXTERNAL = 4 uint8 ARM_DISARM_REASON_MISSION_START = 5 -uint8 ARM_DISARM_REASON_SAFETY_BUTTON = 6 -uint8 ARM_DISARM_REASON_AUTO_DISARM_LAND = 7 -uint8 ARM_DISARM_REASON_AUTO_DISARM_PREFLIGHT = 8 -uint8 ARM_DISARM_REASON_KILL_SWITCH = 9 -uint8 ARM_DISARM_REASON_LOCKDOWN = 10 -uint8 ARM_DISARM_REASON_FAILURE_DETECTOR = 11 -uint8 ARM_DISARM_REASON_SHUTDOWN = 12 -uint8 ARM_DISARM_REASON_UNIT_TEST = 13 +uint8 ARM_DISARM_REASON_LANDING = 6 +uint8 ARM_DISARM_REASON_PREFLIGHT_INACTION = 7 +uint8 ARM_DISARM_REASON_KILL_SWITCH = 8 +uint8 ARM_DISARM_REASON_RC_BUTTON = 13 +uint8 ARM_DISARM_REASON_FAILSAFE = 14 uint64 nav_state_timestamp # time when current nav_state activated diff --git a/docs/zh/msg_docs/index.md b/docs/zh/msg_docs/index.md index dfed09c171..2512c7058d 100644 --- a/docs/zh/msg_docs/index.md +++ b/docs/zh/msg_docs/index.md @@ -105,7 +105,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [DebugKeyValue](DebugKeyValue.md) - [DebugValue](DebugValue.md) - [DebugVect](DebugVect.md) -- [DifferentialPressure](DifferentialPressure.md) +- [DifferentialPressure](DifferentialPressure.md) — Differential-pressure (airspeed) sensor - [DistanceSensor](DistanceSensor.md) — DISTANCE_SENSOR message data - [DistanceSensorModeChangeRequest](DistanceSensorModeChangeRequest.md) - [DronecanNodeStatus](DronecanNodeStatus.md) @@ -240,7 +240,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [SensorAccel](SensorAccel.md) - [SensorAccelFifo](SensorAccelFifo.md) - [SensorAirflow](SensorAirflow.md) -- [SensorBaro](SensorBaro.md) +- [SensorBaro](SensorBaro.md) — Barometer sensor - [SensorCombined](SensorCombined.md) — Sensor readings in SI-unit form. These fields are scaled and offset-compensated where possible and do not change with board revisions and sensor updates. From ab1c880aadcee048dc3a29d9792bfdc9fcf77a9a Mon Sep 17 00:00:00 2001 From: Balduin Date: Wed, 5 Nov 2025 09:55:49 +0100 Subject: [PATCH 256/812] pusher_assist: keep pitch setpoint VT_PITCH_MIN (#25871) * pusher_assist: keep pitch setpoint VT_PITCH_MIN resetting the pitch setpoint to zero made little sense, because we lose the forward thrust component of the hover motors, while the pusher throttle was calculated to be applied in addition to the hover forward component * pusher assist: change default min pitches to 0 To make for a smoother transition for users who don't care much about pitch when pusher-assisting and were fine with it (mostly) being at zero --- src/modules/vtol_att_control/vtol_att_control_params.c | 4 ++-- src/modules/vtol_att_control/vtol_type.cpp | 6 +----- 2 files changed, 3 insertions(+), 7 deletions(-) diff --git a/src/modules/vtol_att_control/vtol_att_control_params.c b/src/modules/vtol_att_control/vtol_att_control_params.c index 4b9452d3b6..af664bd632 100644 --- a/src/modules/vtol_att_control/vtol_att_control_params.c +++ b/src/modules/vtol_att_control/vtol_att_control_params.c @@ -365,7 +365,7 @@ PARAM_DEFINE_FLOAT(VT_B_DEC_I, 0.1f); * @decimal 1 * @group VTOL Attitude Control */ -PARAM_DEFINE_FLOAT(VT_PITCH_MIN, -5.0f); +PARAM_DEFINE_FLOAT(VT_PITCH_MIN, 0.0f); /** * Minimum pitch angle during hover landing. @@ -380,7 +380,7 @@ PARAM_DEFINE_FLOAT(VT_PITCH_MIN, -5.0f); * @decimal 1 * @group VTOL Attitude Control */ -PARAM_DEFINE_FLOAT(VT_LND_PITCH_MIN, -5.0f); +PARAM_DEFINE_FLOAT(VT_LND_PITCH_MIN, 0.0f); /** * Spoiler setting while landing (hover) diff --git a/src/modules/vtol_att_control/vtol_type.cpp b/src/modules/vtol_att_control/vtol_type.cpp index def70ece07..8195df5f8b 100644 --- a/src/modules/vtol_att_control/vtol_type.cpp +++ b/src/modules/vtol_att_control/vtol_type.cpp @@ -515,12 +515,8 @@ float VtolType::pusher_assist() // limit forward actuation to [0, 0.9] forward_thrust = math::constrain(forward_thrust, 0.0f, 0.9f); - // Set the pitch to 0 if the pitch limit is negative (pitch down), but allow a positive (pitch up) pitch. - // This can be used for tiltrotor to make them hover with a positive angle of attack - const float pitch_new = pitch_setpoint_min > 0.f ? pitch_setpoint_min : 0.f; - // create corrected desired body z axis in heading frame - const Dcmf R_tmp = Eulerf(roll_new, pitch_new, 0.0f); + const Dcmf R_tmp = Eulerf(roll_new, pitch_setpoint_min, 0.0f); Vector3f tilt_new(R_tmp(0, 2), R_tmp(1, 2), R_tmp(2, 2)); // rotate the vector into a new frame which is rotated in z by the desired heading From 84b5ce9010f110858fa670925d043a7974425705 Mon Sep 17 00:00:00 2001 From: Marco Hauswirth <58551738+haumarco@users.noreply.github.com> Date: Wed, 5 Nov 2025 16:25:15 +0100 Subject: [PATCH 257/812] AirspeedSelector: enable changing ASPD_SCALE manually in-air mid-flight (#25817) Includes a reset in wind estimator states if changed --- src/lib/wind_estimator/WindEstimator.hpp | 8 ++++++++ .../airspeed_selector/AirspeedValidator.hpp | 1 + .../airspeed_selector/airspeed_selector_main.cpp | 14 ++++++++++++++ .../airspeed_selector/airspeed_selector_params.c | 3 --- 4 files changed, 23 insertions(+), 3 deletions(-) diff --git a/src/lib/wind_estimator/WindEstimator.hpp b/src/lib/wind_estimator/WindEstimator.hpp index 462f88ff26..dbdf854da9 100644 --- a/src/lib/wind_estimator/WindEstimator.hpp +++ b/src/lib/wind_estimator/WindEstimator.hpp @@ -94,6 +94,14 @@ public: void set_beta_gate(uint8_t gate_size) {_beta_gate = gate_size; } void set_scale_init(float scale_init) {_scale_init = 1.f / math::constrain(scale_init, 0.1f, 10.f); } + void reset_scale_to_init() + { + _state(INDEX_TAS_SCALE) = _scale_init; + auto P_wind = _P.slice<2, 2>(0, 0); + _P.setZero(); + _P.slice<2, 2>(0, 0) = P_wind; + } + private: enum { INDEX_W_N = 0, diff --git a/src/modules/airspeed_selector/AirspeedValidator.hpp b/src/modules/airspeed_selector/AirspeedValidator.hpp index ec78b9ef8f..f902e8a9de 100644 --- a/src/modules/airspeed_selector/AirspeedValidator.hpp +++ b/src/modules/airspeed_selector/AirspeedValidator.hpp @@ -121,6 +121,7 @@ public: void set_tas_scale_apply(int tas_scale_apply) { _tas_scale_apply = tas_scale_apply; } void set_CAS_scale_validated(float scale) { _CAS_scale_validated = scale; } void set_scale_init(float scale) { _wind_estimator.set_scale_init(scale); } + void reset_scale_estimator() { _wind_estimator.reset_scale_to_init(); } void set_enable_data_stuck_check(bool enable) { _data_stuck_check_enabled = enable; } void set_enable_innovation_check(bool enable) { _innovation_check_enabled = enable; } diff --git a/src/modules/airspeed_selector/airspeed_selector_main.cpp b/src/modules/airspeed_selector/airspeed_selector_main.cpp index b3209e2f33..94a8b9cd8a 100644 --- a/src/modules/airspeed_selector/airspeed_selector_main.cpp +++ b/src/modules/airspeed_selector/airspeed_selector_main.cpp @@ -494,10 +494,24 @@ void AirspeedModule::update_params() param_get(_param_handle_fw_thr_max, &_param_fw_thr_max); } + const float prev_scale[MAX_NUM_AIRSPEED_SENSORS] = { + _param_airspeed_scale[0], + _param_airspeed_scale[1], + _param_airspeed_scale[2] + }; + _param_airspeed_scale[0] = _param_airspeed_scale_1.get(); _param_airspeed_scale[1] = _param_airspeed_scale_2.get(); _param_airspeed_scale[2] = _param_airspeed_scale_3.get(); + for (int i = 0; i < MAX_NUM_AIRSPEED_SENSORS; i++) { + if (fabsf(_param_airspeed_scale[i] - prev_scale[i]) > FLT_EPSILON) { + _airspeed_validator[i].set_scale_init(_param_airspeed_scale[i]); + _airspeed_validator[i].reset_scale_estimator(); + _airspeed_validator[i].set_CAS_scale_validated(_param_airspeed_scale[i]); + } + } + _wind_estimator_sideslip.set_wind_process_noise_spectral_density(_param_aspd_wind_nsd.get()); _wind_estimator_sideslip.set_tas_scale_process_noise_spectral_density(_param_aspd_scale_nsd.get()); _wind_estimator_sideslip.set_tas_noise(_param_west_tas_noise.get()); diff --git a/src/modules/airspeed_selector/airspeed_selector_params.c b/src/modules/airspeed_selector/airspeed_selector_params.c index a7db4cb30c..34d74cbfc5 100644 --- a/src/modules/airspeed_selector/airspeed_selector_params.c +++ b/src/modules/airspeed_selector/airspeed_selector_params.c @@ -95,7 +95,6 @@ PARAM_DEFINE_INT32(ASPD_SCALE_APPLY, 2); * @min 0.5 * @max 2.0 * @decimal 2 - * @reboot_required true * @group Airspeed Validator * @volatile */ @@ -109,7 +108,6 @@ PARAM_DEFINE_FLOAT(ASPD_SCALE_1, 1.0f); * @min 0.5 * @max 2.0 * @decimal 2 - * @reboot_required true * @group Airspeed Validator * @volatile */ @@ -123,7 +121,6 @@ PARAM_DEFINE_FLOAT(ASPD_SCALE_2, 1.0f); * @min 0.5 * @max 2.0 * @decimal 2 - * @reboot_required true * @group Airspeed Validator * @volatile */ From 5f0d222e1b699447a555063d16746f009f915dbd Mon Sep 17 00:00:00 2001 From: Minderring <1701213518@sz.edu.pku.cn> Date: Wed, 5 Nov 2025 17:45:19 +0800 Subject: [PATCH 258/812] update micoair boards config files: remove CONFIG_DRIVERS_RC_INPUT --- boards/micoair/h743-aio/default.px4board | 1 - boards/micoair/h743-lite/default.px4board | 1 - boards/micoair/h743-v2/default.px4board | 1 - boards/micoair/h743/default.px4board | 1 - 4 files changed, 4 deletions(-) diff --git a/boards/micoair/h743-aio/default.px4board b/boards/micoair/h743-aio/default.px4board index d6dd734283..11abe64a47 100644 --- a/boards/micoair/h743-aio/default.px4board +++ b/boards/micoair/h743-aio/default.px4board @@ -37,7 +37,6 @@ CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y CONFIG_DRIVERS_PPS_CAPTURE=y CONFIG_DRIVERS_PWM_OUT=y CONFIG_COMMON_RC=y -CONFIG_DRIVERS_RC_INPUT=y CONFIG_DRIVERS_ROBOCLAW=y CONFIG_COMMON_RPM=y CONFIG_DRIVERS_SMART_BATTERY_BATMON=y diff --git a/boards/micoair/h743-lite/default.px4board b/boards/micoair/h743-lite/default.px4board index 68a87e863c..f24ffc4fdb 100644 --- a/boards/micoair/h743-lite/default.px4board +++ b/boards/micoair/h743-lite/default.px4board @@ -34,7 +34,6 @@ CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y CONFIG_DRIVERS_PPS_CAPTURE=y CONFIG_DRIVERS_PWM_OUT=y CONFIG_COMMON_RC=y -CONFIG_DRIVERS_RC_INPUT=y CONFIG_COMMON_RPM=y CONFIG_DRIVERS_SMART_BATTERY_BATMON=y CONFIG_DRIVERS_TAP_ESC=y diff --git a/boards/micoair/h743-v2/default.px4board b/boards/micoair/h743-v2/default.px4board index 9f6d00a5d0..5276166e42 100644 --- a/boards/micoair/h743-v2/default.px4board +++ b/boards/micoair/h743-v2/default.px4board @@ -36,7 +36,6 @@ CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y CONFIG_DRIVERS_PPS_CAPTURE=y CONFIG_DRIVERS_PWM_OUT=y CONFIG_COMMON_RC=y -CONFIG_DRIVERS_RC_INPUT=y CONFIG_COMMON_RPM=y CONFIG_DRIVERS_SMART_BATTERY_BATMON=y CONFIG_DRIVERS_TAP_ESC=y diff --git a/boards/micoair/h743/default.px4board b/boards/micoair/h743/default.px4board index d6769fa1d8..abf1cfb4ff 100644 --- a/boards/micoair/h743/default.px4board +++ b/boards/micoair/h743/default.px4board @@ -38,7 +38,6 @@ CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y CONFIG_DRIVERS_PPS_CAPTURE=y CONFIG_DRIVERS_PWM_OUT=y CONFIG_COMMON_RC=y -CONFIG_DRIVERS_RC_INPUT=y CONFIG_COMMON_RPM=y CONFIG_DRIVERS_SMART_BATTERY_BATMON=y CONFIG_DRIVERS_TAP_ESC=y From 1250563ed1942b09adcd0e2701dfda3bb704e423 Mon Sep 17 00:00:00 2001 From: Peter van der Perk <57130844+PetervdPerk-NXP@users.noreply.github.com> Date: Wed, 5 Nov 2025 17:48:26 +0100 Subject: [PATCH 259/812] Add support for NXP MR-VMU-Tropic board (#25845) * rt106x: Use platform SPI hal layer * rt106x: Add romapi support and reboot to isp/bootloader * bootloader: imxrt_common: Add rt106x support * NXP MR-Tropic initial commit * Add missing file for mr-tropic bootloader * nxp-mr-tropic:Bootloader Alow Assertion debugging & Keep Ram Vectors * nxp-mr-tropic: Firmware Boot from bootloader * nxp-mr-tropic:Add Bootloader bin file * mr-tropic: Update config and linker Fixes enet issues with write-back and some code cleanup. Furthermore increase NOR LittleFS to 256kB to reflect on linker * Update NuttX * mr-tropic: fix itcm apping and add mr-tropic to itcm check --------- Co-authored-by: David Sidrane --- .github/workflows/itcm_check.yml | 4 + .vscode/cmake-variants.yaml | 10 + boards/nxp/mr-tropic/bootloader.px4board | 3 + boards/nxp/mr-tropic/cmake/upload.cmake | 44 ++ boards/nxp/mr-tropic/default.px4board | 109 +++ .../extras/nxp_mr-tropic_bootloader.bin | Bin 0 -> 74376 bytes boards/nxp/mr-tropic/firmware.prototype | 13 + boards/nxp/mr-tropic/init/rc.board_defaults | 38 + boards/nxp/mr-tropic/init/rc.board_mavlink | 4 + boards/nxp/mr-tropic/init/rc.board_sensors | 68 ++ boards/nxp/mr-tropic/nuttx-config/Kconfig | 4 + .../nuttx-config/bootloader/defconfig | 107 +++ .../mr-tropic/nuttx-config/include/board.h | 416 ++++++++++ .../nxp/mr-tropic/nuttx-config/nsh/defconfig | 270 +++++++ .../nuttx-config/scripts/bootloader_script.ld | 177 +++++ .../scripts/itcm_functions_includes.ld | 719 ++++++++++++++++++ .../scripts/itcm_static_functions.ld | 163 ++++ .../mr-tropic/nuttx-config/scripts/script.ld | 187 +++++ boards/nxp/mr-tropic/src/CMakeLists.txt | 86 +++ boards/nxp/mr-tropic/src/board_config.h | 355 +++++++++ boards/nxp/mr-tropic/src/bootloader_main.c | 61 ++ boards/nxp/mr-tropic/src/hw_config.h | 130 ++++ boards/nxp/mr-tropic/src/hw_rev_ver_tropic.c | 165 ++++ boards/nxp/mr-tropic/src/i2c.cpp | 40 + .../mr-tropic/src/imxrt_flexspi_nor_boot.c | 55 ++ .../mr-tropic/src/imxrt_flexspi_nor_boot.h | 166 ++++ .../mr-tropic/src/imxrt_flexspi_nor_flash.c | 107 +++ .../mr-tropic/src/imxrt_flexspi_nor_flash.h | 349 +++++++++ .../nxp/mr-tropic/src/imxrt_flexspi_storage.c | 411 ++++++++++ .../mr-tropic/src/imxrt_ocram_initialize.c | 102 +++ boards/nxp/mr-tropic/src/init.c | 400 ++++++++++ boards/nxp/mr-tropic/src/manifest.c | 79 ++ boards/nxp/mr-tropic/src/sdhc.c | 128 ++++ boards/nxp/mr-tropic/src/spi.cpp | 95 +++ boards/nxp/mr-tropic/src/timer_config.cpp | 152 ++++ boards/nxp/mr-tropic/src/tropic_led_pwm.cpp | 182 +++++ boards/nxp/mr-tropic/src/usb.c | 129 ++++ .../px4_platform_common/board_common.h | 9 +- platforms/nuttx/CMakeLists.txt | 3 + platforms/nuttx/NuttX/nuttx | 2 +- platforms/nuttx/cmake/px4_impl_os.cmake | 3 + .../src/bootloader/nxp/imxrt_common/main.c | 112 ++- .../src/bootloader/nxp/rt106x/CMakeLists.txt | 34 + .../px4/nxp/imxrt/board_reset/CMakeLists.txt | 2 - .../px4/nxp/imxrt/board_reset/board_reset.cpp | 17 +- .../px4_arch/imxrt_flexspi_nor_flash.h | 17 +- .../nxp/imxrt/include/px4_arch/imxrt_romapi.h | 6 + .../src/px4/nxp/imxrt/romapi/imxrt_romapi.c | 79 +- .../px4/nxp/imxrt/version/board_mcu_version.c | 3 +- .../nuttx/src/px4/nxp/rt106x/CMakeLists.txt | 2 + .../rt106x/include/px4_arch/hw_description.h | 4 +- .../px4_arch/imxrt_flexspi_nor_flash.h | 36 + .../rt106x/include/px4_arch/imxrt_romapi.h | 36 + .../px4_arch/io_timer_hw_description.h | 4 +- .../include/px4_arch/spi_hw_description.h | 105 ++- 55 files changed, 5972 insertions(+), 30 deletions(-) create mode 100644 boards/nxp/mr-tropic/bootloader.px4board create mode 100644 boards/nxp/mr-tropic/cmake/upload.cmake create mode 100644 boards/nxp/mr-tropic/default.px4board create mode 100755 boards/nxp/mr-tropic/extras/nxp_mr-tropic_bootloader.bin create mode 100644 boards/nxp/mr-tropic/firmware.prototype create mode 100644 boards/nxp/mr-tropic/init/rc.board_defaults create mode 100644 boards/nxp/mr-tropic/init/rc.board_mavlink create mode 100644 boards/nxp/mr-tropic/init/rc.board_sensors create mode 100644 boards/nxp/mr-tropic/nuttx-config/Kconfig create mode 100644 boards/nxp/mr-tropic/nuttx-config/bootloader/defconfig create mode 100644 boards/nxp/mr-tropic/nuttx-config/include/board.h create mode 100644 boards/nxp/mr-tropic/nuttx-config/nsh/defconfig create mode 100644 boards/nxp/mr-tropic/nuttx-config/scripts/bootloader_script.ld create mode 100644 boards/nxp/mr-tropic/nuttx-config/scripts/itcm_functions_includes.ld create mode 100644 boards/nxp/mr-tropic/nuttx-config/scripts/itcm_static_functions.ld create mode 100644 boards/nxp/mr-tropic/nuttx-config/scripts/script.ld create mode 100644 boards/nxp/mr-tropic/src/CMakeLists.txt create mode 100644 boards/nxp/mr-tropic/src/board_config.h create mode 100644 boards/nxp/mr-tropic/src/bootloader_main.c create mode 100644 boards/nxp/mr-tropic/src/hw_config.h create mode 100644 boards/nxp/mr-tropic/src/hw_rev_ver_tropic.c create mode 100644 boards/nxp/mr-tropic/src/i2c.cpp create mode 100644 boards/nxp/mr-tropic/src/imxrt_flexspi_nor_boot.c create mode 100644 boards/nxp/mr-tropic/src/imxrt_flexspi_nor_boot.h create mode 100644 boards/nxp/mr-tropic/src/imxrt_flexspi_nor_flash.c create mode 100644 boards/nxp/mr-tropic/src/imxrt_flexspi_nor_flash.h create mode 100644 boards/nxp/mr-tropic/src/imxrt_flexspi_storage.c create mode 100644 boards/nxp/mr-tropic/src/imxrt_ocram_initialize.c create mode 100644 boards/nxp/mr-tropic/src/init.c create mode 100644 boards/nxp/mr-tropic/src/manifest.c create mode 100644 boards/nxp/mr-tropic/src/sdhc.c create mode 100644 boards/nxp/mr-tropic/src/spi.cpp create mode 100644 boards/nxp/mr-tropic/src/timer_config.cpp create mode 100644 boards/nxp/mr-tropic/src/tropic_led_pwm.cpp create mode 100644 boards/nxp/mr-tropic/src/usb.c create mode 100644 platforms/nuttx/src/bootloader/nxp/rt106x/CMakeLists.txt create mode 100644 platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/imxrt_flexspi_nor_flash.h create mode 100644 platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/imxrt_romapi.h diff --git a/.github/workflows/itcm_check.yml b/.github/workflows/itcm_check.yml index 5a1b0ecddc..767f69aa7c 100644 --- a/.github/workflows/itcm_check.yml +++ b/.github/workflows/itcm_check.yml @@ -41,6 +41,10 @@ jobs: scripts: > boards/nxp/tropic-community/nuttx-config/scripts/itcm_functions_includes.ld boards/nxp/tropic-community/nuttx-config/scripts/itcm_static_functions.ld + - target: nxp_mr-tropic + scripts: > + boards/nxp/mr-tropic/nuttx-config/scripts/itcm_functions_includes.ld + boards/nxp/mr-tropic/nuttx-config/scripts/itcm_static_functions.ld steps: - uses: actions/checkout@v4 with: diff --git a/.vscode/cmake-variants.yaml b/.vscode/cmake-variants.yaml index b80cdb73c8..71aec979d4 100644 --- a/.vscode/cmake-variants.yaml +++ b/.vscode/cmake-variants.yaml @@ -481,6 +481,16 @@ CONFIG: buildType: MinSizeRel settings: CONFIG: nxp_mr-canhubk3_fmu + nxp_mr-tropic_default: + short: nxp_mr-tropic_default + buildType: MinSizeRel + settings: + CONFIG: nxp_mr-tropic_default + nxp_mr-tropic_bootloader: + short: nxp_mr-tropic_bootloader + buildType: MinSizeRel + settings: + CONFIG: nxp_mr-tropic_bootloader nxp_tropic-community_default: short: nxp_tropic-community_default buildType: MinSizeRel diff --git a/boards/nxp/mr-tropic/bootloader.px4board b/boards/nxp/mr-tropic/bootloader.px4board new file mode 100644 index 0000000000..19b6e662be --- /dev/null +++ b/boards/nxp/mr-tropic/bootloader.px4board @@ -0,0 +1,3 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ROMFSROOT="" diff --git a/boards/nxp/mr-tropic/cmake/upload.cmake b/boards/nxp/mr-tropic/cmake/upload.cmake new file mode 100644 index 0000000000..79da5c60fd --- /dev/null +++ b/boards/nxp/mr-tropic/cmake/upload.cmake @@ -0,0 +1,44 @@ +############################################################################ +# +# Copyright (c) 2024 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + + +set(PX4_FW_NAME ${PX4_BINARY_DIR}/${PX4_BOARD_VENDOR}_${PX4_BOARD_MODEL}_${PX4_BOARD_LABEL}.hex) + +add_custom_target(upload_teensy + COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/teensy_uploader.py --port ${serial_ports} ${PX4_FW_NAME} --vendor-id 0x1FC9 --product-id 0x0024 + DEPENDS ${PX4_FW_NAME} + COMMENT "uploading px4" + VERBATIM + USES_TERMINAL + WORKING_DIRECTORY ${PX4_BINARY_DIR} +) diff --git a/boards/nxp/mr-tropic/default.px4board b/boards/nxp/mr-tropic/default.px4board new file mode 100644 index 0000000000..2d4888e1aa --- /dev/null +++ b/boards/nxp/mr-tropic/default.px4board @@ -0,0 +1,109 @@ +CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" +CONFIG_BOARD_ARCHITECTURE="cortex-m7" +CONFIG_BOARD_ETHERNET=y +CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS1" +CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2" +CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4" +CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS3" +CONFIG_BOARD_SERIAL_RC="/dev/ttyS6" +CONFIG_BOARD_PARAM_FILE="/fs/nor/mtd_params" +CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_BAROMETER_BMP388=y +CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y +CONFIG_DRIVERS_BAROMETER_MS5611=y +CONFIG_DRIVERS_CAMERA_CAPTURE=y +CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y +CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_SF45_SERIAL=y +CONFIG_DRIVERS_DSHOT=y +CONFIG_DRIVERS_GNSS_SEPTENTRIO=y +CONFIG_DRIVERS_GPS=y +CONFIG_DRIVERS_IMU_BOSCH_BMI088=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y +CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y +CONFIG_COMMON_INS=y +CONFIG_COMMON_LIGHT=y +CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y +CONFIG_COMMON_MAGNETOMETER=y +CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM350=y +CONFIG_COMMON_OPTICAL_FLOW=y +CONFIG_DRIVERS_OSD_MSP_OSD=y +CONFIG_DRIVERS_POWER_MONITOR_INA226=y +CONFIG_DRIVERS_POWER_MONITOR_INA228=y +CONFIG_DRIVERS_POWER_MONITOR_INA238=y +CONFIG_DRIVERS_PWM_OUT=y +CONFIG_COMMON_RC=y +CONFIG_DRIVERS_SAFETY_BUTTON=y +CONFIG_COMMON_TELEMETRY=y +CONFIG_DRIVERS_TONE_ALARM=y +CONFIG_DRIVERS_UAVCAN=y +CONFIG_BOARD_UAVCAN_INTERFACES=1 +CONFIG_COMMON_UWB=y +CONFIG_MODULES_AIRSPEED_SELECTOR=y +CONFIG_MODULES_BATTERY_STATUS=y +CONFIG_MODULES_CAMERA_FEEDBACK=y +CONFIG_MODULES_COMMANDER=y +CONFIG_MODULES_CONTROL_ALLOCATOR=y +CONFIG_MODULES_DATAMAN=y +CONFIG_MODULES_EKF2=y +CONFIG_MODULES_ESC_BATTERY=y +CONFIG_MODULES_EVENTS=y +CONFIG_MODULES_FLIGHT_MODE_MANAGER=y +CONFIG_MODULES_FW_ATT_CONTROL=y +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_FW_MODE_MANAGER=y +CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y +CONFIG_MODULES_FW_RATE_CONTROL=y +CONFIG_MODULES_GIMBAL=y +CONFIG_MODULES_GYRO_CALIBRATION=y +CONFIG_MODULES_GYRO_FFT=y +CONFIG_MODULES_LAND_DETECTOR=y +CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y +CONFIG_MODULES_LOAD_MON=y +CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y +CONFIG_MODULES_LOGGER=y +CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y +CONFIG_MODULES_MANUAL_CONTROL=y +CONFIG_MODULES_MAVLINK=y +CONFIG_MODULES_MC_ATT_CONTROL=y +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y +CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y +CONFIG_MODULES_MC_POS_CONTROL=y +CONFIG_MODULES_MC_RATE_CONTROL=y +CONFIG_MODULES_NAVIGATOR=y +CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y +CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000 +CONFIG_MODULES_RC_UPDATE=y +CONFIG_MODULES_ROVER_POS_CONTROL=y +CONFIG_MODULES_SENSORS=y +CONFIG_MODULES_TEMPERATURE_COMPENSATION=y +CONFIG_MODULES_UXRCE_DDS_CLIENT=y +CONFIG_MODULES_VTOL_ATT_CONTROL=y +CONFIG_MODULES_ZENOH=y +CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y +CONFIG_SYSTEMCMDS_BSONDUMP=y +CONFIG_SYSTEMCMDS_DMESG=y +CONFIG_SYSTEMCMDS_DUMPFILE=y +CONFIG_SYSTEMCMDS_I2C_LAUNCHER=y +CONFIG_SYSTEMCMDS_I2CDETECT=y +CONFIG_SYSTEMCMDS_LED_CONTROL=y +CONFIG_SYSTEMCMDS_MFT=y +CONFIG_SYSTEMCMDS_NETMAN=y +CONFIG_SYSTEMCMDS_NSHTERM=y +CONFIG_SYSTEMCMDS_PARAM=y +CONFIG_SYSTEMCMDS_PERF=y +CONFIG_SYSTEMCMDS_REBOOT=y +CONFIG_SYSTEMCMDS_SD_BENCH=y +CONFIG_SYSTEMCMDS_SD_STRESS=y +CONFIG_SYSTEMCMDS_SERIAL_TEST=y +CONFIG_SYSTEMCMDS_SYSTEM_TIME=y +CONFIG_SYSTEMCMDS_TOP=y +CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y +CONFIG_SYSTEMCMDS_TUNE_CONTROL=y +CONFIG_SYSTEMCMDS_UORB=y +CONFIG_SYSTEMCMDS_USB_CONNECTED=y +CONFIG_SYSTEMCMDS_VER=y +CONFIG_SYSTEMCMDS_WORK_QUEUE=y diff --git a/boards/nxp/mr-tropic/extras/nxp_mr-tropic_bootloader.bin b/boards/nxp/mr-tropic/extras/nxp_mr-tropic_bootloader.bin new file mode 100755 index 0000000000000000000000000000000000000000..c972de6405bf4a97c4292b4180ef567fb66b7346 GIT binary patch literal 74376 zcmeFZ4RjMnmMDCyyY=HAY#A9M%MNZy283mZz$7stle8t%mL-S?B(n@;UfP%>?U0F^ zpP3;)4+JI?ev&sNFf$O69TGA#WRlrICYnV_JaPibPBz1?6wE9?$;N@q2-^@!mW|qy zrT$K}An^9h?!I@$hN-!l|7%Ih{I#do63dvbM+R0hCcXZ;_Gd9BJ!8EFfAZhJ zQ>2`|R{n33@SnW@|M!Fdz;OLr$%Fs-q})h1(v5T@-AFgmjdUa3NH@}rbR*qJ|4*bC zu#LcibalnZ8bAW_yOt!lvZnukf*?22jdUa3NH@}rbR*qJH`0xCBi%?h(v9?gVcO+q z+4rp=O`CD!cY_B1=gELRwEA}zUuROk#nQ5W1lm|{nE)2n`;x2nc(sr9vMt+P_T#LN z^;*;%!b?X1_vR4hMgf=STrA*Ea*?F}$B|^mk99Va*C;F&uHI9)KnA=_0US{P_bU|c zmR&Ma`Ooo1GE?N1nWF1+WGoS1n*Jj6fu3anSXR#>$$(gv{7e=k1t^x?aS8gK3a<{s zwBJX7^Q-V$rgxUu##s_w`3B4}Z=3UjKUDQ)6HM!&4K#Hkfbv zdPkwu43Xa^A&_@3;%{BKHcs!y&H7gu{y82T9PSKkbKS%@pXy3)8gd0cNU%_o2K)l| zGmaZT#k)BFz)c=o@p~Eha&`LIoIW%0efI!zYcnN@J+6XN8Iv}lI0Lw1;~p0`G;t$! z*W9LM=GVIpWn`?+80wn_=qAXNwC&4Zy+ z0TciFpq}9din&O9yQ|<7Oa~kcz?2XB0Xg|R9*5GMmtlrCw%tV?-{gX!!-37_)^bZosoohbb?pk$v* ztsSHO!P=1dkU7VL1RHipWZf)N^6H8txf7r zwVDbNiqrGywt4)iHxg8VrRmkdLKOLidd&l<88UkL@I2kAIN{*T8J`}WS9gkPnA*e* z6mY*9)a&+TsIC5aAMq```S?xI?*JT}D5AE2ld_hCOwg(-QO&fx8Q zQC!RS|HZ^-|Kgta=T8q0QYGz!3_=ZG#P$5Aae;q6zL5{dALhRwckU(kCYG)A?RL>I+FEQedo+D!-)C41CQc;R z9uo&p!97OuTm`pQEvw+5r-B18bAg^xP9M^F0N^tUiJ?l- zkD-8>LgTyXKk%r&E0Y|WEBXgIOJ3%?GC3UR`r9UCZ-^jPn}HEXphC!KTe~tNBVCz9 z;-dLG<~Lk-M#k~g>23I-dAlP)UYkJLmm_cS0p2p>^VkaOq0CT{9(2=f^XN~B9ZxJ- zmRC}4Wxwdg6lKE{{hF{}$UFg#Ik9)21V?cMY?STECkumajOaVmD?_&}eqg05j$RFF{WJp;7p8K5X@>m5&^T2qv&Emzxk;)#N3R8&9hgBWScK)?2= zdziBU>l$uyx$qY1wdMO;e;3!={t%~a=i?BmA+*2kabyULMX9cSWwPUAm^}2=x zrd%i&p>FJSz1KB_zPWRH{lkslo*>S{)l9iCWBwFjiU>2tPS?$!AXr5!rYRRjlvOAc z|3r`Vnnmj{x17A~CpvQH8s=7;1*^AQtig9PO<2#A3sqv%a9>T8P%M6>8|!7nreUsz z5lkYBK{5$N;$H1ouTivNjy4K~;&{wbnV8XM^i+rz%%KW_T<=B|f}y2IbPq#)kw9Cd z_W(B%F?b6{^fek`MkE z@Nd(8+_c({;a)%HIKYdq+y@%{7&ySbwAt$)2IR**9N?z(M6Z9i#{w+iyVB*PWTqd( zLcq7D%gCL@-~l`{U83eoJb)b}k6~55wVJdayH@*$p{&3I_~taSl2KB|8+gF_cL0jC z07W!e8w1!`0CMQ0Z=)e}DOt8TU?W6ltu3BguPa9Z7ynGtNWl z&S3^uGo+ny_f+sy8d50DjG#I526UQR1^H8SNAgors#Ea@T!#nlhDhKd^a)pRG5#m* z7cUrh&ot389GE#x_>bO1yc1X3Cb+M?1bqgdA&)z4z8Tqeas;ELlPDJxUFtG$gheX8-9zM+Akn-vT^juTv^OVIa#+TMRmi-P}<7I_Rwdyid$zVSZk zZL?TnMl}@H(Kp}xLGqsZ50W2KsQxYPO^(XY^?&Q4j!W+;siToLmr2E4>oW;#(?(b3 zsOhTo&+eJrrTNn@E$8!zc5K(4bCjQMq29(r(MUw{Xc2#lt`@Q5oN%0jG+vhQ-xS?muCVBw>C9APR zLb+WV?dB#oy*ZCM=^sA2DiKF>Z7wRx4Q($QjC%(dDE77R95%oa8TKs^I9^G0DnJFg zxB)HY8fd09UNRRNh3@n6k0C<(u=^tP?Yjtl1-?R$GgKjhtziE9Nu9;a>lf^CQ8As* zEI7Mq0o7ZDT45x<<0AB3t@H9l=p%j9hgyKPZR6-PN+_wPvsWcw->qEG6P?(Z*NIFE z%`#rVd$RuFU8@KepUgI4kRDHf^pMKq{}Hw`>mS~s!mh~v0E6`1{{Z%TS^w~JD(pSk zy%?m0e+5?KqghQ$rKs@&zCY_9-m;3w+ih9deh@L%K3jr%J7Jj`07l z)VbPMTQ;Z4t0oJPq6A1&uD}{Xn!qHFV!yr$1RW-`P;rRIEM+Y!HUx57sd!P4gG3Pm}Qtb$cQc=1UC| z=I?0uN#rZjSEgd2Scu2R`xtwXK*#*5rvI0?#!kij!%#2BwQ4S4OU6s>bgaNf-gz-j zY^)FC5FvbFzJxygm(W-ICG;7-gua@K&}Zm_K4U0gL%(k48D2^KOku;Nb)WacOzQIr zfjVgDHjCB)M41ISZVbUUaGiezuF!23M&rtbhR{qOd9SmD%x0zZ(keR9U~8@43ym^U zwB417IedZl(|V0)%G7ht7gjMXp4T zeFc3)XZGI((udyy>EpXV+S&lp{S6>l8bBJk9i)$M2kDjDK_YhJdOLk805I~LAT>W_ z-x}!z+DChOOuHlWU;w1%@<26bSYOCph5OmR1IKKt=IrYWxt^qZvECtt7~Vgy@cy18 z!!e)xhkw3`XqZrDq8C{f$u?mlw_4@gYGJ&0k!*8*5;Q-st9If^1Fxihr+Z54Y z1MS8dnihyfbX?wL*Pc{T?<%i$b)T0wz^4y);0YjgL*&0EKynU&bl(t2de zUFoax0$bHmDUKHl#AE&7KGsiJ+`PeSY5~lrfi3Y)YysSuF2@v%ixzr;HMRhrqqd&s z*l*O8#Kbhz4WFjGB`ufY5UINeeHjI$f69S0kOPTPK&n(ga$bbKhKta5=SArIwgS>l z1*A6>kj^O}#gx2_Qz>4X10S+b9>C{E$=p-`NYaNYg5y23xZOoZH(AO&fKQK}ejL>n zMXB0x(OF?rhdvy%48?n`fIpOh)pu8R_`)As`s3z~!r*s03c_Dn&c%(wvJP4xcoJR2 z0+O7eJG{>x9LLXT(d+=WTx{?H{)bV`-rKyu-qr#?0o*hC*XcP!rRNNlo_{ww-8aKK zqvaM)o}NG`I_p?JWw7xz-dYvrP)BAC?y;gT7cwVmFcV4c3En%nZ zwW-rz$S;5CA9%6oU(Xledu3)WCo^-W^aanGVBdKYSo(tJ8(`o02B_)_o?i$1&aZ=; z`hw?W*mqur@g#@#otM!#lB4&XmuWr8>GqwMbu`J9?mI7+cAv-96s9St)kmQFDu(Ee zfB!Du@Bfwl*=uh-L;6Vi$I8@P|A5iGB3bSB50p1Ol&o&@4@{W%aI$)ye_$g2NV1yu z58Tu&CaatM113*56vFnd=ftG)h#O5bD2Y9GPhKTtKFm8nniG&^>h z^oOba*%?BwtM4M$*Afi%PW)>B{v&QMwaVpnza{kv-~0nc+tqgRd}OGLaex2^(hiP{ za|&-9Lo8sB^&!Adj42niK3%AC9o=|FN1s41qF)2vEYkE605I;l7+jNNj^&*+6 zL@z3-^9n`E2I+&uPLM+y9%>5x+z@)0<@p$0#<6Ktze-%`jC>+ zr-^3C`x9wvsioYbq;jLQwa7BwqohVh$G3oOyq95(0eygGJpsgS4}22vZT!Q=#vvyZ zZSrl}zUh-qMV;=U8k)5j0|@^{VJ(eARv>Rh_?HpVwxs$oCvnBxB+d}}(ZO<_I)GjP zTp?RUw1+yt;QP|rgNE*L(;7kyKaST$?L6Q~GChetb52C{=Y)oCrhYh@iIX*mDf|bE z#-pTM3ge>%#@8u;?TA3;z8y4@vTl%W{VAFMN_`Apx}Z{A83z2z(S>2V=nT?grC1bR zV=3yh@VlE?zM&B!ua)&-($<_)M0u)eH3^auj{;6azqGIeV+mBrFVb zLzHEmuJ8}d}hCB^(Xi|GCqv;U$29o+ql~S@ zL!kF$z^*yX4ZUM|FAn(a%vW)Z+R8i`?9^#)=(y!zT&q6$NJjWC8w#Uq}e=xJ`TV|Gh&&;w>8c7GtEL*k!r2Yp$s`xfY#t_tK@XS%YkGuS& zYlTJUfn9)gqx)RUXWY=ZGRC8%+&PvfE0f^Af>g&K=}rcz_4GdfFf7kqsiRfv_=gXz zB6X%+siWaRy5~xr-`b^+hA-yJPhLuv{U|@fRD_k(4@a%MZob}gxr>u;LylYCJvDV57Jj=mi?_=A1XdcY)7YaS&$m+p%#g|o3%c(sP&nNWLh=8%W*SL z>Ja#=G$8f$A)46HoAUN&ex<3TzRupJN@6to9R^9886-W%5SyXEXBL+S^}b5c7w#Hm zo$DR+=LvN*yqiV!#?53jLxi+X?17&#NGkIgLT2%$putxuc80I{G)Zl66nq9YzPb|JKB05KX!e%bSi}tqgMP54(KLZ?) znMr5Q6u;ESle%xp%%n4Fiw8!Dgp<9I_ZcMJ>jR1SpS0Jlx~BWTkl)*Jn4c?x3uOzOmVrGYqC1S-eX@-;2Vb#}(f8;Wn%N}V;EOmJ@1HVABIBRvf$9CYk>N}D z9eg#fq@GhWy#C#D+Y?={$R^f?+i1&LVxhFIMLf+K-Atm1I@fu$U-K;Be;sA{$v>p< z0~sYH8$HY3Y7V7%A zAyjd{TmxYLOO(OWa>)7AN^R5Mx-J~|4;QR5dz2K;z+ge)8wq{EA)fhGj|}@bp26ig zh7UG1@@V!#p27Xu`@eQEd=^#y|X`MC0$L8NMe7IFr##VpP3wU)s*g z-Atkm-WD|Y&l#3ya5RIgb9g3E2;bsq{EO^GRaXqeAu?V=^rt@9DcZusQ%L4{OXdU7 zEFkOB)%tEy-VoC8Y?vF`S!VDksqvZ3;_P7ClgPoGLUY?zgY8YBp_|a`A2a0t2czWw zTQb2wgAb|i|6PVipe}trK2?2Rr&t+wshWH+owvin??Pm*TDD0vhZ`+gkCOU4edG#% zP|R%^iRU3-e|L!nNnm5VOp8mdH=z21j&v-STJ(D|hmg60SWAKMU6x{xl6p67=NHN) zbI%EY=gOKyF#x_@CY2iC5%1x7}2nh{mRX7^sbt)l9I+)UUSgdO&LaT;IDfwdeO)XL4_H2pPg{3QYHg1igQh38 zxb(44yNDmJK3FR*6&@8|63)ddMI2w?s}zp}=X+>emobHX9va&->>-Ef7FLR#!Zkl8 zlVH)sE*k$iO=iCjhk8L;0ST_d`ME^(8P6!&VG-f8QQZ98XlcM1;ih_F(m zTd%#3Nz6y&jr-D;7BcRp%6S?nsfom2xg~F@+BRq%`q;mvmqU3ly+z(athrnCQFOWk zPtZEmxv&ElX+MwKHfS7ljIj`Do|(37&^a!}9P9Ls3o-I!c$CCF9Mm9**pOG{>6Lql z{ek_@9AtPJH>GLOj{|xpF~1P)WD@u3-X66&shwoxlJ}n7{$RRubo?-^E{tv^JLuSv zMtf<2+S|5Sqt0y$dHO{fKa{3l((+)x5dCsH{bJ)VtopKZ4o~CB>0Y_%U`X^0XfzM4 zAT6vBwTWUxzvO&scQbhly)*xwIlPm%4#VoRoy#A)pW8H0L`~qH87R^`w1UQLn%ncu{vW{uAfsuGpd-=s-@zdcIEj*@!x9Wr0(Lt0;@c;<>ereeU-_+Lg5 ztE3EazT6ZHi27jlG~#{jU8V8lQd!0Bq;WJ2_TC7vNVUN~Qgyf9J6^6gY;luh*HQYVz9L9k6Abz!5+sMgga?C^m2 z+;v)kJo&1N#+_-^Zm${FM_T?7(rd&u!Q0oNH^6#KF5b~VEbRtlBlhqd6=F^r-KxK> zX!<}5Se2`tp!S=*!w@>Mo#87r6MF9m2Sj_&{UmZwvDr=<2NXi}B6S|&$H;7QID2k8 z@im|8G;|w?X2QIxX<3=&32y-R947j#fu-=OoT`tl#BUuM1@^JlhAZ}iA=K1PT6=FS zUyH)--`6++2i_rVl9|6UJjYVx$)zSMV54|sG4UGw_h~B+HmwD*8XQc6&B|*n6sy5+ zrpYcHL}qKr+J)gwVa`(O$)$8kU@}ZmQgcSz9D9!i{g=33izIcmw=q9A6nYJ!5ClibnF8;4kyzpjWh`v6_@vO*Kv9SGnaN0oh1Hp#-_8deA{LcJCo;rLpLoJh5yEK zF0Qj6TsfAEuh9}78G`f%or8|vX3=_bsXe5$6v9oUK}7J6%eaZOm&OdV|JM z5~Cg)A2e>MWa!>+tF@oZ8MmPN$}VF7Z1jpe?)vV1T4GmSn-8fCn%c4$^H_P%x@9~= z_ugmGdvd72_Y_`~)$m}S7lnkNtNXs4H{Cjur*KZ`cBNthOJP@*;q~DYmYO~$A!w+nRrgH& zKFgbC6R1Ju7p_!{V<~)#3U$U(*2g3`4NNuOGj$Ei8&s&1%3D{Us-DULe6U^YWY%XCCPn8NEUWH$W47~q#=u)iJQTzP+#RY!C{Q8n?i(GL35U6uk* zF1372?^`U-G|+=b>B=XFuN<&vwC;xu-4tGvOUEH{w+=}cRR1fzf#J>7bS-`ATk1QS z#u)D+x!yqGwK=faerV`kas{^9N3`|Lq9HiRS1DEo{g#_Oxm4X)m9KK0#=)G*rS|3Y z!G)IOb+(;tOJx^03O=`O0T#`z?6L*yD=v2tdrRuBeXKCJ#`0O*wk2QU5bIVvy16L) zlI7F5o!3|pUOO5ZwF21x9OYc+R5>I3TdPA7@qLlGhm49t3Vm}rO6E7RFV0NTo?hXi z@V>0N8gd%cIHZOU*k?qqaf;s3d|6pt*|pQ9iRF3Gfww_JH?8VfIzX#Q8D>DGFXX7>Epvt|^;}GdpaZ^$sURjw@cxfINb!Dbp z(D+QmU%r8MpjeMc)^Ze({bynW5gWglpUCg#iME{;-F673-E!tqvh3OX{NNUgf=cRW zuDS)yeq1OKKa`6DlfuLsHYZ!x=j3PcV0%GaW*#F^p!uJX^y#A)HL%*K`raRXn- zs^$(?Z&wkbO%~x}H^i zn0dbskxeO7GT$cpf-i}ad6i@eYy z?rt88gIeDZqMkN~TT~mVAX6kB3RXS6%ccEvskl7c(+{(j2ztTTS1As~$(=#)2*4Ki z)m&g9S!XkRRNe)E|0c(V^EMEJKX}K` z?F=#e)`O%BO(thdmv?|oSo!73s#$F-ej^(UsOdNIc<1wSxfAWs?bQC{SU)v6n|e5d z-sn}^J2tj&<&vP~F|;EOolPzIrYtgM<>{6@+>va78cX=`cR`Bvm(DVTj7`P7p7*U_ z@UPQ(jFi-y5h6dG;shS1JkZV!A>$sGHX0n+xS=W9flZ+Dt`_infnD-OcIhEh>mLrR zDUSGuVKrFIZae>LVVC@zb1$MXN1NUGyE9rE!(yZRO;X0bsG~5r$la?QH0~VRC2w+S z9lEH_Q5e-Yietcj5;yWE<8O*22K-IovYKP*QT6JiN8(WXRCK5K63{1ln zUx;m%H?l{P0VBcj)koTrKy8*c37h5T*iXCO6ptjiHEqdF)YbblrESSZ^-k3ZQ;BR7 zOOsq%JHC)t1h%zLyk{au4d|(Dt*6zM@44@>e5I(akv8Swwzty*db-}dy*2O2x!CoW zM~JQJjXS@=RzKxeaorSPUyp01yr$}ixp9a<4=z>iF2zK$cE|z9rY?+ub(b7~GSx26 zrG$4ILKM&N+7?otOD)N0cvF}_WK#oUcD|u|-g1zfA^M4}2N@n5jnQ6t2Y~&FSg*Vr zz`iEhE5B@jX&inwz^Sp{b23NemjUcgMcX?3!+}{a8NE?e-z&ci&&%Zt(av7^Ehn|} z4&SkU+JWeJ)${ zgnYo+7T)JNA;0CE9jP(*Bv{7OWHDt^HKQNO2RKrGLVk-yb3asbuRE(9(Ff=Rq6#Bm z`%r$J{ZM}0*`Ur-Z|TU|fwHORvQ4A3C(d?^r|1*p$+HTwp}SBN9N`$SGVz=0 zkfhw*cekcR>(PgZPn~XI)H6IZ{=6F^#lW&XIwXCfLuw469O_BZQ*QEU_&;``8TIl+ zsW?i_7#F=QoZqp}rr7i#qwgj9$J9s8FAc|OtIm>$59o?~8k_@9sXeWMr`sT zo?2Jl!tmvuLTQ_{2!W++5z|n%P-vIJ`=s7}`rf1c8aUcd!}CF8W%;*wvet2OLi1}P z+Bsf#U*wr~n5?8eQqW#I|5ZF6*KP`wa8)}>xKeWdsS#>!7SWV({x9T)!1FN)cuzKUIalTz-(r>)qh(8tI6xOfOMPZ(qgaNEQDIC;ZBvNX{6i6@ zr=w=x(te=%a-7^Hqht+snVdNalyEcjNUFYqdsU!>Gw@Q#8s>(6WHETMsiV0G>#C>g zPJTG}Av5lt*THskebY-WD(WA$uKGG|xRuzL)zhg{+|Ub_zr>l5vy!uk_-D!PHAG0; zFpXuAmA2G-q);}+jL!0cWtNAW1^N^1#^Y(D;2&;XP2ANJJjW z32k?kaD>)UNXwJmx@l>!o90hHLp(zFK2h;*l@+l|-M=u2tL#s_v1+&L?*zi-AI~Hl zpmWTuC8)fq#Jh3P$*#Td+DKp#od~$8I}8#%@|dkcAUit~(=0D_=V^B$1~tQRs2Pb9 z+z1Z{9{La)bgwf8RT+wLLm$j6@MKfHWL3IO=i4N>q)k$VM6cTmq;=A=8d0F~&>Se? zh*WQXY8v_Pz1vs3#cMoD>hDL_co2R=A%2jA{-rTy_z08&OP_NwDx#`ziKS-98?2{+< z9oX8FEGd3np43BNi^=;fddsVwZ$7oxKx2lkaFe_d>*?x9NG=YnY^O8&~znLyGa90aP-702P}#ntNTI*hkvmEyF_Bz&vZA`|PIOGO+Fe zm#xTsu5 zzDCT_`#bYEQMUb^q4*(@&_Wv}>%I+HqK%17`zP5HXvTW_uv{hS6D<0JY~nb6>Hw|# z+}(@~x&v~R^mgl5>etyd?e2LW#Ol`-dY7R+OUH4)>6(WPnpYMvchs+2hF)Iyc0A92 zqBn_*LqJi8EHOJuxJf%oxQ37+*trg=I%$7nu_v2)Ym6bgC7prE#PaLur^jzvN7XV> z%DPF?c*~_-(v>|mbw7{DW(CnXAtFhiHR?Rs)b_D!zKae_qp!M@)Z}blhZA_c3R`q9 zk>2l*(d+cyW$2})!7&S)OxA%~*{9 z8-LH%gEhFCnT)G720xA88vBI{oh&$ryU(@H;^*+d>UQpL*Y0d<*X*>lGds_T^v?Yv zwX;n`J8dHDwDH;0{4sX+x%k;aByoD;^OoJ?_;P*{PYu%g$`+ch^y+wEUy<1z+0<=g z4xYrQ-qey!Imc{#xfj?8E!kAYhqJwDQ&<*l&&cho4-t#CR2%-ju*e~R8ccv>wp*UQzMe^Q>pt< zX1{n=w6qKD@Zvq{bHDohJDL6MXWK203Xj5z9`(6beZC-buEQ$!$^k>KycyudMzyR- zExS9@D{pZw7cV8tHv)UCA1rrx?`p}W>NEQvz1<7!oh{ka^o&EC>uuy=?p%*4f^4wU zKO9)Bq|W3VVo~t83;|?ox-J$v7q9RxjGKH9#GM_0HKPy48U9FIe|tCC?Q7KGJHx~mMdIyl zFF;aV5t48rk{&HU((VEzeN=#?;Q}OC3z2khA(F^9qQpWZJywXMRfR|@Eke>;g-E*i zC`iQblM2xrwETnx)ZAM{5)xE&sNQN0@W+Qq`?nP#iNu!?oEt)&E6MqVGJbEE z{p^g!Ezl?Q{U;(VJ0>rjEYy$x{9=-_r>$vK3<&W3LH%KfejQNSHCiMNW!&Z;M$ zhT_`!`jG9qSbPSrP1{6M2VhFw(?dLBAp~EL2wi=sfbgPC--70n^GBJO&PTji?HMKI zP-8d{zV|Rh2(2#t{x|>ny@$x!?3!+*x9siu=Cp7if5L-!Bun^tlP1Wh)DT=#`I!r1 z9jR^RM5ThO;^dOBP(lp zu$XuXFVCD^N%OT$XWN#qTvWNd%|zl5Y?(MsV&~Wj{wigZ3zF)GEnUFOogorGE@v4> z_&=IU&B&6K*so+~kVGh2gR`#iTIzO)+ADn^J7p(S|KWn7{NAz@>RhSiiB`4+H*P?f zMoQ`hrLM`&*I*sfTKQ3b$^EO^0MC?(-Kt#JbP#L>EwB?_+T=pVse@88+KFD;=Auu* zOK29nI21=Op;_p~;W$KYe;+}6@W{=mN$<5`9Zh8BWAj$MN!;OrSXp>0=y|D`sYi20 z;)IVoLPu}zJV@RPzqRsDgy-BGcG)9y2+imUv(9J1G_o{pb1|{v+q?N4-KZ%Mcgf6L za(0K*Z(P~4Qb~OjDex3}S*)Ys@~FgO9rTz3`U>#{7sT{oa?XpXM-9Zr*IkjHh7e4C zUu5`a9{%uQ%_FU0lg}jjhoNoX2ncO$NBc|Em>nhc+X%O^*E)^gm*}PYR+^gFM=1PE z`rOLamDY};CZo{SZtbvPM1LS}cKUH(wXNfbyoK$+6DeEAOUtp9-2ZW*tz)Us(0zcc zC&@l*up<0z%Op=W^|IXgIQ?#wkDS}RIaayAAsW@aO?`7uzuCAy(F?uS3f?Y^r8X!I zkxukdX2Ixnh)3kjY{0sdoZnkb-Y0c$e7M(&I^KWy)kH6_kBp@rQEVM~c%7HvK;Q`$ zwvMmj4;LX-uMnBet|IYF<9tB0%CN^$}}A2ZnO{QifP zlqHw5g!pvWMF%J2rp6fMK+N{z7< zKwDnrh-?)w1;v|!mf>GFTJZhq9p!LDX~(!Ia@0nFt?Bb$9$R%WZW*q<*Me(N3)513 zF^+IC?Kq_F%&O*1mYj#CjL^K@|nb*RAhH?F;2MHE zB+ijGLKApoE#@~0l;9Z(P-rA@uWLZ#atY(SW!(D$GXnRPaj2CU;qEQt8e5r>Kw}{X z2^RJAYbTGTzALv@khNd~H_>Rov)yhCdWMy#?0)I*jZEv2&vNX;iC; zX|3k9#8WxZM^>du>b)FTk-F#eeva7F$UY%(QaUkLfd-l`i>;fq;A^}(BLAP zjA*l19&rr=<-!5VEJ)pIE0_b)(yj;$cG5I&5TO{DGjSpdKQBU3ejF2d7{~7q((6mS zOY}x^suCl5B5#TqoSj^u$0*Dci(F$dBo?{kn5~@-lNfd-^;Wi)&&x+Jn~cAWW^jkm z49*bJlW~0YizDkh@b^%O_p2_o-GRllvFR$d)?uKmDz@(R*3T z#L^NR4IwGmPIk_(v`X3}>$X?_4fML;s_SAdk+op`nJy}g5}O_`bZ>f?*f3;wY2tj_ z(;7!bRO^@&11n<7cqKKE)7xxo!D{fCg-)SeD56uDe)v-CbmVQFd$iswtB_+Ki?kz@L)0a8SoZ zt^Rv>-QYaKy4!Sv^KK&JK9l+|dsrN8M@^YjPxdJ>-TvC3(Pi6eY}(sp+qg&GVfa{A zbRsOTH*9l#xuq~-eFCgRo9}Vmbh0b#ZJEB&wtyRQ3fmHe|J}b@)p9 zt}ktgDyfBvJ*c%2jb&SF`-X3Ko&XE$QBoVmz*2pMZ%@28spZuK2bt9PtdiQIoQs2P zqSv<8NO;ZOtNXHdmn;}y+UHRhW~j|_D{CZQxWU-%9%yVc3b8oY3ca?qqw#{d$ibZC zhI(6zJY%Vc#;&K>?}-GceY{=NSes7>ms&e#7x*p^AKUDK>M#FB0o?cky*z*$bA*^Nk|Q+lDu&9@4;a zgg?ltJChdHgYbJjNRPw>Ig`g)CXg~lLe>Q%OnEGHvIE8mM8Y;FJ-}* zrB znLCMYA~H$t3Eh^EX914wK{GfHn!z^IB@qrMSs5F=iWMTyjafZqGxsJgp&G~>^YiTk7w(I-^Zc$ zcx-u+G3MU}_CJyndF>y?U+|eRBAD*`NQQk>6j&wobj~~+xSNXpe}uh#d=pjLH-65{ zq?x`zLW>aES|$x(+E54-w1O`oZBK*6EsCosx(=f5RMZC1wdiV7S``F#E3Iy6bw%sC zC@M{%y9BHO@!i|q1i`zsD3z`Zw1Sfon8{n``COBt-uLr)e!oAUlbQ4WdY$WhukQtz z%s-4)Ntk7$`twhrtf4dm9e`U7RsJp^Di7vzPnVrPrNPO(bD znREF*{jQ@m62a?SsysOXPql#iPqZj6*#A%kd&LRmbp3UtQF+1MqP%N|H;u}>c4(pG z^Gf?dVG()IRT@Ui7VDU7|tgd9aOaGvSJ=v zY?w>J>3dno83_ zYF1sic-KoJ#GkFjze8Vl;h|l34q=R6s0$0bAQdWstk;L{*@d_DiTx>c;k$NCD6I?M zv8!&@^%rm3)uOoVjS8=gua)Q5Yy0D8kiMZV?Ak@czGg*UdwiKBeLCf7$uxR#t_Lk03LiZX)*IU`dG0UQ7{W(UYn$ z`lC~6$*Br^9(M9ol7p?f7=L8_{e7C`p^MU?XMgWenmCZN4k(RolOH4{kMc+EdA&Wb zU3uDri*xNp+o>Q}73a8O@^>+0&aSMI9L|ZZDZHsNn^)y{WU|JNM^V{)wvZ`NR4h2L zGTU6w{iiFN&#aunXD*J*SI6qPnEbCeXq7>KrOHnpK~yYlqFcID{<3}W3Gx8+^)e$o4139?NSn|;sJh@ac-uasF8@?mN z;!=gpcs<0T8~FjABTj|AbD6?kb5bZSUB)A6orbSg97wunFAf>#v@%HZaCX;)*X!Kf zbniiPrYkQ0NdZ04>la>sv?~1iBbO8U!s~y)Qbm*|D8y0d!uB<mA9)_;_iunt~ei=k@Um9tjeppa|In);>B+vNsi*yOUQYUo)YrG zII(7~6%wX50Bdiay|b7}8!zN9CcvyN!LAKr-P)W5tHv;bCD}1A5m{n zm}}k$vA9oww}gLp>k#q1m?u^r6YR>5@UW%Xw3;p(w5QIkVLjlUJzI1(3IA5>;NM zo)JL`A0F+#;4zFp40%;%pu z(6(lRq|FNJ8#eFO%5ZcP?8}h>F@RH4d``>BwDUWZ^-eQuiR$N4D#73W5BvKJK&1XcO>D%=~4>a zz8PZiyfS7ejd{~)3#5ct>Q;rl=5=R!8GY;}^AuN1{%rL197Ew>{QsHqMu^qJzt?km zb4qxpgi$R|6n5qfFfync_&bD>v3fel9sEL}BgCevvS;*aq6Bv{J~zAAG_d`s~0sot}~SA6d6+f0`WZ)DFb zdwJ;%d^TSuv@d5Q%;c7q@nET>I8?dt11e<1o1Lj&Z!^7-oebB$9QtWBe^!J(snzB@ zmOfTk??gM>gIsa3%)xQ`Zrp@{hoF^`{uW0Tnok$9d@S$c-4&IBiI0lu0?pGt7tiwU z3R>fK$P_ZYHwbM`98~2~{%nEbf%h+6pvWe#$J^j!gV{nF4D{Nj9$q|~J z(IAr2_qr=+!RCc{l+VcnCn#ti(*#<$*;}clTqPmuGXE68#bci0li#6il|m_Sua1?^ z#K%NrDdnMrSw6swx+?%<>aGZ!L38K&()nWF4Lq^{qSRfH#mnLyyexulzDyWTC;^$- z${!}PuE7{puD^jZRY{00AI3N$j~})3N&E-;qHW>zP6Ki{4TvH7ZkFWw7MN39F}XGI z)fq%#X^8@C6x%Ce@{0-Ne<1_A?cS~nsER(E*+u=zwv+AtpYPcoRlZW4WTC;v(=Llv zuh~m)KwM52U|B&ok+cUrKZZJ1<*Di~_Mm_v|BY6TTM~1;_-d+Pp1($V2G>ZJVV1Bx zZ)RZk)Ph(2z@vvlw2)rf=BN22-qKz1>o1%B#}{a2=#8lbulQ-f62&1bVU#RQ#-22S zx;J*N@nS;lK+?OT>2IfPqjun}u!p5;%q(!z0N?zhlBn-STTy;GnLv<4kFmOdUEH7H z9(Ve;3g6j0b_PO{zHwh@x`7SgVyf99+(bBn=N}`j6*IqYR`B+=T=+_D4F%8@Y5CWY zy<~6bdP8OJzL3puZD3;Wz7S_v7}yuG7_JMv9kSE?U8%OJUQ^gpm+7Zs`m0=$hoxdE zSLz4$g^COXfqfynVJPU5FiW*(DR?K<3@5Q8!M8)@G-a#pO$%{pt}t2-_7{)}>rc62 zU+6wVq{|^a@4<6iVUO$cE|kA%z$H%OXH7gW{pCZxyZ+ zH?OS3ZKfgGkR8k->|0E6dKum}#hazzDfWVbKu(A;*!r8x3;OnlkO5kN>c{Qv<+&7bC3UGHkx6QQVlu5Vlr_6 zZ*%1x?7}a6A>#JC^S%?&6~{%BWHgxkxL6dS6`1Cx3Z@+|%omXDVsL(09{Jy`0WFsi z>>|uST1Z`B*ILdZKqv@*D*@~5+xnnHZG>(fzjH-d)Q6VOk%(O)aHc@zr~sy?z6MlIa8Ma&^I3W{zMe*(vh4Mxe%Xew!n$w6`wfA zaz^|j1G_)W!0t~nup1pv)mN11MvlxW$n!&QTO=dB1^x=H6==3axb|CWewBpNAf48V z+sZA1rOy;bcSDa(^p~6OGq+YiFERadp+xrnlvzi=459QQbF$Cv=KY~m!;Is}Ult)f zWXBv~=C@XSe+sw3x^#2-^ZxN~+s!wZrG;?X27jiKl?y9HYsIHp58)u5|FH=9Q}bIZ z4v02$P{ea~hSJhM?+S>=2)<%mh)cU&VHR#tI6L&wWx-CO8(>3f$))jKQ7(V|f%DB_ zJw4Bl^0UdI5TZ-`$Z}a(URm0(p8c>K2d^z_Jq4xAR&Y*h1)3EO;Oj=jeW7~|Y?xa` z1@?ui4UY$RU*Kw124OzJT#THiFtS?1o)v3Ch_*?_^prk_voh>i0UoKQMmNQB!k#)N zFx9to2-8S9h{_G8WQ7n=~N}zGO>A1CrkHjDOo%mZ?mcX)kn0uXqZ>2W}{ojAJ2KgF|}913D~S zV7JpV^07zGKHpVQ)-kM02Me{{qzu%3T!Yq zfXv^EkVAAV2T#|5uCQp8CZ(rYF0~XLm<%mN%?dy}trn^FoZ4G$X+f$TcCu0-ThMRC z0^DWP#y|O?QZlCJNJaw=RE9m3M$5O!@e-&EAE>MfGi#5E(4W)IFm94-T5HA5A6U!h z;$BiFmXbblyI4wY6SKpfDjdYcXn-p2@8ZQpBPmq&5M{VNykggRNCW2J{ML%}VIAGy zwcB~2|I+#bJuxj{5t3^Gq>~xM^Y@WJxvl^2!z|ic{+Sw_frn84=!?%HKi8AOySo>}>bLQ-@=Wdg~$UGz_bAvUc zwc-nr4XMTB-{#28(T0(`qYa8h$W%$il_+A0aB=8|tGmyksypV&x5em0U?xQ`qn5GwV!eeTZk6b0K@|Lf&H9@b>!KLg$j z2dM1bb2AxhBnCbfSdHa{b^bj}!^6a=Jm>E&e-#iVB2 zxi3sFIa80L>HDXkd^@>g%{6PT9b=!N6`cN)xMwUL_21x8U`Xsdci_oa&z7y;bB;U- z=~3U7NeuIy`0Ck3PwqMQsg}oGN1cmVi(xwEUOju=>KD!$pXAQzpWJiq6D@}BD2meY z&T|#%e;dxw;f3tgyF=>r!@;@U=|exP#l_iWFFAMkCy}|8^zbKi^I7zy{hU7i)w8yr z(`Wj-&M{Bo`JQw7bbUz2o>1P{enNSp^QIq-=@FTV)JP1yk)Wpj9NdiCOUwT1{PVXr zlNAKDE+!GVPeCDj#_eP&L0h+xw0vY?75rsH{+F_zY$B(`%f`z7!dc^L?p(_1J?B1M z4K-!@ljSDq_my2L^^d_0G06*=bjR~k9YXVFTv(k^iaY~Xtvj@+bo)5$?#;mN<>Rm$ zc|LjL=`A#ZyHNXXB>h{#X6|w{14;P`HZ!562uYV~PhhKJQjRF6mrnNqBJi+cC+?nZ zrOe*0*B`}Z&=#=Dl|x*L)t^F&gkdp-oE4SsQb9)y1lg|Z@6^IBIEtjtln1Nh-gDJ^ zoO(?&Go<`jU0r=|Hk@m154`N05xg>IE-@29z*2q;S;zIgs1VI={TYSWRrxm&M!44r zIew-5M`X&b%rk0yix^?&^&vUq|R66V-aLwLM7;jRUe(HC7NBTDW~5BZpo z1F7=+Dihj_;Et3D^^T!wy8OVF!!G&B- zJ%+5P-`JzdpDCb+3I|mAkU|TaZ9fJ6X2!0l93O@7arxH$Y&SAjNoq09XYIJYln3?` zXaTT~P~{za!Hxp@A4`8yb!1Rzb!G;b5SwBraXA#F^YneH{GygiQroq{xz>j*Kk#V- zmglQ3s*f}~nP63T=Niftl@E^MV#|7W&*)fLv2?ErDKdeo@bH@PuBhBOYI#1(=NS3# z39^W7Feo6j|JNDv*mi2HK2k9l-cBVPq6_vM)9uQVlU!MJ< z)9SyBprW*IE!Bm@R2G$M6N5s2H8R`E2KnGEVDEMJcl86gG>z(4p1E??-bXPd@fN7Lc@b$7yiCaD8i3eI2@oQ|xa;PPx-V(dvLSqip6Iu}KnWD{IGp%xWHgT`!k z1yzQxrirn;*{KgqP;eEk;7T-84mLYc(AWdNA|gd_nX&tMXBNRhQ?{`uw-(PuGcN`e zv83DNd(mukMdddVhDwzG^%-=_W@l>f3h>LHRdapUm@`~anNM8t1ey+acqx}>%wwav^HZHEfm@a7$mG36nQo`Otrd7a zQxpmUg8mJI#$B=~ZArf1^rhXH_M7yo6Ut0ax04QHi-m_Uzg3up`<)lQE-gQQxV0iA zx*XsG6?jjv+c*okll~`wA07#84>ALn=T{$4(p~#Nci)&ua&Kksg)wC$VE=T3w^Dds zpd}rhRl14K^0L)&xiF$xwp*&g{f|(KDHoRXKIH$%fZhKzfc}gjV26oc=wIDhfwv*6 z9Dv^|R>M83(P63p9pcBE7}6QZw;M=NR}-m{JZX6TPG_$lO}A{$>DuXJ1B082y6$-Z zv?u?4%MT5}1PBt$Y_JgD2;2$DaQVT(+N}N9vdTU9P|oUfuXe_J2%9<5zPh!72~9$A z`B7!?p%jA5?W^JI-O-H^;8GZ@UFAcwKJBZKX!LIp%>di}x|E;98YvBZ3eV^x5#)&m z0Z^KF>(|Oe4;!+kx=38ERG7SZ{b(ALyGp|8z{8+B+^W#r1G_VPHBue(3#US_awm8A zfi$m!G*u++*x?N}JIL1Rri#5vp>eM=lS}Q&?0Uhe55l+09=P0#@*M=&=ODL76!235 zoOlotVi>zpyXu|hK(Asq;<@adnO%D$vy3l5`{nOYW^%m>%VmZK>U4oLt3C)GuT1`N z9G<6BaQY5$oHY{6414NK{xmKuqM18_T>>gx7MLeYlpM^>z)$rYv@n##OdLe*`oBwB ztd;aqz5d@dq5@!t`>+UY)8%7BCbU7JI%D$ND!fNlrXRkb!t29#?Mgn?h40=~Bhk!V zS|1FH5boFMyTlr4Df1iXC#F)n>1z<~s@8=jvJMiHpH`W?-2UNOWSbY9Rg15jB&jKL z19+BAt5p&`XjJRKR*k_3*77&Z~LD57B)q1S@H+_)+YC zAl(a3!w-QB(q7$K0r6(JzlV}C--$KSWTsz~yT=n0x>t`vkLqqyn99xGRl@5+sbr#y z9a*Ive5Dt^#Z`~WQUbRl8+Dwkj>+}vF6ZeWV8a3Z(;$o|mytWG(aeA z+w3iuOgg~8sq$78Se6*uhe2eikqr8^D|G{p2|9_<9Tid0k3nd`Ts4UoT3d~57Xz2` zkF5l3U8ep#^i)NI;2{PwiQH9PUYR3Uyu-CSz0h`32cq(_1hQTX>O#3`OG!*_8)fn) z_7B(6l8RUChBrTro&na1F*KKcIEAe!PYEVbee*Pop7h+X02-lQJ$-asfi9S>*Byb| zlYb=6h-n3pV3st^KnKQ|;oUolG_xf3Dv0wE=Bm{t(hQpUkF^G~9aB-7uLVDc{ZdCT$PH-}T1p-r~U z$@WbR3~TGuug1~p)(WU!-RR3A+|xljp-?UhsCj77%SLs1reE<(3__dekZpEga8r#` zr?WIBc^|k+R5VrCM&|TEtmR4m&*ugoYE*F3|GhFoj;9lY59xkh7g14P|H)03v2vaa zehoO0R3OO(JQRD297NxHP zwiBB-y&7&T(pTy%U-BUBGND|=geK`nf}3+B`FoK6KZc|X3#f(pqaC#i zy&(UYP=_0Kp_u$>PtpdPF{|?Q(N$yLC!tki-~ZVIxXnv*aqyv>>Sg;KBl_aMI*S7T zxZteI>HEip=j$E|I7TkZ`l}O3TRgzu0E`asYqRGc7wYSbLGTy-Cy!0&;8zQS{IFnI znLl6)I7U*7|LVL}V|;M;v{o2HQw)IsvYrUYFviE2re5E&YD;p|q#a+i<@GH&U720& z*{HxF(~#-)!BZpz=B(={OGZywkLq4Vvi zOZ-*XUwS>I&$9XCrer>N;pgJXP2A>7F*38m5N8Y>K3}3JeQ?#5j%NlR%6TBmJAuI7 zim$~*Oz+?(j#wH2YnSAac}sMT7}vlG^1|qI;(Tw1VB-gc)x4#8m~Yqcw|^9q2-#oK zua_`=$i2~LGOO~fiB+{0FYM*_xnuHhyrb6kb6>{f!T2S%8aS~a^CUZ#4k|F#ObAQw zYbVNFgr$FKPgaDbE`l;;i0A)HRDk7qQTY~-w`SSV6-8Z_BrWhduBBJqT4CD# z=9VkF-g8b23_gV4;>e2X){6I>KLu88!B^$4&glx=V(Y^5S3Lt`Eh(p+5TWOh?Nk8g z?}^MZLjS`E1}P2Lbye9hsv+y@Kiou*tt!(3c=LywQoBkY0BMKXZ0Mt->(7_2I<$$} zoE&wBRv}BnD*E0-53P7$wbxWZgU|U@)aD6YosoR*=IjG!#?L*pDW~hK=&o=+KyP03 zAQf#m?_AyHH10_Y(wjRY`3@Xy80m_I&oi+sOHLQv2=|4?;zO&Zc<)k}N>ye)fWN>u z!*(;3CJp1*E`YQRaxL)QYiBCyF`v@iPzx*BCg;q)nVP0+v=q^u**_YR+;+ zhGiBUa?e;L^xkeSGhTJV^J7fjb^UO!a1+_4Q1-q4w2&TuZrtSDL{g9AIl!Fe zR+&7y4`c{)%sS8)LUfv>XO1b%0b0`2%l&sc?^JAD)zBtP4Kta|0*Al$eW)N0GyEll z;+8F^%kJinDU5x^a=PrVKR>z1w|q>NHO?I6&tH>%5zjNuWoLdHOb_8SC=HsntbF8n zdWgbMj+rWxx4$3KsT%r%S*8@)4=Kn4zu`HV13V>jfTwTy4y_%)--LkxSL=!ilUxz` zFQdqk&Lhc}NFkCJ6;17LsO=s;WXS1@$=jk#o}quOFl5w8dfhT5AE9C0W!LgMg<`Lb z*a;vYUx|WV3G_dJqDo_ct(|4UT3%8&u!kaPQzFT;tTX4hBJ%G>WAcMhWS!WLW{&IM zS-WTWkRi42q;a*tNO~rj3p24pDE3)NOnxX@Be6)=DfL*$!-NSL^(KKWUZya)bIE=u z{oy2XF=zzV05U3HP$9-GQGp<-Ch{Mx48Xs&f9&=-ArJiO_8Cb}?giZpk`9h$RWjrb z;d0XC%nalaSOG0jWYza2 zxhRUPseK7~lS&K7#(aC1nQ{F`#0#?P*`L$B%n18DO&DU*bO(h#l#^>u$o+AX&)74& z@O<#1h(abBUo%m`von1tKifSb&Mu4wXa(ECBHIm&9N(#zaBI)A*uBJ&(JwxA8LXdQw zLf3jo2^sdP@_VYwS0kk}DXpv*Y{WUj!ilc_TJLJ%z!_93@D;!tJpH7Y;d|8lso0^t z-OisERk=w;)`7tMpF^T)cD_$UGlv3~LR}DRBqI~h@OwcK`DYlh8`si=BG^91JG(#$ zW)VDhO6}}|XaKMPFz#6|t+9dsv}UF&B4;PEYiAd-fx;Um+6xzBDN9*hjcjEB8-GQm zRmc@s-)ZxZNY~D`T^mF*t|Ci(`J_g|bm7X6&miXGGt?hU8Xx&&TngHse`hIp_WL1Z zFa*=QvkNB&fm4L8-R~XT2>$SB+r&VJFoU3J=>z%R*@aY~rCj&*$zy05q?u2?7FP*Z zkX-VmNRh8Zz-oR0T;}wDK@I88#p{gN4gK_6W3sORYi9CYYfg7X=8s|pjGaA<@P?i}+90g(=2TaD`-O$tK4Ge; zkup$nr+`@(5vO)%5WMwvFa4G(pG?5n6}OoQ-3mTu!1n@RDxxCHv7w*m*sRfC5FYA} zfIv^l+dw9gsbppU0w0oQ#X*bvym_uGA}^132*{=cs9BS~#cu%yY*#{;$Moa&R>AJ8 zk+2TUUJyW*h5S_miwKh5RE*vlDMNQ&q-Gsa*rwudmv9OB?ifQlcc+Htr7a~<`J$@J zqx(3LkQc^Ih{qIe&agL^UrIh#xJ5C!T!EEhT7n5pqrtPl{rswxmV4e%$~+&PNwH*D z8Wm!H)r+QI!&}F^F?_D%E;=DDna0FYT1w`fg!N6gTjQDU6t5+~8~1<_Yik{Fc3w`v z$Ip=jlb6{~zm2y63V7Kllb700x1(u&8v%(0c7lh_F!%M-L^AB9zQK+CDQQPl`IE#d zVVUPZ+WL(8esuKpO&d^^@K&^!R9-@Q8PU z<}IyXK(>h*vsngmSHS$Kk#q?Dhu?5s(~%9GTS+TH1$-b=N-r!4a`N8sFi;~NKb%whCt24~~NO~v2xym9^6VN~<+ z8T2O1En`5Z@v+|)K~{!L=tGtgvXfWkC)Jcz!JCk8jHV65#%7i=xUf1`nCDAr-R?uv z#@3nV3WiwvW&){fuQ)DZTWWA&b&h~+!vQ#nek~?sTT~QlB;D95a#GxCOxnpl+c{1{ z-wr0sgeHZ66M9LN8&&WHf-FocYSy)XdxpwXBS@OHsSM&;vikjCIl6%*av9}B>gZxv9%tpRi4 zEyoUx)iymySErEzvO<%I%lg*}AOWxCoda(PsNlMQIo~vg&mEO};-GWhDP&jA_4aFV zDcj^=iuSHeNb}`Xr~4R-#jVOu#orND2|M{LZ`(#Zx2;~4U)Ok=KOPN;dK(U=TK*#f zFC=3b5U~vhDa&z@vEd+X=@oUhZvrW{qd~ppu-K4`f^cp~+N8O=KN60dLAMT%m3w^9 zR-LoD!wc9~Kw^VVqGi-h67ugOus&@USg$H?8s!L@mXPm?oD*}&kDx;-O(B~)H5TXp+to3BQChT%v$>@yA55a8`-t+;~t%9-QW5HvH? z|0w^HXsgC=!xv~jCQt0gSDh1IbMEuMD@-K43cFO5FT}=qUn@5RdllCGnZho;%)4_V zF5X$M%9G+~c3%KS>{X-Rhyym)gR^VXM_}DAeTxvC1|U*>^}a$ z#N8`a)4TE8FdCV>^nToaIgej~J+n3;@Z(&coS}5898ZAWQ|ig!5^`9f$x<(FLeq5o z4xyEYwc-b{M!Jpp5mq1OjQAPixI@D20{E~7oULv!)6Q1_XKy7D`QZpfFtL-U{8I$1q~@x? z`*2j7XULL4{v;d}uJ&#b(uDV%#$bojmJ|!3S?T;(%0y zHrB7i78J_RNL0oN$l;MV;{GN6ICic9?(cu7zCV#sS}LhwSk zbe~1Y@vSuLT@l%<(E0g~Q~BAC4~vw=@;LDNL%P7RQ8)qa_(}zaH27#C$5&-$T@kre zq4V+d?8iBxTbz(TiGr0qd<)hD3O8;g|7wkB7xIX4(~z zZX$_8b;Z$gr@CxvYM6?ZY3mRfZ}v3eE?9Zu$WQmX*AnY{|KFH@!=*1MQ=R^WN( z#7jO&aHUDO#9NzrLrM2#LI%-!r}(ZjgY3;IZf{hcAKC65))@aOn?CTi&>*xq=>Y6) z`T;8`U2WkTR(v>K6f!Q<$d4#~D5n?Xl!@!2-yFzCokPg0K)k*7sr-L#UZ41ObU z-*WQ_5nnT{>y-HN1h`)nyzC9g+!-4=PsOqjaMJ)!5N?8#j{9d{gMjZX={78xF2D-F zs^cniG-lqZ>NLSh7_((FF19qn$cW0bW7vFJ0G}$f#qzjiGhS$E1b-x##tYjWm0wd3 z_&(@ycaQ&7pG4&s6^5Mc8c4DQ2lO`j*kk5#E=69Wj?-A06Y^^j;GKd~*<2ElL+WdF z!0AF`upWrW``?GJ8pCi;*MubJ^Zz&huv}`;xQFKloI-A8n{&>uytkcD?rjpt#jaxt z@+4#&1)dXVmlDMoN;fbhC8&AQm^OB!)bN}azXi4?zl(rw7q?zbI)+)Q$@#qhKsMqW zWk@<3ff%Q>vjzBEQa^872zp+sE~PLn=onG+w<~vYkLG)n-*G6Px<4jA&;z=a8#H^% zabzpW6;g=F*Ke+HDe@`Mm5nj7=>?d(|BRG4?v8GdanomBydxr;6JQ@6k&nh%-+A+Y z#3C<6ZdRDk2CeW7Nii8<5387L$wea`g(0Ne`3Ca@OxGrw%(tiYDw5nb0)WLd-WfNL0>n7E zeR0_|Y8{})Y**fP(#P&KKj>0qHSt=AO^M4dCT>%hYmVvh5x03n>PQy>imz7&@EPMN#J9p%o$e;a10 za&lfQBxt%MZWdnVGrV64gM5?o&0#7f|5&=vo^7zD^SC!=-X`8$HkW4w2Y4spT?EPi z)5!!)&4fLo5a{967}%q)m$ z9~7@4gJQqJa&3I37vg@+7YjSeZDqy$)MGn_b-IwrP;_A_)ms(bzUEf3Sg7Pn$8O)s zd1$FC67YX!;(h1!;p$y)hgb@Hk0|oO_)5{KS-51CmhwM}5K4`kwN~AqU10vt3xIfQ0fzqJZEwdPiLDP;~^}3@5Av zxQM|Q8mcz=ZZtD4MSeLBcLBiQ`tAG3e>f9l1MqXedge zTn%`zxeB(21D8CsCgY`6(tKt0Dz8^5v+Hlj3VZ7Gl_q}{0WYn9_HkFxmB68}(TCjC zz9fDps~a~Z|fj>P5u1iXc> zrh#SE3w^LExP?)9o66*!?i&$}Bq3WgA40!T03!z>VeKnTpqagWFO4DQo>hoFD1LJ$ zWoc11SA>I8XXp0zI2RGC|5{Q={ywZrRpjrY=c~J_*1G+|EV_b*xV-jKeeA}b((3cxg#1yQd*GhxCTCV)u)0O5Fy>@)}G%Cn? zz8_iUk^;gDjY@?bOE)Jlp#1FM)kYLu-qPx2UO*^jNffOMU~@u#ZGX}p2XqTm0S+SR z>HS#y``vy(;UH;yEQ!s@eZQpJa3ezsYcr*UAvO4+UVjuxuf&j*?oX?v^0VE{fUOqW zsAG_0Nl%A9dK5|H;>dcjpQ^<9=fvMSIPT7J;L~82@I02jR8{$?Hp6sdjQqx)RRXew zf>Dt#=eXq#@C&8NqPjiA(aW977l90vx&%Dj=hsq&P}+tV+?eTt;L#qW8YB(vclRJa zb{h0TVf9%zGGC0c3aFknBvHM53r$LlE;|62_AH_E-7Ngk<|KqEj@P9F53kOpw zb83ry9fHM2ag_9!GS||<8+)K$w`jJ>y?md53gba{1-t`WrW4BP^)Gay89LHcwLw9= z?xptyEP2!u%8}OrAwSOhg@Ts8Q~8C$@_Fu7u$j3MbCh(IGTjTlL4n!vk@djU@EbLy zDWx6RM*89VWF@8Dyl|@RbT5AWX2l{s^Z{}=e1P0f`H|b#^UJ^2#(tL{KyKYZTV<9Xp8Jn?6MDoBmh4U#Ic^_k7_4md}CML zT^B{he820w$e8bQNn(|ho9ZH|Atn_|6)Iz9o7f$y{N1Q8G}ADmu@vG|$mOe1D9f38 zT{|!v(Kd%PSdT4L5=y7I4IrCJe}FMEx}0DMs|<1N*WM#6J)!OwI-J&CT|1gqDlzm1 z1vzxhUns2OQd+n@r1Ri=-61_%&&>N$oXe^5s!=-cz{rdBSrVP4 z>d?rB`V&fL=N)8QxiR<|2eze9uczt@Bs%rAvL)r9L6{VT_G0OB4O#Kk8EP)*P*R#w zwxNOpBfqat*_Il@sdO9FPANF&n7HQxx|<`6zh6N-_@M1qkP%C5qfowAMpr0|t;y+- z^6Qy-{}Q1suh8-=t%o{&NlFJ`uE2O_vanl192Z8(H2~%(jQcywIL>zg-MuilCim(9 z`%>!-Hwg!QEhL?=z&kO11^Yn=8T5e$>7mkwa0%TIrb`aWF1@W9E3bW9A!BZy& z*&WDiRPaJPr(r0aW(xYdZdNSzhM^qW`5=sd{X%8=7rl&`-SL&eb*gfI0@}eyA3WtE zSSlH1n+}TXPU!P(o#cVaPtS+D{^hdpZ- zX`z=SkW~n9`3n|TNt08@4O1u~KNDrl`W;^>xlO8EHWtgF#X@UmoVu4&<(vev-q?S4 z)D!WA@(iwCt^X6qS{f*DVd+na24Zz#>G{MJmF?wM2d}7XbzT`fp|p0IU5kg(({CqO z`a>emg{5_g<>l9h?|*O6NM_cWQ^|FJPN3aubH@c?wy--Wb8@zz1mwFiF#$A-e}*}h zL+9AigL8mSV=0z?1Drrhv9vVttn>T8H{zm^%;I0>+V^o}(KX-q!<`O}`!N%{x4%lG zH(sSt(t<C}jumo9Izlo^w!?AITIUY-Q#4;+8*93CP-1Hku%_gCcACN98v({sh=R!AEv#CC8hDnA|>!^8wS%30T@5!PaxZR}?)uD?%EO2jq9@ zJT)rE_rd$TN_Tg%78^QMIW3m6IE7&8VpK;;cAFL>4ogzhz8g!S2t!KEfWN;#PUmIy zXWm#%Y&@1G$EbEQ5r`$ccWtR;r>W+I+#Y#=AhT7#(zuviyG3+6V)Bv?s>0vT)7{uF z!rxvIY4?~=|I=fB6fV_2q5M*R_?B9!?=}g@n%7!l!SeyusvCCguorfU+$ zl3F}d7ocXQ2VVAqmU&QIETsDGHUB7jYLV14+ACHH>0Xn-`W`f&6wx#!%~yeeuSPO4 zUx{fj9=d4(WETzJN!;E~JadRmu#%kW)`}Fu@m8NrFq3)2s^NG*7w@icdFh82dYhG6 z`=y(pI_>@kEV`2{0QAGf-ezSTqOF&>0l>c{w3pEvP@3!(pJSwQj@c#4_x%bj6i}M@ zPJ3MDl?}UFly!Ezuu)lOUnETMIYw5`5k=4~Iz}Fzb5eXQpSmL3&E>zk<_@ici>N5`I`;V&GF2xmhzn7 z_nY!JC-Kfq@T7)v+Pb=_Vv-jm?knS9cM0g@Z+yT{j_i<168-Eg|NhvF&G$TTW!Kib zoVVly+KC6hi7z?x8}acsz^Zr7ry>*TL^1iFYKyXtD8bEvk zni*OD9{9J0Jqw5+*Pr$_3dg-cFI#;8*Z{{gluW1-U+jv>cS34*TnxPf+OY0On%$y# znF9Wg2mS7zrC#)~!+W*&7pxNoE;_$kI|nm__ulSJ6()Fr*$XTI0a4p8fUIn)aQBpW z=XgCrlTvHX^1^wb_I-B+=bhq3W{;4N*Srrl6!4WHJK>#DYfQ-Z$HAKrEdas{e9K&V zYDKgFcWNsHQw1OxGl=9pz0U|={i<%r40^xPIA})$DzaSc8g8&PLhUTVifW6O zBXBBCme1Io^k}@soa&NgCV?#J^^3Jp`k48G7*JZ#p$%VplKHk*n<`*@!M&*Fd2g&O zQE0oqghb@4loqAlj%-f^T9mq_sOS$tCbXA5qU_bYJMsben&oX#>bQJwRrseh^Ifw1 zWgO5vppP3_b5S%2mv3CP#iy`FT>MZrThV%c`by!;WIPT z_>_{=Y{S_|dagz?=)fl?w9%BWfcH1xWgdQcH_X=-O>%-l$+AXc`y6+h+cVvfdb%&m=mUX$JhTS~&8C^0Zx*pB#lAtG5Go0Zktfu?60@C?5NhUWg5hh!hRy zuVfGY5XTlBfj&MdqUi&Gx%DLN7GB%3YD;QYPS-XkdwkWF*S6$zrFN~zKB#dQKOnxg z<-RSc8Wy;yYjMuVui}|E4{l1v11zw4b57Su(Y*PGO%OWYUX;WFkLB_GCd=kzSik~* zzbTmqUihW>{if-gFU44#6Na@@*D^MaOS%~^3nB7XfKY*UhQ6eIFY=`D(Puap3ru{C+ru*BuDI_ge1Z|N&452&9qCF zKh}8YRr%jN$vISXM%8?-TYXR>D`7NT6|9zC-3*87T`{sxUcC&QgWRi3F() znOwG~(+T{+1!RZcPHbyVduoMbt&w$7AF`~j&l-UEt7Eia;Y)>8JiRfEv(yiYm1Mya zZ0G>C3P}1oimZKoa3fkEAnCVJSp?sDFM95d{wV}3PeY^UL{EW3+U&6jtx7GI?Z(`P zA}(-94W3q|){bpY2YZ!|>@Sy70bKlY`Qt$}^RXbrbi`YgS|dDtHj20%Vtqk%5Mm(P zeg7lIiXfVKd(bB2x`QG&^S0p4wcG-_aGAzeJCQ27_O*f=$HFfTE?3si)^j!?o8PN2 zT$`s=N#WYoJRzD376$dRu7+@2OZog@sW)5rOj*yhZP=ka%eAlDplq=BDx2-d<_jRM zwc;P5xgdWm)x6+%i5?GMHzt#|M)!Uk*?lSS?+Keh=0;=w7i# z;?PR5M*1E4od`HJY0)@>td9mz!6Si20nMz@5Z&*`=5i5vpL#@TGS2aW)C|%GSRFUn z!IxoyR}fVB*;vy5U5oOB`wFjPM8C4YCCg_NZFI9RvJ1S)*{~+|iITA<<4RI~9(*GH zuQXfjzer*re=)YSAQS4;A5l8(rM?zroqLzpF=AW!Z_zO_b>)AFB_t;Ak1i5W!Px-J zPE}qM`$eiA6qCC!_#rI#x$GY)EpB8PY_K!}8Z#-kC{>NZIHD&je_ts$%rEm$r~gEf zo*C-`iz;#cA>K-CLW^?5m?zMdMUn@1R(zy1AwcP6G6fon>n`>FfkqzZLo2l?y~aF& z`Z*-{Iy@6-$c^ydECzRIhourYk3Zpg2R{Lwj%_HlA zz?;hdY46*^+bXVo*KA3C#fg9^6$qhAc^M?Ooz zQ>F35X*C75!@)7R#rTU9o8m;S*g4TC-J*8ynK5i7w8)`KxOirC+G=6bUxtdDyQG{x z-0gOBGp-q*_$>MmYTG;*f`KPq1lGrN{Q=nde5xI&{9IgbFgypQOOaoW)rWQIT%JA` z_efTr-N)-6O?l+C&(n^)_Ibwj7a|v~=!LbY6>CWCLk&aKK1AhNc^Q~sv3}&Fp;5RL zd3bF4h%qx5y`$$hpJl=CK40GUyU$D7vR=ek){9Snri1!(*2;xj4t}PCXQOwQrse%E z8a!q+1*3;b>(9+of>GTu{ogXCeSA^-r4IE^6b|0!*+X6Kk88It;X8leSS@O zR_(W<`rfK&Mroz+YBbGqF(O~UvG=9OcTfxQU0x^`E<_Grc`me5*d<(u)Lk(M&xBy0 zU^bDr&L(pCY+Q#rcG@hYJuglEmi&?|pGdF!Ybd?$qfmO?aOlfjWF;3RIb4);eZb!IFGDc!+-xFO z%^`B{Y$88Co5)ZtZ|WKxJ@bFQ#pQ2uplo*{plyj5pNUG6KgB{!oZ zBlrG}RNi8E*Qj4&E!4<8A!kvR}E^M|oSHSYXAedGP^6vXZw|H14{Kp*^@`6z~SsymcXz9o|J<}14rk{Mqx40wEx5pWb&h4oWr=)%CgS=pL zeouW^mzJlrD7@e94@PGV=LL=iJ_-b*3x->|{z>^%`Ot6bZ0j_21)~dlBxf*c8YWdA zcBPtvQQjy?!DvCLExexuqj^2S=#rDcXs*#>3Pub0U^L&DVG2eU8*g(4qsvOUs$g`v zF&Hf_)sK{tV003Sg;Eo#BFfc3&MK|ivFpkD80x`Can`1Zo=0kWhg zg!kc9_8d$T=AtHh{{~Z5_4!Esm3y5V`c_LNeXFH~eaANA+M9fW6dMM);*7xpoB@IJ zp;qVYDkzGcwzsr6asTqo@I?p)-kOd3(K7|z4{>evehP)@r*((PQ`!B8OuFjx5z`fu zfagV`<}&i4-f~FO(7X_NBVlg<{la)WyML1@qxyU#<%-T3be>L4eQRr9p0vL2h_k2< zN1Lj)G|sc6!Nt&DCzQRFtuDoMrQcyCVrgH-OFNQK8tU#{Vmh#f)40xx`g4~e!|a54 z)cZYjEZPV8B#-ox=TaV1_3*i>*FM)*U5-2&J!;K7%{`sdzs)qQ`h4VPmvu*O?Q3=3 z(t>9L!AjJ=zYzH!O#9w=LVsjh|8CR2g<73YwR{;mtF^&v^l;y?u}pqN-wXFy!$$6f z19(n^@kEs~r|&V7q56Czc=>YVvx~fdGBAOW5DZ{i)P+I~w(S0OtbIE!m!nlirbCoI zhsYVs{wqAc2DQk0;gQ~7kmn%$ag-c^r>^TRE+&IT#j}RUO7f^lAcrAb5G^jw8ag%t z_37_ih-A=Qwn7V*ef@KXq2PJ0C2n$ie!ddTLhzwnUe6(fg z`Nf((f;RP*|BB^^R%KSU)6s4S=R}|Hos{EQ=1I zy@m|Ia+b`5@I%kze#&{mbm96ww5r1u>xNMO48pUbD+FGsKX;%*U8lYMdA`svn7&qD z_<&~96z457g!*&$cR+a0^N?#fJ9j38+nx^}pDy4IrtJPQQ%Uvt2)Xo4=R7Bvn+DfQ zzwNi2oxbwB*6HsZAFbFw%SjAIT=zW6g>lb@Kfm-N%KqINh={L;4y-Q=_O~KNrwubJ-l!F~OaM z7b6c`wk<5mp2_wm6$e0wc^qT6?$cyxvT9TV$npZu)W!{!s z@MoL1<*Al=Ti$Jf+|kJQFGKE}>Y2i5u zL2ed5Q%F00KJw8e$km%Tc3$&nB=jp7!1IpTY3+;M+?0p!&ZIiEGJnpI*98S46(o{ zltTDe|2?UOAsC6pzvyQvczJV7Zz$$(!g?m@cD1$ghTQ@mPNCVe5>cf-vQBYthp1nV&B#PC11uk+5V_<&Ujv2bK%h)n4bE z8%{G!8@jpga%AWV=C@RsRXrN{!Ps&kt9E4zG0m;M9NBe+GtH^K9NDSupqNE3M}BoB z8mc&ZsGKZ$Ap`@5&cHBUZ)U}G3$Bl2o2DL1J+{^|-E#DM2Km|V8RXsCdgRFi(=99K z5LuXmvO3y>f&3p^;k10>CZ=~i8aaQNl#enwZu=aRr_r+T^dYPrm@=wIBR7qu*Jf}*=(tv?s^QPai9o4-QY&#)C|mPV<5G>Ez( zl&iJ37*F(U!hO=53?pfz{#=hQ?Ktk8;I14SMeDlindytR@L{Sm9^dYK+PZY`jc8`Y zf3q$bB6;=af`0u)UEayB4(b>5Z~gVW+83gk;L*2*Yva@^Bwtko3FZAcm1Sg0Su zav!98-IbI!fvJ9Asvr0-)eqQw?#?yEZnMqjZuZ&S zoua*2@<@Kk=8|p~OYD$HcgukiI{?w8W-Z#dpVBLrqT%6_Jy4*m;~Ofr)l`~HCcaTr zL|>=q;3bb=^!Wm^KLhMeNj6LFZlAwd@^zHhC#I+pTLbNUo!2Azy*}P2+C`~TbYx6q zY7jk+rknmAb%$bW7x^|@z~zs#tm6wx*Sfls^05Y#e~52eT}?cv3{dOtaZ6gLHK4G< zv}gc}PXuJq<4`&^s-v~ttzMi4__QWUY?pRf@|M_PS<&+15_4(Uik0Q7RmR3yC(bE z`3rKcTexW7op-60_5YrOo&^>-xxfODV*yK!1t8M`09LSo6?(u5C&BvA2*^Jh0r^iO zApiRa$XRDWPR0NLC@q9aaxWy8WhLKC!j{4&awrL-w2Iu9ge?O~?@z)g^~1N4FcT>7 zKoV8}UU)DG%Y_d3b`rK2d`SqUc_70zN$3*zS`tF(qi_T4g>0f;@hL`sf;19Jb2RKt zh8>0*wK%#zGprXHfYMei&$pQWBv2Y4c8&L68CJyp9U9-bn@7Y67*Dp7nedGXSUzbY zMrfXZQMw)|ZArq`0j0JH*tKvI%z}3{>~&VB>tF{^`pyKt`LGk_!VC?2oAE7#n_+gG z>rV_@0F-WwV}lG^1e8|9u_1<`v&6AC;@F0GDCTat3ZeAtgwx09{S+e2q+z9p>Ck`B^G)(&a;0+fEhLI;7;SKw2iG@IMSeH`aiT@H6E_g9A9 zK`8wLd_pLFA1Liis`Yz}Co2KvxyOJ~qUE=l`T5-AKqBb5lSB+bI7M0r8f{RPNj4=tMk{$>4dtgt`i<*eA6dT zo&ZYcz%-!r8jjLW38jRz5=vJy-o5c_vje4T2&cvWh^`GscrEVI@>oIEbB#dhbVBKV4J#w-xEq1eX@t@q z4WqP>P|E2tfYN;$wwx>_^SCyW4wT-mVWou9UBpGwfYO5+W+s&0O4>!&K)XI-oQ-0o#&LLdl9V^|3}a2qtmpJ+<&f)&8So;dPXLg}4Q2Kmqi z^MFzgDE*jFdOJ|M8eDO{4+y3EU^%RT_Bi%YyarCNYUnV-R5R$5N%&G~T$5FL3Zav0Yim7szUYbZbS^riR8EHkj<@8yaisDw=AwSWQDy zqZX{J-?qK6eybYOl2!_Fa`kwyYCLEaDq`s?;;5Qa}@2yp8V^ z?Ko!k+ge>B?-Om>s5xC7Qj49U$Dc7_2=BD{9BiPf4(-R|6S&->JAo-aKcIBlZ7x^x z@Le5yvr1{LoPZ?Neuu{)wn-i~JD~V|0XyCst+{GEoi>-`;1$2kFD79PmAuPqb1diW zwtyl!_}0C=&BIGt3XO{Brk$0|jhnXbXxygdu+7U?dS##2E-H%Gr-4m=n|%*o-zoaq zT;47X+~Kjgq;{;E&5qm}TqSi%4iWRdUG#Y;w&wV_Uu({B05_MrGV-5wWfVNSk91jJ z#&Q5y5Btcf7JzctM^;;QWt3O|HsJU<$!)NZBm{aU$G9ZEU62w~p*Dbdz_MAIlG2+3 z0J|V{oVGAVOYKc%v^0(81Tv4XY?r2_^`0ss;8SbL$(M|?2Q z)*!ZN%s)CG?b`tSS);$F#s8@JtzNGmUqjK??6ygscv-DJ$kGyI*ujim$|ucmmceDLzo_PSIgz|IIG1eGfK4 z0wg(HqTi+6d}b!%T{g+D&MYT1;DmYX1l-2HIulz> zYvvL=bUD23<}OFG-R7~2*y72TG%?$RhtlS7wBoZWCSQ(vClhEBt_ka&bp1AmL-t8t zpX8TrXSvZY9;@g11X)ZGeUc4pXLg94X1{-LQ|WlH4CohcHG}*^8_0dlAV1y=@+Z4N zF0+Ar?QW3Ipl<_t$8NRnK(~H3$cuJ^T(BGDCCH1klj|)2H(0=OgJnN#gpG+4)}q60 z(?kI_&(1_2SGOAZNB-6CYk|VEudyaNDDpZUUBc8o&$rqXQOjOU#Pf=D`$UL!HS6Np z@v@h#Kk$;md%S+WOY%D<5AS!1C|}t3WB^|v17D!9ev0P{${pkXYg_@0Xx>VfqoknB z+9+&wpGP$eQ|MdF&_G*dIf8=d&TZw(!G*=9ZX=u?%uw~ z5pc^W<~IApcI=FNaR39&c&8XyaeBKjqOcgFvGfp-n{Di#gWcJG6F79k=o-u(FD5G?hsv)+RY`r@&TpQA$DTF{-F=#Ko`gd6_6iSK<-yS z9#YhI`JDjBW1S$M2!Q1zqh~9yFBD%p!TjLc-(>#atS0971Q#+NZu?A?*$@3f z^)34~8NNpI=UAS45?%ksJLdd!^M|(wHx^gs{OzOF^Ea-0p!B0}@7=WFH}{=-;^%KX zeZ$Ise(tTj^EKCh?Vrz8UC#Q!itj%0z@O57b!$PT_s5RHl$Y?63;_9BzF$}UL%(Hy z@a-omV&`68<1rjR{`{lD=-9^3b@glOR$Ny)R^4^?EjJ7(``@ph8&LcX$!m5=t<5f} zH7-_~onE(ScGx;4N3*iZtoZEahMnbRpD243Gs<|_kC_F@=kBukM6>L&`P;lcw_^4L z{Qhq9wt(NiQwvKTyDQ)jwHW*EmpDN!iIwXX-QIvdUUUKlZ(JhDFZ$e)S7E8_ZHg>v z-$1o309F97!AmUwplss-0F-U+1ppjBdI2x@27$R z3383B$KEQU-Yz{%ei!*nCSaQiBl zf&A%TgDfM&g;a;Aj+tYheQY;;-ec`@-(ip+JUsqQe^?8zJOXmp_d$O6Ns!-vTBSey zJ&<);Sn_xsqPb0Jj>)HSfCbn)rg1PpTfe>vS45kSiK7LIxj=!=HU%@aySz-a)uL?< zuPkB@FtLzv5m@8XxGH`I^68&|eCA&+hfCTNjg$DqO5$yxr^Zun|}WXe@lA z_EnTT?R;fbrMaTAj#tG@-r>W~(KxFnYzeB^i{1i;hW?Yb7UqM0{fG%QD`lb=nl!CwcsB*rIIA%sLOn??~)d8g`ajw|175 zl&vl)ZC_n#D{s5r;aJ_u`ikYy>b3bCc0Ybn)K9J1?y%eJ_z8>&*%g&_1rDGGhd{n> z5ab(Q2f67bkf*-{^4K3he)2_-kG}}=zo4ChH$eXGE9!G9Y5wTTtJT58Fwwv9R78cn6k%T|@5i$fKa zb*1XKa~JMO(k^mJr|iF$PTAD`p1R*ty2Mku#8dsiR6j7)4@~s~Q~kjIyZyi+J>8FT zIt75==!mRmXI%Ve?mYvar>+&^tjb|N7XHuOsZ=6oPFBXrYzxk>pj!-SV4E@5B6AxK z;rtC-9M93}u#N!?DqaeGIzZiAyM;q9)PtELy@Lkbvw2iD;D@7|JxjI7)=35aZy{d&$w4?+Bm@ij5 z-^ta^XSPUkfQR1AXq#k#^N2HhGluaj!v)f + * David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +#ifndef __NUTTX_CONFIG_NXP_TROPIC_INCLUDE_BOARD_H +#define __NUTTX_CONFIG_NXP_TROPIC_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ + +/* Set VDD_SOC to 1.25V */ + +#define IMXRT_VDD_SOC (0x12) + +/* Set Arm PLL (PLL1) to fOut = (24Mhz * ARM_PLL_DIV_SELECT/2) / ARM_PODF_DIVISOR + * 576Mhz = (24Mhz * ARM_PLL_DIV_SELECT/2) / ARM_PODF_DIVISOR + * ARM_PLL_DIV_SELECT = 96 + * ARM_PODF_DIVISOR = 2 + * 576Mhz = (24Mhz * 96/2) / 2 + * + * AHB_CLOCK_ROOT = PLL1fOut / IMXRT_AHB_PODF_DIVIDER + * 1Hz to 600 Mhz = 576Mhz / IMXRT_ARM_CLOCK_DIVIDER + * IMXRT_ARM_CLOCK_DIVIDER = 1 + * 576Mhz = 576Mhz / 1 + * + * PRE_PERIPH_CLK_SEL = PRE_PERIPH_CLK_SEL_PLL1 + * PERIPH_CLK_SEL = 1 (0 select PERIPH_CLK2_PODF, 1 select PRE_PERIPH_CLK_SEL_PLL1) + * PERIPH_CLK = 576Mhz + * + * IPG_CLOCK_ROOT = AHB_CLOCK_ROOT / IMXRT_IPG_PODF_DIVIDER + * IMXRT_IPG_PODF_DIVIDER = 4 + * 144Mhz = 576Mhz / 4 + * + * PRECLK_CLOCK_ROOT = IPG_CLOCK_ROOT / IMXRT_PERCLK_PODF_DIVIDER + * IMXRT_PERCLK_PODF_DIVIDER = 1 + * 16Mhz = 144Mhz / 9 + * + * SEMC_CLK_ROOT = 576Mhz / IMXRT_SEMC_PODF_DIVIDER (labeled AIX_PODF in 18.2) + * IMXRT_SEMC_PODF_DIVIDER = 8 + * 72Mhz = 576Mhz / 8 + * + * Set Sys PLL (PLL2) to fOut = (24Mhz * (20+(2*(DIV_SELECT))) + * 528Mhz = (24Mhz * (20+(2*(1))) + * + * Set USB1 PLL (PLL3) to fOut = (24Mhz * 20) + * 480Mhz = (24Mhz * 20) + * + * Set LPSPI PLL3 PFD0 to fOut = (480Mhz / 12 * 18) + * 720Mhz = (480Mhz / 12 * 18) + * 90Mhz = (720Mhz / LSPI_PODF_DIVIDER) + * + * Set LPI2C PLL3 / 8 to fOut = (480Mhz / 8) + * 60Mhz = (480Mhz / 8) + * 12Mhz = (60Mhz / LSPI_PODF_DIVIDER) + * + * Set USDHC1 PLL2 PFD2 to fOut = (528Mhz / 24 * 18) + * 396Mhz = (528Mhz / 24 * 18) + * 198Mhz = (396Mhz / IMXRT_USDHC1_PODF_DIVIDER) + */ + +#define BOARD_XTAL_FREQUENCY 24000000 +#define IMXRT_PRE_PERIPH_CLK_SEL CCM_CBCMR_PRE_PERIPH_CLK_SEL_PLL1 +#define IMXRT_PERIPH_CLK_SEL CCM_CBCDR_PERIPH_CLK_SEL_PRE_PERIPH +#define IMXRT_ARM_PLL_DIV_SELECT 96 +#define IMXRT_ARM_PODF_DIVIDER 2 +#define IMXRT_AHB_PODF_DIVIDER 1 +#define IMXRT_IPG_PODF_DIVIDER 4 +#define IMXRT_PERCLK_CLK_SEL CCM_CSCMR1_PERCLK_CLK_SEL_IPG_CLK_ROOT +#define IMXRT_PERCLK_PODF_DIVIDER 9 +#define IMXRT_SEMC_PODF_DIVIDER 8 +#define IMXRT_CAN_CLK_SELECT CCM_CSCMR2_CAN_CLK_SEL_PLL3_SW_80 +#define IMXRT_CAN_PODF_DIVIDER 1 + +#define IMXRT_LPSPI_CLK_SELECT CCM_CBCMR_LPSPI_CLK_SEL_PLL3_PFD0 +#define IMXRT_LSPI_PODF_DIVIDER 8 + +#define IMXRT_LPI2C_CLK_SELECT CCM_CSCDR2_LPI2C_CLK_SEL_PLL3_60M +#define IMXRT_LSI2C_PODF_DIVIDER 5 + +#define IMXRT_USDHC1_CLK_SELECT CCM_CSCMR1_USDHC1_CLK_SEL_PLL2_PFD0 +#define IMXRT_USDHC1_PODF_DIVIDER 2 + +#define IMXRT_USB1_PLL_DIV_SELECT CCM_ANALOG_PLL_USB1_DIV_SELECT_20 + +#define IMXRT_SYS_PLL_SELECT CCM_ANALOG_PLL_SYS_DIV_SELECT_22 + +#define IMXRT_USB1_PLL_DIV_SELECT CCM_ANALOG_PLL_USB1_DIV_SELECT_20 + +#define BOARD_CPU_FREQUENCY \ + (BOARD_XTAL_FREQUENCY * (IMXRT_ARM_PLL_DIV_SELECT / 2)) / IMXRT_ARM_PODF_DIVIDER + +#define BOARD_GPT_FREQUENCY \ + (BOARD_CPU_FREQUENCY / IMXRT_IPG_PODF_DIVIDER) / IMXRT_PERCLK_PODF_DIVIDER + + +/* 108Mhz clock for FlexIO using PLL3 PFD2 @ 520 */ +#define CONFIG_FLEXIO1_CLK 1 +#define CONFIG_FLEXIO1_PRED_DIVIDER 5 +#define CONFIG_FLEXIO1_PODF_DIVIDER 1 +#define CONFIG_PLL3_PFD2_FRAC 16 +#define BOARD_FLEXIO_PREQ 108000000 + +/* Define this to enable tracing */ +#if CONFIG_USE_TRACE +# define IMXRT_TRACE_PODF_DIVIDER 1 +# define IMXRT_TRACE_CLK_SELECT CCM_CBCMR_TRACE_CLK_SEL_PLL2_PFD0 +#endif + +/* SDIO *****************************************************************************/ + +/* Pin drive characteristics */ + +#define USDHC1_DATAX_IOMUX (IOMUX_SLEW_FAST | IOMUX_DRIVE_130OHM | IOMUX_PULL_UP_47K | IOMUX_SCHMITT_TRIGGER) +#define USDHC1_CMD_IOMUX (IOMUX_SLEW_FAST | IOMUX_DRIVE_130OHM | IOMUX_PULL_UP_47K | IOMUX_SCHMITT_TRIGGER) +#define USDHC1_CLK_IOMUX (IOMUX_SLEW_FAST | IOMUX_DRIVE_130OHM | IOMUX_SPEED_MAX) +#define USDHC1_CD_IOMUX (IOMUX_PULL_UP_47K | IOMUX_SCHMITT_TRIGGER) + +#define PIN_USDHC1_D0 (GPIO_USDHC1_DATA0_1 | USDHC1_DATAX_IOMUX) /* GPIO_SD_B0_02 */ +#define PIN_USDHC1_D1 (GPIO_USDHC1_DATA1_1 | USDHC1_DATAX_IOMUX) /* GPIO_SD_B0_03 */ +#define PIN_USDHC1_D2 (GPIO_USDHC1_DATA2_1 | USDHC1_DATAX_IOMUX) /* GPIO_SD_B0_04 */ +#define PIN_USDHC1_D3 (GPIO_USDHC1_DATA3_1 | USDHC1_DATAX_IOMUX) /* GPIO_SD_B0_05 */ +#define PIN_USDHC1_DCLK (GPIO_USDHC1_CLK_1 | USDHC1_CLK_IOMUX) /* GPIO_SD_B0_01 */ +#define PIN_USDHC1_CMD (GPIO_USDHC1_CMD_1 | USDHC1_CMD_IOMUX) /* GPIO_SD_B0_00 */ +#define PIN_USDHC1_CD (PIN_USDHC1_D3) + +/* #define PIN_USDHC1_CD (GPIO_USDHC1_CD_3 | USDHC1_CD_IOMUX) + * CD_B Pin works fine but somehow the driver has a timing issue with + * Thus use D3 instead + */ + +/* Ideal 400Khz for initial inquiry. + * Given input clock 198 Mhz. + * 386.71875 KHz = 198 Mhz / (256 * 2) + */ + +#define BOARD_USDHC_IDMODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV256 +#define BOARD_USDHC_IDMODE_DIVISOR USDHC_SYSCTL_DVS_DIV(2) + +/* Ideal 25 Mhz for other modes + * Given input clock 198 Mhz. + * 24.75 MHz = 198 Mhz / (8 * 1) + */ + +#define BOARD_USDHC_MMCMODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV8 +#define BOARD_USDHC_MMCMODE_DIVISOR USDHC_SYSCTL_DVS_DIV(1) + +#define BOARD_USDHC_SD1MODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV8 +#define BOARD_USDHC_SD1MODE_DIVISOR USDHC_SYSCTL_DVS_DIV(1) + +#define BOARD_USDHC_SD4MODE_PRESCALER USDHC_SYSCTL_SDCLKFS_DIV8 +#define BOARD_USDHC_SD4MODE_DIVISOR USDHC_SYSCTL_DVS_DIV(1) + +/* ETH Disambiguation *******************************************************/ + +/* Ethernet Interrupt: GPIO_B0_15 + * + * This pin has a week pull-up within the PHY, is open-drain, and requires + * an external 1k ohm pull-up resistor (present on the EVK). A falling + * edge then indicates a change in state of the PHY. + */ + +#define GPIO_ENET_INT (IOMUX_ENET_INT_DEFAULT | \ + GPIO_PORT2 | GPIO_PIN15) /* B0_15 */ +#define GPIO_ENET_IRQ IMXRT_IRQ_GPIO2_15 + +/* Ethernet Reset: GPIO_B0_14 + * + * The #RST uses inverted logic. The initial value of zero will put the + * PHY into the reset state. + */ + +#define GPIO_ENET_RST (GPIO_OUTPUT | GPIO_OUTPUT_ZERO | \ + GPIO_PORT2 | GPIO_PIN14 | IOMUX_ENET_RST_DEFAULT) /* B0_14 */ + +#define GPIO_ENET_TX_DATA00 (GPIO_ENET_TX_DATA00_1| \ + IOMUX_ENET_DATA_DEFAULT) /* GPIO_B1_07 */ +#define GPIO_ENET_TX_DATA01 (GPIO_ENET_TX_DATA01_1| \ + IOMUX_ENET_DATA_DEFAULT) /* GPIO_B1_08 */ +#define GPIO_ENET_RX_DATA00 (GPIO_ENET_RX_DATA00_1| \ + IOMUX_ENET_DATA_DEFAULT) /* GPIO_B1_04 */ +#define GPIO_ENET_RX_DATA01 (GPIO_ENET_RX_DATA01_1| \ + IOMUX_ENET_DATA_DEFAULT) /* GPIO_B1_05 */ +#define GPIO_ENET_MDIO (GPIO_ENET_MDIO_1|IOMUX_ENET_MDIO_DEFAULT) /* GPIO_B1_15 */ +#define GPIO_ENET_MDC (GPIO_ENET_MDC_1|IOMUX_ENET_MDC_DEFAULT) /* GPIO_B1_14 */ +#define GPIO_ENET_RX_EN (GPIO_ENET_RX_EN_1|IOMUX_ENET_EN_DEFAULT) /* GPIO_B1_06 */ +#define GPIO_ENET_RX_ER (GPIO_ENET_RX_ER_1|IOMUX_ENET_RXERR_DEFAULT) /* GPIO_B1_11 */ +#define GPIO_ENET_TX_CLK (GPIO_ENET_REF_CLK_2|\ + IOMUX_ENET_TX_CLK_DEFAULT) /* GPIO_B1_10 */ +#define GPIO_ENET_TX_EN (GPIO_ENET_TX_EN_1|IOMUX_ENET_EN_DEFAULT) /* GPIO_B1_09 */ + +/* LED definitions ******************************************************************/ +/* The nxp fmutr1062 board has numerous LEDs but only three, LED_GREEN a Green LED, + * LED_BLUE a Blue LED and LED_RED a Red LED, that can be controlled by software. + * + * If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any way. + * The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with board_userled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_LED3 2 +#define BOARD_NLEDS 3 + +#define BOARD_LED_RED BOARD_LED1 +#define BOARD_LED_GREEN BOARD_LED2 +#define BOARD_LED_BLUE BOARD_LED3 + +/* LED bits for use with board_userled_all() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) +#define BOARD_LED3_BIT (1 << BOARD_LED3) + +/* If CONFIG_ARCH_LEDS is defined, the usage by the board port is defined in + * include/board.h and src/stm32_leds.c. The LEDs are used to encode OS-related + * events as follows: + * + * + * SYMBOL Meaning LED state + * Red Green Blue + * ---------------------- -------------------------- ------ ------ ----*/ + +#define LED_STARTED 0 /* NuttX has been started OFF OFF OFF */ +#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF ON */ +#define LED_IRQSENABLED 2 /* Interrupts enabled OFF ON OFF */ +#define LED_STACKCREATED 3 /* Idle stack created OFF ON ON */ +#define LED_INIRQ 4 /* In an interrupt N/C N/C GLOW */ +#define LED_SIGNAL 5 /* In a signal handler N/C GLOW N/C */ +#define LED_ASSERTION 6 /* An assertion failed GLOW N/C GLOW */ +#define LED_PANIC 7 /* The system has crashed Blink OFF N/C */ +#define LED_IDLE 8 /* MCU is is sleep mode ON OFF OFF */ + +/* Thus if the Green LED is statically on, NuttX has successfully booted and + * is, apparently, running normally. If the Red LED is flashing at + * approximately 2Hz, then a fatal error has been detected and the system + * has halted. + */ + +/* PIO Disambiguation ***************************************************************/ +/* LPUARTs + */ +#define LPUART_IOMUX (IOMUX_PULL_UP_22K | IOMUX_DRIVE_40OHM | IOMUX_SLEW_SLOW | IOMUX_SPEED_LOW | IOMUX_SCHMITT_TRIGGER) +#define IOMUX_UART_CTS_DEFAULT (IOMUX_PULL_DOWN_100K | IOMUX_DRIVE_40OHM | IOMUX_SLEW_SLOW) + +/* Debug */ + +#define GPIO_LPUART6_RX (GPIO_LPUART6_RX_2 | LPUART_IOMUX) /* GPIO_EMC_26 */ +#define GPIO_LPUART6_TX (GPIO_LPUART6_TX_2 | LPUART_IOMUX) /* GPIO_EMC_25 */ + + +/* Telem 2 */ + +#define GPIO_LPUART5_RX (GPIO_LPUART5_RX_1 | LPUART_IOMUX) /* GPIO_B1_13 */ +#define GPIO_LPUART5_TX (GPIO_LPUART5_TX_1 | LPUART_IOMUX) /* GPIO_B1_12 */ +#define GPIO_LPUART5_CTS (GPIO_LPUART5_CTS_1 | IOMUX_UART_CTS_DEFAULT | PADMUX_SION) /* GPIO_EMC_28 GPIO4_IO27 */ +#define GPIO_LPUART5_RTS (GPIO_PORT4 | GPIO_PIN27 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | IOMUX_UART_DEFAULT) /* GPIO_EMC_27 GPIO4_IO27 (GPIO only, no HW Flow control) */ + +/* AUX */ + +#define GPIO_LPUART4_RX (GPIO_LPUART4_RX_1 | LPUART_IOMUX) /* GPIO_B1_01 */ +#define GPIO_LPUART4_TX (GPIO_LPUART4_TX_1 | LPUART_IOMUX) /* GPIO_B1_00 */ +#define GPIO_LPUART4_CTS (GPIO_PORT1 | GPIO_PIN15 | GPIO_INPUT | PADMUX_SION | IOMUX_UART_CTS_DEFAULT) /* GPIO_AD_B0_15 GPIO1_IO14 (Fixme Add GPIO Flow support in LPUART) */ +#define GPIO_LPUART4_RTS (GPIO_PORT1 | GPIO_PIN14 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | IOMUX_UART_DEFAULT) /* GPIO_AD_B0_14 GPIO1_IO14 (GPIO only, no HW Flow control) */ + +/* GPS 1 */ + +#define GPIO_LPUART2_RX (GPIO_LPUART2_RX_1 | LPUART_IOMUX) /* GPIO_AD_B1_03 */ +#define GPIO_LPUART2_TX (GPIO_LPUART2_TX_1 | LPUART_IOMUX) /* GPIO_AD_B1_02 */ + +/* Telem 1 */ + +#define GPIO_LPUART3_RX (GPIO_LPUART3_RX_1 | LPUART_IOMUX) /* GPIO_AD_B1_07 */ +#define GPIO_LPUART3_TX (GPIO_LPUART3_TX_1 | LPUART_IOMUX) /* GPIO_AD_B1_06 */ +#define GPIO_LPUART3_CTS (GPIO_LPUART3_CTS_1 | IOMUX_UART_CTS_DEFAULT | PADMUX_SION) /* GPIO_AD_B1_04 GPIO1_IO20 */ +#define GPIO_LPUART3_RTS (GPIO_PORT1 | GPIO_PIN21 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | IOMUX_UART_DEFAULT) /* GPIO_AD_B1_05 GPIO1_IO21 (GPIO only, no HW Flow control) */ +//TODO check RT7 partial HW handshake + +/* ESC ONEWIRE */ +#define GPIO_LPUART7_RX (GPIO_LPUART7_TX_1 | LPUART_IOMUX) /* GPIO_EMC_31 */ +#define GPIO_LPUART7_TX (GPIO_LPUART7_TX_1 | LPUART_IOMUX) /* GPIO_EMC_31 */ + + +/* RC INPUT single wire mode on Input on TX, for CRSF use TX and RX */ + +#define GPIO_LPUART8_RX (GPIO_LPUART8_RX_1 | LPUART_IOMUX) /* GPIO_AD_B1_11 */ +#define GPIO_LPUART8_TX (GPIO_LPUART8_TX_1 | LPUART_IOMUX) /* GPIO_AD_B1_10 */ + +/* CAN + * + * CAN1 is routed to transceiver. + * CAN2 is routed to transceiver. + * CAN3 is routed to transceiver. + */ +#define FLEXCAN_IOMUX (IOMUX_PULL_UP_100K | IOMUX_DRIVE_40OHM | IOMUX_SLEW_FAST | IOMUX_SPEED_MEDIUM) + +#define GPIO_FLEXCAN3_RX (GPIO_FLEXCAN3_RX_3 | FLEXCAN_IOMUX) /* GPIO_EMC_37 */ +#define GPIO_FLEXCAN3_TX (GPIO_FLEXCAN3_TX_3 | FLEXCAN_IOMUX) /* GPIO_EMC_36 */ + +/* LPSPI */ +#define LPSPI_IOMUX (IOMUX_PULL_UP_100K | IOMUX_DRIVE_33OHM | IOMUX_SLEW_FAST | IOMUX_SPEED_MAX) + + +#define GPIO_LPSPI3_SCK (GPIO_LPSPI3_SCK_1 | LPSPI_IOMUX) /* GPIO_AD_B1_15 */ +#define GPIO_LPSPI3_MISO (GPIO_LPSPI3_SDI_1 | LPSPI_IOMUX) /* GPIO_AD_B1_13 */ +#define GPIO_LPSPI3_MOSI (GPIO_LPSPI3_SDO_1 | LPSPI_IOMUX) /* GPIO_AD_B1_14 */ + +#define GPIO_LPSPI4_SCK (GPIO_LPSPI4_SCK_2 | LPSPI_IOMUX) /* GPIO_B0_03 */ +#define GPIO_LPSPI4_MISO (GPIO_LPSPI4_SDI_2 | LPSPI_IOMUX) /* GPIO_B0_01 */ +#define GPIO_LPSPI4_MOSI (GPIO_LPSPI4_SDO_2 | LPSPI_IOMUX) /* GPIO_B0_02 */ + +#define BOARD_SPI_BUS_MAX_BUS_ITEMS 2 + +/* LPI2Cs */ + +#define LPI2C_IOMUX (IOMUX_SPEED_MEDIUM | IOMUX_DRIVE_33OHM | IOMUX_OPENDRAIN | GPIO_SION_ENABLE) +#define LPI2C_IO_IOMUX (IOMUX_SPEED_MAX | IOMUX_SLEW_FAST | IOMUX_DRIVE_33OHM | IOMUX_OPENDRAIN | IOMUX_PULL_NONE) + +#define GPIO_LPI2C1_SDA (GPIO_LPI2C1_SDA_2 | LPI2C_IOMUX) /* EVK J24-9 R276 */ /* GPIO_AD_B1_01 */ +#define GPIO_LPI2C1_SCL (GPIO_LPI2C1_SCL_2 | LPI2C_IOMUX) /* EVK J24-10 R277 */ /* GPIO_AD_B1_00 */ + +#define GPIO_LPI2C1_SDA_RESET (GPIO_PORT1 | GPIO_PIN17 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_AD_B1_01 GPIO1_IO17 */ +#define GPIO_LPI2C1_SCL_RESET (GPIO_PORT1 | GPIO_PIN16 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_AD_B1_00 GPIO1_IO16 */ + +#define GPIO_LPI2C3_SDA (GPIO_LPI2C3_SDA_2 | LPI2C_IOMUX) /* GPIO_EMC_21 */ +#define GPIO_LPI2C3_SCL (GPIO_LPI2C3_SCL_2 | LPI2C_IOMUX) /* GPIO_EMC_22 */ + +#define GPIO_LPI2C3_SDA_RESET (GPIO_PORT4 | GPIO_PIN21 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_EMC_21 */ +#define GPIO_LPI2C3_SCL_RESET (GPIO_PORT4 | GPIO_PIN22 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_EMC_22 */ + +#define GPIO_LPI2C4_SDA (GPIO_LPI2C4_SDA_1 | LPI2C_IOMUX) /* GPIO_AD_B0_13 */ +#define GPIO_LPI2C4_SCL (GPIO_LPI2C4_SCL_1 | LPI2C_IOMUX) /* GPIO_AD_B0_12 */ + +#define GPIO_LPI2C4_SDA_RESET (GPIO_PORT1 | GPIO_PIN13 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_AD_B0_13 */ +#define GPIO_LPI2C4_SCL_RESET (GPIO_PORT1 | GPIO_PIN12 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LPI2C_IO_IOMUX) /* GPIO_AD_B0_12 */ + +#define BOARD_PHY_ADDR (18) + +/* Board doesn't provide GPIO or other Hardware for signaling to timing analyzer */ + +#define PROBE_INIT(mask) +#define PROBE(n,s) +#define PROBE_MARK(n) + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __NUTTX_CONFIG_NXP_TROPIC_INCLUDE_BOARD_H */ diff --git a/boards/nxp/mr-tropic/nuttx-config/nsh/defconfig b/boards/nxp/mr-tropic/nuttx-config/nsh/defconfig new file mode 100644 index 0000000000..1811763a82 --- /dev/null +++ b/boards/nxp/mr-tropic/nuttx-config/nsh/defconfig @@ -0,0 +1,270 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MW is not set +# CONFIG_SPI_CALLBACK is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/nxp/mr-tropic/nuttx-config" +CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y +CONFIG_ARCH_BOARD_CUSTOM_NAME="px4" +CONFIG_ARCH_CHIP="imxrt" +CONFIG_ARCH_CHIP_IMXRT=y +CONFIG_ARCH_CHIP_MIMXRT1064DVL6A=y +CONFIG_ARCH_INTERRUPTSTACK=2048 +CONFIG_ARCH_RAMVECTORS=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DTCM=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_ITCM=y +CONFIG_ARMV7M_MEMCPY=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARM_MPU=y +CONFIG_ARM_MPU_RESET=y +CONFIG_BOARDCTL_RESET=y +CONFIG_BOARD_ASSERT_RESET_VALUE=0 +CONFIG_BOARD_LOOPSPERMSEC=115000 +CONFIG_BOARD_RESET_ON_ASSERT=2 +CONFIG_BUILTIN=y +CONFIG_CDCACM=y +CONFIG_CDCACM_BULKIN_REQLEN=96 +CONFIG_CDCACM_PRODUCTID=0x0025 +CONFIG_CDCACM_PRODUCTSTR="PX4 MR-TROPIC" +CONFIG_CDCACM_RXBUFSIZE=600 +CONFIG_CDCACM_TXBUFSIZE=12000 +CONFIG_CDCACM_VENDORID=0x1FC9 +CONFIG_CDCACM_VENDORSTR="NXP SEMICONDUCTORS" +CONFIG_DEBUG_ERROR=y +CONFIG_DEBUG_FEATURES=y +CONFIG_DEBUG_HARDFAULT_ALERT=y +CONFIG_DEBUG_MEMFAULT=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_TCBINFO=y +CONFIG_DEV_FIFO_SIZE=0 +CONFIG_DEV_PIPE_SIZE=70 +CONFIG_DEV_URANDOM=y +CONFIG_ETH0_PHY_TJA1103=y +CONFIG_FAT_DMAMEMORY=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_LFN_ALIAS_HASH=y +CONFIG_FDCLONE_STDIO=y +CONFIG_FSUTILS_IPCFG=y +CONFIG_FS_BINFS=y +CONFIG_FS_CROMFS=y +CONFIG_FS_FAT=y +CONFIG_FS_FATTIME=y +CONFIG_FS_LITTLEFS=y +CONFIG_FS_LITTLEFS_CACHE_SIZE_FACTOR=2 +CONFIG_FS_LITTLEFS_LOOKAHEAD_SIZE=64 +CONFIG_FS_LITTLEFS_PROGRAM_SIZE_FACTOR=1 +CONFIG_FS_PROCFS=y +CONFIG_FS_PROCFS_MAX_TASKS=64 +CONFIG_FS_PROCFS_REGISTER=y +CONFIG_FS_ROMFS=y +CONFIG_GRAN=y +CONFIG_GRAN_INTR=y +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_I2C=y +CONFIG_I2C_RESET=y +CONFIG_IDLETHREAD_STACKSIZE=2048 +CONFIG_IMXRT_DTCM_HEAP=y +CONFIG_IMXRT_DTCM_HEAP_SIZE=127 +CONFIG_IMXRT_EDMA=y +CONFIG_IMXRT_EDMA_EDBG=y +CONFIG_IMXRT_EDMA_ELINK=y +CONFIG_IMXRT_EDMA_NTCD=64 +CONFIG_IMXRT_ENET=y +CONFIG_IMXRT_ENET_NTXBUFFERS=8 +CONFIG_IMXRT_ENET_PHYINIT=y +CONFIG_IMXRT_FLEXCAN3=y +CONFIG_IMXRT_FLEXCAN_TXMB=1 +CONFIG_IMXRT_GPIO1_0_15_IRQ=y +CONFIG_IMXRT_GPIO1_16_31_IRQ=y +CONFIG_IMXRT_GPIO2_0_15_IRQ=y +CONFIG_IMXRT_GPIO2_16_31_IRQ=y +CONFIG_IMXRT_GPIO_IRQ=y +CONFIG_IMXRT_INIT_FLEXRAM=y +CONFIG_IMXRT_ITCM=384 +CONFIG_IMXRT_LPI2C1=y +CONFIG_IMXRT_LPI2C3=y +CONFIG_IMXRT_LPI2C4=y +CONFIG_IMXRT_LPI2C_DMA=y +CONFIG_IMXRT_LPI2C_DMA_MAXMSG=16 +CONFIG_IMXRT_LPI2C_DYNTIMEO=y +CONFIG_IMXRT_LPI2C_DYNTIMEO_STARTSTOP=10 +CONFIG_IMXRT_LPSPI3=y +CONFIG_IMXRT_LPSPI3_DMA=y +CONFIG_IMXRT_LPSPI4=y +CONFIG_IMXRT_LPSPI4_DMA=y +CONFIG_IMXRT_LPSPI_DMA=y +CONFIG_IMXRT_LPUART2=y +CONFIG_IMXRT_LPUART3=y +CONFIG_IMXRT_LPUART4=y +CONFIG_IMXRT_LPUART5=y +CONFIG_IMXRT_LPUART6=y +CONFIG_IMXRT_LPUART7=y +CONFIG_IMXRT_LPUART8=y +CONFIG_IMXRT_LPUART_INVERT=y +CONFIG_IMXRT_LPUART_SINGLEWIRE=y +CONFIG_IMXRT_PHY_POLLING=y +CONFIG_IMXRT_SNVS_LPSRTC=y +CONFIG_IMXRT_USBDEV=y +CONFIG_IMXRT_USDHC1=y +CONFIG_IMXRT_USDHC1_INVERT_CD=y +CONFIG_IMXRT_USDHC1_WIDTH_D1_D4=y +CONFIG_INIT_ENTRYPOINT="nsh_main" +CONFIG_INIT_STACKSIZE=2944 +CONFIG_IOB_NBUFFERS=24 +CONFIG_IOB_THROTTLE=0 +CONFIG_IPCFG_BINARY=y +CONFIG_IPCFG_PATH="/fs/nor" +CONFIG_LIBC_MAX_EXITFUNS=1 +CONFIG_LIBC_STRERROR=y +CONFIG_LPI2C1_DMA=y +CONFIG_LPI2C3_DMA=y +CONFIG_LPI2C4_DMA=y +CONFIG_LPUART2_RXDMA=y +CONFIG_LPUART2_TXDMA=y +CONFIG_LPUART3_BAUD=57600 +CONFIG_LPUART3_IFLOWCONTROL=y +CONFIG_LPUART3_OFLOWCONTROL=y +CONFIG_LPUART3_RXBUFSIZE=600 +CONFIG_LPUART3_RXDMA=y +CONFIG_LPUART3_TXBUFSIZE=3000 +CONFIG_LPUART3_TXDMA=y +CONFIG_LPUART4_BAUD=57600 +CONFIG_LPUART4_IFLOWCONTROL=y +CONFIG_LPUART4_RXBUFSIZE=600 +CONFIG_LPUART4_RXDMA=y +CONFIG_LPUART4_TXBUFSIZE=3000 +CONFIG_LPUART4_TXDMA=y +CONFIG_LPUART5_BAUD=57600 +CONFIG_LPUART5_IFLOWCONTROL=y +CONFIG_LPUART5_OFLOWCONTROL=y +CONFIG_LPUART5_RXBUFSIZE=600 +CONFIG_LPUART5_RXDMA=y +CONFIG_LPUART5_TXBUFSIZE=3000 +CONFIG_LPUART5_TXDMA=y +CONFIG_LPUART6_BAUD=57600 +CONFIG_LPUART6_SERIAL_CONSOLE=y +CONFIG_LPUART7_RXDMA=y +CONFIG_LPUART7_TXBUFSIZE=128 +CONFIG_LPUART8_BAUD=420000 +CONFIG_LPUART8_RXBUFSIZE=600 +CONFIG_LPUART8_RXDMA=y +CONFIG_LPUART8_TXDMA=y +CONFIG_MEMSET_64BIT=y +CONFIG_MEMSET_OPTSPEED=y +CONFIG_MMCSD=y +CONFIG_MMCSD_SDIO=y +CONFIG_MM_REGIONS=2 +CONFIG_MTD=y +CONFIG_MTD_BYTE_WRITE=y +CONFIG_MTD_PARTITION=y +CONFIG_NAME_MAX=40 +CONFIG_NET=y +CONFIG_NETDB_DNSCLIENT=y +CONFIG_NETDB_DNSSERVER_NOADDR=y +CONFIG_NETDEV_CAN_BITRATE_IOCTL=y +CONFIG_NETDEV_CAN_FILTER_IOCTL=y +CONFIG_NETDEV_LATEINIT=y +CONFIG_NETDEV_PHY_IOCTL=y +CONFIG_NETINIT_DHCPC=y +CONFIG_NETINIT_DNS=y +CONFIG_NETINIT_DNSIPADDR=0XC0A800FE +CONFIG_NETINIT_DRIPADDR=0XC0A800FE +CONFIG_NETINIT_MONITOR=y +CONFIG_NETINIT_RETRY_MOUNTPATH=10 +CONFIG_NETINIT_THREAD=y +CONFIG_NETINIT_THREAD_PRIORITY=49 +CONFIG_NETUTILS_TELNETD=y +CONFIG_NET_ARP_IPIN=y +CONFIG_NET_ARP_SEND=y +CONFIG_NET_BROADCAST=y +CONFIG_NET_CAN=y +CONFIG_NET_CAN_EXTID=y +CONFIG_NET_CAN_NOTIFIER=y +CONFIG_NET_CAN_RAW_TX_DEADLINE=y +CONFIG_NET_CAN_SOCK_OPTS=y +CONFIG_NET_ETH_PKTSIZE=1518 +CONFIG_NET_ICMP=y +CONFIG_NET_ICMP_SOCKET=y +CONFIG_NET_IGMP=y +CONFIG_NET_SOLINGER=y +CONFIG_NET_TCP=y +CONFIG_NET_TCPBACKLOG=y +CONFIG_NET_TCP_DELAYED_ACK=y +CONFIG_NET_TCP_KEEPALIVE=y +CONFIG_NET_TCP_WRITE_BUFFERS=y +CONFIG_NET_TIMESTAMP=y +CONFIG_NET_UDP=y +CONFIG_NET_UDP_CHECKSUMS=y +CONFIG_NET_UDP_WRITE_BUFFERS=y +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_CROMFSETC=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=15 +CONFIG_NSH_NESTDEPTH=8 +CONFIG_NSH_READLINE=y +CONFIG_NSH_ROMFSETC=y +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_TELNET_LOGIN=y +CONFIG_NSH_VARS=y +CONFIG_PIPES=y +CONFIG_PREALLOC_TIMERS=50 +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_PTHREAD_MUTEX_TYPES=y +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_RAM_SIZE=1048576 +CONFIG_RAM_START=0x20200000 +CONFIG_RAW_BINARY=y +CONFIG_READLINE_CMD_HISTORY=y +CONFIG_READLINE_TABCOMPLETION=y +CONFIG_RTC=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_HPWORKPRIORITY=249 +CONFIG_SCHED_HPWORKSTACKSIZE=1800 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y +CONFIG_SCHED_INSTRUMENTATION_SWITCH=y +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKSTACKSIZE=2032 +CONFIG_SDIO_BLOCKSETUP=y +CONFIG_SEM_PREALLOCHOLDERS=32 +CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SIG_DEFAULT=y +CONFIG_SIG_SIGALRM_ACTION=y +CONFIG_SIG_SIGUSR1_ACTION=y +CONFIG_SIG_SIGUSR2_ACTION=y +CONFIG_SIG_SIGWORK=4 +CONFIG_SPI=y +CONFIG_STACK_COLORATION=y +CONFIG_START_DAY=30 +CONFIG_START_MONTH=11 +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_SYSTEM_CDCACM=y +CONFIG_SYSTEM_CLE=y +CONFIG_SYSTEM_DHCPC_RENEW=y +CONFIG_SYSTEM_NSH=y +CONFIG_SYSTEM_PING=y +CONFIG_SYSTEM_SYSTEM=y +CONFIG_TASK_NAME_SIZE=24 +CONFIG_USBDEV=y +CONFIG_USBDEV_BUSPOWERED=y +CONFIG_USBDEV_DUALSPEED=y +CONFIG_USBDEV_MAXPOWER=500 +CONFIG_USEC_PER_TICK=1000 +CONFIG_WATCHDOG=y diff --git a/boards/nxp/mr-tropic/nuttx-config/scripts/bootloader_script.ld b/boards/nxp/mr-tropic/nuttx-config/scripts/bootloader_script.ld new file mode 100644 index 0000000000..81fb1e0c40 --- /dev/null +++ b/boards/nxp/mr-tropic/nuttx-config/scripts/bootloader_script.ld @@ -0,0 +1,177 @@ +/**************************************************************************** + * boards/nxp/mr-tropic/nuttx-config/scripts/bootloader_script.ld + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/* Specify the memory areas */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x70000000, LENGTH = 128K + sram (rwx) : ORIGIN = 0x20200000, LENGTH = 512K + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 384K + dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 128K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +EXTERN(g_flash_config) +EXTERN(g_image_vector_table) +EXTERN(g_boot_data) +EXTERN(board_get_manifest) +EXTERN(_bootdelay_signature) + +ENTRY(_stext) + +SECTIONS +{ + /* Image Vector Table and Boot Data for booting from external flash */ + + .boot_hdr : ALIGN(4) + { + FILL(0xff) + __boot_hdr_start__ = ABSOLUTE(.) ; + KEEP(*(.boot_hdr.conf)) + . = 0x1000 ; + KEEP(*(.boot_hdr.ivt)) + . = 0x1020 ; + KEEP(*(.boot_hdr.boot_data)) + . = 0x1030 ; + KEEP(*(.boot_hdr.dcd_data)) + __boot_hdr_end__ = ABSOLUTE(.) ; + . = 0x2000 ; + } >flash + + .vectors : + { + KEEP(*(.vectors)) + *(.text .text.__start) + } >flash + + .itcmfunc : + { + . = ALIGN(8); + _sitcmfuncs = ABSOLUTE(.); + FILL(0xFF) + . = 0x40 ; + *(.ram_vectors) + . = ALIGN(8); + _eitcmfuncs = ABSOLUTE(.); + } > itcm AT > flash + + _fitcmfuncs = LOADADDR(.itcmfunc); + + .text : ALIGN(4) + { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + . = ALIGN(4096); + _etext = ABSOLUTE(.); + _srodata = ABSOLUTE(.); + *(.rodata .rodata.*) + . = ALIGN(4096); + _erodata = ABSOLUTE(.); + } > flash + + .init_section : + { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : + { + *(.ARM.extab*) + } > flash + + .ARM.exidx : + { + __exidx_start = ABSOLUTE(.); + *(.ARM.exidx*) + __exidx_end = ABSOLUTE(.); + } > flash + + _eronly = ABSOLUTE(.); + + .data : + { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + . = ALIGN(4); + _edata = ABSOLUTE(.); + } > sram AT > flash + + .ramfunc ALIGN(4): + { + _sramfuncs = ABSOLUTE(.); + *(.ramfunc .ramfunc.*) + _eramfuncs = ABSOLUTE(.); + } > sram AT > flash + + _framfuncs = LOADADDR(.ramfunc); + + .bss : + { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } + + _boot_loadaddr = ORIGIN(flash); + _boot_size = LENGTH(flash); + _ram_size = LENGTH(sram); + _sdtcm = ORIGIN(dtcm); + _edtcm = ORIGIN(dtcm) + LENGTH(dtcm); +} diff --git a/boards/nxp/mr-tropic/nuttx-config/scripts/itcm_functions_includes.ld b/boards/nxp/mr-tropic/nuttx-config/scripts/itcm_functions_includes.ld new file mode 100644 index 0000000000..36330c1e85 --- /dev/null +++ b/boards/nxp/mr-tropic/nuttx-config/scripts/itcm_functions_includes.ld @@ -0,0 +1,719 @@ +*(.text._ZN4uORB7Manager27orb_add_internal_subscriberE6ORB_IDhPj) +*(.text._ZN13MavlinkStream6updateERKy) +*(.text._ZN7Mavlink16update_rate_multEv) +*(.text._ZN3sym17PredictCovarianceIfEEN6matrix6MatrixIT_Lj23ELj23EEERKNS2_IS3_Lj24ELj1EEERKS4_RKNS2_IS3_Lj3ELj1EEES3_SC_SC_S3_S3_) /* itcm-check-ignore */ +*(.text._ZN13MavlinkStream12get_size_avgEv) +*(.text._ZN16ControlAllocator3RunEv) +*(.text._ZN22MulticopterRateControl3RunEv.part.0) +*(.text._ZN7Mavlink9task_mainEiPPc) +*(.text._ZN7sensors22VehicleAngularVelocity3RunEv) +*(.text._ZN4uORB12Subscription9subscribeEv.part.0) +*(.text._ZN4uORB7Manager13orb_data_copyEPvS1_Rjb) +*(.text._ZN4uORB10DeviceNode5writeEP4filePKcj) +*(.text._ZN4uORB10DeviceNode7publishEPK12orb_metadataPvPKv) +*(.text._ZN4uORB12DeviceMaster19getDeviceNodeLockedEPK12orb_metadatah) +*(.text._Z12get_orb_meta6ORB_ID) +*(.text._ZN9ICM42688P12ProcessAccelERKyPKN20InvenSense_ICM42688P4FIFO4DATAEh) +*(.text._ZN3px49WorkQueue3RunEv) +*(.text._ZN9ICM42688P11ProcessGyroERKyPKN20InvenSense_ICM42688P4FIFO4DATAEh) +*(.text._ZN4EKF23RunEv) +*(.text._ZN7sensors10VehicleIMU7PublishEv) +*(.text._ZN4math17WelfordMeanVectorIfLj3EE6updateERKN6matrix6VectorIfLj3EEE) +*(.text._ZN7sensors10VehicleIMU10UpdateGyroEv) +*(.text._ZN9ICM42688P8FIFOReadERKyh) +*(.text._ZN3Ekf20controlGravityFusionERKN9estimator9imuSampleE) +*(.text._ZN16PX4Accelerometer10updateFIFOER19sensor_accel_fifo_s) +*(.text._ZN7sensors22VehicleAngularVelocity19CalibrateAndPublishERKyRKN6matrix7Vector3IfEES7_) +*(.text._ZN4uORB12Subscription10advertisedEv) +*(.text._ZNK15AttitudeControl6updateERKN6matrix10QuaternionIfEE) +*(.text._ZN7sensors10VehicleIMU11UpdateAccelEv) +*(.text.perf_set_elapsed.part.0) +*(.text._ZN4uORB12Subscription6updateEPv) +*(.text._ZN12PX4Gyroscope10updateFIFOER18sensor_gyro_fifo_s) +*(.text._ZN7sensors10VehicleIMU3RunEv) +*(.text.__aeabi_l2f) +*(.text._ZN39ControlAllocationSequentialDesaturation23computeDesaturationGainERKN6matrix6VectorIfLj16EEES4_) +*(.text.pthread_mutex_timedlock) +*(.text._ZN7sensors22VehicleAngularVelocity21FilterAngularVelocityEiPfi) +*(.text._ZN26MulticopterAttitudeControl3RunEv.part.0) +*(.text._ZN6device3SPI9_transferEPhS1_j) +*(.text._ZN15OutputPredictor21calculateOutputStatesEyRKN6matrix7Vector3IfEEfS4_f) +*(.text._ZN7sensors18VotedSensorsUpdate7imuPollER17sensor_combined_s) +*(.text._Z9rotate_3i8RotationRsS0_S0_) +*(.text.fs_getfilep) +*(.text.MEM_DataCopy0_1) +*(.text._ZN7sensors19VehicleAcceleration3RunEv) +*(.text.uart_ioctl) +*(.text._ZN26MulticopterPositionControl3RunEv.part.0) +*(.text.pthread_mutex_take) +*(.text._ZN14ImuDownSampler6updateERKN9estimator9imuSampleE) +*(.text._ZN39ControlAllocationSequentialDesaturation6mixYawEv) +*(.text._ZN16ControlAllocator25publish_actuator_controlsEv.part.0) +*(.text._ZN9ICM42688P7RunImplEv) +*(.text._ZN4uORB12Subscription9subscribeEv) +*(.text.param_get) +*(.text._ZN7sensors22VehicleAngularVelocity21SensorSelectionUpdateERKyb) +*(.text._ZN3px49WorkQueue3AddEPNS_8WorkItemE) +*(.text._ZN4EKF220PublishLocalPositionERKy) +*(.text._mav_finalize_message_chan_send) +*(.text._ZN7sensors22VehicleAngularVelocity16ParametersUpdateEb) +*(.text._ZN6events12SendProtocol6updateERKy) +*(.text._ZN6device3SPI8transferEPhS1_j) +*(.text._ZN27MavlinkStreamDistanceSensor4sendEv) +*(.text.hrt_call_internal) +*(.text._ZN39ControlAllocationSequentialDesaturation18mixAirmodeDisabledEv) +*(.text._ZN7Mavlink15get_free_tx_bufEv) +*(.text.nx_poll) +*(.text._ZN15MavlinkReceiver3runEv) +*(.text._ZN9ICM42688P18ProcessTemperatureEPKN20InvenSense_ICM42688P4FIFO4DATAEh) +*(.text._ZN15OutputPredictor19correctOutputStatesEyRKN6matrix10QuaternionIfEERKNS0_7Vector3IfEERK9LatLonAltS8_S8_) +*(.text._ZN3Ekf12predictStateERKN9estimator9imuSampleE) +*(.text._ZN3px46logger6Logger3runEv) +*(.text._ZN4uORB20SubscriptionInterval7updatedEv) +*(.text._ZN24MavlinkStreamCommandLong4sendEv) +*(.text._ZN9Commander3runEv) +*(.text._ZN3Ekf17predictCovarianceERKN9estimator9imuSampleE) +*(.text.wd_cancel) +*(.text._ZN7Sensors3RunEv) +*(.text.perf_end) +*(.text._ZN4uORB12Subscription7updatedEv) +*(.text._ZN13land_detector12LandDetector3RunEv) +*(.text.sched_idletask) +*(.text.atanf) +*(.text.uart_write) +*(.text.pthread_mutex_unlock) +*(.text.__ieee754_asinf) +*(.text.MEM_DataCopy0_2) +*(.text._ZN20MavlinkCommandSender13check_timeoutE17mavlink_channel_t) +*(.text._ZN16ControlAllocator32publish_control_allocator_statusEi) +*(.text.__ieee754_atan2f) +*(.text._ZNK18DynamicSparseLayer3getEt) +*(.text.__udivmoddi4) +*(.text._ZN8Failsafe17checkStateAndModeERKyRKN12FailsafeBase5StateERK16failsafe_flags_s) +*(.text._ZN29MavlinkStreamHygrometerSensor4sendEv) +*(.text.pthread_mutex_give) +*(.text._ZN3Ekf18controlFusionModesERKN9estimator9imuSampleE) +*(.text._ZN4cdev4CDev11poll_notifyEm) +*(.text.file_vioctl) +*(.text._ZN7sensors18VotedSensorsUpdate11sensorsPollER17sensor_combined_s) +*(.text.nxsig_nanosleep) +*(.text.sem_wait) +*(.text.perf_count_interval.part.0) +*(.text._ZN16ControlAllocator37update_effectiveness_matrix_if_neededE25EffectivenessUpdateReason) +*(.text.MEM_LongCopyJump) +*(.text.px4_arch_adc_sample) +*(.text._ZN31MulticopterHoverThrustEstimator3RunEv) +*(.text._ZNK17ControlAllocation20clipActuatorSetpointERN6matrix6VectorIfLj16EEE) +*(.text._ZN4uORB7Manager17get_device_masterEv) +*(.text._ZN13DataValidator3putEyPKfmh) +*(.text.cdcuart_ioctl) +*(.text.cdcacm_sndpacket) +*(.text._ZN7sensors22VehicleAngularVelocity16SensorBiasUpdateEb) +*(.text._ZN13MavlinkStream11update_dataEv) +*(.text._ZN7sensors18VotedSensorsUpdate21calcGyroInconsistencyEv) +*(.text.param_set_used) +*(.text._ZN18EstimatorInterface10setIMUDataERKN9estimator9imuSampleE) +*(.text._ZN18DataValidatorGroup8get_bestEyPi) +*(.text._ZN4EKF218PublishInnovationsERKy) +*(.text._ZN21MavlinkMissionManager4sendEv) +*(.text._ZN22MulticopterRateControl28updateActuatorControlsStatusERK25vehicle_torque_setpoint_sf) +*(.text._ZN11RateControl6updateERKN6matrix7Vector3IfEES4_S4_fb) +*(.text._ZN39ControlAllocationSequentialDesaturation19desaturateActuatorsERN6matrix6VectorIfLj16EEERKS2_b) +*(.text.imxrt_lpi2c_transfer) +*(.text.uart_putxmitchar) +*(.text.clock_nanosleep) +*(.text.up_release_pending) +*(.text.MEM_DataCopy0) +*(.text._ZN22MavlinkStreamGPSRawInt4sendEv) +*(.text.dq_rem) +*(.text._ZN15GyroCalibration3RunEv.part.0) +*(.text._ZN7sensors18VotedSensorsUpdate22calcAccelInconsistencyEv) +*(.text._ZN24MavlinkStreamADSBVehicle4sendEv) +*(.text.sinf) +*(.text.hrt_call_after) +*(.text._ZN39ControlAllocationSequentialDesaturation8allocateEv) +*(.text.up_invalidate_dcache) +*(.text._ZN15PositionControl16_velocityControlEf) +*(.text._ZN4EKF222PublishAidSourceStatusERKy) +*(.text._ZN4ListIP13MavlinkStreamE8IteratorppEv) +*(.text._ZN20MavlinkStreamESCInfo4sendEv) +*(.text.sem_post) +*(.text._ZN3px417ScheduledWorkItem15ScheduleDelayedEm) +*(.text._ZN10FlightTaskC1Ev) +*(.text.usleep) +*(.text._ZN14FlightTaskAutoC1Ev) +*(.text.sem_getvalue) +*(.text._ZN23MavlinkStreamHighresIMU4sendEv) +*(.text.imxrt_gpio_write) +*(.text._ZN3Ekf6updateEv) +*(.text.__ieee754_acosf) +*(.text._ZN3Ekf20updateIMUBiasInhibitERKN9estimator9imuSampleE) +*(.text._ZN9Commander13dataLinkCheckEv) +*(.text._ZN17FlightModeManager10switchTaskE15FlightTaskIndex) +*(.text._ZN12PX4Gyroscope9set_scaleEf) +*(.text._ZN12FailsafeBase6updateERKyRKNS_5StateEbbRK16failsafe_flags_s) +*(.text._ZN18MavlinkStreamDebug4sendEv) +*(.text._ZN27MavlinkStreamServoOutputRawILi0EE4sendEv) +*(.text.asinf) +*(.text._ZN6matrix5EulerIfEC1ERKNS_3DcmIfEE) +*(.text._ZN4EKF227PublishInnovationTestRatiosERKy) +*(.text._ZN4EKF213PublishStatusERKy) +*(.text._ZN4EKF226PublishInnovationVariancesERKy) +*(.text._ZN13land_detector23MulticopterLandDetector25_get_ground_contact_stateEv) +*(.text.imxrt_dmach_start) +*(.text._ZN3ADC19update_system_powerEy) +*(.text._ZNK3Ekf19get_ekf_soln_statusEv) +*(.text._ZN3px46logger15watchdog_updateERNS0_15watchdog_data_tEb) +*(.text.imxrt_gpio_read) +*(.text._ZN32MavlinkStreamNavControllerOutput4sendEv) +*(.text._ZN39MavlinkStreamGimbalDeviceAttitudeStatus4sendEv) +*(.text._ZNK10ConstLayer3getEt) +*(.text.__aeabi_uldivmod) +*(.text.up_udelay) +*(.text.up_idle) +*(.text._ZN20MavlinkStreamGPS2Raw4sendEv) +*(.text._ZN4EKF217UpdateCalibrationERKyRNS_19InFlightCalibrationERKN6matrix7Vector3IfEES8_fbb) +*(.text._ZN28MavlinkStreamGpsGlobalOrigin4sendEv) +*(.text._ZN11ControlMath15bodyzToAttitudeEN6matrix7Vector3IfEEfR27vehicle_attitude_setpoint_s) +*(.text._ZN4EKF217UpdateRangeSampleER17ekf2_timestamps_s) +*(.text._ZN3Ekf24controlOpticalFlowFusionERKN9estimator9imuSampleE) +*(.text._ZN19MavlinkStreamRawRpm4sendEv) +*(.text._ZN13MavlinkStream10const_rateEv) +*(.text._ZN4EKF215PublishOdometryERKyRKN9estimator9imuSampleE) +*(.text._ZN15FailureDetector20updateAttitudeStatusERK16vehicle_status_s) +*(.text._ZN7Mavlink19configure_sik_radioEv) +*(.text._ZN13BatteryStatus8adc_pollEv) +*(.text.getpid) +*(.text._ZN13DataValidator10confidenceEy) +*(.text._ZN22MavlinkStreamGPSStatus4sendEv) +*(.text._ZN4EKF220UpdateAirspeedSampleER17ekf2_timestamps_s) +*(.text._ZN23MavlinkStreamStatustext4sendEv) +*(.text.uart_poll) +*(.text._ZN24MavlinkParametersManager4sendEv) +*(.text._ZN26MulticopterPositionControl18set_vehicle_statesERK24vehicle_local_position_sf) +*(.text.file_poll) +*(.text.hrt_elapsed_time) +*(.text._ZN7Mavlink11send_finishEv) +*(.text._ZNK3Ekf36estimateInertialNavFallingLikelihoodEv) +*(.text._ZN15PositionControl16_positionControlEv) +*(.text._ZN28MavlinkStreamDebugFloatArray4sendEv) +*(.text._ZN11ControlMath9limitTiltERN6matrix7Vector3IfEERKS2_f) +*(.text.pthread_mutex_lock) +*(.text._ZN21MavlinkStreamAltitude8get_sizeEv) +*(.text._ZN7Mavlink29check_requested_subscriptionsEv) +*(.text.imxrt_lpspi_setmode) +*(.text._ZN3Ekf34controlZeroInnovationHeadingUpdateEv) +*(.text.perf_begin) +*(.text.imxrt_lpspi_setfrequency) +*(.text._ZN17FlightModeManager9_initTaskE15FlightTaskIndex) +*(.text._ZN22MulticopterRateControl3RunEv) +*(.text.cosf) +*(.text._ZN22MavlinkStreamESCStatus4sendEv) +*(.text._ZN26MavlinkStreamCameraTrigger4sendEv) +*(.text._ZN36MavlinkStreamPositionTargetGlobalInt4sendEv) +*(.text._ZN4uORB12Subscription4copyEPv) +*(.text._ZN7sensors19VehicleAcceleration21SensorSelectionUpdateEb) +*(.text.crc_accumulate) +*(.text._ZN3px46logger6Logger13update_paramsEv) +*(.text._ZN11calibration14DeviceExternalEm) +*(.text._ZN25MavlinkStreamHomePosition8get_sizeEv) +*(.text.imxrt_lpspi_modifyreg32) +*(.text._ZN7sensors19VehicleAcceleration16SensorBiasUpdateEb) +*(.text.modifyreg32) +*(.text._ZNK6matrix6MatrixIfLj3ELj1EEmlEf) +*(.text._ZN6matrix5EulerIfEC1ERKNS_10QuaternionIfEE) +*(.text.imxrt_queuedtd) +*(.text._ZN27MavlinkStreamDistanceSensor8get_sizeEv) +*(.text._ZN3Ekf23controlBaroHeightFusionERKN9estimator9imuSampleE) +*(.text._ZN16PX4Accelerometer9set_scaleEf) +*(.text._ZN11ControlMath11constrainXYERKN6matrix7Vector2IfEES4_RKf) +*(.text._ZN22MavlinkStreamEfiStatus4sendEv) +*(.text._ZN22MavlinkStreamDebugVect4sendEv) +*(.text._ZN4EKF217PublishSensorBiasERKy) +*(.text._ZN17FlightModeManager3RunEv) +*(.text._ZN15PositionControl11_inputValidEv) +*(.text._ZN7sensors14VehicleAirData3RunEv) +*(.text.perf_count) +*(.text._ZN3Ekf16controlMagFusionERKN9estimator9imuSampleE) +*(.text.pthread_sem_give) +*(.text._ZN7sensors10VehicleIMU16ParametersUpdateEb) +*(.text._ZN4uORB20SubscriptionInterval4copyEPv) +*(.text._ZN12I2CSPIDriverI9ICM42688PE3RunEv) +*(.text.imxrt_epcomplete.constprop.0) +*(.text._ZNK6matrix6MatrixIfLj3ELj1EEmiERKS1_) +*(.text._ZN9Commander30handleModeIntentionAndFailsafeEv) +*(.text.perf_event_count) +*(.text._ZN4EKF215PublishAttitudeERKy) +*(.text._ZN19MavlinkStreamRawRpm8get_sizeEv) +*(.text._ZNK3px46atomicIbE4loadEv) +*(.text._ZN29MavlinkStreamHygrometerSensor8get_sizeEv) +*(.text.pthread_mutex_add) +*(.text._ZN12HomePosition6updateEbb) +*(.text.poll_fdsetup) +*(.text._ZN15PositionControl20_accelerationControlEv) +*(.text._ZN3Ekf19controlHeightFusionERKN9estimator9imuSampleE) +*(.text._ZN9Commander19control_status_ledsEbh) +*(.text._ZN6device3I2C8transferEPKhjPhj) +*(.text.orb_publish) +*(.text._ZN7sensors19VehicleAcceleration16ParametersUpdateEb) +*(.text._ZN22MavlinkStreamVibration8get_sizeEv) +*(.text._ZN15MavlinkReceiver15CheckHeartbeatsERKyb) +*(.text._ZNK6matrix7Vector3IfEmiES1_) +*(.text.__aeabi_f2ulz) +*(.text._ZN9ICM42688P26DataReadyInterruptCallbackEiPvS0_) +*(.text._ZN13land_detector23MulticopterLandDetector23_get_maybe_landed_stateEv) +*(.text.acosf) +*(.text._ZN14ImuDownSampler5resetEv) +*(.text._ZN3Ekf31checkVerticalAccelerationHealthERKN9estimator9imuSampleE) +*(.text._ZN6matrix6MatrixIfLj3ELj1EEC1ERKS1_) +*(.text.udp_pollsetup) +*(.text._ZL14timer_callbackPv) +*(.text._ZN3Ekf4fuseERKN6matrix6VectorIfLj24EEEf) +*(.text._ZN13land_detector23MulticopterLandDetector22_set_hysteresis_factorEi) +*(.text.nxsem_wait_irq) +*(.text._ZN20MavlinkCommandSender4lockEv) +*(.text.MEM_LongCopyEnd) +*(.text._ZThn24_N16ControlAllocator3RunEv) +*(.text._ZN15TimestampedListIN20MavlinkCommandSender14command_item_sELi3EE8get_nextEv) +*(.text._ZNK3Ekf21get_ekf_lpos_accuracyEPfS0_) +*(.text._ZN17FlightModeManager17start_flight_taskEv) +*(.text.MEM_DataCopyBytes) +*(.text._ZN29MavlinkStreamLocalPositionNED8get_sizeEv) +*(.text._ZN6SticksC1EP12ModuleParams) +*(.text._ZN27MavlinkStreamServoOutputRawILi1EE4sendEv) +*(.text._ZN3Ekf35updateHorizontalDeadReckoningstatusEv) +*(.text._ZN3Ekf20controlAirDataFusionERKN9estimator9imuSampleE) +*(.text._ZN24FlightTaskManualAltitudeC1Ev) +*(.text._ZN25MavlinkStreamHomePosition4sendEv) +*(.text._ZN24MavlinkParametersManager8send_oneEv) +*(.text._ZN15OutputPredictor29applyCorrectionToOutputBufferERKN6matrix7Vector3IfEES4_) +*(.text._ZN21HealthAndArmingChecks6updateEbb) +*(.text._ZThn24_N22MulticopterRateControl3RunEv) +*(.text._ZN26MavlinkStreamManualControl4sendEv) +*(.text._ZN27MavlinkStreamOpticalFlowRad4sendEv) +*(.text._ZN18mag_bias_estimator16MagBiasEstimator3RunEv) +*(.text._ZN4uORB7Manager11orb_publishEPK12orb_metadataPvPKv) +*(.text._ZN24MavlinkParametersManager18send_untransmittedEv) +*(.text._ZN10MavlinkFTP4sendEv) +*(.text._ZN3Ekf27controlExternalVisionFusionERKN9estimator9imuSampleE) +*(.text.clock_gettime) +*(.text._ZN3ADC17update_adc_reportEy) +*(.text._ZN32MavlinkStreamGimbalManagerStatus4sendEv) +*(.text._ZN9LockGuardD1Ev) /* itcm-check-ignore */ +*(.text._ZN4EKF213PublishStatesERKy) +*(.text._ZN3ADC3RunEv) +*(.text._ZN6BMP38815compensate_dataEhPK16bmp3_uncomp_dataP9bmp3_data) +*(.text._ZN3Ekf20controlFakePosFusionEv) +*(.text._ZN11calibration9Gyroscope13set_device_idEm) +*(.text._ZN24MavlinkStreamOrbitStatus8get_sizeEv) +*(.text.imxrt_progressep) +*(.text.imxrt_gpio_configinput) +*(.text._ZN17FlightModeManager26generateTrajectorySetpointEfRK24vehicle_local_position_s) +*(.text._ZN7Sensors14diff_pres_pollEv) +*(.text._ZN21MavlinkStreamAttitude4sendEv) +*(.text._ZN4EKF220UpdateMagCalibrationERKy) +*(.text._ZN22MavlinkStreamEfiStatus8get_sizeEv) +*(.text._ZN9ICM42688P9DataReadyEv) +*(.text._ZN21MavlinkMissionManager20check_active_missionEv) +*(.text._ZNK3Ekf20get_ekf_vel_accuracyEPfS0_) +*(.text._ZN4EKF216UpdateBaroSampleER17ekf2_timestamps_s) +*(.text._ZN4EKF223UpdateSystemFlagsSampleER17ekf2_timestamps_s) +*(.text._ZThn16_N7sensors22VehicleAngularVelocity3RunEv) +*(.text._ZN29MavlinkStreamObstacleDistance4sendEv) +*(.text._ZN24MavlinkStreamOrbitStatus4sendEv) +*(.text._ZN9Navigator3runEv) +*(.text._ZN24MavlinkParametersManager11send_paramsEv) +*(.text._ZN17MavlinkLogHandler4sendEv) +*(.text._ZN7control10SuperBlock5setDtEf) +*(.text._ZN29MavlinkStreamMountOrientation8get_sizeEv) +*(.text._ZN26MulticopterAttitudeControl3RunEv) +*(.text._ZThn16_N31ActuatorEffectivenessMultirotor22getEffectivenessMatrixERN21ActuatorEffectiveness13ConfigurationE25EffectivenessUpdateReason) +*(.text._ZN4EKF218PublishStatusFlagsERKy) +*(.text._ZN11WeatherVaneC1EP12ModuleParams) +*(.text._ZN15FailureDetector6updateERK16vehicle_status_sRK22vehicle_control_mode_s) +*(.text._ZN7Mavlink10send_startEi) +*(.text.imxrt_lpspi_setbits) +*(.text._ZN15OutputPredictor37applyCorrectionToVerticalOutputBufferEff) +*(.text._ZN4EKF222UpdateAccelCalibrationERKy) +*(.text._ZN7sensors19VehicleMagnetometer3RunEv) +*(.text._ZN29MavlinkStreamMountOrientation4sendEv) +*(.text._ZN13land_detector12LandDetector19UpdateVehicleAtRestEv) +*(.text._ZN10FlightTask29_evaluateVehicleLocalPositionEv) +*(.text.__aeabi_f2lz) +*(.text._ZN32MavlinkStreamCameraImageCaptured4sendEv) +*(.text._ZN21MavlinkStreamOdometry8get_sizeEv) +*(.text._ZN28MavlinkStreamNamedValueFloat4sendEv) +*(.text.__aeabi_ul2f) +*(.text.poll) +*(.text._ZN14FlightTaskAutoD1Ev) +*(.text._ZN4uORB10DeviceNode22get_initial_generationEv) +*(.text._ZN3Ekf23controlGnssHeightFusionERKN9estimator10gnssSampleE) +*(.text._ZN3Ekf40updateOnGroundMotionForOpticalFlowChecksEv) +*(.text._ZN6matrix6MatrixIfLj3ELj1EEC1Ev) +*(.text._ZN14ZeroGyroUpdate6updateER3EkfRKN9estimator9imuSampleE) +*(.text._ZN30MavlinkStreamOpenDroneIdSystem4sendEv) +*(.text._ZN22MavlinkStreamScaledIMU4sendEv) +*(.text.imxrt_ioctl) +*(.text._ZN36MavlinkStreamGimbalDeviceSetAttitude4sendEv) +*(.text._ZN4math13expo_deadzoneIfEEKT_RS2_S3_S3_.isra.0) +*(.text._ZN19StickAccelerationXYC1EP12ModuleParams) +*(.text.imxrt_epsubmit) +*(.text._ZN15PositionControl6updateEf) +*(.text._ZN23MavlinkStreamScaledIMU24sendEv) +*(.text.imxrt_dma_send) +*(.text._ZN20MavlinkStreamWindCov4sendEv) +*(.text._ZN7sensors18VotedSensorsUpdate13checkFailoverERNS0_10SensorDataEPKcN6events3px45enums13sensor_type_tE) +*(.text._ZN21MavlinkStreamOdometry4sendEv) +*(.text.vsprintf_internal.constprop.0) +*(.text.udp_pollteardown) +*(.text._ZN12MixingOutput6updateEv) +*(.text.clock_abstime2ticks) +*(.text._ZN13BatteryStatus3RunEv) +*(.text._ZN32MavlinkStreamGimbalManagerStatus8get_sizeEv) +*(.text._ZN10FlightTask15_resetSetpointsEv) +*(.text._ZN9systemlib10Hysteresis20set_state_and_updateEbRKy) +*(.text.devif_callback_free.part.0) +*(.text._ZN6Sticks25checkAndUpdateStickInputsEv) +*(.text.atan2f) +*(.text._ZN23MavlinkStreamRCChannels4sendEv) +*(.text._ZN4EKF221UpdateExtVisionSampleER17ekf2_timestamps_s) +*(.text.imxrt_dmach_stop) +*(.text._ZN9Commander16handleAutoDisarmEv) +*(.text._ZN9Commander11updateTunesEv) +*(.text._ZN4EKF215UpdateMagSampleER17ekf2_timestamps_s) +*(.text._ZN18DataValidatorGroup3putEjyPKfmh) +*(.text._ZNK3Ekf19get_ekf_ctrl_limitsEPfS0_S0_S0_S0_) +*(.text._ZN12FailsafeBase13checkFailsafeEibbRKNS_13ActionOptionsE) +*(.text._ZN17FlightTaskDescendD1Ev) +*(.text._ZN30MavlinkStreamOpenDroneIdSystem8get_sizeEv) +*(.text._ZNK3px46logger9LogWriter10is_startedENS0_7LogTypeE) +*(.text._ZN24FlightTaskManualAltitudeD1Ev) +*(.text._Z35px4_indicate_external_reset_lockout16LockoutComponentb) +*(.text.uart_pollnotify) +*(.text._ZN4EKF215PublishBaroBiasERKy) +*(.text._ZN4EKF221UpdateGyroCalibrationERKy) +*(.text._ZN6matrix9constrainIfLj3ELj1EEENS_6MatrixIT_XT0_EXT1_EEERKS3_S2_S2_) +*(.text._ZN4uORB22SubscriptionMultiArrayI16battery_status_sLh3EE16advertised_countEv) +*(.text._ZN23MavlinkStreamScaledIMU34sendEv) +*(.text.__aeabi_ldivmod) +*(.text._ZN15PositionControl16setInputSetpointERK21trajectory_setpoint_s) +*(.text.nxsig_pendingset) +*(.text.psock_poll) +*(.text._ZN15FailureInjector6updateEv) +*(.text.imxrt_writedtd) +*(.text.cdcacm_wrcomplete) +*(.text.cdcuart_txint) +*(.text._ZN3Ekf33updateVerticalDeadReckoningStatusEv) +*(.text._ZN33FlightTaskManualAltitudeSmoothVelC1Ev) +*(.text.powf) +*(.text._ZN4EKF217PublishEventFlagsERKy) +*(.text._ZN17FlightTaskDescend6updateEv) +*(.text.imxrt_iomux_configure) +*(.text.hrt_store_absolute_time) +*(.text.nxsem_set_protocol) +*(.text.write) +*(.text._ZN22MavlinkStreamSysStatus4sendEv) +*(.text._ZN4EKF216UpdateFlowSampleER17ekf2_timestamps_s) +*(.text._ZN4cdevL10cdev_ioctlEP4fileim) +*(.text._ZN7Mavlink10send_bytesEPKhj) +*(.text._ZNK8Failsafe17checkModeFallbackERK16failsafe_flags_sh) +*(.text.clock_systime_timespec) +*(.text._ZN4uORB10DeviceNode26remove_internal_subscriberEv) +*(.text._ZThn16_N4EKF23RunEv) +*(.text._ZNK3Ekf22computeYawInnovVarAndHEfRfRN6matrix6VectorIfLj24EEE) +*(.text._ZN12ActuatorTest6updateEif) +*(.text._ZN17VelocitySmoothingC1Efff) +*(.text._ZN13AnalogBattery19get_voltage_channelEv) +*(.text._ZN10FlightTask37_evaluateVehicleLocalPositionSetpointEv) +*(.text._ZN4uORB12Subscription11unsubscribeEv) +*(.text.net_lock) +*(.text.clock_time2ticks) +*(.text._ZN12FailsafeBase16updateStartDelayERKyb) +*(.text._ZN23MavlinkStreamStatustext8get_sizeEv) +*(.text._ZN11calibration13Accelerometer13set_device_idEm) +*(.text._ZN3px46logger6Logger18start_stop_loggingEv) +*(.text._ZN14FlightTaskAuto17_evaluateTripletsEv) +*(.text._ZN11calibration9Gyroscope23SensorCorrectionsUpdateEb) +*(.text._ZN25MavlinkStreamMagCalReport4sendEv) +*(.text.imxrt_config_gpio) +*(.text.nxsig_timeout) +*(.text._ZN11RateControl19setSaturationStatusERKN6matrix7Vector3IbEES4_) +*(.text._ZN3Ekf17measurementUpdateERN6matrix6VectorIfLj24EEERKS2_ff) +*(.text.dq_addlast) +*(.text._ZN19MavlinkStreamVFRHUD4sendEv) +*(.text.hrt_call_reschedule) +*(.text.nxsem_boost_priority) +*(.text._ZN4EKF215UpdateGpsSampleER17ekf2_timestamps_s) +*(.text._ZN8StickYawC1EP12ModuleParams) +*(.text._ZN7control12BlockLowPass6updateEf) +*(.text._ZN15FailureDetector26updateImbalancedPropStatusEv) +*(.text._ZN9systemlib10Hysteresis6updateERKy) +*(.text.nxsem_tickwait_uninterruptible) +*(.text._ZN12HomePosition31hasMovedFromCurrentHomeLocationEv) +*(.text.devif_callback_alloc) +*(.text._ZN28MavlinkStreamNamedValueFloat8get_sizeEv) +*(.text._ZN24MavlinkStreamADSBVehicle8get_sizeEv) +*(.text._ZN26MavlinkStreamBatteryStatus8get_sizeEv) +*(.text._ZN26MulticopterPositionControl17parameters_updateEb) +*(.text._ZN3px46logger6Logger29handle_vehicle_command_updateEv) +*(.text.imxrt_lpspi_send) +*(.text._ZN4uORB10DeviceNode23add_internal_subscriberEv) +*(.text._ZN6matrix6MatrixIfLj3ELj1EEaSERKS1_) +*(.text._ZNK6matrix6MatrixIfLj3ELj1EE5emultERKS1_) +*(.text.mallinfo_handler) +*(.text._ZN13land_detector23MulticopterLandDetector14_update_topicsEv) +*(.text._ZN24ManualVelocitySmoothingZC1Ev) /* itcm-check-ignore */ +*(.text._ZN3ADC6sampleEj) +*(.text._ZNK3Ekf22isTerrainEstimateValidEv) +*(.text._ZN15EstimatorChecks23setModeRequirementFlagsERK7ContextbbbRK24vehicle_local_position_sRK12sensor_gps_sR16failsafe_flags_sR6Report) +*(.text._ZN11ControlMath11addIfNotNanERff) +*(.text._ZN9Commander21checkForMissionUpdateEv) +*(.text._Z8set_tunei) +*(.text._ZNK6matrix7Vector3IfE5crossERKNS_6MatrixIfLj3ELj1EEE) +*(.text._ZN10FlightTask22_checkEkfResetCountersEv) +*(.text._ZNK6matrix6MatrixIfLj3ELj1EE11isAllFiniteEv) +*(.text._ZN14FlightTaskAuto24_evaluateGlobalReferenceEv) +*(.text._ZN6matrix9constrainIfLj2ELj1EEENS_6MatrixIT_XT0_EXT1_EEERKS3_S2_S2_) +*(.text._ZN3px46logger6Logger23handle_file_write_errorEv) +*(.text._ZN10FlightTask16updateInitializeEv) +*(.text._ZN11calibration9Gyroscope10set_offsetERKN6matrix7Vector3IfEE) +*(.text._ZNK6matrix6VectorIfLj3EE4normEv) +*(.text._ZN14FlightTaskAuto16updateInitializeEv) +*(.text.fabsf) +*(.text._ZN27MavlinkStreamAttitudeTarget8get_sizeEv) +*(.text.nxsem_get_value) +*(.text._ZN13AnalogBattery8is_validEv) +*(.text._ZN4uORB16SubscriptionDataI15home_position_sEC1EPK12orb_metadatah) +*(.text._ZN22MavlinkStreamGPSStatus8get_sizeEv) +*(.text.nxsem_destroyholder) +*(.text.psock_udp_cansend) +*(.text.MEM_DataCopy2_2) +*(.text._ZN10FlightTask8activateERK21trajectory_setpoint_s) +*(.text.sock_file_poll) +*(.text._ZN10Ringbuffer9pop_frontEPhj) +*(.text.nx_write) +*(.text._ZN9Commander18manualControlCheckEv) +*(.text._ZN31MavlinkStreamAttitudeQuaternion4sendEv) +*(.text.nxsem_canceled) +*(.text._ZN10FlightTask21getTrajectorySetpointEv) +*(.text.imxrt_dmach_getcount) +*(.text.sem_clockwait) +*(.text.inet_poll) +*(.text._ZN6BMP3887collectEv) +*(.text._ZNK15PositionControl24getLocalPositionSetpointER33vehicle_local_position_setpoint_s) +*(.text._ZN3Ekf16controlGpsFusionERKN9estimator9imuSampleE) +*(.text._ZN23MavlinkStreamRCChannels8get_sizeEv) +*(.text._ZN20MavlinkStreamESCInfo8get_sizeEv) +*(.text._ZNK6matrix6VectorIfLj2EE4normEv) +*(.text._Z15arm_auth_updateyb) +*(.text._ZN3LED5ioctlEP4fileim) /* itcm-check-ignore */ +*(.text._ZNK3px46logger9LogWriter20had_file_write_errorEv) +*(.text._ZN29MavlinkStreamLocalPositionNED4sendEv) +*(.text._ZNK6matrix6VectorIfLj3EE3dotERKNS_6MatrixIfLj3ELj1EEE) +*(.text.imxrt_lpi2c_setclock) +*(.text._ZN6matrix12typeFunction9constrainIfEET_S2_S2_S2_.part.0) +*(.text._ZN13MapProjection13initReferenceEddy) +*(.text._ZN11calibration13Accelerometer23SensorCorrectionsUpdateEb) +*(.text._ZN31MavlinkStreamAttitudeQuaternion8get_sizeEv) +*(.text._ZN30MavlinkStreamGlobalPositionInt4sendEv) +*(.text._ZN6SticksD1Ev) +*(.text._ZN13NavigatorMode3runEb) +*(.text._ZL19param_find_internalPKcb) +*(.text.uart_datasent) +*(.text._ZN4EKF221PublishOpticalFlowVelERKy) +*(.text.nxsem_destroy) +*(.text.file_write) +*(.text._ZN21MavlinkStreamAltitude4sendEv) +*(.text._ZN7sensors14VehicleAirData12UpdateStatusEv) +*(.text.imxrt_padmux_map) +*(.text._ZN6BMP38815get_sensor_dataEhP9bmp3_data) +*(.text._ZN18MavlinkRateLimiter5checkERKy) +*(.text._ZThn24_N26MulticopterAttitudeControl3RunEv) +*(.text.imxrt_periphclk_configure) +*(.text._ZN4EKF218UpdateAuxVelSampleER17ekf2_timestamps_s) +*(.text._ZN3RTL11on_inactiveEv) +*(.text._ZN12FailsafeBase10modeCanRunERK16failsafe_flags_sh) +*(.text._ZN4EKF216PublishEvPosBiasERKy) +*(.text._ZN21MavlinkStreamAttitude8get_sizeEv) +*(.text._ZThn16_N7sensors19VehicleAcceleration3RunEv) +*(.text._ZN33MavlinkStreamTimeEstimateToTarget4sendEv) +*(.text._ZN6matrix6MatrixIfLj3ELj1EE6setAllEf) +*(.text._ZN12ModuleParamsD1Ev) +*(.text._ZN3Ekf20controlFakeHgtFusionEv) +*(.text.imxrt_reqcomplete) +*(.text._ZNK6matrix7Vector3IfEmlEf) +*(.text._ZN18ZeroVelocityUpdate6updateER3EkfRKN9estimator9imuSampleE) +*(.text._ZN11ControlMath19addIfNotNanVector3fERN6matrix7Vector3IfEERKS2_) +*(.text._ZN11ControlMath16thrustToAttitudeERKN6matrix7Vector3IfEEfR27vehicle_attitude_setpoint_s) +*(.text.cos) +*(.text.net_unlock) +*(.text._ZN7sensors18VotedSensorsUpdate21setRelativeTimestampsER17sensor_combined_s) +*(.text._ZN12FailsafeBase13ActionOptionsC1ENS_6ActionE) +*(.text._ZN24FlightTaskManualAltitude16updateInitializeEv) +*(.text._ZN26MulticopterPositionControl3RunEv) +*(.text._ZN8Failsafe21fromQuadchuteActParamEi) +*(.text._ZN24VariableLengthRingbuffer9pop_frontEPhj) +*(.text._ZN7control15BlockDerivative6updateEf) /* itcm-check-ignore */ +*(.text._ZN9Commander18safetyButtonUpdateEv) +*(.text._ZN13BatteryChecks14checkAndReportERK7ContextR6Report) +*(.text._ZN18DataValidatorGroup16get_sensor_stateEj) +*(.text.uart_xmitchars_done) +*(.text._ZN4EKF225PublishYawEstimatorStatusERKy) +*(.text.sin) +*(.text._ZN6Safety19safetyButtonHandlerEv) +*(.text._ZN3Ekf19controlAuxVelFusionERKN9estimator9imuSampleE) +*(.text._ZNK6matrix6MatrixIfLj2ELj1EEplERKS1_) +*(.text._ZThn24_N7Sensors3RunEv) +*(.text._ZN6matrix6MatrixIfLj2ELj1EEC1ERKS1_) +*(.text._ZN10FlightTask10reActivateEv) +*(.text._ZNK15PositionControl19getAttitudeSetpointER27vehicle_attitude_setpoint_s) +*(.text._ZN4cdev4CDev4pollEP4fileP6pollfdb) +*(.text._ZN9Commander20offboardControlCheckEv) +*(.text._ZN4EKF216PublishGpsStatusERKy) +*(.text._ZN4uORB12SubscriptionaSEOS0_) +*(.text._ZN15TakeoffHandling18updateTakeoffStateEbbbfbRKy) +*(.text._ZN10ModeChecks14checkAndReportERK7ContextR6Report) +*(.text._ZN14FlightTaskAuto24_updateInternalWaypointsEv) +*(.text._ZN8Failsafe17updateArmingStateERKybRK16failsafe_flags_s) +*(.text.imxrt_lpi2c_modifyreg) +*(.text.up_flush_dcache) +*(.text._ZN15GyroCalibration3RunEv) +*(.text.mavlink_start_uart_send) +*(.text.MEM_DataCopy2) +*(.text._ZNK9Commander14getPrearmStateEv) +*(.text._ZN15EstimatorChecks14checkAndReportERK7ContextR6Report) +*(.text._ZN28FlightTaskManualAccelerationD1Ev) +*(.text._ZN11RateControl20getRateControlStatusER18rate_ctrl_status_s) +*(.text._ZN4uORB10DeviceNode15poll_notify_oneEP6pollfdm) +*(.text._ZN3GPS21handleInjectDataTopicEv.part.0) +*(.text._ZN9Commander17systemPowerUpdateEv) +*(.text._ZN4EKF221PublishGlobalPositionERKy) +*(.text._ZNK12FailsafeBase17getSelectedActionERKNS_5StateERK16failsafe_flags_sbbRNS_19SelectedActionStateE) +*(.text.imxrt_padctl_address) +*(.text._ZNK6matrix6VectorIfLj2EE4unitEv) +*(.text._ZN19RcCalibrationChecks14checkAndReportERK7ContextR6Report) +*(.text.devif_conn_callback_free) +*(.text._ZN13InnovationLpf6updateEfff.isra.0) +*(.text._ZN9Commander18landDetectorUpdateEv) +*(.text._ZN3Ekf18updateGroundEffectEv) +*(.text.nxsem_init) +*(.text._ZN9Commander16vtolStatusUpdateEv) +*(.text._ZN6matrix6MatrixIfLj4ELj1EEC1EPKf) +*(.text._ZN11ControlMath20setZeroIfNanVector3fERN6matrix7Vector3IfEE) +*(.text._ZThn8_N3ADC3RunEv) +*(.text._ZN11StickTiltXYC1EP12ModuleParams) +*(.text._ZN12SafetyButton3RunEv) +*(.text._ZN6BMP38811set_op_modeEh) +*(.text._ZN3GPS8callbackE15GPSCallbackTypePviS1_) +*(.text._ZN13AnalogBattery19get_current_channelEv) +*(.text._ZN15EstimatorChecks20checkEstimatorStatusERK7ContextR6ReportRK18estimator_status_s8NavModes) +*(.text._ZN12FailsafeBase11updateDelayERKy) +*(.text._ZN10FlightTask25_evaluateDistanceToGroundEv) +*(.text._ZN4EKF218PublishGnssHgtBiasERKy) +*(.text._ZN6matrix6VectorIfLj3EE9normalizeEv) +*(.text._ZThn16_N7sensors10VehicleIMU3RunEv) +*(.text.__kernel_cos) +*(.text._ZN12SafetyButton19CheckPairingRequestEb) +*(.text.imxrt_dma_txavailable) +*(.text.perf_set_elapsed) +*(.text.pthread_sem_take) +*(.text._ZN8StickYawD1Ev) +*(.text._Z15blink_msg_statev) +*(.text._ZN19AccelerometerChecks14checkAndReportERK7ContextR6Report) +*(.text._ZN8Failsafe14fromGfActParamEi) +*(.text._ZN3Ekf17controlBetaFusionERKN9estimator9imuSampleE) +*(.text._ZN36do_not_explicitly_use_this_namespace5ParamIfLN3px46paramsE919EEC1Ev) /* itcm-check-ignore */ +*(.text._ZN22MavlinkStreamHeartbeat8get_sizeEv) +*(.text._ZN6matrix6MatrixIfLj3ELj1EEdVEf) +*(.text._ZN17FlightTaskDescendC1Ev) +*(.text._ZN26MavlinkStreamCameraTrigger8get_sizeEv) +*(.text.iob_navail) +*(.text._ZN12FailsafeBase25removeNonActivatedActionsEv) +*(.text._ZN15TakeoffHandling10updateRampEff) +*(.text._Z7led_offi) +*(.text.led_off) +*(.text.udp_wrbuffer_test) +*(.text._ZNK4math17WelfordMeanVectorIfLj3EE8varianceEv) +*(.text._ZN27MavlinkStreamAttitudeTarget4sendEv) +*(.text._ZN12MixingOutput19updateSubscriptionsEb) +*(.text._ZN10FlightTaskD1Ev) +*(.text._ZThn24_N13land_detector12LandDetector3RunEv) +*(.text._ZN18MavlinkStreamDebug8get_sizeEv) +*(.text._ZN12GPSDriverUBX7receiveEj) +*(.text._ZN13BatteryStatus21parameter_update_pollEb) +*(.text._ZN3RTL18updateDatamanCacheEv) +*(.text.__ieee754_sqrtf) +*(.text._ZThn24_N18mag_bias_estimator16MagBiasEstimator3RunEv) +*(.text.__kernel_sin) +*(.text._ZN11MissionBase17parameters_updateEv) +*(.text.nx_start) +*(.text._ZN3Ekf17controlDragFusionERKN9estimator9imuSampleE) +*(.text._ZNK8Failsafe22modifyUserIntendedModeEN12FailsafeBase6ActionES1_h) +*(.text._ZN3px417ScheduledWorkItem19schedule_trampolineEPv) +*(.text.uart_xmitchars_dma) +*(.text._ZN13land_detector23MulticopterLandDetector19_get_freefall_stateEv) +*(.text._ZThn24_N31MulticopterHoverThrustEstimator3RunEv) +*(.text._ZN11MissionBase11on_inactiveEv) +*(.text._ZN21FailureDetectorChecks14checkAndReportERK7ContextR6Report) +*(.text._ZN12SystemChecks14checkAndReportERK7ContextR6Report) +*(.text._ZN6matrix6MatrixIfLj3ELj1EEC1EPKf) +*(.text.imxrt_padmux_address) +*(.text._ZN19MavlinkStreamVFRHUD8get_sizeEv) +*(.text._ZN15EstimatorChecks15checkSensorBiasERK7ContextR6Report8NavModes) +*(.text._ZN20ImuConsistencyChecks14checkAndReportERK7ContextR6Report) +*(.text._ZN28MavlinkStreamGpsGlobalOrigin8get_sizeEv) +*(.text.MEM_DataCopy2_1) +*(.text._ZN6BMP3887measureEv) +*(.text._ZN4EKF217PublishRngHgtBiasERKy) +*(.text._ZN36MavlinkStreamPositionTargetGlobalInt8get_sizeEv) +*(.text._ZN28MavlinkStreamEstimatorStatus8get_sizeEv) +*(.text.up_clean_dcache) +*(.text._ZThn24_N26MulticopterPositionControl3RunEv) +*(.text._ZN16FlightTimeChecks14checkAndReportERK7ContextR6Report) +*(.text._ZN13ManualControl12processInputEy) +*(.text._ZN17CpuResourceChecks14checkAndReportERK7ContextR6Report) +*(.text._ZN10GyroChecks14checkAndReportERK7ContextR6Report) +*(.text._ZN8Failsafe26fromImbalancedPropActParamEi) +*(.text._ZThn24_N13BatteryStatus3RunEv) +*(.text.mm_foreach) +*(.text._ZN35MavlinkStreamPositionTargetLocalNed8get_sizeEv) +*(.text._ZN32MavlinkStreamNavControllerOutput8get_sizeEv) +*(.text._ZN6matrix8wrap_2piIfEET_S1_) +*(.text._ZN4uORB7Manager30orb_remove_internal_subscriberEPv) +*(.text._ZN10BMP388_I2C7get_regEhPh) +*(.text._ZN4math17WelfordMeanVectorIfLj3EE5resetEv) +*(.text._ZN27MavlinkStreamScaledPressure8get_sizeEv) +*(.text._ZN3RTL17parameters_updateEv) +*(.text._ZN18EstimatorInterface11setBaroDataERKN9estimator10baroSampleE.part.0) +*(.text._ZN32MavlinkStreamOpenDroneIdLocation8get_sizeEv) +*(.text._ZN21MavlinkStreamTimesync4sendEv) +*(.text._ZN9Navigator23reset_position_setpointER19position_setpoint_s) +*(.text._ZN19RcAndDataLinkChecks14checkAndReportERK7ContextR6Report) +*(.text.imxrt_dma_txcallback) +*(.text._ZN24MavlinkParametersManager11send_uavcanEv) +*(.text._ZN4uORB10DeviceNode4readEP4filePcj) +*(.text._ZN4uORB10DeviceNode10poll_stateEP4file) +*(.text._ZN4uORB7Manager8orb_copyEPK12orb_metadataiPv) +*(.text._ZN27MavlinkStreamServoOutputRawILi0EE8get_sizeEv) +*(.text._ZN8Geofence3runEv) +*(.text._ZN15EstimatorChecks25checkEstimatorStatusFlagsERK7ContextR6ReportRK18estimator_status_sRK24vehicle_local_position_s) +*(.text._ZN18MagnetometerChecks14checkAndReportERK7ContextR6Report) +*(.text._ZN6events9SendEvent3RunEv) +*(.text._ZN30MavlinkStreamGlobalPositionInt8get_sizeEv) +*(.text._ZN22MavlinkStreamESCStatus8get_sizeEv) +*(.text._Z20px4_spi_bus_externalRK13px4_spi_bus_t) +*(.text.read) +*(.text._ZN4uORB15PublicationBaseD1Ev) +*(.text._ZN22MavlinkStreamDebugVect8get_sizeEv) +*(.text._ZN7Mission11on_inactiveEv) +*(.text._ZN7sensors19VehicleMagnetometer20UpdateMagCalibrationEv) +*(.text._ZN11calibration27FindCurrentCalibrationIndexEPKcm) +*(.text._ZN4cdevL9cdev_readEP4filePcj) +*(.text.sem_timedwait) +*(.text.snprintf) +*(.text._ZN27MavlinkStreamOpticalFlowRad8get_sizeEv) +*(.text._ZNK6matrix6MatrixIfLj3ELj1EE6copyToEPf) +*(.text._ZN6Report13healthFailureIJhEEEv8NavModes20HealthComponentIndexmRKN6events9LogLevelsEPKcDpT_.isra.0.constprop.0) +*(.text._ZN13BatteryChecks16rtlEstimateCheckERK7ContextR6Reportf) +*(.text.sigemptyset) +*(.text.nx_read) diff --git a/boards/nxp/mr-tropic/nuttx-config/scripts/itcm_static_functions.ld b/boards/nxp/mr-tropic/nuttx-config/scripts/itcm_static_functions.ld new file mode 100644 index 0000000000..bc0b57099c --- /dev/null +++ b/boards/nxp/mr-tropic/nuttx-config/scripts/itcm_static_functions.ld @@ -0,0 +1,163 @@ +/* Static */ +*(.text.arm_ack_irq) +*(.text.arm_doirq) +*(.text.arm_svcall) +*(.text.arm_switchcontext) +*(.text.clock_timer) +*(.text.exception_common) +*(.text.flexio_irq_handler) +*(.text.hrt_absolute_time) +*(.text.hrt_call_enter) +*(.text.hrt_tim_isr) +*(.text.imxrt_configwaitints) +*(.text.imxrt_dma_callback) +*(.text.imxrt_dmach_interrupt) +*(.text.imxrt_dmach_xfrsetup) +*(.text.imxrt_dmaterminate) +*(.text.imxrt_dispatch) +*(.text.imxrt_edma_interrupt) +*(.text.imxrt_endwait) +*(.text.imxrt_enet_interrupt) +*(.text.imxrt_enet_interrupt_work) +*(.text.imxrt_interrupt) +*(.text.imxrt_gpio1_16_31_interrupt) +*(.text.imxrt_gpio2_0_15_interrupt) +*(.text.imxrt_lpi2c_isr) +*(.text.imxrt_lpspi3select) +*(.text.imxrt_lpspi4select) +*(.text.imxrt_lpspi_exchange) +*(.text.imxrt_recvdma) +*(.text.imxrt_tcd_free) +*(.text.imxrt_timerisr) +*(.text.imxrt_transmit) +*(.text.imxrt_txdone) +*(.text.imxrt_txtimeout_work) +*(.text.imxrt_txtimeout_expiry) +*(.text.imxrt_txpoll) +*(.text.imxrt_txringfull) +*(.text.imxrt_txavail_work) +*(.text.imxrt_txavail) +*(.text.imxrt_usbinterrupt) +*(.text.irq_dispatch) +*(.text.ioctl) +*(.text.memcpy) +*(.text.memset) +*(.text.nxsched_add_blocked) +*(.text.nxsched_add_prioritized) +*(.text.nxsched_add_readytorun) +*(.text.nxsched_get_files) +*(.text.nxsched_get_tcb) +*(.text.nxsched_merge_pending) +*(.text.nxsched_process_timer) +*(.text.nxsched_remove_blocked) +*(.text.nxsched_remove_readytorun) +*(.text.nxsched_resume_scheduler) +*(.text.nxsched_suspend_scheduler) +*(.text.nxsem_add_holder) +*(.text.nxsem_add_holder_tcb) +*(.text.nxsem_clockwait) +*(.text.nxsem_foreachholder) +*(.text.nxsem_freecount0holder) +*(.text.nxsem_freeholder) +*(.text.nxsem_post) +*(.text.nxsem_release_holder) +*(.text.nxsem_restore_baseprio) +*(.text.nxsem_tickwait) +*(.text.nxsem_timeout) +*(.text.nxsem_trywait) +*(.text.nxsem_wait) +*(.text.nxsem_wait_uninterruptible) +*(.text.nxsig_timedwait) +*(.text.sched_lock) +*(.text.sched_note_resume) +*(.text.sched_note_suspend) +*(.text.sched_unlock) +*(.text.strcmp) +*(.text.sq_addafter) +*(.text.sq_addlast) +*(.text.sq_rem) +*(.text.sq_remafter) +*(.text.sq_remfirst) +*(.text.uart_connected) +*(.text.up_block_task) +*(.text.up_unblock_task) +*(.text.wd_timer) +*(.text.wd_start) +*(.text.work_thread) +*(.text.work_queue) +*(.text._do_memcpy) + +/* Tropic Eth tune */ +*(.text.devif_poll) +*(.text.devif_poll_tcp_connections) +*(.text.tcp_poll) +*(.text.devif_poll_udp_connections) +*(.text.udp_nextconn) +*(.text.udp_poll) +*(.text.udp_ipv4_select) +*(.text.udp_callback) +*(.text.udp_datahandler) +*(.text.udp_send) +*(.text.udp_active) +*(.text.udp_ipv4_active) +*(.text.psock_udp_sendto) +*(.text.sendto_eventhandler) +*(.text.net_dataevent) +*(.text.devif_conn_event) +*(.text.devif_event_trigger) +*(.text.devif_poll_icmp) +*(.text.icmp_poll) +*(.text.arp_out) +*(.text.arp_find) +*(.text.arp_format) +*(.text.net_ipv4addr_hdrcmp) /* itcm-check-ignore */ +*(.text.net_ipv4addr_copy) /* itcm-check-ignore */ +*(.text.net_ipv4addr_broadcast) /* itcm-check-ignore */ +*(.text.wd_start) +*(.text.arp_arpin) +*(.text.ipv4_input) +*(.text.work_thread) +*(.text.work_queue) + +/* ICM45686 */ +*(.text._ZN8ICM4568612ProcessAccelERKyPKN19InvenSense_ICM456864FIFO4DATAEh) +*(.text._ZN8ICM4568611ProcessGyroERKyPKN19InvenSense_ICM456864FIFO4DATAEh) +*(.text._ZN8ICM456868FIFOReadERKy) +*(.text._ZN8ICM456867RunImplEv) +*(.text._ZN8ICM4568618ProcessTemperatureEPKN19InvenSense_ICM456864FIFO4DATAEh) +*(.text._ZN12I2CSPIDriverI8ICM45686E3RunEv) +*(.text._ZN8ICM4568613FIFOReadCountEv) + +/* BMI088 */ +*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer12RegisterReadENS1_8RegisterE) +*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer13FIFOReadCountEv) +*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer8FIFOReadERKyh) +*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer13RegisterCheckERKNS2_17register_config_tE) +*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer13RegisterWriteENS1_8RegisterEh) +*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer17UpdateTemperatureEv) +*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer23RegisterSetAndClearBitsENS1_8RegisterEhh) +*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer26DataReadyInterruptCallbackEiPvS3_) +*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer7RunImplEv) +*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_Accelerometer9DataReadyEv) +*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_AccelerometerD0Ev) +*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_AccelerometerD1Ev) +*(.text._ZN5Bosch6BMI08813Accelerometer20BMI088_AccelerometerD2Ev) +*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope12RegisterReadENS1_8RegisterE) +*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope13RegisterCheckERKNS2_17register_config_tE) +*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope13RegisterWriteENS1_8RegisterEh) +*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope23RegisterSetAndClearBitsENS1_8RegisterEhh) +*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope26DataReadyInterruptCallbackEiPvS3_) +*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope7RunImplEv) +*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope8FIFOReadERKyh) +*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_Gyroscope9DataReadyEv) +*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_GyroscopeD0Ev) +*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_GyroscopeD1Ev) +*(.text._ZN5Bosch6BMI0889Gyroscope16BMI088_GyroscopeD2Ev) +*(.text._ZN12I2CSPIDriverI6BMI088E3RunEv) + +/* BMM350 */ +*(.text._ZN12I2CSPIDriverI6BMM350E3RunEv) +*(.text._ZN6BMM3507RunImplEv) +*(.text._ZN6BMM35013RegisterWriteEN12Bosch_BMM3508RegisterEh) +*(.text._ZN6BMM35012RegisterReadEN12Bosch_BMM3508RegisterEPh) +*(.text._ZN6BMM35014ReadOutRawDataEPf) diff --git a/boards/nxp/mr-tropic/nuttx-config/scripts/script.ld b/boards/nxp/mr-tropic/nuttx-config/scripts/script.ld new file mode 100644 index 0000000000..8e5f852a82 --- /dev/null +++ b/boards/nxp/mr-tropic/nuttx-config/scripts/script.ld @@ -0,0 +1,187 @@ +/**************************************************************************** + * boards/nxp/mr-tropic/nuttx-config/scripts/script.ld + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/* Specify the memory areas */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x70020000, LENGTH = 4194304 - 256K + sram (rwx) : ORIGIN = 0x20200000, LENGTH = 512K + itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 384K + dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 127K + dtcm_nocache (rwx) : ORIGIN = 0x2001FC00, LENGTH = 1K +} + +OUTPUT_ARCH(arm) +EXTERN(_vectors) +EXTERN(g_flash_config) +EXTERN(g_image_vector_table) +EXTERN(g_boot_data) +EXTERN(board_get_manifest) +EXTERN(_bootdelay_signature) + +ENTRY(_stext) + +SECTIONS +{ + /* Image Vector Table and Boot Data for booting from external flash */ + + .boot_hdr : ALIGN(4) + { + FILL(0xff) + __boot_hdr_start__ = ABSOLUTE(.) ; + KEEP(*(.boot_hdr.conf)) + . = 0x1000 ; + KEEP(*(.boot_hdr.ivt)) + . = 0x1020 ; + KEEP(*(.boot_hdr.boot_data)) + . = 0x1030 ; + KEEP(*(.boot_hdr.dcd_data)) + __boot_hdr_end__ = ABSOLUTE(.) ; + . = 0x2000 ; + } >flash + + /* Workaround for ethernet issue, by placing g_desc_pool into DTCM, + which effectively puts it into a no-cache region */ + .dtcm_nocache : { + *(.bss.g_desc_pool) + } > dtcm_nocache + + .vectors : + { + KEEP(*(.vectors)) + *(.text .text.__start) + } >flash + + .itcmfunc : + { + . = ALIGN(8); + _sitcmfuncs = ABSOLUTE(.); + FILL(0xFF) + . = 0x40 ; + *(.ram_vectors) + INCLUDE "itcm_static_functions.ld" + INCLUDE "itcm_functions_includes.ld" + . = ALIGN(8); + _eitcmfuncs = ABSOLUTE(.); + } > itcm AT > flash + + _fitcmfuncs = LOADADDR(.itcmfunc); + + .text : + { + _stext = ABSOLUTE(.); + *(.vectors) + . = ALIGN(32); + /* + This signature provides the bootloader with a way to delay booting + */ + _bootdelay_signature = ABSOLUTE(.); + FILL(0xffecc2925d7d05c5) + . += 8; + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + . = ALIGN(4096); + _etext = ABSOLUTE(.); + _srodata = ABSOLUTE(.); + *(.rodata .rodata.*) + . = ALIGN(4096); + _erodata = ABSOLUTE(.); + } > flash + + .init_section : + { + _sinit = ABSOLUTE(.); + KEEP(*(SORT_BY_INIT_PRIORITY(.init_array.*) SORT_BY_INIT_PRIORITY(.ctors.*))) + KEEP(*(.init_array .ctors)) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : + { + *(.ARM.extab*) + } > flash + + .ARM.exidx : + { + __exidx_start = ABSOLUTE(.); + *(.ARM.exidx*) + __exidx_end = ABSOLUTE(.); + } > flash + + _eronly = ABSOLUTE(.); + + .data : + { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + . = ALIGN(4); + _edata = ABSOLUTE(.); + } > sram AT > flash + + .ramfunc ALIGN(4): + { + _sramfuncs = ABSOLUTE(.); + *(.ramfunc .ramfunc.*) + _eramfuncs = ABSOLUTE(.); + } > sram AT > flash + + _framfuncs = LOADADDR(.ramfunc); + + .bss : + { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + . = ALIGN(4); + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } + + _boot_loadaddr = ORIGIN(flash); + _boot_size = LENGTH(flash); + _ram_size = LENGTH(sram); + _sdtcm = ORIGIN(dtcm); + _edtcm = ORIGIN(dtcm) + LENGTH(dtcm); +} diff --git a/boards/nxp/mr-tropic/src/CMakeLists.txt b/boards/nxp/mr-tropic/src/CMakeLists.txt new file mode 100644 index 0000000000..4f0710f546 --- /dev/null +++ b/boards/nxp/mr-tropic/src/CMakeLists.txt @@ -0,0 +1,86 @@ +############################################################################ +# +# Copyright (c) 2024 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +if("${PX4_BOARD_LABEL}" STREQUAL "bootloader") + add_compile_definitions(BOOTLOADER) + add_library(drivers_board + bootloader_main.c + init.c + usb.c + imxrt_flexspi_nor_boot.c + imxrt_flexspi_nor_flash.c + timer_config.cpp + ) + target_link_libraries(drivers_board + PRIVATE + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer #gpio + arch_io_pins # iotimer + arch_board_romapi + bootloader + ) + target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/bootloader/common) + +else() + + px4_add_library(drivers_board + i2c.cpp + init.c + sdhc.c + spi.cpp + timer_config.cpp + tropic_led_pwm.cpp + usb.c + imxrt_flexspi_nor_boot.c + imxrt_flexspi_nor_flash.c + imxrt_flexspi_storage.c + imxrt_ocram_initialize.c + hw_rev_ver_tropic.c + manifest.c + ) + + + # Force compiler not to use builtin functions (like memcpy) + # to optimize for loops in init.c (imxrt_ocram_initialize) + set_source_files_properties(imxrt_ocram_initialize.c PROPERTIES COMPILE_FLAGS -fno-builtin) + + target_link_libraries(drivers_board + PRIVATE + arch_board_romapi + arch_spi + nuttx_arch # sdio + nuttx_drivers # sdio + px4_layer + ) + +endif() diff --git a/boards/nxp/mr-tropic/src/board_config.h b/boards/nxp/mr-tropic/src/board_config.h new file mode 100644 index 0000000000..45e6eecd54 --- /dev/null +++ b/boards/nxp/mr-tropic/src/board_config.h @@ -0,0 +1,355 @@ +/**************************************************************************** + * + * Copyright (c) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file board_config.h + * + * Tropic Community internal definitions + */ + +#pragma once + +/**************************************************************************************************** + * Included Files + ****************************************************************************************************/ + +#include +#include +#include +#include + +#include "imxrt_gpio.h" +#include "imxrt_iomuxc.h" +#include "hardware/imxrt_pinmux.h" +#include "hardware/imxrt_usb_analog.h" + +#include +#include + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +/* Configuration ************************************************************************************/ + +/* FMURT1062 GPIOs ***********************************************************************************/ +/* LEDs */ +/* An RGB LED is connected through GPIO as shown below: + */ +#define LED_IOMUX (IOMUX_OPENDRAIN | IOMUX_PULL_NONE | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_SLOW) +#define GPIO_nLED_RED /* GPIO_EMC_33 GPIO3_IO19 */ (GPIO_PORT3 | GPIO_PIN19 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LED_IOMUX) +#define GPIO_nLED_BLUE /* GPIO_EMC_34 GPIO3_IO20 */ (GPIO_PORT3 | GPIO_PIN20 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LED_IOMUX) +#define GPIO_nLED_GREEN /* GPIO_EMC_38 GPIO3_IO24 */ (GPIO_PORT3 | GPIO_PIN24 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | LED_IOMUX) + +#define BOARD_HAS_CONTROL_STATUS_LEDS 1 +#define BOARD_OVERLOAD_LED LED_RED +#define BOARD_ARMED_STATE_LED LED_BLUE + +/* + * Define the ability to shut off off the sensor signals + * by changing the signals to inputs + */ + +#define _PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT | IOMUX_PULL_DOWN_100K | IOMUX_CMOS_INPUT)) + +/* Define the Chip Selects, Data Ready and Control signals per SPI bus */ + +#define CS_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_UP_100K | IOMUX_DRIVE_33OHM | IOMUX_SPEED_LOW | IOMUX_SLEW_FAST) +#define OUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_UP_100K | IOMUX_DRIVE_50OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST) + + +/* SPI1 off */ + +#define _GPIO_LPSPI1_SCK /* GPIO_EMC_27 GPIO4_IO27 */ (GPIO_PORT4 | GPIO_PIN27 | CS_IOMUX) +#define _GPIO_LPSPI1_MISO /* GPIO_EMC_29 GPIO4_IO29 */ (GPIO_PORT4 | GPIO_PIN29 | CS_IOMUX) +#define _GPIO_LPSPI1_MOSI /* GPIO_EMC_28 GPIO4_IO28 */ (GPIO_PORT4 | GPIO_PIN28 | CS_IOMUX) + +#define GPIO_SPI1_SCK_OFF _PIN_OFF(_GPIO_LPSPI1_SCK) +#define GPIO_SPI1_MISO_OFF _PIN_OFF(_GPIO_LPSPI1_MISO) +#define GPIO_SPI1_MOSI_OFF _PIN_OFF(_GPIO_LPSPI1_MOSI) + +#define _GPIO_LPSPI3_SCK /* GPIO_AD_B1_15 GPIO1_IO27 */ (GPIO_PORT1 | GPIO_PIN31 | CS_IOMUX) +#define _GPIO_LPSPI3_MISO /* GPIO_AD_B1_13 GPIO1_IO27 */ (GPIO_PORT1 | GPIO_PIN29 | CS_IOMUX) +#define _GPIO_LPSPI3_MOSI /* GPIO_AD_B1_14 GPIO1_IO27 */ (GPIO_PORT1 | GPIO_PIN30 | CS_IOMUX) + +#define GPIO_SPI3_SCK_OFF _PIN_OFF(_GPIO_LPSPI3_SCK) +#define GPIO_SPI3_MISO_OFF _PIN_OFF(_GPIO_LPSPI3_MISO) +#define GPIO_SPI3_MOSI_OFF _PIN_OFF(_GPIO_LPSPI3_MOSI) + +/* Define the SPI4 Data Ready and Control signals */ + +#define GPIO_SPI4_DRDY7_EXTERNAL1 /* GPIO_EMC_35 GPIO3_IO21*/ (GPIO_PORT3 | GPIO_PIN21 | GPIO_INPUT | DRDY_IOMUX) + +#define GPIO_DRDY_OFF_SPI4_DRDY7_EXTERNAL1 _PIN_OFF(GPIO_SPI4_DRDY7_EXTERNAL1) + +#define ADC_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_HIZ) + +#define ADC1_CH(n) (n) +#define ADC1_GPIO(n, p) (GPIO_PORT1 | GPIO_PIN##p | ADC_IOMUX) // + +/* Define GPIO pins used as ADC N.B. Channel numbers are for reference, */ + +#define PX4_ADC_GPIO \ + /* ADC_5V_RAIL_SENSE GPIO_AD_B1_08 GPIO1 Pin 24 */ ADC1_GPIO(0, 24) + +/* Define Channel numbers must match above GPIO pin IN(n)*/ + +#define ADC_5V_RAIL_SENSE /* GPIO_AD_B1_08 GPIO1 Pin 24 */ ADC1_CH(13) + +#define ADC_CHANNELS (1 << ADC_5V_RAIL_SENSE) + +/* Power supply control and monitoring GPIOs */ + +#define GENERAL_INPUT_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_UP_47K | IOMUX_DRIVE_HIZ) +#define GENERAL_OUTPUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_KEEP | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST) + + +/* PWM + */ + +#define DIRECT_PWM_OUTPUT_CHANNELS 8 +#define BOARD_NUM_IO_TIMERS 4 + +// Input Capture not supported on MVP + +#define BOARD_HAS_NO_CAPTURE + +//#define BOARD_HAS_UI_LED_PWM 1 Not ported yet (Still Kinetis driver) +#define BOARD_HAS_LED_PWM 1 +#define BOARD_LED_PWM_DRIVE_ACTIVE_LOW 1 +#define BOARD_HAS_CUSTOM_LED_PWM 1 + +#define PWM_LED_RED /* GPIO_EMC_33 */ (GPIO_FLEXPWM3_PWMA02_1 | GENERAL_OUTPUT_IOMUX) +#define PWM_LED_BLUE /* GPIO_EMC_34 */ (GPIO_FLEXPWM3_PWMB02_1 | GENERAL_OUTPUT_IOMUX) +#define PWM_LED_GREEN /* GPIO_EMC_38 */ (GPIO_FLEXPWM1_PWMA03_2 | GENERAL_OUTPUT_IOMUX) + + +/* ETHERNET GPIO */ + +#define GPIO_ENET_RX_ER_CONFIG1 /* GPIO_B1_11 GPIO2_IO27 PHYAD18 Open */ (GPIO_PORT2 | GPIO_PIN27 | GPIO_INPUT | IOMUX_PULL_NONE) +#define GPIO_ENET_RX_DATA01_CONFIG4 /* GPIO_B1_05 GPIO2_IO21 (RMII-clkmode) High */ (GPIO_PORT2 | GPIO_PIN21 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | GENERAL_OUTPUT_IOMUX) +#define GPIO_ENET_RX_DATA00_CONFIG5 /* GPIO_B1_04 GPIO2_IO20 SLAVE:Auto Open */ (GPIO_PORT2 | GPIO_PIN20 | GPIO_INPUT | IOMUX_PULL_NONE) +#define GPIO_ENET_CRS_DV_CONFIG6 /* GPIO_B1_06 GPIO4_IO22 SLAVE:POl Corr Low */ (GPIO_PORT2 | GPIO_PIN22 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX) + +/* Tone alarm output */ + +//FIXME FlexPWM TONE DRIVER +#define TONE_ALARM_FLEXPWM PWMA_VAL +#define TONE_ALARM_TIMER 1 /* FlexPWM 3 */ +#define TONE_ALARM_CHANNEL 0 /* GPIO_EMC_23 PWM1_PWMA00 */ + +#define GPIO_BUZZER_1 /* GPIO_EMC_23 GPIO4_IO23 */ (GPIO_PORT4 | GPIO_PIN23 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO | GENERAL_OUTPUT_IOMUX) + +#define GPIO_TONE_ALARM_IDLE GPIO_BUZZER_1 +#define GPIO_TONE_ALARM (GPIO_FLEXPWM1_PWMA00_1 | GENERAL_OUTPUT_IOMUX) + +/* USB OTG FS + * + * VBUS_VALID is detected in USB_ANALOG_USB1_VBUS_DETECT_STAT + */ + +/* High-resolution timer */ +#define HRT_TIMER 1 /* use GPT1 for the HRT */ +#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 1 */ + +#define RC_SERIAL_PORT "/dev/ttyS6" +//#define RC_SERIAL_SINGLEWIRE 1 // Suport Single wire wiring +//#define RC_SERIAL_SWAP_RXTX 1 // Set Swap (but not supported in HW) to use Single wire +//#define RC_SERIAL_SWAP_USING_SINGLEWIRE 1 // Set to use Single wire swap as HW does not support swap +#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT + +/* Safety Switch is HW version dependent on having an PX4IO + * So we init to a benign state with the _INIT definition + * and provide the the non _INIT one for the driver to make a run time + * decision to use it. + */ +#define SAFETY_INIT_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_HIZ) +#define SAFETY_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_NONE | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_SLOW) +#define SAFETY_SW_IOMUX (IOMUX_CMOS_INPUT | IOMUX_PULL_UP_22K | IOMUX_DRIVE_HIZ) + +/* Safety Switch is HW version dependent on having an PX4IO + * So we init to a benign state with the _INIT definition + * and provide the the non _INIT one for the driver to make a run time + * decision to use it. + */ +#define GPIO_nSAFETY_SWITCH_LED_OUT_INIT /* EMC_39 */ (GPIO_PORT3 | GPIO_PIN25 | GPIO_INPUT | SAFETY_INIT_IOMUX) +#define GPIO_nSAFETY_SWITCH_LED_OUT /* EMC_39 */ (GPIO_PORT3 | GPIO_PIN25 | GPIO_OUTPUT | GPIO_OUTPUT_ONE | SAFETY_IOMUX) + +/* Enable the FMU to control it if there is no px4io fixme:This should be BOARD_SAFETY_LED(__ontrue) */ +#define GPIO_LED_SAFETY GPIO_nSAFETY_SWITCH_LED_OUT + +#define GPIO_SAFETY_SWITCH_IN /* GPIO_B0_12 GPIO2_IO12 */ (GPIO_PORT2 | GPIO_PIN12 | GPIO_INPUT | SAFETY_SW_IOMUX) +/* Enable the FMU to use the switch it if there is no px4io fixme:This should be BOARD_SAFTY_BUTTON() */ +#define GPIO_BTN_SAFETY GPIO_SAFETY_SWITCH_IN /* Enable the FMU to control it if there is no px4io */ + +#define SDIO_SLOTNO 0 /* Only one slot */ +#define SDIO_MINOR 0 + +/* SD card bringup does not work if performed on the IDLE thread because it + * will cause waiting. Use either: + * + * CONFIG_BOARDCTL=y, OR + * CONFIG_BOARD_INITIALIZE=y && CONFIG_BOARD_INITTHREAD=y + */ + +#if defined(CONFIG_BOARD_INITIALIZE) && !defined(CONFIG_BOARDCTL) && \ + !defined(CONFIG_BOARD_INITTHREAD) +# warning SDIO initialization cannot be perfomed on the IDLE thread +#endif + +/* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction) + * this board support the ADC system_power interface, and therefore + * provides the true logic GPIO BOARD_ADC_xxxx macros. + */ + +#define BOARD_NUMBER_BRICKS 1 +#define BOARD_NUMBER_DIGITAL_BRICKS 1 + +#define BOARD_ADC_BRICK_VALID 1 + +#define BOARD_ADC_USB_CONNECTED (board_read_VBUS_state() == 0) + +/* FMUv5 never powers odd the Servo rail */ + +#define BOARD_ADC_SERVO_VALID (1) + + +/* This board provides a DMA pool and APIs */ +#define BOARD_DMA_ALLOC_POOL_SIZE 5120 + +/* This board provides the board_on_reset interface */ + +#define BOARD_HAS_ON_RESET 1 +#define BOARD_HAS_ISP_BOOTLOADER 1 + +#define PX4_GPIO_INIT_LIST { \ + GPIO_FLEXCAN3_TX, \ + GPIO_FLEXCAN3_RX, \ + GPIO_TONE_ALARM_IDLE, \ + GPIO_SAFETY_SWITCH_IN, \ + GPIO_ENET_RX_ER_CONFIG1, \ + GPIO_ENET_RX_DATA01_CONFIG4, \ + GPIO_ENET_RX_DATA00_CONFIG5, \ + GPIO_ENET_CRS_DV_CONFIG6, \ + GPIO_ENET_RST \ + } + +#define BOARD_ENABLE_CONSOLE_BUFFER + +/* To detect IMU */ +#define BOARD_HAS_HW_VERSIONING 1 +#define BOARD_HAS_HW_SPLIT_VERSIONING 1 +#define HW_INFO_INIT_PREFIX "TROPIC" + +#define BOARD_NUM_SPI_CFG_HW_VERSIONS 3 +// Base/FMUM +#define TROPIC_0 HW_FMUM_ID(0x0) // ICM45686 +#define TROPIC_1 HW_FMUM_ID(0x1) // ICM42688 +#define TROPIC_2 HW_FMUM_ID(0x2) // ICM42686 + +/* Flash instance for storage */ +#define NOR_INSTANCE 1 + +__BEGIN_DECLS + +/**************************************************************************************************** + * Public Types + ****************************************************************************************************/ + +/**************************************************************************************************** + * Public data + ****************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/**************************************************************************************************** + * Public Functions + ****************************************************************************************************/ + +/**************************************************************************** + * Name: fmurt1062_usdhc_initialize + * + * Description: + * Initialize SDIO-based MMC/SD card support + * + ****************************************************************************/ + +int fmurt1062_usdhc_initialize(void); + +/**************************************************************************************************** + * Name: imxrt_spidev_initialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the PX4FMU board. + * + ****************************************************************************************************/ + +extern void imxrt_spidev_initialize(void); + +/************************************************************************************ + * Name: imxrt_spi_bus_initialize + * + * Description: + * Called to configure SPI Buses. + * + ************************************************************************************/ + +extern int imxrt1062_spi_bus_initialize(void); + +/************************************************************************************ + * Name: imxrt_usb_initialize + * + * Description: + * Called to configure USB. + * + ************************************************************************************/ + +extern void imxrt_spiinitialize(void); + +extern int imxrt_usb_initialize(void); + +extern void imxrt_usbinitialize(void); + +extern void board_peripheral_reset(int ms); + +extern void fmurt1062_timer_initialize(void); + +#include + +void imxrt_flash_romapi_initialize(void); + +int imxrt_flexspi_storage_initialize(void); + +#endif /* __ASSEMBLY__ */ + +__END_DECLS diff --git a/boards/nxp/mr-tropic/src/bootloader_main.c b/boards/nxp/mr-tropic/src/bootloader_main.c new file mode 100644 index 0000000000..04008aa2ff --- /dev/null +++ b/boards/nxp/mr-tropic/src/bootloader_main.c @@ -0,0 +1,61 @@ +/**************************************************************************** + * + * Copyright (c) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file bootloader_main.c + * + * FMU-specific early startup code for bootloader +*/ + +#include "board_config.h" +#include "bl.h" + +#include +#include +#include +#include +#include "arm_internal.h" +#include + +extern int sercon_main(int c, char **argv); + +void board_late_initialize(void) +{ + sercon_main(0, NULL); +} + +extern void sys_tick_handler(void); +void board_timerhook(void) +{ + sys_tick_handler(); +} diff --git a/boards/nxp/mr-tropic/src/hw_config.h b/boards/nxp/mr-tropic/src/hw_config.h new file mode 100644 index 0000000000..22e0680203 --- /dev/null +++ b/boards/nxp/mr-tropic/src/hw_config.h @@ -0,0 +1,130 @@ +/* + * hw_config.h + * + * Created on: May 17, 2015 + * Author: david_s5 + */ + +#ifndef HW_CONFIG_H_ +#define HW_CONFIG_H_ + +/**************************************************************************** + * 10-8--2016: + * To simplify the ripple effect on the tools, we will be using + * /dev/serial/by-id/PX4 to locate PX4 devices. Therefore + * moving forward all Bootloaders must contain the prefix "PX4 BL " + * in the USBDEVICESTRING + * This Change will be made in an upcoming BL release + ****************************************************************************/ +/* + * Define usage to configure a bootloader + * + * + * Constant example Usage + * APP_LOAD_ADDRESS 0x08004000 - The address in Linker Script, where the app fw is org-ed + * BOOTLOADER_DELAY 5000 - Ms to wait while under USB pwr or bootloader request + * BOARD_FMUV2 + * INTERFACE_USB 1 - (Optional) Scan and use the USB interface for bootloading + * INTERFACE_USART 1 - (Optional) Scan and use the Serial interface for bootloading + * USBDEVICESTRING "PX4 BL FMU v2.x" - USB id string + * USBPRODUCTID 0x0011 - PID Should match defconfig + * BOOT_DELAY_ADDRESS 0x000001a0 - (Optional) From the linker script from Linker Script to get a custom + * delay provided by an APP FW + * BOARD_TYPE 9 - Must match .prototype boad_id + * _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) - Run time flash size detection + * BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) - Run time determine the physical last sector + * BOARD_FLASH_SECTORS 11 - Hard coded zero based last sector + * BOARD_FLASH_SIZE (_FLASH_KBYTES*1024)- Total Flash size of device, determined at run time. + * (1024 * 1024) - Hard coded Total Flash of device - The bootloader and app reserved will be deducted + * programmatically + * + * BOARD_FIRST_FLASH_SECTOR_TO_ERASE 2 - Optional sectors index in the flash_sectors table (F4 only), to begin erasing. + * This is to allow sectors to be reserved for app fw usage. That will NOT be erased + * during a FW upgrade. + * The default is 0, and selects the first sector to be erased, as the 0th entry in the + * flash_sectors table. Which is the second physical sector of FLASH in the device. + * The first physical sector of FLASH is used by the bootloader, and is not defined + * in the table. + * + * APP_RESERVATION_SIZE (BOARD_FIRST_FLASH_SECTOR_TO_ERASE * 16 * 1024) - Number of bytes reserved by the APP FW. This number plus + * BOOTLOADER_RESERVATION_SIZE will be deducted from + * BOARD_FLASH_SIZE to determine the size of the App FW + * and hence the address space of FLASH to erase and program. + * USBMFGSTRING "PX4 AP" - Optional USB MFG string (default is '3D Robotics' if not defined.) + * SERIAL_BREAK_DETECT_DISABLED - Optional prevent break selection on Serial port from entering or staying in BL + * + * * Other defines are somewhat self explanatory. + */ + +/* Boot device selection list*/ +#define USB0_DEV 0x01 +#define SERIAL0_DEV 0x02 +#define SERIAL1_DEV 0x04 + +#define APP_LOAD_ADDRESS 0x70020000 +#define APP_VECTOR_OFFSET 0x2000 +#define BOOTLOADER_DELAY 5000 +#define INTERFACE_USB 1 +#define INTERFACE_USB_CONFIG "/dev/ttyACM0" + +//#define USE_VBUS_PULL_DOWN +#define INTERFACE_USART 1 +#define INTERFACE_USART_CONFIG "/dev/ttyS0,1500000" +#define BOOT_DELAY_ADDRESS 0x00039FA0 +#define BOARD_TYPE 37 +// The board has a 64 Mb part with 16384, 4K secors, but we artificialy limit it to 4 Mb +// as 1024, 4K sectors +#define BOARD_FLASH_SECTORS 960 // 1024 * 4k sectors, 128k for bootloader, 128k for storage +#define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 32 // We resreve 128K for the bootloader +#define BOARD_FLASH_SIZE (BOARD_FLASH_SECTORS * 4096) + +#define OSC_FREQ 24 + +#define BOARD_PIN_LED_ACTIVITY GPIO_nLED_BLUE // BLUE +#define BOARD_PIN_LED_BOOTLOADER GPIO_nLED_GREEN // GREEN +#define BOARD_LED_ON 0 +#define BOARD_LED_OFF 1 + +#define SERIAL_BREAK_DETECT_DISABLED 1 + +/* + * Uncommenting this allows to force the bootloader through + * a PWM output pin. As this can accidentally initialize + * an ESC prematurely, it is not recommended. This feature + * has not been used and hence defaults now to off. + * + * # define BOARD_FORCE_BL_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN14) + * # define BOARD_FORCE_BL_PIN_IN (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTE|GPIO_PIN11) + * + * # define BOARD_POWER_PIN_OUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) + * # define BOARD_POWER_ON 1 + * # define BOARD_POWER_OFF 0 + * # undef BOARD_POWER_PIN_RELEASE // Leave pin enabling Power - un comment to release (disable power) + * +*/ + +#if !defined(ARCH_SN_MAX_LENGTH) +# define ARCH_SN_MAX_LENGTH 12 +#endif + +#if !defined(APP_RESERVATION_SIZE) +# define APP_RESERVATION_SIZE 0 +#endif + +#if !defined(BOARD_FIRST_FLASH_SECTOR_TO_ERASE) +# define BOARD_FIRST_FLASH_SECTOR_TO_ERASE 1 +#endif + +#if !defined(USB_DATA_ALIGN) +# define USB_DATA_ALIGN +#endif + +#ifndef BOOT_DEVICES_SELECTION +# define BOOT_DEVICES_SELECTION USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#ifndef BOOT_DEVICES_FILTER_ONUSB +# define BOOT_DEVICES_FILTER_ONUSB USB0_DEV|SERIAL0_DEV|SERIAL1_DEV +#endif + +#endif /* HW_CONFIG_H_ */ diff --git a/boards/nxp/mr-tropic/src/hw_rev_ver_tropic.c b/boards/nxp/mr-tropic/src/hw_rev_ver_tropic.c new file mode 100644 index 0000000000..7414c21a32 --- /dev/null +++ b/boards/nxp/mr-tropic/src/hw_rev_ver_tropic.c @@ -0,0 +1,165 @@ +/**************************************************************************** + * + * Copyright (C) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file hw_rev_ver_canhubk3.c + * CANHUBK3 Hardware Revision and Version ID API + */ +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +#if defined(BOARD_HAS_HW_VERSIONING) + +#define HW_INFO_SIZE HW_INFO_VER_DIGITS + HW_INFO_REV_DIGITS + +/**************************************************************************** + * Private Data + ****************************************************************************/ +static int hw_revision = 0; +static char hw_info[HW_INFO_SIZE] = {0}; +#if defined(BOARD_HAS_HW_SPLIT_VERSIONING) +static char hw_base_info[HW_INFO_SIZE] = {0}; +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ +/************************************************************************************ + * Name: board_get_hw_type + * + * Description: + * Optional returns a 0 terminated string defining the HW type. + * + * Input Parameters: + * None + * + * Returned Value: + * a 0 terminated string defining the HW type. This my be a 0 length string "" + * + ************************************************************************************/ + +__EXPORT const char *board_get_hw_type_name() +{ + return (const char *) hw_info; +} + +#if defined(BOARD_HAS_HW_SPLIT_VERSIONING) +/************************************************************************************ + * Name: board_get_hw_base_type_name + * + * Description: + * Optional returns a 0 terminated string defining the base type. + * + * Input Parameters: + * None + * + * Returned Value: + * a 0 terminated string defining the HW type. This my be a 0 length string "" + * + ************************************************************************************/ + +__EXPORT const char *board_get_hw_base_type_name() +{ + return (const char *) hw_base_info; +} +#endif + +/************************************************************************************ + * Name: board_get_hw_version + * + * Description: + * Optional returns a integer HW version + * + * Input Parameters: + * None + * + * Returned Value: + * An integer value of this boards hardware version. + * A value of -1 is the default for boards not supporting the BOARD_HAS_VERSIONING API. + * A value of 0 is the default for boards supporting the API but not having version. + * + ************************************************************************************/ + +__EXPORT int board_get_hw_version() +{ + return 0; +} + +/************************************************************************************ + * Name: board_get_hw_revision + * + * Description: + * Optional returns a integer HW revision + * + * Input Parameters: + * None + * + * Returned Value: + * An integer value of this boards hardware revision. + * A value of -1 is the default for boards not supporting the BOARD_HAS_VERSIONING API. + * A value of 0 is the default for boards supporting the API but not having revision. + * + ************************************************************************************/ + +__EXPORT int board_get_hw_revision() +{ + return hw_revision; +} + +/************************************************************************************ + * Name: board_determine_hw_info + * + * Description: + * Uses GPIO to detect MR-CANHUBK3-ADAP + * + ************************************************************************************/ + +int board_determine_hw_info() +{ + hw_revision = 0; //TODO Read fuses + + sprintf(hw_info, "%03d", hw_revision); + + return 0; +} +#endif diff --git a/boards/nxp/mr-tropic/src/i2c.cpp b/boards/nxp/mr-tropic/src/i2c.cpp new file mode 100644 index 0000000000..a118a69d0f --- /dev/null +++ b/boards/nxp/mr-tropic/src/i2c.cpp @@ -0,0 +1,40 @@ +/**************************************************************************** + * + * Copyright (C) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include + +constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = { + initI2CBusExternal(1), + initI2CBusExternal(3), + initI2CBusInternal(4), +}; diff --git a/boards/nxp/mr-tropic/src/imxrt_flexspi_nor_boot.c b/boards/nxp/mr-tropic/src/imxrt_flexspi_nor_boot.c new file mode 100644 index 0000000000..894c959d33 --- /dev/null +++ b/boards/nxp/mr-tropic/src/imxrt_flexspi_nor_boot.c @@ -0,0 +1,55 @@ +/**************************************************************************** + * boards/arm/imxrt/imxrt1064-evk/src/imxrt_flexspi_nor_boot.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "imxrt_flexspi_nor_boot.h" + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +locate_data(".boot_hdr.ivt") +const struct ivt_s g_image_vector_table = { + IVT_HEADER, /* IVT Header */ + IMAGE_ENTRY_ADDRESS, /* Image Entry Function */ + IVT_RSVD, /* Reserved = 0 */ + (uint32_t)DCD_ADDRESS, /* Address where DCD information is stored */ + (uint32_t)BOOT_DATA_ADDRESS, /* Address where BOOT Data Structure is stored */ + (uint32_t)IMAG_VECTOR_TABLE, /* Pointer to IVT Self (absolute address */ + (uint32_t)CSF_ADDRESS, /* Address where CSF file is stored */ + IVT_RSVD /* Reserved = 0 */ +}; + +locate_data(".boot_hdr.boot_data") +const struct boot_data_s g_boot_data = { + IMAGE_DEST, /* boot start location */ + (IMAGE_DEST_END - IMAGE_DEST), /* size */ + PLUGIN_FLAG, /* Plugin flag */ + 0xffffffff /* empty - extra data word */ +}; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/* None */ diff --git a/boards/nxp/mr-tropic/src/imxrt_flexspi_nor_boot.h b/boards/nxp/mr-tropic/src/imxrt_flexspi_nor_boot.h new file mode 100644 index 0000000000..ca6b9cf8b3 --- /dev/null +++ b/boards/nxp/mr-tropic/src/imxrt_flexspi_nor_boot.h @@ -0,0 +1,166 @@ +/**************************************************************************** + * boards/arm/imxrt/imxrt1064-evk/src/imxrt_flexspi_nor_boot.h + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __BOARDS_ARM_IMXRT_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_BOOT_H +#define __BOARDS_ARM_IMXRT_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_BOOT_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* IVT Data */ + +#define IVT_MAJOR_VERSION 0x4 +#define IVT_MAJOR_VERSION_SHIFT 0x4 +#define IVT_MAJOR_VERSION_MASK 0xf +#define IVT_MINOR_VERSION 0x1 +#define IVT_MINOR_VERSION_SHIFT 0x0 +#define IVT_MINOR_VERSION_MASK 0xf + +#define IVT_VERSION(major, minor) \ + ((((major) & IVT_MAJOR_VERSION_MASK) << IVT_MAJOR_VERSION_SHIFT) | \ + (((minor) & IVT_MINOR_VERSION_MASK) << IVT_MINOR_VERSION_SHIFT)) + +#define IVT_TAG_HEADER (0xd1) /* Image Vector Table */ +#define IVT_SIZE 0x2000 +#define IVT_PAR IVT_VERSION(IVT_MAJOR_VERSION, IVT_MINOR_VERSION) + +#define IVT_HEADER (IVT_TAG_HEADER | (IVT_SIZE << 8) | (IVT_PAR << 24)) +#define IVT_RSVD (uint32_t)(0x00000000) + +/* DCD Data */ + +#define DCD_TAG_HEADER (0xd2) +#define DCD_TAG_HEADER_SHIFT (24) +#define DCD_VERSION (0x40) +#define DCD_ARRAY_SIZE 1 + +#define FLASH_BASE 0x70000000 +#define FLASH_END 0x70400000 + +/* This needs to take into account the memory configuration at boot + * bootloader + */ + +#define ROM_BOOTLOADER_OCRAM_RES 0x8000 +#define OCRAM_BASE (0x20200000 + ROM_BOOTLOADER_OCRAM_RES) +#define OCRAM_END (OCRAM_BASE + (512 * 1024) + (256 * 1024) \ + - ROM_BOOTLOADER_OCRAM_RES) + +#define SCLK 1 +#if defined(CONFIG_BOOT_RUNFROMFLASH) +# define IMAGE_DEST FLASH_BASE +# define IMAGE_DEST_END FLASH_END +# define IMAGE_DEST_OFFSET 0 +#else +# define IMAGE_DEST OCRAM_BASE +# define IMAGE_DEST_END OCRAM_END +# define IMAGE_DEST_OFFSET IVT_SIZE +#endif + +#define LOCATE_IN_DEST(x) (((uint32_t)(x)) - FLASH_BASE + IMAGE_DEST) +#define LOCATE_IN_SRC(x) (((uint32_t)(x)) - IMAGE_DEST + FLASH_BASE) + +#ifdef CONFIG_IMXRT1064_EVK_SDRAM +# define DCD_ADDRESS &g_dcd_data +#else +# define DCD_ADDRESS 0 +#endif +#define BOOT_DATA_ADDRESS LOCATE_IN_DEST(&g_boot_data) +#define CSF_ADDRESS 0 +#define PLUGIN_FLAG (uint32_t)0 + +/* Located in Destination Memory */ + +#define IMAGE_ENTRY_ADDRESS ((uint32_t)&_vectors) +#define IMAG_VECTOR_TABLE LOCATE_IN_DEST(&g_image_vector_table) + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* IVT Data */ + +struct ivt_s { + /* Header with tag #HAB_TAG_IVT, length and HAB version fields + * (see data) + */ + + uint32_t hdr; + + /* Absolute address of the first instruction to execute from the + * image + */ + + uint32_t entry; + + /* Reserved in this version of HAB: should be NULL. */ + + uint32_t reserved1; + + /* Absolute address of the image DCD: may be NULL. */ + + uint32_t dcd; + + /* Absolute address of the Boot Data: may be NULL, but not interpreted + * any further by HAB + */ + + uint32_t boot_data; + + /* Absolute address of the IVT. */ + + uint32_t self; + + /* Absolute address of the image CSF. */ + + uint32_t csf; + + /* Reserved in this version of HAB: should be zero. */ + + uint32_t reserved2; +}; + +/* Boot Data */ + +struct boot_data_s { + uint32_t start; /* boot start location */ + uint32_t size; /* size */ + uint32_t plugin; /* plugin flag - 1 if downloaded application is plugin */ + uint32_t placeholder; /* placeholder to make even 0x10 size */ +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +extern const struct boot_data_s g_boot_data; +#ifdef CONFIG_IMXRT1064_EVK_SDRAM +extern const uint8_t g_dcd_data[]; +#endif +extern const uint32_t _vectors[]; + +#endif /* __BOARDS_ARM_IMXRT_IMXRT1060_EVK_SRC_IMXRT_FLEXSPI_NOR_BOOT_H */ diff --git a/boards/nxp/mr-tropic/src/imxrt_flexspi_nor_flash.c b/boards/nxp/mr-tropic/src/imxrt_flexspi_nor_flash.c new file mode 100644 index 0000000000..25fcd2e2a1 --- /dev/null +++ b/boards/nxp/mr-tropic/src/imxrt_flexspi_nor_flash.c @@ -0,0 +1,107 @@ +/**************************************************************************** + * boards/arm/imxrt/teensy-4.x/src/imxrt_flexspi_nor_flash.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "imxrt_flexspi_nor_flash.h" + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +enum { + /* SPI instructions */ + + READ_FAST = 0, + READ_STATUS_REG = 1, + WRITE_ENABLE = 3, + SECTOR_ERASE_4K = 5, + READ_FAST_QUAD_OUTPUT = 6, + PAGE_PROGRAM_QUAD_INPUT = 7, + ERASE_BLOCK = 8, + PAGE_PROGRAM = 9, + CHIP_ERASE = 11, +}; + +locate_data(".boot_hdr.conf") +const struct flexspi_nor_config_s g_flash_config = { + .mem_config = + { + .tag = FLEXSPI_CFG_BLK_TAG, + .version = FLEXSPI_CFG_BLK_VERSION, + .read_sample_clksrc = FLASH_READ_SAMPLE_CLK_LOOPBACK_FROM_DQSPAD, + .cs_hold_time = 3u, + .cs_setup_time = 3u, + .column_address_width = 0u, + .device_type = FLEXSPI_DEVICE_TYPE_SERIAL_NOR, + .sflash_pad_type = SERIAL_FLASH_4PADS, + .serial_clk_freq = FLEXSPI_SERIAL_CLKFREQ_133MHz, + .sflash_a1size = 4u * 1024u * 1024u, + .lookup_table = + { + [4 * READ_FAST] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0xeb, + RADDR_SDR, FLEXSPI_4PAD, 0x18), + [4 * READ_FAST + 1] = FLEXSPI_LUT_SEQ(DUMMY_SDR, FLEXSPI_4PAD, 0x06, + READ_SDR, FLEXSPI_4PAD, 0x04), + + [4 * READ_STATUS_REG] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x05, + READ_SDR, FLEXSPI_1PAD, 0x04), + + [4 * WRITE_ENABLE] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x06, + STOP, FLEXSPI_1PAD, 0), + + [4 * SECTOR_ERASE_4K] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x20, + RADDR_SDR, FLEXSPI_1PAD, 0x18), + + [4 * CHIP_ERASE] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x60, + STOP, FLEXSPI_1PAD, 0), + + [4 * ERASE_BLOCK] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0xd8, + RADDR_SDR, FLEXSPI_1PAD, 0x18), + + [4 * PAGE_PROGRAM] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x02, + RADDR_SDR, FLEXSPI_1PAD, 0x18), + [4 * PAGE_PROGRAM + 1] = FLEXSPI_LUT_SEQ(WRITE_SDR, FLEXSPI_1PAD, 0x04, + STOP, FLEXSPI_1PAD, 0x0), + + [4 * READ_FAST_QUAD_OUTPUT] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x6b, + RADDR_SDR, FLEXSPI_1PAD, 0x18), + [4 * READ_FAST_QUAD_OUTPUT + 1] = FLEXSPI_LUT_SEQ(DUMMY_SDR, FLEXSPI_4PAD, 0x08, + READ_SDR, FLEXSPI_4PAD, 0x04), + + [4 * PAGE_PROGRAM_QUAD_INPUT] = FLEXSPI_LUT_SEQ(CMD_SDR, FLEXSPI_1PAD, 0x32, + RADDR_SDR, FLEXSPI_1PAD, 0x18), + [4 * PAGE_PROGRAM_QUAD_INPUT + 1] = FLEXSPI_LUT_SEQ(WRITE_SDR, FLEXSPI_4PAD, 0x04, + STOP, FLEXSPI_1PAD, 0), + + }, + }, + + .page_size = 256u, + .sector_size = 4u * 1024u, + .blocksize = 64u * 1024u, + .is_uniform_blocksize = false, +}; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ diff --git a/boards/nxp/mr-tropic/src/imxrt_flexspi_nor_flash.h b/boards/nxp/mr-tropic/src/imxrt_flexspi_nor_flash.h new file mode 100644 index 0000000000..1fb3f41cce --- /dev/null +++ b/boards/nxp/mr-tropic/src/imxrt_flexspi_nor_flash.h @@ -0,0 +1,349 @@ +/**************************************************************************** + * boards/arm/imxrt/imxrt1064-evk/src/imxrt_flexspi_nor_flash.h + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __BOARDS_ARM_IMXRT_IMXRT1064_EVK_SRC_IMXRT_FLEXSPI_NOR_FLASH_H +#define __BOARDS_ARM_IMXRT_IMXRT1064_EVK_SRC_IMXRT_FLEXSPI_NOR_FLASH_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* FLEXSPI memory config block related definitions */ + +#define FLEXSPI_CFG_BLK_TAG (0x42464346ul) +#define FLEXSPI_CFG_BLK_VERSION (0x56010400ul) +#define FLEXSPI_CFG_BLK_SIZE (512) + +/* FLEXSPI Feature related definitions */ + +#define FLEXSPI_FEATURE_HAS_PARALLEL_MODE 1 + +/* Lookup table related definitions */ + +#define CMD_INDEX_READ 0 +#define CMD_INDEX_READSTATUS 1 +#define CMD_INDEX_WRITEENABLE 2 +#define CMD_INDEX_WRITE 4 + +#define CMD_LUT_SEQ_IDX_READ 0 +#define CMD_LUT_SEQ_IDX_READSTATUS 1 +#define CMD_LUT_SEQ_IDX_WRITEENABLE 3 +#define CMD_LUT_SEQ_IDX_WRITE 9 + +#define CMD_SDR 0x01 +#define CMD_DDR 0x21 +#define RADDR_SDR 0x02 +#define RADDR_DDR 0x22 +#define CADDR_SDR 0x03 +#define CADDR_DDR 0x23 +#define MODE1_SDR 0x04 +#define MODE1_DDR 0x24 +#define MODE2_SDR 0x05 +#define MODE2_DDR 0x25 +#define MODE4_SDR 0x06 +#define MODE4_DDR 0x26 +#define MODE8_SDR 0x07 +#define MODE8_DDR 0x27 +#define WRITE_SDR 0x08 +#define WRITE_DDR 0x28 +#define READ_SDR 0x09 +#define READ_DDR 0x29 +#define LEARN_SDR 0x0a +#define LEARN_DDR 0x2a +#define DATSZ_SDR 0x0b +#define DATSZ_DDR 0x2b +#define DUMMY_SDR 0x0c +#define DUMMY_DDR 0x2c +#define DUMMY_RWDS_SDR 0x0d +#define DUMMY_RWDS_DDR 0x2d +#define JMP_ON_CS 0x1f +#define STOP 0 + +#define FLEXSPI_1PAD 0 +#define FLEXSPI_2PAD 1 +#define FLEXSPI_4PAD 2 +#define FLEXSPI_8PAD 3 + +#define FLEXSPI_LUT_OPERAND0_MASK (0xffu) +#define FLEXSPI_LUT_OPERAND0_SHIFT (0U) +#define FLEXSPI_LUT_OPERAND0(x) (((uint32_t) \ + (((uint32_t)(x)) << FLEXSPI_LUT_OPERAND0_SHIFT)) & \ + FLEXSPI_LUT_OPERAND0_MASK) +#define FLEXSPI_LUT_NUM_PADS0_MASK (0x300u) +#define FLEXSPI_LUT_NUM_PADS0_SHIFT (8u) +#define FLEXSPI_LUT_NUM_PADS0(x) (((uint32_t) \ + (((uint32_t)(x)) << FLEXSPI_LUT_NUM_PADS0_SHIFT)) & \ + FLEXSPI_LUT_NUM_PADS0_MASK) +#define FLEXSPI_LUT_OPCODE0_MASK (0xfc00u) +#define FLEXSPI_LUT_OPCODE0_SHIFT (10u) +#define FLEXSPI_LUT_OPCODE0(x) (((uint32_t) \ + (((uint32_t)(x)) << FLEXSPI_LUT_OPCODE0_SHIFT)) & \ + FLEXSPI_LUT_OPCODE0_MASK) +#define FLEXSPI_LUT_OPERAND1_MASK (0xff0000u) +#define FLEXSPI_LUT_OPERAND1_SHIFT (16U) +#define FLEXSPI_LUT_OPERAND1(x) (((uint32_t) \ + (((uint32_t)(x)) << FLEXSPI_LUT_OPERAND1_SHIFT)) & \ + FLEXSPI_LUT_OPERAND1_MASK) +#define FLEXSPI_LUT_NUM_PADS1_MASK (0x3000000u) +#define FLEXSPI_LUT_NUM_PADS1_SHIFT (24u) +#define FLEXSPI_LUT_NUM_PADS1(x) (((uint32_t) \ + (((uint32_t)(x)) << FLEXSPI_LUT_NUM_PADS1_SHIFT)) & \ + FLEXSPI_LUT_NUM_PADS1_MASK) +#define FLEXSPI_LUT_OPCODE1_MASK (0xfc000000u) +#define FLEXSPI_LUT_OPCODE1_SHIFT (26u) +#define FLEXSPI_LUT_OPCODE1(x) (((uint32_t)(((uint32_t)(x)) << FLEXSPI_LUT_OPCODE1_SHIFT)) & \ + FLEXSPI_LUT_OPCODE1_MASK) + +#define FLEXSPI_LUT_SEQ(cmd0, pad0, op0, cmd1, pad1, op1) \ + (FLEXSPI_LUT_OPERAND0(op0) | FLEXSPI_LUT_NUM_PADS0(pad0) | \ + FLEXSPI_LUT_OPCODE0(cmd0) | FLEXSPI_LUT_OPERAND1(op1) | \ + FLEXSPI_LUT_NUM_PADS1(pad1) | FLEXSPI_LUT_OPCODE1(cmd1)) + +/* */ + +#define NOR_CMD_INDEX_READ CMD_INDEX_READ +#define NOR_CMD_INDEX_READSTATUS CMD_INDEX_READSTATUS +#define NOR_CMD_INDEX_WRITEENABLE CMD_INDEX_WRITEENABLE +#define NOR_CMD_INDEX_ERASESECTOR 3 +#define NOR_CMD_INDEX_PAGEPROGRAM CMD_INDEX_WRITE +#define NOR_CMD_INDEX_CHIPERASE 5 +#define NOR_CMD_INDEX_DUMMY 6 +#define NOR_CMD_INDEX_ERASEBLOCK 7 + +/* READ LUT sequence id in lookupTable stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_READ CMD_LUT_SEQ_IDX_READ + +/* Read Status LUT sequence id in lookupTable stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_READSTATUS CMD_LUT_SEQ_IDX_READSTATUS + +/* 2 Read status DPI/QPI/OPI sequence id in LUT stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_READSTATUS_XPI 2 + +/* 3 Write Enable sequence id in lookupTable stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_WRITEENABLE CMD_LUT_SEQ_IDX_WRITEENABLE + +/* 4 Write Enable DPI/QPI/OPI sequence id in LUT stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_WRITEENABLE_XPI 4 + +/* 5 Erase Sector sequence id in lookupTable stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_ERASESECTOR 5 + +/* 8 Erase Block sequence id in lookupTable stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_ERASEBLOCK 8 + +/* 9 Program sequence id in lookupTable stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_PAGEPROGRAM CMD_LUT_SEQ_IDX_WRITE + +/* 11 Chip Erase sequence in lookupTable id stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_CHIPERASE 11 + +/* 13 Read SFDP sequence in lookupTable id stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_READ_SFDP 13 + +/* 14 Restore 0-4-4/0-8-8 mode sequence id in LUT stored in config block */ + +#define NOR_CMD_LUT_SEQ_IDX_RESTORE_NOCMD 14 + +/* 15 Exit 0-4-4/0-8-8 mode sequence id in LUT stored in config blobk */ + +#define NOR_CMD_LUT_SEQ_IDX_EXIT_NOCMD 15 + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* Definitions for FlexSPI Serial Clock Frequency */ + +enum flexspi_serial_clkfreq_e { + FLEXSPI_SERIAL_CLKFREQ_30MHz = 1, + FLEXSPI_SERIAL_CLKFREQ_50MHz = 2, + FLEXSPI_SERIAL_CLKFREQ_60MHz = 3, + FLEXSPI_SERIAL_CLKFREQ_75MHz = 4, + FLEXSPI_SERIAL_CLKFREQ_80MHz = 5, + FLEXSPI_SERIAL_CLKFREQ_100MHz = 6, + FLEXSPI_SERIAL_CLKFREQ_120MHz = 7, + FLEXSPI_SERIAL_CLKFREQ_133MHz = 8, + FLEXSPI_SERIAL_CLKFREQ_166MHz = 9, +}; + +/* FlexSPI clock configuration type */ + +enum flexspi_serial_clockmode_e { + FLEXSPI_CLKMODE_SDR, + FLEXSPI_CLKMODE_DDR, +}; + +/* FlexSPI Read Sample Clock Source definition */ + +enum flash_read_sample_clk_e { + FLASH_READ_SAMPLE_CLK_LOOPBACK_INTERNELLY = 0, + FLASH_READ_SAMPLE_CLK_LOOPBACK_FROM_DQSPAD = 1, + FLASH_READ_SAMPLE_CLK_LOOPBACK_FROM_SCKPAD = 2, + FLASH_READ_SAMPLE_CLK_EXT_INPUT_FROM_DQSPAD = 3, +}; + +/* Misc feature bit definitions */ + +enum flash_misc_feature_e { + FLEXSPIMISC_OFFSET_DIFFCLKEN = 0, /* Bit for Differential clock enable */ + FLEXSPIMISC_OFFSET_CK2EN = 1, /* Bit for CK2 enable */ + FLEXSPIMISC_OFFSET_PARALLELEN = 2, /* Bit for Parallel mode enable */ + FLEXSPIMISC_OFFSET_WORD_ADDRESSABLE_EN = 3, /* Bit for Word Addressable enable */ + FLEXSPIMISC_OFFSET_SAFECONFIG_FREQ_EN = 4, /* Bit for Safe Configuration Frequency enable */ + FLEXSPIMISC_OFFSET_PAD_SETTING_OVERRIDE_EN = 5, /* Bit for Pad setting override enable */ + FLEXSPIMISC_OFFSET_DDR_MODE_EN = 6, /* Bit for DDR clock confiuration indication. */ +}; + +/* Flash Type Definition */ + +enum flash_flash_type_e { + FLEXSPI_DEVICE_TYPE_SERIAL_NOR = 1, /* Flash devices are Serial NOR */ + FLEXSPI_DEVICE_TYPE_SERIAL_NAND = 2, /* Flash devices are Serial NAND */ + FLEXSPI_DEVICE_TYPE_SERIAL_RAM = 3, /* Flash devices are Serial RAM/HyperFLASH */ + FLEXSPI_DEVICE_TYPE_MCP_NOR_NAND = 0x12, /* Flash device is MCP device, A1 is Serial NOR, A2 is Serial NAND */ + FLEXSPI_DEVICE_TYPE_MCP_NOR_RAM = 0x13, /* Flash device is MCP device, A1 is Serial NOR, A2 is Serial RAMs */ +}; + +/* Flash Pad Definitions */ + +enum flash_flash_pad_e { + SERIAL_FLASH_1PAD = 1, + SERIAL_FLASH_2PADS = 2, + SERIAL_FLASH_4PADS = 4, + SERIAL_FLASH_8PADS = 8, +}; + +/* Flash Configuration Command Type */ + +enum flash_config_cmd_e { + DEVICE_CONFIG_CMD_TYPE_GENERIC, /* Generic command, for example: configure dummy cycles, drive strength, etc */ + DEVICE_CONFIG_CMD_TYPE_QUADENABLE, /* Quad Enable command */ + DEVICE_CONFIG_CMD_TYPE_SPI2XPI, /* Switch from SPI to DPI/QPI/OPI mode */ + DEVICE_CONFIG_CMD_TYPE_XPI2SPI, /* Switch from DPI/QPI/OPI to SPI mode */ + DEVICE_CONFIG_CMD_TYPE_SPI2NO_CMD, /* Switch to 0-4-4/0-8-8 mode */ + DEVICE_CONFIG_CMD_TYPE_RESET, /* Reset device command */ +}; + +/* FlexSPI LUT Sequence structure */ + +struct flexspi_lut_seq_s { + uint8_t seq_num; /* Sequence Number, valid number: 1-16 */ + uint8_t seq_id; /* Sequence Index, valid number: 0-15 */ + uint16_t reserved; +}; + +/* FlexSPI Memory Configuration Block */ + +struct flexspi_mem_config_s { + uint32_t tag; + uint32_t version; + uint32_t reserved0; + uint8_t read_sample_clksrc; + uint8_t cs_hold_time; + uint8_t cs_setup_time; + uint8_t column_address_width; /* [0x00f-0x00f] Column Address with, for + * HyperBus protocol, it is fixed to 3, + * For Serial NAND, need to refer to + * datasheet + */ + uint8_t device_mode_cfg_enable; + uint8_t device_mode_type; + uint16_t wait_time_cfg_commands; + struct flexspi_lut_seq_s device_mode_seq; + uint32_t device_mode_arg; + uint8_t config_cmd_enable; + uint8_t config_mode_type[3]; + struct flexspi_lut_seq_s config_cmd_seqs[3]; + uint32_t reserved1; + uint32_t config_cmd_args[3]; + uint32_t reserved2; + uint32_t controller_misc_option; + uint8_t device_type; + uint8_t sflash_pad_type; + uint8_t serial_clk_freq; + uint8_t lut_custom_seq_enable; + uint32_t reserved3[2]; + uint32_t sflash_a1size; + uint32_t sflash_a2size; + uint32_t sflash_b1size; + uint32_t sflash_b2size; + uint32_t cspad_setting_override; + uint32_t sclkpad_setting_override; + uint32_t datapad_setting_override; + uint32_t dqspad_setting_override; + uint32_t timeout_in_ms; + uint32_t command_interval; + uint16_t data_valid_time[2]; + uint16_t busy_offset; + uint16_t busybit_polarity; + uint32_t lookup_table[64]; + struct flexspi_lut_seq_s lut_customseq[12]; + uint32_t reserved4[4]; +}; + +/* Serial NOR configuration block */ + +struct flexspi_nor_config_s { + struct flexspi_mem_config_s mem_config; /* Common memory configuration info + * via FlexSPI + */ + + uint32_t page_size; /* Page size of Serial NOR */ + uint32_t sector_size; /* Sector size of Serial NOR */ + uint8_t ipcmd_serial_clkfreq; /* Clock frequency for IP command */ + uint8_t is_uniform_blocksize; /* Sector/Block size is the same */ + uint8_t reserved0[2]; /* Reserved for future use */ + uint8_t serial_nor_type; /* Serial NOR Flash type: 0/1/2/3 */ + uint8_t need_exit_nocmdmode; /* Need to exit NoCmd mode before + * other IP command + */ + + uint8_t halfclk_for_nonreadcmd; /* Half the Serial Clock for non-read + * command: true/false + */ + + uint8_t need_restore_nocmdmode; /* Need to Restore NoCmd mode after IP + * command execution + */ + + uint32_t blocksize; /* Block size */ + uint32_t reserve2[11]; /* Reserved for future use */ +}; + +extern const struct flexspi_nor_config_s g_flash_config; + +#endif /* __BOARDS_ARM_IMXRT_IMXRT1064_EVK_SRC_IMXRT_FLEXSPI_NOR_FLASH_H */ diff --git a/boards/nxp/mr-tropic/src/imxrt_flexspi_storage.c b/boards/nxp/mr-tropic/src/imxrt_flexspi_storage.c new file mode 100644 index 0000000000..2b505176b4 --- /dev/null +++ b/boards/nxp/mr-tropic/src/imxrt_flexspi_storage.c @@ -0,0 +1,411 @@ +/**************************************************************************** + * boards/nxp/mr-tropic/src/imxrt_flexspi_storage.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include "px4_log.h" + +#include +#include +#include "board_config.h" +#include "hardware/imxrt_pinmux.h" +#include "barriers.h" + +/* Used sectors must be multiple of the flash block size + * i.e. W25Q32JV has a block size of 64KB +*/ + +#define NOR_USED_SECTORS (0x40U) /* 64 * 4KB = 256KB */ +#define NOR_TOTAL_SECTORS (0x0400U) +#define NOR_PAGE_SIZE (0x0100U) /* 256 bytes */ +#define NOR_SECTOR_SIZE (0x1000U) /* 4KB */ +#define NOR_START_SECTOR (NOR_TOTAL_SECTORS - NOR_USED_SECTORS) +#define NOR_START_PAGE ((NOR_START_SECTOR * NOR_SECTOR_SIZE) / NOR_PAGE_SIZE) +#define NOR_STORAGE_ADDR (IMXRT_FLEX2CIPHER_BASE + NOR_START_SECTOR * NOR_SECTOR_SIZE) +#define NOR_STORAGE_END (IMXRT_FLEX2CIPHER_BASE + (NOR_START_SECTOR + NOR_TOTAL_SECTORS) * NOR_SECTOR_SIZE) + +#define MIN(a, b) (((a) < (b)) ? (a) : (b)) + +extern struct flexspi_nor_config_s g_bootConfig; + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* FlexSPI NOR device private data */ + +struct imxrt_flexspi_storage_dev_s { + struct mtd_dev_s mtd; + uint8_t *ahb_base; +}; + +/**************************************************************************** + * Private Functions Prototypes + ****************************************************************************/ + +/* MTD driver methods */ + +static int imxrt_flexspi_storage_erase(struct mtd_dev_s *dev, + off_t startblock, + size_t nblocks); +static ssize_t imxrt_flexspi_storage_read(struct mtd_dev_s *dev, + off_t offset, + size_t nbytes, + uint8_t *buffer); +static ssize_t imxrt_flexspi_storage_bread(struct mtd_dev_s *dev, + off_t startblock, + size_t nblocks, + uint8_t *buffer); +static ssize_t imxrt_flexspi_storage_bwrite(struct mtd_dev_s *dev, + off_t startblock, + size_t nblocks, + const uint8_t *buffer); +static int imxrt_flexspi_storage_ioctl(struct mtd_dev_s *dev, + int cmd, + unsigned long arg); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static struct imxrt_flexspi_storage_dev_s g_flexspi_nor = { + .mtd = + { + .erase = imxrt_flexspi_storage_erase, + .bread = imxrt_flexspi_storage_bread, + .bwrite = imxrt_flexspi_storage_bwrite, + .read = imxrt_flexspi_storage_read, + .ioctl = imxrt_flexspi_storage_ioctl, +#ifdef CONFIG_MTD_BYTE_WRITE + .write = NULL, +#endif + .name = "imxrt_flexspi_storage" + }, + .ahb_base = (uint8_t *) NOR_STORAGE_ADDR, +}; + +/* Ensure exclusive access to the driver */ + +static sem_t g_exclsem = SEM_INITIALIZER(1); + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static int imxrt_flexspi_storage_erase_chip( + const struct imxrt_flexspi_storage_dev_s *dev) +{ + /* We can't erase the chip we're executing from */ + return -EINVAL; +} + +static ssize_t imxrt_flexspi_storage_read(struct mtd_dev_s *dev, + off_t offset, + size_t nbytes, + uint8_t *buffer) +{ + ssize_t ret; + struct imxrt_flexspi_storage_dev_s *priv = + (struct imxrt_flexspi_storage_dev_s *)dev; + uint8_t *src; + + finfo("offset: %08lx nbytes: %d\n", (long)offset, (int)nbytes); + + if (offset < 0) { + return -EIO; + } + + src = priv->ahb_base + offset; + + if (src + nbytes > (uint8_t *)NOR_STORAGE_END) { + return -EIO; + } + + ret = nxsem_wait(&g_exclsem); + + if (ret < 0) { + return ret; + } + + memcpy(buffer, src, nbytes); + + nxsem_post(&g_exclsem); + + finfo("return nbytes: %d\n", (int)nbytes); + return (ssize_t)nbytes; +} + +static ssize_t imxrt_flexspi_storage_bread(struct mtd_dev_s *dev, + off_t startblock, + size_t nblocks, + uint8_t *buffer) +{ + ssize_t nbytes; + + finfo("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks); + + /* On this device, we can handle the block read just like the byte-oriented + * read + */ + + nbytes = imxrt_flexspi_storage_read(dev, startblock * NOR_PAGE_SIZE, + nblocks * NOR_PAGE_SIZE, buffer); + + if (nbytes > 0) { + nbytes /= NOR_PAGE_SIZE; + } + + return nbytes; +} + +locate_code(".ramfunc") +static ssize_t imxrt_flexspi_storage_bwrite(struct mtd_dev_s *dev, + off_t startblock, + size_t nblocks, + const uint8_t *buffer) +{ + ssize_t ret; + struct flexspi_nor_config_s *pConfig = &g_bootConfig; + size_t len = nblocks * NOR_PAGE_SIZE; + off_t offset = (startblock + NOR_START_PAGE) * NOR_PAGE_SIZE; + uint8_t *src = (uint8_t *) buffer; +#ifdef CONFIG_ARMV7M_DCACHE + struct imxrt_flexspi_storage_dev_s *priv = + (struct imxrt_flexspi_storage_dev_s *)dev; + uint8_t *dst = priv->ahb_base + startblock * NOR_PAGE_SIZE; +#endif + int i; + + if (((uintptr_t)buffer % 4) != 0) { + return -EINVAL; // Byte aligned write not supported + } + + finfo("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks); + + ret = nxsem_wait(&g_exclsem); + + if (ret < 0) { + return ret; + } + + while (len) { + i = MIN(NOR_PAGE_SIZE, len); + cpsid(); // Disable interrupts +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wcast-align" + volatile uint32_t status = ROM_FLEXSPI_NorFlash_ProgramPage(NOR_INSTANCE, pConfig, offset, (const uint32_t *)src); +#pragma GCC diagnostic pop + cpsie(); // Enable interrupts + usleep(0); // Yield to scheduler + UNUSED(status); + + offset += i; + src += i; + len -= i; + } + +#ifdef CONFIG_ARMV7M_DCACHE + up_invalidate_dcache((uintptr_t)dst, + (uintptr_t)dst + nblocks * NOR_PAGE_SIZE); +#endif + + nxsem_post(&g_exclsem); + + return nblocks; +} + +locate_code(".ramfunc") +static int imxrt_flexspi_storage_erase(struct mtd_dev_s *dev, + off_t startblock, + size_t nblocks) +{ + struct flexspi_nor_config_s *pConfig = &g_bootConfig; + size_t blocksleft = nblocks; +#ifdef CONFIG_ARMV7M_DCACHE + struct imxrt_flexspi_storage_dev_s *priv = + (struct imxrt_flexspi_storage_dev_s *)dev; + uint8_t *dst = priv->ahb_base + startblock * NOR_SECTOR_SIZE; +#endif + ssize_t ret; + + startblock += NOR_START_SECTOR; + + finfo("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks); + + ret = nxsem_wait(&g_exclsem); + + if (ret < 0) { + return ret; + } + + while (blocksleft-- > 0) { + /* Erase each sector */ + cpsid(); // Disable interrupts + volatile uint32_t status = ROM_FLEXSPI_NorFlash_Erase(NOR_INSTANCE, pConfig, + (startblock * NOR_SECTOR_SIZE), NOR_SECTOR_SIZE); + cpsie(); // Enable interrupts + usleep(0); // Yield to scheduler + UNUSED(status); + startblock++; + } + +#ifdef CONFIG_ARMV7M_DCACHE + up_invalidate_dcache((uintptr_t)dst, + (uintptr_t)dst + nblocks * NOR_SECTOR_SIZE); +#endif + nxsem_post(&g_exclsem); + + return (int)nblocks; +} + +static int imxrt_flexspi_storage_ioctl(struct mtd_dev_s *dev, + int cmd, + unsigned long arg) +{ + struct imxrt_flexspi_storage_dev_s *priv = + (struct imxrt_flexspi_storage_dev_s *)dev; + int ret = -EINVAL; /* Assume good command with bad parameters */ + + finfo("cmd: %d\n", cmd); + + switch (cmd) { + case MTDIOC_GEOMETRY: { + struct mtd_geometry_s *geo = + (struct mtd_geometry_s *)((uintptr_t)arg); + + if (geo) { + /* Populate the geometry structure with information need to + * know the capacity and how to access the device. + * + * NOTE: + * that the device is treated as though it where just an array + * of fixed size blocks. That is most likely not true, but the + * client will expect the device logic to do whatever is + * necessary to make it appear so. + */ + + geo->blocksize = (NOR_PAGE_SIZE); + geo->erasesize = (NOR_SECTOR_SIZE); + geo->neraseblocks = (NOR_USED_SECTORS); + + ret = OK; + + finfo("blocksize: %lu erasesize: %lu neraseblocks: %lu\n", + geo->blocksize, geo->erasesize, geo->neraseblocks); + } + } + break; + + case BIOC_PARTINFO: { + struct partition_info_s *info = + (struct partition_info_s *)arg; + + if (info != NULL) { + info->numsectors = (NOR_USED_SECTORS * NOR_SECTOR_SIZE) / NOR_PAGE_SIZE; + info->sectorsize = NOR_PAGE_SIZE; + info->startsector = 0; + info->parent[0] = '\0'; + ret = OK; + } + } + break; + + case MTDIOC_BULKERASE: { + /* Erase the entire device */ + + imxrt_flexspi_storage_erase_chip(priv); + ret = OK; + } + break; + + default: + ret = -ENOTTY; /* Bad/unsupported command */ + break; + } + + finfo("return %d\n", ret); + return ret; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + + +/**************************************************************************** + * Name: imxrt_flexspi_storage_initialize + * + * Description: + * This function is called by board-bringup logic to configure the + * flash device. + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int imxrt_flexspi_storage_initialize(void) +{ + struct mtd_dev_s *mtd_dev = &g_flexspi_nor.mtd; + int ret = -ENODEV; + + /* Register the MTD driver so that it can be accessed from the + * VFS. + */ + + ret = register_mtddriver("/dev/nor", mtd_dev, 0755, NULL); + + if (ret < 0) { + syslog(LOG_ERR, "ERROR: Failed to register MTD driver: %d\n", + ret); + } + +#ifdef CONFIG_FS_LITTLEFS + + /* Mount the LittleFS file system */ + + ret = nx_mount("/dev/nor", "/fs/nor", "littlefs", 0, + "autoformat"); + + if (ret < 0) { + syslog(LOG_ERR, + "ERROR: Failed to mount LittleFS at /mnt/lfs: %d\n", + ret); + } + +#endif + + return ret; +} diff --git a/boards/nxp/mr-tropic/src/imxrt_ocram_initialize.c b/boards/nxp/mr-tropic/src/imxrt_ocram_initialize.c new file mode 100644 index 0000000000..67c1a4ca36 --- /dev/null +++ b/boards/nxp/mr-tropic/src/imxrt_ocram_initialize.c @@ -0,0 +1,102 @@ +/**************************************************************************** + * + * Copyright (c) 2018-2019, 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file imxrt_ocram_initialize.c + * + * PX4 fmu-v6xrt RAM startup early startup code. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "arm_internal.h" +#include "imxrt_iomuxc.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +__BEGIN_DECLS +extern const uint64_t _fitcmfuncs; /* Copy source address in FLASH */ +extern uint64_t _sitcmfuncs; /* Copy destination start address in ITCM */ +extern uint64_t _eitcmfuncs; /* Copy destination end address in ITCM */ +extern uint64_t _sdtcm; /* Copy destination start address in DTCM */ +extern uint64_t _edtcm; /* Copy destination end address in DTCM */ +__END_DECLS + +/**************************************************************************** + * Name: imxrt_ocram_initialize + * + * Description: + * Called off reset vector to reconfigure the flexRAM + * and finish the FLASH to RAM Copy. + * CMakeLists.txt Forces compiler not to use builtin functions using -fno-builtin + * + ****************************************************************************/ + +__EXPORT void imxrt_ocram_initialize(void) +{ + uint32_t regval; + register uint64_t *src; + register uint64_t *dest; + + /* FlexRAM Configuration + * F = 64K ITCM + * A = 64K DTCM + * 5 = 64K OCRAM + * So 0xFFFFFFAA is + * 384K FlexRAM ITCM + * 128K FlexRAM DTCM + * */ + + putreg32(0xFFFFFFAA, IMXRT_IOMUXC_GPR_GPR17); + regval = getreg32(IMXRT_IOMUXC_GPR_GPR16); + putreg32(regval | GPR_GPR16_FLEXRAM_BANK_CFG_SEL, IMXRT_IOMUXC_GPR_GPR16); + + /* Copy any necessary code sections from FLASH to ITCM. The process is the + * same as the code copying from FLASH to RAM above. */ + for (src = (uint64_t *)&_fitcmfuncs, dest = (uint64_t *)&_sitcmfuncs; + dest < (uint64_t *)&_eitcmfuncs;) { + *dest++ = *src++; + } + + /* Clear .dtcm. We'll do this inline (vs. calling memset) just to be + * certain that there are no issues with the state of global variables. + */ + + for (dest = &_sdtcm; dest < &_edtcm;) { + *dest++ = 0; + } +} diff --git a/boards/nxp/mr-tropic/src/init.c b/boards/nxp/mr-tropic/src/init.c new file mode 100644 index 0000000000..7c71fbbef0 --- /dev/null +++ b/boards/nxp/mr-tropic/src/init.c @@ -0,0 +1,400 @@ +/**************************************************************************** + * + * Copyright (c) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file init.c + * + * NXP imxrt1062-v1 specific early startup code. This file implements the + * board_app_initialize() function that is called early by nsh during startup. + * + * Code here is run before the rcS script is invoked; it should start required + * subsystems and perform board-specific initialization. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "board_config.h" + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "arm_internal.h" +#include "imxrt_flexspi_nor_boot.h" +#include +#include "imxrt_iomuxc.h" +#include "imxrt_flexcan.h" +#include "imxrt_enet.h" +#include +#include "board_config.h" + +#include +#undef FLEXSPI_LUT_COUNT +#include +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/* Configuration ************************************************************/ + +/* + * Ideally we'd be able to get these from arm_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(void); +extern void led_on(int led); +extern void led_off(int led); + +extern uint32_t _srodata; /* Start of .rodata */ +extern uint32_t _erodata; /* End of .rodata */ +__END_DECLS + +/************************************************************************************ + * Name: board_peripheral_reset + * + * Description: + * + ************************************************************************************/ +__EXPORT void board_peripheral_reset(int ms) +{ + +} +/************************************************************************************ + * Name: board_on_reset + * + * Description: + * Optionally provided function called on entry to board_system_reset + * It should perform any house keeping prior to the rest. + * + * status - 1 if resetting to boot loader + * 0 if just resetting + * + ************************************************************************************/ + +__EXPORT void board_on_reset(int status) +{ + for (int i = 0; i < DIRECT_PWM_OUTPUT_CHANNELS; ++i) { + px4_arch_configgpio(PX4_MAKE_GPIO_INPUT(io_timer_channel_get_gpio_output(i))); + } + + /* + * On resets invoked from system (not boot) ensure we establish a low + * output state on PWM pins to disarm the ESC and prevent the reset from potentially + * spinning up the motors. + */ + if (status >= 0) { + up_mdelay(100); + } +} + +/**************************************************************************** + * Name: imxrt_flash_romapi_initialize + * + * Description: + * + ****************************************************************************/ +struct flexspi_nor_config_s g_bootConfig; + +locate_code(".ramfunc") +void imxrt_flash_romapi_initialize(void) +{ + memcpy((struct flexspi_nor_config_s *)&g_bootConfig, &g_flash_config, + sizeof(struct flexspi_nor_config_s)); + g_bootConfig.memConfig.tag = FLEXSPI_CFG_BLK_TAG; + + ROM_API_Init(); + + ROM_FLEXSPI_NorFlash_Init(NOR_INSTANCE, (struct flexspi_nor_config_s *)&g_bootConfig); + ROM_FLEXSPI_NorFlash_ClearCache(NOR_INSTANCE); + + ARM_DSB(); + ARM_ISB(); + ARM_DMB(); +} + +locate_code(".ramfunc") +void imxrt_flash_setup_prefetch_partition(void) +{ +//Prefetch tuning to be determined +#if 0 + putreg32((uint32_t)&_srodata, IMXRT_FLEXSPI1_AHBBUFREGIONSTART0); + putreg32((uint32_t)&_erodata, IMXRT_FLEXSPI1_AHBBUFREGIONEND0); + /*putreg32((uint32_t)&_stext, IMXRT_FLEXSPI1_AHBBUFREGIONSTART1); + putreg32((uint32_t)&_etext, IMXRT_FLEXSPI1_AHBBUFREGIONEND1); + putreg32((uint32_t)&_stext, IMXRT_FLEXSPI1_AHBBUFREGIONSTART2); + putreg32((uint32_t)&_etext, IMXRT_FLEXSPI1_AHBBUFREGIONEND2); + putreg32((uint32_t)&_stext, IMXRT_FLEXSPI1_AHBBUFREGIONSTART3); + putreg32((uint32_t)&_etext, IMXRT_FLEXSPI1_AHBBUFREGIONEND3);*/ +#endif +#if 0 + struct flexspi_type_s *g_flexspi = (struct flexspi_type_s *)IMXRT_FLEXSPIC_BASE; + /* RODATA */ + g_flexspi->AHBRXBUFCR0[0] = FLEXSPI_AHBRXBUFCR0_BUFSZ(48) | + FLEXSPI_AHBRXBUFCR0_MSTRID(0) | + FLEXSPI_AHBRXBUFCR0_PREFETCHEN(1) | + FLEXSPI_AHBRXBUFCR0_REGIONEN(1); + + + /* All Text */ + g_flexspi->AHBRXBUFCR0[1] = FLEXSPI_AHBRXBUFCR0_BUFSZ(80) | + FLEXSPI_AHBRXBUFCR0_MSTRID(0) | + FLEXSPI_AHBRXBUFCR0_PREFETCHEN(1) | + FLEXSPI_AHBRXBUFCR0_REGIONEN(1); + + /* Disable 2 */ + g_flexspi->AHBRXBUFCR0[2] = FLEXSPI_AHBRXBUFCR0_BUFSZ(0) | + FLEXSPI_AHBRXBUFCR0_MSTRID(0) | + FLEXSPI_AHBRXBUFCR0_PREFETCHEN(1) | + FLEXSPI_AHBRXBUFCR0_REGIONEN(0); + + /* Disable 3 */ + g_flexspi->AHBRXBUFCR0[3] = FLEXSPI_AHBRXBUFCR0_BUFSZ(0) | + FLEXSPI_AHBRXBUFCR0_MSTRID(0) | + FLEXSPI_AHBRXBUFCR0_PREFETCHEN(1) | + FLEXSPI_AHBRXBUFCR0_REGIONEN(0); +#endif + + ARM_DSB(); + ARM_ISB(); + ARM_DMB(); +} + +/**************************************************************************** + * Name: imxrt_boardinitialize + * + * Description: + * All i.MX RT architectures must provide the following entry point. This + * entry point is called early in the initialization -- after clocking and + * memory have been configured but before caches have been enabled and + * before any devices have been initialized. + * + ****************************************************************************/ + +__EXPORT void imxrt_boardinitialize(void) +{ + imxrt_flash_setup_prefetch_partition(); + + imxrt_flash_romapi_initialize(); + + board_on_reset(-1); /* Reset PWM first thing */ + + /* configure LEDs */ + + board_autoled_initialize(); + + /* configure pins */ + + const uint32_t gpio[] = PX4_GPIO_INIT_LIST; + px4_gpio_init(gpio, arraySize(gpio)); + + imxrt_usb_initialize(); + + fmurt1062_timer_initialize(); +} + +/**************************************************************************** + * Function: imxrt_phy_boardinitialize + * + * Description: + * Some boards require specialized initialization of the PHY before it can + * be used. This may include such things as configuring GPIOs, resetting + * the PHY, etc. + * If CONFIG_IMXRT_ENET_PHYINIT is defined in the configuration then the + * board specific logic must provide imxrt_phyinitialize(); + * The i.MX RT Ethernet driver will call this function one time before it + * first uses the PHY. + * + * Input Parameters: + * intf - Always zero for now. + * + * Returned Value: + * OK on success; Negated errno on failure. + * + ****************************************************************************/ + +int imxrt_phy_boardinitialize(int intf) +{ +#ifdef CONFIG_IMXRT_GPIO1_0_15_IRQ + /* Configure the PHY interrupt pin */ + + printf("Configuring interrupt: %08x\n", GPIO_ENET_INT); + imxrt_config_gpio(GPIO_ENET_INT); +#endif + return OK; +} + +void imxrt_flexio_clocking(void) +{ + uint32_t reg; + + /* Init USB PLL3 PFD2 */ + + reg = getreg32(IMXRT_CCM_ANALOG_PFD_480); + + while ((getreg32(IMXRT_CCM_ANALOG_PLL_USB1) & + CCM_ANALOG_PLL_USB1_LOCK) == 0) { + } + + reg &= ~CCM_ANALOG_PFD_480_PFD2_FRAC_MASK; + + /* Set PLL3 PFD2 to 480 * 18 / CONFIG_PLL3_PFD2_FRAC */ + + reg |= ((uint32_t)(CONFIG_PLL3_PFD2_FRAC) << CCM_ANALOG_PFD_480_PFD3_FRAC_SHIFT); + + putreg32(reg, IMXRT_CCM_ANALOG_PFD_480); + + reg = getreg32(IMXRT_CCM_CDCDR); + reg &= ~(CCM_CDCDR_FLEXIO1_CLK_SEL_MASK | + CCM_CDCDR_FLEXIO1_CLK_PODF_MASK | + CCM_CDCDR_FLEXIO1_CLK_PRED_MASK); + reg |= CCM_CDCDR_FLEXIO1_CLK_SEL(CONFIG_FLEXIO1_CLK); + reg |= CCM_CDCDR_FLEXIO1_CLK_PODF + (CCM_PODF_FROM_DIVISOR(CONFIG_FLEXIO1_PODF_DIVIDER)); + reg |= CCM_CDCDR_FLEXIO1_CLK_PRED + (CCM_PRED_FROM_DIVISOR(CONFIG_FLEXIO1_PRED_DIVIDER)); + putreg32(reg, IMXRT_CCM_CDCDR); +} + + +/**************************************************************************** + * Name: board_app_initialize + * + * Description: + * Perform application specific initialization. This function is never + * called directly from application code, but only indirectly via the + * (non-standard) boardctl() interface using the command BOARDIOC_INIT. + * + * Input Parameters: + * arg - The boardctl() argument is passed to the board_app_initialize() + * implementation without modification. The argument has no + * meaning to NuttX; the meaning of the argument is a contract + * between the board-specific initalization logic and the the + * matching application logic. The value cold be such things as a + * mode enumeration value, a set of DIP switch switch settings, a + * pointer to configuration data read from a file or serial FLASH, + * or whatever you would like to do with it. Every implementation + * should accept zero/NULL as a default configuration. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure to indicate the nature of the failure. + * + ****************************************************************************/ +__EXPORT int board_app_initialize(uintptr_t arg) +{ + int ret = OK; + +#if !defined(BOOTLOADER) + + imxrt_flexio_clocking(); + + /* Power on Interfaces */ + + px4_platform_init(); + + imxrt_spiinitialize(); + + board_determine_hw_info(); + + /* configure the DMA allocator */ + + if (board_dma_alloc_init() < 0) { + syslog(LOG_ERR, "[boot] DMA alloc FAILED\n"); + } + +#if defined(SERIAL_HAVE_RXDMA) + // set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event. + static struct hrt_call serial_dma_call; + hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)imxrt_serial_dma_poll, NULL); +#endif + +#if defined(CONFIG_IMXRT_USDHC) + ret = fmurt1062_usdhc_initialize(); +#endif + + imxrt_spiinitialize(); + + board_spi_reset(10, 0xffff); + +#ifdef CONFIG_IMXRT_ENET + imxrt_gpio_write(GPIO_ENET_RST, true); + + usleep(2000); + + imxrt_netinitialize(0); +#endif + +#ifdef CONFIG_IMXRT_FLEXCAN3 + imxrt_caninitialize(3); +#endif + + ret = imxrt_flexspi_storage_initialize(); + + if (ret < 0) { + syslog(LOG_ERR, + "ERROR: imxrt_flexspi_nor_initialize failed: %d\n", ret); + } + +#endif /* !defined(BOOTLOADER) */ + + return ret; +} diff --git a/boards/nxp/mr-tropic/src/manifest.c b/boards/nxp/mr-tropic/src/manifest.c new file mode 100644 index 0000000000..afd3de58e5 --- /dev/null +++ b/boards/nxp/mr-tropic/src/manifest.c @@ -0,0 +1,79 @@ +/**************************************************************************** + * + * Copyright (c) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file manifest.c + * + * This module supplies the interface to the manifest of hardware that is + * optional and dependent on the HW REV and HW VER IDs + * + * The manifest allows the system to know whether a hardware option + * say for example the PX4IO is an no-pop option vs it is broken. + * + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#include "systemlib/px4_macros.h" +#include "px4_log.h" + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + + +/************************************************************************************ + * Name: board_query_manifest + * + * Description: + * Optional returns manifest item. + * + * Input Parameters: + * manifest_id - the ID for the manifest item to retrieve + * + * Returned Value: + * 0 - item is not in manifest => assume legacy operations + * pointer to a manifest item + * + ************************************************************************************/ + +__EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id) +{ + return px4_hw_mft_unsupported; +} diff --git a/boards/nxp/mr-tropic/src/sdhc.c b/boards/nxp/mr-tropic/src/sdhc.c new file mode 100644 index 0000000000..df2f92cc1c --- /dev/null +++ b/boards/nxp/mr-tropic/src/sdhc.c @@ -0,0 +1,128 @@ +/**************************************************************************** + * + * Copyright (C) 2016-2018 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +/* A micro Secure Digital (SD) card slot is available on the board connected to + * the SD Host Controller (USDHC1) signals of the MCU. This slot will accept + * micro format SD memory cards. + * + * ------------ ------------- -------- + * SD Card Slot Board Signal IMXRT Pin + * ------------ ------------- -------- + * DAT0 USDHC1_DATA0 GPIO_SD_B0_02 + * DAT1 USDHC1_DATA1 GPIO_SD_B0_03 + * DAT2 USDHC1_DATA2 GPIO_SD_B0_04 + * CD/DAT3 USDHC1_DATA3 GPIO_SD_B0_05 + * CMD USDHC1_CMD GPIO_SD_B0_00 + * CLK USDHC1_CLK GPIO_SD_B0_01 + * CD USDHC1_CD GPIO_B1_12 + * ------------ ------------- -------- + * + * There are no Write Protect available to the IMXRT. + */ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "imxrt_usdhc.h" + +#include "board_config.h" + +#ifdef CONFIG_IMXRT_USDHC +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ +/**************************************************************************** + * Private Data + ****************************************************************************/ +/**************************************************************************** + * Private Functions + ****************************************************************************/ +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fmurt1062_usdhc_initialize + * + * Description: + * Inititialize the SDHC SD card slot + * + ****************************************************************************/ + +int fmurt1062_usdhc_initialize(void) +{ + int ret; + + /* Mount the SDHC-based MMC/SD block driver */ + /* First, get an instance of the SDHC interface */ + + struct sdio_dev_s *sdhc = imxrt_usdhc_initialize(CONFIG_NSH_MMCSDSLOTNO); + + if (!sdhc) { + PX4_ERR("ERROR: Failed to initialize SDHC slot %d\n", CONFIG_NSH_MMCSDSLOTNO); + return -ENODEV; + } + + /* Now bind the SDHC interface to the MMC/SD driver */ + + ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdhc); + + if (ret != OK) { + PX4_ERR("ERROR: Failed to bind SDHC to the MMC/SD driver: %d\n", ret); + return ret; + } + + syslog(LOG_INFO, "Successfully bound SDHC to the MMC/SD driver\n"); + + return OK; +} +#endif /* CONFIG_IMXRT_USDHC */ diff --git a/boards/nxp/mr-tropic/src/spi.cpp b/boards/nxp/mr-tropic/src/spi.cpp new file mode 100644 index 0000000000..afea0032a5 --- /dev/null +++ b/boards/nxp/mr-tropic/src/spi.cpp @@ -0,0 +1,95 @@ +/************************************************************************************ + * + * Copyright (C) 2016, 2018 Gregory Nutt. All rights reserved. + * Authors: Gregory Nutt + * David Sidrane + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include +#include + +#include +#include + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include +#include "imxrt_lpspi.h" +#include "imxrt_gpio.h" +#include "board_config.h" +#include + +constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSIONS] = { + initSPIFmumID(TROPIC_0, { + initSPIBus(SPI::Bus::LPSPI3, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::Port1, GPIO::Pin28}, SPI::DRDY{GPIO::Port3, GPIO::Pin18}), /* GPIO_AD_B1_12 GPIO1_IO28 */ + }), + initSPIBus(SPI::Bus::LPSPI4, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin18}, SPI::DRDY{GPIO::Port2, GPIO::Pin10}), /* GPIO_B1_02 GPIO2_IO18 */ + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin0}, SPI::DRDY{GPIO::Port1, GPIO::Pin25}), /* GPIO_B0_00 GPIO2_IO00 */ + }), + }), + + initSPIFmumID(TROPIC_1, { + initSPIBus(SPI::Bus::LPSPI3, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::Port1, GPIO::Pin28}), /* GPIO_AD_B1_12 GPIO1_IO28 */ + }), + initSPIBus(SPI::Bus::LPSPI4, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin18}), /* GPIO_B1_02 GPIO2_IO18 */ + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin0}), /* GPIO_B0_00 GPIO2_IO00 */ + }), + }), + + initSPIFmumID(TROPIC_2, { + initSPIBus(SPI::Bus::LPSPI3, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42686P, SPI::CS{GPIO::Port1, GPIO::Pin28}), /* GPIO_AD_B1_12 GPIO1_IO28 */ + }), + initSPIBus(SPI::Bus::LPSPI4, { + initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin18}), /* GPIO_B1_02 GPIO2_IO18 */ + initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin0}), /* GPIO_B0_00 GPIO2_IO00 */ + }), + }), +}; + +static constexpr bool unused = validateSPIConfig(px4_spi_buses_all_hw); diff --git a/boards/nxp/mr-tropic/src/timer_config.cpp b/boards/nxp/mr-tropic/src/timer_config.cpp new file mode 100644 index 0000000000..a15a7e83fb --- /dev/null +++ b/boards/nxp/mr-tropic/src/timer_config.cpp @@ -0,0 +1,152 @@ +/**************************************************************************** + * + * Copyright (C) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#include + +#include +#include "hardware/imxrt_tmr.h" +#include "hardware/imxrt_flexpwm.h" +#include "imxrt_gpio.h" +#include "imxrt_iomuxc.h" +#include "hardware/imxrt_pinmux.h" +#include "imxrt_xbar.h" +#include "imxrt_periphclks.h" + +#include +#include + +#include "board_config.h" + +/**************************************************************************************************** + * Definitions + ****************************************************************************************************/ + +/* Register accessors */ + +#define _REG(_addr) (*(volatile uint16_t *)(_addr)) + +/* QTimer3 register accessors */ + +#define REG(_reg) _REG(IMXRT_QTIMER3_BASE + IMXRT_TMR_OFFSET(IMXRT_TMR_CH0,(_reg))) + +#define rCOMP1 REG(IMXRT_TMR_COMP1_OFFSET) +#define rCOMP2 REG(IMXRT_TMR_COMP2_OFFSET) +#define rCAPT REG(IMXRT_TMR_CAPT_OFFSET) +#define rLOAD REG(IMXRT_TMR_LOAD_OFFSET) +#define rHOLD REG(IMXRT_TMR_HOLD_OFFSET) +#define rCNTR REG(IMXRT_TMR_CNTR_OFFSET) +#define rCTRL REG(IMXRT_TMR_CTRL_OFFSET) +#define rSCTRL REG(IMXRT_TMR_SCTRL_OFFSET) +#define rCMPLD1 REG(IMXRT_TMR_CMPLD1_OFFSET) +#define rCMPLD2 REG(IMXRT_TMR_CMPLD2_OFFSET) +#define rCSCTRL REG(IMXRT_TMR_CSCTRL_OFFSET) +#define rFILT REG(IMXRT_TMR_FILT_OFFSET) +#define rDMA REG(IMXRT_TMR_DMA_OFFSET) +#define rENBL REG(IMXRT_TMR_ENBL_OFFSET) + + +constexpr io_timers_t io_timers[MAX_IO_TIMERS] = { + initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule0), // PWM_1, PMW_2 + initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule1), // PWM_3, PWM_4 + initIOPWMDshot(PWM::FlexPWM4, PWM::Submodule1), // PWM_5, PWM_6 + initIOPWMDshot(PWM::FlexPWM4, PWM::Submodule2), // PWM_7, PWM_8 +}; + +#define FXIO_IOMUX (IOMUX_SLEW_FAST | IOMUX_DRIVE_130OHM | IOMUX_PULL_UP_47K | IOMUX_SCHMITT_TRIGGER) + +constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = { + initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_06, GPIO_FLEXIO1_FLEXIO06_1 | FXIO_IOMUX, 6), + initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_B, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_07, GPIO_FLEXIO1_FLEXIO07_1 | FXIO_IOMUX, 7), + initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_08, GPIO_FLEXIO1_FLEXIO08_1 | FXIO_IOMUX, 8), + initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_B, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_09, GPIO_FLEXIO1_FLEXIO09_1 | FXIO_IOMUX, 9), + initIOTimerChannelDshot(io_timers, {PWM::PWM4_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_02, GPIO_FLEXIO1_FLEXIO02_1 | FXIO_IOMUX, 2), + initIOTimerChannelDshot(io_timers, {PWM::PWM4_PWM_B, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_03, GPIO_FLEXIO1_FLEXIO03_1 | FXIO_IOMUX, 3), + initIOTimerChannelDshot(io_timers, {PWM::PWM4_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_04, GPIO_FLEXIO1_FLEXIO04_1 | FXIO_IOMUX, 4), + initIOTimerChannelDshot(io_timers, {PWM::PWM4_PWM_B, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_05, GPIO_FLEXIO1_FLEXIO05_1 | FXIO_IOMUX, 5), +}; + +constexpr io_timers_channel_mapping_t io_timers_channel_mapping = + initIOTimerChannelMapping(io_timers, timer_io_channels); + +constexpr io_timers_t led_pwm_timers[MAX_LED_TIMERS] = { +}; + +constexpr timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS] = { +}; + +#include +void fmurt1062_timer_initialize(void) +{ + /* We must configure Qtimer 3 as the IPG divide by to yield 16 Mhz + * and deliver that clock to the eFlexPWM234 via XBAR + * + * IPG = 144 Mhz + * 16Mhz = 144 / 9 + * COMP 1 = 5, COMP2 = 4 + * + * */ + + /* Enable Block Clocks for Qtimer and XBAR1 */ + + imxrt_clockall_timer3(); + imxrt_clockall_xbar1(); + + /* Disable Timer */ + + rCTRL = 0; + rCOMP1 = 5 - 1; // N - 1 + rCOMP2 = 4 - 1; + + rCAPT = 0; + rLOAD = 0; + rCNTR = 0; + + rSCTRL = TMR_SCTRL_OEN; + + rCMPLD1 = 0; + rCMPLD2 = 0; + rCSCTRL = 0; + rFILT = 0; + rDMA = 0; + + /* Count rising edges of primary source, + * Prescaler is /1 + * Count UP until compare, then re-initialize. a successful compare occurs when the counter reaches a COMP1 value. + * Toggle OFLAG output using alternating compare registers + */ + rCTRL = (TMR_CTRL_CM_MODE1 | TMR_CTRL_PCS_DIV1 | TMR_CTRL_LENGTH | TMR_CTRL_OUTMODE_TOG_ALT); + + /* QTIMER3_TIMER0 -> Flexpwm234ExtClk */ + + imxrt_xbar_connect(IMXRT_XBARA1_OUT_FLEXPWM234_EXT_CLK_SEL_OFFSET, IMXRT_XBARA1_IN_QTIMER3_TMR0_OUT); + imxrt_xbar_connect(IMXRT_XBARA1_OUT_FLEXPWM1_EXT_CLK_SEL_OFFSET, IMXRT_XBARA1_IN_QTIMER3_TMR0_OUT); +} diff --git a/boards/nxp/mr-tropic/src/tropic_led_pwm.cpp b/boards/nxp/mr-tropic/src/tropic_led_pwm.cpp new file mode 100644 index 0000000000..45598fc787 --- /dev/null +++ b/boards/nxp/mr-tropic/src/tropic_led_pwm.cpp @@ -0,0 +1,182 @@ +/**************************************************************************** + * + * Copyright (c) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name Airmind nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** +* @file tropic_led_pwm.cpp +*/ + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include + +#include +#include "imxrt_xbar.h" +#include "imxrt_periphclks.h" +#include "hardware/imxrt_tmr.h" +#include "hardware/imxrt_flexpwm.h" + +#define LED_PWM_FREQ 1000 +#define FLEXPWM_FREQ 1000000 +#define QTMR_FREQ (144000000/128) + +#define SM_SPACING (IMXRT_FLEXPWM_SM1CNT_OFFSET-IMXRT_FLEXPWM_SM0CNT_OFFSET) + +#define FLEXPWM_TIMER_BASE IMXRT_FLEXPWM2_BASE + +/* Register accessors */ +#define _REG(_addr) (*(volatile uint16_t *)(_addr)) +#define _REG16(_base, _reg) (*(volatile uint16_t *)(_base + _reg)) +#define FLEXPWMREG(_tmr, _sm, _reg) _REG16(_tmr + ((_sm) * SM_SPACING), (_reg)) + +/* FlexPWM Registers for LED_G */ +#define rINIT(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0INIT_OFFSET) /* Initial Count Register */ +#define rCTRL(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0CTRL_OFFSET) /* Control Register */ +#define rCTRL2(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0CTRL2_OFFSET) /* Control 2 Register */ +#define rFSTS0(_tim) FLEXPWMREG(_tim, 0, IMXRT_FLEXPWM_FSTS0_OFFSET) /* Fault Status Register */ +#define rVAL0(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0VAL0_OFFSET) /* Value Register 0 */ +#define rVAL1(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0VAL1_OFFSET) /* Value Register 1 */ +#define rVAL2(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0VAL2_OFFSET) /* Value Register 2 */ +#define rVAL3(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0VAL3_OFFSET) /* Value Register 3 */ +#define rVAL4(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0VAL4_OFFSET) /* Value Register 4 */ +#define rVAL5(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0VAL5_OFFSET) /* Value Register 5 */ +#define rFFILT0(_tim) FLEXPWMREG(_tim, 0, IMXRT_FLEXPWM_FFILT0_OFFSET) /* Fault Filter Register */ +#define rDISMAP0(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0DISMAP0_OFFSET) /* Fault Disable Mapping Register 0 */ +#define rDISMAP1(_tim, _sm) FLEXPWMREG(_tim, _sm,IMXRT_FLEXPWM_SM0DISMAP1_OFFSET) /* Fault Disable Mapping Register 1 */ +#define rOUTEN(_tim) FLEXPWMREG(_tim, 0, IMXRT_FLEXPWM_OUTEN_OFFSET) /* Output Enable Register */ +#define rDTSRCSEL(_tim) FLEXPWMREG(_tim, 0, IMXRT_FLEXPWM_DTSRCSEL_OFFSET) /* PWM Source Select Register */ +#define rMCTRL(_tim) FLEXPWMREG(_tim, 0, IMXRT_FLEXPWM_MCTRL_OFFSET) /* Master Control Register */ + +#define OUTEN_A_MASK 0x1 +#define OUTEN_B_MASK 0x2 + +#define FREQ + +static void flexpwm_led(uint32_t timer, uint32_t sm, uint16_t cvalue, uint32_t gpio_mux, uint32_t pwm_mux, + uint32_t out_mask) +{ + if (cvalue == 0) { + //rMCTRL(timer) &= ~MCTRL_RUN(1 << sm); + px4_arch_configgpio(gpio_mux); + + } else { + rMCTRL(timer) |= (1 << (sm + MCTRL_CLDOK_SHIFT)); + rVAL1(timer, sm) = (FLEXPWM_FREQ / LED_PWM_FREQ) - 1; + + if (out_mask & OUTEN_A_MASK) { + rVAL3(timer, sm) = (FLEXPWM_FREQ / LED_PWM_FREQ) - (cvalue); + + } else if (out_mask & OUTEN_B_MASK) { + rVAL5(timer, sm) = (FLEXPWM_FREQ / LED_PWM_FREQ) - (cvalue); + } + + rMCTRL(timer) |= MCTRL_LDOK(1 << sm) | MCTRL_RUN(1 << sm); + px4_arch_configgpio(pwm_mux); + } +} + +int +led_pwm_servo_set(unsigned channel, uint8_t cvalue) +{ + if (channel == 0) { + flexpwm_led(IMXRT_FLEXPWM3_BASE, 2, cvalue, GPIO_nLED_RED, PWM_LED_RED, OUTEN_A_MASK); + + } else if (channel == 1) { + flexpwm_led(IMXRT_FLEXPWM1_BASE, 3, cvalue, GPIO_nLED_GREEN, PWM_LED_GREEN, OUTEN_A_MASK); + + } else if (channel == 2) { + flexpwm_led(IMXRT_FLEXPWM3_BASE, 2, cvalue * 3, GPIO_nLED_BLUE, PWM_LED_BLUE, OUTEN_B_MASK); + } + + return 0; +} + +void flexpwm_init(uint32_t timer, uint32_t sm, uint32_t out_mask) +{ + /* Clear all Faults */ + rFSTS0(timer) = FSTS_FFLAG_MASK; + rMCTRL(timer) |= (1 << (sm + MCTRL_CLDOK_SHIFT)); + + rCTRL2(timer, sm) = SMCTRL2_CLK_SEL_EXT_CLK | SMCTRL2_DBGEN | SMCTRL2_INDEP; + rCTRL(timer, sm) = SMCTRL_PRSC_DIV16 | SMCTRL_FULL; + /* Edge aligned at 0 */ + rINIT(timer, sm) = 0; + rVAL0(timer, sm) = 0; + rVAL2(timer, sm) = 0; + rVAL4(timer, sm) = 0; + rFFILT0(timer) &= ~FFILT_FILT_PER_MASK; + rDISMAP0(timer, sm) = 0xf000; + rDISMAP1(timer, sm) = 0xf000; + + + if (out_mask & OUTEN_A_MASK) { + rOUTEN(timer) |= OUTEN_PWMA_EN(1 << sm); + } + + if (out_mask & OUTEN_B_MASK) { + rOUTEN(timer) |= OUTEN_PWMB_EN(1 << sm); + } + + rDTSRCSEL(timer) = 0; + rMCTRL(timer) |= MCTRL_LDOK(1 << sm); +} + +int led_pwm_servo_init() +{ + /* PWM_LED_GREEN - FLEXPWM2_PWMB03 */ + imxrt_clockall_pwm1(); + imxrt_clockall_pwm3(); + + flexpwm_init(IMXRT_FLEXPWM3_BASE, 2, OUTEN_A_MASK | OUTEN_B_MASK); // GPIO_FLEXPWM3_PWMA02_1 + flexpwm_init(IMXRT_FLEXPWM1_BASE, 3, OUTEN_A_MASK); // GPIO_FLEXPWM1_PWMA03_2 + + + + return OK; +} diff --git a/boards/nxp/mr-tropic/src/usb.c b/boards/nxp/mr-tropic/src/usb.c new file mode 100644 index 0000000000..cae9750e9c --- /dev/null +++ b/boards/nxp/mr-tropic/src/usb.c @@ -0,0 +1,129 @@ +/**************************************************************************** + * + * Copyright (C) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file usb.c + * + * Board-specific USB functions. + */ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include "board_config.h" +#include "imxrt_periphclks.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ +int imxrt_usb_initialize(void) +{ + imxrt_clockall_usboh3(); + return 0; +} +/************************************************************************************ + * Name: imxrt_usbpullup + * + * Description: + * If USB is supported and the board supports a pullup via GPIO (for USB software + * connect and disconnect), then the board software must provide imxrt_usbpullup. + * See include/nuttx/usb/usbdev.h for additional description of this method. + * Alternatively, if no pull-up GPIO the following EXTERN can be redefined to be + * NULL. + * + ************************************************************************************/ + +__EXPORT +int imxrt_usbpullup(FAR struct usbdev_s *dev, bool enable) +{ + usbtrace(TRACE_DEVPULLUP, (uint16_t)enable); + + return OK; +} + +/************************************************************************************ + * Name: imxrt_usbsuspend + * + * Description: + * Board logic must provide the imxrt_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +__EXPORT +void imxrt_usbsuspend(FAR struct usbdev_s *dev, bool resume) +{ + uinfo("resume: %d\n", resume); +} + +/************************************************************************************ + * Name: board_read_VBUS_state + * + * Description: + * All boards must provide a way to read the state of VBUS, this my be simple + * digital input on a GPIO. Or something more complicated like a Analong input + * or reading a bit from a USB controller register. + * + * Returns - 0 if connected. + * + ************************************************************************************/ + +int board_read_VBUS_state(void) +{ + + return (getreg32(IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT) & USB_ANALOG_USB_VBUS_DETECT_STAT_VBUS_VALID) ? 0 : 1; +} diff --git a/platforms/common/include/px4_platform_common/board_common.h b/platforms/common/include/px4_platform_common/board_common.h index 8905507cd0..1056d721b9 100644 --- a/platforms/common/include/px4_platform_common/board_common.h +++ b/platforms/common/include/px4_platform_common/board_common.h @@ -157,8 +157,13 @@ #if BOARD_NUMBER_BRICKS == 0 /* allow SITL to disable all bricks */ #elif BOARD_NUMBER_BRICKS == 1 -# define BOARD_BATT_V_LIST {ADC_BATTERY_VOLTAGE_CHANNEL} -# define BOARD_BATT_I_LIST {ADC_BATTERY_CURRENT_CHANNEL} +# if defined(BOARD_NUMBER_DIGITAL_BRICKS) +# define BOARD_BATT_V_LIST {-1} +# define BOARD_BATT_I_LIST {-1} +# else +# define BOARD_BATT_V_LIST {ADC_BATTERY_VOLTAGE_CHANNEL} +# define BOARD_BATT_I_LIST {ADC_BATTERY_CURRENT_CHANNEL} +# endif # define BOARD_BRICK_VALID_LIST {BOARD_ADC_BRICK_VALID} #elif BOARD_NUMBER_BRICKS == 2 # if defined(BOARD_NUMBER_DIGITAL_BRICKS) diff --git a/platforms/nuttx/CMakeLists.txt b/platforms/nuttx/CMakeLists.txt index 4bee8ed581..49e44b12ae 100644 --- a/platforms/nuttx/CMakeLists.txt +++ b/platforms/nuttx/CMakeLists.txt @@ -507,6 +507,9 @@ if(NOT NUTTX_DIR MATCHES "external") if(CONFIG_ARCH_CHIP_MIMXRT1062DVL6A) set(DEBUG_DEVICE "MIMXRT1062XXX6A") set(DEBUG_SVD_FILE "MIMXRT1062.xml") + elseif(CONFIG_ARCH_CHIP_MIMXRT1064DVL6A) + set(DEBUG_DEVICE "MIMXRT1064XXX6A") + set(DEBUG_SVD_FILE "MIMXRT1064.xml") elseif(CONFIG_ARCH_CHIP_MIMXRT1176DVMAA) set(DEBUG_DEVICE "MIMXRT1176DVMAA") set(DEBUG_SVD_FILE "MIMXRT1176_cm7.xml") diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index d50ffd3544..fb2fadf6f5 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit d50ffd354495ce5d30814dba41d2eb70a32b8fa3 +Subproject commit fb2fadf6f599c1406f052db013efd00a2518e72c diff --git a/platforms/nuttx/cmake/px4_impl_os.cmake b/platforms/nuttx/cmake/px4_impl_os.cmake index cefa37a6c2..98be37ff3f 100644 --- a/platforms/nuttx/cmake/px4_impl_os.cmake +++ b/platforms/nuttx/cmake/px4_impl_os.cmake @@ -158,6 +158,9 @@ function(px4_os_determine_build_chip) elseif(CONFIG_ARCH_CHIP_MIMXRT1062DVL6A) set(CHIP_MANUFACTURER "nxp") set(CHIP "rt106x") + elseif(CONFIG_ARCH_CHIP_MIMXRT1064DVL6A) + set(CHIP_MANUFACTURER "nxp") + set(CHIP "rt106x") elseif(CONFIG_ARCH_CHIP_MIMXRT1176DVMAA) set(CHIP_MANUFACTURER "nxp") set(CHIP "rt117x") diff --git a/platforms/nuttx/src/bootloader/nxp/imxrt_common/main.c b/platforms/nuttx/src/bootloader/nxp/imxrt_common/main.c index dcdc50a911..a137c8477b 100644 --- a/platforms/nuttx/src/bootloader/nxp/imxrt_common/main.c +++ b/platforms/nuttx/src/bootloader/nxp/imxrt_common/main.c @@ -9,9 +9,19 @@ #include "hw_config.h" #include #include -#include -#include -#include +#ifdef CONFIG_ARCH_FAMILY_IMXRT117x +# include +# include +# include +#else +# include +# include +# include +# include +# include "hardware/imxrt_ccm.h" +# include "imxrt_periphclks.h" +# define SNVS_LPCR_GPR_Z_DIS (1 << 24) /* Bit 24: General Purpose Registers Zeroization Disable */ +#endif #include #include "imxrt_clockconfig.h" @@ -30,14 +40,31 @@ #define APP_SIZE_MAX (BOARD_FLASH_SIZE - (BOOTLOADER_RESERVATION_SIZE + APP_RESERVATION_SIZE)) +#ifdef CONFIG_ARCH_FAMILY_IMXRT117x #define CHIP_TAG "i.MX RT11?0,r??" -#define CHIP_TAG_LEN sizeof(CHIP_TAG)-1 - #define SI_REV(n) ((n & 0x7000000) >> 24) #define DIFPROG_TYPE(n) ((n & 0xF000) >> 12) #define DIFPROG_REV_MAJOR(n) ((n & 0xF0) >> 4) #define DIFPROG_REV_MINOR(n) ((n & 0xF)) +#elif defined(CONFIG_ARCH_FAMILY_IMXRT106x) +#define CHIP_TAG "i.MX RT10?? r?.?" +#define DIGPROG_MINOR_SHIFT 0 +#define DIGPROG_MINOR_MASK (0xff << DIGPROG_MINOR_SHIFT) +#define DIGPROG_MINOR(info) (((info) & DIGPROG_MINOR_MASK) >> DIGPROG_MINOR_SHIFT) +#define DIGPROG_MAJOR_LOWER_SHIFT 8 +#define DIGPROG_MAJOR_LOWER_MASK (0xff << DIGPROG_MAJOR_LOWER_SHIFT) +#define DIGPROG_MAJOR_LOWER(info) (((info) & DIGPROG_MAJOR_LOWER_MASK) >> DIGPROG_MAJOR_LOWER_SHIFT) +#define DIGPROG_MAJOR_UPPER_SHIFT 16 +#define DIGPROG_MAJOR_UPPER_MASK (0xff << DIGPROG_MAJOR_UPPER_SHIFT) +#define DIGPROG_MAJOR_UPPER(info) (((info) & DIGPROG_MAJOR_UPPER_MASK) >> DIGPROG_MAJOR_UPPER_SHIFT) +#endif +#define CHIP_TAG_LEN sizeof(CHIP_TAG)-1 +#ifdef CONFIG_ARCH_FAMILY_IMXRT117x +#define FLASH_BASE IMXRT_FLEXSPI1_CIPHER_BASE +#elif defined(CONFIG_ARCH_CHIP_MIMXRT1064DVL6A) +#define FLASH_BASE IMXRT_FLEX2CIPHER_BASE +#endif /* context passed to cinit */ #if INTERFACE_USART @@ -287,6 +314,27 @@ board_deinit(void) px4_arch_configgpio(MK_GPIO_INPUT(BOARD_PIN_LED_BOOTLOADER)); #endif +#ifdef CONFIG_ARCH_FAMILY_IMXRT106x + + // Restore CCM registers to ROM state + putreg32(0x00000001, IMXRT_CCM_CACRR); + putreg32(0x000A8200, IMXRT_CCM_CBCDR); + putreg32(0x06490B03, IMXRT_CCM_CSCDR1); + putreg32(0x75AE8104, IMXRT_CCM_CBCMR); + putreg32(0x67930001, IMXRT_CCM_CSCMR1); + + imxrt_clockoff_lpuart3(); + imxrt_clockoff_usboh3(); + imxrt_clockoff_timer3(); + imxrt_clockoff_xbar1(); + imxrt_clockoff_xbar3(); + + up_disable_icache(); + up_disable_dcache(); + +#endif + +#ifdef CONFIG_ARCH_FAMILY_IMXRT117x const uint32_t dnfw[] = { CCM_CR_M7, CCM_CR_BUS, @@ -309,6 +357,8 @@ board_deinit(void) putreg32(CCM_CR_CTRL_OFF, IMXRT_CCM_CR_CTRL(i)); } } + +#endif } inline void arch_systic_init(void) @@ -365,7 +415,7 @@ ssize_t arch_flash_write(uintptr_t address, const void *buffer, size_t buflen) j++; } - uintptr_t offset = ((uintptr_t) address) - IMXRT_FLEXSPI1_CIPHER_BASE; + uintptr_t offset = ((uintptr_t) address) - FLASH_BASE; volatile uint32_t status = ROM_FLEXSPI_NorFlash_ProgramPage(1, pConfig, offset, (const uint32_t *)buffer); up_invalidate_dcache((uintptr_t)address, @@ -400,7 +450,7 @@ flash_func_sector_size(unsigned sector) ssize_t up_progmem_ispageerased(unsigned sector) { const uint32_t bytes_per_sector = flash_func_sector_size(sector); - uint32_t *address = (uint32_t *)(IMXRT_FLEXSPI1_CIPHER_BASE + (sector * bytes_per_sector)); + uint32_t *address = (uint32_t *)(FLASH_BASE + (sector * bytes_per_sector)); const uint32_t uint32_per_sector = bytes_per_sector / sizeof(*address); int blank = 0; /* Assume it is Bank */ @@ -437,9 +487,9 @@ flash_func_erase_sector(unsigned sector, bool force) struct flexspi_nor_config_s *pConfig = &g_bootConfig; const uint32_t bytes_per_sector = flash_func_sector_size(sector); - uint32_t *address = (uint32_t *)(IMXRT_FLEXSPI1_CIPHER_BASE + (sector * bytes_per_sector)); + uint32_t *address = (uint32_t *)(FLASH_BASE + (sector * bytes_per_sector)); - uintptr_t offset = ((uintptr_t) address) - IMXRT_FLEXSPI1_CIPHER_BASE; + uintptr_t offset = ((uintptr_t) address) - FLASH_BASE; irqstate_t flags; flags = enter_critical_section(); volatile uint32_t status = ROM_FLEXSPI_NorFlash_Erase(1, pConfig, (uintptr_t) offset, bytes_per_sector); @@ -473,6 +523,8 @@ flash_func_read_otp(uintptr_t address) return 0; } +#ifdef CONFIG_ARCH_FAMILY_IMXRT117x + uint32_t get_mcu_id(void) { // ??? is DEBUGMCU get able @@ -499,6 +551,36 @@ int get_mcu_desc(int max, uint8_t *revstr) return strp - revstr; } +#elif defined(CONFIG_ARCH_FAMILY_IMXRT106x) + +uint32_t get_mcu_id(void) +{ + return getreg32(IMXRT_OCOTP_UNIQUE_ID_LSB); +} + +int get_mcu_desc(int max, uint8_t *revstr) +{ + uint32_t info = getreg32(IMXRT_USB_ANALOG_DIGPROG); + // CHIP_TAG "i.MX RT10?? r?.?" + static uint8_t chip[sizeof(CHIP_TAG) + 1] = CHIP_TAG; + chip[CHIP_TAG_LEN - 1] = '0' + DIGPROG_MINOR(info); + chip[CHIP_TAG_LEN - 3] = '1' + DIGPROG_MAJOR_LOWER(info); + chip[CHIP_TAG_LEN - 6] = getreg32(0x401F867C) == 0x10 ? '4' : '2'; + chip[CHIP_TAG_LEN - 7] = DIGPROG_MAJOR_UPPER(info) == 0x6a ? '5' : '6'; + + uint8_t *endp = &revstr[max - 1]; + uint8_t *strp = revstr; + uint8_t *des = chip; + + while (strp < endp && *des) { + *strp++ = *des++; + } + + return strp - revstr; +} + +#endif + int check_silicon(void) { @@ -717,6 +799,7 @@ bootloader_main(void) * Returns - 0 if connected. * ************************************************************************************/ +#ifdef CONFIG_ARCH_FAMILY_IMXRT117x #undef IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT #define USB1_VBUS_DET_STAT_OFFSET 0xd0 #define IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT (IMXRT_USBPHY1_BASE + USB1_VBUS_DET_STAT_OFFSET) @@ -727,6 +810,17 @@ bootloader_main(void) try_boot = false; } +#elif defined(CONFIG_ARCH_FAMILY_IMXRT106x) +#undef IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT +#define IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT (IMXRT_ANATOP_BASE + IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT_OFFSET) + + if ((getreg32(IMXRT_USB_ANALOG_USB1_VBUS_DETECT_STAT) & USB_ANALOG_USB_VBUS_DETECT_STAT_VBUS_VALID) != 0) { + usb_connected = true; + /* don't try booting before we set up the bootloader */ + try_boot = false; + } + +#endif #endif #if INTERFACE_USART diff --git a/platforms/nuttx/src/bootloader/nxp/rt106x/CMakeLists.txt b/platforms/nuttx/src/bootloader/nxp/rt106x/CMakeLists.txt new file mode 100644 index 0000000000..a1c9b593c9 --- /dev/null +++ b/platforms/nuttx/src/bootloader/nxp/rt106x/CMakeLists.txt @@ -0,0 +1,34 @@ +############################################################################ +# +# Copyright (c) 2023 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +add_subdirectory(../imxrt_common arch_bootloader) diff --git a/platforms/nuttx/src/px4/nxp/imxrt/board_reset/CMakeLists.txt b/platforms/nuttx/src/px4/nxp/imxrt/board_reset/CMakeLists.txt index deff20f14c..cba22cb320 100644 --- a/platforms/nuttx/src/px4/nxp/imxrt/board_reset/CMakeLists.txt +++ b/platforms/nuttx/src/px4/nxp/imxrt/board_reset/CMakeLists.txt @@ -35,9 +35,7 @@ px4_add_library(arch_board_reset board_reset.cpp ) -if (CONFIG_ARCH_FAMILY_IMXRT117x) target_link_libraries(arch_board_reset PRIVATE arch_board_romapi) -endif() # up_systemreset if (NOT DEFINED CONFIG_BUILD_FLAT) diff --git a/platforms/nuttx/src/px4/nxp/imxrt/board_reset/board_reset.cpp b/platforms/nuttx/src/px4/nxp/imxrt/board_reset/board_reset.cpp index 1d29a64dfb..85236a00e6 100644 --- a/platforms/nuttx/src/px4/nxp/imxrt/board_reset/board_reset.cpp +++ b/platforms/nuttx/src/px4/nxp/imxrt/board_reset/board_reset.cpp @@ -45,6 +45,12 @@ #ifdef CONFIG_ARCH_FAMILY_IMXRT117x #include +#elif defined CONFIG_ARCH_FAMILY_IMXRT106x +# include +# define SNVS_LPCR_GPR_Z_DIS (1 << 24) /* Bit 24: General Purpose Registers Zeroization Disable */ +#endif + +#ifdef BOARD_HAS_ISP_BOOTLOADER #include #include #endif @@ -59,13 +65,9 @@ static int board_reset_enter_bootloader() { -#ifdef CONFIG_ARCH_FAMILY_IMXRT117x uint32_t regvalue = BOOT_RTC_SIGNATURE; modifyreg32(IMXRT_SNVS_LPCR, 0, SNVS_LPCR_GPR_Z_DIS); putreg32(regvalue, PX4_IMXRT_RTC_REBOOT_REG_ADDRESS); -#elif defined(BOARD_HAS_TEENSY_BOOTLOADER) - asm("BKPT #251"); /* Enter Teensy MKL02 bootloader */ -#endif return OK; } @@ -75,15 +77,16 @@ int board_reset(int status) board_reset_enter_bootloader(); } -#if defined(BOARD_HAS_ISP_BOOTLOADER) - else if (status == REBOOT_TO_ISP) { +#ifdef BOARD_HAS_TEENSY_BOOTLOADER + asm("BKPT #251"); /* Enter Teensy MKL02 bootloader */ +#elif defined(BOARD_HAS_ISP_BOOTLOADER) uint32_t arg = 0xeb100000; ROM_API_Init(); ROM_RunBootloader(&arg); +#endif } -#endif #if defined(BOARD_HAS_ON_RESET) board_on_reset(status); diff --git a/platforms/nuttx/src/px4/nxp/imxrt/include/px4_arch/imxrt_flexspi_nor_flash.h b/platforms/nuttx/src/px4/nxp/imxrt/include/px4_arch/imxrt_flexspi_nor_flash.h index 727744b974..e58554aa5b 100644 --- a/platforms/nuttx/src/px4/nxp/imxrt/include/px4_arch/imxrt_flexspi_nor_flash.h +++ b/platforms/nuttx/src/px4/nxp/imxrt/include/px4_arch/imxrt_flexspi_nor_flash.h @@ -138,18 +138,33 @@ (FLEXSPI_LUT_OPERAND0(op0) | FLEXSPI_LUT_NUM_PADS0(pad0) | FLEXSPI_LUT_OPCODE0(cmd0) | FLEXSPI_LUT_OPERAND1(op1) | \ FLEXSPI_LUT_NUM_PADS1(pad1) | FLEXSPI_LUT_OPCODE1(cmd1)) +#ifdef CONFIG_ARCH_FAMILY_IMXRT106x +//!@brief Definitions for FlexSPI Serial Clock Frequency +typedef enum _FlexSpiSerialClockFreq { + kFlexSpiSerialClk_30MHz = 1, + kFlexSpiSerialClk_50MHz = 2, + kFlexSpiSerialClk_60MHz = 3, + kFlexSpiSerialClk_75MHz = 4, + kFlexSpiSerialClk_80MHz = 5, + kFlexSpiSerialClk_100MHz = 6, + kFlexSpiSerialClk_120MHz = 7, + kFlexSpiSerialClk_133MHz = 8, + kFlexSpiSerialClk_166MHz = 9, +} flexspi_serial_clk_freq_t; +#elif defined(CONFIG_ARCH_FAMILY_IMXRT117x) //!@brief Definitions for FlexSPI Serial Clock Frequency typedef enum _FlexSpiSerialClockFreq { kFlexSpiSerialClk_30MHz = 1, kFlexSpiSerialClk_50MHz = 2, kFlexSpiSerialClk_60MHz = 3, kFlexSpiSerialClk_80MHz = 4, - kFlexSpiSerialClk_100MHz = 5, + kFlexSpiSerialClk_100MHz = 5, kFlexSpiSerialClk_120MHz = 6, kFlexSpiSerialClk_133MHz = 7, kFlexSpiSerialClk_166MHz = 8, kFlexSpiSerialClk_200MHz = 9, } flexspi_serial_clk_freq_t; +#endif //!@brief FlexSPI clock configuration type enum { diff --git a/platforms/nuttx/src/px4/nxp/imxrt/include/px4_arch/imxrt_romapi.h b/platforms/nuttx/src/px4/nxp/imxrt/include/px4_arch/imxrt_romapi.h index f51775e2bd..fa944e0c1b 100644 --- a/platforms/nuttx/src/px4/nxp/imxrt/include/px4_arch/imxrt_romapi.h +++ b/platforms/nuttx/src/px4/nxp/imxrt/include/px4_arch/imxrt_romapi.h @@ -239,7 +239,9 @@ status_t ROM_FLEXSPI_NorFlash_Erase(uint32_t instance, flexspi_nor_config_t *con * @retval kStatus_ROM_FLEXSPI_SequenceExecutionTimeout Sequence Execution timeout. * @retval kStatus_ROM_FLEXSPI_DeviceTimeout the device timeout */ +#ifdef CONFIG_ARCH_FAMILY_IMXRT117x status_t ROM_FLEXSPI_NorFlash_EraseSector(uint32_t instance, flexspi_nor_config_t *config, uint32_t start); +#endif /*! * @brief Erase one block specified by address @@ -259,7 +261,9 @@ status_t ROM_FLEXSPI_NorFlash_EraseSector(uint32_t instance, flexspi_nor_config_ * @retval kStatus_ROM_FLEXSPI_SequenceExecutionTimeout Sequence Execution timeout. * @retval kStatus_ROM_FLEXSPI_DeviceTimeout the device timeout */ +#ifdef CONFIG_ARCH_FAMILY_IMXRT117x status_t ROM_FLEXSPI_NorFlash_EraseBlock(uint32_t instance, flexspi_nor_config_t *config, uint32_t start); +#endif /*! * @brief Erase all the Serial NOR devices connected on FLEXSPI. @@ -342,10 +346,12 @@ status_t ROM_FLEXSPI_NorFlash_UpdateLut(uint32_t instance, * @retval kStatus_ROM_FLEXSPI_InvalidSequence A invalid Sequence is provided. * @retval kStatus_ROM_FLEXSPI_DeviceTimeout Device timeout. */ +#ifdef CONFIG_ARCH_FAMILY_IMXRT117x status_t ROM_FLEXSPI_NorFlash_WaitBusy(uint32_t instance, flexspi_nor_config_t *config, bool isParallelMode, uint32_t address); +#endif /*@}*/ /*! diff --git a/platforms/nuttx/src/px4/nxp/imxrt/romapi/imxrt_romapi.c b/platforms/nuttx/src/px4/nxp/imxrt/romapi/imxrt_romapi.c index 68443e3353..1d63860965 100644 --- a/platforms/nuttx/src/px4/nxp/imxrt/romapi/imxrt_romapi.c +++ b/platforms/nuttx/src/px4/nxp/imxrt/romapi/imxrt_romapi.c @@ -52,8 +52,29 @@ typedef union _standard_version { #endif } standard_version_t; + +#ifdef CONFIG_ARCH_FAMILY_IMXRT106x + /*! - * @brief Interface for the ROM FLEXSPI NOR flash driver. + * @brief Interface for the IMXRT106X ROM FLEXSPI NOR flash driver. + */ +typedef struct { + uint32_t version; + status_t (*init)(uint32_t instance, flexspi_nor_config_t *config); + status_t (*page_program)(uint32_t instance, flexspi_nor_config_t *config, uint32_t dst_addr, const uint32_t *src); + status_t (*erase_all)(uint32_t instance, flexspi_nor_config_t *config); + status_t (*erase)(uint32_t instance, flexspi_nor_config_t *config, uint32_t start, uint32_t length); + status_t (*read)(uint32_t instance, flexspi_nor_config_t *config, uint32_t *dst, uint32_t start, uint32_t bytes); + void (*clear_cache)(uint32_t instance); + status_t (*xfer)(uint32_t instance, flexspi_xfer_t *xfer); + status_t (*update_lut)(uint32_t instance, uint32_t seqIndex, const uint32_t *lutBase, uint32_t numberOfSeq); + status_t (*get_config)(uint32_t instance, flexspi_nor_config_t *config, serial_nor_config_option_t *option); +} flexspi_nor_driver_interface_t; + +#elif defined(CONFIG_ARCH_FAMILY_IMXRT117x) + +/*! + * @brief Interface for the IMXRT117X ROM FLEXSPI NOR flash driver. */ typedef struct { uint32_t version; @@ -73,6 +94,33 @@ typedef struct { const uint32_t reserved1[2]; /*!< Reserved */ } flexspi_nor_driver_interface_t; +#endif + + +#ifdef CONFIG_ARCH_FAMILY_IMXRT106x + +/*! +* @brief Root of the bootloader api tree. +* +* An instance of this struct resides in read-only memory in the bootloader. It +* provides a user application access to APIs exported by the bootloader. +* +* @note The order of existing fields must not be changed. +*/ +typedef struct { + const uint32_t version; //!< Bootloader version number + const char *copyright; //!< Bootloader Copyright + void (*runBootloader)(void *arg); //!< Function to start the bootloader executing + const uint32_t *reserved0; //!< Reserved + const flexspi_nor_driver_interface_t *flexSpiNorDriver; //!< FlexSPI NOR Flash API + const uint32_t *reserved1; //!< Reserved + const uint32_t *unused_rtwdogDriver; + const uint32_t *unused_wdogDriver; + const uint32_t *reserved2; +} bootloader_api_entry_t; + +#elif defined(CONFIG_ARCH_FAMILY_IMXRT117x) + /*! * @brief Root of the bootloader api tree. * @@ -89,6 +137,8 @@ typedef struct { const uint32_t reserved[8]; /*!< Reserved */ } bootloader_api_entry_t; +#endif + /******************************************************************************* * Variables ******************************************************************************/ @@ -104,6 +154,9 @@ static bootloader_api_entry_t *g_bootloaderTree = NULL; locate_code(".ramfunc") void ROM_API_Init(void) { +#ifdef CONFIG_ARCH_FAMILY_IMXRT106x + g_bootloaderTree = ((bootloader_api_entry_t *) * (uint32_t *)0x0020001cU); +#else if ((getreg32(IMXRT_ANADIG_MISC_MISC_DIFPROG) & ANADIG_MISC_MISC_DIFPROG_CHIPID(0x10U)) != 0U) { g_bootloaderTree = ((bootloader_api_entry_t *) * (uint32_t *)0x0021001cU); @@ -111,6 +164,8 @@ void ROM_API_Init(void) } else { g_bootloaderTree = ((bootloader_api_entry_t *) * (uint32_t *)0x0020001cU); } + +#endif } /*! @@ -193,6 +248,8 @@ status_t ROM_FLEXSPI_NorFlash_Erase(uint32_t instance, flexspi_nor_config_t *con return g_bootloaderTree->flexSpiNorDriver->erase(instance, config, start, length); } +#ifdef CONFIG_ARCH_FAMILY_IMXRT117x + /*! * @brief Erase one sector specified by address. * @@ -219,6 +276,8 @@ status_t ROM_FLEXSPI_NorFlash_EraseBlock(uint32_t instance, flexspi_nor_config_t return g_bootloaderTree->flexSpiNorDriver->erase_block(instance, config, start); } +#endif + /*! @brief Erase all the Serial NOR devices connected on FLEXSPI. */ locate_code(".ramfunc") status_t ROM_FLEXSPI_NorFlash_EraseAll(uint32_t instance, flexspi_nor_config_t *config) @@ -242,6 +301,19 @@ status_t ROM_FLEXSPI_NorFlash_UpdateLut(uint32_t instance, return g_bootloaderTree->flexSpiNorDriver->update_lut(instance, seqIndex, lutBase, seqNumber); } + +#ifdef CONFIG_ARCH_FAMILY_IMXRT106x + +/*! @brief Software reset for the FLEXSPI logic. */ +locate_code(".ramfunc") +void ROM_FLEXSPI_NorFlash_ClearCache(uint32_t instance) +{ + g_bootloaderTree->flexSpiNorDriver->clear_cache(instance); +} + + +#elif defined(CONFIG_ARCH_FAMILY_IMXRT117x) + /*! @brief Software reset for the FLEXSPI logic. */ locate_code(".ramfunc") void ROM_FLEXSPI_NorFlash_ClearCache(uint32_t instance) @@ -259,6 +331,9 @@ void ROM_FLEXSPI_NorFlash_ClearCache(uint32_t instance) MISRA_CAST(clearCacheCommand_t, clearCacheCommand, uint32_t, clearCacheFunctionAddress); (void)clearCacheCommand(instance); } +#endif + +#ifdef CONFIG_ARCH_FAMILY_IMXRT117x /*! @brief Wait until device is idle*/ locate_code(".ramfunc") @@ -269,3 +344,5 @@ status_t ROM_FLEXSPI_NorFlash_WaitBusy(uint32_t instance, { return g_bootloaderTree->flexSpiNorDriver->wait_busy(instance, config, isParallelMode, address); } + +#endif diff --git a/platforms/nuttx/src/px4/nxp/imxrt/version/board_mcu_version.c b/platforms/nuttx/src/px4/nxp/imxrt/version/board_mcu_version.c index ae8594bd4f..94c75844d8 100644 --- a/platforms/nuttx/src/px4/nxp/imxrt/version/board_mcu_version.c +++ b/platforms/nuttx/src/px4/nxp/imxrt/version/board_mcu_version.c @@ -90,7 +90,7 @@ int board_mcu_version(char *rev, const char **revstr, const char **errata) #define DIGPROG_MAJOR_UPPER_MASK (0xff << DIGPROG_MAJOR_UPPER_SHIFT) #define DIGPROG_MAJOR_UPPER(info) (((info) & DIGPROG_MAJOR_UPPER_MASK) >> DIGPROG_MAJOR_UPPER_SHIFT) // 876543210 -#define CHIP_TAG "i.MX RT10?2 r?.?" +#define CHIP_TAG "i.MX RT10?? r?.?" #define CHIP_TAG_LEN sizeof(CHIP_TAG)-1 int board_mcu_version(char *rev, const char **revstr, const char **errata) @@ -100,6 +100,7 @@ int board_mcu_version(char *rev, const char **revstr, const char **errata) chip[CHIP_TAG_LEN - 1] = '0' + DIGPROG_MINOR(info); chip[CHIP_TAG_LEN - 3] = '1' + DIGPROG_MAJOR_LOWER(info); + chip[CHIP_TAG_LEN - 6] = getreg32(0x401F867C) == 0x10 ? '4' : '2'; chip[CHIP_TAG_LEN - 7] = DIGPROG_MAJOR_UPPER(info) == 0x6a ? '5' : '6'; *revstr = chip; *rev = '0' + DIGPROG_MINOR(info); diff --git a/platforms/nuttx/src/px4/nxp/rt106x/CMakeLists.txt b/platforms/nuttx/src/px4/nxp/rt106x/CMakeLists.txt index f487b031c7..57bd94ee6e 100644 --- a/platforms/nuttx/src/px4/nxp/rt106x/CMakeLists.txt +++ b/platforms/nuttx/src/px4/nxp/rt106x/CMakeLists.txt @@ -36,11 +36,13 @@ add_subdirectory(../imxrt/adc adc) add_subdirectory(../imxrt/board_critmon board_critmon) add_subdirectory(../imxrt/board_hw_info board_hw_info) add_subdirectory(../imxrt/board_reset board_reset) +add_subdirectory(../imxrt/romapi romapi) add_subdirectory(../imxrt/dshot dshot) add_subdirectory(../imxrt/hrt hrt) add_subdirectory(../imxrt/led_pwm led_pwm) add_subdirectory(../imxrt/io_pins io_pins) add_subdirectory(../imxrt/tone_alarm tone_alarm) add_subdirectory(../imxrt/version version) +add_subdirectory(../imxrt/spi spi) add_subdirectory(px4io_serial) diff --git a/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/hw_description.h b/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/hw_description.h index d4aada2ffe..27da505127 100644 --- a/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/hw_description.h +++ b/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/hw_description.h @@ -41,8 +41,8 @@ #include #include -#ifndef CONFIG_ARCH_CHIP_MIMXRT1062DVL6A -# error "This code has only been validated with IMXRT1062. Make sure it is correct before using it on another board." +#if !defined(CONFIG_ARCH_CHIP_MIMXRT1062DVL6A) && !defined(CONFIG_ARCH_CHIP_MIMXRT1064DVL6A) +# error "This code has only been validated with IMXRT1062 and IMXRT1064. Make sure it is correct before using it on another board." #endif /* diff --git a/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/imxrt_flexspi_nor_flash.h b/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/imxrt_flexspi_nor_flash.h new file mode 100644 index 0000000000..3925012e86 --- /dev/null +++ b/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/imxrt_flexspi_nor_flash.h @@ -0,0 +1,36 @@ +/**************************************************************************** + * + * Copyright (c) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#pragma once + + +#include "../../../imxrt/include/px4_arch/imxrt_flexspi_nor_flash.h" diff --git a/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/imxrt_romapi.h b/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/imxrt_romapi.h new file mode 100644 index 0000000000..aeab841162 --- /dev/null +++ b/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/imxrt_romapi.h @@ -0,0 +1,36 @@ +/**************************************************************************** + * + * Copyright (c) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +#pragma once + + +#include "../../../imxrt/include/px4_arch/imxrt_romapi.h" diff --git a/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/io_timer_hw_description.h b/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/io_timer_hw_description.h index 5cbc33fdc3..a5ec76ea25 100644 --- a/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/io_timer_hw_description.h +++ b/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/io_timer_hw_description.h @@ -47,8 +47,8 @@ #include #include -#ifndef CONFIG_ARCH_CHIP_MIMXRT1062DVL6A -# error "This code has only been validated with IMXRT1062. Make sure it is correct before using it on another board." +#if !defined(CONFIG_ARCH_CHIP_MIMXRT1062DVL6A) && !defined(CONFIG_ARCH_CHIP_MIMXRT1064DVL6A) +# error "This code has only been validated with IMXRT1062 and IMXRT1064. Make sure it is correct before using it on another board." #endif diff --git a/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/spi_hw_description.h b/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/spi_hw_description.h index de0c30247d..0e1a46b8e3 100644 --- a/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/spi_hw_description.h +++ b/platforms/nuttx/src/px4/nxp/rt106x/include/px4_arch/spi_hw_description.h @@ -46,6 +46,58 @@ #define GENERAL_OUTPUT_IOMUX (IOMUX_CMOS_OUTPUT | IOMUX_PULL_KEEP | IOMUX_DRIVE_33OHM | IOMUX_SPEED_MEDIUM | IOMUX_SLEW_FAST) +constexpr bool validateSPIConfig(const px4_spi_bus_t spi_busses_conf[SPI_BUS_MAX_BUS_ITEMS]) +{ + const bool nuttx_enabled_spi_buses[] = { +#ifdef CONFIG_IMXRT_LPSPI1 + true, +#else + false, +#endif +#ifdef CONFIG_IMXRT_LPSPI2 + true, +#else + false, +#endif +#ifdef CONFIG_IMXRT_LPSPI3 + true, +#else + false, +#endif +#ifdef CONFIG_IMXRT_LPSPI4 + true, +#else + false, +#endif +#ifdef CONFIG_IMXRT_LPSPI5 + true, +#else + false, +#endif +#ifdef CONFIG_IMXRT_LPSPI6 + true, +#else + false, +#endif + }; + + for (unsigned i = 0; i < sizeof(nuttx_enabled_spi_buses) / sizeof(nuttx_enabled_spi_buses[0]); ++i) { + bool found_bus = false; + + for (int j = 0; j < SPI_BUS_MAX_BUS_ITEMS; ++j) { + if (spi_busses_conf[j].bus == (int)i + 1) { + found_bus = true; + } + } + + // Either the bus is enabled in NuttX and configured in spi_busses_conf, or disabled and not configured + constexpr_assert(found_bus == nuttx_enabled_spi_buses[i], "SPI bus config mismatch (CONFIG_STM32H7_SPIx)"); + } + + return false; +} + + static inline constexpr px4_spi_bus_device_t initSPIDevice(uint32_t devid, SPI::CS cs_gpio, SPI::DRDY drdy_gpio = {}) { px4_spi_bus_device_t ret{}; @@ -138,8 +190,57 @@ static inline constexpr SPI::bus_device_external_cfg_t initSPIConfigExternal(SPI return ret; } -constexpr bool validateSPIConfig(const px4_spi_bus_t spi_busses_conf[SPI_BUS_MAX_BUS_ITEMS]) + +struct px4_spi_bus_array_t { + px4_spi_bus_t item[SPI_BUS_MAX_BUS_ITEMS]; +}; +#if defined(BOARD_HAS_HW_SPLIT_VERSIONING) +static inline constexpr px4_spi_bus_all_hw_t initSPIFmumID(hw_fmun_id_t hw_fmun_id, + const px4_spi_bus_array_t &bus_items) { - return true; + px4_spi_bus_all_hw_t ret{}; + + for (int i = 0; i < SPI_BUS_MAX_BUS_ITEMS; ++i) { + ret.buses[i] = bus_items.item[i]; + } + + ret.board_hw_fmun_id = hw_fmun_id; + return ret; } +#else +static inline constexpr px4_spi_bus_all_hw_t initSPIHWVersion(int hw_version_revision, + const px4_spi_bus_array_t &bus_items) +{ + px4_spi_bus_all_hw_t ret{}; + + for (int i = 0; i < SPI_BUS_MAX_BUS_ITEMS; ++i) { + ret.buses[i] = bus_items.item[i]; + } + + ret.board_hw_version_revision = hw_version_revision; + return ret; +} +#endif +constexpr bool validateSPIConfig(const px4_spi_bus_t spi_buses_conf[SPI_BUS_MAX_BUS_ITEMS]); + +constexpr bool validateSPIConfig(const px4_spi_bus_all_hw_t spi_buses_conf[BOARD_NUM_SPI_CFG_HW_VERSIONS]) +{ + for (int ver = 0; ver < BOARD_NUM_SPI_CFG_HW_VERSIONS; ++ver) { + validateSPIConfig(spi_buses_conf[ver].buses); + } + + for (int ver = 1; ver < BOARD_NUM_SPI_CFG_HW_VERSIONS; ++ver) { + for (int i = 0; i < SPI_BUS_MAX_BUS_ITEMS; ++i) { + const bool equal_power_enable_gpio = spi_buses_conf[ver].buses[i].power_enable_gpio == spi_buses_conf[ver - + 1].buses[i].power_enable_gpio; + // currently board_control_spi_sensors_power_configgpio() depends on that - this restriction can be removed + // by ensuring board_control_spi_sensors_power_configgpio() is called after the hw version is determined + // and SPI config is initialized. + constexpr_assert(equal_power_enable_gpio, "All HW versions must define the same power enable GPIO"); + } + } + + return false; +} + #endif // CONFIG_SPI From cbbdc20bd3d30cf77a97490b3fe4a14f8831a305 Mon Sep 17 00:00:00 2001 From: Beniamino Pozzan Date: Mon, 3 Nov 2025 22:25:03 +0000 Subject: [PATCH 260/812] docs(uxrce_dds): add missing closure for info section Signed-off-by: Beniamino Pozzan --- docs/en/middleware/uxrce_dds.md | 1 + 1 file changed, 1 insertion(+) diff --git a/docs/en/middleware/uxrce_dds.md b/docs/en/middleware/uxrce_dds.md index 8f8da255d3..e931cda1a9 100644 --- a/docs/en/middleware/uxrce_dds.md +++ b/docs/en/middleware/uxrce_dds.md @@ -441,6 +441,7 @@ uxrce_dds_client start -n fancy_uav ``` This can be included in `etc/extras.txt` as part of a custom [System Startup](../concept/system_startup.md). +::: ## PX4 ROS 2 QoS Settings From 311b3cfb677bad7d28643c08c53ebba22eae8194 Mon Sep 17 00:00:00 2001 From: Hubert <1701213518@sz.pku.edu.cn> Date: Thu, 6 Nov 2025 07:05:42 +0800 Subject: [PATCH 261/812] docs: add micoair743-lite documentation. (#25870) * add docs for MicoAir743-Lite * Update images and prettier * update micoair743-lite.md * Update docs/en/flight_controller/micoair743-lite.md * Prettier and cross link RC + add badges * Update docs/en/flight_controller/micoair743-lite.md --------- Co-authored-by: Minderring <1701213518@sz.edu.pku.cn> Co-authored-by: Farhang <46557204+farhangnaderi@users.noreply.github.com> Co-authored-by: Hamish Willee --- .../micoair743_lite/back_view.png | Bin 0 -> 63849 bytes .../micoair743_lite/front_view.png | Bin 0 -> 78387 bytes .../micoair743_lite/interfaces_diagram.png | Bin 0 -> 517207 bytes .../micoair743_lite_pinout.xlsx | Bin 0 -> 14523 bytes .../micoair743_lite/size.png | Bin 0 -> 130706 bytes .../micoair743_lite/wiring_diagram.png | Bin 0 -> 368632 bytes docs/en/SUMMARY.md | 1 + .../autopilot_manufacturer_supported.md | 1 + docs/en/flight_controller/micoair743-lite.md | 152 ++++++++++++++++++ 9 files changed, 154 insertions(+) create mode 100644 docs/assets/flight_controller/micoair743_lite/back_view.png create mode 100644 docs/assets/flight_controller/micoair743_lite/front_view.png create mode 100644 docs/assets/flight_controller/micoair743_lite/interfaces_diagram.png create mode 100644 docs/assets/flight_controller/micoair743_lite/micoair743_lite_pinout.xlsx create mode 100644 docs/assets/flight_controller/micoair743_lite/size.png create mode 100644 docs/assets/flight_controller/micoair743_lite/wiring_diagram.png create mode 100644 docs/en/flight_controller/micoair743-lite.md diff --git a/docs/assets/flight_controller/micoair743_lite/back_view.png b/docs/assets/flight_controller/micoair743_lite/back_view.png new file mode 100644 index 0000000000000000000000000000000000000000..eee32821146b5f8ef3ff8b9882966dfbe129a6c5 GIT binary patch literal 63849 zcmY(pb8saN&@6gl+cq|KvaxO3Jh5$ilWc6;wl>MeIY$vaN_kHiad#7rurh2Bj zyZY~mR#uckg2#sk002lb(&DNB05}i;0DQqh004kq^EFlg003zvq96hQG$tZ^m_Pvl z05DfoDN#V(4B;6702XPZuI;9+AkS;&XwPI~?r3Vk#`^z>x%WM^`8 zv0`TZ`ST|;3mY>V8>5T4C8MjigPVyLqk}8O{}6~Js1I-z+T5 zY^EfJSL)si|ohzTclvkdd7n?Ok2H2=ECgsc7Hdp1eHW~DR2zHKe`V_{+6UYt--k?*cg|4N7jEzB`7(kUq^?JW&_ygXP~STNAje!Sj7LqVyj zscp=4+1lE(u(N)DzUt}eMurD{f82e4eFg^yYH4Y)v#=lUEb{TNf4)B*Y|VXryZ~)1 zO-&3VA|m2r!WU*HQ&Uq{=7-i-7Gq-Lo^DQ)l9Doi1)Oe8goK3sJ6L|dKlb(YZ)j-X zWMjxnkE||;dcNNK(_5RJm5~(VQ&m-Uyf!Ezz}eB+WoT&Z>t+d0;m-%y^?-qtidT)Xo(wW2WT>*LbFLTP_}w6m#buD>WPIp*(h zdw*|7pu5S+XnAQ)NKS5kLb!8(ds$(2;@8V@QDF`PEy?4>x&SwQq`!@eopD5vo2QF) zpts${{&Z(uhMA!%I}=rJU;oX&b)boio|eMqbYojp!qqXzOjiPEq3dETda%^2t|EKB zJw!!{D=)=&e=;{bJls^BGuWJ=t|+p#xjr#5aSQtW{r%Kf8ZtjMWMd>4=A*ecQ!FdY zT2+>v8?86jom80a{rRwmkA?g@K>1g&iIFDX`^{z$E9c?i;l$s;hT4*W`uN+!k@_sR z%gxrz82f)qr7>=jIbOnvK+cjxi-t5aO*yXqV!J?l-XLS<-g5tkla9$I|H=r(*Uh5c z;m`nUjmxPJXLY*Q>xCje$CrO2k;*FlsmVZMGGS_x#%8TV0Du%ABQB!uwSJKmsGRal zGzP}UAZ@xxKB{4&YD&wUN}>vJWlU!VVk;!x+e9Pvh>)maVa%So*@!fimn208ub>o0 z?6-hKV`KTi1U2CE1Y;nF&0o}=kQ_N|B^=cI_wAg(6}7Bf&de+b)YAwN55#)%*ZT(c zU0;Xh5+VJ+HI0%gOj9oW)-HU{mih*rBit&i%axT5b8wCZpNoq4h9iEz#V1`Yc~4Zj z9$WNEv1GksZJ2Bw1KX%QF!Dmtp7ZfTvrlAF@_y$a!ppEVO1yP_EMi?Mo*3v}ga=mV zugC1w$1@PwfAh-mO_S6r%W|Jc3LrOy)#>!$nZ4Ie%RQ1>cXbwgG0jmhkj9IPW zdz=3=W(h;?Ub7miLAM5W5!}?-#5o`-8RbE*Du48?w7mTN#V#6(^xf&E_U_M*Av1-k!70TT|Belh^@dSi+5srW}$xHXP9h%Q%_MQI7rjr;$KzZH>2)x z(yHe)$Bb3=sB~@>U!|%7L6H&`{=!{W2Es5;_3fTi??G_>MLG@pS=pk9!(KEIgahCV zIT)Gx4z^y{b`P9-<>F447y4Hkw5b#nqn(|dn)2a_=?0j2T|(~P^@@4?-;-P0+m||L zXF57MEHp4o9=hrS6n+)I91lbN2KNP&b<}5z66O1j&RiQUUBkem&&vRd4~uf*DUo$v(}wK__X?`*%={z5n2flExW1gL}b8_?#=Ej zQj+;Jy>8{5P_RZ)PAJEBaL|(Nts$_*>0Gt7B!6eJu7b9fRo>m5larg9i)*>W0-%wp zae%3zaSCTX6s&{h;^1&vrMY3lyDXR0g!qpkgSQns6&pF*X0J=Gn@njTfxj#!NEZnUprj}P701EIrE1UZ7OQu$jC3h^%+IB zM|lKl0)$Bxn#D(Hu3&A3Af|4+Ca8RSK#HlZhUS8Z%UR^9#F^AvJECOqB^FqEpVvA3 z9!zs;Cs7!TNSt79m;ZZnWo1B;H2Sm$l$RfJ{QN&eQ z8MT6(nXaV9x);_2{{>N|Z>II>gp}mrsSU@_D&q{(?W6y7?~PGpWaK;X`=^odNcz(D zRW4_*d6R1MBYl(gFGsp6C;saly4RZ6M-0;Jpgy1Tn9Ir)#|ZB*v|`V`m%F58^LfFy zjh*}=V^^oBjgEN}vz%Um#gwzFi9N7@B!1%j*+l4dN_03#V+dAWemmOpKFEJZmL+6t zvU2RHF2Fa-{gFI<2lb&~VS2&bI#Dgv^<%KTCcF8E0Mue!a# zeaJA1T;RE#pX3%Ns>z>4J_;?I^fDEUu%+dt+44DD_bAtf#AYkDXK!9UzHXNcdFt%( zV?dp8j+p$1b7c#v2r4=3P#aet?1wGs8(&v&41gGiPSI}iZY!&NNmjLYA}giU44Ch($OWg3Cv_~zPy0Y!ZYfuZf;k02lKe%zty6) zf*iJuJ{6|8Qa9OzxuWMp3s~vq#Y1}Pn0Z-QU4cqJ0q9K6qDr-n&#c9CG5QDaHnV-- zRT3jT&9zQdRa%Y_f{`9F^M;lEyElzv#YkYzfXek4+q}Fhh9^y~NM->wZ_B44J9SXz z+TaAeH_4E(1VtLe^*k8yQveJ#%{%gg0x=JZx48=&<)1`mI8=%I;!E!jE_t#3L6*(= z#Vx<$htXDoUmm3T)hc;5)jj4r!o=$=`;dg9BM_JEn3q4Vo6p8fD{%G6R#a#|B)68g z$4g&#hF6_H^fiUHhqFKzm~D?*T*UmlmH-t%Wfo0o7T>Fz6;x*k@U<0=^>%!mwH!Gw z_2`7?q_fGuIURuP?^6A=D-!zql!g-B#zY8FSH-QxA0V{AOlgju8L3)dhkOXh9Egbu zNNpdU1KG1+ax5P%3(tlRW+z3=j8`Q&VMD_JaXdFyY^H`%MXp1?edB5+11gGGGuRCf_+f8+1c8jr*7I zf+J`;MqPGpuM&vrdJd$Na#!8S_gq}=%2~Tz%*S*@L_`>{5yTJfd++XrWTdUxaJw8l z@qoH6^iMfgyAt0FM|YLxV%cHVw&xV$bC$#6Nl743IL3Cfn$|lYk);wx1XDI8DX8JW z)<%*PPGmUFiXh;yPVPtN5`)%$HzAdTvitB3GqaKcqoY>#yZ}p=NRRF&p@9oBT5+O+ z&sEm^fw>|IGX*7qR`sZ8&r}J zV~4==7OaMILxtess(H)a?H$i)}G-~LW9ef!}>&{Ht4f48vF)`3?f#Kh3= z6HGSvN!}d~`!2!CWqBA*XA3t~W{m&Tm|{ol25m1}vA zE-HVmI80A+!Jh~&`4hT^_5CgF zo-5gO^J-Wn+H2ok4je$wsqX0uB@y^#XZry5en5}Tc7cM8(G#zsEn}u zrGp$={ld*>MUb)_Fy@@7Rn;Uyx;_M_rg}u?Aj25$;3Uz>BJGeNa<*#-6Cx^E77om1 zMB`l2EMb&vv8gU0y3B3W<$M~~+~_jw{^u9fD!aH*!`a?^eo3Ex(PtxiRsH#OLb|@( zdyKRL5lIn^Hbk?tL!n8;he548T#<}x4GDZy%ujRiurw(&FZ@&-|HvK1fM)E_HG(M^ zg@Fgb=!r2F&hJ(l-++vm^-ufP7k$=oZ;X2X0sGhlzi#%1C#P%Ktq879ksjUM@e>Ek z*>GJXprCXm@ag%~N*L!PDXjj#uKkaH6+f&;mK#9r84x z3SBMB8gKusjXph%Hihte`rGECaC()FE(Q`HhKm-LqXGpO8OhRH%_eXgkOh4`_WmBy z&mH9*4<-!u@psBtXazrbe;l^Dk%|U&2jF6dFfVXxW1226XPhOWs z?k;sz4O(Us5@J#sIf|Ch?prTv`taL-DCzN_@cO;X6(%RYzIuGF*ic(3L_)FsprtCO z&SP{BtrkJ#drZ7i{#(_fPA%a7sS_CZog`B-pY|mes!7A7d=#tt6ORx+GUS#l0o#=a zlT!w%ui7po$&h{lfysx&j_pdey-`1to_!AA8BK z*Zo3+^u~BOocLsOEU9Il&ZQmibr8Vl-YIE!{Y(>c6tpaz0ZDrug?xviZLqw^UQpl*Br8=mb??eclXl;YZ$4|Uu70&1+v%j}Ki8Kk zKi`f=?;c(r$Zg35#3rAQoq^{rp1C3X<|-Z4tZiKTP|Q|!K!@eP?-W+E-nBS(f62(M zk=ZR3HUQK|z7_7mMS6a0Dqowv)e#-OziNyKZ|I(Mar19>dN`c)K?0rKTJzm^6J|Ui zur@e(z&O|EG&m#tDE?W&a%9S1&+J=;c$bzacWmkto`}?iTg@%vc6NqilWV15r%zZN z8zmO>tyg{t_%bP^nwFNDCFHGNt)rO(F{WGPeCxFIIs+Ucx@Qv2?^i#J9q{|5Z0@c3 zi3xbSw-gieR!r7j&VRL7P|Ouo%vV~QOIom0AhK{aQ}DZ7uU?1$X;(cV_b_WsScHdUB`g`_| zNZ#F9T2~!=uI#0=wys>KJ-1f@-UhDzor4wHRN2Ihl7G$Y+^GuEO-oC-<^ZS##I*Vt=Rl(|M{_EdBH>ub-%9QP-P5cB4^Z!ar5k6 z>;SLc5xw+%Bzgg~)Xtl%|Zr2{nO=ljSi>QAk5%NN1F^4WZ6YL+j>WZVyrAGvh__^b?w;A>s{Nl<#!B^9+YGv%qXd#Ma443H*5 z7WQT!AX5K~3afT0Ys6CnP?r##$aK!t!^rnqu+oI_HbX zl!k`Z`5vDBk2?rOrl441q(NvJH;H5zG*Ag}L?-AJ(oW@=t@u#{w5+YY__jWPcbEdh>ze^9*S9VO|j%1U0*m8?#!CS zk+6?dCY;`jMPvo-ijbRN2n1j%M>ne4)hIr^p!t_0k#qCl^8Ttti$nXJ`s?1GeDdYZ6(pTmgX!7$5DcNH;X{Roo!jfFTPvKn;7+3cn@IQD(h1rV=ZWrgdd3sYh(44w6n0 zzk~0wB&an&eyBh;FUXRYm?^&?%KRKItY|=sscAU6c{>gTMkp-4MErm~y|w0vNE_pt zyp#y;DT7462E+8p{o2n;kR4p(N*Eib^Wxw6n32oTe?wJ7%zfS@$dDKnBTGwwR>a$z z6i=Z(Z@2qdjTXkbCy8t24bS1y8Wbt03I^3t1^{=Q`=3Xo-6QeMUv`8$8n)_QQ7MuNWqg5uGIZq(f73SSx>C5JF`$mI|2s$G5$bxUrK3w;i2bn%WLo#0 zYVZEw{gX9wvu)*4QL6_SC7l>+?6lG^{1bfXl)IUN}Uq|?7*jU>UMWT%qGy! z<8tO+%hnc!q}Hm*R1MzY@N%mVh{_pWBx)dRFSnuVE@_5QPG6FryJ*62e^~Z) zvAVk2Mkv#JGxhErFI{MBTUAF*xVEgQOoS`&-C~1JIaDM2@z5BrRTW6_(*yMXBH)}fe%RX{iu|P-R%-NS&^y;dcsjonM5HJ zM#~)D3&M$di5n@ZtgOM*i{*5z)HN$7=24Eqk1?UUR0RFoP=RZu23^?IaF;ZAymdRWN~oH-#tfmA7pVRVAz2B2_oR>o`=B&eZ&F_qw=*usTJMnpzL zGBa-dHFr6giBC*?SF-`DW*P;uQGHKaX({!3`lJWC1a7pqOJR4LzE4!7{%RHS`UhX( z?*^bt6|D_hd0r#PTq^AA zGkRm1HgD>b)2h?&bUXW6U@Rd8O3{OWc<68LPfHWgvE|#SZ30q)JRV;&IOl711n-LJ zD)hNkSjrHG>e#g}aDSovmZB=K;E7RNyJFzcI1$Y;yNfKSjl(=z(#$BcC;P0#jZZnWtPZuf zCCeVv#unO@0D%sybu5hVt)>M1LmcBfAX`pH{~fk%iLsz4PpPmKv*xP@p0wMN=e}W$ zAmajP7N+|}e#UR3M12owTP#4C`_Pr#ajK8!t7Un$Z0^9q)xp}CInEzkGQw3vVc?`M z4i_oc0^lrN$TA4zLby&3@D13hq>xhd_q*5~#L&|Edi8r6AxCXJ{A2@`O2m7WS7B|P zC~9nU<6KwJ7eEtQ=T=4Oy7txjp4o()gnL0q?6;uOY&!7H$XNW!w1eiE8ywVU=<3Y;B!d^;SjFw+KL8}? zI(qWj6BBL1v|2VReZ61r1n6bweqJ0;X9vPS*9-69ea;qnIqW&wTYzM(g*xGWsH+XM zR=|(6X)IsxR8S+;*t>5&g5_dXi-2Hjw1=Q7oS{HKPJFN90iZjrFU2KemM+wV(YX1* zNtPm)j*Y$)ET)xI4>ZXD;=m}&?_7&D$ZVw-ZBkpv9V}CmzJZsIPURI)ye$Q(aIAtk zjj0N1O|X-FOnX*VwOx)d{#$PAzK1VY^ViX38q#WH$L>+FkB(b_3jlbR{wv?r#_)kt`c~=pO|7vARV9ViD{fDtGsn{WI@Eqed zD{|qZBKy!URE`^HwDdiNo1;K+oMxm9*;0+$SD`c&`qHXgR$C2WkTC8eG;rS^ zykkx8GpkBu-40A&Pla~xszI}*bN(j4WQd@k>?gd-FrAvKtG!08Y$AGvXgGNkp+%1( zikumBEYv)z4L5@aq-rILUHDtcIOl3ya@i`W4dIcaak>71Ty?eFryRy>=^mN!aJ7x0 zB|8@$c#?F(jx7frnQav3;a_u{z>cTslO6x(*R@k0E(mE1n()^TqlvL7SsM~?kUESq zTI+YCXF$D8jSbQ%kvNhe~ z6#3~If);)unhVA%gxo5E=URlANg?CK^pHy$L&=4KqmRau(b}`O)O2E-Z|C^hQxb4N z*5)?l`kwzf@mkFzeO4M_AXtp2#H`svaVgn!>%kAeX{GMcMp67O-*AxErm%1$iA5FE z^dgOOM(R$b9iayu!xRgFk^ZIG7wcN;?}l{UPcmpqP}6}|+EX*h3-(pE^sjxX-^znv zcKgHkxgrY{C%rm)b5Kn~TSJ4vHtYaw@`n&%=*ksqOnNw5w9384_uJ&G8giZL5-Ly> zb(xQ;avcvCJP@vn^y$(KHQVV*WK|)tG2F-DB0Bu1bX4mfc&cjJiE<(J;Y$diR+<)$ zmRZ-YNn|>Y^vvtyM0|>M7HjFVU4-8vt?PA6^v)8|WAp5NP!Qa8#u`k$9k6ZMr-_;v zB5Qd^A_B&HK|~PO`_{_`kpmU}0?%vFr|<_!xN&U}nrSXsIvS-P0bsh|C>#aq1Jq1z zU%)(^`hTj#>67Cp(jq|u02(}o6pQtJVK z21WIlQh8@%a)}M1%Z`oQ(^G;RVUg=MKJTnOTxRyJEGrVqNQ$1uRkk+cce1`WO;2!L zSgy2EZR}{K-~iZP+WCb~`zQG--Le|KjPQF7B}?(t=k~U=UM*caz@_fAvd7^n76(xX z9#7NFg)@$v-{vK|HzkV%ZYqcIrMYo?n0`#{i~(H0ZFcVi@T_@)H_SC{U;oode!lTJ z@wSyqP%M$SMzc+`2lLM5eu+2a8b*7u0%T4ns3h~&@Vf$2-ei>$Zh=K#J!%YI@fT}E zbGdg17#HaN&3+-M_215rN21OD_X`lf`?-ep41W;jDcN27RKU!&Fj7&|y+qS*? z=cJ87ITi|Ur_r3B+>k>rV}9*+d3(?*Wov7jsJOf>fId;!*ga?g;$b3fC8W(r2_gy&D8&xH`1^ubn6U1~crcE8XgF)wf`IN1eaN151FQcv~G-Vn8fk-#! z7DD?Am-9>jbP+VY{_mdIB;dLH3Ct*;wYPpq)UA|{K_a48wb?eUXxdOM>Z;aDbXb7> zX9x`kP;e|Q9_(T2c6ibAIv|+j^wFx`ACf!T)spE6j+=Ulz47Qsf+}5_2ePm1*acX; zQ2!EEVYzhw)Op3v;8~zG$qUr>z_&m4JdfXopL8a4B~x9n7LZtOWVQ)m7#2|ZEsPi8 ze$ZVFGDm>4#>o3PqG8X+1nw%c2*q1T8pQ_A8fv4`E}!8j%;R10ZH?DZspi!kJ8-WX zr19NPXK!-1@lCj8UGoQgzC1kK@)4HP9HBUKNiwRpL#nIy8XQg6AR~0g6fIhWNLrhp zWB=8~K(oZLPg}AF_;k}Ya%E3P%YRk3$r8@1vey#fL~1w&vc*E3>Q*&kb%Bl zj;3hTs;BMjr}x$l+vg`a@v`A7;MAjBRDbWJn%}%~ByL<|52+NMx*3Tx9zCwxsECrd zwfKV9P1+_l$eo?hhrF@?S4(5;>&y|&jH)w2c?-?*Gr&bD##uNpY9DMr*HtN-`yE^U z38zC9Efb#Uj!M92Kly`` zf5z6zOexqqGBem6to8`_Gp5y{xXwwazEtHR>hpPH=5 z8d^VkwOVTev)UHw^x{o6MD9%tk0`ZTrc}pcE5iA+)=!ZlW_kG{v0uyvLnL_9pwW^k z!_a}O(P5;Jt|o?<%_HP-7<7ylPe^8!Lom6R=f6&4e`0!28mAd$Qes$y>FQ|RP0MP= za}06#5_8UKF9q~E9gIE-)Ny^!zns3a=-zYbv8%DGN&hV?yLjKvHmVWxYXwvLtAgB% zT)fSz!s8sgGB!$~b~EG=+Aoh%WBn z;VVH$=7bKY>F$)S?8=IsV=nvqOq8>b9!q2DwFzS09gnmBJJ^WlWqNe#QNljpt(f&Y z>6z?oNLyj8u{WBS)ReXj2i2;%xtYc0{A+l+)0Wkz2ZKr|NS6)uE`1qVt|w!OTr)eO z=I?Izp9O2>@Oa%Qs7+Bs1sXKEOrpu(Sm~OTDU~29kmxpt7*Fxf2x@a1afDs0A^JaH zd=f4V5=zYsj2L*usZ?%6h16Ht{%a~{*8~ZZRg$cTGMbZcO~MFpI&j$8l4f%U1`G}e zl4I(U@xe|v-SGrMvY;~i6bU{NML#BGthVUJtfs}op%K8!nU2?#>2lC&H4`!P&#BNtR2IzS&cbxj0qIOJ|5na(V zGZT$Rb_|Mn=aSI?))!{djEa;}@eL3c<}X$0eJ3eArTePNiI(|utis(DtbH3sT;>Y2 z>Z4>P8s*9Dkc>D$4iVjT4+H}oz zvgPfBfvyv*R%_tx)z-*JcWgCbbd`|s<@;#170ej(bgoZy_hv9PUKXWH2qh};_GP2} zdDpOM&k5~8dWru;+4rqH(BMGV9{+3x52&YhqMZE>Zt}GBHcHtimgwrdgWarW)^WAj zX!OmWpts|9|5zKoaj%slTHA(u+^kf^HdU>cHexD4Ut0rP0YZuFWD}W#(_KL@Z{IlQ zWTQ5U{ZW<0m}Q!PB6W5c#>wNX=l}IF(mpoE{Pdg-DP0fd2=MLCcMTq^fchHV>=Y{X zwsh`s1TU(#n7*SUr4WZAa%$gY9ArQfNg20{27|&@=2)2}5sjQb>0TbOw;THSf(pG5$+on6c%WIyoFyt`yN)_UY$SDz`wAETy|t<#qpuL3x4 zfV$Gca6Y=aGY{uUNhy9Mqwc84I`+X4Jv*hES=AH|CbIu$D${Q+A?j~+a}m&gXH{7RcDb-!a2?K$Z?bVV!55DxK*XKkfm>bxf>7fY&Y z?-Sp19zA-mkU-MI8gc6sk+M+9(?OL3CAVVk`X6CRjgnE9KD`M@XdKxjQ;07^b!o(H z=rUZT>ua0?P;-ZiSb{t2TBjW5q6+EP_3L1^4A4YPc#K&F;wyH*GJg~xka(31(W@Gb zQ0NCpFrj=N>YRe==K13LQG6=E{3Qws^@T=J9bb$bLFUc4fInDW=g^VLI4Buyv>*(B z6x9}ef=P~2!CT?)`nq9nmX5B0fws2w%i@_CTl?6N3(6-9NLg|u;PTaqz)DOM^uY+^dDF+FuPDz zFGS=~6e1xK6idmI)YekWchDsO~Ma%C@K&(=zQY?J2%67R_6Jg}2O;_Q;t(_mBCbFOf zWL9mNnu|YnAMoqP;az5Ct|beEKRCTrSN1M<(G!C2R~Y1zMUkS#KjgeKNBCRVfs(Ab zS~Y8a9Nf>dzI_%+Y#9{8Lf|pQLHO|^_1a&D0)-L(aL>r()<~%2szm8XGFeSnz>J{5 zcm`@KYAO&<(tdBmB<+SRSZ}6&qmpN5d90%vE1?-#Htz^QALHGJO)VwltfMe%Mxbx6 zv;O^eU0=nYBl}~JXM%h_w4wsk5ET_Fe(B`Oyu$6iat-{3EI!V|7ub<$Y%gG_Eo3=!+a_0q05zh6Lou>f6ZYa>_&bFUnVb=!xVQ}`O z9@c4v-pHT+VJMWTq--AF@`0s#*Wo9oxMbKa`YBaK2AW3p4S-%z-Ca5e5agwx(EAk&e+Q7FC!CB@^+u)VMvApjpkC(Fz0uXfw;%Xb$mCl1fk`3 zFXX*&>6ytLuz5;M@J$60eAyLUvVdgs$i%fd{JEEmpXyuim{hZQY*}~kg{9;B?qPrF zENs8Pr^{TCjT-EP!)l}3x%UNH$xeixJ8aww*~@Ba#$p8I$~rDpLly0UnZa_Zv$Lbh z3%+yjK^oW^fAIk){41y|>6pZ_Q}7Qfz0h)LRN<+(JVAeF=ZR-#6p?r#;?asrk@Kp``1f(p!txvJ+ydt^+Kk zG{q7x+nN@lVqPRz6fdd+MksqmLO2n;=0IG{EgXxIYYPi>Sme`|$|iqD zHwRJ?PLn(J*_zk*kMBGk?OwF>mEgNA=;@gfZEuh4U^yvYo~JGqp-X&t9G zYLjqT?IP8fN=UR*$jCJ`fQ?M`Te=N+qhv zxqrtGSz^QW^n$G*P|vcl@UT!$2K$`M=Q2KaouLaIz(nmY7k@W+#^cknQ3gI~P}9!Q zvQuMTE)6yyu&3?)X0zlLm8FEOqiXS5_j}{`AVoSR7V`=w`*ED~`WcXTBJ-Sx)YN?( z5l^=EQZ&Zs`uX5;ORzF=c=%#kjNbZwl48h6X2yChESr(tW@?; zOR5(ClCnZaj949&IAf0daS98{LupxsowH5Y3l3g^0DC738JG8K-kK>`gz8&L_Kd^t zXxXd)shiPNsUjka8pBg%O2BFFL8zhgn^KJWkiHjn8WC^1k0K=ibiv<{oJA*6(yI zDr>rvT{z+9!JrcmctAHLN1>3@B|13nq#;dT7=uD`RPq$iX`*B4t7Koj37!H)YlS45 zJX+m#L({MeUB@_T&(9~3dv#+HWHV3iHO~>Ta#LJ)6lP~%iKjf5K|Eg_ojv{!3nRtp z2_#w;EE2x8ilAs5`edH?x0Yj)NS(ks-Bm(X`xB#JN$#_(QezLR+?ye zS8|927-_w_Nt$~4H$7aa6`!BXMav%hL@;wGtUyV#-)LAPl%elt7JogZDZPVq)G836 zZ4T)Qn&*PZOV&{M85J43RMt#~@Au1PNGC41ef7V|uP#Efq_27E4Eb$pJAwOQR9KSD za8P^>%UV6*=3cp$60!@{qWrokXSp!*tDJHiSpZfpnebxtMO;|i1i*{MmE=KF_CL?T**v!O4aLj^BNK17^F*q5I(|kMP^e zauoq@=nR)il(~jn>%7?U;@CL>EQ>SCw9{eD>6=D~e%|)Spd=Whu8NIZ6w$p0uAUd;f)oKaV)gnp8Jj8Ah>xO&KaSwmDAcTm7DO^4cS~Mj6 z3wgj}Ug_~GozCr9|19=$i~^{~@V8CY=VDD-ByL5D_k{fH&au^FrG}dy(8J>^Iu+&s z;(Wzu*nLn}7+?JIF}#Bwa=$5f6eYa}0o3$V=2Ca^RHmcHfSVhd`2lkS2onhS$UhHN zQ*)R;wC0UN+(Fst|9&8u*Nn>A5Lo)Uw8{q)gOy~1SGRx1J$RsD68FDp*$u~+^aV2v z$TBfNrnxlFfGRIev9!kFV?*Cm$!c{z$TA8EoOe97n$5cwtWi}^-0me%tk~VA9_}3j zT(OKo<2$>(Q9Dap%+`Q57dh7khK4Ej?imX3Y{3gt7F3JUDJ z{9O}PO@|o5Gv*nV^w7vkX)f7%mh;F8luPGBZ6;rR2tsl|@U*TTxfT+P;p8L4BDHCW z%b7JA5kB|c2WeA4wEd(TFJSR@sQKX;k`-E?G@q^g-rbmNsd`)yF(Z6YP%Zu3TbHO# zBhgkn$5IWmk9}_zY59fcnBaQ=hnHk4uc_#gL~Jl^S$4rv2oYWHYXV zV@s&81v}OG4fm?OJ`xwV7<_eam6#vLsmG8O>Q-cRw|0Lr>$u(H8z|q`yC-sX5+6U{ zastr@u-FCjK8W)TSoXcX{uWX84V>0qAaQ#D^LfL=xpd;O*3wGfCv)nRk+29>r#p09 zYx;l`Mrt^Y9RmZVg8}>CZayHXv6z@nBRpG&Z(Im8(bZygWBz6+=r~{=;w@zuR5z@# z+PfZi9kiOup*ggfXE2~AwTi2hj8H)*TS>4qgDtA6`qx0(r!jJC*;m>!v1=?9jg07} z-6HJLxMFD)O8=NRzK7&*gq()xGy2!&Co7-%1y|RLr`Kz`voBy{Bo*J@bGducc@5p# zYkOZg$Lqi2>31avmuZbtY%Xw6!I(C@1|vchfqLghO+2BkBLSh^#>ZKmI0ich2RAD> zJ2x@>pn=vK%s$E>DI7XXz@nF)01V3^TT z!5Qq^$0ZJW?L~*s+#Dca?<^OGc~qx-F*7PoOl+J-r@|a=S%ObzH)Vc43Mc3&DooTL z(3&(y4vd>5=mgvESWEf6X35nhc`XZ$nw8jjF#*g8v)f~BQufMgH+GuPb=!8yg zZ6~+dcjjO5Hgvy__U;O-a}IQ^MtL62Z^qUWD=H0Z8WN^h#v|jMvV<#J6S29AY;7joznU zNxtRV-!cAow!eRDnjE;_)D|nm3zXBe-|ld+2neY6y~~tbnx8MMf`vTf+!%y}VM)7_ zA+^Y=bgWaNk}^?Ftg7hNPT2gBJm*V{sOnc{(KSSO)Li@}Vowt|}Un zhYIGW7ltPNN)MeH3-bQ60&{$eis8<7gOwHi60&7w`TbH7&ZhPhdv#(1;?b~0QU9x< zW%ADfcStiU0a3Q_hXF!!w^TyShq>$3mxg2XdZg5V5s#1C^OX=GPjhimclX&)Jn8hG z_cwS8E&_NY?2eYqC9!ti(81l_nX*ND5~K5L7{jeOW&X%nC9J5RSM`A$+dO&dmUMda zCc9|7!5Zo!WyxcaD;A}5#;-1u;qT{W9r5^Y0nl>oqzyuzFHVI&0MgzIQ(q;+ zApED6Q(7bhoiYDWaOL3nifxh0ZuK|?!ey|NF(r6T1NF|!(5iN_KiHq>D+2tG3j6fQ zu`7Oj5|}S7&}@_8I^F|V9AV|!D>U#1s{q)C39O4n&LZmaD!d>6xOlZ}o?g|szgU}0 zXI88DeB3eVtSS<%JG%_mG1Znof=5RQN{xg&sMbmZ=TGoU&hGxMP4g{LA%G_F+#Q%# z$mZp`2g0`E)-MBb2I2>b2_)90SyLLddmjsT2ePy z@yVb!MEpS%jTy4Tte>fqiie)k4BLp`N7sY1d_t9gRs|1Jpe9w0R)l>-ULlh;h!B^m zkjd4pOp%6d1RIMPF>j3KP%+n;B4v7Ec0R#bT=pNiRgnlmT`G*BcjC|f8z`(;hD)y@ zYUv`tZWm2I6!f#zjOywlLUn+RCqwS?Wt8hjTkICR(P=KLqQJMDCLTc?Iwt8>6KzAy zc}oPN%5Vwgc~j&M6yMX~62Z%lD^5zgMPl?HpLm~j*H}FniTx*@GuJuyDdY>XvSp&< zWTJbET>2X-)gMAt)TnNOEi(me_k6c+N3IYdvRH zJe^o^Y>d5qU2_XoJi{1B?gjIX3~hjqpDTh2zA}V#|BI8E1)4HM4|b@rFc=$2Y*r{D z16zebzJ` zL+jN~5o}B>kFoL>(4KwQ$*!)RGb1D4Kk%X@ey_g!=2=EL5o~8h&h+#Q_e>w3o<2C> z`Hfy_^b2+Uy7Fofr{jZ925;}%cYAPfvgw?9@Fx!*Jn&2m_Q}{SNhz}|e+|cv`l}T> z1MaWG4MV~mDT^ZH#O*ez-)rF8>oBiV(cdrb1P|4&!_B>zzrR{xmg(yZ%5n>ipT_j! z8a=00uax0RnL=OQqHoi6okKDv;dxT>AGVVxw;d`0e+V&vgIZcbPrh7x*N82&6HnA&_AJZ}Vs7hlh`^pKB~L>MCqwA+borDeLC-HksSK z-gX_Y`}D0J+#cN5bFjx*i;9f7jVk7pYz32w0W*%?2{8pI7iuhR z+nZcg{ZCcfL`@)g|D%gQ z47m}6n_>`bVzHQZfFl`87ZGZKL;^5LFRWxeXC_vurMn;Ac@hPD9CUOA=@vT&7iM7& zFxcg1XRYze`Fz2e&HCJVlRN8s=#FRO@$p`()oeBsCISX(l$c%hG+g`DwJ*Q?bMkP^ zlgW6rQzw@qYfEd9h6`ZS5n?D7bLqWH@WZh74ocE|{txeGyU$-`Nn3u3+w%O#{K5P} zUvHnkqSx!Js1c${kwbe9z5O<)?3GtKIK0zpQ@gFbsl1G-ZIR2BN~J=C(lt~l+@Mg& zfe#Gj^uiKOA;mB`ikx6FDaPmFT%8IhcuI4VQfE_%T?WNy6YjOEdQ&`E%CGb~F&&|5 z0gu#d)YlF1lzOESQ*nh`%YPA{CkC7ZGFa$Wm7D<)t7ludiMH{^94RA!wc5=I)MEZS zK<#V^wOA}xEG7cUa50iz^pVAkV=n@(IW_}uZly2%vxnp|-}ZT#W7H6AZyFRRtP zy}c$^yBV=YmzbMhM&%M*15RU=cKi3)^Iz|7@xnN~l5UKuzHoDNPi zue?pp_^LJ4H7Mq>Ihfjm(rxL$S$HW>FEmE_q+Co`jmdd(+)$ykSa8`fxzr}Xy>)oq zkX#ayAG$`e001BWNkl?yW}o9k`r(bTgMt^hTX)h+ipl+AN(zeh~;(rMMCu zFja|ix=R*RBtUq*QS};woPg~`#P7cO2lPq3MsQv4Hptw{lQi+5kOl5L8 zq-RM_+D*lhzMPMy=tKe@QGq}jPz<0ACO|FWh9!Msj`o0sBOQ;Ucb*^}%Tj?Tn8?+_ z^|^RBg~j) zM%VO_O#WP(Ld@X;R~6MlF6vpv5i;?r#zugrtxc{v%B|_(5R*2Wrjc7KmZQX;tyt<7 zVsgb6Y^7&%_BXf)M3z6)Bn^{GajZgtmviwQd|Y*!iyf07KLTYEDHT%H7HY!&&}egI zXX=)&)8z+Ys}e{MP9S8ulm#XN9#skq2C+;gkRixKrS33*+QIJ%wewdWfvQC*iYkV4 z$;V(P9Vc@jWa%`hTG0_m_~;@Hkdah47~DjSTxC&n&lTv5Co`2HbJ06@z%6iR>BMZo zmtCKW=dIcG!ozlJ+*^1UA2*xFHENAU7dCax@w69^=7m0)m+ai>m@XEM$32%&WI5H`VX9F>xn!9k9N zv&7;V2S0FP#m3-xlrbSjU2BY{!pcK9_M$2_-gMofvY^#gw%BNwO3e=oyHb-sVE=&r zy64XLmC)T)*zECSJQMpT>oebT?mg$8yXfUmPDwxw+$gBpD3{I7PmOYHWN~VN<01=F zi*c5V`&03mM2ho2fBNH($*)r*Gv0V=WpHS4ngqhsYErFMk)%qca=QRBq-tPBS(jA3 zoS}8NGtF3u4oMvm7y`On7MCL@X@k71jfAh-E;WWi5nsgjD7M7L&JGNWeZ!Y|@UR`s z*AxlGc0%g?T~ND#P-}t%{zB*o!5v(m9%yN?g-0ClxL7h1R9SUN*?(<*eG@{>84gaU z`y~OLu+se(P+M=+Xe%hGbiWV+=4)>AZWR%SDk5{F@rh4qMf-`*Pj=Ps=TTG0gM^E* z1e_V2Dr2%_WMYwlF`F3^<~CV921V3C!Lv+>sbJJ>rFEFcii7ubGG?lLa_dpsw{M&9 ztLNGr2#tZZ<==S){rJk>hHu8cd-LMOw}2Yw{dQgm!xkU0SwEl#Y6aSsjj;1~yGR%Ti@oc7QeV~2#&xzici(i4q3Ev}%)W9_k^h|OVLo9zy@ggRpnvcAzJ_I_;a ztFP{$d?>#*rlfxD1GH}W{FRUXH&ttH>f}|8_o5*fl7otN+Fq@OGwCpGwFfD_C`X}K z-xq;LtwU#4g7TR<5NbR|MbvV@@%OdTO5|3nh41iZ{$su=3||<@lLxv7_ea}{nkU61 z^)L)Q)>Q-F`K0y}IZYYULEM=k+!=!RD7UB|w-xBYmB#;63)$O2<3ZQ&x1 z8Zy0E3y+(QFdLPm4wp~{ZQ9-&v{nKc?a57 zTT|P%rvx=wM_qrbj1H<1Xw_xF59)6$k>s}$DzSCqRzxv}UJgQO{%h5ITv%VfUq+Q} z@9L72V|6%QA*~gYVwuBOsg2@VhHz!{dV@Jbsu;7@Z8QQ`w3}jF7)C@rGO;yiG^QOm zVb;S)f|6WL+}vu^&?-)#4D|!LP_%1@PMtb*W_dZ|c^svCfBN%*tBtn5zWMnDAa-#%R^caLsi~0M{5)6VVCeJe|=X?P1bPm_f%JGdG8d*Jf?LrWiu4 z(>M0FJG`!qk00dM8lcrQIo{5nJ9lo^#dpe3@u)TPuN-Yi)CAOG$^O2bb=b}_)IK5C zD6*}+O~?)9Q40nqocb2>I%HB&R{YJ!yXS4 z)Kp5*92q4RQ5rd+ljBCSfsk3WE+^rp#0nRU(=I?wuF!jod-f0-T*ElzdqiRsM zlY?7~+P;0C{RPna>>7yJl?~lA4&9h@sz+Qybnk%!hi$g|Z+`w^o?FUt_aO{JGqraY zK(@Sh7qUwc76ScjBpc6;W@8aQg3OzU`ICvK-vea;l@biW#Uu6$lxYjXrUjCUtm$xf zuOnbK8_dpSWgwukI)h9)oo3J}lSvDgbLqLcx!H*CYPYW`a{Kmuwkh^-Z0zc#XQ)(? zFGA;G%O8lf3n)dkY1V#|M-7yXS2d(*p{9YeXsEC@2|@qy2aj4=ZZ8V?M%4Jt8Ksq*MolWM=pe|)8H;Y%WD1zDdZ`?f18lW>+oT6z$UbpqA0c$%BT{(B^)TtfU z)}i+6E9VdG{VA**8nQTo%ZK+KvEBdsKmIV!E@hY4RKm|jBK`&NkTGw>4|*1dV`a_n zpG|o=IQv(!G2g3}Dk$}>q>H1KkZSM^|#iS)z=(7Cd|L0j6fSd<i`bT!3jOuE&z}! z-zlh?oZlf$FbPgoY`~~ArYjM=%D0{Fc1otCt@rAx>nL0!sYR2vl_F^_?^!9<(MFM6 ztc!xkVPdgDfu?YarVyKDI6UeOErC@``rqGD)T*j>_oi>Whq?p3)z=J!ZTAs7KSyfG z96oa76+6E;{{*5imR-pDvoY|HK-5~&myN^da@6C5jEGl?1B?5oDcZhNEMZoe_8 zSCgs|)X36nm11Gvn_c9RFb3uBu;c-hnnZ18hRP*382O zs12Nr4TOAglTu9%IhP$ftNZr1*0&!$d4gXC{CTdDt){xKj1D^0rdC3)+0O@R6?q4` z9yQc$w+<^Wva|`*Iw;&k7--r<(-X29M4FVZB@(im2F5Lxi#4=a6E&i#T9m6Q*$o_S zFohUoPma}1dcWLC)OLNCw$6G%<8*j}4htO)PdMqKuFYMwjZA)#aKrbG)qxCi5GIhh(hXVKXItjlA3fl2g!jB8&a!IMGVK|ul->TYwuyRU91~W>X z(P&f$DnK~_HPOFVJO9`;&NGge)Hc+0XlB|ul(;13LUPtBc_K@)4X5D>maJsPbTDBe z@IbR7e&hndLgnHXax--1CMz+HQHXKV6An&R$8&<>Sk2-&!6|6V%sdC&Yf9|hJ zskA@$yzhbSP3`1Fe$E1Hz?RM*eZSB1yxjAyqvp!10Vxw>Qs-%s=EHOx?<9jiI#erZ zQb-!XMjOF%oAmu7-CKv+5BHa%LEr3!JK!+gKkNQwH@XGl@a>-NJ?N^t_fL*HCPPl0 zV|CTxxY_gRT!+th?$euNlXvF^2PY>d9^ZI$a<|`q@>DYUWVB-`X?%OPvBFt}H36pz zUg*xYhMOS_{tUGw6DyUB^>szwfGpIz#u}6eHWQq8xtyR}PUN0rW2g>bqTW!TgQlZ& z(8u7a0Hd}v=DR;IH4^EIqz^?dUAuPd7_!kb@1yIT@uV5_u_B1}_V<4D0;uh~g#7bh zg)|{u166D9>N=EJ>Tr0YzFZ+JJJBh!^Bn=ZwP*hNe9!!GyWQ>5g&;fAD5c=8TDBuz zZeNIHWmQw40lPxT;PF~xfnE3ZY7| zsoq$2V(sEtCZ8-6i!1f@E5;HZU|xN-7&X9iVef`?&7d|BgiUR8nd4rdDi5GRBsq@u zhMdt{&`UGeK?Pxp-u!%KG&2>+o{qGgKRvd(6uH#WcJR)fmMgnw_mAl$uUUrz@v34fJ3C0^<5DJ)sQ;xYwZ! z$OXJQmo%=X1k~OFRg-~R$`nemq=H(bY}1gHm8`0YP?7>_)uc>G$vq6ia-386JsVMr z=i~6e9J9L64l+&x{Iqt5omJUPys1hRq#7`2Cw4Se_4H@A2(?#UdFf~|=twNwyZCJJ z%Lflqsnpt}s`3EZJ-}M3x%suUfST4y>1ccPk@?4uEmlX;d1QWYbal+r<1rR@7mFv0 z{_hNqQJ7-=3LlImSteHSudEa}V_ls;gkHCSHLPo9w;5_G z$`rt@4WT;V1G!u@7YKPfI+%6TMh9>8_hqKCy>02?;f$yMi{9bshY!DocnEO;#bwYT zK<(&DH8nLasA`C`M}oAq;MIbzLy__0hb_`hi)NeDa@b-GdhB;+X8r|n|Nh{B+)Q(* z;`Eqxx;SB$Z$rbE0X0H_wqk5VJ0UbwP=l!CLN#mxD#5N*Dm=E z)a)2Flbx~3W3<_8f^Suf*{0x3VmVJ7z+)qKAk+pksVzh8*ToKJV&Tuvo-Ka$$9oU1 zrm(10j&5Pb%bs7o(R}8Kz#7_nMgwL1Var*2(pYd2a++m>3AYZ2`X10w6j|J=#i#{1 zCJ#ng$}?=NU@V1##k!SfbpNh;v^$Bh5MybtA&fOIyjF&W;V|2P&M-w$RytORWQ-4a zg9#_caNa<2Ovu;ZR%;m?&-P|}BiZxW^uWaRKcuIp5ouq~PES7s>eAV4B$CZ$lX*z4 zN=KjTw7vOXswVV20JW}5ZEeGuC7o04HrW$O>EXkcnS|SMZt{1x|91Pc+jsBInc^&~ z0o3#|sYMiGX|q(w?{`XYwx*E5BS~4;lnNQzz^+lTDd2X>k%~rm>IXrZAUUdv;)q&2W)0p|)pP&+)}gj< zg>yK2yDnZ_y!P8Gi~qigdI6~oBagdNn6@{Y&qSR7n@(%e%h3=xg3u4@IM%0?4-#6Z zPCKV9Rah(fPyVl{L5;u)g(dLDuk5NfmW=Q-BdA)5VU0y&3>TJsAQbWjaPAd`*V>S- zt+#T+wg4RqQgX~%9`|ekHV&;B(9tNzAqN$@Yq2Cfcz<-YFVdS?h@{i~6SqDdnx4fm zG@VW_4E05Z`g(m(RimB1f?TQQ1yEb_Pjo=8*4~wF8;*=SIs)FPGwA|V>%2KNnO+$A z=vx%M4u{>t(jw6|0vV`DVGC1&s!1AN-@CIxERmL{gW^!BNF_;!>MAls!(!@vXvIXRCqPRkte-c3CnO3oH-W7RQxJB_1uOa~$9nHaNo^7Zz+b z7-}sqhC;;Zd4eJc!o?S`s3EwLNd`66%E=p(^Xc4ft+{^yP|Nm3`qJ4nzkWMNnI7cOcZ-y54Jn3UrlW*<>_VvI1&nJyX6+ zb{doRkD;N}8)nua5{XW@-H@xv<8m2Vm1;odCz0-b=bgP0yfP)wLXt`-6cj3QQ>yls zplSpuu%^(<)w!HU7t(n@1^J z)id*p?kz+ulXTpj>RmYW;nU@BzIpmC;;b7dZTPD@wKkdKiNldl18N#QK@GrvTrbx} zxv`R4?}_a0m-@cF75)s9Lj)aP`mRmPS@bBE9KP zM$XPpeDulh(E`HA)MR2Zk#Hv5Zl?o(AOvmv1$Bjg`}3o=A<7F=UG149WR9FO%E&t{ zmWe4xUnVmIs`jUE|9&Bz)@jFrVyUKDBeF=P!Cb4U$zFd z?c0B{Z{^9@($tN~$?@iYE-o)GL%Np2BSVG2<3oj>=ZBBRqoWC}OAo3>5CaqeE~<_) zep+ca?%IE6S7JDt3;c(*^N(rr&g1x= z=h~I{quWskJgZ(a`^YFePX!enrMstVcTA03NzNd5S?-_Hg%C;ahC_$b(gQ z`TqR;e!hH1N1!D&V@fTr4J@Zjp_V0+A4jP?Dp6Gntnt;pYO@~cn!b_q4u`xxXPDEv zEsh2oZID(}kOZr!u)@!gYA`geuMZ|i+M1K?k?Do8?$$GBE`RZ5bEiA(4Fv(wjEESCLC8J?6pU8 zB{L_7?!yMTqI2r#$K@N8SKD8{>s~azf@U)nUj6R=g}+_;5zJ=cl`9Z;zE_B6zTmmE zH?Cj*BtC?CejIv0tp^qj9-A$ezZ|nQwybR{jXm-JY#vjkDZMJiUm}9=$#4k|uo;jyktl@c6oLIu3BteiDC>=thq;5Jck-Of-h}PUryEFZV@$!k}@-1uf@qZYdKpkYG@}x4r;>2(99@tVF@!) z!HXoxit+CHcQy*Ot>vZnqHTjCiHWBA#qTbF3H|!P?+eA5RSzF7E-vC^XI))g<*{R* z#KKx_qZy$_18N49iY^%qTMRaCru6OQC6C9GMyxUivfpIbGo23$%z$Mydh=6$aK6@3 z%N-rd!~WjkK!7hnktS$fH9Q-6p2tv>NV(71m2te)gyBnrzTfu-v+hT1^iIb;qd~@OZ@BjPHTc~EUh{vFzsZ`f* zpouG}52x((u5~8t7F3PKvs5X)&1UN{hijKgH!r7vHBVO5Fm(9b==7z>6blXe5HH4( zYEZNDz5b3Cug?cgnbC-HAxOtWQ;BdxFHzK*W(|MFZs{@uX;krExl$pO7svoI19ITZ zjg5A#LnBovB&530**hAVSYJuD4vw_VxyI+3Bh9UsN3M0c*b@aubPk9-u)l`3!(b~4 z_B^!($^47UD{0jFb49Ix&*43PJRFZF+)jv|yi013wV>AFW)f5LcWzEiC6dXB=`n)X zDJ$-B@{C(;<~Zu7QIq8<HfD|CP%1y)giI(r zglGH^X{!`3Os3fRRIN~!3UDG!#+-JdoB$wOCP1)p>Au{6RspI8?|cxc8X?~)aW`0a zbC=D+8v{OXi3+6%G-{j0I668s)SgTZMxxI7+t*qnt*`(!!m9hI>U9S&24MsQ2)q+- z@bB?O@3$lh)?f9OQL!nWw#bl7Pa@W8~t!rVmYISvCZ0y@R zx91weJ#vDioqVm+tfJ8^KZTk^rB*ASMy&|N3K9q~g{lC28zAnKWqXcGpOb41jG&FqOt*OL~!D*@(n}n7x@4hz&4aPi%@&=pC^|de!BSJ zY`QxAW@hp&LaprRBd1nG4YLNE^-wgWb%s3o`S%`)m{oexCe)MGGw~&O`~lQ>ixyCn zDOF|r*0LXBl>pzt`#{)G(X>nNu;}%anyT4bK*;31Rw}nBhg`IeD+{|xZ7PaHgg`fwH*X=p} ze*e9dP)AGC%#uMaXDimjw-;9N`lzaEbzyEYWFh2MmL%n@YS_ydGN_^dG*Ssk$iNi< zF940Lg@2?*DHSti_!jg;k`f82Fwio%mTKV3%o547VhF0HHlA8z(4oi`N(hq39cY4h zkyr}N+2D>&uR^=7ba*hFPPed--VRuU4!J#O?QFigf8$i`?Nc!{*rct!?W=Q_kgEOp z>bd`2c@MXB72--kJ)V3Etd)Vr?TRsdoqaSmpqMn8HrpB*u4&Y>trVNktg4xiIrZdP zQ3wt~d||9#ef-O?3NN>jSq(r zZ2_OJWy=RIM(s5;^F9Z*Jvi5K;4nh1b$pCvfdKIM<*aLT^3Ltx0<2XaZfv@5BIMXv zEVqXtXofh{mqm?~YBUCgQln6)z$=iE7#JDwhlVBRpjIqXg1?|vN#J)7TgqU1001BW zNkl&GjF__Wt_A0Z|U)!jcU zJ6#%`?d$950VfpoS-AbZqr-l$KYVhiWqI?jv#fbMSszUZ6~xPwlPS@b(_LwQsKt=X+Rl((Z`x2_7EJ)u_v_iD9Dst|T^?4xLd z+Y$<`L?#B~gA;R80%{{uEbdlsaA5WsxIJACu*dGFgr3)HtjuJej zc~eogYfV6HAE2hgq=EAGOe8KQ5{Zj=BwY90)a?B1U;na!sJ&ADaVbKrKN|ntn-3QM zb?aQ+gHJ)#J`~U3#7)xmLaQ_$k9YL{tetyMQ~4Fgz1gI3Vdb&G4cEIE;od~zqrAdv zxP~Uiwm1zt4MbPMuyUGalQOj6nw$2v+ za13kr&;I2f%lo=juQnP8TBr@zABDK?c&iO8Ce zf99v@cf;FJ@M7$=@!(laAIhSwR33naF4&K`}v^}*X7#21W zxZLV6aA@Gf;cJR)k6hSRq>1Pn0%o(dp;RTo`++^Zu*6~^q)Konj@Hte#(dJ6mXQ#p zLsd(Y64KCNaJ5dSFRTEEqiyqYst%6z1OiV31Ec2xfl6T^3N+_{WjFTCq`0Og!!8gu zr`y2WJn(ez2U!_MP4LqXGBYzjT(Qc+Cx}|ka#6#whB^JMqj=zu_e~p>1krJPw70+e za{K&$=jV@}?LG;rW`)4Yvo_AEVEvVh9V={C0BSOv6<2{uK_(z0X*r-KB}}Rqf{6)9 z+B;Aa7qFaDY>5<2cSpS{V|JCyn{EcjnWNqJRI} z_jHICRjoW{LDfXmz`>m=A3Wrr^LG_L4l)wL((xQr?bc;s4fNl)`j6f{G~@tc_`1$w zH>olaW~$q! zJ3O5kB4q}a!%bOODM-_|v20H(jtduXw@d$%{wGg*M@G8;_QRjQcZ3 zGFsQPCM|KTT&qkgD9|Tq8P3Wi$>j+NDG6dem7$gcKaADN1*`q%RFxL2m+}HG<~#|J zhc%(hM2y@)NlhxPN)`hdD=Ey}7>$#@;I`D%=x3W(Y!AQglho3jcgb2&c}`LJ`N27V zbF;rXNP<_J92^JKuFnt8&kuk1#f1^pKaHv;Q4lc_&Rfq@h?<~kavJ`8Qm&=J^`k+9 z*odcFK<>g>!SX?Xy~8zj>$^~^E2%ZbRAiY*%3^odc#U$UGR|tu152jYTNrww+}g&d zG;T7`dS0wQQeKXAZ;C?WR73iyRYFa8H?ubbYX=91z^wHT9$P6)&`yI3dht*z~1J=RLUZ(Hqv%hXX>{r*u>r4a!GSusMK zgpV0SNAVC_eyH7Qe7+hd7Blqvd@X5gvpHGB(rHE8taaYe&{lYC$1dKOloBVz&opsH zC_@i-)G{N4Lzl@pR|ZGeU>Df4 zEQr^nQD$haQz2@CJjqbiXo@CL*BC?%e3&ehimrf~oL1n3oRnN1KxHx&O_`msAHqz3>vzGOP=G7;b}u!C;RDd=U+He`9D#BzzMu zoXRIyBt)=<~z_WFFmV0}q* zHJ>NU8)alzD)M3k)bAipXtJ%^*SXx>vw=MSD4*|9D@zM77;okn%$^%A*$g@+1`nnpHGBLC{f|{HL!XW>o zaaNGQv=cuADur|<)Zj5Wg;@dk(xs@al`2S%Z{mvUi~U^&!p@HwNQF|V*ufPKjE{{U zzcJ^Q>B6X~6B9BHoGdTO%`MF>y%Zh|_|@l5WXgPUsWVswJj&wsnl4j_h^Hz2lnB=JsG!@>n*t<6d!YgCc| z78XV+%ufLmCm@PJw@{Z+m`M5_SD&u;)m0Wdc$y-(fcaWsPLD+GAswHr!cnrsQZ)=dZ+p&qYM5dC- zEDo=mmn^6nElzT%7_EskB5Js(YXpf~!kLO@Xi};`1|?ECxB!J*u>`fX$|Q@-pNStgfm-H2(a9O+!6k2)i%LUfp?Y>ZfZD-n@D9{Y#wi*ty8E3ElF9UYnaL@t{GK zzXmHKcw8<+vzwy`!eui#oGd)V_XKAmBX}Oi%;Cd({>R$+#x#+qar|bkvjr~KK-$et zGht`7Q@EPbQoAel=;BS8BT{>AONtJ~vbKAybVNAySg{bP#qBM{a7tOSOW@XJ<-k9H zi*m3Wv4}@J!gVIbxf|>|AS|=w^r%|Ib>nM1)bSy!b45`p_e@(Ra9ohcN zcV2%Q3i_55UfKhJxk^?1&t8KUB*9L=5WNh?XZ-85;9=lO#U>S#1> zRY)W89ETo9vnI{~{|1Lvt>jM!Nvd8Xjo?gb24qi$(rf4Kd_tbqJ=g_=6*e@0qP1S0$0M-UM#sj+c*#xc5HT#`ajc`r zSdqoDM$h28&|hMePlbFwyAQ*RSum&ckf6fGE^VAAF-mURmkfd7rH8do@uOvo2CgS5ZQk`L{J>#T1Ab7o=D3Y zSiONTH~=*jsv7G6a9->@afm^HvLR|}Jw=)fS_7wAKfu)sg5MXCA|3V71W(oYr4Xyh z$WX=Narm#V-e1kjZ9ztEp6{b~IW3^pRasV6UXJ#ct68+|^S0T>#?n(e4`*(ss$~Ld znLp`=9=EIK>*?2*5Ve1O`taGqwrwTox+sr0n(&GrbZNf}=vQ_x_Vo>};7xFeYS6IL ziBRxkKIWio7FV#w-OP5@j6eAGks~__OIv%pdhiaWvtNzKgXo#@@tGMf=PGtOUm{>B z(wu9;CbBjWDzlK+@AF|VAp&bm7Idk|TF&lVd<-Lnnu_F3Mu+0|kUcLH4Dx{pk2WE8 zNor?U#{Sz5J*~5uaoFK9Y5+A7QjkukQ8O4?trk>nU?4eoYFqv*P}_;9O>H=Z3+-oR zS!wG^q%Kk)hz5uX#lKHOyJcr9{7UE6z$Z+@P+EfYpM)g4ikj9W2tbfPQF_L~Q6#0( z3c$X4{fqGClF2b;n{I&MSkW!yCP2aO|;| zX)DL_?JlUG9-nKO?`b)UF#?Qz@x|{y`RublkB{HGcW{7h zW)AhP`B+#(`Mo}mKa_{E=8K6O&PB`?Y$I^emW##{TQf3nDHt4z4h8IXp68DaMDzH( zxbjS4$O9c-;J#Ev%cvE(XhLVU5hOwD%uupny28D+k%&gb!R-f9PPs3&%SF@*cD*oG zOQBX;+CMW~Tw&FckQ$Yn3HGE9O6-0F9eO4sH5tif&|CtlwJepoigm<~hX0sAOWnR|yI1U#cpgZ@2fd_Zr^h3CgH{4i za~4@>k~X{G4Zu9AN%eV9zB$E^lvr5ESDbQRdVT0#8MUdGsM@Zw)|QbPmyR~lW*d-| zlaoW|&~K-L*3p=)HNwe(`hk#}VoCEVYS1evsS=Ac4dhP~rw5HAG#gRVkZPQQpj8$i zNfONZu^JTwJ@iO^Z$~&9{a7NZpv1!s7#or%=jQ(Nk58^u`_auim+_vik3?1;H1ro# zHdHpCD$6&9RZc0SO_jH`p83UQqLwemq1uH5tuks|-<-d=H2WNy@MmeF2WOv1s(6+KkCSP8|2JorGjo(aZ$6>($fRQ*@%4kDtwqG zCzBv*b8?X^IMY(*Tvab8=VP3y1e%=)uU2hW`}*8QEl$yVSg}D8#T2U6$tzL#Y|5-b zKwc4~NTeDhY%(a>Lw=DXYP`Jcd%0x&f z?VjhVhCtz&;?y8b1w|N184M}_k64Ql$ruDdD{m0U^iOX*M5JZJ@OwiQf?nV}Rzg0Z z1fnL`lhtG6lh^B{kSEvc4F(ygH^`cq{?ZEtij>LeGo3(hSKd}o+q8onY1C?K^A{!{ ze|DWe|LD=BWk3x``}d{g&)e=cm8373E!nolG-}JX6NM|)=PHVAQY^+Xr*DZ)lbFW` z>>}Y|osVlmL-UJ^JuRb?lau2!BV&*{=g_9;>M-b9^W#)aW@IfzGH6gg)&Db)#>>oy zG%3M*d}nm9*+MfxpATmq%IH@#Ft}<#&m8#5gsme7ty?l~x3_n8CIPh3kUvymtr0?) zK}Yye`^@-UeaEe1!FG#`no&iY&G5cM?PjzYmAcA?Yc4MQUG1w-`@@HCJx`zz-O8w= zprG+$cWdwBepaVk?4wH=dZ(@x(`eo#XdBwfbN*mZ)H|YU6DYi>C>6t`!GWF_zKy%8 z7a@Y5B2`e#(W^VqjX?rxYKPv%c_qIdS_k<7hBrPS{qbbo*yz~xI?=AzM#ACa*|~43 z-R{Z$3*7}u(ky$iR)Yk3xha3Mwo*SjjF=sM?eJ@R_wIdv;RvvH{+qu)`tstF+j0W^ z_J_vV<<}L9q61srKk(e6NY=HV6%N+iu{oeA%-xz*9~ONBzMz4&6q`-OMb??f3ZT|E z26)~3A8Y3ylUA0+@xtE(| zTYpw6x;Cg`jk>zJXfiF-$|zc$hIUHCA2m!fHCatYlQGqFy8rFpn@skvz4tyqXWLHy z@jitIiT=Zf?>Xn5bI+Nd1*ok!p`+FXJk!=dVHh=|-4r#Xib+cZwLD9K-d^h+ixeZ%)FlT{BUC6kCgvcyA|YxRm-|-XBb&n&s3_qF zP{TD^U2_XOAge88F=ZhoPJd`~ZFqRC!$DKWP2H4`O4QPFdd7y1=I540(otnaWs4vl zEm|yEy6KKRb9ksh%)phDbpCwh_sRW0)SkY4`L7>Ve|`;X*A{>%dvFXf?vP_;lRfE5>;O0;h1kfs&F2*QCeeGWtSYUcg$wzp~K<`=m_! zL;iVB7%JI~UOI{zZIz>U&B0(v`HK`81>CO9wy(Zw^GwzgS@F0@8%Y_+^|Vf@q?8(+ z2~}i(C$PHZEfc1K-I@7X+xW!z-i&X>+}fJv@H@?|&_P_-mQtBwr;It4I=Uld&-ZF%z+02(| zVpF)%q#>dCgh!iMt<(N7_i)>o%Rzr}f+CbSUNdOl8(SMob*F}-0)$!-GNg+DHh@~f zA)=NPW(~;N_obze*KYUqy?pu853B7v|9!pm=FJX3Et@$OS_&@M#$zO^YJj!tv#nhg znj%hQrKf0L)QIi&-dl+po`jI{RR)Weo)0>~$Gibp1A6B5dd*%hcj= z90j%LKIl{U6wj>^s&-;?=I(!&yrk2;yL)<#?FLjX}gQm9Nkh3iN zr6rNKj~XAukwDV`Xy|+$@cBtTA7l1k4lWW$CAi!uYHu?KP~#9LO^IGh(;8tK3_e-F zdlaz)^R}@8kJ}Y85;`kx)e|{(`=+bIHu}gNcGWJxNy6x<2oV)nTLszwrV3Xy_ zjD(840f5@epN6i-wy)0JygBuHaVq8jlB}eyMtSdwU_Yv9f|l^LiHmdEm46qPTPW(n>8YlR12J;O^I7H*D@1 zK)A5oHRG9_eBR;@27jksFK>m?|W=v8&ZuEQ*5N-CYle zc71CwJu$vMJ3TwoHoP`|b@W>}m*qinY3b*mUVKrHrC=Nk8hUm31P4060n-(iGU>XL zK-B)azkX4&eB{WnFlynTpg%%d*=X)is%^Se06~k1kBJ*}Nb~3h0iI#Qtw11A1O;?uSsrO|+(FqQyS=je!l6Tf~bK z#Nm#B%{?&SZU}04`ew2I7L{|)KDg%|Pqi^&!G!~>s0gW=E#uhXtJ>vih+0PRIzp}Q zX;stK&g$G8M6GE64M6h0swo?&+LeU;21Q|61L0`XdXLYd!#{>8@~m4eN&#-_*6TGo zf*T_hl&I5G&Xtfqgn;qF;1gJ~<%i1)3xKo*|NKhpo^gA*cHQP_Xt;mB!_$*_Nw(Y? z@VSh&w8}E=bfVs5W@nGRfGy<+HE6>_k&}bw955}M;SGowEOOwc`8L;g_c|KdhHVuU z6^)M@D;gUgPqlAtZM8Qs!_0s$@M-?F7X=u`#ds1lRw6uIhbeo`6XksfwKG?$E}V_T zo&6BEe&*HakZs64TgZe2G3i+%5%}3>EuI%|O4RExSR)H!P)j|HA26W6|L5=t4#p=4 z9OXATEDW9^#;}7n^cU5*=ryG89ln};uuiT*egy%-RT%gR_*%cuZ5tSNcLWV8jkU(w zO@M!IUg=;ub}_P6w9i>lXXnzKt@^izuWCTns;e_H67p?*eYc-Jz3txFYTEgBZfb6E zYG-w7D>mGDEg{->Ev#w@`C~?l3CUVk`tkCd)B2oloJ`5gBw_?yUJB1_?&=BwH?6CS z;S4PR8_={u%gl^_axl0oce$pYJ^S%T;L(BbQ1(z^{m!T;SKKi=9Y_kz{<>YeoWz8b z#z5;8&ESGN7;v}-SUuoQZc)_k4esp?UahLC_*47ic9=bDLR049V8#crXlUL@a%^() z_0mr+)>%mcD@3SeGE)OC9mf^1&A>ZzI2qFkT()O_zkBz7hi_pU zSkH$+&zfh_B^Kg3ITVyZ(3zwjsUF-~~rwWW&bZ`zv-NHv0i&E%thT-E*2$6-pS$&?BlQ zk;(FOg#2Ru=hf%WzZbP5S0bn(>lxl#>rc(S(ALnfNy93DtZ;@vErqO!P=o*?1!mS1 zTX(Pbj#Vl7LRFH&ilD|3irE}otP-nO1P)Q-i-kC@Qo#bD_n^k+Qm_t7$9{*ZVU$ke z=xu3v{`?zUAVO)1Ka+`$8TX?#w{2!cPFe1i=X5K9+Y#_L^rylR9|tTbBWZxOn-}_% zjvS_{F{>K&^sX!}PQE$}Q5(3O+aBArv(@>})z!cK;|Xf=7i}jA%R8d5C0E@^)S84s z0{K0eS;uSY>&xZM%9zui9sM6|*Bg{%p2vfD)|;!i*&|nTn0{{RZ07*naRF*HC zxtu0nH0kWz%e$GIeRnVK_x(M9X6>u%eyI3w#Nqky`TqNSzu$w%hE6UlKp+qeho{}+ zOH1x0Tl-3M4YArnUugV7Fc=kwqVYupv}ezr1UIV50=d1qTSL~}n&^;7v~h#M5elkZu^Xa88Ue=DzKDzz<`S&lk zjxGi18ovK6?l{OA6RYgz^Bl(WIbpwQCr=2B^vV2u==xeHT5vALE^Ms$HVT`5_i=7h zZk8{;hB#!+=~>^1>O89xVesbu`79i5tm)8Xp5&2AO2k#j^n9lyuGPk)P|^y=g2CX- zOryuM>h^gt#Hvi_0CX;Urbi0fEkIe&D$U$dnv_J#Gzg*sId{_Ul$z2_KF@^CAule5 zmMf+rR>Tnq$U2RUcAVMu6rh#@8iWYUI+zV?MwD1=zAve8N ziM~-F7XhEK&YR7j@iUHqdZT z5RtwCHHx5H?Sx*bbjbK9(qV76Th6Id`%b4v<^~4-iaa(y3ff-Oj?O>2{nJm+|M3D{G@Mz3 z!(6_E1ib)p6$#V>E%=vr-zIy=>Jxk4uE>{Ksw_BkDnXgC-ONv46r+`hp}pEpM$ z;Dl}3MfhO4)HPIbWhw{#V~pM@xg>9E(--;zF9wAl=a??P@`ao-(vZz&YGjqgO1oZ4 z@(taOF{_oQZ0L5V?R=Ft=p9TR3^KeSWAK}W-!paFO6IOWq)^Cl>#kaznW@O+s?7Z= zg35l_-_tKB-b-i7H%mz@o`B>LY(Afckdq*29*-oEFUHG!y}pTDc{WokO@sw+Hn#)R z(ny)Iy3OYGAE`f%`wF&j8phh}@aOLq zYVYkV-4pdnVd$Ws9{A1SmjcrlCTTD;F=LcoIg!CqNcR;cOpzM>p%Bzap>6n!}9l zP2Zo|Tb7=TU+}k>b;rn)GnuMtI;vaaQiGNaj8?!Aa+Gz3>}xvXh5q%dl0)ZO-Uc;D z;hx!1a(aBa%hNSJGO{$%_@&$C9vT`#d|?asL3u4D6UZk8Qt{06OfW1Cspw4PpQlkI z2}(4`m}w+hDt}9A7DWOAxc;~_MWxYH8saxXNWBg5 zR&UT6RCQbhcJR0vGMU3;^A4BUVh%p_Xf+3o|>Ava<|Ys?rFQG zN3kcBT$GxB;ux*WFQ7GgsZtvYAup@7)u30>B%iHdi4^KiV84$jCCODN4Bi^A&+E0> z{9b?PKBPCIu_yN*EUq@^=2l@NiOr;i0U6_eAxns{R=N*+`j$vxMOk6{l%*6VUEbNB zz7=apqncg{F@p&O4^>l<-2S$j3lM}BROatx@$8!H^X9RhiE5*+y1VCTOUYYV4L^Hl z{+9u90uP{`383-^GHVaM5JEPKm%k?A=>X#Fz2ozV*SC)y1gzLL03R zF{M$K)^1lyGd2BYrF=UbrO1mwS}1x*BLx(Jv%a9+rKN&5XpNuAYL1N87O7;pj%-o*3=_N@%Gl%BcIsc7}6PU z>C6{3zrY%9ra>40M-d0*a*NXm*G#_1LZR@SJkIOgf1>0MWKlosG z+o$=(l}uOo{jdJ;^;a=S8Qy;qD_WqH(12a1RDM`2BxMW8{>K*k99l`YL;+$CsCQUL|p$T#|>cpOqGG%R0SUS94= zHj!rV^wDvz_sF0-95pl?J9Z$0)amNtv9KRcyi7%)o32`K@1vo}o_B0OTXrT{4PkBf z?tM9?W-y_M)@*l&f0(xd)UbHXV#Pw-*(-RsUu`{t+33A{_lEt`F^NR4(rBayn0A2^ zi6%SvT!e+stS_(vT8#_|I(@Q)=)SM7Z!tRKZ^|nyENpISYHx3kSYN!b1gy62W^54* zHRwJ)4a*Y}w*bC_kIa5-Msi|7SUX-jYYl9!kisW{Fj&JfKMP|b(80R-HUX)Uif>*X zgUyk4$+c`F&F3RWNUAr8&-cGN-15n9ehz9o$Lwl36TTL$bvnaO7AGI{EjlOH5(-Zy zq~&Po&Ui316YYzOC5>0PY|Ls0xrBg&9!MkBr-@RNgZP}I>;^Wwp&>
- 1. In QGroundControl, open the menu **Vehicle setup > PID Tuning**: ![Tuning Setup > Autotune Enabled](../../assets/qgc/setup/autotune/autotune.png) @@ -197,11 +196,8 @@ By default, the autotune maneuvers ensure that a sufficient angular rate is reac If the signal-to-noise ratio of the vehicle is low, the system identification algorithm might have issues finding the correct coefficients. Ensure that there is no excessive noise and/or platform vibration. - - - ### The drone oscillates after auto-tuning Due to effects not included in the mathematical model such as delays, saturation, slew-rate, airframe flexibility, the loop gain can be too high. diff --git a/docs/en/config/flight_mode.md b/docs/en/config/flight_mode.md index 545f1a2acc..71be6f1990 100644 --- a/docs/en/config/flight_mode.md +++ b/docs/en/config/flight_mode.md @@ -4,15 +4,15 @@ This topic explains how to map [flight modes](../getting_started/px4_basic_conce :::tip In order to set up flight modes you must already have: + - [Configured your radio](../config/radio.md) - [Setup your transmitter](#rc-transmitter-setup) to encode the physical positions of your mode switch(es) into a single channel. - We provide examples for the popular *Taranis* transmitter [below](#taranis-setup-3-way-switch-configuration-for-single-channel-mode) (check your documentation if you use a different transmitter). -::: - + We provide examples for the popular _Taranis_ transmitter [below](#taranis-setup-3-way-switch-configuration-for-single-channel-mode) (check your documentation if you use a different transmitter). + ::: ## What Flight Modes and Switches Should I Set? -Flight Modes provide different types of *autopilot-assisted flight*, and *fully autonomous flight*. +Flight Modes provide different types of _autopilot-assisted flight_, and _fully autonomous flight_. You can set any (or none) of the flight modes [available to your vehicle](../flight_modes/index.md#flight-modes). Most users should set the following modes and functions, as these make the vehicle easier and safer to fly: @@ -33,26 +33,25 @@ You can also separately specify channels for mapping a kill switch, return to la To configure single-channel flight mode selection: -1. Start *QGroundControl* and connect the vehicle. +1. Start _QGroundControl_ and connect the vehicle. 1. Turn on your RC transmitter. 1. Select **"Q" icon > Vehicle Setup > Flight Modes** (sidebar) to open _Flight Modes Setup_. ![Flight modes single-channel](../../assets/qgc/setup/flight_modes/flight_modes_single_channel.jpg) -1. Specify *Flight Mode Settings*: - * Select the **Mode channel** (above this shown as Channel 5, but this will depend on your transmitter configuration). - * Move the transmitter switch (or switches) that you have set up for mode selection through the available positions. - The mode slot matching your current switch position will be highlighted (above this is *Flight Mode 1*). +1. Specify _Flight Mode Settings_: + - Select the **Mode channel** (above this shown as Channel 5, but this will depend on your transmitter configuration). + - Move the transmitter switch (or switches) that you have set up for mode selection through the available positions. + The mode slot matching your current switch position will be highlighted (above this is _Flight Mode 1_). ::: info While you can set flight modes in any of the 6 slots, only the channels that are mapped to switch positions will be highlighted/used. ::: - * Select the flight mode that you want triggered for each switch position. -1. Specify *Switch Settings*: - * Select the channels that you want to map to specific actions - e.g.: *Return* mode, *Kill switch*, *offboard* mode, etc. (if you have spare switches and channels on your transmitter). - + - Select the flight mode that you want triggered for each switch position. +1. Specify _Switch Settings_: + - Select the channels that you want to map to specific actions - e.g.: _Return_ mode, _Kill switch_, _offboard_ mode, etc. (if you have spare switches and channels on your transmitter). 1. Test that the modes are mapped to the right transmitter switches: - * Check the *Channel Monitor* to confirm that the expected channel is changed by each switch. - * Select each mode switch on your transmitter in turn, and check that the desired flight mode is activated (the text turns yellow on *QGroundControl* for the active mode). + - Check the _Channel Monitor_ to confirm that the expected channel is changed by each switch. + - Select each mode switch on your transmitter in turn, and check that the desired flight mode is activated (the text turns yellow on _QGroundControl_ for the active mode). All values are automatically saved as they are changed. @@ -61,7 +60,6 @@ All values are automatically saved as they are changed. This section contains a small number of possible setup configurations for taranis. QGroundControl _may_ have [setup information for other transmitters here](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/flight_modes.html#transmitter-setup). - ### Taranis Setup: 3-way Switch Configuration for Single-Channel Mode @@ -70,7 +68,7 @@ If you only need to support selecting between two or three modes then you can ma Below we show how to map the Taranis 3-way "SD" switch to channel 5. ::: info -This example shows how to set up the popular *FrSky Taranis* transmitter. +This example shows how to set up the popular _FrSky Taranis_ transmitter. Transmitter setup will be different on other transmitters. ::: @@ -78,15 +76,14 @@ Open the Taranis UI **MIXER** page and scroll down to **CH5**, as shown below: ![Taranis - Map channel to switch](../../assets/qgc/setup/flight_modes/single_channel_mode_selection_1.png) -Press **ENT(ER)** to edit the **CH5** configuration then change the **Source** to be the *SD* button. +Press **ENT(ER)** to edit the **CH5** configuration then change the **Source** to be the _SD_ button. ![Taranis - Configure channel](../../assets/qgc/setup/flight_modes/single_channel_mode_selection_2.png) That's it! Channel 5 will now output 3 different PWM values for the three different **SD** switch positions. -The *QGroundControl* configuration is then as described in the previous section. - +The _QGroundControl_ configuration is then as described in the previous section. ### Taranis Setup: Multi-Switch Configuration for Single-Channel Mode @@ -96,19 +93,18 @@ Commonly this is done by encoding the positions of a 2- and a 3-position switch On the FrSky Taranis this process involves assigning a "logical switch" to each combination of positions of the two real switches. Each logical switch is then assigned to a different PWM value on the same channel. -The video below shows how this is done with the *FrSky Taranis* transmitter. +The video below shows how this is done with the _FrSky Taranis_ transmitter. -The *QGroundControl* configuration is then [as described above](#flight-mode-selection). - +The _QGroundControl_ configuration is then [as described above](#flight-mode-selection). ## Further Information -* [Flight Modes Overview](../flight_modes/index.md) -* [QGroundControl > Flight Modes](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/flight_modes.html#px4-pro-flight-mode-setup) -* [PX4 Setup Video - @6m53s](https://youtu.be/91VGmdSlbo4?t=6m53s) (Youtube) -* [Radio switch parameters](../advanced_config/parameter_reference.md#radio-switches) - Can be used to set mappings via parameters +- [Flight Modes Overview](../flight_modes/index.md) +- [QGroundControl > Flight Modes](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/flight_modes.html#px4-pro-flight-mode-setup) +- [PX4 Setup Video - @6m53s](https://youtu.be/91VGmdSlbo4?t=6m53s) (Youtube) +- [Radio switch parameters](../advanced_config/parameter_reference.md#radio-switches) - Can be used to set mappings via parameters diff --git a/docs/en/config/level_horizon_calibration.md b/docs/en/config/level_horizon_calibration.md index 6eb708b16a..30c2fc0a71 100644 --- a/docs/en/config/level_horizon_calibration.md +++ b/docs/en/config/level_horizon_calibration.md @@ -18,7 +18,6 @@ To level the horizon: You should already have set the [Autopilot Orientation](../config/flight_controller_orientation.md). If not, you can also set it here. ::: 1. Place the vehicle in its level flight orientation on a level surface: - - For planes this is the position during level flight (planes tend to have their wings slightly pitched up!) - For copters this is the hover position. diff --git a/docs/en/config/safety.md b/docs/en/config/safety.md index 9f72f4589f..f8a224f945 100644 --- a/docs/en/config/safety.md +++ b/docs/en/config/safety.md @@ -128,10 +128,10 @@ Additional (and underlying) parameter settings are shown below. | Parameter | Setting | Description | | ----------------------------------------------------------------------------------------------------- | --------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [COM_RC_LOSS_T](../advanced_config/parameter_reference.md#COM_RC_LOSS_T) | Manual Control Loss Timeout | Time after last setpoint received from the selected manual control source after which manual control is considered lost. This must be kept short because the vehicle will continue to fly using the last known stick position until the timeout triggers. | +| [COM_RC_LOSS_T](../advanced_config/parameter_reference.md#COM_RC_LOSS_T) | Manual Control Loss Timeout | Time after last setpoint received from the selected manual control source after which manual control is considered lost. This must be kept short because the vehicle will continue to fly using the last known stick position until the timeout triggers. | | [COM_FAIL_ACT_T](../advanced_config/parameter_reference.md#COM_FAIL_ACT_T) | Failsafe Reaction Delay | Delay in seconds between failsafe condition being triggered (`COM_RC_LOSS_T`) and failsafe action (RTL, Land, Hold). In this state the vehicle waits in hold mode for the manual control source to reconnect. This might be set longer for long-range flights so that intermittent connection loss doesn't immediately invoke the failsafe. It can be to zero so that the failsafe triggers immediately. | | [NAV_RCL_ACT](../advanced_config/parameter_reference.md#NAV_RCL_ACT) | Failsafe Action | Disabled, Loiter, Return, Land, Disarm, Terminate. | -| [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | RC Loss Exceptions | Set modes in which manual control loss is ignored. | +| [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | RC Loss Exceptions | Set modes in which manual control loss is ignored. | ## Data Link Loss Failsafe @@ -142,11 +142,11 @@ Users that want to disable this failsafe in specific modes can do so using the p The settings and underlying parameters are shown below. -| Setting | Parameter | Description | -| ---------------------- | ------------------------------------------------------------------------ | --------------------------------------------------------------------------------- | -| Data Link Loss Timeout | [COM_DL_LOSS_T](../advanced_config/parameter_reference.md#COM_DL_LOSS_T) | Amount of time after losing the data connection before the failsafe will trigger. | -| Failsafe Action | [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT) | Disabled, Hold mode, Return mode, Land mode, Disarm, Terminate. | -| Mode exceptions for DLL failsafe | [COM_DLL_EXCEPT](../advanced_config/parameter_reference.md#COM_DLL_EXCEPT) | Set modes in which data link loss is ignored. | +| Setting | Parameter | Description | +| ----------------------------------------------------------- | -------------------------------------------------------------------------- | --------------------------------------------------------------------------------- | +| Data Link Loss Timeout | [COM_DL_LOSS_T](../advanced_config/parameter_reference.md#COM_DL_LOSS_T) | Amount of time after losing the data connection before the failsafe will trigger. | +| Failsafe Action | [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT) | Disabled, Hold mode, Return mode, Land mode, Disarm, Terminate. | +| Mode exceptions for DLL failsafe | [COM_DLL_EXCEPT](../advanced_config/parameter_reference.md#COM_DLL_EXCEPT) | Set modes in which data link loss is ignored. | ## Geofence Failsafe diff --git a/docs/en/config/safety_intro.md b/docs/en/config/safety_intro.md index 771f113d73..2c4fdeec33 100644 --- a/docs/en/config/safety_intro.md +++ b/docs/en/config/safety_intro.md @@ -13,7 +13,7 @@ These are covered in the following topics: - [Safe Points (Rally)](../flying/plan_safety_points.md) - [Prearm/Arm/Disarm Configuration](../advanced_config/prearm_arm_disarm.md) - [Flight Termination Configuration](../advanced_config/flight_termination.md) -- [First Flight Guidelines](../flying/first_flight_guidelines.md) +- [First Flight Guidelines](../flying/first_flight_guidelines.md) ::: tip Note that the [First Flight Guidelines](../flying/first_flight_guidelines.md) are listed _last_. diff --git a/docs/en/config_heli/index.md b/docs/en/config_heli/index.md index 131f1c7e70..d74e4c8d79 100644 --- a/docs/en/config_heli/index.md +++ b/docs/en/config_heli/index.md @@ -42,14 +42,12 @@ To setup and configure a helicopter: ![Geometry: helicopter](../../assets/config/actuators/qgc_geometry_helicopter.png) The motors have no configurable geometry: - - `Rotor (Motor 1)`: The main rotor - `Yaw tail motor (Motor 2)`: The tail rotor Swash plate servos: `3` | `4` For each servo set: - - `Angle`: Clockwise angle in degree on the swash plate circle at which the servo arm is attached starting from `0` pointing forwards. Example for a typical setup where three servos are controlling the swash plate equally distributed over the circle (360° / 3 =) 120° apart each which results in the angles: @@ -65,7 +63,6 @@ To setup and configure a helicopter: - `Trim`: Offset individual servo positions. This is only needed in rare case when the swash plate is not level even though all servos are centered. Additional settings: - - `Yaw compensation scale based on collective pitch`: How much yaw is feed forward compensated based on the current collective pitch. - `Main rotor turns counter-clockwise`: `Disabled` (clockwise rotation) | `Enabled` - `Throttle spoolup time`: Set value (in seconds) greater than the achievable minimum motor spool up time. @@ -73,12 +70,10 @@ To setup and configure a helicopter: 1. Remove the rotor blades and propellers 1. Assign motors and servos to outputs and test (also in [Actuator configuration](../config/actuators.md)): - 1. Assign the [motors and servos to the outputs](../config/actuators.md#actuator-outputs). 1. Power the vehicle with a battery and use the [actuator testing sliders](../config/actuators.md#actuator-testing) to validate correct servo and motor assignment and direction. 1. Using an RC in [Acro mode](../flight_modes_mc/acro.md), verify the correct movement of the swash-plate. With most airframes you need to see the following: - - Moving the roll stick to the right should tilt the swash-plate to the right. - Moving the pitch stick forward should tilt the swash-plate forward. @@ -144,7 +139,6 @@ The rate controller should be tuned in [Acro mode](../flight_modes_mc/acro.md), 3. Then enable the PID gains. Start off with following values: - - [MC_ROLLRATE_P](../advanced_config/parameter_reference.md#MC_ROLLRATE_P), [MC_PITCHRATE_P](../advanced_config/parameter_reference.md#MC_PITCHRATE_P) a quarter of the value you found to work well as the corresponding feed forward value in the previous step. `P = FF / 4` ```sh diff --git a/docs/en/config_mc/index.md b/docs/en/config_mc/index.md index 9d15f9924e..db4fd6809a 100644 --- a/docs/en/config_mc/index.md +++ b/docs/en/config_mc/index.md @@ -123,14 +123,12 @@ Tuning is the final step, carried out only after most other setup and configurat ::: info Automatic tuning works on frames that have reasonable authority and dynamics around all the body axes. It has primarily been tested on racing quads and X500, and is expected to be less effective on tricopters with a tiltable rotor. - + Manual tuning using these guides are only needed if there is a problem with autotune: - - [MC PID Tuning (Manual/Basic)](../config_mc/pid_tuning_guide_multicopter_basic.md) — Manual tuning basic how to. - [MC PID Tuning Guide (Manual/Detailed)](../config_mc/pid_tuning_guide_multicopter.md) — Manual tuning with detailed explanation. - - ::: + ::: - [MC Filter/Control Latency Tuning](../config_mc/filter_tuning.md) — Trade off control latency and noise filtering. - [MC Setpoint Tuning (Trajectory Generator)](../config_mc/mc_trajectory_tuning.md) diff --git a/docs/en/config_mc/pid_tuning_guide_multicopter_basic.md b/docs/en/config_mc/pid_tuning_guide_multicopter_basic.md index 1faf538b8f..dcadf60b94 100644 --- a/docs/en/config_mc/pid_tuning_guide_multicopter_basic.md +++ b/docs/en/config_mc/pid_tuning_guide_multicopter_basic.md @@ -46,7 +46,6 @@ Then adjust the sliders (as discussed below) to improve the tracking of the resp These need to be set low, but such that the **motors never stop** when the vehicle is armed. This can be tested in [Acro mode](../flight_modes_mc/acro.md) or in [Stabilized mode](../flight_modes_mc/manual_stabilized.md): - - Remove propellers - Arm the vehicle and lower the throttle to the minimum - Tilt the vehicle to all directions, about 60 degrees @@ -77,7 +76,6 @@ The tuning procedure is: As a result, the optimal tuning at hover thrust may not be ideal when the vehicle is operating at higher thrust. The thrust curve value can be used to compensate for this non-linearity: - - For PWM controllers, 0.3 is a good default (which may benefit from [further tuning](../config_mc/pid_tuning_guide_multicopter.md#thrust-curve)). - For RPM-based controllers, use 1 (no further tuning is required as these have a quadratic thrust curve). @@ -120,7 +118,6 @@ The tuning procedure is: ::: 1. Repeat the tuning process for the attitude controller on all the axes. 1. Repeat the tuning process for the velocity and positions controllers (on all the axes). - - Use Position mode when tuning these controllers - Select the **Simple position control** option in the _Position control mode ..._ selector (this allows direct control for the generation of step inputs) diff --git a/docs/en/config_rover/rate_tuning.md b/docs/en/config_rover/rate_tuning.md index 92d4ea5d98..fd327d34ef 100644 --- a/docs/en/config_rover/rate_tuning.md +++ b/docs/en/config_rover/rate_tuning.md @@ -15,13 +15,11 @@ Configure the following [parameters](../advanced_config/parameters.md) in QGroun Small rovers especially can be prone to rolling over when steering aggressively at high speeds. If this is the case: - 1. In [Acro mode](../flight_modes_rover/manual.md#acro-mode), set [RO_YAW_RATE_LIM](#RO_YAW_RATE_LIM) to a small value, drive the rover at full throttle and steer all the way to the left or right. 2. Increase [RO_YAW_RATE_LIM](#RO_YAW_RATE_LIM) until the wheels of the rover start to lift up. 3. Set [RO_YAW_RATE_LIM](#RO_YAW_RATE_LIM) to the highest value that does not cause the rover to lift up. If you see no need to limit the yaw rate, set this parameter to the maximum yaw rate the rover can achieve: - 1. In [Manual mode](../flight_modes_rover/manual.md#manual-mode) drive the rover at full throttle and with the maximum steering angle. 2. Plot the `measured_yaw_rate` from [RoverRateStatus](../msg_docs/RoverRateStatus.md) and enter the highest observed value for [RO_YAW_RATE_LIM](#RO_YAW_RATE_LIM). @@ -51,7 +49,6 @@ Configure the following [parameters](../advanced_config/parameters.md) in QGroun :::tip To tune this parameter: - 1. Put the rover in [Acro mode](../flight_modes_rover/manual.md#acro-mode) and hold the throttle stick and the right stick at a few different levels for a couple of seconds each. 1. Disarm the rover and from the flight log plot the `adjusted_yaw_rate_setpoint` and the `measured_yaw_rate` from [RoverRateStatus](../msg_docs/RoverRateStatus.md) over each other. 1. Increase [RO_YAW_RATE_P](#RO_YAW_RATE_P) if the measured value does not track the setpoint fast enough or decrease it if the measurement overshoots the setpoint by too much. diff --git a/docs/en/config_vtol/vtol_ice_shedding.md b/docs/en/config_vtol/vtol_ice_shedding.md index 629a599f93..bf9ccc80af 100644 --- a/docs/en/config_vtol/vtol_ice_shedding.md +++ b/docs/en/config_vtol/vtol_ice_shedding.md @@ -14,7 +14,8 @@ seconds. In each cycle, the rotors are spun for two seconds at a motor output of :::warning When enabling the feature on a new airframe, there is the risk of producing torques that disturb the fixed-wing rate controller. To mitigate this risk: - - Set your `PWM_MIN` values correctly, so that the motor output 0.01 actually - produces 1% thrust - - Be prepared to take control and switch back to multicopter -::: + +- Set your `PWM_MIN` values correctly, so that the motor output 0.01 actually + produces 1% thrust +- Be prepared to take control and switch back to multicopter + ::: diff --git a/docs/en/config_vtol/vtol_without_airspeed_sensor.md b/docs/en/config_vtol/vtol_without_airspeed_sensor.md index 758543c354..dbcfc56ec2 100644 --- a/docs/en/config_vtol/vtol_without_airspeed_sensor.md +++ b/docs/en/config_vtol/vtol_without_airspeed_sensor.md @@ -66,7 +66,7 @@ Set the minimum front transition time ([VT_TRANS_MIN_TM](../advanced_config/para Because the risk of stalling is real, it is recommended to set the 'fixed-wing minimum altitude' (a.k.a. 'quad-chute') threshold ([VT_FW_MIN_ALT](../advanced_config/parameter_reference.md#VT_FW_MIN_ALT)). -This will cause the VTOL to transition back to multicopter mode and initiate the [Return mode](../flight_modes_vtol/return.md) below a certain altitude. +This will cause the VTOL to transition back to multicopter mode and initiate the [Return mode](../flight_modes_vtol/return.md) below a certain altitude. You could set this to 15 or 20 meters to give the multicopter time to recover from a stall. The position estimator tested for this mode is EKF2, which is enabled by default (for more information see [Switching State Estimators](../advanced/switching_state_estimators.md#how-to-enable-different-estimators) and [EKF2_EN ](../advanced_config/parameter_reference.md#EKF2_EN)). diff --git a/docs/en/dev_airframes/adding_a_new_frame.md b/docs/en/dev_airframes/adding_a_new_frame.md index addec0b132..f34ec3ea30 100644 --- a/docs/en/dev_airframes/adding_a_new_frame.md +++ b/docs/en/dev_airframes/adding_a_new_frame.md @@ -306,7 +306,6 @@ If the airframe is for a **new group** you additionally need to: ``` 1. Update _QGroundControl_: - - Add the svg image for the group into: [src/AutopilotPlugins/Common/images](https://github.com/mavlink/qgroundcontrol/tree/master/src/AutoPilotPlugins/Common/Images) - Add reference to the svg image into [qgcimages.qrc](https://github.com/mavlink/qgroundcontrol/blob/master/qgcimages.qrc), following the pattern below: diff --git a/docs/en/dev_log/logging.md b/docs/en/dev_log/logging.md index 47d4d6f385..daa0d6d9e7 100644 --- a/docs/en/dev_log/logging.md +++ b/docs/en/dev_log/logging.md @@ -33,12 +33,12 @@ The logging system is configured by default to collect sensible logs for [flight Logging may further be configured using the [SD Logging](../advanced_config/parameter_reference.md#sd-logging) parameters. The parameters you are most likely to change are listed below. -| Parameter | Description | -| ------------------------------------------------------------------------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| Parameter | Description | +| ------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | | [SDLOG_MODE](../advanced_config/parameter_reference.md#SDLOG_MODE) | Logging Mode. Defines when logging starts and stops.
- `0`: Log when armed until disarm (default).
- `1`: Log from boot until disarm.
- `2`: Log from boot until shutdown.
- `3`: Log based on the [AUX1 RC channel](../advanced_config/parameter_reference.md#RC_MAP_AUX1).
- `4`: Log from first armed until shutdown. | -| [SDLOG_BACKEND](../advanced_config/parameter_reference.md#SDLOG_BACKEND) | Logging Backend (bitmask). Setting a bit enables the corresponding backend. If no backend is selected, the logger is disabled.
- bit `0`: SD card logging.
- bit `1`: Mavlink logging. -| [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) | Logging profile. Use this to enable less common logging/analysis (e.g. for EKF2 replay, high rate logging for PID & filter tuning, thermal temperature calibration). | -| [SDLOG_MISSION](../advanced_config/parameter_reference.md#SDLOG_MISSION) | Create very small additional "Mission Log".
This log can _not_ be used with [Flight Review](../log/flight_log_analysis.md#flight-review-online-tool), but is useful when you need a small log for geotagging or regulatory compliance. | +| [SDLOG_BACKEND](../advanced_config/parameter_reference.md#SDLOG_BACKEND) | Logging Backend (bitmask). Setting a bit enables the corresponding backend. If no backend is selected, the logger is disabled.
- bit `0`: SD card logging.
- bit `1`: Mavlink logging. | +| [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) | Logging profile. Use this to enable less common logging/analysis (e.g. for EKF2 replay, high rate logging for PID & filter tuning, thermal temperature calibration). | +| [SDLOG_MISSION](../advanced_config/parameter_reference.md#SDLOG_MISSION) | Create very small additional "Mission Log".
This log can _not_ be used with [Flight Review](../log/flight_log_analysis.md#flight-review-online-tool), but is useful when you need a small log for geotagging or regulatory compliance. | Useful settings for specific cases: diff --git a/docs/en/dev_setup/building_px4.md b/docs/en/dev_setup/building_px4.md index d9ac63b279..b5ab7ccdc3 100644 --- a/docs/en/dev_setup/building_px4.md +++ b/docs/en/dev_setup/building_px4.md @@ -39,8 +39,8 @@ Navigate into the **PX4-Autopilot** directory and start [Gazebo SITL](../sim_gaz make px4_sitl gz_x500 ``` -::: details If you installed Gazebo Classic -Start [Gazebo Classic SITL](../sim_gazebo_classic/index.md) using the following command: +::: details If you installed Gazebo Classic +Start [Gazebo Classic SITL](../sim_gazebo_classic/index.md) using the following command: ```sh make px4_sitl gazebo-classic diff --git a/docs/en/dev_setup/config_initial.md b/docs/en/dev_setup/config_initial.md index 1e29ed30c6..f636aef195 100644 --- a/docs/en/dev_setup/config_initial.md +++ b/docs/en/dev_setup/config_initial.md @@ -18,7 +18,6 @@ The equipment below is highly recommended: ::: info The listed computers have acceptable performance, but a more recent and powerful computer is recommended. ::: - - Lenovo Thinkpad with i5-core running Windows 11 - MacBook Pro (early 2015 and later) with macOS 10.15 or later - Lenovo Thinkpad i5 with Ubuntu Linux 20.04 or later diff --git a/docs/en/dev_setup/dev_env.md b/docs/en/dev_setup/dev_env.md index 33069072c6..b57ab037c0 100644 --- a/docs/en/dev_setup/dev_env.md +++ b/docs/en/dev_setup/dev_env.md @@ -11,13 +11,13 @@ The _supported platforms_ for PX4 development are: The table below shows what PX4 targets you can build on each OS. | Target | Linux (Ubuntu) | macOS | Windows | -| -------------------------------------------------------------------------------------------------------------------------------------- | :------------: | :-: | :-----: | -| **NuttX based hardware:** [Pixhawk Series](../flight_controller/pixhawk_series.md), [Crazyflie](../complete_vehicles_mc/crazyflie2.md) | ✓ | ✓ | ✓ | -| **Linux-based hardware:** [Raspberry Pi 2/3](../flight_controller/raspberry_pi_navio2.md) | ✓ | | | -| **Simulation:** [Gazebo SITL](../sim_gazebo_gz/index.md) | ✓ | ✓ | ✓ | -| **Simulation:** [Gazebo Classic SITL](../sim_gazebo_classic/index.md) | ✓ | ✓ | ✓ | -| **Simulation:** [ROS with Gazebo Classic](../simulation/ros_interface.md) | ✓ | | ✓ | -| **Simulation:** ROS 2 with Gazebo | ✓ | | ✓ | +| -------------------------------------------------------------------------------------------------------------------------------------- | :------------: | :---: | :-----: | +| **NuttX based hardware:** [Pixhawk Series](../flight_controller/pixhawk_series.md), [Crazyflie](../complete_vehicles_mc/crazyflie2.md) | ✓ | ✓ | ✓ | +| **Linux-based hardware:** [Raspberry Pi 2/3](../flight_controller/raspberry_pi_navio2.md) | ✓ | | | +| **Simulation:** [Gazebo SITL](../sim_gazebo_gz/index.md) | ✓ | ✓ | ✓ | +| **Simulation:** [Gazebo Classic SITL](../sim_gazebo_classic/index.md) | ✓ | ✓ | ✓ | +| **Simulation:** [ROS with Gazebo Classic](../simulation/ros_interface.md) | ✓ | | ✓ | +| **Simulation:** ROS 2 with Gazebo | ✓ | | ✓ | Experienced Docker users can also build with the containers used by our continuous integration system: [Docker Containers](../test_and_ci/docker.md) diff --git a/docs/en/dev_setup/dev_env_mac.md b/docs/en/dev_setup/dev_env_mac.md index fee66f554e..25757f8657 100644 --- a/docs/en/dev_setup/dev_env_mac.md +++ b/docs/en/dev_setup/dev_env_mac.md @@ -107,7 +107,6 @@ To setup the environment for [Gazebo Classic](../sim_gazebo_classic/index.md) si sh macos.sh ``` - ## Next Steps Once you have finished setting up the command-line toolchain: diff --git a/docs/en/dev_setup/vscode.md b/docs/en/dev_setup/vscode.md index fb4d9e79e3..302e68b250 100644 --- a/docs/en/dev_setup/vscode.md +++ b/docs/en/dev_setup/vscode.md @@ -23,7 +23,6 @@ You must already have installed the command line [PX4 developer environment](../ 1. [Download and install VSCode](https://code.visualstudio.com/) (you will be offered the correct version for your OS). 1. Open VSCode and add the PX4 source code: - - Select _Open folder ..._ option on the welcome page (or using the menu: **File > Open Folder**): ![Open Folder](../../assets/toolchain/vscode/welcome_open_folder.jpg) @@ -45,7 +44,6 @@ You must already have installed the command line [PX4 developer environment](../ :::tip If the prompts disappear, click the little "alarm" icon on the right of the bottom blue bar. ::: - - If prompted to install a new version of _cmake_: - Say **No** (the right version is installed with the [PX4 developer environment](../dev_setup/dev_env.md)). - If prompted to sign into _github.com_ and add your credentials: @@ -59,7 +57,6 @@ You must already have installed the command line [PX4 developer environment](../ To build: 1. Select your build target ("cmake build config"): - - The current _cmake build target_ is shown on the blue _config_ bar at the bottom (if this is already your desired target, skip to next step). ![Select Cmake build target](../../assets/toolchain/vscode/cmake_build_config.jpg) diff --git a/docs/en/dronecan/ark_cannode.md b/docs/en/dronecan/ark_cannode.md index e1fca0c6d7..fdb403f717 100644 --- a/docs/en/dronecan/ark_cannode.md +++ b/docs/en/dronecan/ark_cannode.md @@ -83,10 +83,10 @@ This is done using the the parameters named like `UAVCAN_SUB_*` in the parameter On the ARK CANnode, you may need to configure the following parameters: -| Parameter | Description | -| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | -| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | +| Parameter | Description | +| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | ## LED Meanings diff --git a/docs/en/dronecan/ark_flow.md b/docs/en/dronecan/ark_flow.md index 8b43846bd3..c3c7906c87 100644 --- a/docs/en/dronecan/ark_flow.md +++ b/docs/en/dronecan/ark_flow.md @@ -72,7 +72,6 @@ The Ark Flow will not boot if there is no SD card in the flight controller when ### Enable DroneCAN - The steps are: - In _QGroundControl_ set the parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` for dynamic node allocation (or `3` if using [DroneCAN ESCs](../dronecan/escs.md)) and reboot (see [Finding/Updating Parameters](../advanced_config/parameters.md)). @@ -111,10 +110,10 @@ When optical flow is the only source of horizontal position/velocity, then lower On the ARK Flow, you may need to configure the following parameters: -| Parameter | Description | -| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | -| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | +| Parameter | Description | +| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | ## LED Meanings diff --git a/docs/en/dronecan/ark_flow_mr.md b/docs/en/dronecan/ark_flow_mr.md index dae831b467..f6207cae73 100644 --- a/docs/en/dronecan/ark_flow_mr.md +++ b/docs/en/dronecan/ark_flow_mr.md @@ -1,6 +1,6 @@ # ARK Flow MR -ARK Flow MR ("Mid Range") is an open source [DroneCAN](index.md) [optical flow](../sensor/optical_flow.md), [distance sensor](../sensor/rangefinders.md), and IMU module. +ARK Flow MR ("Mid Range") is an open source [DroneCAN](index.md) [optical flow](../sensor/optical_flow.md), [distance sensor](../sensor/rangefinders.md), and IMU module. It is the next generation of the [Ark Flow](ark_flow.md), designed for mid-range applications. ![ARK Flow MR](../../assets/hardware/sensors/optical_flow/ark_flow_mr.jpg) @@ -28,7 +28,7 @@ Order this module from: - Invensense IIM-42653 6-Axis IMU - Two Pixhawk Standard CAN Connectors (4 Pin JST GH) - Pixhawk Standard Debug Connector (6 Pin JST SH) -- Software controlled built-in CAN termination resistor via node parameter (CANNODE_TERM) +- Software controlled built-in CAN termination resistor via node parameter (CANNODE_TERM) - Small Form Factor - 3cm x 3cm x 1.4cm - LED Indicators @@ -70,7 +70,6 @@ The Ark Flow MR will not boot if there is no SD card in the flight controller wh ### Enable DroneCAN - The steps are: - In _QGroundControl_ set the parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` for dynamic node allocation (or `3` if using [DroneCAN ESCs](../dronecan/escs.md)) and reboot (see [Finding/Updating Parameters](../advanced_config/parameters.md)). @@ -106,17 +105,16 @@ Set the following parameters in _QGroundControl_: You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK Flow MR itself: -| Parameter | Description | -| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | -| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | +| Parameter | Description | +| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | ## LED Meanings - Blinking green is normal operation - Rapid blinking blue and red is firmware update - If you see a solid red LED there is an error and you should check the following: - Make sure the flight controller has an SD card installed. diff --git a/docs/en/dronecan/ark_gps.md b/docs/en/dronecan/ark_gps.md index 51f07f92c1..9b91601ca6 100644 --- a/docs/en/dronecan/ark_gps.md +++ b/docs/en/dronecan/ark_gps.md @@ -97,10 +97,10 @@ If the sensor is not centred within the vehicle you will also need to define sen You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK GPS itself: -| Parameter | Description | -| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | -| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. | +| Parameter | Description | +| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. | ## LED Meanings diff --git a/docs/en/dronecan/ark_rtk_gps.md b/docs/en/dronecan/ark_rtk_gps.md index bbb8940fec..e3114685fa 100644 --- a/docs/en/dronecan/ark_rtk_gps.md +++ b/docs/en/dronecan/ark_rtk_gps.md @@ -91,10 +91,10 @@ You need to set necessary [DroneCAN](index.md) parameters and define offsets if You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK RTK GPS itself: -| Parameter | Description | -| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | -| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. | +| Parameter | Description | +| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. | ### Setting Up Rover and Fixed Base diff --git a/docs/en/dronecan/holybro_h_rtk_zed_f9p_gps.md b/docs/en/dronecan/holybro_h_rtk_zed_f9p_gps.md index 12879ef265..de1de36510 100644 --- a/docs/en/dronecan/holybro_h_rtk_zed_f9p_gps.md +++ b/docs/en/dronecan/holybro_h_rtk_zed_f9p_gps.md @@ -100,7 +100,6 @@ In order to use dual ZED-F9P GPS heading in PX4, follow these steps: 1. Components should be visible on the left panel. Click on the first `_Component_` that maps to the ZED-F9P DroneCAN node (below shown as _Component 124_). 1. Click on the _GPS_ subsection and configure the parameters listed below: - - `GPS_TYPE`: Either set to `17` for moving baseline _base_, or set to `18` to be the moving baseline _rover_. One F9P MUST be _rover_, and the other MUST be _base_. - `GPS_AUTO_CONFIG`: set to 1 for both the rover and base diff --git a/docs/en/esc/ark_4in1_esc.md b/docs/en/esc/ark_4in1_esc.md index 5d094198ce..40fb8d607f 100644 --- a/docs/en/esc/ark_4in1_esc.md +++ b/docs/en/esc/ark_4in1_esc.md @@ -32,12 +32,10 @@ Order this module from: - 10 Pin JST-SH Debug - Motor & Battery Connectors (with-connector version) - - MR30 Connector Limit Per Motor: 30A Continuous, 40A Burst - Four MR30 Motor Connectors - Dimensions (with connectors) - - Size: 77.00mm x 42.00mm x 9.43mm - Mounting Pattern: 30.5mm - Weight: 24g diff --git a/docs/en/flight_controller/airlink.md b/docs/en/flight_controller/airlink.md index 0d4fb1ec2b..30218fc14c 100644 --- a/docs/en/flight_controller/airlink.md +++ b/docs/en/flight_controller/airlink.md @@ -26,7 +26,6 @@ AIRLink has two computers and integrated LTE Module: ## Specifications - **Sensors** - - 3x Accelerometers, 3x Gyroscopes, 3x Magnetometers, 3x Pressure sensorss - GNSS, Rangefinders, Lidars, Optical Flow, Cameras - 3x-redundant IMU @@ -34,7 +33,6 @@ AIRLink has two computers and integrated LTE Module: - Temperature stabilization - **Flight Controller** - - STM32F7, ARM Cortex M7 with FPU, 216 MHz, 2MB Flash, 512 kB RAM - STM32F1, I/O co-processor - Ethernet, 10/100 Mbps @@ -51,7 +49,6 @@ AIRLink has two computers and integrated LTE Module: - Safety switch / LED option - **AI Mission Computer** - - 6-Core CPU: Dual-Core Cortex-A72 + Quad-Core Cortex-A53 - GPU Mali-T864, OpenGL ES1.1/2.0/3.0/3.1 - VPU with 4K VP8/9, 4K 10bits H265/H264 60fps Decoding @@ -65,7 +62,6 @@ AIRLink has two computers and integrated LTE Module: - 2x Video: 4-Lane MIPI CSI (FPV Camera) and 4-Lane MIPI CSI with HMDI Input (Payload Camera) - **LTE/5G Connectivity Module** - - Up to 600 Mbps bandwidth - 5G sub-6 and mmWave, SA and NSA operations - 4G Cat 20, up to 7xCA, 256-QAM DL/UL, 2xCA UL @@ -142,7 +138,6 @@ SmartAP AIRLink's Core edition is intended for medium to high volume production ![Left side](../../assets/flight_controller/airlink/airlink-interfaces-left.jpg) - **Left side interfaces:** - - Power input with voltage & current monitoring - AI Mission Computer micro SD card - Flight Controller micro SD card @@ -169,12 +164,12 @@ SmartAP AIRLink's Core edition is intended for medium to high volume production - **RC Connector - JST GH SM06B-GHS-TB** | Pin number | Pin name | Direction | Voltage | Function | - | ---------- | -------- | --------- | ------- | ----------- | + | ---------- | -------- | --------- | ------- | ----------- | --- | --- | ------ | | 1 | 5V | OUT | +5V | 5V output | | 2 | PPM_IN | IN | +3.3V | PPM input | | 3 | RSSI_IN | IN | +3.3V | RSSI input | | 4 | FAN_OUT | OUT | +5V | Fan output | - | 5 | SBUS_OUT | OUT | +3.3V | SBUS output | 6 | GND | Ground | + | 5 | SBUS_OUT | OUT | +3.3V | SBUS output | 6 | GND | Ground | * **FMU SD card - microSD** @@ -183,7 +178,6 @@ SmartAP AIRLink's Core edition is intended for medium to high volume production ![Right side](../../assets/flight_controller/airlink/airlink-interfaces-right.jpg) - **Right side interfaces:** - - Ethernet port with power output - Telemetry port - Second GPS port @@ -247,7 +241,6 @@ SmartAP AIRLink's Core edition is intended for medium to high volume production ![Front side](../../assets/flight_controller/airlink/airlink-interfaces-front.jpg) - **Front side interfaces:** - - Main GNSS and compass port - Main telemetry port - CSI camera input @@ -305,7 +298,6 @@ SmartAP AIRLink's Core edition is intended for medium to high volume production ![Back side](../../assets/flight_controller/airlink/airlink-interfaces-back.jpg) - **Rear side interfaces:** - - SBUS input - 16 PWM output channels - 2x LTE antenna sockets (MIMO) diff --git a/docs/en/flight_controller/cuav_x25-evo.md b/docs/en/flight_controller/cuav_x25-evo.md index 2d53c32fbd..881290e9c8 100644 --- a/docs/en/flight_controller/cuav_x25-evo.md +++ b/docs/en/flight_controller/cuav_x25-evo.md @@ -83,7 +83,7 @@ These flight controllers are [manufacturer supported](../flight_controller/autop ### Mechanical Data - - Not provided. +- Not provided. ## Purchase Channels @@ -91,11 +91,11 @@ Order from [CUAV](https://store.cuav.net/). ## Assembly/Setup - - Not provided. +- Not provided. ## Pin Definitions - - Not provided. +- Not provided. ## Serial Port Mapping @@ -112,11 +112,13 @@ Order from [CUAV](https://store.cuav.net/). ## Voltage Ratings The _X25-EVO_ achieves triple redundancy on power supplies if three power sources are provided. The three power rails are POWERC1, POWERC2, and USB. + - **POWER C1** and **POWER C2** are DroneCAN/UAVCAN battery interfaces. **Normal Operation Maximum Ratings** Under these conditions, all power sources will be used to power the system in the following order: + 1. **POWER C1** and **POWER C2** Inputs (10V to 18V) 2. USB Input (4.75V to 5.25V) @@ -143,14 +145,14 @@ make cuav_x25-evo_default The [PX4 System Console](../debug/system_console.md) and [SWD Interface](../debug/swd_debug.md) operate on the **FMU Debug** port. -| Pin | Signal | Volt | -| -------- | ---------------- | ----- | -| 1 (red) | 5V+ | +5V | -| 2 (blk) | DEBUG TX (OUT) | +3.3V | -| 3 (blk) | DEBUG RX (IN) | +3.3V | -| 4 (blk) | FMU_SWDIO | +3.3V | -| 5 (blk) | FMU_SWCLK | +3.3V | -| 6 (blk) | GND | GND | +| Pin | Signal | Volt | +| ------- | -------------- | ----- | +| 1 (red) | 5V+ | +5V | +| 2 (blk) | DEBUG TX (OUT) | +3.3V | +| 3 (blk) | DEBUG RX (IN) | +3.3V | +| 4 (blk) | FMU_SWDIO | +3.3V | +| 5 (blk) | FMU_SWCLK | +3.3V | +| 6 (blk) | GND | GND | ## Supported Platforms / Airframes diff --git a/docs/en/flight_controller/gearup_airbrainh743.md b/docs/en/flight_controller/gearup_airbrainh743.md index 8fe379f606..98c14710d7 100644 --- a/docs/en/flight_controller/gearup_airbrainh743.md +++ b/docs/en/flight_controller/gearup_airbrainh743.md @@ -39,20 +39,20 @@ The pin order is different from the Pixhawk standard (compatible to the Betaflig Current UART configuration: -| UART | Device | Function | -| ------ | ---------- | ---------------------------- | -| USART1 | /dev/ttyS0 | Console/Debug | -| USART2 | /dev/ttyS1 | RC Input | -| USART3 | /dev/ttyS2 | TEL4 (DJI/MSP) | -| UART4 | /dev/ttyS3 | TEL1 | -| UART5 | /dev/ttyS4 | TEL2 | -| UART7 | /dev/ttyS5 | TEL3 (ESC Telemetry) | -| UART8 | /dev/ttyS6 | GPS1 | +| UART | Device | Function | +| ------ | ---------- | -------------------- | +| USART1 | /dev/ttyS0 | Console/Debug | +| USART2 | /dev/ttyS1 | RC Input | +| USART3 | /dev/ttyS2 | TEL4 (DJI/MSP) | +| UART4 | /dev/ttyS3 | TEL1 | +| UART5 | /dev/ttyS4 | TEL2 | +| UART7 | /dev/ttyS5 | TEL3 (ESC Telemetry) | +| UART8 | /dev/ttyS6 | GPS1 | ### Motor/Servo Outputs | Connector | Pin | Function | -| ----------| ------------------ | +| --------- | --- | ------------ | | ESC | M1 | Motor 1 | | ESC | M2 | Motor 2 | | ESC | M3 | Motor 3 | diff --git a/docs/en/flight_controller/kakuteh7-wing.md b/docs/en/flight_controller/kakuteh7-wing.md index 775eca078b..2546a5cc01 100644 --- a/docs/en/flight_controller/kakuteh7-wing.md +++ b/docs/en/flight_controller/kakuteh7-wing.md @@ -1,4 +1,4 @@ -# Holybro Kakute H743-Wing +# Holybro Kakute H743-Wing @@ -9,7 +9,6 @@ Contact the [manufacturer](https://holybro.com/) for hardware support or complia The [Holybro Kakute H743 Wing](https://holybro.com/products/kakute-h743-wing) is a fully featured flight controller specifically aimed at fixed-wing and VTOL applications. It has the STM32 H743 Processor running at 480 MHz and CAN Bus support, along with dual camera support & switch, ON/OFF Pit Switch, 5V, 6V/8V, 9V/12 BEC, and plug-and-play GPS, CAN, I2C ports. - ::: info This flight controller is [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md). ::: @@ -20,7 +19,6 @@ The board can be bought from one of the following shops (for example): - [Holybro](https://holybro.com/products/kakute-h743-wing) - ## Connectors and Pins | Pin | Function | PX4 default | @@ -69,15 +67,15 @@ Firmware can be manually installed in any of the normal ways: ## Serial Port Mapping -| UART | Device | Port | Default function | -| ------ | ---------- | --------------------- | ---------------- | -| USART1 | /dev/ttyS0 | GPS 1 | GPS1 | -| USART2 | /dev/ttyS1 | R2, T2 | GPS2 | -| USART3 | /dev/ttyS2 | R3, T3 | TELEM1 | -| UART5 | /dev/ttyS3 | R5, T5 | TELEM2 | -| USART6 | /dev/ttyS4 | R6, (T6) | RC input | -| UART7 | /dev/ttyS5 | R7, T7, RTS, CTS | TELEM3 | -| UART8 | /dev/ttyS6 | R8, T8 | Console | +| UART | Device | Port | Default function | +| ------ | ---------- | ---------------- | ---------------- | +| USART1 | /dev/ttyS0 | GPS 1 | GPS1 | +| USART2 | /dev/ttyS1 | R2, T2 | GPS2 | +| USART3 | /dev/ttyS2 | R3, T3 | TELEM1 | +| UART5 | /dev/ttyS3 | R5, T5 | TELEM2 | +| USART6 | /dev/ttyS4 | R6, (T6) | RC input | +| UART7 | /dev/ttyS5 | R7, T7, RTS, CTS | TELEM3 | +| UART8 | /dev/ttyS6 | R8, T8 | Console | ## Debug Port diff --git a/docs/en/flight_controller/pixhawk_series.md b/docs/en/flight_controller/pixhawk_series.md index cc92192d48..cf1fd037d3 100644 --- a/docs/en/flight_controller/pixhawk_series.md +++ b/docs/en/flight_controller/pixhawk_series.md @@ -102,21 +102,21 @@ At very high level, the main differences are: ### FMUv6 Comparison -| Feature | **FMUv6X-RT** | **FMUv6X** | **FMUv6C** | -| ------------------ | --------------------- | ----------------- | ------------------ | -| **FMU MCU** | NXP i.MX RT1176 | STM32H753 | STM32H743V | -| **RAM** | 2 MB | 1 MB | 1 MB | -| **Flash** | 64 MB Octal SPI | 2 MB internal | 2 MB internal | -| **IO MCU** | STM32F103 | STM32F103 | STM32F103 | -| **Secure Element** | NXP SE051 | NXP SE051 | Not supported | -| **PAB Standard** | Supported | Supported | Not supported | -| **Ethernet** | Supported | Supported | Not supported | -| **IMUs** | 3× | 3× | 2× | -| **Barometers** | 2× | 2× | 1× | -| **Magnetometer** | 1× | 1× | 1× | -| **FMU PWM** | 12× | 8× | 8× | -| **IO PWM** | 8× | 8× | 8× | -| **CAN Bus** | 3× | 2× | 2× | +| Feature | **FMUv6X-RT** | **FMUv6X** | **FMUv6C** | +| ------------------ | --------------- | ------------- | ------------- | +| **FMU MCU** | NXP i.MX RT1176 | STM32H753 | STM32H743V | +| **RAM** | 2 MB | 1 MB | 1 MB | +| **Flash** | 64 MB Octal SPI | 2 MB internal | 2 MB internal | +| **IO MCU** | STM32F103 | STM32F103 | STM32F103 | +| **Secure Element** | NXP SE051 | NXP SE051 | Not supported | +| **PAB Standard** | Supported | Supported | Not supported | +| **Ethernet** | Supported | Supported | Not supported | +| **IMUs** | 3× | 3× | 2× | +| **Barometers** | 2× | 2× | 1× | +| **Magnetometer** | 1× | 1× | 1× | +| **FMU PWM** | 12× | 8× | 8× | +| **IO PWM** | 8× | 8× | 8× | +| **CAN Bus** | 3× | 2× | 2× | ### Licensing and Trademarks diff --git a/docs/en/flight_controller/svehicle_e2.md b/docs/en/flight_controller/svehicle_e2.md index bbddcba59e..61629c8b6a 100644 --- a/docs/en/flight_controller/svehicle_e2.md +++ b/docs/en/flight_controller/svehicle_e2.md @@ -63,6 +63,7 @@ These flight controllers are [manufacturer supported](../flight_controller/autop Order from [S-Vehicle](https://svehicle.cn/). ## Radio Control + A Radio Control (RC) system is required if you want to manually control your vehicle (PX4 does not require a radio system for autonomous flight modes). You will need to select a compatible transmitter/receiver and then bind them so that they communicate (read the instructions that come with your specific transmitter/receiver). diff --git a/docs/en/flight_modes_fw/index.md b/docs/en/flight_modes_fw/index.md index 052bfe7dd3..74a7fe66f0 100644 --- a/docs/en/flight_modes_fw/index.md +++ b/docs/en/flight_modes_fw/index.md @@ -18,7 +18,7 @@ Manual-Easy: - [Altitude](../flight_modes_fw/altitude.md) — Easiest and safest _non-GPS_ manual mode. The only difference compared to _Position mode_ is that the pilot always directly controls the roll angle of the plane and there is no automatic course holding. - Altitude Cruise mode — It behaves exactly like _Altitude mode_, with the only difference being that the manual control failsafe can be disabled. This is done by setting the corresponding flag in [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT). In that case the current altitude, airspeed and heading (by leveling out the roll angle) are kept until the manual control link is regained or the mode is exited. -It is highly recommended to only disable the manual control loss failsafe for this mode if there is a stable data link connection to the vehicle at all times, or to enable the data link loss failsafe through [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT). + It is highly recommended to only disable the manual control loss failsafe for this mode if there is a stable data link connection to the vehicle at all times, or to enable the data link loss failsafe through [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT). - [Stabilized mode](../flight_modes_fw/stabilized.md) — The pilot directly commands the roll and pitch angle and the vehicle keeps the setpoint until the sticks are moved again. Thrust is directly set by the pilot. Turn coordination is still handled by the controller. @@ -35,6 +35,7 @@ Manual-Acrobatic Autonomous: All autonomous flight modes require a valid position estimate (GPS). Airspeed is actively controlled if an airspeed sensor is installed in any autonomous flight mode. + - [Hold](../flight_modes_fw/hold.md) — Vehicle circles around the GPS hold position at the current altitude. The mode can be used to pause a mission or to help regain control of a vehicle in an emergency. It can be activated with a pre-programmed RC switch or the QGroundControl Pause button. diff --git a/docs/en/flight_modes_fw/land.md b/docs/en/flight_modes_fw/land.md index 43d8ff9294..77a26d0666 100644 --- a/docs/en/flight_modes_fw/land.md +++ b/docs/en/flight_modes_fw/land.md @@ -24,6 +24,7 @@ Where possible, instead use [Return mode](../flight_modes_fw/return.md) with a p - The mode can be triggered using the [MAV_CMD_NAV_LAND](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LAND) MAVLink command, or by explicitly switching to Land mode. + ::: ## Technical Summary @@ -40,12 +41,12 @@ The vehicle will flare if configured to do so (see [Flaring](../flight_modes_fw/ Land mode behaviour can be configured using the parameters below. -| Parameter | Description | -| ----------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------- | -| [NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | The loiter radius that the controller tracks for the whole landing sequence. | -| [FW_LND_ANG](../advanced_config/parameter_reference.md#FW_LND_ANG) | The flight path angle setpoint. | -| [FW_LND_AIRSPD](../advanced_config/parameter_reference.md#FW_LND_AIRSPD) | The airspeed setpoint. | -| [FW_AIRSPD_FLP_SC](../advanced_config/parameter_reference.md#FW_AIRSPD_FLP_SC) | Factor applied to the minimum airspeed when flaps are fully deployed. Necessary if FW_LND_AIRSPD is below FW_AIRSPD_MIN. +| Parameter | Description | +| ----------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------ | +| [NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | The loiter radius that the controller tracks for the whole landing sequence. | +| [FW_LND_ANG](../advanced_config/parameter_reference.md#FW_LND_ANG) | The flight path angle setpoint. | +| [FW_LND_AIRSPD](../advanced_config/parameter_reference.md#FW_LND_AIRSPD) | The airspeed setpoint. | +| [FW_AIRSPD_FLP_SC](../advanced_config/parameter_reference.md#FW_AIRSPD_FLP_SC) | Factor applied to the minimum airspeed when flaps are fully deployed. Necessary if FW_LND_AIRSPD is below FW_AIRSPD_MIN. | ## See Also diff --git a/docs/en/flight_modes_fw/mission.md b/docs/en/flight_modes_fw/mission.md index 91f48a8300..f3ee6ee95f 100644 --- a/docs/en/flight_modes_fw/mission.md +++ b/docs/en/flight_modes_fw/mission.md @@ -28,7 +28,6 @@ Missions are uploaded onto a SD card that needs to be inserted **before** bootin At high level all vehicle types behave in the same way when MISSION mode is engaged: 1. If no mission is stored, or if PX4 has finished executing all mission commands, or if the [mission is not feasible](#mission-feasibility-checks): - - If flying the vehicle will loiter. - If landed the vehicle will "wait". @@ -163,9 +162,9 @@ Mission Items: - [MAV_CMD_DO_SET_CAMERA_ZOOM](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_ZOOM) - [MAV_CMD_DO_SET_CAMERA_FOCUS](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_FOCUS) - [MAV_CMD_DO_AUTOTUNE_ENABLE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_AUTOTUNE_ENABLE) - - Disabling autotune by setting `param1` to zero is currently not supported. To abort autotune during a mission, switch to another flight mode. - - Axis selection specified in the MAVLink message is ignored (`param2` must be set to 0). - Instead, the axis bitmask defined by [`FW_AT_AXES`](../advanced_config/parameter_reference.md#FW_AT_AXES) is used. + - Disabling autotune by setting `param1` to zero is currently not supported. To abort autotune during a mission, switch to another flight mode. + - Axis selection specified in the MAVLink message is ignored (`param2` must be set to 0). + Instead, the axis bitmask defined by [`FW_AT_AXES`](../advanced_config/parameter_reference.md#FW_AT_AXES) is used. GeoFence Definitions diff --git a/docs/en/flight_modes_mc/altitude.md b/docs/en/flight_modes_mc/altitude.md index 7d35590443..b08688caa0 100644 --- a/docs/en/flight_modes_mc/altitude.md +++ b/docs/en/flight_modes_mc/altitude.md @@ -43,8 +43,8 @@ The horizontal position of the vehicle can move due to wind (or pre-existing mom The mode is affected by the following parameters: -| Parameter | Description | -| ----------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | Maximum vertical ascent velocity. Default: 3 m/s. | -| [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | Maximum vertical descent velocity. Default: 1 m/s. | -| `MPC_XXXX` | Most of the MPC_xxx parameters affect flight behaviour in this mode (at least to some extent). For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | +| Parameter | Description | +| ----------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | Maximum vertical ascent velocity. Default: 3 m/s. | +| [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | Maximum vertical descent velocity. Default: 1 m/s. | +| `MPC_XXXX` | Most of the MPC_xxx parameters affect flight behaviour in this mode (at least to some extent). For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | diff --git a/docs/en/flight_modes_mc/follow_me.md b/docs/en/flight_modes_mc/follow_me.md index 08ff63687d..33b02a896e 100644 --- a/docs/en/flight_modes_mc/follow_me.md +++ b/docs/en/flight_modes_mc/follow_me.md @@ -115,7 +115,6 @@ The altitude control mode determine whether the vehicle altitude is relative to The relative distance to the drone to the target will change as you ascend and descend (use with care in hilly terrain). - `2D + Terrain` makes the drone follow at a fixed height relative to the terrain underneath it, using information from a distance sensor. - - If the vehicle does not have a distance sensor following will be identical to `2D tracking`. - Distance sensors aren't always accurate and vehicles may be "jumpy" when flying in this mode. - Note that that height is relative to the ground underneath the vehicle, not the follow target. @@ -163,7 +162,6 @@ The follow-me behavior can be configured using the following parameters: - This video demonstrates a Google-Earth view perspective, by adjusting the height to around 50 meters (high), distance to 1 meter (close). Which allows a perspective as shot from a satellite. ## Known Issues diff --git a/docs/en/flight_modes_mc/mission.md b/docs/en/flight_modes_mc/mission.md index 61e2358929..04e7ccf433 100644 --- a/docs/en/flight_modes_mc/mission.md +++ b/docs/en/flight_modes_mc/mission.md @@ -30,7 +30,6 @@ Missions are uploaded onto a SD card that needs to be inserted **before** bootin At high level all vehicle types behave in the same way when MISSION mode is engaged: 1. If no mission is stored, or if PX4 has finished executing all mission commands, or if the [mission is not feasible](#mission-feasibility-checks): - - If flying the vehicle will hold. - If landed the vehicle will "wait". @@ -167,8 +166,8 @@ Mission Items: - `MAV_CMD_NAV_VTOL_TAKEOFF.param2` (transition heading) is ignored. Instead the heading to the next waypoint is used for the transition heading. - [MAV_CMD_DO_AUTOTUNE_ENABLE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_AUTOTUNE_ENABLE) - - Disabling autotune by setting `param1` to zero is currently not supported. To abort autotune during a mission, switch to another flight mode. - - Axis selection specified in the MAVLink message is ignored (`param2` must be set to 0) . + - Disabling autotune by setting `param1` to zero is currently not supported. To abort autotune during a mission, switch to another flight mode. + - Axis selection specified in the MAVLink message is ignored (`param2` must be set to 0) . GeoFence Definitions diff --git a/docs/en/flight_modes_vtol/return.md b/docs/en/flight_modes_vtol/return.md index cfcccf68ae..46ec8ec1e4 100644 --- a/docs/en/flight_modes_vtol/return.md +++ b/docs/en/flight_modes_vtol/return.md @@ -47,7 +47,6 @@ If returning as a fixed-wing, the vehicle: A mission landing pattern for a VTOL vehicle consists of a [MAV_CMD_DO_LAND_START](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_LAND_START), one or more position waypoints, and a [MAV_CMD_NAV_VTOL_LAND](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_VTOL_LAND). - If the destination is a rally point or home it will: - - Loiter/spiral down to [RTL_DESCEND_ALT](#RTL_DESCEND_ALT). - Circle for a short time, as defined by [RTL_LAND_DELAY](#RTL_LAND_DELAY). - Yaw towards the destination (centre of loiter). diff --git a/docs/en/flight_stack/controller_diagrams.md b/docs/en/flight_stack/controller_diagrams.md index b5465d5072..26453c1361 100644 --- a/docs/en/flight_stack/controller_diagrams.md +++ b/docs/en/flight_stack/controller_diagrams.md @@ -13,24 +13,24 @@ The diagrams use the standard [PX4 notation](../contribute/notation.md) (and eac ![MC Controller Diagram](../../assets/diagrams/mc_control_arch.jpg) -* This is a standard cascaded control architecture. -* The controllers are a mix of P and PID controllers. -* Estimates come from [EKF2](../advanced_config/tuning_the_ecl_ekf.md). -* Depending on the mode, the outer (position) loop is bypassed (shown as a multiplexer after the outer loop). +- This is a standard cascaded control architecture. +- The controllers are a mix of P and PID controllers. +- Estimates come from [EKF2](../advanced_config/tuning_the_ecl_ekf.md). +- Depending on the mode, the outer (position) loop is bypassed (shown as a multiplexer after the outer loop). The position loop is only used when holding position or when the requested velocity in an axis is null. ### Multicopter Angular Rate Controller ![MC Rate Control Diagram](../../assets/diagrams/mc_angular_rate_diagram.jpg) -* K-PID controller. See [Rate Controller](../config_mc/pid_tuning_guide_multicopter.md#rate-controller) for more information. -* The integral authority is limited to prevent wind up. -* The outputs are limited (in the control allocation module), usually at -1 and 1. -* A Low Pass Filter (LPF) is used on the derivative path to reduce noise (the gyro driver provides a filtered derivative to the controller). +- K-PID controller. See [Rate Controller](../config_mc/pid_tuning_guide_multicopter.md#rate-controller) for more information. +- The integral authority is limited to prevent wind up. +- The outputs are limited (in the control allocation module), usually at -1 and 1. +- A Low Pass Filter (LPF) is used on the derivative path to reduce noise (the gyro driver provides a filtered derivative to the controller). ::: info The IMU pipeline is: - gyro data > apply calibration parameters > remove estimated bias > notch filter (`IMU_GYRO_NF0_BW` and `IMU_GYRO_NF0_FRQ`) > low-pass filter (`IMU_GYRO_CUTOFF`) > vehicle_angular_velocity (*filtered angular rate used by the P and I controllers*) > derivative -> low-pass filter (`IMU_DGYRO_CUTOFF`) > vehicle_angular_acceleration (*filtered angular acceleration used by the D controller*) + gyro data > apply calibration parameters > remove estimated bias > notch filter (`IMU_GYRO_NF0_BW` and `IMU_GYRO_NF0_FRQ`) > low-pass filter (`IMU_GYRO_CUTOFF`) > vehicle_angular_velocity (_filtered angular rate used by the P and I controllers_) > derivative -> low-pass filter (`IMU_DGYRO_CUTOFF`) > vehicle_angular_acceleration (_filtered angular acceleration used by the D controller_) ![IMU pipeline](../../assets/diagrams/px4_imu_pipeline.png) ::: @@ -41,51 +41,51 @@ The diagrams use the standard [PX4 notation](../contribute/notation.md) (and eac ![MC Angle Control Diagram](../../assets/diagrams/mc_angle_diagram.jpg) -* The attitude controller makes use of [quaternions](https://en.wikipedia.org/wiki/Quaternion). -* The controller is implemented from this [article](https://www.research-collection.ethz.ch/bitstream/handle/20.500.11850/154099/eth-7387-01.pdf). -* When tuning this controller, the only parameter of concern is the P gain. -* The rate command is saturated. +- The attitude controller makes use of [quaternions](https://en.wikipedia.org/wiki/Quaternion). +- The controller is implemented from this [article](https://www.research-collection.ethz.ch/bitstream/handle/20.500.11850/154099/eth-7387-01.pdf). +- When tuning this controller, the only parameter of concern is the P gain. +- The rate command is saturated. ### Multicopter Acceleration to Thrust and Attitude Setpoint Conversion -* The acceleration setpoints generated by the velocity controller will be converted to thrust and attitude setpoints. -* Converted acceleration setpoints will be saturated and prioritized in vertical and horizontal thrust. -* Thrust saturation is done after computing the corresponding thrust: - 1. Compute required vertical thrust (`thrust_z`) - 1. Saturate `thrust_z` with `MPC_THR_MAX` - 1. Saturate `thrust_xy` with `(MPC_THR_MAX^2 - thrust_z^2)^0.5` - -Implementation details can be found in `PositionControl.cpp` and `ControlMath.cpp`. +- The acceleration setpoints generated by the velocity controller will be converted to thrust and attitude setpoints. +- Converted acceleration setpoints will be saturated and prioritized in vertical and horizontal thrust. +- Thrust saturation is done after computing the corresponding thrust: + 1. Compute required vertical thrust (`thrust_z`) + 1. Saturate `thrust_z` with `MPC_THR_MAX` + 1. Saturate `thrust_xy` with `(MPC_THR_MAX^2 - thrust_z^2)^0.5` + +Implementation details can be found in `PositionControl.cpp` and `ControlMath.cpp`. ### Multicopter Velocity Controller ![MC Velocity Control Diagram](../../assets/diagrams/mc_velocity_diagram.png) -* PID controller to stabilise velocity. Commands an acceleration. -* The integrator includes an anti-reset windup (ARW) using a clamping method. -* The commanded acceleration is NOT saturated - a saturation will be applied to the converted thrust setpoints in combination with the maximum tilt angle. -* Horizontal gains set via parameter `MPC_XY_VEL_P_ACC`, `MPC_XY_VEL_I_ACC` and `MPC_XY_VEL_D_ACC`. -* Vertical gains set via parameter `MPC_Z_VEL_P_ACC`, `MPC_Z_VEL_I_ACC` and `MPC_Z_VEL_D_ACC`. +- PID controller to stabilise velocity. Commands an acceleration. +- The integrator includes an anti-reset windup (ARW) using a clamping method. +- The commanded acceleration is NOT saturated - a saturation will be applied to the converted thrust setpoints in combination with the maximum tilt angle. +- Horizontal gains set via parameter `MPC_XY_VEL_P_ACC`, `MPC_XY_VEL_I_ACC` and `MPC_XY_VEL_D_ACC`. +- Vertical gains set via parameter `MPC_Z_VEL_P_ACC`, `MPC_Z_VEL_I_ACC` and `MPC_Z_VEL_D_ACC`. ### Multicopter Position Controller ![MC Position Control Diagram](../../assets/diagrams/mc_position_diagram.png) -* Simple P controller that commands a velocity. -* The commanded velocity is saturated to keep the velocity in certain limits. See parameter `MPC_XY_VEL_MAX`. This parameter sets the maximum possible horizontal velocity. This differs from the maximum **desired** speed `MPC_XY_CRUISE` (autonomous modes) and `MPC_VEL_MANUAL` (manual position control mode). -* Horizontal P gain set via parameter `MPC_XY_P`. -* Vertical P gain set via parameter `MPC_Z_P`. - +- Simple P controller that commands a velocity. +- The commanded velocity is saturated to keep the velocity in certain limits. See parameter `MPC_XY_VEL_MAX`. This parameter sets the maximum possible horizontal velocity. This differs from the maximum **desired** speed `MPC_XY_CRUISE` (autonomous modes) and `MPC_VEL_MANUAL` (manual position control mode). +- Horizontal P gain set via parameter `MPC_XY_P`. +- Vertical P gain set via parameter `MPC_Z_P`. #### Combined Position and Velocity Controller Diagram ![MC Position Controller Diagram](../../assets/diagrams/px4_mc_position_controller_diagram.png) -* Mode dependent feedforwards (ff) - e.g. Mission mode trajectory generator (jerk-limited trajectory) computes position, velocity and acceleration setpoints. -* Acceleration setpoints (inertial frame) will be transformed (with yaw setpoint) into attitude setpoints (quaternion) and collective thrust setpoint. +- Mode dependent feedforwards (ff) - e.g. Mission mode trajectory generator (jerk-limited trajectory) computes position, velocity and acceleration setpoints. +- Acceleration setpoints (inertial frame) will be transformed (with yaw setpoint) into attitude setpoints (quaternion) and collective thrust setpoint. + ## Fixed-Wing Position Controller ### Total Energy Control System (TECS) @@ -117,7 +117,6 @@ An increase in pitch angle transfers kinetic to potential energy and a negative The control problem was therefore decoupled by transforming the initial setpoints into energy quantities which can be controlled independently. We use thrust to regulate the specific total energy of the vehicle and pitch maintain a specific balance between potential (height) and kinetic (speed) energy. - #### Total energy control loop ![Energy loop](../../assets/diagrams/TECS_throttle.png) @@ -130,7 +129,6 @@ We use thrust to regulate the specific total energy of the vehicle and pitch mai - The total energy of an aircraft is the sum of kinetic and potential energy: $$E_T = \frac{1}{2} m V_T^2 + m g h$$ @@ -178,7 +176,7 @@ The angular position of the control effectors (ailerons, elevators, rudders, ... Furthermore, since the control surfaces are more effective at high speed and less effective at low speed, the controller - tuned for cruise speed - is scaled using the airspeed measurements (if such a sensor is used). ::: info -If no airspeed sensor is used then gain scheduling for the FW attitude controller is disabled (it's open loop); no correction is/can be made in TECS using airspeed feedback. +If no airspeed sensor is used then gain scheduling for the FW attitude controller is disabled (it's open loop); no correction is/can be made in TECS using airspeed feedback. ::: The feedforward gain is used to compensate for aerodynamic damping. @@ -188,14 +186,12 @@ In order to keep a constant rate, this damping can be compensated using feedforw ### Turn coordination The roll and pitch controllers have the same structure and the longitudinal and lateral dynamics are assumed to be uncoupled enough to work independently. -The yaw controller, however, generates its yaw rate setpoint using the turn coordination constraint in order to minimize lateral acceleration, generated when the aircraft is slipping. The turn coordination algorithm is based solely on coordinated turn geometry calculation. +The yaw controller, however, generates its yaw rate setpoint using the turn coordination constraint in order to minimize lateral acceleration, generated when the aircraft is slipping. The turn coordination algorithm is based solely on coordinated turn geometry calculation. $$\dot{\Psi}_{sp} = \frac{g}{V_T} \tan{\phi_{sp}} \cos{\theta_{sp}}$$ The yaw rate controller also helps to counteract [adverse yaw effects](https://youtu.be/sNV_SDDxuWk) and to damp the [Dutch roll mode](https://en.wikipedia.org/wiki/Dutch_roll) by providing extra directional damping. - - ## VTOL Flight Controller ![VTOL Attitude Controller Diagram](../../assets/diagrams/VTOL_controller_diagram.png) @@ -212,12 +208,11 @@ The inputs into this block are called "virtual" as, depending on the current VTO For a standard and tilt-rotor VTOL, during transition the fixed-wing attitude controller produces the rate setpoints, which are then fed into the separate rate controllers, resulting in torque commands for the multicopter and fixed-wing actuators. For tailsitters, during transition the multicopter attitude controller is running. -The outputs of the VTOL attitude block are separate torque and force commands for the multicopter and fixed-wing actuators (two instances for `vehicle_torque_setpoint` and `vehicle_thrust_setpoint`). +The outputs of the VTOL attitude block are separate torque and force commands for the multicopter and fixed-wing actuators (two instances for `vehicle_torque_setpoint` and `vehicle_thrust_setpoint`). These are handled in an airframe-specific control allocation class. For more information on the tuning of the transition logic inside the VTOL block, see [VTOL Configuration](../config_vtol/index.md). - ### Airspeed Scaling The objective of this section is to explain with the help of equations why and how the output of the rate PI and feedforward (FF) controllers can be scaled with airspeed to improve the control performance. diff --git a/docs/en/flying/first_flight_guidelines.md b/docs/en/flying/first_flight_guidelines.md index 2aa3fd4bac..7facee2cb7 100644 --- a/docs/en/flying/first_flight_guidelines.md +++ b/docs/en/flying/first_flight_guidelines.md @@ -1,6 +1,6 @@ # First Flight Guidelines -Learning to fly is a lot of fun! +Learning to fly is a lot of fun! These guidelines are designed to ensure that your first flight experience is enjoyable, educational, and safe. ## Know the Law @@ -10,10 +10,10 @@ Familiarise yourself with the flight regulations in your area. ## Select a Good Location -Selecting the right location for your first flight is critical. +Selecting the right location for your first flight is critical. The main things to look for are: -- Make sure the space is open. +- Make sure the space is open. There should be no high trees, hills or buildings nearby, because those will impair the GNSS reception. - Make sure no people are within 100 m (300 feet). - Make sure there is nothing that you shouldn't crash onto within 100 m - no houses, structures, cars, water, corn fields (hard to find drones in). @@ -24,12 +24,12 @@ The main things to look for are: ## Bring a Pro -Bring someone with experience for your first flight. +Bring someone with experience for your first flight. Get them to help you to run through the pre-flight checks and let them intervene if something goes wrong! ## Plan the Flight -Plan the flight before taking off. +Plan the flight before taking off. Make sure you know the whole route and where/how the vehicle will land. ## Limit the Damage diff --git a/docs/en/flying/missions.md b/docs/en/flying/missions.md index 607ca605f7..7817fa9a2a 100644 --- a/docs/en/flying/missions.md +++ b/docs/en/flying/missions.md @@ -5,9 +5,7 @@ A mission is a predefined flight plan, which can be planned in QGroundControl an Missions typically include items for controlling taking off, flying a sequence of waypoints, capturing images and/or video, deploying cargo, and landing. QGroundControl allows you to plan missions using a fully manual approach, or you can use its more advanced features to plan ground area surveys, corridor surveys, or structure surveys. -This topic provides an overview of how to plan and fly missions. - - +This topic provides an overview of how to plan and fly missions. ## Planning Missions diff --git a/docs/en/flying/package_delivery_mission.md b/docs/en/flying/package_delivery_mission.md index 3ff6f87874..9ad16c403c 100644 --- a/docs/en/flying/package_delivery_mission.md +++ b/docs/en/flying/package_delivery_mission.md @@ -32,7 +32,6 @@ To create a package delivery mission (with a Gripper): 1. Create a normal mission with a `Takeoff` mission item, and additional waypoints for your required flight path. 1. Add a waypoint on the map for where you'd like to release the package. - - To drop the package while flying set an appropriate altitude for the waypoint (and ensure the waypoint is at a safe location to drop the package). - If you'd like to land the vehicle to make the delivery you will need to change the `Waypoint` to a `Land` mission item. @@ -48,7 +47,6 @@ To create a package delivery mission (with a Gripper): 1. Configure the action for the gripper in the editor. ![Gripper action setting](../../assets/flying/qgc_mission_plan_gripper_action_setting.png) - - Set it to "Release" in order to release the package. - The gripper ID does not need to be set for now. diff --git a/docs/en/flying/plan_safety_points.md b/docs/en/flying/plan_safety_points.md index dfca1f4087..311517c2c7 100644 --- a/docs/en/flying/plan_safety_points.md +++ b/docs/en/flying/plan_safety_points.md @@ -1,25 +1,26 @@ # Safety Points (Rally Points) Safety points are alternative [Return Mode](../flight_modes/return.md) destinations/landing points. -When enabled, the vehicle will choose the *closest return destination* of: home location, mission landing pattern or a *safety point*. +When enabled, the vehicle will choose the _closest return destination_ of: home location, mission landing pattern or a _safety point_. ![Safety Points](../../assets/qgc/plan/rally_point/rally_points.jpg) ## Creating/Defining Safety Points -Safety points are created in *QGroundControl* (which calls them "Rally Points"). +Safety points are created in _QGroundControl_ (which calls them "Rally Points"). At high level: + 1. Open **QGroundControl > Plan View** -1. Select the **Rally** tab/button on the *Plan Editor* (right of screen). +1. Select the **Rally** tab/button on the _Plan Editor_ (right of screen). 1. Select the **Rally Point** button on the toolbar (left of screen). 1. Click anywhere on the map to add a rally/safety point. - - The *Plan Editor* displays and lets you edit the current rally point (shown as a green **R** on the map). + - The _Plan Editor_ displays and lets you edit the current rally point (shown as a green **R** on the map). - You can select another rally point (shown as a more orange/yellow **R** on the map) to edit it instead. 1. Select the **Upload Required** button to upload the rally points (along with any [mission](../flying/missions.md) and [geofence](../flying/geofence.md)) to the vehicle. :::tip -More complete documentation can be found in the *QGroundControl User Guide*: [Plan View - Rally Points](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/plan_view/plan_rally_points.html). +More complete documentation can be found in the _QGroundControl User Guide_: [Plan View - Rally Points](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/plan_view/plan_rally_points.html). ::: ## Using Safety Points @@ -27,4 +28,5 @@ More complete documentation can be found in the *QGroundControl User Guide*: [Pl Safety points are not enabled by default (there are a number of different [Return Mode Types](../flight_modes/return.md#return_types)). To enable safety points: + 1. [Use the QGroundControl Parameter Editor](../advanced_config/parameters.md) to set parameter: [RTL_TYPE=3](../advanced_config/parameter_reference.md#RTL_TYPE). diff --git a/docs/en/flying/terrain_following_holding.md b/docs/en/flying/terrain_following_holding.md index fb4cc842f6..6ce0f46bdc 100644 --- a/docs/en/flying/terrain_following_holding.md +++ b/docs/en/flying/terrain_following_holding.md @@ -1,27 +1,27 @@ # Terrain Following/Holding -PX4 supports [Terrain Following](#terrain_following) and [Terrain Hold](#terrain_hold) in [Position](../flight_modes_mc/position.md) and [Altitude modes](../flight_modes_mc/altitude.md), on *multicopters* and *VTOL vehicles in MC mode* that have a [distance sensor](../sensor/rangefinders.md). +PX4 supports [Terrain Following](#terrain_following) and [Terrain Hold](#terrain_hold) in [Position](../flight_modes_mc/position.md) and [Altitude modes](../flight_modes_mc/altitude.md), on _multicopters_ and _VTOL vehicles in MC mode_ that have a [distance sensor](../sensor/rangefinders.md). ::: info PX4 does not "natively" support terrain following in missions. -*QGroundControl* can be used to define missions that *approximately* follow terrain (this just sets waypoint altitudes based on height above terrain, where terrain height at waypoints is obtained from a map database). +_QGroundControl_ can be used to define missions that _approximately_ follow terrain (this just sets waypoint altitudes based on height above terrain, where terrain height at waypoints is obtained from a map database). ::: ## Terrain Following -*Terrain following* enables a vehicle to automatically maintain a relatively constant height above ground level when traveling at low altitudes. +_Terrain following_ enables a vehicle to automatically maintain a relatively constant height above ground level when traveling at low altitudes. This is useful for avoiding obstacles and for maintaining constant height when flying over varied terrain (e.g. for aerial photography). :::tip -This feature can be enabled in [Position](../flight_modes_mc/position.md) and [Altitude modes](../flight_modes_mc/altitude.md), on *multicopters* and *VTOL vehicles in MC mode* that have a [distance sensor](../sensor/rangefinders.md). +This feature can be enabled in [Position](../flight_modes_mc/position.md) and [Altitude modes](../flight_modes_mc/altitude.md), on _multicopters_ and _VTOL vehicles in MC mode_ that have a [distance sensor](../sensor/rangefinders.md). ::: -When *terrain following* is enabled, PX4 uses the output of the EKF estimator to provide the altitude estimate, and the estimated terrain altitude (calculated from distance sensor measurements using another estimator) to provide the altitude setpoint. +When _terrain following_ is enabled, PX4 uses the output of the EKF estimator to provide the altitude estimate, and the estimated terrain altitude (calculated from distance sensor measurements using another estimator) to provide the altitude setpoint. As the distance to ground changes, the altitude setpoint adjusts to keep the height above ground constant. -At higher altitudes (when the estimator reports that the distance sensor data is invalid) the vehicle switches to *altitude following*, and will typically fly at a near-constant height above mean sea level (AMSL) using an absolute height sensor for altitude data. +At higher altitudes (when the estimator reports that the distance sensor data is invalid) the vehicle switches to _altitude following_, and will typically fly at a near-constant height above mean sea level (AMSL) using an absolute height sensor for altitude data. ::: info More precisely, the vehicle will use the available selected sources of altitude data as defined in [Using PX4's Navigation Filter (EKF2) > Height](../advanced_config/tuning_the_ecl_ekf.md#height). @@ -29,24 +29,23 @@ More precisely, the vehicle will use the available selected sources of altitude Terrain following is enabled by setting [MPC_ALT_MODE](../advanced_config/parameter_reference.md#MPC_ALT_MODE) to `1`. - ## Terrain Hold -*Terrain hold* uses a distance sensor to help a vehicle to better maintain a constant height above ground in altitude control modes, when horizontally stationary at low altitude. +_Terrain hold_ uses a distance sensor to help a vehicle to better maintain a constant height above ground in altitude control modes, when horizontally stationary at low altitude. This allows a vehicle to avoid altitude changes due to barometer drift or excessive barometer interference from rotor wash. ::: info -This feature can be enabled in [Position](../flight_modes_mc/position.md) and [Altitude modes](../flight_modes_mc/altitude.md), on *multicopters* and *VTOL vehicles in MC mode* that have a [distance sensor](../sensor/rangefinders.md). +This feature can be enabled in [Position](../flight_modes_mc/position.md) and [Altitude modes](../flight_modes_mc/altitude.md), on _multicopters_ and _VTOL vehicles in MC mode_ that have a [distance sensor](../sensor/rangefinders.md). ::: -When moving horizontally (`speed >` [MPC_HOLD_MAX_XY](../advanced_config/parameter_reference.md#MPC_HOLD_MAX_XY)), or above the altitude where the distance sensor is providing valid data, the vehicle will switch into *altitude following*. +When moving horizontally (`speed >` [MPC_HOLD_MAX_XY](../advanced_config/parameter_reference.md#MPC_HOLD_MAX_XY)), or above the altitude where the distance sensor is providing valid data, the vehicle will switch into _altitude following_. Terrain holding is enabled by setting [MPC_ALT_MODE](../advanced_config/parameter_reference.md#MPC_ALT_MODE) to `2`. ::: info -*Terrain hold* is implemented similarly to [terrain following](#terrain_following). +_Terrain hold_ is implemented similarly to [terrain following](#terrain_following). It uses the output of the EKF estimator to provide the altitude estimate, and the estimated terrain altitude (calculated from distance sensor measurements using a separate, single state terrain estimator) to provide the altitude setpoint. If the distance to ground changes due to external forces, the altitude setpoint adjusts to keep the height above ground constant. ::: diff --git a/docs/en/frames_plane/index.md b/docs/en/frames_plane/index.md index ccbdc9547a..6108b190f3 100644 --- a/docs/en/frames_plane/index.md +++ b/docs/en/frames_plane/index.md @@ -22,7 +22,6 @@ The linked sections instructions for assembling and configuring fixed-wing frame ## Videos - --- diff --git a/docs/en/frames_rover/index.md b/docs/en/frames_rover/index.md index 09492e324c..b3a705ed31 100644 --- a/docs/en/frames_rover/index.md +++ b/docs/en/frames_rover/index.md @@ -9,13 +9,12 @@ Maintainer volunteers, [contribution](../contribute/index.md) of new features, n ![Rovers](../../assets/airframes/rover/rovers.png) - PX4 provides support for the three most common types of rovers: -| Rover Type | Steering | +| Rover Type | Steering | | --------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [**Ackermann**](#ackermann) | Direction is controlled by pointing wheels in the direction of travel. This kind of steering is used on most commercial vehicles, including cars, trucks etc. | -| [**Differential**](#differential) | Direction is controlled by moving the left- and right-side wheels at different speeds. | -| [**Mecanum**](#mecanum) | Direction is controlled by moving each mecanum wheel individually at different speeds and in different directions. | +| [**Ackermann**](#ackermann) | Direction is controlled by pointing wheels in the direction of travel. This kind of steering is used on most commercial vehicles, including cars, trucks etc. | +| [**Differential**](#differential) | Direction is controlled by moving the left- and right-side wheels at different speeds. | +| [**Mecanum**](#mecanum) | Direction is controlled by moving each mecanum wheel individually at different speeds and in different directions. | The supported frames can be seen in [Airframes Reference > Rover](../airframes/airframe_reference.md#rover). diff --git a/docs/en/frames_vtol/standardvtol.md b/docs/en/frames_vtol/standardvtol.md index f6fab32ad4..d244912c52 100644 --- a/docs/en/frames_vtol/standardvtol.md +++ b/docs/en/frames_vtol/standardvtol.md @@ -4,9 +4,7 @@ A **Standard VTOL** is a [VTOL](../frames_vtol/index.md) that has _completely se ![Vertical Technologies: Deltaquad QuadPlane VTOL](../../assets/airframes/vtol/vertical_technologies_deltaquad/hero_small.png) -*Vertical Technologies: Deltaquad QuadPlane VTOL* - - +_Vertical Technologies: Deltaquad QuadPlane VTOL_ ## Videos diff --git a/docs/en/frames_vtol/tailsitter.md b/docs/en/frames_vtol/tailsitter.md index 7a393f3720..cddc2bfb1e 100644 --- a/docs/en/frames_vtol/tailsitter.md +++ b/docs/en/frames_vtol/tailsitter.md @@ -86,7 +86,6 @@ This section contains videos that are specific to Tailsitter VTOL (videos that a - ## Gallery
diff --git a/docs/en/frames_vtol/tiltrotor.md b/docs/en/frames_vtol/tiltrotor.md index 320e23a598..c3ba16af08 100644 --- a/docs/en/frames_vtol/tiltrotor.md +++ b/docs/en/frames_vtol/tiltrotor.md @@ -4,7 +4,6 @@ A **Tiltrotor VTOL** is a [VTOL](../frames_vtol/index.md) vehicle that has rotor ![Horizon Hobby E-flite Convergence](../../assets/airframes/vtol/eflite_convergence_pixfalcon/hero.jpg) - ## Builds - [Convergence Tiltrotor](../frames_vtol/vtol_tiltrotor_eflite_convergence_pixfalcon.md) diff --git a/docs/en/frames_vtol/vtol_tiltrotor_eflite_convergence_pixfalcon.md b/docs/en/frames_vtol/vtol_tiltrotor_eflite_convergence_pixfalcon.md index 4d81aa8625..36ea66ad45 100644 --- a/docs/en/frames_vtol/vtol_tiltrotor_eflite_convergence_pixfalcon.md +++ b/docs/en/frames_vtol/vtol_tiltrotor_eflite_convergence_pixfalcon.md @@ -4,20 +4,21 @@ The [E-Flite Convergence](https://youtu.be/HNedXQ_jhYo) can easily be converted There is not much space but it's enough for a [Pixfalcon](../flight_controller/pixfalcon.md) flight controller with GPS and telemetry. ::: info -The original Horizon Hobby *E-Flite Convergence* frame and [Pixfalcon](../flight_controller/pixfalcon.md) have been discontinued. +The original Horizon Hobby _E-Flite Convergence_ frame and [Pixfalcon](../flight_controller/pixfalcon.md) have been discontinued. Alternatives are provided in the [Purchase](#where-to-buy) section. ::: - ## Where to Buy Vehicle frame options: + - **WL Tech XK X450** - [AliExpress](https://www.aliexpress.com/item/1005001946025611.html) - **JJRC M02** - [Banggood (AU)](https://au.banggood.com/JJRC-M02-2_4G-6CH-450mm-Wingspan-EPO-Brushless-6-axis-Gyro-Aerobatic-RC-Airplane-RTF-3D-or-6G-Mode-Aircraft-p-1588201.html), [AliExpress](https://www.aliexpress.com/item/4001031497018.html) Flight controller options (): + - [Pixhawk 4 Mini](../flight_controller/pixhawk4_mini.md) - [Holybro Pixhawk Mini](../flight_controller/pixhawk_mini.md). - Any other compatible flight controller with small enough form-factor. @@ -25,6 +26,7 @@ Flight controller options (): ## Hardware Setup The vehicle needs 7 PWM signals for the motors and control surfaces: + - Motor (left/right/back) - Tilt servos (right/left) - Elevons (left/right) @@ -38,7 +40,6 @@ Note that left and right in the configuration screen and frame reference are def - ### Flight Controller The flight controller can be mounted at the same place the original autopilot was. @@ -58,14 +59,14 @@ That way the GPS can be put inside the body and is nicely stowed away without co ![Mount GPS](../../assets/airframes/vtol/eflite_convergence_pixfalcon/eflight_convergence_gps_mounting.jpg) - ## PX4 Configuration -Follow the [Standard Configuration](../config/index.md) in *QGroundControl* (radio, sensors, flight modes, etc.). +Follow the [Standard Configuration](../config/index.md) in _QGroundControl_ (radio, sensors, flight modes, etc.). The particular settings that are relevant to this vehicle are: + - [Airframe](../config/airframe.md) - - Select the airframe configuration **E-flite Convergence** under **VTOL Tiltrotor** and restart *QGroundControl*. + - Select the airframe configuration **E-flite Convergence** under **VTOL Tiltrotor** and restart _QGroundControl_. ![QGroundControl Vehicle Setting - Airframe selection E-Flight](../../assets/airframes/vtol/eflite_convergence_pixfalcon/qgc_setup_airframe.jpg) - [Flight Modes/Switches](../config/flight_mode.md) - As this is a VTOL vehicle, you must [assign an RC controller switch](../config/flight_mode.md#what-flight-modes-and-switches-should-i-set) for transitioning between multicopter and fixed-wing modes. diff --git a/docs/en/getting_started/flight_controller_selection.md b/docs/en/getting_started/flight_controller_selection.md index 92c300957d..04a27a42f2 100644 --- a/docs/en/getting_started/flight_controller_selection.md +++ b/docs/en/getting_started/flight_controller_selection.md @@ -33,7 +33,6 @@ Similarly, PX4 can also run natively Raspberry Pi (this approach is not generall - [Raspberry Pi 2/3 Navio2](../flight_controller/raspberry_pi_navio2.md) - [Raspberry Pi 2/3/4 PilotPi Shield](../flight_controller/raspberry_pi_pilotpi.md) - ## Commercial UAVs that can run PX4 PX4 is available on many popular commercial drone products, including some that ship with PX4 and others that can be updated with PX4 (allowing you to add mission planning and other PX4 Flight modes to your vehicle). diff --git a/docs/en/getting_started/led_meanings.md b/docs/en/getting_started/led_meanings.md index cdc86d5cbb..2e6e57e5e4 100644 --- a/docs/en/getting_started/led_meanings.md +++ b/docs/en/getting_started/led_meanings.md @@ -1,7 +1,8 @@ # LED Meanings (Pixhawk Series) [Pixhawk-series flight controllers](../flight_controller/pixhawk_series.md) use LEDs to indicate the current status of the vehicle. -- The [UI LED](#ui_led) provides user-facing status information related to *readiness for flight*. + +- The [UI LED](#ui_led) provides user-facing status information related to _readiness for flight_. - The [Status LEDs](#status_led) provide status for the PX4IO and FMU SoC. They indicate power, bootloader mode and activity, and errors. @@ -9,7 +10,7 @@ ## UI LED -The RGB *UI LED* indicates the current *readiness for flight* status of the vehicle. +The RGB _UI LED_ indicates the current _readiness for flight_ status of the vehicle. This is typically a superbright I2C peripheral, which may or may not be mounted on the flight controller board (i.e. FMUv4 does not have one on board, and typically uses an LED mounted on the GPS). The image below shows the relationship between LED and vehicle status. @@ -19,47 +20,45 @@ It is possible to have a GPS lock (Green LED) and still not be able to arm the v ::: :::tip -In the event of an error (blinking red), or if the vehicle can't achieve GPS lock (change from blue to green), check for more detailed status information in *QGroundControl* including calibration status, and errors messages reported by the [Preflight Checks (Internal)](../flying/pre_flight_checks.md). +In the event of an error (blinking red), or if the vehicle can't achieve GPS lock (change from blue to green), check for more detailed status information in _QGroundControl_ including calibration status, and errors messages reported by the [Preflight Checks (Internal)](../flying/pre_flight_checks.md). Also check that the GPS module is properly attached, Pixhawk is reading your GPS properly, and that the GPS is sending a proper GPS position. ::: ![LED meanings](../../assets/flight_controller/pixhawk_led_meanings.gif) +- **[Solid Blue] Armed, No GPS Lock:** Indicates vehicle has been armed and has no position lock from a GPS unit. + When vehicle is armed, PX4 will unlock control of the motors, allowing you to fly your drone. + As always, exercise caution when arming, as large propellers can be dangerous at high revolutions. + Vehicle cannot perform guided missions in this mode. -* **[Solid Blue] Armed, No GPS Lock:** Indicates vehicle has been armed and has no position lock from a GPS unit. -When vehicle is armed, PX4 will unlock control of the motors, allowing you to fly your drone. -As always, exercise caution when arming, as large propellers can be dangerous at high revolutions. -Vehicle cannot perform guided missions in this mode. +- **[Pulsing Blue] Disarmed, No GPS Lock:** Similar to above, but your vehicle is disarmed. + This means you will not be able to control motors, but all other subsystems are working. -* **[Pulsing Blue] Disarmed, No GPS Lock:** Similar to above, but your vehicle is disarmed. -This means you will not be able to control motors, but all other subsystems are working. +- **[Solid Green] Armed, GPS Lock:** Indicates vehicle has been armed and has a valid position lock from a GPS unit. + When vehicle is armed, PX4 will unlock control of the motors, allowing you to fly your drone. + As always, exercise caution when arming, as large propellers can be dangerous at high revolutions. + In this mode, vehicle can perform guided missions. -* **[Solid Green] Armed, GPS Lock:** Indicates vehicle has been armed and has a valid position lock from a GPS unit. -When vehicle is armed, PX4 will unlock control of the motors, allowing you to fly your drone. -As always, exercise caution when arming, as large propellers can be dangerous at high revolutions. -In this mode, vehicle can perform guided missions. - -* **[Pulsing Green] Disarmed, GPS Lock:** Similar to above, but your vehicle is disarmed. +- **[Pulsing Green] Disarmed, GPS Lock:** Similar to above, but your vehicle is disarmed. This means you will not be able to control motors, but all other subsystems including GPS position lock are working. -* **[Solid Purple] Failsafe Mode:** This mode will activate whenever vehicle encounters an issue during flight, -such as losing manual control, a critically low battery, or an internal error. -During failsafe mode, vehicle will attempt to return to its takeoff location, or may simply descend where it currently is. +- **[Solid Purple] Failsafe Mode:** This mode will activate whenever vehicle encounters an issue during flight, + such as losing manual control, a critically low battery, or an internal error. + During failsafe mode, vehicle will attempt to return to its takeoff location, or may simply descend where it currently is. -* **[Solid Amber] Low Battery Warning:** Indicates your vehicle's battery is running dangerously low. -After a certain point, vehicle will go into failsafe mode. However, this mode should signal caution that it's time to end -this flight. - -* **[Blinking Red] Error / Setup Required:** Indicates that your autopilot needs to be configured or calibrated before flying. -Attach your autopilot to a Ground Control Station to verify what the problem is. -If you have completed the setup process and autopilot still appears as red and flashing, there may be another error. +- **[Solid Amber] Low Battery Warning:** Indicates your vehicle's battery is running dangerously low. + After a certain point, vehicle will go into failsafe mode. However, this mode should signal caution that it's time to end + this flight. +- **[Blinking Red] Error / Setup Required:** Indicates that your autopilot needs to be configured or calibrated before flying. + Attach your autopilot to a Ground Control Station to verify what the problem is. + If you have completed the setup process and autopilot still appears as red and flashing, there may be another error. ## Status LED -Three *Status LEDs* provide status for the FMU SoC, and three more provide status for the PX4IO (if present). +Three _Status LEDs_ provide status for the FMU SoC, and three more provide status for the PX4IO (if present). They indicate power, bootloader mode and activity, and errors. ![Pixhawk 4](../../assets/flight_controller/pixhawk4/pixhawk4_status_leds.jpg) @@ -67,11 +66,11 @@ They indicate power, bootloader mode and activity, and errors. From power on, the FMU and PX4IO CPUs first run the bootloader (BL) and then the application (APP). The table below shows how the Bootloader and then APP use the LEDs to indicate condition. -Color | Label | Bootloader usage | APP usage ---- | --- | --- | --- -Blue | ACT (Activity) | Flutters when the bootloader is receiving data | Indication of ARM state -Red/Amber | B/E (In Bootloader / Error) | Flutters when in the bootloader | Indication of an ERROR -Green |PWR (Power) | Not used by bootloader | Indication of ARM state +| Color | Label | Bootloader usage | APP usage | +| --------- | --------------------------- | ---------------------------------------------- | ----------------------- | +| Blue | ACT (Activity) | Flutters when the bootloader is receiving data | Indication of ARM state | +| Red/Amber | B/E (In Bootloader / Error) | Flutters when in the bootloader | Indication of an ERROR | +| Green | PWR (Power) | Not used by bootloader | Indication of ARM state | ::: info The LED labels shown above are commonly used, but might differ on some boards. @@ -79,11 +78,11 @@ The LED labels shown above are commonly used, but might differ on some boards. More detailed information for how to interpret the LEDs is given below (where "x" means "any state") -Red/Amber | Blue | Green | Meaning ---- | --- | --- | --- -10Hz | x | x | Overload CPU load > 80%, or RAM usage > 98% -OFF | x | x | Overload CPU load <= 80%, or RAM usage <= 98% -NA | OFF | 4 Hz| actuator_armed->armed && failsafe -NA | ON | 4 Hz | actuator_armed->armed && !failsafe -NA | OFF |1 Hz | !actuator_armed-> armed && actuator_armed->ready_to_arm -NA | OFF |10 Hz | !actuator_armed->armed && !actuator_armed->ready_to_arm +| Red/Amber | Blue | Green | Meaning | +| --------- | ---- | ----- | ------------------------------------------------------- | +| 10Hz | x | x | Overload CPU load > 80%, or RAM usage > 98% | +| OFF | x | x | Overload CPU load <= 80%, or RAM usage <= 98% | +| NA | OFF | 4 Hz | actuator_armed->armed && failsafe | +| NA | ON | 4 Hz | actuator_armed->armed && !failsafe | +| NA | OFF | 1 Hz | !actuator_armed-> armed && actuator_armed->ready_to_arm | +| NA | OFF | 10 Hz | !actuator_armed->armed && !actuator_armed->ready_to_arm | diff --git a/docs/en/getting_started/tunes.md b/docs/en/getting_started/tunes.md index 15bc693b53..4615c101b1 100644 --- a/docs/en/getting_started/tunes.md +++ b/docs/en/getting_started/tunes.md @@ -9,16 +9,16 @@ The set of standard sounds are listed below. You can search for tune use using the string `TUNE_ID_name`(e.g. `TUNE_ID_PARACHUTE_RELEASE) ::: - ## Boot/Startup These tunes are played during the boot sequence. - + #### Startup Tone + - microSD card successfully mounted (during boot). @@ -26,36 +26,37 @@ These tunes are played during the boot sequence. #### Error Tune + - Hard fault has caused a system reboot. - System set to use PX4IO but no IO present. - UAVCAN is enabled but driver can't start. -- SITL/HITL enabled but *pwm_out_sim* driver can't start. +- SITL/HITL enabled but _pwm_out_sim_ driver can't start. - FMU startup failed. - #### Make File System + -- Formatting microSD card. +- Formatting microSD card. - Mounting failed (if formatting succeeds boot sequence will try to mount again). - No microSD card. - #### Format Failed + - Formatting microSD card failed (following previous attempt to mount card). - -#### Program PX4IO +#### Program PX4IO + - Starting to program PX4IO. @@ -63,6 +64,7 @@ These tunes are played during the boot sequence. #### Program PX4IO Success + - PX4IO programming succeeded. @@ -70,21 +72,23 @@ These tunes are played during the boot sequence. #### Program PX4IO Fail + - PX4IO programming failed. - PX4IO couldn't start. - AUX Mixer not found. - ## Operational These tones/tunes are emitted during normal operation. + #### Error Tune + - RC Loss @@ -92,6 +96,7 @@ These tones/tunes are emitted during normal operation. #### Notify Positive Tone + - Calibration succeeded. @@ -102,6 +107,7 @@ These tones/tunes are emitted during normal operation. #### Notify Neutral Tone + - Mission is valid and has no warnings. @@ -111,6 +117,7 @@ These tones/tunes are emitted during normal operation. #### Notify Negative Tone + - Calibration failed. @@ -123,6 +130,7 @@ These tones/tunes are emitted during normal operation. #### Arming Warning + - Vehicle is now armed. @@ -130,6 +138,7 @@ These tones/tunes are emitted during normal operation. #### Arming Failure Tune + - Arming failed @@ -137,6 +146,7 @@ These tones/tunes are emitted during normal operation. #### Battery Warning Slow + - Low battery warning ([failsafe](../config/safety.md#battery-level-failsafe)). @@ -144,27 +154,29 @@ These tones/tunes are emitted during normal operation. #### Battery Warning Fast + - Critical low battery warning ([failsafe](../config/safety.md#battery-level-failsafe)). - #### GPS Warning Slow + #### Parachute Release + - Parachute release triggered. - #### Single Beep + - Magnetometer/Compass calibration: Notify user to start rotating vehicle. @@ -172,6 +184,7 @@ These tones/tunes are emitted during normal operation. #### Home Set Tune + - Home position initialised (first time only). diff --git a/docs/en/getting_started/vehicle_status.md b/docs/en/getting_started/vehicle_status.md index 9fed271f74..b77083e876 100644 --- a/docs/en/getting_started/vehicle_status.md +++ b/docs/en/getting_started/vehicle_status.md @@ -7,6 +7,6 @@ In addition, PX4 provides more fine-grained information about readiness to fly i The LED, tune, and GCS notifications are linked below: -* [LED Meanings](../getting_started/led_meanings.md) -* [Tune/Sound Meanings](../getting_started/tunes.md) -* [QGroundControl Flight-Readiness Status](../flying/pre_flight_checks.md) +- [LED Meanings](../getting_started/led_meanings.md) +- [Tune/Sound Meanings](../getting_started/tunes.md) +- [QGroundControl Flight-Readiness Status](../flying/pre_flight_checks.md) diff --git a/docs/en/gps_compass/rtk_gps.md b/docs/en/gps_compass/rtk_gps.md index 29e2fe5358..9b12190bdc 100644 --- a/docs/en/gps_compass/rtk_gps.md +++ b/docs/en/gps_compass/rtk_gps.md @@ -20,45 +20,45 @@ The RTK compatible devices below that are expected to work with PX4 (it omits di The table indicates devices that also output yaw, and that can provide yaw when two on-vehicle units are used. It also highlights devices that connect via the CAN bus, and those which support PPK (Post-Processing Kinematic). -| Device | GPS | Compass | [DroneCAN] | [GPS Yaw] | PPK | -| :-------------------------------------------------------------------------------------------------------- | :------------------: | :------: | :--------: | :-----------------------: | :-: | -| [ARK G5 RTK GPS](../dronecan/ark_g5_rtk_gps.md) | [mosaic-G5 P3] | IIS2MDC | ✓ | | | -| [ARK G5 RTK HEADING GPS](../dronecan/ark_g5_rtk_heading_gps.md) | [mosaic-G5 P3H] | IIS2MDC | ✓ | [Heading Capability][mosaic-G5 P3H] | | -| [ARK RTK GPS](../dronecan/ark_rtk_gps.md) | F9P | BMM150 | ✓ | [Dual F9P] | | -| [ARK RTK GPS L1 L5](../dronecan/ark_rtk_gps_l1_l2.md) | F9P | BMM150 | ✓ | | | -| [ARK MOSAIC-X5 RTK GPS](../dronecan/ark_mosaic__rtk_gps.md) | Mosaic-X5 | IIS2MDC | ✓ | [Septentrio Dual Antenna] | | -| [ARK X20 RTK GPS](../dronecan/ark_x20_rtk_gps.md) | X20P | IIS2MDC | ✓ | | | -| [CUAV C-RTK GPS](../gps_compass/rtk_gps_cuav_c-rtk.md) | M8P/M8N | ✓ | | | | -| [CUAV C-RTK2](../gps_compass/rtk_gps_cuav_c-rtk2.md) | F9P | ✓ | | [Dual F9P] | | -| [CUAV C-RTK 9Ps GPS](../gps_compass/rtk_gps_cuav_c-rtk-9ps.md) | F9P | RM3100 | | [Dual F9P] | | -| [CUAV C-RTK2 PPK/RTK GNSS](../gps_compass/rtk_gps_cuav_c-rtk.md) | F9P | RM3100 | | | ✓ | -| [CubePilot Here+ RTK GPS](../gps_compass/rtk_gps_hex_hereplus.md) | M8P | HMC5983 | | | | -| [CubePilot Here3 CAN GNSS GPS (M8N)](https://www.cubepilot.org/#/here/here3) | M8P | ICM20948 | ✓ | | | -| [Drotek SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | RM3100 | | [Dual F9P] | | -| [DATAGNSS NANO HRTK Receiver](../gps_compass/rtk_gps_datagnss_nano_hrtk.md) | [D10P] | IST8310 | | ✘ | | -| [DATAGNSS GEM1305 RTK Receiver](../gps_compass/rtk_gps_gem1305.md) | TAU951M | IST8310 | | ✘ | | -| [Femtones MINI2 Receiver](../gps_compass/rtk_gps_fem_mini2.md) | FB672, FB6A0 | ✓ | | | | -| [Freefly RTK GPS](../gps_compass/rtk_gps_freefly.md) | F9P | IST8310 | | | | -| [Holybro H-RTK ZED-F9P RTK Rover (DroneCAN variant)](../dronecan/holybro_h_rtk_zed_f9p_gps.md) | F9P | RM3100 | ✓ | [Dual F9P] | | -| [Holybro H-RTK ZED-F9P RTK Rover](https://holybro.com/collections/h-rtk-gps/products/h-rtk-zed-f9p-rover) | F9P | RM3100 | | [Dual F9P] | | -| [Holybro H-RTK F9P Ultralight](https://holybro.com/products/h-rtk-f9p-ultralight) | F9P | IST8310 | | [Dual F9P] | | -| [Holybro H-RTK F9P Helical or Base](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | [Dual F9P] | | -| [Holybro DroneCAN H-RTK F9P Helical](https://holybro.com/products/dronecan-h-rtk-f9p-helical) | F9P | BMM150 | ✓ | [Dual F9P] | | -| [Holybro H-RTK F9P Rover Lite](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | | | -| [Holybro DroneCAN H-RTK F9P Rover](https://holybro.com/products/dronecan-h-rtk-f9p-rover) | F9P | BMM150 | | [Dual F9P] | | -| [Holybro H-RTK M8P GNSS](../gps_compass/rtk_gps_holybro_h-rtk-m8p.md) | M8P | IST8310 | | | | -| [Holybro H-RTK Unicore UM982 GPS](../gps_compass/rtk_gps_holybro_unicore_um982.md) | UM982 | IST8310 | | [Unicore Dual Antenna] | | -| [LOCOSYS Hawk R1](../gps_compass/rtk_gps_locosys_r1.md) | MC-1612-V2b | | | | | -| [LOCOSYS Hawk R2](../gps_compass/rtk_gps_locosys_r2.md) | MC-1612-V2b | IST8310 | | | | -| [mRo u-blox ZED-F9 RTK L1/L2 GPS](https://store.mrobotics.io/product-p/m10020d.htm) | F9P | ✓ | | [Dual F9P] | | -| [Navisys L1/L2 ZED-F9P RTK - Base only](https://www.navisys.com.tw/productdetail?name=GR901&class=RTK) | F9P | | | | | -| [RaccoonLab L1/L2 ZED-F9P][RaccoonLab L1/L2 ZED-F9P] | F9P | RM3100 | ✓ | | | -| [RaccoonLab L1/L2 ZED-F9P with external antenna][RaccnLabL1L2ZED-F9P ext_ant] | F9P | RM3100 | ✓ | | | -| [Septentrio AsteRx-m3 Pro](../gps_compass/septentrio_asterx-rib.md) | AsteRx | ✓ | | [Septentrio Dual Antenna] | ✓ | -| [Septentrio mosaic-go](../gps_compass/septentrio_mosaic-go.md) | mosaic X5 / mosaic H | ✓ | | [Septentrio Dual Antenna] | ✓ | -| [SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | ✓ | | [Dual F9P] | | -| [SparkFun GPS-RTK2 Board - ZED-F9P](https://www.sparkfun.com/products/15136) | F9P | ✓ | | [Dual F9P] | | -| [Trimble MB-Two](../gps_compass/rtk_gps_trimble_mb_two.md) | F9P | ✓ | | ✓ | | +| Device | GPS | Compass | [DroneCAN] | [GPS Yaw] | PPK | +| :-------------------------------------------------------------------------------------------------------- | :------------------: | :------: | :--------: | :---------------------------------: | :-: | +| [ARK G5 RTK GPS](../dronecan/ark_g5_rtk_gps.md) | [mosaic-G5 P3] | IIS2MDC | ✓ | | | +| [ARK G5 RTK HEADING GPS](../dronecan/ark_g5_rtk_heading_gps.md) | [mosaic-G5 P3H] | IIS2MDC | ✓ | [Heading Capability][mosaic-G5 P3H] | | +| [ARK RTK GPS](../dronecan/ark_rtk_gps.md) | F9P | BMM150 | ✓ | [Dual F9P] | | +| [ARK RTK GPS L1 L5](../dronecan/ark_rtk_gps_l1_l2.md) | F9P | BMM150 | ✓ | | | +| [ARK MOSAIC-X5 RTK GPS](../dronecan/ark_mosaic__rtk_gps.md) | Mosaic-X5 | IIS2MDC | ✓ | [Septentrio Dual Antenna] | | +| [ARK X20 RTK GPS](../dronecan/ark_x20_rtk_gps.md) | X20P | IIS2MDC | ✓ | | | +| [CUAV C-RTK GPS](../gps_compass/rtk_gps_cuav_c-rtk.md) | M8P/M8N | ✓ | | | | +| [CUAV C-RTK2](../gps_compass/rtk_gps_cuav_c-rtk2.md) | F9P | ✓ | | [Dual F9P] | | +| [CUAV C-RTK 9Ps GPS](../gps_compass/rtk_gps_cuav_c-rtk-9ps.md) | F9P | RM3100 | | [Dual F9P] | | +| [CUAV C-RTK2 PPK/RTK GNSS](../gps_compass/rtk_gps_cuav_c-rtk.md) | F9P | RM3100 | | | ✓ | +| [CubePilot Here+ RTK GPS](../gps_compass/rtk_gps_hex_hereplus.md) | M8P | HMC5983 | | | | +| [CubePilot Here3 CAN GNSS GPS (M8N)](https://www.cubepilot.org/#/here/here3) | M8P | ICM20948 | ✓ | | | +| [Drotek SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | RM3100 | | [Dual F9P] | | +| [DATAGNSS NANO HRTK Receiver](../gps_compass/rtk_gps_datagnss_nano_hrtk.md) | [D10P] | IST8310 | | ✘ | | +| [DATAGNSS GEM1305 RTK Receiver](../gps_compass/rtk_gps_gem1305.md) | TAU951M | IST8310 | | ✘ | | +| [Femtones MINI2 Receiver](../gps_compass/rtk_gps_fem_mini2.md) | FB672, FB6A0 | ✓ | | | | +| [Freefly RTK GPS](../gps_compass/rtk_gps_freefly.md) | F9P | IST8310 | | | | +| [Holybro H-RTK ZED-F9P RTK Rover (DroneCAN variant)](../dronecan/holybro_h_rtk_zed_f9p_gps.md) | F9P | RM3100 | ✓ | [Dual F9P] | | +| [Holybro H-RTK ZED-F9P RTK Rover](https://holybro.com/collections/h-rtk-gps/products/h-rtk-zed-f9p-rover) | F9P | RM3100 | | [Dual F9P] | | +| [Holybro H-RTK F9P Ultralight](https://holybro.com/products/h-rtk-f9p-ultralight) | F9P | IST8310 | | [Dual F9P] | | +| [Holybro H-RTK F9P Helical or Base](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | [Dual F9P] | | +| [Holybro DroneCAN H-RTK F9P Helical](https://holybro.com/products/dronecan-h-rtk-f9p-helical) | F9P | BMM150 | ✓ | [Dual F9P] | | +| [Holybro H-RTK F9P Rover Lite](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | | | +| [Holybro DroneCAN H-RTK F9P Rover](https://holybro.com/products/dronecan-h-rtk-f9p-rover) | F9P | BMM150 | | [Dual F9P] | | +| [Holybro H-RTK M8P GNSS](../gps_compass/rtk_gps_holybro_h-rtk-m8p.md) | M8P | IST8310 | | | | +| [Holybro H-RTK Unicore UM982 GPS](../gps_compass/rtk_gps_holybro_unicore_um982.md) | UM982 | IST8310 | | [Unicore Dual Antenna] | | +| [LOCOSYS Hawk R1](../gps_compass/rtk_gps_locosys_r1.md) | MC-1612-V2b | | | | | +| [LOCOSYS Hawk R2](../gps_compass/rtk_gps_locosys_r2.md) | MC-1612-V2b | IST8310 | | | | +| [mRo u-blox ZED-F9 RTK L1/L2 GPS](https://store.mrobotics.io/product-p/m10020d.htm) | F9P | ✓ | | [Dual F9P] | | +| [Navisys L1/L2 ZED-F9P RTK - Base only](https://www.navisys.com.tw/productdetail?name=GR901&class=RTK) | F9P | | | | | +| [RaccoonLab L1/L2 ZED-F9P][RaccoonLab L1/L2 ZED-F9P] | F9P | RM3100 | ✓ | | | +| [RaccoonLab L1/L2 ZED-F9P with external antenna][RaccnLabL1L2ZED-F9P ext_ant] | F9P | RM3100 | ✓ | | | +| [Septentrio AsteRx-m3 Pro](../gps_compass/septentrio_asterx-rib.md) | AsteRx | ✓ | | [Septentrio Dual Antenna] | ✓ | +| [Septentrio mosaic-go](../gps_compass/septentrio_mosaic-go.md) | mosaic X5 / mosaic H | ✓ | | [Septentrio Dual Antenna] | ✓ | +| [SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | ✓ | | [Dual F9P] | | +| [SparkFun GPS-RTK2 Board - ZED-F9P](https://www.sparkfun.com/products/15136) | F9P | ✓ | | [Dual F9P] | | +| [Trimble MB-Two](../gps_compass/rtk_gps_trimble_mb_two.md) | F9P | ✓ | | ✓ | | @@ -150,7 +150,6 @@ The RTK GPS connection is essentially plug and play: ![survey-in](../../assets/qgc/setup/rtk/qgc_rtk_survey-in.png) 1. Once Survey-in completes: - - The RTK GPS icon changes to white and _QGroundControl_ starts to stream position data to the vehicle: ![RTK streaming](../../assets/qgc/setup/rtk/qgc_rtk_streaming.png) diff --git a/docs/en/log/flight_review.md b/docs/en/log/flight_review.md index a9e8ccd318..49d2d5c240 100644 --- a/docs/en/log/flight_review.md +++ b/docs/en/log/flight_review.md @@ -36,6 +36,7 @@ For the rate controller in particular, it is useful to enable the high-rate logg Vibration is one of the most common problems for multirotor vehicles. High vibration levels can lead to: + - less efficient flight and reduced flight time - the motors can heat up - increased material wearout @@ -45,7 +46,7 @@ High vibration levels can lead to: It is therefore important to keep an eye on the vibration levels and improve the setup if needed. -There is a point where vibration levels are clearly too high, and generally lower vibration levels are better. +There is a point where vibration levels are clearly too high, and generally lower vibration levels are better. However there is a broad range between 'everything is ok' and 'the levels are too high'. This range depends on a number of factors, including vehicle size - as larger vehicles have higher inertia, allowing for more software filtering (at the same time the vibrations on larger vehicles are of lower frequency). @@ -61,7 +62,7 @@ It is worth looking at multiple charts when analyzing vibration (different chart You need to enable the high-rate logging profile ([SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE)) to see this plot. ::: -This graph shows a frequency plot for the roll, pitch and yaw axis based on the actuator controls signal (the PID output from the rate controller). +This graph shows a frequency plot for the roll, pitch and yaw axis based on the actuator controls signal (the PID output from the rate controller). It helps to identify frequency peaks and configuring the software filters. There should only be a single peak at the lowest end (below around 20 Hz), the rest should be low and flat. @@ -96,7 +97,6 @@ This example shows a peak in frequency close to 50 Hz (in this case due to "loos ![Vibrations in landing gear - FFT plot](../../assets/flight_log_analysis/flight_review/vibrations_landing_gear_actuator_controls_fft.png) - ### Acceleration Power Spectral Density This is a 2D frequency plot showing the frequency response of the raw accelerometer data over time (it displays the sum for the x, y and z axis). @@ -104,12 +104,12 @@ The more yellow an area is, the higher the frequency response at that time and f Ideally only the lowest part up to a few Hz is yellow, and the rest is mostly green or blue. - #### Examples: Good Vibration [QAV-R 5" Racer](../frames_multicopter/qav_r_5_kiss_esc_racer.md) frame (excellent vibration). ![Low vibration QAV-R 5 Racer - spectral density plot](../../assets/flight_log_analysis/flight_review/vibrations_good_spectral.png) + DJI F450 frame (good vibration). @@ -122,7 +122,6 @@ Above you can see the blade passing frequency of the propellers at around 100 Hz S500 frame: ![Vibration S500 - spectral density plot](../../assets/flight_log_analysis/flight_review/vibrations_s500_spectral.png) - #### Examples: Bad Vibration The strong yellow lines at around 100Hz indicate a potential issue that requires further investigation (starting with a review of the other charts). @@ -138,7 +137,6 @@ With the default filter settings of 80 Hz vibrations at 50 Hz will not be filter ![Vibrations in landing gear - spectral density plot](../../assets/flight_log_analysis/flight_review/vibrations_landing_gear_spectral.png) - Extremely high (unsafe) vibration! Note that the graph is almost completely yellow. :::warning @@ -147,13 +145,12 @@ You should not fly with such high vibration levels. ![Exceedingly high vibration in spectral density plot](../../assets/flight_log_analysis/flight_review/vibrations_exceedingly_high_spectral.png) - ### Raw Acceleration -This graph shows the raw accelerometer measurements for the x, y and z axis. +This graph shows the raw accelerometer measurements for the x, y and z axis. Ideally each line is thin and clearly shows the vehicle's accelerations. -As a rule of thumb if the z-axis graph is touching the x/y-axis graph during hover or slow flight, the vibration levels are too high. +As a rule of thumb if the z-axis graph is touching the x/y-axis graph during hover or slow flight, the vibration levels are too high. :::tip The best way to use this graph is to zoom in a bit to a part where the vehicle is hovering. @@ -170,7 +167,6 @@ DJI F450 frame (good vibration). - #### Examples: Bad Vibration @@ -179,18 +175,15 @@ This is at the limit where it starts to negatively affect flight performance. ![Borderline vibration S500 x, y - raw accel. plot](../../assets/flight_log_analysis/flight_review/vibrations_s500_accel.png) - Vibration too high. Note how the graph of the z-axis overlaps with the x/y-axis graph: ![Vibrations in landing gear - raw accel. plot](../../assets/flight_log_analysis/flight_review/vibrations_landing_gear_accel.png) - Vibration levels are too high. Note how the graph of the z-axis overlaps with the x/y-axis graph: ![High vibration in raw accel. plot](../../assets/flight_log_analysis/flight_review/vibrations_too_high_accel.png) - -Very high (unsafe) vibration levels. +Very high (unsafe) vibration levels. :::warning You should not fly with such high vibration levels. @@ -198,7 +191,6 @@ You should not fly with such high vibration levels. ![Exceedingly high vibration in raw accel. plot](../../assets/flight_log_analysis/flight_review/vibrations_exceedingly_high_accel.png) - ### Raw High-rate IMU Data Plots @@ -207,16 +199,17 @@ For an in-depth analysis there is an option to log the raw IMU data at full rate This allows inspection of much higher frequencies than with normal logging, which can help when selecting vibration mounts or configuring low-pass and notch filters appropriately. To use it, some parameters need to be changed: + - Set [IMU_GYRO_RATEMAX](../advanced_config/parameter_reference.md#IMU_GYRO_RATEMAX) to 400. - This ensures that the raw sensor data is more efficiently packed when sent from the sensor to the rest of the system, and reduces the log size (without reducing useful data). + This ensures that the raw sensor data is more efficiently packed when sent from the sensor to the rest of the system, and reduces the log size (without reducing useful data). - Use a good SD card, as the IMU data requires a high logging bandwidth (Flight Review will show dropouts if the logging rate gets too high). - + :::tip See [Logging > SD Cards](../dev_log/logging.md#sd-cards) for a comparison of popular SD card. ::: - + - Enable either the gyro or accel high-rate FIFO profile in [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) and disable the rest of the entries. If you are using a really good SD card (seeing few/no dropouts), you can: - either enable both accel and gyro profiles @@ -244,17 +237,16 @@ Often a source of vibration (or combination of multiple sources) cannot be ident In this case the vehicle should be inspected. [Vibration Isolation](../assembly/vibration_isolation.md) explains some basic things you can check (and do) to reduce vibration levels. - - ## Actuator Outputs -The *Actuator Outputs* graph shows the signals that are sent to the individual actuators (motors/servos). +The _Actuator Outputs_ graph shows the signals that are sent to the individual actuators (motors/servos). Generally it is in the range between the minimum and maximum configured PWM values (e.g. from 1000 to 2000). This is an example for a quadrotor where everything is OK (all of the signals are within the range, approximately overlap each other, and are not too noisy): ![Good actuator outputs](../../assets/flight_log_analysis/flight_review/actuator_outputs_good.png) The plot can help to identify different problems: + - If one or more of the signals is at the maximum over a longer time, it means the controller runs into **saturation**. It is not necessarily a problem, for example when flying at full throttle this is expected. But if it happens for example during a mission, it's an indication that the vehicle is overweight for the amount of thrust that it can provide. @@ -270,20 +262,20 @@ The plot can help to identify different problems: This is an example from a hexarotor: motors 1, 3 and 6 run at higher thrust: ![Hexrotor imbalanced actuator outputs](../../assets/flight_log_analysis/flight_review/actuator_outputs_hex_imbalanced.png) + - If the signals look very **noisy** (with high amplitudes), it can have two causes: sensor noise or vibrations passing through the controller (this shows up in other plots as well, see previous section) or too high PID gains. This is an extreme example: ![Noisy actuator outputs - extreme case](../../assets/flight_log_analysis/flight_review/actuator_outputs_noisy.png) - ## GPS Uncertainty -The *GPS Uncertainty* plot shows information from the GPS device: +The _GPS Uncertainty_ plot shows information from the GPS device: + - Number of used satellites (should be around 12 or higher) - Horizontal position accuracy (should be below 1 meter) - Vertical position accuracy (should be below 2 meters) - GPS fix: this is 3 for a 3D GPS fix, 4 for GPS + Dead Reckoning, 5 for RTK float and 6 for RTK fixed type - ## GPS Noise & Jamming The GPS Noise & Jamming plot is useful to check for GPS signal interferences and jamming. @@ -301,21 +293,21 @@ This is an example without any interference: ![GPS jamming - good plot](../../assets/flight_log_analysis/flight_review/gps_jamming_good.png) - ## Thrust and Magnetic Field -The *Thrust and Magnetic Field* plot shows the thrust and the norm of the magnetic sensor measurement vector. +The _Thrust and Magnetic Field_ plot shows the thrust and the norm of the magnetic sensor measurement vector. The norm should be constant over the whole flight and uncorrelated with the thrust. This is a good example where the norm is very close to constant: ![Thrust and mag close to constant](../../assets/flight_log_analysis/flight_review/thrust_and_mag_good.png) -*If it is correlated*, it means that the current drawn by the motors (or other consumers) is influencing the magnetic field. +_If it is correlated_, it means that the current drawn by the motors (or other consumers) is influencing the magnetic field. This must be avoided as it leads to incorrect yaw estimation. The following plot shows a strong correlation between the thrust and the norm of the magnetometer: ![Correlated thrust and mag](../../assets/flight_log_analysis/flight_review/thrust_and_mag_correlated.png) Solutions to this are: + - Use an external magnetometer (avoid using the internal magnetometer) - If using an external magnetometer, move it further away from strong currents (i.e. by using a (longer) GPS mast). @@ -325,10 +317,9 @@ However it could also be due to external disturbances (for example when flying c This example shows that the norm is non-constant, but it does not correlate with the thrust: ![Uncorrelated thrust and mag](../../assets/flight_log_analysis/flight_review/thrust_and_mag_uncorrelated_problem.png) - ## Estimator Watchdog -The *Estimator Watchdog* plot shows the health report of the estimator. +The _Estimator Watchdog_ plot shows the health report of the estimator. It should be constant zero. This is what it should look like if there are no problems: @@ -337,12 +328,12 @@ This is what it should look like if there are no problems: If one of the flags is non-zero, the estimator detected a problem that needs to be further investigated. Most of the time it is an issue with a sensor, for example magnetometer interferences. It usually helps to look at the plots of the corresponding sensor. + Here is an example with magnetometer problems: ![Estimator watchdog with magnetometer problems](../../assets/flight_log_analysis/flight_review/estimator_watchdog_mag_problem.png) - ## Sampling Regularity of Sensor Data The sampling regularity plot provides insights into problems with the logging system and scheduling. @@ -373,14 +364,13 @@ The following example contains too many dropouts, the quality of the used SD car ## Logged Messages -This is a table with system error and warning messages. +This is a table with system error and warning messages. For example they show when a task becomes low on stack size. The messages need to be examined individually, and not all of them indicate a problem. For example the following shows a kill-switch test: ![Logged Messages](../../assets/flight_log_analysis/flight_review/logged_messages.png) - ## Flight/Frame Log Review Examples It is often worth looking at multiple charts for a particular flight when analyzing vehicle condition (different charts can better highlight some issues). @@ -391,9 +381,11 @@ The section below groups a few (previously presented) charts by flight/vehicle. ### QAV-R 5" Racer These charts are all from the same flight of a [QAV-R 5" Racer](../frames_multicopter/qav_r_5_kiss_esc_racer.md). + They show a vehicle that has very low vibration: + - Actuator Controls FFT shows only a single peak at the lowest end, with the rest low and flat. - Spectral density is mostly green, with only a little yellow at the low frequencies. - Raw Acceleration has z-axis trace well separated from the x/y-axis traces. @@ -404,14 +396,15 @@ They show a vehicle that has very low vibration: ![Low vibration QAV-R 5 Racer - raw accel. plot](../../assets/flight_log_analysis/flight_review/vibrations_good_accel.png) - ### DJI F450 -These charts are all from the same flight of a *DJI F450*. +These charts are all from the same flight of a _DJI F450_. + They show a vehicle that has low vibration (but not as low as the QAV-R above!): -- Actuator Controls FFT shows a peak at the lowest end. + +- Actuator Controls FFT shows a peak at the lowest end. Most of the rest is flat, except for a bump at around 100Hz (this is the blade passing frequency of the propellers). - Spectral density is mostly green. The blade passing frequency is again visible. - Raw Acceleration has z-axis trace well separated from the x/y-axis traces. @@ -422,16 +415,16 @@ They show a vehicle that has low vibration (but not as low as the QAV-R above!): ![Low vibration DJI F450 - raw accel. plot](../../assets/flight_log_analysis/flight_review/vibrations_f450_accel.png) - ### S500 These charts are all from the same flight of an S500. They show a vehicle that has borderline-acceptable vibration: -- Actuator Controls FFT shows a peak at the lowest end. + +- Actuator Controls FFT shows a peak at the lowest end. Most of the rest is flat, except for a bump at around 100Hz. - Spectral density is mostly green, but more yellow than for the DJI F450 at 100Hz. -- Raw Acceleration has z-axis trace fairly close to the x/y-axis traces. +- Raw Acceleration has z-axis trace fairly close to the x/y-axis traces. This is at the limit where it starts to negatively affect flight performance. ![Low vibration S500 actuator controls - FFT plot](../../assets/flight_log_analysis/flight_review/vibrations_s500_actuator_controls_fft.png) diff --git a/docs/en/log/plotjuggler_log_analysis.md b/docs/en/log/plotjuggler_log_analysis.md index be9b0be76f..25cd7ce6eb 100644 --- a/docs/en/log/plotjuggler_log_analysis.md +++ b/docs/en/log/plotjuggler_log_analysis.md @@ -66,17 +66,17 @@ This shows the position / velocity relationship described above in detail. ::: info Try out the boat testing log analysis yourself by downloading the ULog and Layout file used above! + - [Boat testing ULog](https://github.com/PX4/PX4-Autopilot/raw/main/docs/assets/flight_log_analysis/plot_juggler/sample_log_boat_testing_2022-7-28-13-31-16.ulg) - [Boat testing Analysis Layout](https://raw.githubusercontent.com/PX4/PX4-user_guide/main/assets/flight_log_analysis/plot_juggler/sample_log_boat_testing_layout.xml) -::: + ::: ### Layout Templates There are a number of PlotJuggler layout files shared by PX4 Developers. Each can be used for a specific purpose (Multicopter tuning, VTOL tuning, Boat debugging, etc.): -* [Sample View layout](https://github.com/PX4/PX4-user_guide/blob/main/assets/flight_log_analysis/plot_juggler/plotjuggler_sample_view.xml) : Template used in the [Multi-panel example](#splitting-horizontally-vertically-multi-panel) above. - +- [Sample View layout](https://github.com/PX4/PX4-user_guide/blob/main/assets/flight_log_analysis/plot_juggler/plotjuggler_sample_view.xml) : Template used in the [Multi-panel example](#splitting-horizontally-vertically-multi-panel) above. ## Advanced Usage @@ -105,6 +105,7 @@ Here the custom series `Roll` is displayed along with other timeseries, includin ![Quaternion Roll plotted](../../assets/flight_log_analysis/plot_juggler/plotjuggler_quaternion_roll_plotted.png) The `quat_to_roll` function looks like this: + ```lua w = value x = v1 diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index 07ec63404c..8dc46fa490 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -94,191 +94,199 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages -- [BatteryInfo](../msg_docs/BatteryInfo.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) -- [Airspeed](../msg_docs/Airspeed.md) -- [PpsCapture](../msg_docs/PpsCapture.md) -- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [Px4ioStatus](../msg_docs/Px4ioStatus.md) -- [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) -- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) -- [AirspeedWind](../msg_docs/AirspeedWind.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) -- [GpioOut](../msg_docs/GpioOut.md) -- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) -- [Gripper](../msg_docs/Gripper.md) -- [VehicleAirData](../msg_docs/VehicleAirData.md) -- [TuneControl](../msg_docs/TuneControl.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) -- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) -- [EstimatorBias](../msg_docs/EstimatorBias.md) -- [GpioConfig](../msg_docs/GpioConfig.md) -- [SystemPower](../msg_docs/SystemPower.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) -- [MissionResult](../msg_docs/MissionResult.md) -- [PowerButtonState](../msg_docs/PowerButtonState.md) -- [EscStatus](../msg_docs/EscStatus.md) -- [HealthReport](../msg_docs/HealthReport.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [SensorGyro](../msg_docs/SensorGyro.md) -- [GpioRequest](../msg_docs/GpioRequest.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [ParameterUpdate](../msg_docs/ParameterUpdate.md) -- [SensorAirflow](../msg_docs/SensorAirflow.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) -- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) -- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) -- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) -- [ActionRequest](../msg_docs/ActionRequest.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) -- [PwmInput](../msg_docs/PwmInput.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [Mission](../msg_docs/Mission.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) -- [RadioStatus](../msg_docs/RadioStatus.md) -- [VehicleRoi](../msg_docs/VehicleRoi.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) -- [Rpm](../msg_docs/Rpm.md) -- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [Ping](../msg_docs/Ping.md) +- [EventV0](../msg_docs/EventV0.md) +- [IrlockReport](../msg_docs/IrlockReport.md) - [QshellReq](../msg_docs/QshellReq.md) -- [SensorMag](../msg_docs/SensorMag.md) -- [EstimatorStates](../msg_docs/EstimatorStates.md) -- [SensorUwb](../msg_docs/SensorUwb.md) -- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) -- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) -- [AdcReport](../msg_docs/AdcReport.md) -- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) -- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [SensorCorrection](../msg_docs/SensorCorrection.md) -- [UlogStream](../msg_docs/UlogStream.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) -- [GpsInjectData](../msg_docs/GpsInjectData.md) -- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) -- [SensorBaro](../msg_docs/SensorBaro.md) -- [OrbTestMedium](../msg_docs/OrbTestMedium.md) - [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) -- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) -- [UlogStreamAck](../msg_docs/UlogStreamAck.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) -- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) -- [PositionSetpoint](../msg_docs/PositionSetpoint.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [LedControl](../msg_docs/LedControl.md) -- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [Event](../msg_docs/Event.md) -- [ActuatorArmed](../msg_docs/ActuatorArmed.md) -- [GpioIn](../msg_docs/GpioIn.md) -- [SensorGyroFft](../msg_docs/SensorGyroFft.md) -- [SensorAccel](../msg_docs/SensorAccel.md) -- [SensorsStatus](../msg_docs/SensorsStatus.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) -- [GeneratorStatus](../msg_docs/GeneratorStatus.md) -- [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) -- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) -- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [RoverRateStatus](../msg_docs/RoverRateStatus.md) -- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) -- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [MagWorkerData](../msg_docs/MagWorkerData.md) -- [Cpuload](../msg_docs/Cpuload.md) -- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [SensorTemp](../msg_docs/SensorTemp.md) -- [LandingGearWheel](../msg_docs/LandingGearWheel.md) -- [OrbTestLarge](../msg_docs/OrbTestLarge.md) -- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [CellularStatus](../msg_docs/CellularStatus.md) -- [QshellRetval](../msg_docs/QshellRetval.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) -- [LogMessage](../msg_docs/LogMessage.md) -- [SatelliteInfo](../msg_docs/SatelliteInfo.md) -- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) -- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) -- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) -- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) -- [EstimatorStatus](../msg_docs/EstimatorStatus.md) -- [NeuralControl](../msg_docs/NeuralControl.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) -- [RcParameterMap](../msg_docs/RcParameterMap.md) -- [SensorSelection](../msg_docs/SensorSelection.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) -- [ActuatorTest](../msg_docs/ActuatorTest.md) -- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [MountOrientation](../msg_docs/MountOrientation.md) -- [CameraStatus](../msg_docs/CameraStatus.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [FollowTarget](../msg_docs/FollowTarget.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [ButtonEvent](../msg_docs/ButtonEvent.md) -- [DebugArray](../msg_docs/DebugArray.md) - [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) -- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) -- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) -- [VehicleImu](../msg_docs/VehicleImu.md) -- [GpsDump](../msg_docs/GpsDump.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) -- [DebugValue](../msg_docs/DebugValue.md) +- [OrbTestLarge](../msg_docs/OrbTestLarge.md) +- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) +- [FollowTarget](../msg_docs/FollowTarget.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) +- [CameraStatus](../msg_docs/CameraStatus.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) +- [Mission](../msg_docs/Mission.md) - [LandingTargetPose](../msg_docs/LandingTargetPose.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) -- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) -- [RtlStatus](../msg_docs/RtlStatus.md) -- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) -- [GimbalControls](../msg_docs/GimbalControls.md) -- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) +- [Airspeed](../msg_docs/Airspeed.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) +- [Rpm](../msg_docs/Rpm.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) +- [GpioOut](../msg_docs/GpioOut.md) +- [SensorSelection](../msg_docs/SensorSelection.md) +- [ButtonEvent](../msg_docs/ButtonEvent.md) +- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) - [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) +- [SensorMag](../msg_docs/SensorMag.md) +- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) +- [DifferentialPressure](../msg_docs/DifferentialPressure.md) +- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) +- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) +- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [HealthReport](../msg_docs/HealthReport.md) +- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) +- [RtlStatus](../msg_docs/RtlStatus.md) +- [VehicleRoi](../msg_docs/VehicleRoi.md) +- [QshellRetval](../msg_docs/QshellRetval.md) +- [GeneratorStatus](../msg_docs/GeneratorStatus.md) - [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [CameraCapture](../msg_docs/CameraCapture.md) +- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [Gripper](../msg_docs/Gripper.md) +- [ActuatorTest](../msg_docs/ActuatorTest.md) +- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) +- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) +- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [PwmInput](../msg_docs/PwmInput.md) +- [BatteryInfo](../msg_docs/BatteryInfo.md) +- [NeuralControl](../msg_docs/NeuralControl.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) +- [DeviceInformation](../msg_docs/DeviceInformation.md) +- [Vtx](../msg_docs/Vtx.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [GimbalControls](../msg_docs/GimbalControls.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [Ping](../msg_docs/Ping.md) +- [LedControl](../msg_docs/LedControl.md) +- [ActionRequest](../msg_docs/ActionRequest.md) +- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) +- [GpioConfig](../msg_docs/GpioConfig.md) +- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [OrbTest](../msg_docs/OrbTest.md) +- [LandingGearWheel](../msg_docs/LandingGearWheel.md) +- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [MissionResult](../msg_docs/MissionResult.md) +- [SystemPower](../msg_docs/SystemPower.md) +- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) +- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [EstimatorStatus](../msg_docs/EstimatorStatus.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [OrbTestMedium](../msg_docs/OrbTestMedium.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [GpioRequest](../msg_docs/GpioRequest.md) +- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [RadioStatus](../msg_docs/RadioStatus.md) +- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [SensorAirflow](../msg_docs/SensorAirflow.md) +- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) +- [RoverRateStatus](../msg_docs/RoverRateStatus.md) +- [VehicleAirData](../msg_docs/VehicleAirData.md) +- [PowerButtonState](../msg_docs/PowerButtonState.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [AdcReport](../msg_docs/AdcReport.md) +- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) +- [EstimatorStates](../msg_docs/EstimatorStates.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) +- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) +- [MagWorkerData](../msg_docs/MagWorkerData.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [FuelTankStatus](../msg_docs/FuelTankStatus.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) +- [DebugValue](../msg_docs/DebugValue.md) +- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) +- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) - [RcChannels](../msg_docs/RcChannels.md) -- [TecsStatus](../msg_docs/TecsStatus.md) +- [VehicleImu](../msg_docs/VehicleImu.md) - [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) - [InputRc](../msg_docs/InputRc.md) -- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) -- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [GeofenceStatus](../msg_docs/GeofenceStatus.md) +- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) +- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) +- [GpsInjectData](../msg_docs/GpsInjectData.md) - [CameraTrigger](../msg_docs/CameraTrigger.md) - [EscReport](../msg_docs/EscReport.md) -- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) -- [GeofenceStatus](../msg_docs/GeofenceStatus.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [SensorAccel](../msg_docs/SensorAccel.md) +- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) +- [LogMessage](../msg_docs/LogMessage.md) +- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [RcParameterMap](../msg_docs/RcParameterMap.md) +- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) - [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) -- [EventV0](../msg_docs/EventV0.md) +- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [SensorGyro](../msg_docs/SensorGyro.md) +- [SensorBaro](../msg_docs/SensorBaro.md) +- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [PpsCapture](../msg_docs/PpsCapture.md) +- [SensorsStatus](../msg_docs/SensorsStatus.md) +- [SensorHygrometer](../msg_docs/SensorHygrometer.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) +- [SatelliteInfo](../msg_docs/SatelliteInfo.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [UlogStream](../msg_docs/UlogStream.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) - [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) -- [IrlockReport](../msg_docs/IrlockReport.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) +- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) +- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [ActuatorArmed](../msg_docs/ActuatorArmed.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) +- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [AirspeedWind](../msg_docs/AirspeedWind.md) +- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) +- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) +- [GpsDump](../msg_docs/GpsDump.md) +- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) +- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) +- [GainCompression](../msg_docs/GainCompression.md) +- [SensorCorrection](../msg_docs/SensorCorrection.md) +- [SensorUwb](../msg_docs/SensorUwb.md) +- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) +- [Cpuload](../msg_docs/Cpuload.md) +- [GpioIn](../msg_docs/GpioIn.md) +- [CellularStatus](../msg_docs/CellularStatus.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [PositionSetpoint](../msg_docs/PositionSetpoint.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [Event](../msg_docs/Event.md) ::: diff --git a/docs/en/middleware/drivers.md b/docs/en/middleware/drivers.md index 6b29331d21..e64a3bfefb 100644 --- a/docs/en/middleware/drivers.md +++ b/docs/en/middleware/drivers.md @@ -1,27 +1,27 @@ # Driver Development -PX4 device drivers are based on the [Device](https://github.com/PX4/PX4-Autopilot/tree/main/src/lib/drivers/device) framework. +PX4 device drivers are based on the [Device](https://github.com/PX4/PX4-Autopilot/tree/main/src/lib/drivers/device) framework. ## Creating a Driver PX4 almost exclusively consumes data from [uORB](../middleware/uorb.md). Drivers for common peripheral types must publish the correct uORB messages (for example: gyro, accelerometer, pressure sensors, etc.). -The best approach for creating a new driver is to start with a similar driver as a template (see [src/drivers](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers)). +The best approach for creating a new driver is to start with a similar driver as a template (see [src/drivers](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers)). ::: info More detailed information about working with specific I/O buses and sensors may be available in [Sensor and Actuator Buses](../sensor_bus/index.md) section. ::: ::: info -Publishing the correct uORB topics is the only pattern that drivers *must* follow. +Publishing the correct uORB topics is the only pattern that drivers _must_ follow. ::: ## Core Architecture PX4 is a [reactive system](../concept/architecture.md) and uses [uORB](../middleware/uorb.md) publish/subscribe to transport messages. File handles are not required or used for the core operation of the system. Two main APIs are used: -* The publish / subscribe system which has a file, network or shared memory backend depending on the system PX4 runs on. -* The global device registry, which can be used to enumerate devices and get/set their configuration. This can be as simple as a linked list or map to the file system. +- The publish / subscribe system which has a file, network or shared memory backend depending on the system PX4 runs on. +- The global device registry, which can be used to enumerate devices and get/set their configuration. This can be as simple as a linked list or map to the file system. ## Device IDs @@ -33,7 +33,6 @@ The order of sensors (e.g. if there is a `/dev/mag0` and an alternate `/dev/mag1 For the example of three magnetometers on a system, use the flight log (.px4log) to dump the parameters. The three parameters encode the sensor IDs and `MAG_PRIME` identifies which magnetometer is selected as the primary sensor. Each MAGx_ID is a 24bit number and should be padded left with zeros for manual decoding. - ``` CAL_MAG0_ID = 73225.0 CAL_MAG1_ID = 66826.0 @@ -83,6 +82,7 @@ struct DeviceStructure { uint8_t devtype; // device class specific device type }; ``` + The `bus_type` is decoded according to: ```C @@ -126,17 +126,19 @@ Drivers (and other modules) output minimally verbose logs strings by default (e. Log verbosity is defined at build time using the `RELEASE_BUILD` (default), `DEBUG_BUILD` (verbose) or `TRACE_BUILD` (extremely verbose) macros. Change the logging level using `COMPILE_FLAGS` in the driver `px4_add_module` function (**CMakeLists.txt**). -The code fragment below shows the required change to enable DEBUG_BUILD level debugging for a single module or driver. +The code fragment below shows the required change to enable DEBUG_BUILD level debugging for a single module or driver. ``` px4_add_module( MODULE templates__module MAIN module ``` + ``` COMPILE_FLAGS -DDEBUG_BUILD ``` + ``` SRCS module.cpp diff --git a/docs/en/middleware/index.md b/docs/en/middleware/index.md index dc9d0464b7..3c35eeb96c 100644 --- a/docs/en/middleware/index.md +++ b/docs/en/middleware/index.md @@ -1,6 +1,6 @@ # Middleware -This section contains topics about PX4 middleware, including PX4 internal communication mechanisms ([uORB](../middleware/uorb.md)), and between PX4 and offboard systems like companion computers and GCS (e.g. [MAVLink](../middleware/mavlink.md), [uXRCE-DDS](../middleware/uxrce_dds.md)). +This section contains topics about PX4 middleware, including PX4 internal communication mechanisms ([uORB](../middleware/uorb.md)), and between PX4 and offboard systems like companion computers and GCS (e.g. [MAVLink](../middleware/mavlink.md), [uXRCE-DDS](../middleware/uxrce_dds.md)). :::tip For a detailed overview of the platform architecture see the [Architectural Overview](../concept/architecture.md). diff --git a/docs/en/middleware/uorb_graph.md b/docs/en/middleware/uorb_graph.md index 7376e951b6..9dbdb57c2d 100644 --- a/docs/en/middleware/uorb_graph.md +++ b/docs/en/middleware/uorb_graph.md @@ -10,7 +10,6 @@ Usage instructions are provided [below](#graph-properties). import { withBase } from 'vitepress'; - ## Graph Properties The graph has the following properties: @@ -27,5 +26,5 @@ The graph has the following properties: - Double-clicking on a topic opens its message definition. - Make sure your browser window is wide enough to display the full graph (the sidebar menu can be hidden with the icon in the top-left corner). You can also zoom the image. -- The *Preset* selection list allows you to refine the list of modules that are shown. -- The *Search* box can be used to find particular modules/topics (topics that are not selected by the search are greyed-out). +- The _Preset_ selection list allows you to refine the list of modules that are shown. +- The _Search_ box can be used to find particular modules/topics (topics that are not selected by the search are greyed-out). diff --git a/docs/en/modules/module_template.md b/docs/en/modules/module_template.md index 5d9fa26c6a..291c6ff0cf 100644 --- a/docs/en/modules/module_template.md +++ b/docs/en/modules/module_template.md @@ -1,6 +1,6 @@ # Module Template for Full Applications -An application can be written to run as either a *task* (a module with its own stack and process priority) or as a *work queue task* (a module that runs on a work queue thread, sharing the stack and thread priority with other tasks on the work queue). +An application can be written to run as either a _task_ (a module with its own stack and process priority) or as a _work queue task_ (a module that runs on a work queue thread, sharing the stack and thread priority with other tasks on the work queue). In most cases a work queue task can be used, as this minimizes resource usage. ::: info @@ -13,26 +13,28 @@ All the things learned in the [First Application Tutorial](../modules/hello_sky. ## Work Queue Task -PX4-Autopilot contains a template for writing a new application (module) that runs as a *work queue task*: +PX4-Autopilot contains a template for writing a new application (module) that runs as a _work queue task_: [src/examples/work_item](https://github.com/PX4/PX4-Autopilot/tree/main/src/examples/work_item). A work queue task application is just the same as an ordinary (task) application, except that it needs to specify that it is a work queue task, and schedule itself to run during initialisation. The example shows how. In summary: + 1. Specify the dependency on the work queue library in the cmake definition file ([CMakeLists.txt](https://github.com/PX4/PX4-Autopilot/blob/main/src/examples/work_item/CMakeLists.txt)): ``` ... DEPENDS px4_work_queue ``` -1. In addition to `ModuleBase`, the task should also derive from `ScheduledWorkItem` (included from [ScheduledWorkItem.hpp]( https://github.com/PX4/PX4-Autopilot/blob/main/platforms/common/include/px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp)) +1. In addition to `ModuleBase`, the task should also derive from `ScheduledWorkItem` (included from [ScheduledWorkItem.hpp](https://github.com/PX4/PX4-Autopilot/blob/main/platforms/common/include/px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp)) 1. Specify the queue to add the task to in the constructor initialisation. The [work_item](https://github.com/PX4/PX4-Autopilot/blob/main/src/examples/work_item/WorkItemExample.cpp#L42) example adds itself to the `wq_configurations::test1` work queue as shown below: + ```cpp WorkItemExample::WorkItemExample() : - ModuleParams(nullptr), - ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::test1) + ModuleParams(nullptr), + ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::test1) { } ``` @@ -45,8 +47,6 @@ In summary: 1. Implement the `task_spawn` method, specifying that the task is a work queue (using the `task_id_is_work_queue` id. 1. Schedule the work queue task using one of the scheduling methods (in the example we use `ScheduleOnInterval` from within the `init` method). - - ## Tasks PX4/PX4-Autopilot contains a template for writing a new application (module) that runs as a task on its own stack: diff --git a/docs/en/modules/modules_autotune.md b/docs/en/modules/modules_autotune.md index 2292dd7494..f0570f8925 100644 --- a/docs/en/modules/modules_autotune.md +++ b/docs/en/modules/modules_autotune.md @@ -1,15 +1,11 @@ # Modules Reference: Autotune - - ## fw_autotune_attitude_control Source: [modules/fw_autotune_attitude_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_autotune_attitude_control) - ### Description - ### Usage {#fw_autotune_attitude_control_usage} ``` @@ -27,10 +23,8 @@ fw_autotune_attitude_control [arguments...] Source: [modules/mc_autotune_attitude_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mc_autotune_attitude_control) - ### Description - ### Usage {#mc_autotune_attitude_control_usage} ``` diff --git a/docs/en/modules/modules_command.md b/docs/en/modules/modules_command.md index 4bba93f042..499d7f1fdb 100644 --- a/docs/en/modules/modules_command.md +++ b/docs/en/modules/modules_command.md @@ -1,12 +1,9 @@ # Modules Reference: Command - - ## actuator_test Source: [systemcmds/actuator_test](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/actuator_test) - Utility to test actuators. WARNING: remove all props before using this command. @@ -36,6 +33,7 @@ actuator_test [arguments...] Source: [systemcmds/bl_update](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/bl_update) Utility to flash the bootloader from a file + ### Usage {#bl_update_usage} ``` @@ -51,6 +49,7 @@ bl_update [arguments...] Source: [systemcmds/bsondump](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/bsondump) Utility to read BSON from a file and print or output document size. + ### Usage {#bsondump_usage} ``` @@ -63,6 +62,7 @@ bsondump [arguments...] Source: [systemcmds/dumpfile](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/dumpfile) Dump file utility. Prints file size and contents in binary mode (don't replace LF with CR LF) to stdout. + ### Usage {#dumpfile_usage} ``` @@ -74,16 +74,16 @@ dumpfile [arguments...] Source: [systemcmds/dyn](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/dyn) - ### Description + Load and run a dynamic PX4 module, which was not compiled into the PX4 binary. ### Example + ``` dyn ./hello.px4mod start ``` - ### Usage {#dyn_usage} ``` @@ -96,14 +96,16 @@ dyn [arguments...] Source: [systemcmds/failure](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/failure) - ### Description + Inject failures into system. ### Implementation + This system command sends a vehicle command over uORB to trigger failure. ### Examples + Test the GPS failsafe by stopping GPS: failure gps off @@ -125,32 +127,37 @@ failure [arguments...] Source: [systemcmds/gpio](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/gpio) - ### Description + This command is used to read and write GPIOs + ``` gpio read / [PULLDOWN|PULLUP] [--force] gpio write / [PUSHPULL|OPENDRAIN] [--force] ``` ### Examples + Read the value on port H pin 4 configured as pullup, and it is high + ``` gpio read H4 PULLUP ``` + 1 OK Set the output value on Port E pin 7 to high + ``` gpio write E7 1 --force ``` Set the output value on device /dev/gpio1 to high + ``` gpio write /dev/gpio1 1 ``` - ### Usage {#gpio_usage} ``` @@ -203,6 +210,7 @@ hardfault_log [arguments...] Source: [systemcmds/hist](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/hist) Command-line tool to show the px4 message history. There are no arguments. + ### Usage {#hist_usage} ``` @@ -214,6 +222,7 @@ hist [arguments...] Source: [systemcmds/i2cdetect](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/i2cdetect) Utility to scan for I2C devices on a particular bus. + ### Usage {#i2cdetect_usage} ``` @@ -226,8 +235,8 @@ i2cdetect [arguments...] Source: [systemcmds/led_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/led_control) - ### Description + Command-line tool to control & test the (external) LED's. To use it make sure there's a driver running, which handles the led_control uorb topic. @@ -237,12 +246,13 @@ module can blink N times with high priority, and the LED's automatically return after the blinking. The `reset` command can also be used to return to a lower priority. ### Examples + Blink the first LED 5 times in blue: + ``` led_control blink -c blue -l 0 -n 5 ``` - ### Usage {#led_control_usage} ``` @@ -279,7 +289,6 @@ led_control [arguments...] Source: [systemcmds/topic_listener](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/topic_listener) - Utility to listen on uORB topics and print the data to the console. The listener can be exited any time by pressing Ctrl+C, Esc, or Q. @@ -303,6 +312,7 @@ listener [arguments...] Source: [systemcmds/mft](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/mft) Utility interact with the manifest + ### Usage {#mfd_usage} ``` @@ -316,6 +326,7 @@ mfd [arguments...] Source: [systemcmds/mft_cfg](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/mft_cfg) Tool to set and get manifest configuration + ### Usage {#mft_cfg_usage} ``` @@ -336,6 +347,7 @@ mft_cfg [arguments...] Source: [systemcmds/mtd](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/mtd) Utility to mount and test partitions (based on FRAM/EEPROM storage as defined by the board) + ### Usage {#mtd_usage} ``` @@ -378,8 +390,8 @@ nshterm [arguments...] Source: [systemcmds/param](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/param) - ### Description + Command to access and manipulate parameters via shell or script. This is used for example in the startup script to set airframe-specific parameters. @@ -396,7 +408,9 @@ Each parameter has a 'used' flag, which is set when it's read during boot. It is parameters to a ground control station. ### Examples + Change the airframe and make sure the airframe's default parameters are loaded: + ``` param set SYS_AUTOSTART 4001 param set SYS_AUTOCONFIG 1 @@ -476,12 +490,11 @@ param [arguments...] Source: [modules/payload_deliverer](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/payload_deliverer) - ### Description + Handles payload delivery with either Gripper or a Winch with an appropriate timeout / feedback sensor setting, and communicates back the delivery result as an acknowledgement internally - ### Usage {#payload_deliverer_usage} ``` @@ -505,6 +518,7 @@ payload_deliverer [arguments...] Source: [systemcmds/perf](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/perf) Tool to print performance counters + ### Usage {#perf_usage} ``` @@ -521,6 +535,7 @@ perf [arguments...] Source: [systemcmds/reboot](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/reboot) Reboot the system + ### Usage {#reboot_usage} ``` @@ -535,6 +550,7 @@ reboot [arguments...] Source: [systemcmds/sd_bench](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/sd_bench) Test the speed of an SD Card + ### Usage {#sd_bench_usage} ``` @@ -557,6 +573,7 @@ sd_bench [arguments...] Source: [systemcmds/sd_stress](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/sd_stress) Test operations on an SD Card + ### Usage {#sd_stress_usage} ``` @@ -592,7 +609,6 @@ serial_passthru [arguments...] Source: [systemcmds/system_time](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/system_time) - ### Description Command-line tool to set and get system time. @@ -600,6 +616,7 @@ Command-line tool to set and get system time. ### Examples Set the system time and read it back + ``` system_time set 1600775044 system_time get @@ -620,6 +637,7 @@ system_time [arguments...] Source: [systemcmds/top](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/top) Monitor running processes and their CPU, stack usage, priority and state + ### Usage {#top_usage} ``` @@ -633,6 +651,7 @@ Source: [systemcmds/usb_connected](https://github.com/PX4/PX4-Autopilot/tree/mai Utility to check if USB is connected. Was previously used in startup scripts. A return value of 0 means USB is connected, 1 otherwise. + ### Usage {#usb_connected_usage} ``` @@ -644,6 +663,7 @@ usb_connected [arguments...] Source: [systemcmds/ver](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/ver) Tool to print various version information + ### Usage {#ver_usage} ``` diff --git a/docs/en/modules/modules_driver.md b/docs/en/modules/modules_driver.md index f4ebd987eb..349b98659d 100644 --- a/docs/en/modules/modules_driver.md +++ b/docs/en/modules/modules_driver.md @@ -45,6 +45,26 @@ atxxxx [arguments...] status print status info ``` +## auterion_autostarter + +Source: [drivers/auterion_autostarter](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/auterion_autostarter) + +### Description + +Driver for starting and auto-detecting different power monitors. + +### Usage {#auterion_autostarter_usage} + +``` +auterion_autostarter [arguments...] + Commands: + start + + stop + + status print status info +``` + ## batmon Source: [drivers/smart_battery/batmon](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/smart_battery/batmon) @@ -925,26 +945,6 @@ pca9685_pwm_out [arguments...] status print status info ``` -## pm_selector_auterion - -Source: [drivers/power_monitor/pm_selector_auterion](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/power_monitor/pm_selector_auterion) - -### Description - -Driver for starting and auto-detecting different power monitors. - -### Usage {#pm_selector_auterion_usage} - -``` -pm_selector_auterion [arguments...] - Commands: - start - - stop - - status print status info -``` - ## pmw3901 Source: [drivers/optical_flow/pmw3901](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/pmw3901) @@ -1109,7 +1109,7 @@ px4io [arguments...] ## rgbled -Source: [drivers/lights/rgbled_ncp5623c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/lights/rgbled_ncp5623c) +Source: [drivers/lights/rgbled](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/lights/rgbled) ### Usage {#rgbled_usage} @@ -1124,9 +1124,7 @@ rgbled [arguments...] [-f ] bus frequency in kHz [-q] quiet startup (no message if no device found) [-a ] I2C address - default: 57 - [-o ] RGB PWM Assignment - default: 123 + default: 85 stop @@ -1438,6 +1436,30 @@ tap_esc [arguments...] default: 4 ``` +## tmp102 + +Source: [drivers/temperature_sensor/tmp102](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/temperature_sensor/tmp102) + +### Usage {#tmp102_usage} + +``` +tmp102 [arguments...] + Commands: + start + [-I] Internal I2C bus(es) + [-X] External I2C bus(es) + [-b ] board-specific bus (default=all) (external SPI: n-th bus + (default=1)) + [-f ] bus frequency in kHz + [-q] quiet startup (no message if no device found) + [-a ] I2C address + default: 72 + + stop + + status print status info +``` + ## tone_alarm Source: [drivers/tone_alarm](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/tone_alarm) @@ -1627,6 +1649,76 @@ voxlpm [arguments...] status print status info ``` +## vtx + +Source: [drivers/vtx](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/vtx) + +### Description + +This module communicates with a VTX camera via serial port. It can be used to +configure the camera settings and to control the camera's video transmission. +Supported protocols are: + +- SmartAudio v1, v2.0, v2.1 +- Tramp + +### Usage {#vtx_usage} + +``` +vtx [arguments...] + Commands: + start + -d VTX device + values: + + Sets an entry in the mapping table: + + + stop + + status print status info +``` + +## vtxtable + +Source: [drivers/vtxtable](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/vtxtable) + +### Description + +Manages the VTX frequency, power level and RC mapping table for VTX configuration. + +### Usage {#vtxtable_usage} + +``` +vtxtable [arguments...] + Commands: + status Shows the current VTX table configuration. + + name Sets the VTX table name: + + bands Sets the number of bands: + + band Sets the band frequencies: <1-index> + + + channels Sets the number of channels: + + powerlevels Sets number of power levels: + + powervalues Sets the power level values: + + powerlabels Sets the power level labels: <3 chars...> + + Sets an entry in the mapping table: <0-index> + + + clear Clears the VTX table configuration. + + save Saves the VTX config to a file: + + load Loads the VTX config from a file: +``` + ## zenoh Source: [modules/zenoh](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/zenoh) diff --git a/docs/en/modules/modules_driver_airspeed_sensor.md b/docs/en/modules/modules_driver_airspeed_sensor.md index a1545bfe53..efab35a02a 100644 --- a/docs/en/modules/modules_driver_airspeed_sensor.md +++ b/docs/en/modules/modules_driver_airspeed_sensor.md @@ -4,8 +4,8 @@ Source: [drivers/differential_pressure/asp5033](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/asp5033) - ### Description + Driver to enable an external [ASP5033] (https://www.qio-tek.com/index.php/product/qiotek-asp5033-dronecan-airspeed-and-compass-module/) TE connected via I2C. diff --git a/docs/en/modules/modules_driver_camera.md b/docs/en/modules/modules_driver_camera.md index 58f3cfb45d..c63df4619f 100644 --- a/docs/en/modules/modules_driver_camera.md +++ b/docs/en/modules/modules_driver_camera.md @@ -4,7 +4,6 @@ Source: [drivers/camera_trigger](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/camera_trigger) - ### Description Camera trigger driver. diff --git a/docs/en/modules/modules_driver_optical_flow.md b/docs/en/modules/modules_driver_optical_flow.md index 2c734b5c3f..d69b6d28cc 100644 --- a/docs/en/modules/modules_driver_optical_flow.md +++ b/docs/en/modules/modules_driver_optical_flow.md @@ -4,7 +4,6 @@ Source: [drivers/optical_flow/thoneflow](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/thoneflow) - ### Description Serial bus driver for the ThoneFlow-3901U optical flow sensor. @@ -16,10 +15,13 @@ Setup/usage information: https://docs.px4.io/main/en/sensor/pmw3901.html#thone-t ### Examples Attempt to start driver on a specified serial device. + ``` thoneflow start -d /dev/ttyS1 ``` + Stop driver + ``` thoneflow stop ``` diff --git a/docs/en/modules/modules_estimator.md b/docs/en/modules/modules_estimator.md index 71041bcd50..8186889dd4 100644 --- a/docs/en/modules/modules_estimator.md +++ b/docs/en/modules/modules_estimator.md @@ -1,15 +1,12 @@ # Modules Reference: Estimator - - ## AttitudeEstimatorQ Source: [modules/attitude_estimator_q](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/attitude_estimator_q) - ### Description -Attitude estimator q. +Attitude estimator q. ### Usage {#AttitudeEstimatorQ_usage} @@ -27,8 +24,8 @@ AttitudeEstimatorQ [arguments...] Source: [modules/airspeed_selector](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/airspeed_selector) - ### Description + This module provides a single airspeed_validated topic, containing indicated (IAS), calibrated (CAS), true airspeed (TAS) and the information if the estimation currently is invalid and if based sensor readings or on groundspeed minus windspeed. @@ -37,7 +34,6 @@ to a valid sensor in case of failure detection. For failure detection as well as the estimation of a scale factor from IAS to CAS, it runs several wind estimators and also publishes those. - ### Usage {#airspeed_estimator_usage} ``` @@ -54,8 +50,8 @@ airspeed_estimator [arguments...] Source: [modules/ekf2](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/ekf2) - ### Description + Attitude and position estimator using an Extended Kalman Filter. It is used for Multirotors and Fixed-Wing. The documentation can be found on the [ECL/EKF Overview & Tuning](https://docs.px4.io/main/en/advanced_config/tuning_the_ecl_ekf.html) page. @@ -63,7 +59,6 @@ The documentation can be found on the [ECL/EKF Overview & Tuning](https://docs.p ekf2 can be started in replay mode (`-r`): in this mode, it does not access the system time, but only uses the timestamps from the sensor topics. - ### Usage {#ekf2_usage} ``` @@ -85,10 +80,9 @@ ekf2 [arguments...] Source: [modules/local_position_estimator](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/local_position_estimator) - ### Description -Attitude and position estimator using an Extended Kalman Filter. +Attitude and position estimator using an Extended Kalman Filter. ### Usage {#local_position_estimator_usage} @@ -106,10 +100,8 @@ local_position_estimator [arguments...] Source: [modules/mc_hover_thrust_estimator](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mc_hover_thrust_estimator) - ### Description - ### Usage {#mc_hover_thrust_estimator_usage} ``` diff --git a/docs/en/modules/modules_main.md b/docs/en/modules/modules_main.md index 34e325dcd2..4403a1ffa5 100644 --- a/docs/en/modules/modules_main.md +++ b/docs/en/modules/modules_main.md @@ -1,4 +1,3 @@ - # Modules & Commands Reference The following pages document the PX4 modules, drivers and commands. @@ -21,9 +20,11 @@ the root of the PX4-Autopilot directory: ``` make module_documentation ``` + The generated files will be written to the `modules` directory. ## Categories + - [Autotune](modules_autotune.md) - [Command](modules_command.md) - [Communication](modules_communication.md) diff --git a/docs/en/modules/modules_simulation.md b/docs/en/modules/modules_simulation.md index 18c267517b..f0a12f6604 100644 --- a/docs/en/modules/modules_simulation.md +++ b/docs/en/modules/modules_simulation.md @@ -1,13 +1,11 @@ # Modules Reference: Simulation - - ## simulator_sih Source: [modules/simulation/simulator_sih](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/simulator_sih) - ### Description + This module provides a simulator for quadrotors and fixed-wings running fully inside the hardware autopilot. @@ -18,13 +16,12 @@ This simulator publishes the sensors signals corrupted with realistic noise in order to incorporate the state estimator in the loop. ### Implementation + The simulator implements the equations of motion using matrix algebra. Quaternion representation is used for the attitude. Forward Euler is used for integration. Most of the variables are declared global in the .hpp file to avoid stack overflow. - - ### Usage {#simulator_sih_usage} ``` diff --git a/docs/en/modules/modules_template.md b/docs/en/modules/modules_template.md index 523d9ff02b..10e0e16f05 100644 --- a/docs/en/modules/modules_template.md +++ b/docs/en/modules/modules_template.md @@ -1,27 +1,58 @@ # Modules Reference: Template +## mc_raptor +Source: [modules/mc_raptor](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mc_raptor) + +### Description + +RAPTOR Policy Flight Mode + +### Usage {#mc_raptor_usage} + +``` +mc_raptor [arguments...] + Commands: + start + + intref Modify internal reference + lissajous Set Lissajous trajectory parameters + Amplitude X [m] + Amplitude Y [m] + Amplitude Z [m] + Frequency a + Frequency b + Frequency c + Total duration [s] + Ramp duration [s] + + stop + + status print status info +``` ## module Source: [templates/template_module](https://github.com/PX4/PX4-Autopilot/tree/main/src/templates/template_module) - ### Description + Section that describes the provided module functionality. This is a template for a module running as a task in the background with start/stop/status functionality. ### Implementation + Section describing the high-level implementation of this module. ### Examples + CLI usage example: + ``` module start -f -p 42 ``` - ### Usage {#module_usage} ``` @@ -41,10 +72,9 @@ module [arguments...] Source: [examples/work_item](https://github.com/PX4/PX4-Autopilot/tree/main/src/examples/work_item) - ### Description -Example of a simple module running out of a work queue. +Example of a simple module running out of a work queue. ### Usage {#work_item_example_usage} diff --git a/docs/en/msg_docs/ActionRequest.md b/docs/en/msg_docs/ActionRequest.md index 1c724dabb7..9d3bad8a5f 100644 --- a/docs/en/msg_docs/ActionRequest.md +++ b/docs/en/msg_docs/ActionRequest.md @@ -1,12 +1,56 @@ +--- +pageClass: is-wide-page +--- + # ActionRequest (UORB message) -Action request for the vehicle's main state +Action request for the vehicle's main state. Message represents actions requested by a PX4 internal component towards the main state machine such as a request to arm or switch mode. It allows mapping triggers from various external interfaces like RC channels or MAVLink to cause an action. Request are published by `manual_control` and subscribed by the `commander` and `vtol_att_control` modules. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActionRequest.msg) +**TOPICS:** action_request + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | -------- | ------------ | ----------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| action | `uint8` | | [ACTION](#ACTION) | Requested action | +| source | `uint8` | | [SOURCE](#SOURCE) | Request trigger type, such as a switch, button or gesture | +| mode | `uint8` | | | Requested mode. Only applies when `action` is `ACTION_SWITCH_MODE`. Values for this field are defined by the `vehicle_status_s::NAVIGATION_STATE_*` enumeration. | + +## Enums + +### ACTION {#ACTION} + +| Name | Type | Value | Description | +| ------------------------------------------------------------------------------------------- | ------- | ----- | --------------------------------------------------------------------- | +| ACTION_DISARM | `uint8` | 0 | Disarm vehicle | +| ACTION_ARM | `uint8` | 1 | Arm vehicle | +| ACTION_TOGGLE_ARMING | `uint8` | 2 | Toggle arming | +| ACTION_UNKILL | `uint8` | 3 | Revert a kill action | +| ACTION_KILL | `uint8` | 4 | Kill vehicle (instantly stop the motors) | +| ACTION_SWITCH_MODE | `uint8` | 5 | Switch mode. The target mode is set in the `mode` field. | +| ACTION_VTOL_TRANSITION_TO_MULTICOPTER | `uint8` | 6 | Transition to hover flight | +| ACTION_VTOL_TRANSITION_TO_FIXEDWING | `uint8` | 7 | Transition to fast forward flight | +| ACTION_TERMINATION | `uint8` | 8 | Irreversibly output failsafe values on all outputs, trigger parachute | + +### SOURCE {#SOURCE} + +| Name | Type | Value | Description | +| --------------------------------------------------------- | ------- | ----- | --------------------------------------------------------------- | +| SOURCE_STICK_GESTURE | `uint8` | 0 | Triggered by holding the sticks in a certain position | +| SOURCE_RC_SWITCH | `uint8` | 1 | Triggered by an RC switch moving into a certain position | +| SOURCE_RC_BUTTON | `uint8` | 2 | Triggered by a momentary button on the RC being pressed or held | +| SOURCE_RC_MODE_SLOT | `uint8` | 3 | Mode change through the RC mode selection mechanism | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActionRequest.msg) + +::: details Click here to see original file ```c # Action request for the vehicle's main state @@ -35,5 +79,6 @@ uint8 SOURCE_RC_BUTTON = 2 # Triggered by a momentary button on the RC bein uint8 SOURCE_RC_MODE_SLOT = 3 # Mode change through the RC mode selection mechanism uint8 mode # Requested mode. Only applies when `action` is `ACTION_SWITCH_MODE`. Values for this field are defined by the `vehicle_status_s::NAVIGATION_STATE_*` enumeration. - ``` + +::: diff --git a/docs/en/msg_docs/ActuatorArmed.md b/docs/en/msg_docs/ActuatorArmed.md index adee89cb21..e859fec479 100644 --- a/docs/en/msg_docs/ActuatorArmed.md +++ b/docs/en/msg_docs/ActuatorArmed.md @@ -1,6 +1,29 @@ +--- +pageClass: is-wide-page +--- + # ActuatorArmed (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorArmed.msg) +**TOPICS:** actuator_armed + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------------- | -------- | ------------ | ---------- | ------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| armed | `bool` | | | Set to true if system is armed | +| prearmed | `bool` | | | Set to true if the actuator safety is disabled but motors are not armed | +| ready_to_arm | `bool` | | | Set to true if system is ready to be armed | +| lockdown | `bool` | | | Set to true if actuators are forced to being disabled (due to emergency or HIL) | +| kill | `bool` | | | Set to true if manual throttle kill switch is engaged | +| termination | `bool` | | | Send out failsafe (by default same as disarmed) output | +| in_esc_calibration_mode | `bool` | | | IO/FMU should ignore messages from the actuator controls topics | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorArmed.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -12,5 +35,6 @@ bool lockdown # Set to true if actuators are forced to being disabled (due to e bool kill # Set to true if manual throttle kill switch is engaged bool termination # Send out failsafe (by default same as disarmed) output bool in_esc_calibration_mode # IO/FMU should ignore messages from the actuator controls topics - ``` + +::: diff --git a/docs/en/msg_docs/ActuatorControlsStatus.md b/docs/en/msg_docs/ActuatorControlsStatus.md index 2eb1d53f22..f15aff69ee 100644 --- a/docs/en/msg_docs/ActuatorControlsStatus.md +++ b/docs/en/msg_docs/ActuatorControlsStatus.md @@ -1,8 +1,23 @@ +--- +pageClass: is-wide-page +--- + # ActuatorControlsStatus (UORB message) +**TOPICS:** actuator_controls_status_0 actuator_controls_status_1 +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------- | ------------ | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| control_power | `float32[3]` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -10,5 +25,6 @@ uint64 timestamp # time since system start (microseconds) float32[3] control_power # TOPICS actuator_controls_status_0 actuator_controls_status_1 - ``` + +::: diff --git a/docs/en/msg_docs/ActuatorMotors.md b/docs/en/msg_docs/ActuatorMotors.md index 701465d6ea..e50477ebb2 100644 --- a/docs/en/msg_docs/ActuatorMotors.md +++ b/docs/en/msg_docs/ActuatorMotors.md @@ -1,11 +1,38 @@ +--- +pageClass: is-wide-page +--- + # ActuatorMotors (UORB message) -Motor control message +Motor control message. Normalised thrust setpoint for up to 12 motors. Published by the vehicle's allocation and consumed by the ESC protocol drivers e.g. PWM, DSHOT, UAVCAN. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorMotors.msg) +**TOPICS:** actuator_motors + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ------------- | ------------ | ---------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| timestamp_sample | `uint64` | us | | Sampling timestamp of the data this control response is based on | +| reversible_flags | `uint16` | | | Bitset indicating which motors are configured to be reversible | +| control | `float32[12]` | | [-1 : 1] | Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | +| ACTUATOR_FUNCTION_MOTOR1 | `uint8` | 101 | +| NUM_CONTROLS | `uint8` | 12 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorMotors.msg) + +::: details Click here to see original file ```c # Motor control message @@ -24,5 +51,6 @@ uint8 ACTUATOR_FUNCTION_MOTOR1 = 101 # uint8 NUM_CONTROLS = 12 # float32[12] control # [@range -1, 1] Normalized thrust. where 1 means maximum positive thrust, -1 maximum negative (if not supported by the output, <0 maps to NaN). NaN maps to disarmed (stop the motors) - ``` + +::: diff --git a/docs/en/msg_docs/ActuatorOutputs.md b/docs/en/msg_docs/ActuatorOutputs.md index 3fc4a94c9d..fa8b313c4c 100644 --- a/docs/en/msg_docs/ActuatorOutputs.md +++ b/docs/en/msg_docs/ActuatorOutputs.md @@ -1,8 +1,31 @@ +--- +pageClass: is-wide-page +--- + # ActuatorOutputs (UORB message) +**TOPICS:** actuator_outputs actuator_outputs_sim actuator_outputs_debug +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | ------------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| noutputs | `uint32` | | | valid outputs | +| output | `float32[16]` | | | output data, in natural output units | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------------- | ------- | ----- | ------------------- | +| NUM_ACTUATOR_OUTPUTS | `uint8` | 16 | +| NUM_ACTUATOR_OUTPUT_GROUPS | `uint8` | 4 | for sanity checking | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -13,5 +36,6 @@ float32[16] output # output data, in natural output units # actuator_outputs_sim is used for SITL, HITL & SIH (with an output range of [-1, 1]) # TOPICS actuator_outputs actuator_outputs_sim actuator_outputs_debug - ``` + +::: diff --git a/docs/en/msg_docs/ActuatorServos.md b/docs/en/msg_docs/ActuatorServos.md index ea053f67a3..de537fcca6 100644 --- a/docs/en/msg_docs/ActuatorServos.md +++ b/docs/en/msg_docs/ActuatorServos.md @@ -1,11 +1,36 @@ +--- +pageClass: is-wide-page +--- + # ActuatorServos (UORB message) -Servo control message +Servo control message. Normalised output setpoint for up to 8 servos. Published by the vehicle's allocation and consumed by the actuator output drivers. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorServos.msg) +**TOPICS:** actuator_servos + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ------------ | ------------ | ---------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| timestamp_sample | `uint64` | us | | Sampling timestamp of the data this control response is based on | +| control | `float32[8]` | | [-1 : 1] | Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | +| NUM_CONTROLS | `uint8` | 8 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorServos.msg) + +::: details Click here to see original file ```c # Servo control message @@ -20,5 +45,6 @@ uint64 timestamp_sample # [us] Sampling timestamp of the data this control resp uint8 NUM_CONTROLS = 8 # float32[8] control # [-] [@range -1, 1] Normalized output. 1 means maximum positive position. -1 maximum negative position (if not supported by the output, <0 maps to NaN). NaN maps to disarmed. - ``` + +::: diff --git a/docs/en/msg_docs/ActuatorServosTrim.md b/docs/en/msg_docs/ActuatorServosTrim.md index 07f42a43ce..380f53832b 100644 --- a/docs/en/msg_docs/ActuatorServosTrim.md +++ b/docs/en/msg_docs/ActuatorServosTrim.md @@ -1,8 +1,31 @@ +--- +pageClass: is-wide-page +--- + # ActuatorServosTrim (UORB message) -Servo trims, added as offset to servo outputs +Servo trims, added as offset to servo outputs. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorServosTrim.msg) +**TOPICS:** actuator_servostrim + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | ------------ | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| trim | `float32[8]` | | | range: [-1, 1] | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------- | ------- | ----- | ----------- | +| NUM_CONTROLS | `uint8` | 8 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorServosTrim.msg) + +::: details Click here to see original file ```c # Servo trims, added as offset to servo outputs @@ -10,5 +33,6 @@ uint64 timestamp # time since system start (microseconds) uint8 NUM_CONTROLS = 8 float32[8] trim # range: [-1, 1] - ``` + +::: diff --git a/docs/en/msg_docs/ActuatorTest.md b/docs/en/msg_docs/ActuatorTest.md index 923d829774..820c6214fa 100644 --- a/docs/en/msg_docs/ActuatorTest.md +++ b/docs/en/msg_docs/ActuatorTest.md @@ -1,8 +1,38 @@ +--- +pageClass: is-wide-page +--- + # ActuatorTest (UORB message) +**TOPICS:** actuator_test +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorTest.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------- | --------- | ------------ | ---------- | ------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| action | `uint8` | | | one of ACTION\_\* | +| function | `uint16` | | | actuator output function | +| value | `float32` | | | range: [-1, 1], where 1 means maximum positive output, | +| timeout_ms | `uint32` | | | timeout in ms after which to exit test mode (if 0, do not time out) | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------------------- | ------- | ----- | ---------------------------------------------------- | +| ACTION_RELEASE_CONTROL | `uint8` | 0 | exit test mode for the given function | +| ACTION_DO_CONTROL | `uint8` | 1 | enable actuator test mode | +| FUNCTION_MOTOR1 | `uint8` | 101 | +| MAX_NUM_MOTORS | `uint8` | 12 | +| FUNCTION_SERVO1 | `uint8` | 201 | +| MAX_NUM_SERVOS | `uint8` | 8 | +| ORB_QUEUE_LENGTH | `uint8` | 16 | >= MAX_NUM_MOTORS to support code in esc_calibration | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorTest.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -26,5 +56,6 @@ float32 value # range: [-1, 1], where 1 means maximum positive output, uint32 timeout_ms # timeout in ms after which to exit test mode (if 0, do not time out) uint8 ORB_QUEUE_LENGTH = 16 # >= MAX_NUM_MOTORS to support code in esc_calibration - ``` + +::: diff --git a/docs/en/msg_docs/AdcReport.md b/docs/en/msg_docs/AdcReport.md index 50fde63ff5..9cb57dc674 100644 --- a/docs/en/msg_docs/AdcReport.md +++ b/docs/en/msg_docs/AdcReport.md @@ -1,10 +1,31 @@ +--- +pageClass: is-wide-page +--- + # AdcReport (UORB message) ADC raw data. Communicates raw data from an analog-to-digital converter (ADC) to other modules, such as battery status. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/AdcReport.msg) +**TOPICS:** adc_report + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------- | ----------- | ------------ | ---------- | ------------------------------------------------------------------------------------ | +| timestamp | `uint64` | us | | Time since system start | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| channel_id | `int16[16]` | | | ADC channel IDs, negative for non-existent, TODO: should be kept same as array index | +| raw_data | `int32[16]` | | | ADC channel raw value, accept negative value, valid if channel ID is positive | +| resolution | `uint32` | | | ADC channel resolution | +| v_ref | `float32` | V | | ADC channel voltage reference, use to calculate LSB voltage(lsb=scale/resolution) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/AdcReport.msg) + +::: details Click here to see original file ```c # ADC raw data. @@ -17,5 +38,6 @@ int16[16] channel_id # [-] ADC channel IDs, negative for non-existent, TODO: sh int32[16] raw_data # [-] ADC channel raw value, accept negative value, valid if channel ID is positive uint32 resolution # [-] ADC channel resolution float32 v_ref # [V] ADC channel voltage reference, use to calculate LSB voltage(lsb=scale/resolution) - ``` + +::: diff --git a/docs/en/msg_docs/Airspeed.md b/docs/en/msg_docs/Airspeed.md index 949af8d5e7..d769925620 100644 --- a/docs/en/msg_docs/Airspeed.md +++ b/docs/en/msg_docs/Airspeed.md @@ -1,11 +1,31 @@ +--- +pageClass: is-wide-page +--- + # Airspeed (UORB message) -Airspeed data from sensors +Airspeed data from sensors. This is published by airspeed sensor drivers, CAN airspeed sensors, simulators. It is subscribed by the airspeed selector module, which validates the data from multiple sensors and passes on a single estimation to the EKF, controllers and telemetry providers. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Airspeed.msg) +**TOPICS:** airspeed + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------- | --------- | ------------ | ---------- | -------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| timestamp_sample | `uint64` | us | | Timestamp of the raw data | +| indicated_airspeed_m_s | `float32` | m/s | | Indicated airspeed | +| true_airspeed_m_s | `float32` | m/s | | True airspeed | +| confidence | `float32` | | [0 : 1] | Confidence value for this sensor | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Airspeed.msg) + +::: details Click here to see original file ```c # Airspeed data from sensors @@ -18,5 +38,6 @@ uint64 timestamp_sample # [us] Timestamp of the raw data float32 indicated_airspeed_m_s # [m/s] Indicated airspeed float32 true_airspeed_m_s # [m/s] True airspeed float32 confidence # [@range 0,1] Confidence value for this sensor - ``` + +::: diff --git a/docs/en/msg_docs/AirspeedValidated.md b/docs/en/msg_docs/AirspeedValidated.md index 61f607e7fa..92b2f35f1d 100644 --- a/docs/en/msg_docs/AirspeedValidated.md +++ b/docs/en/msg_docs/AirspeedValidated.md @@ -1,11 +1,55 @@ +--- +pageClass: is-wide-page +--- + # AirspeedValidated (UORB message) -Validated airspeed +Validated airspeed. Provides information about airspeed (indicated, true, calibrated) and the source of the data. Used by controllers, estimators and for airspeed reporting to operator. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/AirspeedValidated.msg) +**TOPICS:** airspeed_validated + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------------------- | --------- | ------------ | ----------------- | ---------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| indicated_airspeed_m_s | `float32` | m/s | | Indicated airspeed (IAS) (Invalid: NaN) | +| calibrated_airspeed_m_s | `float32` | m/s | | Calibrated airspeed (CAS) (Invalid: NaN) | +| true_airspeed_m_s | `float32` | m/s | | True airspeed (TAS) (Invalid: NaN) | +| airspeed_source | `int8` | | [SOURCE](#SOURCE) | Source of currently published airspeed values | +| calibrated_ground_minus_wind_m_s | `float32` | m/s | | CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption (Invalid: NaN) | +| calibraded_airspeed_synth_m_s | `float32` | m/s | | Synthetic airspeed (Invalid: NaN) | +| airspeed_derivative_filtered | `float32` | m/s^2 | | Filtered indicated airspeed derivative | +| throttle_filtered | `float32` | | | Filtered fixed-wing throttle | +| pitch_filtered | `float32` | rad | | Filtered pitch | + +## Enums + +### SOURCE {#SOURCE} + +| Name | Type | Value | Description | +| ----------------------------------------------------------------- | ------ | ----- | ----------------------- | +| SOURCE_DISABLED | `int8` | -1 | Disabled | +| SOURCE_GROUND_MINUS_WIND | `int8` | 0 | Ground speed minus wind | +| SOURCE_SENSOR_1 | `int8` | 1 | Sensor 1 | +| SOURCE_SENSOR_2 | `int8` | 2 | Sensor 2 | +| SOURCE_SENSOR_3 | `int8` | 3 | Sensor 3 | +| SOURCE_SYNTHETIC | `int8` | 4 | Synthetic airspeed | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 1 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/AirspeedValidated.msg) + +::: details Click here to see original file ```c # Validated airspeed @@ -35,5 +79,6 @@ float32 calibraded_airspeed_synth_m_s # [m/s] [@invalid NaN] Synthetic airsp float32 airspeed_derivative_filtered # [m/s^2] Filtered indicated airspeed derivative float32 throttle_filtered # [-] Filtered fixed-wing throttle float32 pitch_filtered # [rad] Filtered pitch - ``` + +::: diff --git a/docs/en/msg_docs/AirspeedValidatedV0.md b/docs/en/msg_docs/AirspeedValidatedV0.md index 9cd392a955..8650ee3116 100644 --- a/docs/en/msg_docs/AirspeedValidatedV0.md +++ b/docs/en/msg_docs/AirspeedValidatedV0.md @@ -1,8 +1,38 @@ +--- +pageClass: is-wide-page +--- + # AirspeedValidatedV0 (UORB message) +**TOPICS:** airspeed_validatedv0 +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/AirspeedValidatedV0.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------------------------- | --------- | ------------ | ---------- | ------------------------------------------------------------------------------------------------------------------------------------ | +| timestamp | `uint64` | | | time since system start (microseconds) | +| indicated_airspeed_m_s | `float32` | | | indicated airspeed in m/s (IAS), set to NAN if invalid | +| calibrated_airspeed_m_s | `float32` | | | calibrated airspeed in m/s (CAS, accounts for instrumentation errors), set to NAN if invalid | +| true_airspeed_m_s | `float32` | | | true filtered airspeed in m/s (TAS), set to NAN if invalid | +| calibrated_ground_minus_wind_m_s | `float32` | | | CAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid | +| true_ground_minus_wind_m_s | `float32` | | | TAS calculated from groundspeed - windspeed, where windspeed is estimated based on a zero-sideslip assumption, set to NAN if invalid | +| airspeed_sensor_measurement_valid | `bool` | | | True if data from at least one airspeed sensor is declared valid. | +| selected_airspeed_index | `int8` | | | 1-3: airspeed sensor index, 0: groundspeed-windspeed, -1: airspeed invalid | +| airspeed_derivative_filtered | `float32` | | | filtered indicated airspeed derivative [m/s/s] | +| throttle_filtered | `float32` | | | filtered fixed-wing throttle [-] | +| pitch_filtered | `float32` | | | filtered pitch [rad] | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/AirspeedValidatedV0.msg) + +::: details Click here to see original file ```c uint32 MESSAGE_VERSION = 0 @@ -23,5 +53,6 @@ int8 selected_airspeed_index # 1-3: airspeed sensor index, 0: groundspeed-win float32 airspeed_derivative_filtered # filtered indicated airspeed derivative [m/s/s] float32 throttle_filtered # filtered fixed-wing throttle [-] float32 pitch_filtered # filtered pitch [rad] - ``` + +::: diff --git a/docs/en/msg_docs/AirspeedWind.md b/docs/en/msg_docs/AirspeedWind.md index 23e91399b0..3be13ac999 100644 --- a/docs/en/msg_docs/AirspeedWind.md +++ b/docs/en/msg_docs/AirspeedWind.md @@ -1,6 +1,10 @@ +--- +pageClass: is-wide-page +--- + # AirspeedWind (UORB message) -Wind estimate (from airspeed_selector) +Wind estimate (from airspeed_selector). Contains wind estimation and airspeed innovation information estimated by the WindEstimator in the airspeed selector module. @@ -8,7 +12,41 @@ in the airspeed selector module. This message is published by the airspeed selector for debugging purposes, and is not subscribed to by any other modules. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/AirspeedWind.msg) +**TOPICS:** airspeed_wind + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------- | --------- | ------------ | ---------- | --------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| timestamp_sample | `uint64` | us | | Timestamp of the raw data | +| windspeed_north | `float32` | m/s | | Wind component in north / X direction | +| windspeed_east | `float32` | m/s | | Wind component in east / Y direction | +| variance_north | `float32` | (m/s)^2 | | Wind estimate error variance in north / X direction (Invalid: 0 if not estimated) | +| variance_east | `float32` | (m/s)^2 | | Wind estimate error variance in east / Y direction (Invalid: 0 if not estimated) | +| tas_innov | `float32` | m/s | | True airspeed innovation | +| tas_innov_var | `float32` | m/s | | True airspeed innovation variance | +| tas_scale_raw | `float32` | | | Estimated true airspeed scale factor (not validated) | +| tas_scale_raw_var | `float32` | | | True airspeed scale factor variance | +| tas_scale_validated | `float32` | | | Estimated true airspeed scale factor after validation | +| beta_innov | `float32` | rad | | Sideslip measurement innovation | +| beta_innov_var | `float32` | rad^2 | | Sideslip measurement innovation variance | +| source | `uint8` | | | source of wind estimate | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------------- | ------- | ----- | ---------------------------------------------------------------------------------- | +| SOURCE_AS_BETA_ONLY | `uint8` | 0 | Wind estimate only based on synthetic sideslip fusion | +| SOURCE_AS_SENSOR_1 | `uint8` | 1 | Combined synthetic sideslip and airspeed fusion (data from first airspeed sensor) | +| SOURCE_AS_SENSOR_2 | `uint8` | 2 | Combined synthetic sideslip and airspeed fusion (data from second airspeed sensor) | +| SOURCE_AS_SENSOR_3 | `uint8` | 3 | Combined synthetic sideslip and airspeed fusion (data from third airspeed sensor) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/AirspeedWind.msg) + +::: details Click here to see original file ```c # Wind estimate (from airspeed_selector) @@ -45,5 +83,6 @@ uint8 SOURCE_AS_BETA_ONLY = 0 # Wind estimate only based on synthetic sideslip f uint8 SOURCE_AS_SENSOR_1 = 1 # Combined synthetic sideslip and airspeed fusion (data from first airspeed sensor) uint8 SOURCE_AS_SENSOR_2 = 2 # Combined synthetic sideslip and airspeed fusion (data from second airspeed sensor) uint8 SOURCE_AS_SENSOR_3 = 3 # Combined synthetic sideslip and airspeed fusion (data from third airspeed sensor) - ``` + +::: diff --git a/docs/en/msg_docs/ArmingCheckReply.md b/docs/en/msg_docs/ArmingCheckReply.md index 14af54f0d1..b6119357d7 100644 --- a/docs/en/msg_docs/ArmingCheckReply.md +++ b/docs/en/msg_docs/ArmingCheckReply.md @@ -1,6 +1,10 @@ +--- +pageClass: is-wide-page +--- + # ArmingCheckReply (UORB message) -Arming check reply +Arming check reply. This is a response to an ArmingCheckRequest message sent by the FMU to an external component, such as a ROS 2 navigation mode. The response contains the current set of external mode requirements, and a queue of events indicating recent failures to set the mode (which the FMU may then forward to a ground station). @@ -9,7 +13,54 @@ The request is sent regularly to all registered ROS modes, even while armed, so Note that the external component is identified by its registration_id, which is allocated to the component during registration (arming_check_id in RegisterExtComponentReply). The message is not used by internal/FMU components, as their mode requirements are known at compile time. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ArmingCheckReply.msg) +**TOPICS:** arming_checkreply + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------------------- | ---------- | ------------ | ------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start. | +| request_id | `uint8` | | | Id of ArmingCheckRequest for which this is a response | +| registration_id | `uint8` | | | Id of external component emitting this response | +| health_component_index | `uint8` | | [HEALTH_COMPONENT_INDEX](#HEALTH_COMPONENT_INDEX) | +| health_component_is_present | `bool` | | | Unused. Intended for use with health events interface (health_component_t in events.json) | +| health_component_warning | `bool` | | | Unused. Intended for use with health events interface (health_component_t in events.json) | +| health_component_error | `bool` | | | Unused. Intended for use with health events interface (health_component_t in events.json) | +| can_arm_and_run | `bool` | | | True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed | +| num_events | `uint8` | | | Number of queued failure messages (Event) in the events field | +| events | `Event[5]` | | | Arming failure reasons (Queue of events to report to GCS) | +| mode_req_angular_velocity | `bool` | | | Requires angular velocity estimate (e.g. from gyroscope) | +| mode_req_attitude | `bool` | | | Requires an attitude estimate | +| mode_req_local_alt | `bool` | | | Requires a local altitude estimate | +| mode_req_local_position | `bool` | | | Requires a local position estimate | +| mode_req_local_position_relaxed | `bool` | | | Requires a more relaxed global position estimate | +| mode_req_global_position | `bool` | | | Requires a global position estimate | +| mode_req_global_position_relaxed | `bool` | | | Requires a relaxed global position estimate | +| mode_req_mission | `bool` | | | Requires an uploaded mission | +| mode_req_home_position | `bool` | | | Requires a home position (such as RTL/Return mode) | +| mode_req_prevent_arming | `bool` | | | Prevent arming (such as in Land mode) | +| mode_req_manual_control | `bool` | | | Requires a manual controller | + +## Enums + +### HEALTH_COMPONENT_INDEX {#HEALTH_COMPONENT_INDEX} + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------- | ------- | ----- | --------------------------------------------------------- | +| HEALTH_COMPONENT_INDEX_NONE | `uint8` | 0 | Index of health component for which this response applies | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 1 | +| ORB_QUEUE_LENGTH | `uint8` | 4 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ArmingCheckReply.msg) + +::: details Click here to see original file ```c # Arming check reply @@ -55,5 +106,6 @@ bool mode_req_prevent_arming # Prevent arming (such as in Land mode) bool mode_req_manual_control # Requires a manual controller uint8 ORB_QUEUE_LENGTH = 4 - ``` + +::: diff --git a/docs/en/msg_docs/ArmingCheckReplyV0.md b/docs/en/msg_docs/ArmingCheckReplyV0.md index 48917da802..d93dd9a1b6 100644 --- a/docs/en/msg_docs/ArmingCheckReplyV0.md +++ b/docs/en/msg_docs/ArmingCheckReplyV0.md @@ -1,6 +1,49 @@ +--- +pageClass: is-wide-page +--- + # ArmingCheckReplyV0 (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/ArmingCheckReplyV0.msg) +**TOPICS:** arming_checkreplyv0 + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------------------- | ------------ | ------------ | ---------- | ------------------------------------------------------------------------ | +| timestamp | `uint64` | | | time since system start (microseconds) | +| request_id | `uint8` | | | +| registration_id | `uint8` | | | +| health_component_index | `uint8` | | | HEALTH*COMPONENT_INDEX*\* | +| health_component_is_present | `bool` | | | +| health_component_warning | `bool` | | | +| health_component_error | `bool` | | | +| can_arm_and_run | `bool` | | | whether arming is possible, and if it's a navigation mode, if it can run | +| num_events | `uint8` | | | +| events | `EventV0[5]` | | | +| mode_req_angular_velocity | `bool` | | | +| mode_req_attitude | `bool` | | | +| mode_req_local_alt | `bool` | | | +| mode_req_local_position | `bool` | | | +| mode_req_local_position_relaxed | `bool` | | | +| mode_req_global_position | `bool` | | | +| mode_req_mission | `bool` | | | +| mode_req_home_position | `bool` | | | +| mode_req_prevent_arming | `bool` | | | +| mode_req_manual_control | `bool` | | | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | +| HEALTH_COMPONENT_INDEX_NONE | `uint8` | 0 | +| ORB_QUEUE_LENGTH | `uint8` | 4 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/ArmingCheckReplyV0.msg) + +::: details Click here to see original file ```c uint32 MESSAGE_VERSION = 0 @@ -37,5 +80,6 @@ bool mode_req_manual_control uint8 ORB_QUEUE_LENGTH = 4 - ``` + +::: diff --git a/docs/en/msg_docs/ArmingCheckRequest.md b/docs/en/msg_docs/ArmingCheckRequest.md index d093dfb5e1..083c8743e1 100644 --- a/docs/en/msg_docs/ArmingCheckRequest.md +++ b/docs/en/msg_docs/ArmingCheckRequest.md @@ -1,6 +1,10 @@ +--- +pageClass: is-wide-page +--- + # ArmingCheckRequest (UORB message) -Arming check request +Arming check request. Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. @@ -9,7 +13,27 @@ The request is sent regularly, even while armed, so that the FMU always knows th The reply will include the published request_id, allowing correlation of all arming check information for a particular request. The reply will also include the registration_id for each external component, provided to it during the registration process (RegisterExtComponentReply). -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ArmingCheckRequest.msg) +**TOPICS:** arming_checkrequest + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------------ | -------- | ------------ | ---------- | --------------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| request_id | `uint8` | | | Id of this request. Allows correlation with associated ArmingCheckReply messages. | +| valid_registrations_mask | `uint32` | | | Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 1 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ArmingCheckRequest.msg) + +::: details Click here to see original file ```c # Arming check request @@ -28,5 +52,6 @@ uint64 timestamp # [us] Time since system start uint8 request_id # [-] Id of this request. Allows correlation with associated ArmingCheckReply messages. uint32 valid_registrations_mask # [-] Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) - ``` + +::: diff --git a/docs/en/msg_docs/ArmingCheckRequestV0.md b/docs/en/msg_docs/ArmingCheckRequestV0.md index f5680c11f2..986bb893b3 100644 --- a/docs/en/msg_docs/ArmingCheckRequestV0.md +++ b/docs/en/msg_docs/ArmingCheckRequestV0.md @@ -1,3 +1,7 @@ +--- +pageClass: is-wide-page +--- + # ArmingCheckRequestV0 (UORB message) Arming check request. @@ -9,7 +13,26 @@ The request is sent regularly, even while armed, so that the FMU always knows th The reply will include the published request_id, allowing correlation of all arming check information for a particular request. The reply will also include the registration_id for each external component, provided to it during the registration process (RegisterExtComponentReply). -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/ArmingCheckRequestV0.msg) +**TOPICS:** arming_checkrequestv0 + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------- | -------- | ------------ | ---------- | --------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start. | +| request_id | `uint8` | | | Id of this request. Allows correlation with associated ArmingCheckReply messages. | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/ArmingCheckRequestV0.msg) + +::: details Click here to see original file ```c # Arming check request. @@ -26,5 +49,6 @@ uint32 MESSAGE_VERSION = 0 uint64 timestamp # [us] Time since system start. uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. - ``` + +::: diff --git a/docs/en/msg_docs/AutotuneAttitudeControlStatus.md b/docs/en/msg_docs/AutotuneAttitudeControlStatus.md index 31a47ef204..e4bbd32fa9 100644 --- a/docs/en/msg_docs/AutotuneAttitudeControlStatus.md +++ b/docs/en/msg_docs/AutotuneAttitudeControlStatus.md @@ -1,13 +1,67 @@ +--- +pageClass: is-wide-page +--- + # AutotuneAttitudeControlStatus (UORB message) -Autotune attitude control status +Autotune attitude control status. This message is published by the fw_autotune_attitude_control and mc_autotune_attitude_control modules when the user engages autotune, and is subscribed to by the respective attitude controllers to command rate setpoints. The rate_sp field is consumed by the controllers, while the remaining fields (model coefficients, gains, filters, and autotune state) are used for logging and debugging. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/AutotuneAttitudeControlStatus.msg) +**TOPICS:** autotune_attitudecontrol_status + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | ------------ | ------------ | --------------- | --------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| coeff | `float32[5]` | | | Coefficients of the identified discrete-time model | +| coeff_var | `float32[5]` | | | Coefficients' variance of the identified discrete-time model | +| fitness | `float32` | | | Fitness of the parameter estimate | +| innov | `float32` | rad/s | | Innovation (residual error between model and measured output) | +| dt_model | `float32` | s | | Model sample time used for identification | +| kc | `float32` | | | Proportional rate-loop gain (ideal form) | +| ki | `float32` | | | Integral rate-loop gain (ideal form) | +| kd | `float32` | | | Derivative rate-loop gain (ideal form) | +| kff | `float32` | | | Feedforward rate-loop gain | +| att_p | `float32` | | | Proportional attitude gain | +| rate_sp | `float32[3]` | rad/s | | Rate setpoint commanded to the attitude controller. | +| u_filt | `float32` | | | Filtered input signal (normalized torque setpoint) used in system identification. | +| y_filt | `float32` | rad/s | | Filtered output signal (angular velocity) used in system identification. | +| state | `uint8` | | [STATE](#STATE) | Current state of the autotune procedure. | + +## Enums + +### STATE {#STATE} + +| Name | Type | Value | Description | +| ------------------------------------------------------------------------------- | ------- | ----- | -------------------------------------------------------- | +| STATE_IDLE | `uint8` | 0 | Idle (not running) | +| STATE_INIT | `uint8` | 1 | Initialize filters and setup | +| STATE_ROLL_AMPLITUDE_DETECTION | `uint8` | 2 | FW only: determine required excitation amplitude (roll) | +| STATE_ROLL | `uint8` | 3 | Roll-axis excitation and model identification | +| STATE_ROLL_PAUSE | `uint8` | 4 | Pause to return to level flight | +| STATE_PITCH_AMPLITUDE_DETECTION | `uint8` | 5 | FW only: determine required excitation amplitude (pitch) | +| STATE_PITCH | `uint8` | 6 | Pitch-axis excitation and model identification | +| STATE_PITCH_PAUSE | `uint8` | 7 | Pause to return to level flight | +| STATE_YAW_AMPLITUDE_DETECTION | `uint8` | 8 | FW only: determine required excitation amplitude (yaw) | +| STATE_YAW | `uint8` | 9 | Yaw-axis excitation and model identification | +| STATE_YAW_PAUSE | `uint8` | 10 | Pause to return to level flight | +| STATE_VERIFICATION | `uint8` | 11 | Verify model and candidate gains | +| STATE_APPLY | `uint8` | 12 | Apply gains | +| STATE_TEST | `uint8` | 13 | Test gains in closed-loop | +| STATE_COMPLETE | `uint8` | 14 | Tuning completed successfully | +| STATE_FAIL | `uint8` | 15 | Tuning failed (model invalid or controller unstable) | +| STATE_WAIT_FOR_DISARM | `uint8` | 16 | Waiting for disarm before finalizing | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/AutotuneAttitudeControlStatus.msg) + +::: details Click here to see original file ```c # Autotune attitude control status @@ -55,5 +109,6 @@ uint8 STATE_TEST = 13 # Test gains in closed-loop uint8 STATE_COMPLETE = 14 # Tuning completed successfully uint8 STATE_FAIL = 15 # Tuning failed (model invalid or controller unstable) uint8 STATE_WAIT_FOR_DISARM = 16 # Waiting for disarm before finalizing - ``` + +::: diff --git a/docs/en/msg_docs/BatteryInfo.md b/docs/en/msg_docs/BatteryInfo.md index 4b0c2823ce..ca105f0d26 100644 --- a/docs/en/msg_docs/BatteryInfo.md +++ b/docs/en/msg_docs/BatteryInfo.md @@ -1,11 +1,29 @@ +--- +pageClass: is-wide-page +--- + # BatteryInfo (UORB message) -Battery information +Battery information. Static or near-invariant battery information. Should be streamed at low rate. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/BatteryInfo.msg) +**TOPICS:** battery_info + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------- | ---------- | ------------ | ---------- | ------------------------------------------------------------------------------------------ | +| timestamp | `uint64` | us | | Time since system start | +| id | `uint8` | | | Must match the id in the battery_status message for the same battery | +| serial_number | `char[32]` | | | Serial number of the battery pack in ASCII characters, 0 terminated (Invalid: 0 All bytes) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/BatteryInfo.msg) + +::: details Click here to see original file ```c # Battery information @@ -17,5 +35,6 @@ uint64 timestamp # [us] Time since system start uint8 id # Must match the id in the battery_status message for the same battery char[32] serial_number # [@invalid 0 All bytes] Serial number of the battery pack in ASCII characters, 0 terminated - ``` + +::: diff --git a/docs/en/msg_docs/BatteryStatus.md b/docs/en/msg_docs/BatteryStatus.md index ec2c19c59e..b9ba00d63a 100644 --- a/docs/en/msg_docs/BatteryStatus.md +++ b/docs/en/msg_docs/BatteryStatus.md @@ -1,12 +1,116 @@ +--- +pageClass: is-wide-page +--- + # BatteryStatus (UORB message) -Battery status +Battery status. Battery status information for up to 3 battery instances. These are populated from power module and smart battery device drivers, and one battery updated from MAVLink. Battery instance information is also logged and streamed in MAVLink telemetry. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/BatteryStatus.msg) +**TOPICS:** battery_status + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------------- | ------------- | ------------ | ---------------------------------- | ----------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| connected | `bool` | | | Whether or not a battery is connected. For power modules this is based on a voltage threshold. | +| voltage_v | `float32` | V | | Battery voltage (Invalid: 0) | +| current_a | `float32` | A | | Battery current (Invalid: -1) | +| current_average_a | `float32` | A | | Battery current average (for FW average in level flight) (Invalid: -1) | +| discharged_mah | `float32` | mAh | | Discharged amount (Invalid: -1) | +| remaining | `float32` | | [0 : 1] | Remaining capacity (Invalid: -1) | +| scale | `float32` | | [1 : -] | Scaling factor to compensate for lower actuation power caused by voltage sag (Invalid: -1) | +| time_remaining_s | `float32` | s | | Predicted time remaining until battery is empty under previous averaged load (Invalid: NaN) | +| temperature | `float32` | °C | | Temperature of the battery (Invalid: NaN) | +| cell_count | `uint8` | | | Number of cells (Invalid: 0) | +| source | `uint8` | | [SOURCE](#SOURCE) | Battery source | +| priority | `uint8` | | | Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 | +| capacity | `uint16` | mAh | | Capacity of the battery when fully charged | +| cycle_count | `uint16` | | | Number of discharge cycles the battery has experienced | +| average_time_to_empty | `uint16` | minutes | | Predicted remaining battery capacity based on the average rate of discharge | +| manufacture_date | `uint16` | | | Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 | +| state_of_health | `uint16` | % | [0 : 100] | State of health. FullChargeCapacity/DesignCapacity | +| max_error | `uint16` | % | [1 : 100] | Max error, expected margin of error in the state-of-charge calculation | +| id | `uint8` | | | ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed | +| interface_error | `uint16` | | | Interface error counter | +| voltage_cell_v | `float32[14]` | V | | Battery individual cell voltages (Invalid: 0) | +| max_cell_voltage_delta | `float32` | V | | Max difference between individual cell voltages | +| is_powering_off | `bool` | | | Power off event imminent indication, false if unknown | +| is_required | `bool` | | | Set if the battery is explicitly required before arming | +| warning | `uint8` | | [WARNING](#WARNING)[STATE](#STATE) | Current battery warning | +| faults | `uint16` | | [FAULT](#FAULT) | Smart battery supply status/fault flags (bitmask) for health indication | +| full_charge_capacity_wh | `float32` | Wh | | Compensated battery capacity | +| remaining_capacity_wh | `float32` | Wh | | Compensated battery capacity remaining | +| over_discharge_count | `uint16` | | | Number of battery overdischarge | +| nominal_voltage | `float32` | V | | Nominal voltage of the battery pack | +| internal_resistance_estimate | `float32` | Ohm | | Internal resistance per cell estimate | +| ocv_estimate | `float32` | V | | Open circuit voltage estimate | +| ocv_estimate_filtered | `float32` | V | | Filtered open circuit voltage estimate | +| volt_based_soc_estimate | `float32` | | [0 : 1] | Normalized volt based state of charge estimate | +| voltage_prediction | `float32` | V | | Predicted voltage | +| prediction_error | `float32` | V | | Prediction error | +| estimation_covariance_norm | `float32` | | | Norm of the covariance matrix | + +## Enums + +### SOURCE {#SOURCE} + +| Name | Type | Value | Description | +| ------------------------------------------------------- | ------- | ----- | ---------------------------------------------- | +| SOURCE_POWER_MODULE | `uint8` | 0 | Power module (analog ADC or I2C power monitor) | +| SOURCE_EXTERNAL | `uint8` | 1 | External (MAVLink, CAN, or external driver) | +| SOURCE_ESCS | `uint8` | 2 | ESCs (via ESC telemetry) | + +### WARNING {#WARNING} + +| Name | Type | Value | Description | +| --------------------------------------------------- | ------- | ----- | -------------------------------------------- | +| WARNING_NONE | `uint8` | 0 | No battery low voltage warning active | +| WARNING_LOW | `uint8` | 1 | Low voltage warning | +| WARNING_CRITICAL | `uint8` | 2 | Critical voltage, return / abort immediately | +| WARNING_EMERGENCY | `uint8` | 3 | Immediate landing required | +| WARNING_FAILED | `uint8` | 4 | Battery has failed completely | + +### STATE {#STATE} + +| Name | Type | Value | Description | +| ----------------------------------------------- | ------- | ----- | ------------------------------------------------------------------------------------------------------------------------------------------------- | +| STATE_UNHEALTHY | `uint8` | 6 | Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field | +| STATE_CHARGING | `uint8` | 7 | Battery is charging | + +### FAULT {#FAULT} + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------- | ------- | ----- | -------------------------------------------------------------------------------------------------------------- | +| FAULT_DEEP_DISCHARGE | `uint8` | 0 | Battery has deep discharged | +| FAULT_SPIKES | `uint8` | 1 | Voltage spikes | +| FAULT_CELL_FAIL | `uint8` | 2 | One or more cells have failed | +| FAULT_OVER_CURRENT | `uint8` | 3 | Over-current | +| FAULT_OVER_TEMPERATURE | `uint8` | 4 | Over-temperature | +| FAULT_UNDER_TEMPERATURE | `uint8` | 5 | Under-temperature fault | +| FAULT_INCOMPATIBLE_VOLTAGE | `uint8` | 6 | Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage) | +| FAULT_INCOMPATIBLE_FIRMWARE | `uint8` | 7 | Battery firmware is not compatible with current autopilot firmware | +| FAULT_INCOMPATIBLE_MODEL | `uint8` | 8 | Battery model is not supported by the system | +| FAULT_HARDWARE_FAILURE | `uint8` | 9 | Hardware problem | +| FAULT_FAILED_TO_ARM | `uint8` | 10 | Battery had a problem while arming | +| FAULT_COUNT | `uint8` | 11 | Counter. Keep this as last element | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 1 | +| MAX_INSTANCES | `uint8` | 3 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/BatteryStatus.msg) + +::: details Click here to see original file ```c # Battery status @@ -88,5 +192,6 @@ float32 volt_based_soc_estimate # [-] [@range 0, 1] Normalized volt based float32 voltage_prediction # [V] Predicted voltage float32 prediction_error # [V] Prediction error float32 estimation_covariance_norm # [-] Norm of the covariance matrix - ``` + +::: diff --git a/docs/en/msg_docs/BatteryStatusV0.md b/docs/en/msg_docs/BatteryStatusV0.md index cd900a1f17..4dfdd4e530 100644 --- a/docs/en/msg_docs/BatteryStatusV0.md +++ b/docs/en/msg_docs/BatteryStatusV0.md @@ -1,12 +1,117 @@ +--- +pageClass: is-wide-page +--- + # BatteryStatusV0 (UORB message) -Battery status +Battery status. Battery status information for up to 4 battery instances. These are populated from power module and smart battery device drivers, and one battery updated from MAVLink. Battery instance information is also logged and streamed in MAVLink telemetry. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/BatteryStatusV0.msg) +**TOPICS:** battery_statusv0 + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------------- | ------------- | ------------ | ---------------------------------- | ----------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| connected | `bool` | | | Whether or not a battery is connected. For power modules this is based on a voltage threshold. | +| voltage_v | `float32` | V | | Battery voltage (Invalid: 0) | +| current_a | `float32` | A | | Battery current (Invalid: -1) | +| current_average_a | `float32` | A | | Battery current average (for FW average in level flight) (Invalid: -1) | +| discharged_mah | `float32` | mAh | | Discharged amount (Invalid: -1) | +| remaining | `float32` | | [0 : 1] | Remaining capacity (Invalid: -1) | +| scale | `float32` | | [1 : -] | Scaling factor to compensate for lower actuation power caused by voltage sag (Invalid: -1) | +| time_remaining_s | `float32` | s | | Predicted time remaining until battery is empty under previous averaged load (Invalid: NaN) | +| temperature | `float32` | °C | | Temperature of the battery (Invalid: NaN) | +| cell_count | `uint8` | | | Number of cells (Invalid: 0) | +| source | `uint8` | | [SOURCE](#SOURCE) | Battery source | +| priority | `uint8` | | | Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 | +| capacity | `uint16` | mAh | | Capacity of the battery when fully charged | +| cycle_count | `uint16` | | | Number of discharge cycles the battery has experienced | +| average_time_to_empty | `uint16` | minutes | | Predicted remaining battery capacity based on the average rate of discharge | +| serial_number | `uint16` | | | Serial number of the battery pack | +| manufacture_date | `uint16` | | | Manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 | +| state_of_health | `uint16` | % | [0 : 100] | State of health. FullChargeCapacity/DesignCapacity | +| max_error | `uint16` | % | [1 : 100] | Max error, expected margin of error in the state-of-charge calculation | +| id | `uint8` | | | ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed | +| interface_error | `uint16` | | | Interface error counter | +| voltage_cell_v | `float32[14]` | V | | Battery individual cell voltages (Invalid: 0) | +| max_cell_voltage_delta | `float32` | | | Max difference between individual cell voltages | +| is_powering_off | `bool` | | | Power off event imminent indication, false if unknown | +| is_required | `bool` | | | Set if the battery is explicitly required before arming | +| warning | `uint8` | | [WARNING](#WARNING)[STATE](#STATE) | Current battery warning | +| faults | `uint16` | | [FAULT](#FAULT) | Smart battery supply status/fault flags (bitmask) for health indication | +| full_charge_capacity_wh | `float32` | Wh | | Compensated battery capacity | +| remaining_capacity_wh | `float32` | Wh | | Compensated battery capacity remaining | +| over_discharge_count | `uint16` | | | Number of battery overdischarge | +| nominal_voltage | `float32` | V | | Nominal voltage of the battery pack | +| internal_resistance_estimate | `float32` | Ohm | | Internal resistance per cell estimate | +| ocv_estimate | `float32` | V | | Open circuit voltage estimate | +| ocv_estimate_filtered | `float32` | V | | Filtered open circuit voltage estimate | +| volt_based_soc_estimate | `float32` | | [0 : 1] | Normalized volt based state of charge estimate | +| voltage_prediction | `float32` | V | | Predicted voltage | +| prediction_error | `float32` | V | | Prediction error | +| estimation_covariance_norm | `float32` | | | Norm of the covariance matrix | + +## Enums + +### SOURCE {#SOURCE} + +| Name | Type | Value | Description | +| ------------------------------------------------------- | ------- | ----- | ---------------------------------------------- | +| SOURCE_POWER_MODULE | `uint8` | 0 | Power module (analog ADC or I2C power monitor) | +| SOURCE_EXTERNAL | `uint8` | 1 | External (MAVLink, CAN, or external driver) | +| SOURCE_ESCS | `uint8` | 2 | ESCs (via ESC telemetry) | + +### WARNING {#WARNING} + +| Name | Type | Value | Description | +| --------------------------------------------------- | ------- | ----- | -------------------------------------------- | +| WARNING_NONE | `uint8` | 0 | No battery low voltage warning active | +| WARNING_LOW | `uint8` | 1 | Low voltage warning | +| WARNING_CRITICAL | `uint8` | 2 | Critical voltage, return / abort immediately | +| WARNING_EMERGENCY | `uint8` | 3 | Immediate landing required | +| WARNING_FAILED | `uint8` | 4 | Battery has failed completely | + +### STATE {#STATE} + +| Name | Type | Value | Description | +| ----------------------------------------------- | ------- | ----- | ------------------------------------------------------------------------------------------------------------------------------------------------- | +| STATE_UNHEALTHY | `uint8` | 6 | Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field | +| STATE_CHARGING | `uint8` | 7 | Battery is charging | + +### FAULT {#FAULT} + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------- | ------- | ----- | -------------------------------------------------------------------------------------------------------------- | +| FAULT_DEEP_DISCHARGE | `uint8` | 0 | Battery has deep discharged | +| FAULT_SPIKES | `uint8` | 1 | Voltage spikes | +| FAULT_CELL_FAIL | `uint8` | 2 | One or more cells have failed | +| FAULT_OVER_CURRENT | `uint8` | 3 | Over-current | +| FAULT_OVER_TEMPERATURE | `uint8` | 4 | Over-temperature | +| FAULT_UNDER_TEMPERATURE | `uint8` | 5 | Under-temperature fault | +| FAULT_INCOMPATIBLE_VOLTAGE | `uint8` | 6 | Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage) | +| FAULT_INCOMPATIBLE_FIRMWARE | `uint8` | 7 | Battery firmware is not compatible with current autopilot firmware | +| FAULT_INCOMPATIBLE_MODEL | `uint8` | 8 | Battery model is not supported by the system | +| FAULT_HARDWARE_FAILURE | `uint8` | 9 | Hardware problem | +| FAULT_FAILED_TO_ARM | `uint8` | 10 | Battery had a problem while arming | +| FAULT_COUNT | `uint8` | 11 | Counter. Keep this as last element | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | +| MAX_INSTANCES | `uint8` | 4 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/BatteryStatusV0.msg) + +::: details Click here to see original file ```c # Battery status @@ -88,5 +193,6 @@ float32 volt_based_soc_estimate # [@range 0, 1] Normalized volt based state of c float32 voltage_prediction # [V] Predicted voltage float32 prediction_error # [V] Prediction error float32 estimation_covariance_norm # Norm of the covariance matrix - ``` + +::: diff --git a/docs/en/msg_docs/ButtonEvent.md b/docs/en/msg_docs/ButtonEvent.md index 967f694fa6..34cf6e40e4 100644 --- a/docs/en/msg_docs/ButtonEvent.md +++ b/docs/en/msg_docs/ButtonEvent.md @@ -1,8 +1,29 @@ +--- +pageClass: is-wide-page +--- + # ButtonEvent (UORB message) +**TOPICS:** button_event safety_button +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| triggered | `bool` | | | Set to true if the event is triggered | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | ------- | ----- | ----------- | +| ORB_QUEUE_LENGTH | `uint8` | 2 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -11,5 +32,6 @@ bool triggered # Set to true if the event is triggered # TOPICS button_event safety_button uint8 ORB_QUEUE_LENGTH = 2 - ``` + +::: diff --git a/docs/en/msg_docs/CameraCapture.md b/docs/en/msg_docs/CameraCapture.md index fb73e30458..cc5fa015d5 100644 --- a/docs/en/msg_docs/CameraCapture.md +++ b/docs/en/msg_docs/CameraCapture.md @@ -1,8 +1,30 @@ +--- +pageClass: is-wide-page +--- + # CameraCapture (UORB message) +**TOPICS:** camera_capture +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CameraCapture.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------- | ------------ | ------------ | ---------- | -------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_utc | `uint64` | | | Capture time in UTC / GPS time | +| seq | `uint32` | | | Image sequence number | +| lat | `float64` | | | Latitude in degrees (WGS84) | +| lon | `float64` | | | Longitude in degrees (WGS84) | +| alt | `float32` | | | Altitude (AMSL) | +| ground_distance | `float32` | | | Altitude above ground (meters) | +| q | `float32[4]` | | | Attitude of the camera relative to NED earth-fixed frame when using a gimbal, otherwise vehicle attitude | +| result | `int8` | | | 1 for success, 0 for failure, -1 if camera does not provide feedback | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CameraCapture.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -14,5 +36,6 @@ float32 alt # Altitude (AMSL) float32 ground_distance # Altitude above ground (meters) float32[4] q # Attitude of the camera relative to NED earth-fixed frame when using a gimbal, otherwise vehicle attitude int8 result # 1 for success, 0 for failure, -1 if camera does not provide feedback - ``` + +::: diff --git a/docs/en/msg_docs/CameraStatus.md b/docs/en/msg_docs/CameraStatus.md index 1bf6d3b33c..47b724a6bd 100644 --- a/docs/en/msg_docs/CameraStatus.md +++ b/docs/en/msg_docs/CameraStatus.md @@ -1,13 +1,30 @@ +--- +pageClass: is-wide-page +--- + # CameraStatus (UORB message) +**TOPICS:** camera_status +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CameraStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------- | -------- | ------------ | ---------- | ------------------------------------------------ | +| timestamp | `uint64` | | | time since system start (microseconds) | +| active_sys_id | `uint8` | | | mavlink system id of the currently active camera | +| active_comp_id | `uint8` | | | mavlink component id of currently active camera | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CameraStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) uint8 active_sys_id # mavlink system id of the currently active camera uint8 active_comp_id # mavlink component id of currently active camera - ``` + +::: diff --git a/docs/en/msg_docs/CameraTrigger.md b/docs/en/msg_docs/CameraTrigger.md index a1949a7569..fee6698518 100644 --- a/docs/en/msg_docs/CameraTrigger.md +++ b/docs/en/msg_docs/CameraTrigger.md @@ -1,8 +1,31 @@ +--- +pageClass: is-wide-page +--- + # CameraTrigger (UORB message) +**TOPICS:** camera_trigger +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CameraTrigger.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------- | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_utc | `uint64` | | | UTC timestamp | +| seq | `uint32` | | | Image sequence number | +| feedback | `bool` | | | Trigger feedback from camera | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | -------- | ----- | ----------- | +| ORB_QUEUE_LENGTH | `uint32` | 2 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CameraTrigger.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -12,5 +35,6 @@ uint32 seq # Image sequence number bool feedback # Trigger feedback from camera uint32 ORB_QUEUE_LENGTH = 2 - ``` + +::: diff --git a/docs/en/msg_docs/CanInterfaceStatus.md b/docs/en/msg_docs/CanInterfaceStatus.md index 234ade997d..0d063764e1 100644 --- a/docs/en/msg_docs/CanInterfaceStatus.md +++ b/docs/en/msg_docs/CanInterfaceStatus.md @@ -1,8 +1,26 @@ +--- +pageClass: is-wide-page +--- + # CanInterfaceStatus (UORB message) +**TOPICS:** can_interfacestatus +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CanInterfaceStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| interface | `uint8` | | | +| io_errors | `uint64` | | | +| frames_tx | `uint64` | | | +| frames_rx | `uint64` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CanInterfaceStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -11,5 +29,6 @@ uint8 interface uint64 io_errors uint64 frames_tx uint64 frames_rx - ``` + +::: diff --git a/docs/en/msg_docs/CellularStatus.md b/docs/en/msg_docs/CellularStatus.md index 04ca0a65dc..10214361e7 100644 --- a/docs/en/msg_docs/CellularStatus.md +++ b/docs/en/msg_docs/CellularStatus.md @@ -1,10 +1,72 @@ +--- +pageClass: is-wide-page +--- + # CellularStatus (UORB message) -Cellular status +Cellular status. This is currently used only for logging cell status from MAVLink. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CellularStatus.msg) +**TOPICS:** cellular_status + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------- | -------- | ------------ | ----------------------------------------------------------- | ------------------------------------------ | +| timestamp | `uint64` | us | | Time since system start | +| status | `uint16` | | [STATUS_FLAG](#STATUS_FLAG) | Status bitmap | +| failure_reason | `uint8` | | [FAILURE_REASON](#FAILURE_REASON) | Failure reason | +| type | `uint8` | | [CELLULAR_NETWORK_RADIO_TYPE](#CELLULAR_NETWORK_RADIO_TYPE) | Cellular network radio type | +| quality | `uint8` | dBm | | Cellular network RSSI/RSRP, absolute value | +| mcc | `uint16` | | | Mobile country code (Invalid: UINT16_MAX) | +| mnc | `uint16` | | | Mobile network code (Invalid: UINT16_MAX) | +| lac | `uint16` | | | Location area code (Invalid: 0) | + +## Enums + +### STATUS_FLAG {#STATUS_FLAG} + +| Name | Type | Value | Description | +| ------------------------------------------------------------------- | -------- | ----- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| STATUS_FLAG_UNKNOWN | `uint16` | 1 | State unknown or not reportable | +| STATUS_FLAG_FAILED | `uint16` | 2 | Modem is unusable | +| STATUS_FLAG_INITIALIZING | `uint16` | 4 | Modem is being initialized | +| STATUS_FLAG_LOCKED | `uint16` | 8 | Modem is locked | +| STATUS_FLAG_DISABLED | `uint16` | 16 | Modem is not enabled and is powered down | +| STATUS_FLAG_DISABLING | `uint16` | 32 | Modem is currently transitioning to the STATUS_FLAG_DISABLED state | +| STATUS_FLAG_ENABLING | `uint16` | 64 | Modem is currently transitioning to the STATUS_FLAG_ENABLED state | +| STATUS_FLAG_ENABLED | `uint16` | 128 | Modem is enabled and powered on but not registered with a network provider and not available for data connections | +| STATUS_FLAG_SEARCHING | `uint16` | 256 | Modem is searching for a network provider to register | +| STATUS_FLAG_REGISTERED | `uint16` | 512 | Modem is registered with a network provider, and data connections and messaging may be available for use | +| STATUS_FLAG_DISCONNECTING | `uint16` | 1024 | Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated | +| STATUS_FLAG_CONNECTING | `uint16` | 2048 | Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered | +| STATUS_FLAG_CONNECTED | `uint16` | 4096 | One or more packet data bearers is active and connected | + +### FAILURE_REASON {#FAILURE_REASON} + +| Name | Type | Value | Description | +| --------------------------------------------------------------------- | ------- | ----- | ----------------------------------------------- | +| FAILURE_REASON_NONE | `uint8` | 0 | No error | +| FAILURE_REASON_UNKNOWN | `uint8` | 1 | Error state is unknown | +| FAILURE_REASON_SIM_MISSING | `uint8` | 2 | SIM is required for the modem but missing | +| FAILURE_REASON_SIM_ERROR | `uint8` | 3 | SIM is available, but not usable for connection | + +### CELLULAR_NETWORK_RADIO_TYPE {#CELLULAR_NETWORK_RADIO_TYPE} + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------------------- | ------- | ----- | ----------- | +| CELLULAR_NETWORK_RADIO_TYPE_NONE | `uint8` | 0 | None | +| CELLULAR_NETWORK_RADIO_TYPE_GSM | `uint8` | 1 | GSM | +| CELLULAR_NETWORK_RADIO_TYPE_CDMA | `uint8` | 2 | CDMA | +| CELLULAR_NETWORK_RADIO_TYPE_WCDMA | `uint8` | 3 | WCDMA | +| CELLULAR_NETWORK_RADIO_TYPE_LTE | `uint8` | 4 | LTE | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CellularStatus.msg) + +::: details Click here to see original file ```c # Cellular status @@ -45,5 +107,6 @@ uint8 quality # [dBm] Cellular network RSSI/RSRP, absolute value uint16 mcc # [@invalid UINT16_MAX] Mobile country code uint16 mnc # [@invalid UINT16_MAX] Mobile network code uint16 lac # [@invalid 0] Location area code - ``` + +::: diff --git a/docs/en/msg_docs/CollisionConstraints.md b/docs/en/msg_docs/CollisionConstraints.md index fd0f562886..cca3930fdf 100644 --- a/docs/en/msg_docs/CollisionConstraints.md +++ b/docs/en/msg_docs/CollisionConstraints.md @@ -1,9 +1,26 @@ +--- +pageClass: is-wide-page +--- + # CollisionConstraints (UORB message) -Local setpoint constraints in NED frame -setting something to NaN means that no limit is provided +Local setpoint constraints in NED frame. setting something to NaN means that no limit is provided. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CollisionConstraints.msg) +**TOPICS:** collision_constraints + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------- | ------------ | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| original_setpoint | `float32[2]` | | | velocities demanded | +| adapted_setpoint | `float32[2]` | | | velocities allowed | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CollisionConstraints.msg) + +::: details Click here to see original file ```c # Local setpoint constraints in NED frame @@ -13,5 +30,6 @@ uint64 timestamp # time since system start (microseconds) float32[2] original_setpoint # velocities demanded float32[2] adapted_setpoint # velocities allowed - ``` + +::: diff --git a/docs/en/msg_docs/ConfigOverrides.md b/docs/en/msg_docs/ConfigOverrides.md index caa4d0816b..62f79f7498 100644 --- a/docs/en/msg_docs/ConfigOverrides.md +++ b/docs/en/msg_docs/ConfigOverrides.md @@ -1,8 +1,39 @@ +--- +pageClass: is-wide-page +--- + # ConfigOverrides (UORB message) -Configurable overrides by (external) modes or mode executors +Configurable overrides by (external) modes or mode executors. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ConfigOverrides.msg) +**TOPICS:** config_overrides config_overrides_request + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------------- | -------- | ------------ | ---------- | -------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| disable_auto_disarm | `bool` | | | Prevent the drone from automatically disarming after landing (if configured) | +| defer_failsafes | `bool` | | | Defer all failsafes that can be deferred (until the flag is cleared) | +| defer_failsafes_timeout_s | `int16` | | | Maximum time a failsafe can be deferred. 0 = system default, -1 = no timeout | +| disable_auto_set_home | `bool` | | | Prevent the drone from automatically setting the home position on arm or takeoff | +| source_type | `int8` | | | +| source_id | `uint8` | | | ID depending on source_type | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 1 | +| SOURCE_TYPE_MODE | `int8` | 0 | +| SOURCE_TYPE_MODE_EXECUTOR | `int8` | 1 | +| ORB_QUEUE_LENGTH | `uint8` | 4 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ConfigOverrides.msg) + +::: details Click here to see original file ```c # Configurable overrides by (external) modes or mode executors @@ -26,5 +57,6 @@ uint8 source_id # ID depending on source_type uint8 ORB_QUEUE_LENGTH = 4 # TOPICS config_overrides config_overrides_request - ``` + +::: diff --git a/docs/en/msg_docs/ConfigOverridesV0.md b/docs/en/msg_docs/ConfigOverridesV0.md index 91e2cf5b48..1b882bb4b8 100644 --- a/docs/en/msg_docs/ConfigOverridesV0.md +++ b/docs/en/msg_docs/ConfigOverridesV0.md @@ -1,8 +1,38 @@ +--- +pageClass: is-wide-page +--- + # ConfigOverridesV0 (UORB message) -Configurable overrides by (external) modes or mode executors +Configurable overrides by (external) modes or mode executors. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/ConfigOverridesV0.msg) +**TOPICS:** config_overrides config_overrides_request + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------------- | -------- | ------------ | ---------- | ---------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| disable_auto_disarm | `bool` | | | Prevent the drone from automatically disarming after landing (if configured) | +| defer_failsafes | `bool` | | | Defer all failsafes that can be deferred (until the flag is cleared) | +| defer_failsafes_timeout_s | `int16` | | | Maximum time a failsafe can be deferred. 0 = system default, -1 = no timeout | +| source_type | `int8` | | | +| source_id | `uint8` | | | ID depending on source_type | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | +| SOURCE_TYPE_MODE | `int8` | 0 | +| SOURCE_TYPE_MODE_EXECUTOR | `int8` | 1 | +| ORB_QUEUE_LENGTH | `uint8` | 4 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/ConfigOverridesV0.msg) + +::: details Click here to see original file ```c # Configurable overrides by (external) modes or mode executors @@ -26,5 +56,6 @@ uint8 source_id # ID depending on source_type uint8 ORB_QUEUE_LENGTH = 4 # TOPICS config_overrides config_overrides_request - ``` + +::: diff --git a/docs/en/msg_docs/ControlAllocatorStatus.md b/docs/en/msg_docs/ControlAllocatorStatus.md index 4068e7b4f4..2bc894471c 100644 --- a/docs/en/msg_docs/ControlAllocatorStatus.md +++ b/docs/en/msg_docs/ControlAllocatorStatus.md @@ -1,6 +1,39 @@ +--- +pageClass: is-wide-page +--- + # ControlAllocatorStatus (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ControlAllocatorStatus.msg) +**TOPICS:** control_allocatorstatus + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------------- | ------------ | ------------ | ---------- | --------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| torque_setpoint_achieved | `bool` | | | Boolean indicating whether the 3D torque setpoint was correctly allocated to actuators. 0 if not achieved, 1 if achieved. | +| unallocated_torque | `float32[3]` | | | Unallocated torque. Equal to 0 if the setpoint was achieved. | +| thrust_setpoint_achieved | `bool` | | | Boolean indicating whether the 3D thrust setpoint was correctly allocated to actuators. 0 if not achieved, 1 if achieved. | +| unallocated_thrust | `float32[3]` | | | Unallocated thrust. Equal to 0 if the setpoint was achieved. | +| actuator_saturation | `int8[16]` | | | Indicates actuator saturation status. | +| handled_motor_failure_mask | `uint16` | | | Bitmask of failed motors that were removed from the allocation / effectiveness matrix. Not necessarily identical to the report from FailureDetector | +| motor_stop_mask | `uint16` | | | Bitmaks of motors stopped by failure injection | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------------------- | ------ | ----- | --------------------------------------------------------------------------------------------------------- | +| ACTUATOR_SATURATION_OK | `int8` | 0 | The actuator is not saturated | +| ACTUATOR_SATURATION_UPPER_DYN | `int8` | 1 | The actuator is saturated (with a value <= the desired value) because it cannot increase its value faster | +| ACTUATOR_SATURATION_UPPER | `int8` | 2 | The actuator is saturated (with a value <= the desired value) because it has reached its maximum value | +| ACTUATOR_SATURATION_LOWER_DYN | `int8` | -1 | The actuator is saturated (with a value >= the desired value) because it cannot decrease its value faster | +| ACTUATOR_SATURATION_LOWER | `int8` | -2 | The actuator is saturated (with a value >= the desired value) because it has reached its minimum value | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ControlAllocatorStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -25,5 +58,6 @@ int8[16] actuator_saturation # Indicates actuator saturation status. uint16 handled_motor_failure_mask # Bitmask of failed motors that were removed from the allocation / effectiveness matrix. Not necessarily identical to the report from FailureDetector uint16 motor_stop_mask # Bitmaks of motors stopped by failure injection - ``` + +::: diff --git a/docs/en/msg_docs/Cpuload.md b/docs/en/msg_docs/Cpuload.md index 84f8447c39..850bc582ce 100644 --- a/docs/en/msg_docs/Cpuload.md +++ b/docs/en/msg_docs/Cpuload.md @@ -1,12 +1,29 @@ +--- +pageClass: is-wide-page +--- + # Cpuload (UORB message) +**TOPICS:** cpuload +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Cpuload.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | --------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| load | `float32` | | | processor load from 0 to 1 | +| ram_usage | `float32` | | | RAM usage from 0 to 1 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Cpuload.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) float32 load # processor load from 0 to 1 float32 ram_usage # RAM usage from 0 to 1 - ``` + +::: diff --git a/docs/en/msg_docs/DatamanRequest.md b/docs/en/msg_docs/DatamanRequest.md index 06d1c5d8b7..cb9692ba34 100644 --- a/docs/en/msg_docs/DatamanRequest.md +++ b/docs/en/msg_docs/DatamanRequest.md @@ -1,8 +1,28 @@ +--- +pageClass: is-wide-page +--- + # DatamanRequest (UORB message) +**TOPICS:** dataman_request +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DatamanRequest.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------ | ----------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| client_id | `uint8` | | | +| request_type | `uint8` | | | id/read/write/clear | +| item | `uint8` | | | dm_item_t | +| index | `uint32` | | | +| data | `uint8[56]` | | | +| data_length | `uint32` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DatamanRequest.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -13,5 +33,6 @@ uint8 item # dm_item_t uint32 index uint8[56] data uint32 data_length - ``` + +::: diff --git a/docs/en/msg_docs/DatamanResponse.md b/docs/en/msg_docs/DatamanResponse.md index 3857d85c69..62ea93d6d5 100644 --- a/docs/en/msg_docs/DatamanResponse.md +++ b/docs/en/msg_docs/DatamanResponse.md @@ -1,8 +1,39 @@ +--- +pageClass: is-wide-page +--- + # DatamanResponse (UORB message) +**TOPICS:** dataman_response +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DatamanResponse.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------ | ----------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| client_id | `uint8` | | | +| request_type | `uint8` | | | id/read/write/clear | +| item | `uint8` | | | dm_item_t | +| index | `uint32` | | | +| data | `uint8[56]` | | | +| status | `uint8` | | | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------- | ------- | ----- | ----------- | +| STATUS_SUCCESS | `uint8` | 0 | +| STATUS_FAILURE_ID_ERR | `uint8` | 1 | +| STATUS_FAILURE_NO_DATA | `uint8` | 2 | +| STATUS_FAILURE_READ_FAILED | `uint8` | 3 | +| STATUS_FAILURE_WRITE_FAILED | `uint8` | 4 | +| STATUS_FAILURE_CLEAR_FAILED | `uint8` | 5 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DatamanResponse.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -20,5 +51,6 @@ uint8 STATUS_FAILURE_READ_FAILED = 3 uint8 STATUS_FAILURE_WRITE_FAILED = 4 uint8 STATUS_FAILURE_CLEAR_FAILED = 5 uint8 status - ``` + +::: diff --git a/docs/en/msg_docs/DebugArray.md b/docs/en/msg_docs/DebugArray.md index 7dc20d00e3..b7fd0c81f9 100644 --- a/docs/en/msg_docs/DebugArray.md +++ b/docs/en/msg_docs/DebugArray.md @@ -1,8 +1,31 @@ +--- +pageClass: is-wide-page +--- + # DebugArray (UORB message) +**TOPICS:** debug_array +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DebugArray.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | ------------- | ------------ | ---------- | ------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| id | `uint16` | | | unique ID of debug array, used to discriminate between arrays | +| name | `char[10]` | | | name of the debug array (max. 10 characters) | +| data | `float32[58]` | | | data | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------- | ------- | ----- | ----------- | +| ARRAY_SIZE | `uint8` | 58 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DebugArray.msg) + +::: details Click here to see original file ```c uint8 ARRAY_SIZE = 58 @@ -10,5 +33,6 @@ uint64 timestamp # time since system start (microseconds) uint16 id # unique ID of debug array, used to discriminate between arrays char[10] name # name of the debug array (max. 10 characters) float32[58] data # data - ``` + +::: diff --git a/docs/en/msg_docs/DebugKeyValue.md b/docs/en/msg_docs/DebugKeyValue.md index ea5709c88e..31883af75f 100644 --- a/docs/en/msg_docs/DebugKeyValue.md +++ b/docs/en/msg_docs/DebugKeyValue.md @@ -1,12 +1,29 @@ +--- +pageClass: is-wide-page +--- + # DebugKeyValue (UORB message) +**TOPICS:** debug_keyvalue +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DebugKeyValue.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | ---------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| key | `char[10]` | | | max. 10 characters as key / name | +| value | `float32` | | | the value to send as debug output | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DebugKeyValue.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) char[10] key # max. 10 characters as key / name float32 value # the value to send as debug output - ``` + +::: diff --git a/docs/en/msg_docs/DebugValue.md b/docs/en/msg_docs/DebugValue.md index 8c86a763a4..9739f056be 100644 --- a/docs/en/msg_docs/DebugValue.md +++ b/docs/en/msg_docs/DebugValue.md @@ -1,12 +1,29 @@ +--- +pageClass: is-wide-page +--- + # DebugValue (UORB message) +**TOPICS:** debug_value +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DebugValue.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | --------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| ind | `int8` | | | index of debug variable | +| value | `float32` | | | the value to send as debug output | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DebugValue.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) int8 ind # index of debug variable float32 value # the value to send as debug output - ``` + +::: diff --git a/docs/en/msg_docs/DebugVect.md b/docs/en/msg_docs/DebugVect.md index 31e1c8d044..941c894409 100644 --- a/docs/en/msg_docs/DebugVect.md +++ b/docs/en/msg_docs/DebugVect.md @@ -1,8 +1,26 @@ +--- +pageClass: is-wide-page +--- + # DebugVect (UORB message) +**TOPICS:** debug_vect +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DebugVect.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | ---------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| name | `char[10]` | | | max. 10 characters as key / name | +| x | `float32` | | | x value | +| y | `float32` | | | y value | +| z | `float32` | | | z value | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DebugVect.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -10,5 +28,6 @@ char[10] name # max. 10 characters as key / name float32 x # x value float32 y # y value float32 z # z value - ``` + +::: diff --git a/docs/en/msg_docs/DeviceInformation.md b/docs/en/msg_docs/DeviceInformation.md index d415461f94..0f68dc8d80 100644 --- a/docs/en/msg_docs/DeviceInformation.md +++ b/docs/en/msg_docs/DeviceInformation.md @@ -1,11 +1,57 @@ +--- +pageClass: is-wide-page +--- + # DeviceInformation (UORB message) -Device information +Device information. Can be used to uniquely associate a device_id from a sensor topic with a physical device using serial number. as well as tracking of the used firmware versions on the devices. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DeviceInformation.msg) +**TOPICS:** device_information + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ---------- | ------------ | ---------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| device_type | `uint8` | | [DEVICE_TYPE](#DEVICE_TYPE) | Type of the device. Matches MAVLink DEVICE_TYPE enum | +| vendor_name | `char[32]` | | | Name of the device vendor | +| model_name | `char[32]` | | | Name of the device model | +| `uint32` | | | Unique device ID for the sensor. Does not change between power cycles. (Invalid: 0 if not available) | +| firmware_version | `char[24]` | | | Firmware version. (Invalid: empty if not available) | +| hardware_version | `char[24]` | | | Hardware version. (Invalid: empty if not available) | +| serial_number | `char[33]` | | | Device serial number or unique identifier. (Invalid: empty if not available) | + +## Enums + +### DEVICE_TYPE {#DEVICE_TYPE} + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------------------- | ------- | ----- | ---------------------- | +| DEVICE_TYPE_GENERIC | `uint8` | 0 | Generic/unknown sensor | +| DEVICE_TYPE_AIRSPEED | `uint8` | 1 | Airspeed sensor | +| DEVICE_TYPE_ESC | `uint8` | 2 | ESC | +| DEVICE_TYPE_SERVO | `uint8` | 3 | Servo | +| DEVICE_TYPE_GPS | `uint8` | 4 | GPS | +| DEVICE_TYPE_MAGNETOMETER | `uint8` | 5 | Magnetometer | +| DEVICE_TYPE_PARACHUTE | `uint8` | 6 | Parachute | +| DEVICE_TYPE_RANGEFINDER | `uint8` | 7 | Rangefinder | +| DEVICE_TYPE_WINCH | `uint8` | 8 | Winch | +| DEVICE_TYPE_BAROMETER | `uint8` | 9 | Barometer | +| DEVICE_TYPE_OPTICAL_FLOW | `uint8` | 10 | Optical flow | +| DEVICE_TYPE_ACCELEROMETER | `uint8` | 11 | Accelerometer | +| DEVICE_TYPE_GYROSCOPE | `uint8` | 12 | Gyroscope | +| DEVICE_TYPE_DIFFERENTIAL_PRESSURE | `uint8` | 13 | Differential pressure | +| DEVICE_TYPE_BATTERY | `uint8` | 14 | Battery | +| DEVICE_TYPE_HYGROMETER | `uint8` | 15 | Hygrometer | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DeviceInformation.msg) + +::: details Click here to see original file ```c # Device information @@ -41,5 +87,6 @@ uint32 device_id # [-] [@invalid 0 if not available] Unique device ID char[24] firmware_version # [-] [@invalid empty if not available] Firmware version. char[24] hardware_version # [-] [@invalid empty if not available] Hardware version. char[33] serial_number # [-] [@invalid empty if not available] Device serial number or unique identifier. - ``` + +::: diff --git a/docs/en/msg_docs/DifferentialPressure.md b/docs/en/msg_docs/DifferentialPressure.md index 83adb2d03e..e9c7410ce7 100644 --- a/docs/en/msg_docs/DifferentialPressure.md +++ b/docs/en/msg_docs/DifferentialPressure.md @@ -1,11 +1,32 @@ +--- +pageClass: is-wide-page +--- + # DifferentialPressure (UORB message) -Differential-pressure (airspeed) sensor +Differential-pressure (airspeed) sensor. This is populated by airspeed sensor drivers and used by the sensor module to calculate airspeed. The information is published in the `SCALED_PRESSURE_n` MAVLink messages (along with information from a corresponding `SensorBaro` instance). -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DifferentialPressure.msg) +**TOPICS:** differential_pressure + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------------ | --------- | ------------ | ---------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time of publication (since system start) | +| timestamp_sample | `uint64` | us | | Time of raw data capture | +| device_id | `uint32` | | | Unique device ID for the sensor that does not change between power cycles | +| differential_pressure_pa | `float32` | Pa | | Differential pressure reading (may be negative) | +| temperature | `float32` | degC | | Temperature (Invalid: NaN if unknown) | +| error_count | `uint32` | | | Number of errors detected by driver | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DifferentialPressure.msg) + +::: details Click here to see original file ```c # Differential-pressure (airspeed) sensor @@ -20,5 +41,6 @@ uint32 device_id # [-] Unique device ID for the sensor that doe float32 differential_pressure_pa # [Pa] Differential pressure reading (may be negative) float32 temperature # [degC] [@invalid NaN if unknown] Temperature uint32 error_count # [-] Number of errors detected by driver - ``` + +::: diff --git a/docs/en/msg_docs/DistanceSensor.md b/docs/en/msg_docs/DistanceSensor.md index c4d5bbc2c0..6bf1ea75b6 100644 --- a/docs/en/msg_docs/DistanceSensor.md +++ b/docs/en/msg_docs/DistanceSensor.md @@ -1,8 +1,63 @@ +--- +pageClass: is-wide-page +--- + # DistanceSensor (UORB message) -DISTANCE_SENSOR message data +DISTANCE_SENSOR message data. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DistanceSensor.msg) +**TOPICS:** distance_sensor + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ------------ | ------------ | ---------- | ---------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| min_distance | `float32` | | | Minimum distance the sensor can measure (in m) | +| max_distance | `float32` | | | Maximum distance the sensor can measure (in m) | +| current_distance | `float32` | | | Current distance reading (in m) | +| variance | `float32` | | | Measurement variance (in m^2), 0 for unknown / invalid readings | +| signal_quality | `int8` | | | Signal quality in percent (0...100%), where 0 = invalid signal, 100 = perfect signal, and -1 = unknown signal quality. | +| type | `uint8` | | | Type from MAV_DISTANCE_SENSOR enum | +| h_fov | `float32` | | | Sensor horizontal field of view (rad) | +| v_fov | `float32` | | | Sensor vertical field of view (rad) | +| q | `float32[4]` | | | Quaterion sensor orientation with respect to the vehicle body frame to specify the orientation ROTATION_CUSTOM | +| orientation | `uint8` | | | Direction the sensor faces from MAV_SENSOR_ORIENTATION enum | +| mode | `uint8` | | | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------------- | ------- | ----- | ----------------------------- | +| MAV_DISTANCE_SENSOR_LASER | `uint8` | 0 | +| MAV_DISTANCE_SENSOR_ULTRASOUND | `uint8` | 1 | +| MAV_DISTANCE_SENSOR_INFRARED | `uint8` | 2 | +| MAV_DISTANCE_SENSOR_RADAR | `uint8` | 3 | +| ROTATION_YAW_0 | `uint8` | 0 | MAV_SENSOR_ROTATION_NONE | +| ROTATION_YAW_45 | `uint8` | 1 | MAV_SENSOR_ROTATION_YAW_45 | +| ROTATION_YAW_90 | `uint8` | 2 | MAV_SENSOR_ROTATION_YAW_90 | +| ROTATION_YAW_135 | `uint8` | 3 | MAV_SENSOR_ROTATION_YAW_135 | +| ROTATION_YAW_180 | `uint8` | 4 | MAV_SENSOR_ROTATION_YAW_180 | +| ROTATION_YAW_225 | `uint8` | 5 | MAV_SENSOR_ROTATION_YAW_225 | +| ROTATION_YAW_270 | `uint8` | 6 | MAV_SENSOR_ROTATION_YAW_270 | +| ROTATION_YAW_315 | `uint8` | 7 | MAV_SENSOR_ROTATION_YAW_315 | +| ROTATION_FORWARD_FACING | `uint8` | 0 | MAV_SENSOR_ROTATION_NONE | +| ROTATION_RIGHT_FACING | `uint8` | 2 | MAV_SENSOR_ROTATION_YAW_90 | +| ROTATION_BACKWARD_FACING | `uint8` | 4 | MAV_SENSOR_ROTATION_YAW_180 | +| ROTATION_LEFT_FACING | `uint8` | 6 | MAV_SENSOR_ROTATION_YAW_270 | +| ROTATION_UPWARD_FACING | `uint8` | 24 | MAV_SENSOR_ROTATION_PITCH_90 | +| ROTATION_DOWNWARD_FACING | `uint8` | 25 | MAV_SENSOR_ROTATION_PITCH_270 | +| ROTATION_CUSTOM | `uint8` | 100 | MAV_SENSOR_ROTATION_CUSTOM | +| MODE_UNKNOWN | `uint8` | 0 | +| MODE_ENABLED | `uint8` | 1 | +| MODE_DISABLED | `uint8` | 2 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DistanceSensor.msg) + +::: details Click here to see original file ```c # DISTANCE_SENSOR message data @@ -52,5 +107,6 @@ uint8 mode uint8 MODE_UNKNOWN = 0 uint8 MODE_ENABLED = 1 uint8 MODE_DISABLED = 2 - ``` + +::: diff --git a/docs/en/msg_docs/DistanceSensorModeChangeRequest.md b/docs/en/msg_docs/DistanceSensorModeChangeRequest.md index 56ed7e1bba..1c4f596106 100644 --- a/docs/en/msg_docs/DistanceSensorModeChangeRequest.md +++ b/docs/en/msg_docs/DistanceSensorModeChangeRequest.md @@ -1,8 +1,30 @@ +--- +pageClass: is-wide-page +--- + # DistanceSensorModeChangeRequest (UORB message) +**TOPICS:** distance_sensormode_changerequest +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DistanceSensorModeChangeRequest.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------- | -------- | ------------ | ---------- | --------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| request_on_off | `uint8` | | | request to disable/enable the distance sensor | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------- | ------- | ----- | ----------- | +| REQUEST_OFF | `uint8` | 0 | +| REQUEST_ON | `uint8` | 1 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DistanceSensorModeChangeRequest.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -10,5 +32,6 @@ uint64 timestamp # time since system start (microseconds) uint8 request_on_off # request to disable/enable the distance sensor uint8 REQUEST_OFF = 0 uint8 REQUEST_ON = 1 - ``` + +::: diff --git a/docs/en/msg_docs/DronecanNodeStatus.md b/docs/en/msg_docs/DronecanNodeStatus.md index 5c8a8d7862..e25f221092 100644 --- a/docs/en/msg_docs/DronecanNodeStatus.md +++ b/docs/en/msg_docs/DronecanNodeStatus.md @@ -1,6 +1,42 @@ +--- +pageClass: is-wide-page +--- + # DronecanNodeStatus (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DronecanNodeStatus.msg) +**TOPICS:** dronecan_nodestatus + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------------------- | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| node_id | `uint16` | | | The node ID which this data comes from | +| uptime_sec | `uint32` | | | Node uptime | +| health | `uint8` | | | +| mode | `uint8` | | | +| sub_mode | `uint8` | | | +| vendor_specific_status_code | `uint16` | | | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------- | ------- | ----- | ------------------------------------------------------------------------------- | +| HEALTH_OK | `uint8` | 0 | The node is functioning properly. | +| HEALTH_WARNING | `uint8` | 1 | A critical parameter went out of range or the node encountered a minor failure. | +| HEALTH_ERROR | `uint8` | 2 | The node encountered a major failure. | +| HEALTH_CRITICAL | `uint8` | 3 | The node suffered a fatal malfunction. | +| MODE_OPERATIONAL | `uint8` | 0 | Normal operating mode. | +| MODE_INITIALIZATION | `uint8` | 1 | Initialization is in progress; this mode is entered immediately after startup. | +| MODE_MAINTENANCE | `uint8` | 2 | E.g. calibration, the bootloader is running, etc. | +| MODE_SOFTWARE_UPDATE | `uint8` | 3 | New software/firmware is being loaded. | +| MODE_OFFLINE | `uint8` | 7 | The node is no longer available. | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DronecanNodeStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -44,5 +80,6 @@ uint8 sub_mode # Optional, vendor-specific node status code, e.g. a fault code or a status bitmask. # uint16 vendor_specific_status_code - ``` + +::: diff --git a/docs/en/msg_docs/Ekf2Timestamps.md b/docs/en/msg_docs/Ekf2Timestamps.md index 8de695f523..970bd52edf 100644 --- a/docs/en/msg_docs/Ekf2Timestamps.md +++ b/docs/en/msg_docs/Ekf2Timestamps.md @@ -1,12 +1,37 @@ +--- +pageClass: is-wide-page +--- + # Ekf2Timestamps (UORB message) -this message contains the (relative) timestamps of the sensor inputs used by EKF2. -It can be used for reproducible replay. +this message contains the (relative) timestamps of the sensor inputs used by EKF2. It can be used for reproducible replay. -the timestamp field is the ekf2 reference time and matches the timestamp of -the sensor_combined topic. +**TOPICS:** ekf2_timestamps -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Ekf2Timestamps.msg) +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------------------- | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| airspeed_timestamp_rel | `int16` | | | +| airspeed_validated_timestamp_rel | `int16` | | | +| distance_sensor_timestamp_rel | `int16` | | | +| optical_flow_timestamp_rel | `int16` | | | +| vehicle_air_data_timestamp_rel | `int16` | | | +| vehicle_magnetometer_timestamp_rel | `int16` | | | +| visual_odometry_timestamp_rel | `int16` | | | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------------- | ------- | ----- | ------------------------------------------ | +| RELATIVE_TIMESTAMP_INVALID | `int16` | 32767 | (0x7fff) If one of the relative timestamps | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Ekf2Timestamps.msg) + +::: details Click here to see original file ```c # this message contains the (relative) timestamps of the sensor inputs used by EKF2. @@ -33,5 +58,6 @@ int16 vehicle_magnetometer_timestamp_rel int16 visual_odometry_timestamp_rel # Note: this is a high-rate logged topic, so it needs to be as small as possible - ``` + +::: diff --git a/docs/en/msg_docs/EscReport.md b/docs/en/msg_docs/EscReport.md index 277402ae69..2887d96454 100644 --- a/docs/en/msg_docs/EscReport.md +++ b/docs/en/msg_docs/EscReport.md @@ -1,6 +1,61 @@ +--- +pageClass: is-wide-page +--- + # EscReport (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EscReport.msg) +**TOPICS:** esc_report + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------- | --------- | ------------ | ---------- | ------------------------------------------------------------------ | +| timestamp | `uint64` | | | time since system start (microseconds) | +| esc_errorcount | `uint32` | | | Number of reported errors by ESC - if supported | +| esc_rpm | `int32` | | | Motor RPM, negative for reverse rotation [RPM] - if supported | +| esc_voltage | `float32` | | | Voltage measured from current ESC [V] - if supported | +| esc_current | `float32` | | | Current measured from current ESC [A] - if supported | +| esc_temperature | `float32` | | | Temperature measured from current ESC [degC] - if supported | +| esc_address | `uint8` | | | Address of current ESC (in most cases 1-8 / must be set by driver) | +| esc_cmdcount | `uint8` | | | Counter of number of commands | +| esc_state | `uint8` | | | State of ESC - depend on Vendor | +| actuator_function | `uint8` | | | actuator output function (one of Motor1...MotorN) | +| failures | `uint16` | | | Bitmask to indicate the internal ESC faults | +| esc_power | `int8` | | | Applied power 0-100 in % (negative values reserved) | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------------- | ------- | ----- | ---------------------------------------------------------------------------- | +| ACTUATOR_FUNCTION_MOTOR1 | `uint8` | 101 | +| ACTUATOR_FUNCTION_MOTOR2 | `uint8` | 102 | +| ACTUATOR_FUNCTION_MOTOR3 | `uint8` | 103 | +| ACTUATOR_FUNCTION_MOTOR4 | `uint8` | 104 | +| ACTUATOR_FUNCTION_MOTOR5 | `uint8` | 105 | +| ACTUATOR_FUNCTION_MOTOR6 | `uint8` | 106 | +| ACTUATOR_FUNCTION_MOTOR7 | `uint8` | 107 | +| ACTUATOR_FUNCTION_MOTOR8 | `uint8` | 108 | +| ACTUATOR_FUNCTION_MOTOR9 | `uint8` | 109 | +| ACTUATOR_FUNCTION_MOTOR10 | `uint8` | 110 | +| ACTUATOR_FUNCTION_MOTOR11 | `uint8` | 111 | +| ACTUATOR_FUNCTION_MOTOR12 | `uint8` | 112 | +| FAILURE_OVER_CURRENT | `uint8` | 0 | (1 << 0) | +| FAILURE_OVER_VOLTAGE | `uint8` | 1 | (1 << 1) | +| FAILURE_MOTOR_OVER_TEMPERATURE | `uint8` | 2 | (1 << 2) | +| FAILURE_OVER_RPM | `uint8` | 3 | (1 << 3) | +| FAILURE_INCONSISTENT_CMD | `uint8` | 4 | (1 << 4) Set if ESC received an inconsistent command (i.e out of boundaries) | +| FAILURE_MOTOR_STUCK | `uint8` | 5 | (1 << 5) | +| FAILURE_GENERIC | `uint8` | 6 | (1 << 6) | +| FAILURE_MOTOR_WARN_TEMPERATURE | `uint8` | 7 | (1 << 7) | +| FAILURE_WARN_ESC_TEMPERATURE | `uint8` | 8 | (1 << 8) | +| FAILURE_OVER_ESC_TEMPERATURE | `uint8` | 9 | (1 << 9) | +| ESC_FAILURE_COUNT | `uint8` | 10 | Counter - keep it as last element! | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EscReport.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -43,5 +98,6 @@ uint8 FAILURE_MOTOR_WARN_TEMPERATURE = 7 # (1 << 7) uint8 FAILURE_WARN_ESC_TEMPERATURE = 8 # (1 << 8) uint8 FAILURE_OVER_ESC_TEMPERATURE = 9 # (1 << 9) uint8 ESC_FAILURE_COUNT = 10 # Counter - keep it as last element! - ``` + +::: diff --git a/docs/en/msg_docs/EscStatus.md b/docs/en/msg_docs/EscStatus.md index 07bd468cee..9f8b0a409a 100644 --- a/docs/en/msg_docs/EscStatus.md +++ b/docs/en/msg_docs/EscStatus.md @@ -1,8 +1,40 @@ +--- +pageClass: is-wide-page +--- + # EscStatus (UORB message) +**TOPICS:** esc_status +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EscStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------ | -------------- | ------------ | ---------- | ------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| counter | `uint16` | | | incremented by the writing thread everytime new data is stored | +| esc_count | `uint8` | | | number of connected ESCs | +| esc_connectiontype | `uint8` | | | how ESCs connected to the system | +| esc_online_flags | `uint8` | | | Bitmask indicating which ESC is online/offline | +| esc_armed_flags | `uint8` | | | Bitmask indicating which ESC is armed. For ESC's where the arming state is not known (returned by the ESC), the arming bits should always be set. | +| esc | `EscReport[8]` | | | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------- | ------- | ----- | ----------------------------------------------------------------- | +| CONNECTED_ESC_MAX | `uint8` | 8 | The number of ESCs supported. Current (Q2/2013) we support 8 ESCs | +| ESC_CONNECTION_TYPE_PPM | `uint8` | 0 | Traditional PPM ESC | +| ESC_CONNECTION_TYPE_SERIAL | `uint8` | 1 | Serial Bus connected ESC | +| ESC_CONNECTION_TYPE_ONESHOT | `uint8` | 2 | One Shot PPM | +| ESC_CONNECTION_TYPE_I2C | `uint8` | 3 | I2C | +| ESC_CONNECTION_TYPE_CAN | `uint8` | 4 | CAN-Bus | +| ESC_CONNECTION_TYPE_DSHOT | `uint8` | 5 | DShot | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EscStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -33,5 +65,6 @@ uint8 esc_online_flags # Bitmask indicating which ESC is online/offline uint8 esc_armed_flags # Bitmask indicating which ESC is armed. For ESC's where the arming state is not known (returned by the ESC), the arming bits should always be set. EscReport[8] esc - ``` + +::: diff --git a/docs/en/msg_docs/EstimatorAidSource1d.md b/docs/en/msg_docs/EstimatorAidSource1d.md index 45d0659de2..908495b407 100644 --- a/docs/en/msg_docs/EstimatorAidSource1d.md +++ b/docs/en/msg_docs/EstimatorAidSource1d.md @@ -1,8 +1,35 @@ +--- +pageClass: is-wide-page +--- + # EstimatorAidSource1d (UORB message) +**TOPICS:** estimator_aid_src_baro_hgt estimator_aid_src_ev_hgt estimator_aid_src_gnss_hgt estimator_aid_src_rng_hgt estimator_aid_src_airspeed estimator_aid_src_sideslip estimator_aid_src_fake_hgt estimator_aid_src_gnss_yaw estimator_aid_src_ev_yaw +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------- | --------- | ------------ | ---------- | -------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| estimator_instance | `uint8` | | | +| device_id | `uint32` | | | +| time_last_fuse | `uint64` | | | +| observation | `float32` | | | +| observation_variance | `float32` | | | +| innovation | `float32` | | | +| innovation_filtered | `float32` | | | +| innovation_variance | `float32` | | | +| test_ratio | `float32` | | | normalized innovation squared | +| test_ratio_filtered | `float32` | | | signed filtered test ratio | +| innovation_rejected | `bool` | | | true if the observation has been rejected | +| fused | `bool` | | | true if the sample was successfully fused | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -32,5 +59,6 @@ bool fused # true if the sample was successfully fused # TOPICS estimator_aid_src_airspeed estimator_aid_src_sideslip # TOPICS estimator_aid_src_fake_hgt # TOPICS estimator_aid_src_gnss_yaw estimator_aid_src_ev_yaw - ``` + +::: diff --git a/docs/en/msg_docs/EstimatorAidSource2d.md b/docs/en/msg_docs/EstimatorAidSource2d.md index 70cc2948e5..cb21f508cb 100644 --- a/docs/en/msg_docs/EstimatorAidSource2d.md +++ b/docs/en/msg_docs/EstimatorAidSource2d.md @@ -1,8 +1,35 @@ +--- +pageClass: is-wide-page +--- + # EstimatorAidSource2d (UORB message) +**TOPICS:** estimator_aid_src_ev_pos estimator_aid_src_fake_pos estimator_aid_src_gnss_pos estimator_aid_src_aux_global_position estimator_aid_src_aux_vel estimator_aid_src_optical_flow estimator_aid_src_drag +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------- | ------------ | ------------ | ---------- | -------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| estimator_instance | `uint8` | | | +| device_id | `uint32` | | | +| time_last_fuse | `uint64` | | | +| observation | `float64[2]` | | | +| observation_variance | `float32[2]` | | | +| innovation | `float32[2]` | | | +| innovation_filtered | `float32[2]` | | | +| innovation_variance | `float32[2]` | | | +| test_ratio | `float32[2]` | | | normalized innovation squared | +| test_ratio_filtered | `float32[2]` | | | signed filtered test ratio | +| innovation_rejected | `bool` | | | true if the observation has been rejected | +| fused | `bool` | | | true if the sample was successfully fused | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -31,5 +58,6 @@ bool fused # true if the sample was successfully fused # TOPICS estimator_aid_src_ev_pos estimator_aid_src_fake_pos estimator_aid_src_gnss_pos estimator_aid_src_aux_global_position # TOPICS estimator_aid_src_aux_vel estimator_aid_src_optical_flow # TOPICS estimator_aid_src_drag - ``` + +::: diff --git a/docs/en/msg_docs/EstimatorAidSource3d.md b/docs/en/msg_docs/EstimatorAidSource3d.md index 457deec9c9..38ed296214 100644 --- a/docs/en/msg_docs/EstimatorAidSource3d.md +++ b/docs/en/msg_docs/EstimatorAidSource3d.md @@ -1,8 +1,35 @@ +--- +pageClass: is-wide-page +--- + # EstimatorAidSource3d (UORB message) +**TOPICS:** estimator_aid_src_ev_vel estimator_aid_src_gnss_vel estimator_aid_src_gravity estimator_aid_src_mag +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource3d.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------- | ------------ | ------------ | ---------- | -------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| estimator_instance | `uint8` | | | +| device_id | `uint32` | | | +| time_last_fuse | `uint64` | | | +| observation | `float32[3]` | | | +| observation_variance | `float32[3]` | | | +| innovation | `float32[3]` | | | +| innovation_filtered | `float32[3]` | | | +| innovation_variance | `float32[3]` | | | +| test_ratio | `float32[3]` | | | normalized innovation squared | +| test_ratio_filtered | `float32[3]` | | | signed filtered test ratio | +| innovation_rejected | `bool` | | | true if the observation has been rejected | +| fused | `bool` | | | true if the sample was successfully fused | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource3d.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -29,5 +56,6 @@ bool innovation_rejected # true if the observation has been rejected bool fused # true if the sample was successfully fused # TOPICS estimator_aid_src_ev_vel estimator_aid_src_gnss_vel estimator_aid_src_gravity estimator_aid_src_mag - ``` + +::: diff --git a/docs/en/msg_docs/EstimatorBias.md b/docs/en/msg_docs/EstimatorBias.md index 3b7408be15..4e19c7590b 100644 --- a/docs/en/msg_docs/EstimatorBias.md +++ b/docs/en/msg_docs/EstimatorBias.md @@ -1,8 +1,29 @@ +--- +pageClass: is-wide-page +--- + # EstimatorBias (UORB message) +**TOPICS:** estimator_baro_bias estimator_gnss_hgt_bias +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorBias.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | --------- | ------------ | ---------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| bias | `float32` | | | estimated barometric altitude bias (m) | +| bias_var | `float32` | | | estimated barometric altitude bias variance (m^2) | +| innov | `float32` | | | innovation of the last measurement fusion (m) | +| innov_var | `float32` | | | innovation variance of the last measurement fusion (m^2) | +| innov_test_ratio | `float32` | | | normalized innovation squared test ratio | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorBias.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -17,5 +38,6 @@ float32 innov_var # innovation variance of the last measurement fusion (m^2) float32 innov_test_ratio # normalized innovation squared test ratio # TOPICS estimator_baro_bias estimator_gnss_hgt_bias - ``` + +::: diff --git a/docs/en/msg_docs/EstimatorBias3d.md b/docs/en/msg_docs/EstimatorBias3d.md index af89bab69f..42b7c0ac7e 100644 --- a/docs/en/msg_docs/EstimatorBias3d.md +++ b/docs/en/msg_docs/EstimatorBias3d.md @@ -1,8 +1,29 @@ +--- +pageClass: is-wide-page +--- + # EstimatorBias3d (UORB message) +**TOPICS:** estimator_bias3d estimator_ev_pos_bias +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorBias3d.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ------------ | ------------ | ---------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| bias | `float32[3]` | | | estimated barometric altitude bias (m) | +| bias_var | `float32[3]` | | | estimated barometric altitude bias variance (m^2) | +| innov | `float32[3]` | | | innovation of the last measurement fusion (m) | +| innov_var | `float32[3]` | | | innovation variance of the last measurement fusion (m^2) | +| innov_test_ratio | `float32[3]` | | | normalized innovation squared test ratio | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorBias3d.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -19,5 +40,6 @@ float32[3] innov_test_ratio # normalized innovation squared test ratio # TOPICS estimator_bias3d # TOPICS estimator_ev_pos_bias - ``` + +::: diff --git a/docs/en/msg_docs/EstimatorEventFlags.md b/docs/en/msg_docs/EstimatorEventFlags.md index c56f29a842..639c3b6db0 100644 --- a/docs/en/msg_docs/EstimatorEventFlags.md +++ b/docs/en/msg_docs/EstimatorEventFlags.md @@ -1,8 +1,41 @@ +--- +pageClass: is-wide-page +--- + # EstimatorEventFlags (UORB message) +**TOPICS:** estimator_eventflags +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorEventFlags.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------------- | -------- | ------------ | ---------- | --------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| information_event_changes | `uint32` | | | number of information event changes | +| gps_checks_passed | `bool` | | | 0 - true when gps quality checks are passing passed | +| reset_vel_to_gps | `bool` | | | 1 - true when the velocity states are reset to the gps measurement | +| reset_vel_to_flow | `bool` | | | 2 - true when the velocity states are reset using the optical flow measurement | +| reset_vel_to_vision | `bool` | | | 3 - true when the velocity states are reset to the vision system measurement | +| reset_vel_to_zero | `bool` | | | 4 - true when the velocity states are reset to zero | +| reset_pos_to_last_known | `bool` | | | 5 - true when the position states are reset to the last known position | +| reset_pos_to_gps | `bool` | | | 6 - true when the position states are reset to the gps measurement | +| reset_pos_to_vision | `bool` | | | 7 - true when the position states are reset to the vision system measurement | +| starting_gps_fusion | `bool` | | | 8 - true when the filter starts using gps measurements to correct the state estimates | +| starting_vision_pos_fusion | `bool` | | | 9 - true when the filter starts using vision system position measurements to correct the state estimates | +| starting_vision_vel_fusion | `bool` | | | 10 - true when the filter starts using vision system velocity measurements to correct the state estimates | +| starting_vision_yaw_fusion | `bool` | | | 11 - true when the filter starts using vision system yaw measurements to correct the state estimates | +| yaw_aligned_to_imu_gps | `bool` | | | 12 - true when the filter resets the yaw to an estimate derived from IMU and GPS data | +| reset_hgt_to_baro | `bool` | | | 13 - true when the vertical position state is reset to the baro measurement | +| reset_hgt_to_gps | `bool` | | | 14 - true when the vertical position state is reset to the gps measurement | +| reset_hgt_to_rng | `bool` | | | 15 - true when the vertical position state is reset to the rng measurement | +| reset_hgt_to_ev | `bool` | | | 16 - true when the vertical position state is reset to the ev measurement | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorEventFlags.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -27,5 +60,6 @@ bool reset_hgt_to_baro # 13 - true when the vertical position s bool reset_hgt_to_gps # 14 - true when the vertical position state is reset to the gps measurement bool reset_hgt_to_rng # 15 - true when the vertical position state is reset to the rng measurement bool reset_hgt_to_ev # 16 - true when the vertical position state is reset to the ev measurement - ``` + +::: diff --git a/docs/en/msg_docs/EstimatorGpsStatus.md b/docs/en/msg_docs/EstimatorGpsStatus.md index e25be3e558..a7c5927b41 100644 --- a/docs/en/msg_docs/EstimatorGpsStatus.md +++ b/docs/en/msg_docs/EstimatorGpsStatus.md @@ -1,8 +1,38 @@ +--- +pageClass: is-wide-page +--- + # EstimatorGpsStatus (UORB message) +**TOPICS:** estimator_gpsstatus +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorGpsStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------------------- | --------- | ------------ | ---------- | -------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| checks_passed | `bool` | | | +| check_fail_gps_fix | `bool` | | | 0 : insufficient fix type (no 3D solution) | +| check_fail_min_sat_count | `bool` | | | 1 : minimum required sat count fail | +| check_fail_max_pdop | `bool` | | | 2 : maximum allowed PDOP fail | +| check_fail_max_horz_err | `bool` | | | 3 : maximum allowed horizontal position error fail | +| check_fail_max_vert_err | `bool` | | | 4 : maximum allowed vertical position error fail | +| check_fail_max_spd_err | `bool` | | | 5 : maximum allowed speed error fail | +| check_fail_max_horz_drift | `bool` | | | 6 : maximum allowed horizontal position drift fail - requires stationary vehicle | +| check_fail_max_vert_drift | `bool` | | | 7 : maximum allowed vertical position drift fail - requires stationary vehicle | +| check_fail_max_horz_spd_err | `bool` | | | 8 : maximum allowed horizontal speed fail - requires stationary vehicle | +| check_fail_max_vert_spd_err | `bool` | | | 9 : maximum allowed vertical velocity discrepancy fail | +| check_fail_spoofed_gps | `bool` | | | 10 : GPS signal is spoofed | +| position_drift_rate_horizontal_m_s | `float32` | | | Horizontal position rate magnitude (m/s) | +| position_drift_rate_vertical_m_s | `float32` | | | Vertical position rate magnitude (m/s) | +| filtered_horizontal_speed_m_s | `float32` | | | Filtered horizontal velocity magnitude (m/s) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorGpsStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -25,5 +55,6 @@ bool check_fail_spoofed_gps # 10 : GPS signal is spoofed float32 position_drift_rate_horizontal_m_s # Horizontal position rate magnitude (m/s) float32 position_drift_rate_vertical_m_s # Vertical position rate magnitude (m/s) float32 filtered_horizontal_speed_m_s # Filtered horizontal velocity magnitude (m/s) - ``` + +::: diff --git a/docs/en/msg_docs/EstimatorInnovations.md b/docs/en/msg_docs/EstimatorInnovations.md index 478fe79831..87b559ecf8 100644 --- a/docs/en/msg_docs/EstimatorInnovations.md +++ b/docs/en/msg_docs/EstimatorInnovations.md @@ -1,8 +1,43 @@ +--- +pageClass: is-wide-page +--- + # EstimatorInnovations (UORB message) +**TOPICS:** estimator_innovations estimator_innovation_variances estimator_innovation_test_ratios +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorInnovations.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ------------ | ------------ | ------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| gps_hvel | `float32[2]` | | | horizontal GPS velocity innovation (m/sec) and innovation variance ((m/sec)\*\*2) | +| `float32` | | | vertical GPS velocity innovation (m/sec) and innovation variance ((m/sec)\*\*2) | +| gps_hpos | `float32[2]` | | | horizontal GPS position innovation (m) and innovation variance (m\*\*2) | +| `float32` | | | vertical GPS position innovation (m) and innovation variance (m\*\*2) | +| ev_hvel | `float32[2]` | | | horizontal external vision velocity innovation (m/sec) and innovation variance ((m/sec)\*\*2) | +| `float32` | | | vertical external vision velocity innovation (m/sec) and innovation variance ((m/sec)\*\*2) | +| ev_hpos | `float32[2]` | | | horizontal external vision position innovation (m) and innovation variance (m\*\*2) | +| `float32` | | | vertical external vision position innovation (m) and innovation variance (m\*\*2) | +| rng_vpos | `float32` | | | range sensor height innovation (m) and innovation variance (m\*\*2) | +| baro_vpos | `float32` | | | barometer height innovation (m) and innovation variance (m\*\*2) | +| aux_hvel | `float32[2]` | | | horizontal auxiliary velocity innovation from landing target measurement (m/sec) and innovation variance ((m/sec)\*\*2) | +| flow | `float32[2]` | | | flow innvoation (rad/sec) and innovation variance ((rad/sec)\*\*2) | +| heading | `float32` | | | heading innovation (rad) and innovation variance (rad\*\*2) | +| mag_field | `float32[3]` | | | earth magnetic field innovation (Gauss) and innovation variance (Gauss\*\*2) | +| gravity | `float32[3]` | | | gravity innovation from accelerometerr vector (m/s\*\*2) | +| drag | `float32[2]` | | | drag specific force innovation (m/sec**2) and innovation variance ((m/sec)**2) | +| airspeed | `float32` | | | airspeed innovation (m/sec) and innovation variance ((m/sec)\*\*2) | +| beta | `float32` | | | synthetic sideslip innovation (rad) and innovation variance (rad\*\*2) | +| hagl | `float32` | | | height of ground innovation (m) and innovation variance (m\*\*2) | +| hagl_rate | `float32` | | | height of ground rate innovation (m/s) and innovation variance ((m/s)\*\*2) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorInnovations.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -44,5 +79,6 @@ float32 hagl_rate # height of ground rate innovation (m/s) and innovation varian # the test ratio will be put in the first component of the vector. # TOPICS estimator_innovations estimator_innovation_variances estimator_innovation_test_ratios - ``` + +::: diff --git a/docs/en/msg_docs/EstimatorSelectorStatus.md b/docs/en/msg_docs/EstimatorSelectorStatus.md index 3e64205a8f..71ed593ee3 100644 --- a/docs/en/msg_docs/EstimatorSelectorStatus.md +++ b/docs/en/msg_docs/EstimatorSelectorStatus.md @@ -1,8 +1,37 @@ +--- +pageClass: is-wide-page +--- + # EstimatorSelectorStatus (UORB message) +**TOPICS:** estimator_selectorstatus +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorSelectorStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------------- | ------------ | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| primary_instance | `uint8` | | | +| instances_available | `uint8` | | | +| instance_changed_count | `uint32` | | | +| last_instance_change | `uint64` | | | +| accel_device_id | `uint32` | | | +| baro_device_id | `uint32` | | | +| gyro_device_id | `uint32` | | | +| mag_device_id | `uint32` | | | +| combined_test_ratio | `float32[9]` | | | +| relative_test_ratio | `float32[9]` | | | +| healthy | `bool[9]` | | | +| accumulated_gyro_error | `float32[4]` | | | +| accumulated_accel_error | `float32[4]` | | | +| gyro_fault_detected | `bool` | | | +| accel_fault_detected | `bool` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorSelectorStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -27,5 +56,6 @@ float32[4] accumulated_gyro_error float32[4] accumulated_accel_error bool gyro_fault_detected bool accel_fault_detected - ``` + +::: diff --git a/docs/en/msg_docs/EstimatorSensorBias.md b/docs/en/msg_docs/EstimatorSensorBias.md index 9b4a1d66c2..b41736370c 100644 --- a/docs/en/msg_docs/EstimatorSensorBias.md +++ b/docs/en/msg_docs/EstimatorSensorBias.md @@ -1,9 +1,43 @@ +--- +pageClass: is-wide-page +--- + # EstimatorSensorBias (UORB message) -Sensor readings and in-run biases in SI-unit form. Sensor readings are compensated for static offsets, -scale errors, in-run bias and thermal drift (if thermal compensation is enabled and available). +Sensor readings and in-run biases in SI-unit form. Sensor readings are compensated for static offsets,. scale errors, in-run bias and thermal drift (if thermal compensation is enabled and available). -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorSensorBias.msg) +**TOPICS:** estimator_sensorbias + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------- | ------------ | ------------ | ---------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| gyro_device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| gyro_bias | `float32[3]` | | | gyroscope in-run bias in body frame (rad/s) | +| gyro_bias_limit | `float32` | | | magnitude of maximum gyroscope in-run bias in body frame (rad/s) | +| gyro_bias_variance | `float32[3]` | | | +| gyro_bias_valid | `bool` | | | +| gyro_bias_stable | `bool` | | | true when the gyro bias estimate is stable enough to use for calibration | +| accel_device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| accel_bias | `float32[3]` | | | accelerometer in-run bias in body frame (m/s^2) | +| accel_bias_limit | `float32` | | | magnitude of maximum accelerometer in-run bias in body frame (m/s^2) | +| accel_bias_variance | `float32[3]` | | | +| accel_bias_valid | `bool` | | | +| accel_bias_stable | `bool` | | | true when the accel bias estimate is stable enough to use for calibration | +| mag_device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| mag_bias | `float32[3]` | | | magnetometer in-run bias in body frame (Gauss) | +| mag_bias_limit | `float32` | | | magnitude of maximum magnetometer in-run bias in body frame (Gauss) | +| mag_bias_variance | `float32[3]` | | | +| mag_bias_valid | `bool` | | | +| mag_bias_stable | `bool` | | | true when the mag bias estimate is stable enough to use for calibration | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorSensorBias.msg) + +::: details Click here to see original file ```c # @@ -36,5 +70,6 @@ float32 mag_bias_limit # magnitude of maximum magnetometer in-run bias float32[3] mag_bias_variance bool mag_bias_valid bool mag_bias_stable # true when the mag bias estimate is stable enough to use for calibration - ``` + +::: diff --git a/docs/en/msg_docs/EstimatorStates.md b/docs/en/msg_docs/EstimatorStates.md index b3a343217b..f4f5f2f149 100644 --- a/docs/en/msg_docs/EstimatorStates.md +++ b/docs/en/msg_docs/EstimatorStates.md @@ -1,8 +1,26 @@ +--- +pageClass: is-wide-page +--- + # EstimatorStates (UORB message) +**TOPICS:** estimator_states +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorStates.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ------------- | ------------ | ---------- | -------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| states | `float32[25]` | | | Internal filter states | +| n_states | `uint8` | | | Number of states effectively used | +| covariances | `float32[24]` | | | Diagonal Elements of Covariance Matrix | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorStates.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -12,5 +30,6 @@ float32[25] states # Internal filter states uint8 n_states # Number of states effectively used float32[24] covariances # Diagonal Elements of Covariance Matrix - ``` + +::: diff --git a/docs/en/msg_docs/EstimatorStatus.md b/docs/en/msg_docs/EstimatorStatus.md index aca77484b9..b07b023f3e 100644 --- a/docs/en/msg_docs/EstimatorStatus.md +++ b/docs/en/msg_docs/EstimatorStatus.md @@ -1,6 +1,108 @@ +--- +pageClass: is-wide-page +--- + # EstimatorStatus (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorStatus.msg) +**TOPICS:** estimator_status + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------------------- | ------------ | ------------ | ---------- | -------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| output_tracking_error | `float32[3]` | | | return a vector containing the output predictor angular, velocity and position tracking error magnitudes (rad), (m/s), (m) | +| gps_check_fail_flags | `uint16` | | | Bitmask to indicate status of GPS checks - see definition below | +| control_mode_flags | `uint64` | | | Bitmask to indicate EKF logic state | +| filter_fault_flags | `uint32` | | | Bitmask to indicate EKF internal faults | +| pos_horiz_accuracy | `float32` | | | 1-Sigma estimated horizontal position accuracy relative to the estimators origin (m) | +| pos_vert_accuracy | `float32` | | | 1-Sigma estimated vertical position accuracy relative to the estimators origin (m) | +| hdg_test_ratio | `float32` | | | low-pass filtered ratio of the largest heading innovation component to the innovation test limit | +| vel_test_ratio | `float32` | | | low-pass filtered ratio of the largest velocity innovation component to the innovation test limit | +| pos_test_ratio | `float32` | | | low-pass filtered ratio of the largest horizontal position innovation component to the innovation test limit | +| hgt_test_ratio | `float32` | | | low-pass filtered ratio of the vertical position innovation to the innovation test limit | +| tas_test_ratio | `float32` | | | low-pass filtered ratio of the true airspeed innovation to the innovation test limit | +| hagl_test_ratio | `float32` | | | low-pass filtered ratio of the height above ground innovation to the innovation test limit | +| beta_test_ratio | `float32` | | | low-pass filtered ratio of the synthetic sideslip innovation to the innovation test limit | +| solution_status_flags | `uint16` | | | Bitmask indicating which filter kinematic state outputs are valid for flight control use. | +| reset_count_vel_ne | `uint8` | | | number of horizontal position reset events (allow to wrap if count exceeds 255) | +| reset_count_vel_d | `uint8` | | | number of vertical velocity reset events (allow to wrap if count exceeds 255) | +| reset_count_pos_ne | `uint8` | | | number of horizontal position reset events (allow to wrap if count exceeds 255) | +| reset_count_pod_d | `uint8` | | | number of vertical position reset events (allow to wrap if count exceeds 255) | +| reset_count_quat | `uint8` | | | number of quaternion reset events (allow to wrap if count exceeds 255) | +| time_slip | `float32` | | | cumulative amount of time in seconds that the EKF inertial calculation has slipped relative to system time | +| pre_flt_fail_innov_heading | `bool` | | | +| pre_flt_fail_innov_height | `bool` | | | +| pre_flt_fail_innov_pos_horiz | `bool` | | | +| pre_flt_fail_innov_vel_horiz | `bool` | | | +| pre_flt_fail_innov_vel_vert | `bool` | | | +| pre_flt_fail_mag_field_disturbed | `bool` | | | +| accel_device_id | `uint32` | | | +| gyro_device_id | `uint32` | | | +| baro_device_id | `uint32` | | | +| mag_device_id | `uint32` | | | +| health_flags | `uint8` | | | Bitmask to indicate sensor health states (vel, pos, hgt) | +| timeout_flags | `uint8` | | | Bitmask to indicate timeout flags (vel, pos, hgt) | +| mag_inclination_deg | `float32` | | | +| mag_inclination_ref_deg | `float32` | | | +| mag_strength_gs | `float32` | | | +| mag_strength_ref_gs | `float32` | | | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------------------------------------- | ------- | ----- | --------------------------------------------------------------------------------------------- | +| GPS_CHECK_FAIL_GPS_FIX | `uint8` | 0 | 0 : insufficient fix type (no 3D solution) | +| GPS_CHECK_FAIL_MIN_SAT_COUNT | `uint8` | 1 | 1 : minimum required sat count fail | +| GPS_CHECK_FAIL_MAX_PDOP | `uint8` | 2 | 2 : maximum allowed PDOP fail | +| GPS_CHECK_FAIL_MAX_HORZ_ERR | `uint8` | 3 | 3 : maximum allowed horizontal position error fail | +| GPS_CHECK_FAIL_MAX_VERT_ERR | `uint8` | 4 | 4 : maximum allowed vertical position error fail | +| GPS_CHECK_FAIL_MAX_SPD_ERR | `uint8` | 5 | 5 : maximum allowed speed error fail | +| GPS_CHECK_FAIL_MAX_HORZ_DRIFT | `uint8` | 6 | 6 : maximum allowed horizontal position drift fail - requires stationary vehicle | +| GPS_CHECK_FAIL_MAX_VERT_DRIFT | `uint8` | 7 | 7 : maximum allowed vertical position drift fail - requires stationary vehicle | +| GPS_CHECK_FAIL_MAX_HORZ_SPD_ERR | `uint8` | 8 | 8 : maximum allowed horizontal speed fail - requires stationary vehicle | +| GPS_CHECK_FAIL_MAX_VERT_SPD_ERR | `uint8` | 9 | 9 : maximum allowed vertical velocity discrepancy fail | +| GPS_CHECK_FAIL_SPOOFED | `uint8` | 10 | 10 : GPS signal is spoofed | +| GPS_CHECK_FAIL_JAMMED | `uint8` | 11 | 11 : GPS signal is jammed | +| CS_TILT_ALIGN | `uint8` | 0 | 0 - true if the filter tilt alignment is complete | +| CS_YAW_ALIGN | `uint8` | 1 | 1 - true if the filter yaw alignment is complete | +| CS_GNSS_POS | `uint8` | 2 | 2 - true if GNSS position measurements are being fused | +| CS_OPT_FLOW | `uint8` | 3 | 3 - true if optical flow measurements are being fused | +| CS_MAG_HDG | `uint8` | 4 | 4 - true if a simple magnetic yaw heading is being fused | +| CS_MAG_3D | `uint8` | 5 | 5 - true if 3-axis magnetometer measurement are being fused | +| CS_MAG_DEC | `uint8` | 6 | 6 - true if synthetic magnetic declination measurements are being fused | +| CS_IN_AIR | `uint8` | 7 | 7 - true when thought to be airborne | +| CS_WIND | `uint8` | 8 | 8 - true when wind velocity is being estimated | +| CS_BARO_HGT | `uint8` | 9 | 9 - true when baro data is being fused | +| CS_RNG_HGT | `uint8` | 10 | 10 - true when range finder data is being fused for height aiding | +| CS_GPS_HGT | `uint8` | 11 | 11 - true when GPS altitude is being fused | +| CS_EV_POS | `uint8` | 12 | 12 - true when local position data from external vision is being fused | +| CS_EV_YAW | `uint8` | 13 | 13 - true when yaw data from external vision measurements is being fused | +| CS_EV_HGT | `uint8` | 14 | 14 - true when height data from external vision measurements is being fused | +| CS_BETA | `uint8` | 15 | 15 - true when synthetic sideslip measurements are being fused | +| CS_MAG_FIELD | `uint8` | 16 | 16 - true when only the magnetic field states are updated by the magnetometer | +| CS_FIXED_WING | `uint8` | 17 | 17 - true when thought to be operating as a fixed wing vehicle with constrained sideslip | +| CS_MAG_FAULT | `uint8` | 18 | 18 - true when the magnetometer has been declared faulty and is no longer being used | +| CS_ASPD | `uint8` | 19 | 19 - true when airspeed measurements are being fused | +| CS_GND_EFFECT | `uint8` | 20 | 20 - true when when protection from ground effect induced static pressure rise is active | +| CS_RNG_STUCK | `uint8` | 21 | 21 - true when a stuck range finder sensor has been detected | +| CS_GPS_YAW | `uint8` | 22 | 22 - true when yaw (not ground course) data from a GPS receiver is being fused | +| CS_MAG_ALIGNED | `uint8` | 23 | 23 - true when the in-flight mag field alignment has been completed | +| CS_EV_VEL | `uint8` | 24 | 24 - true when local frame velocity data fusion from external vision measurements is intended | +| CS_SYNTHETIC_MAG_Z | `uint8` | 25 | 25 - true when we are using a synthesized measurement for the magnetometer Z component | +| CS_VEHICLE_AT_REST | `uint8` | 26 | 26 - true when the vehicle is at rest | +| CS_GPS_YAW_FAULT | `uint8` | 27 | 27 - true when the GNSS heading has been declared faulty and is no longer being used | +| CS_RNG_FAULT | `uint8` | 28 | 28 - true when the range finder has been declared faulty and is no longer being used | +| CS_GNSS_VEL | `uint8` | 44 | 44 - true if GNSS velocity measurement fusion is intended | +| CS_GNSS_FAULT | `uint8` | 45 | 45 - true if GNSS measurements have been declared faulty and are no longer used | +| CS_YAW_MANUAL | `uint8` | 46 | 46 - true if yaw has been set manually | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -130,5 +232,6 @@ float32 mag_inclination_deg float32 mag_inclination_ref_deg float32 mag_strength_gs float32 mag_strength_ref_gs - ``` + +::: diff --git a/docs/en/msg_docs/EstimatorStatusFlags.md b/docs/en/msg_docs/EstimatorStatusFlags.md index aa7250fe1e..f5cd630a8c 100644 --- a/docs/en/msg_docs/EstimatorStatusFlags.md +++ b/docs/en/msg_docs/EstimatorStatusFlags.md @@ -1,6 +1,84 @@ +--- +pageClass: is-wide-page +--- + # EstimatorStatusFlags (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorStatusFlags.msg) +**TOPICS:** estimator_statusflags + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------------- | -------- | ------------ | ---------- | ------------------------------------------------------------------------------------------------ | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| control_status_changes | `uint32` | | | number of filter control status (cs) changes | +| cs_tilt_align | `bool` | | | 0 - true if the filter tilt alignment is complete | +| cs_yaw_align | `bool` | | | 1 - true if the filter yaw alignment is complete | +| cs_gnss_pos | `bool` | | | 2 - true if GNSS position measurement fusion is intended | +| cs_opt_flow | `bool` | | | 3 - true if optical flow measurements fusion is intended | +| cs_mag_hdg | `bool` | | | 4 - true if a simple magnetic yaw heading fusion is intended | +| cs_mag_3d | `bool` | | | 5 - true if 3-axis magnetometer measurement fusion is intended | +| cs_mag_dec | `bool` | | | 6 - true if synthetic magnetic declination measurements fusion is intended | +| cs_in_air | `bool` | | | 7 - true when the vehicle is airborne | +| cs_wind | `bool` | | | 8 - true when wind velocity is being estimated | +| cs_baro_hgt | `bool` | | | 9 - true when baro data is being fused | +| cs_rng_hgt | `bool` | | | 10 - true when range finder data is being fused for height aiding | +| cs_gps_hgt | `bool` | | | 11 - true when GPS altitude is being fused | +| cs_ev_pos | `bool` | | | 12 - true when local position data fusion from external vision is intended | +| cs_ev_yaw | `bool` | | | 13 - true when yaw data from external vision measurements fusion is intended | +| cs_ev_hgt | `bool` | | | 14 - true when height data from external vision measurements is being fused | +| cs_fuse_beta | `bool` | | | 15 - true when synthetic sideslip measurements are being fused | +| cs_mag_field_disturbed | `bool` | | | 16 - true when the mag field does not match the expected strength | +| cs_fixed_wing | `bool` | | | 17 - true when the vehicle is operating as a fixed wing vehicle | +| cs_mag_fault | `bool` | | | 18 - true when the magnetometer has been declared faulty and is no longer being used | +| cs_fuse_aspd | `bool` | | | 19 - true when airspeed measurements are being fused | +| cs_gnd_effect | `bool` | | | 20 - true when protection from ground effect induced static pressure rise is active | +| cs_rng_stuck | `bool` | | | 21 - true when rng data wasn't ready for more than 10s and new rng values haven't changed enough | +| cs_gnss_yaw | `bool` | | | 22 - true when yaw (not ground course) data fusion from a GPS receiver is intended | +| cs_mag_aligned_in_flight | `bool` | | | 23 - true when the in-flight mag field alignment has been completed | +| cs_ev_vel | `bool` | | | 24 - true when local frame velocity data fusion from external vision measurements is intended | +| cs_synthetic_mag_z | `bool` | | | 25 - true when we are using a synthesized measurement for the magnetometer Z component | +| cs_vehicle_at_rest | `bool` | | | 26 - true when the vehicle is at rest | +| cs_gnss_yaw_fault | `bool` | | | 27 - true when the GNSS heading has been declared faulty and is no longer being used | +| cs_rng_fault | `bool` | | | 28 - true when the range finder has been declared faulty and is no longer being used | +| cs_inertial_dead_reckoning | `bool` | | | 29 - true if we are no longer fusing measurements that constrain horizontal velocity drift | +| cs_wind_dead_reckoning | `bool` | | | 30 - true if we are navigationg reliant on wind relative measurements | +| cs_rng_kin_consistent | `bool` | | | 31 - true when the range finder kinematic consistency check is passing | +| cs_fake_pos | `bool` | | | 32 - true when fake position measurements are being fused | +| cs_fake_hgt | `bool` | | | 33 - true when fake height measurements are being fused | +| cs_gravity_vector | `bool` | | | 34 - true when gravity vector measurements are being fused | +| cs_mag | `bool` | | | 35 - true if 3-axis magnetometer measurement fusion (mag states only) is intended | +| cs_ev_yaw_fault | `bool` | | | 36 - true when the EV heading has been declared faulty and is no longer being used | +| cs_mag_heading_consistent | `bool` | | | 37 - true when the heading obtained from mag data is declared consistent with the filter | +| cs_aux_gpos | `bool` | | | 38 - true if auxiliary global position measurement fusion is intended | +| cs_rng_terrain | `bool` | | | 39 - true if we are fusing range finder data for terrain | +| cs_opt_flow_terrain | `bool` | | | 40 - true if we are fusing flow data for terrain | +| cs_valid_fake_pos | `bool` | | | 41 - true if a valid constant position is being fused | +| cs_constant_pos | `bool` | | | 42 - true if the vehicle is at a constant position | +| cs_baro_fault | `bool` | | | 43 - true when the current baro has been declared faulty and is no longer being used | +| cs_gnss_vel | `bool` | | | 44 - true if GNSS velocity measurement fusion is intended | +| cs_gnss_fault | `bool` | | | 45 - true if GNSS true if GNSS measurements (lat, lon, vel) have been declared faulty | +| cs_yaw_manual | `bool` | | | 46 - true if yaw has been set manually | +| cs_gnss_hgt_fault | `bool` | | | 47 - true if GNSS true if GNSS measurements (alt) have been declared faulty | +| fault_status_changes | `uint32` | | | number of filter fault status (fs) changes | +| fs_bad_mag_x | `bool` | | | 0 - true if the fusion of the magnetometer X-axis has encountered a numerical error | +| fs_bad_mag_y | `bool` | | | 1 - true if the fusion of the magnetometer Y-axis has encountered a numerical error | +| fs_bad_mag_z | `bool` | | | 2 - true if the fusion of the magnetometer Z-axis has encountered a numerical error | +| fs_bad_hdg | `bool` | | | 3 - true if the fusion of the heading angle has encountered a numerical error | +| fs_bad_mag_decl | `bool` | | | 4 - true if the fusion of the magnetic declination has encountered a numerical error | +| fs_bad_airspeed | `bool` | | | 5 - true if fusion of the airspeed has encountered a numerical error | +| fs_bad_sideslip | `bool` | | | 6 - true if fusion of the synthetic sideslip constraint has encountered a numerical error | +| fs_bad_optflow_x | `bool` | | | 7 - true if fusion of the optical flow X axis has encountered a numerical error | +| fs_bad_optflow_y | `bool` | | | 8 - true if fusion of the optical flow Y axis has encountered a numerical error | +| fs_bad_acc_vertical | `bool` | | | 10 - true if bad vertical accelerometer data has been detected | +| fs_bad_acc_clipping | `bool` | | | 11 - true if delta velocity data contains clipping (asymmetric railing) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorStatusFlags.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -71,19 +149,6 @@ bool fs_bad_optflow_x # 7 - true if fusion of the optical flow X axis h bool fs_bad_optflow_y # 8 - true if fusion of the optical flow Y axis has encountered a numerical error bool fs_bad_acc_vertical # 10 - true if bad vertical accelerometer data has been detected bool fs_bad_acc_clipping # 11 - true if delta velocity data contains clipping (asymmetric railing) - - -# innovation test failures -uint32 innovation_fault_status_changes # number of innovation fault status (reject) changes -bool reject_hor_vel # 0 - true if horizontal velocity observations have been rejected -bool reject_ver_vel # 1 - true if vertical velocity observations have been rejected -bool reject_hor_pos # 2 - true if horizontal position observations have been rejected -bool reject_ver_pos # 3 - true if vertical position observations have been rejected -bool reject_yaw # 7 - true if the yaw observation has been rejected -bool reject_airspeed # 8 - true if the airspeed observation has been rejected -bool reject_sideslip # 9 - true if the synthetic sideslip observation has been rejected -bool reject_hagl # 10 - true if the height above ground observation has been rejected -bool reject_optflow_x # 11 - true if the X optical flow observation has been rejected -bool reject_optflow_y # 12 - true if the Y optical flow observation has been rejected - ``` + +::: diff --git a/docs/en/msg_docs/Event.md b/docs/en/msg_docs/Event.md index 5d22f337f5..b32143749d 100644 --- a/docs/en/msg_docs/Event.md +++ b/docs/en/msg_docs/Event.md @@ -1,8 +1,35 @@ +--- +pageClass: is-wide-page +--- + # Event (UORB message) -Events interface +Events interface. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/Event.msg) +**TOPICS:** event + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------- | ----------- | ------------ | ---------- | ------------------------------------------------------ | +| timestamp | `uint64` | | | time since system start (microseconds) | +| id | `uint32` | | | Event ID | +| event_sequence | `uint16` | | | Event sequence number | +| arguments | `uint8[25]` | | | (optional) arguments, depend on event id | +| log_levels | `uint8` | | | Log levels: 4 bits MSB: internal, 4 bits LSB: external | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 1 | +| ORB_QUEUE_LENGTH | `uint8` | 16 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/Event.msg) + +::: details Click here to see original file ```c # Events interface @@ -17,5 +44,6 @@ uint8[25] arguments # (optional) arguments, depend on event id uint8 log_levels # Log levels: 4 bits MSB: internal, 4 bits LSB: external uint8 ORB_QUEUE_LENGTH = 16 - ``` + +::: diff --git a/docs/en/msg_docs/EventV0.md b/docs/en/msg_docs/EventV0.md index 19cfa7b70c..e0d8cf8619 100644 --- a/docs/en/msg_docs/EventV0.md +++ b/docs/en/msg_docs/EventV0.md @@ -1,9 +1,35 @@ +--- +pageClass: is-wide-page +--- + # EventV0 (UORB message) -this message is required here in the msg_old folder because other msg are depending on it -Events interface +this message is required here in the msg_old folder because other msg are depending on it. Events interface. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/EventV0.msg) +**TOPICS:** eventv0 + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------- | ----------- | ------------ | ---------- | ------------------------------------------------------ | +| timestamp | `uint64` | | | time since system start (microseconds) | +| id | `uint32` | | | Event ID | +| event_sequence | `uint16` | | | Event sequence number | +| arguments | `uint8[25]` | | | (optional) arguments, depend on event id | +| log_levels | `uint8` | | | Log levels: 4 bits MSB: internal, 4 bits LSB: external | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | +| ORB_QUEUE_LENGTH | `uint8` | 16 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/EventV0.msg) + +::: details Click here to see original file ```c # this message is required here in the msg_old folder because other msg are depending on it @@ -20,5 +46,6 @@ uint8[25] arguments # (optional) arguments, depend on event id uint8 log_levels # Log levels: 4 bits MSB: internal, 4 bits LSB: external uint8 ORB_QUEUE_LENGTH = 16 - ``` + +::: diff --git a/docs/en/msg_docs/FailsafeFlags.md b/docs/en/msg_docs/FailsafeFlags.md index a9e0079ae8..4d55acf155 100644 --- a/docs/en/msg_docs/FailsafeFlags.md +++ b/docs/en/msg_docs/FailsafeFlags.md @@ -1,3 +1,7 @@ +--- +pageClass: is-wide-page +--- + # FailsafeFlags (UORB message) Input flags for the failsafe state machine set by the arming & health checks. @@ -5,7 +9,60 @@ Input flags for the failsafe state machine set by the arming & health checks. Flags must be named such that false == no failure (e.g. \_invalid, \_unhealthy, \_lost) The flag comments are used as label for the failsafe state machine simulation -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FailsafeFlags.msg) +**TOPICS:** failsafe_flags + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------------------------- | -------- | ------------ | ---------- | ----------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| mode_req_angular_velocity | `uint32` | | | +| mode_req_attitude | `uint32` | | | +| mode_req_local_alt | `uint32` | | | +| mode_req_local_position | `uint32` | | | +| mode_req_local_position_relaxed | `uint32` | | | +| mode_req_global_position | `uint32` | | | +| mode_req_global_position_relaxed | `uint32` | | | +| mode_req_mission | `uint32` | | | +| mode_req_offboard_signal | `uint32` | | | +| mode_req_home_position | `uint32` | | | +| mode_req_wind_and_flight_time_compliance | `uint32` | | | if set, mode cannot be entered if wind or flight time limit exceeded | +| mode_req_prevent_arming | `uint32` | | | if set, cannot arm while in this mode | +| mode_req_manual_control | `uint32` | | | +| mode_req_other | `uint32` | | | other requirements, not covered above (for external modes) | +| angular_velocity_invalid | `bool` | | | Angular velocity invalid | +| attitude_invalid | `bool` | | | Attitude invalid | +| local_altitude_invalid | `bool` | | | Local altitude invalid | +| local_position_invalid | `bool` | | | Local position estimate invalid | +| local_position_invalid_relaxed | `bool` | | | Local position with reduced accuracy requirements invalid (e.g. flying with optical flow) | +| local_velocity_invalid | `bool` | | | Local velocity estimate invalid | +| global_position_invalid | `bool` | | | Global position estimate invalid | +| global_position_invalid_relaxed | `bool` | | | Global position estimate invalid with relaxed accuracy requirements | +| auto_mission_missing | `bool` | | | No mission available | +| offboard_control_signal_lost | `bool` | | | Offboard signal lost | +| home_position_invalid | `bool` | | | No home position available | +| manual_control_signal_lost | `bool` | | | Manual control (RC) signal lost | +| gcs_connection_lost | `bool` | | | GCS connection lost | +| battery_warning | `uint8` | | | Battery warning level (see BatteryStatus.msg) | +| battery_low_remaining_time | `bool` | | | Low battery based on remaining flight time | +| battery_unhealthy | `bool` | | | Battery unhealthy | +| geofence_breached | `bool` | | | Geofence breached (one or multiple) | +| mission_failure | `bool` | | | Mission failure | +| vtol_fixed_wing_system_failure | `bool` | | | vehicle in fixed-wing system failure failsafe mode (after quad-chute) | +| wind_limit_exceeded | `bool` | | | Wind limit exceeded | +| flight_time_limit_exceeded | `bool` | | | Maximum flight time exceeded | +| position_accuracy_low | `bool` | | | Position estimate has dropped below threshold, but is currently still declared valid | +| navigator_failure | `bool` | | | Navigator failed to execute a mode | +| fd_critical_failure | `bool` | | | Critical failure (attitude/altitude limit exceeded, or external ATS) | +| fd_esc_arming_failure | `bool` | | | ESC failed to arm | +| fd_imbalanced_prop | `bool` | | | Imbalanced propeller detected | +| fd_motor_failure | `bool` | | | Motor failure | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FailsafeFlags.msg) + +::: details Click here to see original file ```c # Input flags for the failsafe state machine set by the arming & health checks. @@ -68,5 +125,6 @@ bool fd_critical_failure # Critical failure (attitude/altitude limi bool fd_esc_arming_failure # ESC failed to arm bool fd_imbalanced_prop # Imbalanced propeller detected bool fd_motor_failure # Motor failure - ``` + +::: diff --git a/docs/en/msg_docs/FailureDetectorStatus.md b/docs/en/msg_docs/FailureDetectorStatus.md index a112a1e642..66474a28c0 100644 --- a/docs/en/msg_docs/FailureDetectorStatus.md +++ b/docs/en/msg_docs/FailureDetectorStatus.md @@ -1,6 +1,33 @@ +--- +pageClass: is-wide-page +--- + # FailureDetectorStatus (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FailureDetectorStatus.msg) +**TOPICS:** failure_detectorstatus + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------- | --------- | ------------ | ---------- | --------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| fd_roll | `bool` | | | +| fd_pitch | `bool` | | | +| fd_alt | `bool` | | | +| fd_ext | `bool` | | | +| fd_arm_escs | `bool` | | | +| fd_battery | `bool` | | | +| fd_imbalanced_prop | `bool` | | | +| fd_motor | `bool` | | | +| imbalanced_prop_metric | `float32` | | | Metric of the imbalanced propeller check (low-passed) | +| motor_failure_mask | `uint16` | | | Bit-mask with motor indices, indicating critical motor failures | +| motor_stop_mask | `uint16` | | | Bitmaks of motors stopped by failure injection | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FailureDetectorStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -18,5 +45,6 @@ bool fd_motor float32 imbalanced_prop_metric # Metric of the imbalanced propeller check (low-passed) uint16 motor_failure_mask # Bit-mask with motor indices, indicating critical motor failures uint16 motor_stop_mask # Bitmaks of motors stopped by failure injection - ``` + +::: diff --git a/docs/en/msg_docs/FigureEightStatus.md b/docs/en/msg_docs/FigureEightStatus.md index 5487490804..2f1e197a89 100644 --- a/docs/en/msg_docs/FigureEightStatus.md +++ b/docs/en/msg_docs/FigureEightStatus.md @@ -1,8 +1,29 @@ +--- +pageClass: is-wide-page +--- + # FigureEightStatus (UORB message) +**TOPICS:** figure_eightstatus +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FigureEightStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------ | --------- | ------------ | ---------- | ----------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| major_radius | `float32` | | | Major axis radius of the figure eight [m]. Positive values orbit clockwise, negative values orbit counter-clockwise. | +| minor_radius | `float32` | | | Minor axis radius of the figure eight [m]. | +| orientation | `float32` | | | Orientation of the major axis of the figure eight [rad]. | +| frame | `uint8` | | | The coordinate system of the fields: x, y, z. | +| x | `int32` | | | X coordinate of center point. Coordinate system depends on frame field: local = x position in meters _ 1e4, global = latitude in degrees _ 1e7. | +| y | `int32` | | | Y coordinate of center point. Coordinate system depends on frame field: local = y position in meters _ 1e4, global = latitude in degrees _ 1e7. | +| z | `float32` | | | Altitude of center point. Coordinate system depends on frame field. | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FigureEightStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -13,5 +34,6 @@ uint8 frame # The coordinate system of the fields: x, y, z. int32 x # X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7. int32 y # Y coordinate of center point. Coordinate system depends on frame field: local = y position in meters * 1e4, global = latitude in degrees * 1e7. float32 z # Altitude of center point. Coordinate system depends on frame field. - ``` + +::: diff --git a/docs/en/msg_docs/FixedWingLateralGuidanceStatus.md b/docs/en/msg_docs/FixedWingLateralGuidanceStatus.md index 02dc50b410..648e02d748 100644 --- a/docs/en/msg_docs/FixedWingLateralGuidanceStatus.md +++ b/docs/en/msg_docs/FixedWingLateralGuidanceStatus.md @@ -1,9 +1,32 @@ +--- +pageClass: is-wide-page +--- + # FixedWingLateralGuidanceStatus (UORB message) -Fixed Wing Lateral Guidance Status message -Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs +Fixed Wing Lateral Guidance Status message. Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FixedWingLateralGuidanceStatus.msg) +**TOPICS:** fixed_winglateral_guidancestatus + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------------- | --------- | ------------ | ---------- | ------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| course_setpoint | `float32` | rad | [-pi : pi] | Desired direction of travel over ground w.r.t (true) North. Set by guidance law | +| lateral_acceleration_ff | `float32` | FRD | | lateral acceleration demand only for maintaining curvature | +| bearing_feas | `float32` | | [0 : 1] | bearing feasibility | +| bearing_feas_on_track | `float32` | | [0 : 1] | on-track bearing feasibility | +| signed_track_error | `float32` | m | | signed track error | +| track_error_bound | `float32` | m | | track error bound | +| adapted_period | `float32` | s | | adapted period (if auto-tuning enabled) | +| wind_est_valid | `uint8` | boolean | | true = wind estimate is valid and/or being used by controller (also indicates if wind estimate usage is disabled despite being valid) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FixedWingLateralGuidanceStatus.msg) + +::: details Click here to see original file ```c # Fixed Wing Lateral Guidance Status message @@ -19,5 +42,6 @@ float32 signed_track_error # [m] signed track error float32 track_error_bound # [m] track error bound float32 adapted_period # [s] adapted period (if auto-tuning enabled) uint8 wind_est_valid # [boolean] true = wind estimate is valid and/or being used by controller (also indicates if wind estimate usage is disabled despite being valid) - ``` + +::: diff --git a/docs/en/msg_docs/FixedWingLateralSetpoint.md b/docs/en/msg_docs/FixedWingLateralSetpoint.md index 153167bb62..3b1cc74836 100644 --- a/docs/en/msg_docs/FixedWingLateralSetpoint.md +++ b/docs/en/msg_docs/FixedWingLateralSetpoint.md @@ -1,10 +1,33 @@ +--- +pageClass: is-wide-page +--- + # FixedWingLateralSetpoint (UORB message) -Fixed Wing Lateral Setpoint message -Used by the fw_lateral_longitudinal_control module -At least one of course, airspeed_direction, or lateral_acceleration must be finite. +Fixed Wing Lateral Setpoint message. Used by the fw_lateral_longitudinal_control module. At least one of course, airspeed_direction, or lateral_acceleration must be finite. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/FixedWingLateralSetpoint.msg) +**TOPICS:** fixed_winglateral_setpoint + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------- | --------- | ------------ | ---------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| course | `float32` | rad | [-pi : pi] | Desired direction of travel over ground w.r.t (true) North. NAN if not controlled directly. | +| airspeed_direction | `float32` | rad | [-pi : pi] | Desired horizontal angle of airspeed vector w.r.t. (true) North. Same as vehicle heading if in the absence of sideslip. NAN if not controlled directly, takes precedence over course if finite. | +| lateral_acceleration | `float32` | FRD | | Lateral acceleration setpoint. NAN if not controlled directly, used as feedforward if either course setpoint or airspeed_direction is finite. | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/FixedWingLateralSetpoint.msg) + +::: details Click here to see original file ```c # Fixed Wing Lateral Setpoint message @@ -18,5 +41,6 @@ uint64 timestamp # time since system start (microseconds) float32 course # [rad] [@range -pi, pi] Desired direction of travel over ground w.r.t (true) North. NAN if not controlled directly. float32 airspeed_direction # [rad] [@range -pi, pi] Desired horizontal angle of airspeed vector w.r.t. (true) North. Same as vehicle heading if in the absence of sideslip. NAN if not controlled directly, takes precedence over course if finite. float32 lateral_acceleration # [m/s^2] [FRD] Lateral acceleration setpoint. NAN if not controlled directly, used as feedforward if either course setpoint or airspeed_direction is finite. - ``` + +::: diff --git a/docs/en/msg_docs/FixedWingLateralStatus.md b/docs/en/msg_docs/FixedWingLateralStatus.md index 9214d1e9e0..5956a00dfb 100644 --- a/docs/en/msg_docs/FixedWingLateralStatus.md +++ b/docs/en/msg_docs/FixedWingLateralStatus.md @@ -1,9 +1,26 @@ +--- +pageClass: is-wide-page +--- + # FixedWingLateralStatus (UORB message) -Fixed Wing Lateral Status message -Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint +Fixed Wing Lateral Status message. Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FixedWingLateralStatus.msg) +**TOPICS:** fixed_winglateral_status + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------------------- | --------- | ------------ | ---------- | ---------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| lateral_acceleration_setpoint | `float32` | FRD | | resultant lateral acceleration setpoint | +| can_run_factor | `float32` | norm | [0 : 1] | estimate of certainty of the correct functionality of the npfg roll setpoint | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FixedWingLateralStatus.msg) + +::: details Click here to see original file ```c # Fixed Wing Lateral Status message @@ -13,5 +30,6 @@ uint64 timestamp # time since system start (microseconds float32 lateral_acceleration_setpoint # [m/s^2] [FRD] resultant lateral acceleration setpoint float32 can_run_factor # [norm] [@range 0, 1] estimate of certainty of the correct functionality of the npfg roll setpoint - ``` + +::: diff --git a/docs/en/msg_docs/FixedWingLongitudinalSetpoint.md b/docs/en/msg_docs/FixedWingLongitudinalSetpoint.md index 6b8fb29e5b..f58d892f8f 100644 --- a/docs/en/msg_docs/FixedWingLongitudinalSetpoint.md +++ b/docs/en/msg_docs/FixedWingLongitudinalSetpoint.md @@ -1,11 +1,35 @@ +--- +pageClass: is-wide-page +--- + # FixedWingLongitudinalSetpoint (UORB message) -Fixed Wing Longitudinal Setpoint message -Used by the fw_lateral_longitudinal_control module -If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion. -If both altitude and height_rate are NAN, the controller maintains the current altitude. +Fixed Wing Longitudinal Setpoint message. Used by the fw_lateral_longitudinal_control module. If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion. If both altitude and height_rate are NAN, the controller maintains the current altitude. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/FixedWingLongitudinalSetpoint.msg) +**TOPICS:** fixed_winglongitudinal_setpoint + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------- | --------- | ------------ | ---------- | ---------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| altitude | `float32` | m | | Altitude setpoint AMSL, not controlled directly if NAN or if height_rate is finite | +| height_rate | `float32` | ENU | | Scalar height rate setpoint. NAN if not controlled directly | +| equivalent_airspeed | `float32` | m/s | [0 : inf] | Scalar equivalent airspeed setpoint. NAN if system default should be used | +| pitch_direct | `float32` | FRD | [-pi : pi] | NAN if not controlled, overrides total energy controller | +| throttle_direct | `float32` | norm | [0 : 1] | NAN if not controlled, overrides total energy controller | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/FixedWingLongitudinalSetpoint.msg) + +::: details Click here to see original file ```c # Fixed Wing Longitudinal Setpoint message @@ -22,5 +46,6 @@ float32 height_rate # [m/s] [ENU] Scalar height rate setpoint. NAN if not con float32 equivalent_airspeed # [m/s] [@range 0, inf] Scalar equivalent airspeed setpoint. NAN if system default should be used float32 pitch_direct # [rad] [@range -pi, pi] [FRD] NAN if not controlled, overrides total energy controller float32 throttle_direct # [norm] [@range 0,1] NAN if not controlled, overrides total energy controller - ``` + +::: diff --git a/docs/en/msg_docs/FixedWingRunwayControl.md b/docs/en/msg_docs/FixedWingRunwayControl.md index 9e9f5ff428..a51a543a72 100644 --- a/docs/en/msg_docs/FixedWingRunwayControl.md +++ b/docs/en/msg_docs/FixedWingRunwayControl.md @@ -1,19 +1,53 @@ +--- +pageClass: is-wide-page +--- + # FixedWingRunwayControl (UORB message) -Auxiliary control fields for fixed-wing runway takeoff/landing +Auxiliary control fields for fixed-wing runway takeoff/landing. -Passes information from the FixedWingModeManager to the FixedWingAttitudeController +**TOPICS:** fixed_wingrunway_control -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FixedWingRunwayControl.msg) +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------------------- | --------- | ------------ | ---------- | -------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | time since system start | +| runway_takeoff_state | `uint8` | | | Current state of runway takeoff state machine | +| wheel_steering_enabled | `bool` | | | Flag that enables the wheel steering. | +| wheel_steering_nudging_rate | `float32` | FRD | [-1 : 1] | Manual wheel nudging, added to controller output. NAN is interpreted as 0. | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------- | ------- | ----- | ------------------------------------------------------------- | +| STATE_THROTTLE_RAMP | `uint8` | 0 | ramping up throttle | +| STATE_CLAMPED_TO_RUNWAY | `uint8` | 1 | clamped to runway, controlling yaw directly (wheel or rudder) | +| STATE_CLIMBOUT | `uint8` | 2 | climbout to safe height before navigation | +| STATE_FLYING | `uint8` | 3 | navigate freely | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FixedWingRunwayControl.msg) + +::: details Click here to see original file ```c # Auxiliary control fields for fixed-wing runway takeoff/landing -# Passes information from the FixedWingModeManager to the FixedWingAttitudeController +# Passes information from the FixedWingModeManager to the FixedWingAttitudeController (wheel control) and FixedWingLandDetector (takeoff state) uint64 timestamp # [us] time since system start +uint8 STATE_THROTTLE_RAMP = 0 # ramping up throttle +uint8 STATE_CLAMPED_TO_RUNWAY = 1 # clamped to runway, controlling yaw directly (wheel or rudder) +uint8 STATE_CLIMBOUT = 2 # climbout to safe height before navigation +uint8 STATE_FLYING = 3 # navigate freely + +uint8 runway_takeoff_state # Current state of runway takeoff state machine + bool wheel_steering_enabled # Flag that enables the wheel steering. float32 wheel_steering_nudging_rate # [norm] [@range -1, 1] [FRD] Manual wheel nudging, added to controller output. NAN is interpreted as 0. - ``` + +::: diff --git a/docs/en/msg_docs/FlightPhaseEstimation.md b/docs/en/msg_docs/FlightPhaseEstimation.md index b3d9147e28..de23fd4f1b 100644 --- a/docs/en/msg_docs/FlightPhaseEstimation.md +++ b/docs/en/msg_docs/FlightPhaseEstimation.md @@ -1,8 +1,32 @@ +--- +pageClass: is-wide-page +--- + # FlightPhaseEstimation (UORB message) +**TOPICS:** flight_phaseestimation +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FlightPhaseEstimation.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------ | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| flight_phase | `uint8` | | | Estimate of current flight phase | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------- | ------- | ----- | ------------------------------- | +| FLIGHT_PHASE_UNKNOWN | `uint8` | 0 | vehicle flight phase is unknown | +| FLIGHT_PHASE_LEVEL | `uint8` | 1 | Vehicle is in level flight | +| FLIGHT_PHASE_DESCEND | `uint8` | 2 | vehicle is in descend | +| FLIGHT_PHASE_CLIMB | `uint8` | 3 | vehicle is climbing | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FlightPhaseEstimation.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -13,5 +37,6 @@ uint8 FLIGHT_PHASE_UNKNOWN = 0 # vehicle flight phase is unknown uint8 FLIGHT_PHASE_LEVEL = 1 # Vehicle is in level flight uint8 FLIGHT_PHASE_DESCEND = 2 # vehicle is in descend uint8 FLIGHT_PHASE_CLIMB = 3 # vehicle is climbing - ``` + +::: diff --git a/docs/en/msg_docs/FollowTarget.md b/docs/en/msg_docs/FollowTarget.md index e9086f27d6..1aab86e642 100644 --- a/docs/en/msg_docs/FollowTarget.md +++ b/docs/en/msg_docs/FollowTarget.md @@ -1,8 +1,29 @@ +--- +pageClass: is-wide-page +--- + # FollowTarget (UORB message) +**TOPICS:** follow_target +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FollowTarget.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | --------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| lat | `float64` | | | target position (deg \* 1e7) | +| lon | `float64` | | | target position (deg \* 1e7) | +| alt | `float32` | | | target position | +| vy | `float32` | | | target vel in y | +| vx | `float32` | | | target vel in x | +| vz | `float32` | | | target vel in z | +| est_cap | `uint8` | | | target reporting capabilities | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FollowTarget.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -16,5 +37,6 @@ float32 vx # target vel in x float32 vz # target vel in z uint8 est_cap # target reporting capabilities - ``` + +::: diff --git a/docs/en/msg_docs/FollowTargetEstimator.md b/docs/en/msg_docs/FollowTargetEstimator.md index e118475f41..a9a18b8796 100644 --- a/docs/en/msg_docs/FollowTargetEstimator.md +++ b/docs/en/msg_docs/FollowTargetEstimator.md @@ -1,8 +1,33 @@ +--- +pageClass: is-wide-page +--- + # FollowTargetEstimator (UORB message) +**TOPICS:** follow_targetestimator +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FollowTargetEstimator.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------------------- | ------------ | ------------ | ---------- | ----------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| last_filter_reset_timestamp | `uint64` | | | time of last filter reset (microseconds) | +| valid | `bool` | | | True if estimator states are okay to be used | +| stale | `bool` | | | True if estimator stopped receiving follow_target messages for some time. The estimate can still be valid, though it might be inaccurate. | +| lat_est | `float64` | | | Estimated target latitude | +| lon_est | `float64` | | | Estimated target longitude | +| alt_est | `float32` | | | Estimated target altitude | +| pos_est | `float32[3]` | | | Estimated target NED position (m) | +| vel_est | `float32[3]` | | | Estimated target NED velocity (m/s) | +| acc_est | `float32[3]` | | | Estimated target NED acceleration (m^2/s) | +| prediction_count | `uint64` | | | +| fusion_count | `uint64` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FollowTargetEstimator.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -21,5 +46,6 @@ float32[3] acc_est # Estimated target NED acceleration (m^2/s) uint64 prediction_count uint64 fusion_count - ``` + +::: diff --git a/docs/en/msg_docs/FollowTargetStatus.md b/docs/en/msg_docs/FollowTargetStatus.md index 7f24cc1dd5..a40cc3c215 100644 --- a/docs/en/msg_docs/FollowTargetStatus.md +++ b/docs/en/msg_docs/FollowTargetStatus.md @@ -1,8 +1,29 @@ +--- +pageClass: is-wide-page +--- + # FollowTargetStatus (UORB message) +**TOPICS:** follow_targetstatus +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FollowTargetStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------------- | ------------ | ------------ | ---------- | -------------------------------------------------------------------------------------- | +| timestamp | `uint64` | microseconds | | time since system start | +| tracked_target_course | `float32` | rad | | Tracked target course in NED local frame (North is course zero) | +| follow_angle | `float32` | rad | | Current follow angle setting | +| orbit_angle_setpoint | `float32` | rad | | Current orbit angle setpoint from the smooth trajectory generator | +| angular_rate_setpoint | `float32` | rad/s | | Angular rate commanded from Jerk-limited Orbit Angle trajectory for Orbit Angle | +| desired_position_raw | `float32[3]` | m | | Raw 'idealistic' desired drone position if a drone could teleport from place to places | +| in_emergency_ascent | `bool` | bool | | True when doing emergency ascent (when distance to ground is below safety altitude) | +| gimbal_pitch | `float32` | rad | | Gimbal pitch commanded to track target in the center of the frame | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FollowTargetStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # [microseconds] time since system start @@ -17,5 +38,6 @@ float32[3] desired_position_raw # [m] Raw 'idealistic' desired drone position bool in_emergency_ascent # [bool] True when doing emergency ascent (when distance to ground is below safety altitude) float32 gimbal_pitch # [rad] Gimbal pitch commanded to track target in the center of the frame - ``` + +::: diff --git a/docs/en/msg_docs/FuelTankStatus.md b/docs/en/msg_docs/FuelTankStatus.md index 608999e84c..762ad98bfe 100644 --- a/docs/en/msg_docs/FuelTankStatus.md +++ b/docs/en/msg_docs/FuelTankStatus.md @@ -1,8 +1,38 @@ +--- +pageClass: is-wide-page +--- + # FuelTankStatus (UORB message) +**TOPICS:** fuel_tankstatus +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FuelTankStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------------- | --------- | ------------ | ---------- | ------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| maximum_fuel_capacity | `float32` | | | maximum fuel capacity. Must always be provided, either from the driver or a parameter | +| consumed_fuel | `float32` | | | consumed fuel, NaN if not measured. Should not be inferred from the max fuel capacity | +| fuel_consumption_rate | `float32` | | | fuel consumption rate, NaN if not measured | +| percent_remaining | `uint8` | | | percentage of remaining fuel, UINT8_MAX if not provided | +| remaining_fuel | `float32` | | | remaining fuel, NaN if not measured. Should not be inferred from the max fuel capacity | +| fuel_tank_id | `uint8` | | | identifier for the fuel tank. Must match ID of other messages for same fuel system. 0 by default when only a single tank exists | +| fuel_type | `uint32` | | | type of fuel based on MAV_FUEL_TYPE enum. Set to MAV_FUEL_TYPE_UNKNOWN if unknown or it does not fit the provided types | +| temperature | `float32` | | | fuel temperature in Kelvin, NaN if not measured | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------- | ------- | ----- | ----------------------------------------------------------------------------------------------------------------------------------------------------------- | +| MAV_FUEL_TYPE_UNKNOWN | `uint8` | 0 | fuel type not specified. Fuel levels are normalized (i.e., maximum is 1, and other levels are relative to 1). | +| MAV_FUEL_TYPE_LIQUID | `uint8` | 1 | represents generic liquid fuels, such as gasoline or diesel. Fuel levels are measured in millilitres (ml), and flow rates in millilitres per second (ml/s). | +| MAV_FUEL_TYPE_GAS | `uint8` | 2 | represents a gas fuel, such as hydrogen, methane, or propane. Fuel levels are in kilo-Pascal (kPa), and flow rates are in milliliters per second (ml/s). | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FuelTankStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -22,5 +52,6 @@ uint8 MAV_FUEL_TYPE_LIQUID = 1 # represents generic liquid fuels, such as gasol uint8 MAV_FUEL_TYPE_GAS = 2 # represents a gas fuel, such as hydrogen, methane, or propane. Fuel levels are in kilo-Pascal (kPa), and flow rates are in milliliters per second (ml/s). float32 temperature # fuel temperature in Kelvin, NaN if not measured - ``` + +::: diff --git a/docs/en/msg_docs/GainCompression.md b/docs/en/msg_docs/GainCompression.md index e26c1e8fcc..c19a34c34b 100644 --- a/docs/en/msg_docs/GainCompression.md +++ b/docs/en/msg_docs/GainCompression.md @@ -1,6 +1,25 @@ +--- +pageClass: is-wide-page +--- + # GainCompression (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GainCompression.msg) +**TOPICS:** gain_compression + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------- | ------------ | ------------ | ---------- | ------------------------------------------------------------------- | +| timestamp | `uint64` | | | Time since system start (microseconds) | +| compression_gains | `float32[3]` | [FRD] | [0 : 1] | Multiplicative gain to modify the output of the controller per axis | +| spectral_damper_hpf | `float32[3]` | [FRD] | | Squared output of spectral damper high-pass filter | +| spectral_damper_out | `float32[3]` | [FRD] | | Spectral damper output squared | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GainCompression.msg) + +::: details Click here to see original file ```c uint64 timestamp # Time since system start (microseconds) @@ -8,5 +27,6 @@ uint64 timestamp # Time since system start (microseconds) float32[3] compression_gains # [-] [@frame FRD] [@range 0, 1] Multiplicative gain to modify the output of the controller per axis float32[3] spectral_damper_hpf # [-] [@frame FRD] Squared output of spectral damper high-pass filter float32[3] spectral_damper_out # [-] [@frame FRD] Spectral damper output squared - ``` + +::: diff --git a/docs/en/msg_docs/GeneratorStatus.md b/docs/en/msg_docs/GeneratorStatus.md index 159221547f..41092269e5 100644 --- a/docs/en/msg_docs/GeneratorStatus.md +++ b/docs/en/msg_docs/GeneratorStatus.md @@ -1,8 +1,61 @@ +--- +pageClass: is-wide-page +--- + # GeneratorStatus (UORB message) +**TOPICS:** generator_status +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GeneratorStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------- | --------- | ------------ | ---------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| status | `uint64` | | | Status flags | +| battery_current | `float32` | A | | Current into/out of battery. Positive for out. Negative for in. NaN: field not provided. | +| load_current | `float32` | A | | Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided | +| power_generated | `float32` | W | | The power being generated. NaN: field not provided | +| bus_voltage | `float32` | V | | Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus. | +| bat_current_setpoint | `float32` | A | | The target battery current. Positive for out. Negative for in. NaN: field not provided | +| runtime | `uint32` | s | | Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided. | +| time_until_maintenance | `int32` | s | | Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided. | +| generator_speed | `uint16` | rpm | | Speed of electrical generator or alternator. UINT16_MAX: field not provided. | +| rectifier_temperature | `int16` | degC | | The temperature of the rectifier or power converter. INT16_MAX: field not provided. | +| generator_temperature | `int16` | degC | | The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided. | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------------------------------------------------- | -------- | ------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| STATUS_FLAG_OFF | `uint64` | 1 | Generator is off. | +| STATUS_FLAG_READY | `uint64` | 2 | Generator is ready to start generating power. | +| STATUS_FLAG_GENERATING | `uint64` | 4 | Generator is generating power. | +| STATUS_FLAG_CHARGING | `uint64` | 8 | Generator is charging the batteries (generating enough power to charge and provide the load). | +| STATUS_FLAG_REDUCED_POWER | `uint64` | 16 | Generator is operating at a reduced maximum power. | +| STATUS_FLAG_MAXPOWER | `uint64` | 32 | Generator is providing the maximum output. | +| STATUS_FLAG_OVERTEMP_WARNING | `uint64` | 64 | Generator is near the maximum operating temperature, cooling is insufficient. | +| STATUS_FLAG_OVERTEMP_FAULT | `uint64` | 128 | Generator hit the maximum operating temperature and shutdown. | +| STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING | `uint64` | 256 | Power electronics are near the maximum operating temperature, cooling is insufficient. | +| STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT | `uint64` | 512 | Power electronics hit the maximum operating temperature and shutdown. | +| STATUS_FLAG_ELECTRONICS_FAULT | `uint64` | 1024 | Power electronics experienced a fault and shutdown. | +| STATUS_FLAG_POWERSOURCE_FAULT | `uint64` | 2048 | The power source supplying the generator failed e.g. mechanical generator stopped, tether is no longer providing power, solar cell is in shade, hydrogen reaction no longer happening. | +| STATUS_FLAG_COMMUNICATION_WARNING | `uint64` | 4096 | Generator controller having communication problems. | +| STATUS_FLAG_COOLING_WARNING | `uint64` | 8192 | Power electronic or generator cooling system error. | +| STATUS_FLAG_POWER_RAIL_FAULT | `uint64` | 16384 | Generator controller power rail experienced a fault. | +| STATUS_FLAG_OVERCURRENT_FAULT | `uint64` | 32768 | Generator controller exceeded the overcurrent threshold and shutdown to prevent damage. | +| STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT | `uint64` | 65536 | Generator controller detected a high current going into the batteries and shutdown to prevent battery damage. | +| STATUS_FLAG_OVERVOLTAGE_FAULT | `uint64` | 131072 | Generator controller exceeded it's overvoltage threshold and shutdown to prevent it exceeding the voltage rating. | +| STATUS_FLAG_BATTERY_UNDERVOLT_FAULT | `uint64` | 262144 | Batteries are under voltage (generator will not start). | +| STATUS_FLAG_START_INHIBITED | `uint64` | 524288 | Generator start is inhibited by e.g. a safety switch. | +| STATUS_FLAG_MAINTENANCE_REQUIRED | `uint64` | 1048576 | Generator requires maintenance. | +| STATUS_FLAG_WARMING_UP | `uint64` | 2097152 | Generator is not ready to generate yet. | +| STATUS_FLAG_IDLE | `uint64` | 4194304 | Generator is idle. | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GeneratorStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -49,5 +102,6 @@ uint16 generator_speed # [rpm] Speed of electrical generator or alte int16 rectifier_temperature # [degC] The temperature of the rectifier or power converter. INT16_MAX: field not provided. int16 generator_temperature # [degC] The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided. - ``` + +::: diff --git a/docs/en/msg_docs/GeofenceResult.md b/docs/en/msg_docs/GeofenceResult.md index f54a2f9942..66fb6f97bd 100644 --- a/docs/en/msg_docs/GeofenceResult.md +++ b/docs/en/msg_docs/GeofenceResult.md @@ -1,8 +1,37 @@ +--- +pageClass: is-wide-page +--- + # GeofenceResult (UORB message) +**TOPICS:** geofence_result +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GeofenceResult.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------------------- | -------- | ------------ | ---------- | ---------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| geofence_max_dist_triggered | `bool` | | | true the check for max distance from Home is triggered | +| geofence_max_alt_triggered | `bool` | | | true the check for max altitude above Home is triggered | +| geofence_custom_fence_triggered | `bool` | | | true the check for custom inclusion/exclusion geofence(s) is triggered | +| geofence_action | `uint8` | | | action to take when the geofence is breached | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------------- | ------- | ----- | ------------------------------- | ------ | +| GF_ACTION_NONE | `uint8` | 0 | no action on geofence violation | +| GF_ACTION_WARN | `uint8` | 1 | critical mavlink message | +| GF_ACTION_LOITER | `uint8` | 2 | switch to AUTO | LOITER | +| GF_ACTION_RTL | `uint8` | 3 | switch to AUTO | RTL | +| GF_ACTION_TERMINATE | `uint8` | 4 | flight termination | +| GF_ACTION_LAND | `uint8` | 5 | switch to AUTO | LAND | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GeofenceResult.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -18,5 +47,6 @@ bool geofence_max_alt_triggered # true the check for max altitude above Home is bool geofence_custom_fence_triggered # true the check for custom inclusion/exclusion geofence(s) is triggered uint8 geofence_action # action to take when the geofence is breached - ``` + +::: diff --git a/docs/en/msg_docs/GeofenceStatus.md b/docs/en/msg_docs/GeofenceStatus.md index 298fd31ba6..6bde8a6566 100644 --- a/docs/en/msg_docs/GeofenceStatus.md +++ b/docs/en/msg_docs/GeofenceStatus.md @@ -1,8 +1,31 @@ +--- +pageClass: is-wide-page +--- + # GeofenceStatus (UORB message) +**TOPICS:** geofence_status +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GeofenceStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------- | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| geofence_id | `uint32` | | | loaded geofence id | +| status | `uint8` | | | Current geofence status | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------- | ------- | ----- | ----------- | +| GF_STATUS_LOADING | `uint8` | 0 | +| GF_STATUS_READY | `uint8` | 1 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GeofenceStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -12,5 +35,6 @@ uint8 status # Current geofence status uint8 GF_STATUS_LOADING = 0 uint8 GF_STATUS_READY = 1 - ``` + +::: diff --git a/docs/en/msg_docs/GimbalControls.md b/docs/en/msg_docs/GimbalControls.md index cde183d443..0f7c46bdc6 100644 --- a/docs/en/msg_docs/GimbalControls.md +++ b/docs/en/msg_docs/GimbalControls.md @@ -1,8 +1,32 @@ +--- +pageClass: is-wide-page +--- + # GimbalControls (UORB message) +**TOPICS:** gimbal_controls +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalControls.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ------------ | ------------ | ---------- | -------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp the data this control response is based on was sampled | +| control | `float32[3]` | | | Normalized output. 1 means maximum positive position. -1 maximum negative position. 0 means no deflection. NaN maps to disarmed. | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------- | ------- | ----- | ----------- | +| INDEX_ROLL | `uint8` | 0 | +| INDEX_PITCH | `uint8` | 1 | +| INDEX_YAW | `uint8` | 2 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalControls.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -11,6 +35,7 @@ uint8 INDEX_PITCH = 1 uint8 INDEX_YAW = 2 uint64 timestamp_sample # the timestamp the data this control response is based on was sampled -float32[3] control - +float32[3] control # Normalized output. 1 means maximum positive position. -1 maximum negative position. 0 means no deflection. NaN maps to disarmed. ``` + +::: diff --git a/docs/en/msg_docs/GimbalDeviceAttitudeStatus.md b/docs/en/msg_docs/GimbalDeviceAttitudeStatus.md index 0935029087..8d155b1cdd 100644 --- a/docs/en/msg_docs/GimbalDeviceAttitudeStatus.md +++ b/docs/en/msg_docs/GimbalDeviceAttitudeStatus.md @@ -1,6 +1,46 @@ +--- +pageClass: is-wide-page +--- + # GimbalDeviceAttitudeStatus (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalDeviceAttitudeStatus.msg) +**TOPICS:** gimbal_deviceattitude_status + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------------- | ------------ | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| target_system | `uint8` | | | +| target_component | `uint8` | | | +| device_flags | `uint16` | | | +| q | `float32[4]` | | | +| angular_velocity_x | `float32` | | | +| angular_velocity_y | `float32` | | | +| angular_velocity_z | `float32` | | | +| failure_flags | `uint32` | | | +| delta_yaw | `float32` | | | +| delta_yaw_velocity | `float32` | | | +| gimbal_device_id | `uint8` | | | +| received_from_mavlink | `bool` | | | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------------------- | -------- | ----- | ----------- | +| DEVICE_FLAGS_RETRACT | `uint16` | 1 | +| DEVICE_FLAGS_NEUTRAL | `uint16` | 2 | +| DEVICE_FLAGS_ROLL_LOCK | `uint16` | 4 | +| DEVICE_FLAGS_PITCH_LOCK | `uint16` | 8 | +| DEVICE_FLAGS_YAW_LOCK | `uint16` | 16 | +| DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME | `uint16` | 32 | +| DEVICE_FLAGS_YAW_IN_EARTH_FRAME | `uint16` | 64 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalDeviceAttitudeStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -29,5 +69,6 @@ float32 delta_yaw_velocity uint8 gimbal_device_id bool received_from_mavlink - ``` + +::: diff --git a/docs/en/msg_docs/GimbalDeviceInformation.md b/docs/en/msg_docs/GimbalDeviceInformation.md index fd727f4b86..e886ad892a 100644 --- a/docs/en/msg_docs/GimbalDeviceInformation.md +++ b/docs/en/msg_docs/GimbalDeviceInformation.md @@ -1,8 +1,54 @@ +--- +pageClass: is-wide-page +--- + # GimbalDeviceInformation (UORB message) +**TOPICS:** gimbal_deviceinformation +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalDeviceInformation.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ----------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| vendor_name | `uint8[32]` | | | +| model_name | `uint8[32]` | | | +| custom_name | `uint8[32]` | | | +| firmware_version | `uint32` | | | +| hardware_version | `uint32` | | | +| uid | `uint64` | | | +| cap_flags | `uint16` | | | +| custom_cap_flags | `uint16` | | | +| roll_min | `float32` | rad | | +| roll_max | `float32` | rad | | +| pitch_min | `float32` | rad | | +| pitch_max | `float32` | rad | | +| yaw_min | `float32` | rad | | +| yaw_max | `float32` | rad | | +| gimbal_device_id | `uint8` | | | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------------------------------------------- | -------- | ----- | ----------- | +| GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT | `uint32` | 1 | +| GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL | `uint32` | 2 | +| GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS | `uint32` | 4 | +| GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW | `uint32` | 8 | +| GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK | `uint32` | 16 | +| GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS | `uint32` | 32 | +| GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW | `uint32` | 64 | +| GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK | `uint32` | 128 | +| GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS | `uint32` | 256 | +| GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW | `uint32` | 512 | +| GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK | `uint32` | 1024 | +| GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW | `uint32` | 2048 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalDeviceInformation.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -41,5 +87,6 @@ float32 yaw_min # [rad] float32 yaw_max # [rad] uint8 gimbal_device_id - ``` + +::: diff --git a/docs/en/msg_docs/GimbalDeviceSetAttitude.md b/docs/en/msg_docs/GimbalDeviceSetAttitude.md index 9921536084..9b7ee4b8e5 100644 --- a/docs/en/msg_docs/GimbalDeviceSetAttitude.md +++ b/docs/en/msg_docs/GimbalDeviceSetAttitude.md @@ -1,8 +1,39 @@ +--- +pageClass: is-wide-page +--- + # GimbalDeviceSetAttitude (UORB message) +**TOPICS:** gimbal_deviceset_attitude +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalDeviceSetAttitude.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------ | ------------ | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| target_system | `uint8` | | | +| target_component | `uint8` | | | +| flags | `uint16` | | | +| q | `float32[4]` | | | +| angular_velocity_x | `float32` | | | +| angular_velocity_y | `float32` | | | +| angular_velocity_z | `float32` | | | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------------- | -------- | ----- | ----------- | +| GIMBAL_DEVICE_FLAGS_RETRACT | `uint32` | 1 | +| GIMBAL_DEVICE_FLAGS_NEUTRAL | `uint32` | 2 | +| GIMBAL_DEVICE_FLAGS_ROLL_LOCK | `uint32` | 4 | +| GIMBAL_DEVICE_FLAGS_PITCH_LOCK | `uint32` | 8 | +| GIMBAL_DEVICE_FLAGS_YAW_LOCK | `uint32` | 16 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalDeviceSetAttitude.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -22,5 +53,6 @@ float32[4] q float32 angular_velocity_x float32 angular_velocity_y float32 angular_velocity_z - ``` + +::: diff --git a/docs/en/msg_docs/GimbalManagerInformation.md b/docs/en/msg_docs/GimbalManagerInformation.md index ce60d2c5e0..6f0dafc790 100644 --- a/docs/en/msg_docs/GimbalManagerInformation.md +++ b/docs/en/msg_docs/GimbalManagerInformation.md @@ -1,8 +1,49 @@ +--- +pageClass: is-wide-page +--- + # GimbalManagerInformation (UORB message) +**TOPICS:** gimbal_managerinformation +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalManagerInformation.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | --------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| cap_flags | `uint32` | | | +| gimbal_device_id | `uint8` | | | +| roll_min | `float32` | rad | | +| roll_max | `float32` | rad | | +| pitch_min | `float32` | rad | | +| pitch_max | `float32` | rad | | +| yaw_min | `float32` | rad | | +| yaw_max | `float32` | rad | | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------------------------------------------------------------- | -------- | ------ | ----------- | +| GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT | `uint32` | 1 | +| GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL | `uint32` | 2 | +| GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS | `uint32` | 4 | +| GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW | `uint32` | 8 | +| GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK | `uint32` | 16 | +| GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS | `uint32` | 32 | +| GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW | `uint32` | 64 | +| GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK | `uint32` | 128 | +| GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS | `uint32` | 256 | +| GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW | `uint32` | 512 | +| GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK | `uint32` | 1024 | +| GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW | `uint32` | 2048 | +| GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL | `uint32` | 65536 | +| GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL | `uint32` | 131072 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalManagerInformation.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -34,5 +75,6 @@ float32 pitch_max # [rad] float32 yaw_min # [rad] float32 yaw_max # [rad] - ``` + +::: diff --git a/docs/en/msg_docs/GimbalManagerSetAttitude.md b/docs/en/msg_docs/GimbalManagerSetAttitude.md index 22c97eb74e..90690c07ee 100644 --- a/docs/en/msg_docs/GimbalManagerSetAttitude.md +++ b/docs/en/msg_docs/GimbalManagerSetAttitude.md @@ -1,8 +1,43 @@ +--- +pageClass: is-wide-page +--- + # GimbalManagerSetAttitude (UORB message) +**TOPICS:** gimbal_managerset_attitude +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalManagerSetAttitude.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------ | ------------ | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| origin_sysid | `uint8` | | | +| origin_compid | `uint8` | | | +| target_system | `uint8` | | | +| target_component | `uint8` | | | +| flags | `uint32` | | | +| gimbal_device_id | `uint8` | | | +| q | `float32[4]` | | | +| angular_velocity_x | `float32` | | | +| angular_velocity_y | `float32` | | | +| angular_velocity_z | `float32` | | | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------------------------------------- | -------- | ----- | ----------- | +| GIMBAL_MANAGER_FLAGS_RETRACT | `uint32` | 1 | +| GIMBAL_MANAGER_FLAGS_NEUTRAL | `uint32` | 2 | +| GIMBAL_MANAGER_FLAGS_ROLL_LOCK | `uint32` | 4 | +| GIMBAL_MANAGER_FLAGS_PITCH_LOCK | `uint32` | 8 | +| GIMBAL_MANAGER_FLAGS_YAW_LOCK | `uint32` | 16 | +| ORB_QUEUE_LENGTH | `uint8` | 2 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalManagerSetAttitude.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -29,5 +64,6 @@ float32 angular_velocity_y float32 angular_velocity_z uint8 ORB_QUEUE_LENGTH = 2 - ``` + +::: diff --git a/docs/en/msg_docs/GimbalManagerSetManualControl.md b/docs/en/msg_docs/GimbalManagerSetManualControl.md index c419917ba6..23efa6c4f4 100644 --- a/docs/en/msg_docs/GimbalManagerSetManualControl.md +++ b/docs/en/msg_docs/GimbalManagerSetManualControl.md @@ -1,8 +1,42 @@ +--- +pageClass: is-wide-page +--- + # GimbalManagerSetManualControl (UORB message) +**TOPICS:** gimbal_managerset_manualcontrol +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalManagerSetManualControl.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | --------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| origin_sysid | `uint8` | | | +| origin_compid | `uint8` | | | +| target_system | `uint8` | | | +| target_component | `uint8` | | | +| flags | `uint32` | | | +| gimbal_device_id | `uint8` | | | +| pitch | `float32` | | | unitless -1..1, can be NAN | +| yaw | `float32` | | | unitless -1..1, can be NAN | +| pitch_rate | `float32` | | | unitless -1..1, can be NAN | +| yaw_rate | `float32` | | | unitless -1..1, can be NAN | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------------------------------------- | -------- | ----- | ----------- | +| GIMBAL_MANAGER_FLAGS_RETRACT | `uint32` | 1 | +| GIMBAL_MANAGER_FLAGS_NEUTRAL | `uint32` | 2 | +| GIMBAL_MANAGER_FLAGS_ROLL_LOCK | `uint32` | 4 | +| GIMBAL_MANAGER_FLAGS_PITCH_LOCK | `uint32` | 8 | +| GIMBAL_MANAGER_FLAGS_YAW_LOCK | `uint32` | 16 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalManagerSetManualControl.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -26,5 +60,6 @@ float32 pitch # unitless -1..1, can be NAN float32 yaw # unitless -1..1, can be NAN float32 pitch_rate # unitless -1..1, can be NAN float32 yaw_rate # unitless -1..1, can be NAN - ``` + +::: diff --git a/docs/en/msg_docs/GimbalManagerStatus.md b/docs/en/msg_docs/GimbalManagerStatus.md index d0f741ad39..4773e15b50 100644 --- a/docs/en/msg_docs/GimbalManagerStatus.md +++ b/docs/en/msg_docs/GimbalManagerStatus.md @@ -1,8 +1,28 @@ +--- +pageClass: is-wide-page +--- + # GimbalManagerStatus (UORB message) +**TOPICS:** gimbal_managerstatus +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalManagerStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------------ | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| flags | `uint32` | | | +| gimbal_device_id | `uint8` | | | +| primary_control_sysid | `uint8` | | | +| primary_control_compid | `uint8` | | | +| secondary_control_sysid | `uint8` | | | +| secondary_control_compid | `uint8` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalManagerStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -13,5 +33,6 @@ uint8 primary_control_sysid uint8 primary_control_compid uint8 secondary_control_sysid uint8 secondary_control_compid - ``` + +::: diff --git a/docs/en/msg_docs/GotoSetpoint.md b/docs/en/msg_docs/GotoSetpoint.md index 746d15eb00..a656ab2dfc 100644 --- a/docs/en/msg_docs/GotoSetpoint.md +++ b/docs/en/msg_docs/GotoSetpoint.md @@ -1,13 +1,39 @@ +--- +pageClass: is-wide-page +--- + # GotoSetpoint (UORB message) -Position and (optional) heading setpoints with corresponding speed constraints -Setpoints are intended as inputs to position and heading smoothers, respectively -Setpoints do not need to be kinematically consistent -Optional heading setpoints may be specified as controlled by the respective flag -Unset optional setpoints are not controlled -Unset optional constraints default to vehicle specifications +Position and (optional) heading setpoints with corresponding speed constraints. Setpoints are intended as inputs to position and heading smoothers, respectively. Setpoints do not need to be kinematically consistent. Optional heading setpoints may be specified as controlled by the respective flag. Unset optional setpoints are not controlled. Unset optional constraints default to vehicle specifications. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/GotoSetpoint.msg) +**TOPICS:** goto_setpoint + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------------------- | ------------ | ------------ | ---------- | --------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| position | `float32[3]` | m | | NED local world frame | +| flag_control_heading | `bool` | | | true if heading is to be controlled | +| heading | `float32` | | | (optional) [rad] [-pi,pi] from North | +| flag_set_max_horizontal_speed | `bool` | | | true if setting a non-default horizontal speed limit | +| max_horizontal_speed | `float32` | | | (optional) [m/s] maximum speed (absolute) in the NE-plane | +| flag_set_max_vertical_speed | `bool` | | | true if setting a non-default vertical speed limit | +| max_vertical_speed | `float32` | | | (optional) [m/s] maximum speed (absolute) in the D-axis | +| flag_set_max_heading_rate | `bool` | | | true if setting a non-default heading rate limit | +| max_heading_rate | `float32` | | | (optional) [rad/s] maximum heading rate (absolute) | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/GotoSetpoint.msg) + +::: details Click here to see original file ```c # Position and (optional) heading setpoints with corresponding speed constraints @@ -36,5 +62,6 @@ float32 max_vertical_speed # (optional) [m/s] maximum speed (absolute) in the D- bool flag_set_max_heading_rate # true if setting a non-default heading rate limit float32 max_heading_rate # (optional) [rad/s] maximum heading rate (absolute) - ``` + +::: diff --git a/docs/en/msg_docs/GpioConfig.md b/docs/en/msg_docs/GpioConfig.md index 0d21b3ce66..f8b54041c1 100644 --- a/docs/en/msg_docs/GpioConfig.md +++ b/docs/en/msg_docs/GpioConfig.md @@ -1,8 +1,44 @@ +--- +pageClass: is-wide-page +--- + # GpioConfig (UORB message) -GPIO configuration +GPIO configuration. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GpioConfig.msg) +**TOPICS:** gpio_config + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| device_id | `uint32` | | | Device id | +| mask | `uint32` | | | Pin mask | +| state | `uint32` | | | Initial pin output state | +| config | `uint32` | | | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------- | -------- | ----- | ----------- | +| INPUT | `uint32` | 0 | 0x0000 | +| OUTPUT | `uint32` | 1 | 0x0001 | +| PULLUP | `uint32` | 16 | 0x0010 | +| PULLDOWN | `uint32` | 32 | 0x0020 | +| OPENDRAIN | `uint32` | 256 | 0x0100 | +| INPUT_FLOATING | `uint32` | 0 | 0x0000 | +| INPUT_PULLUP | `uint32` | 16 | 0x0010 | +| INPUT_PULLDOWN | `uint32` | 32 | 0x0020 | +| OUTPUT_PUSHPULL | `uint32` | 0 | 0x0000 | +| OUTPUT_OPENDRAIN | `uint32` | 256 | 0x0100 | +| OUTPUT_OPENDRAIN_PULLUP | `uint32` | 272 | 0x0110 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GpioConfig.msg) + +::: details Click here to see original file ```c # GPIO configuration @@ -33,5 +69,6 @@ uint32 OUTPUT_OPENDRAIN = 256 # 0x0100 uint32 OUTPUT_OPENDRAIN_PULLUP = 272 # 0x0110 uint32 config - ``` + +::: diff --git a/docs/en/msg_docs/GpioIn.md b/docs/en/msg_docs/GpioIn.md index 589e7d7841..f3af80cd4e 100644 --- a/docs/en/msg_docs/GpioIn.md +++ b/docs/en/msg_docs/GpioIn.md @@ -1,8 +1,32 @@ +--- +pageClass: is-wide-page +--- + # GpioIn (UORB message) -GPIO mask and state +GPIO mask and state. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GpioIn.msg) +**TOPICS:** gpio_in + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| device_id | `uint32` | | | Device id | +| state | `uint32` | | | pin state mask | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------- | ------- | ----- | ----------- | +| MAX_INSTANCES | `uint8` | 8 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GpioIn.msg) + +::: details Click here to see original file ```c # GPIO mask and state @@ -12,5 +36,6 @@ uint64 timestamp # time since system start (microseconds) uint32 device_id # Device id uint32 state # pin state mask - ``` + +::: diff --git a/docs/en/msg_docs/GpioOut.md b/docs/en/msg_docs/GpioOut.md index fd77f0be3b..fa554844be 100644 --- a/docs/en/msg_docs/GpioOut.md +++ b/docs/en/msg_docs/GpioOut.md @@ -1,8 +1,27 @@ +--- +pageClass: is-wide-page +--- + # GpioOut (UORB message) -GPIO mask and state +GPIO mask and state. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GpioOut.msg) +**TOPICS:** gpio_out + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| device_id | `uint32` | | | Device id | +| mask | `uint32` | | | pin mask | +| state | `uint32` | | | pin state mask | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GpioOut.msg) + +::: details Click here to see original file ```c # GPIO mask and state @@ -12,5 +31,6 @@ uint32 device_id # Device id uint32 mask # pin mask uint32 state # pin state mask - ``` + +::: diff --git a/docs/en/msg_docs/GpioRequest.md b/docs/en/msg_docs/GpioRequest.md index 027b84c685..676b46f79e 100644 --- a/docs/en/msg_docs/GpioRequest.md +++ b/docs/en/msg_docs/GpioRequest.md @@ -1,13 +1,31 @@ +--- +pageClass: is-wide-page +--- + # GpioRequest (UORB message) -Request GPIO mask to be read +Request GPIO mask to be read. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GpioRequest.msg) +**TOPICS:** gpio_request + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| device_id | `uint32` | | | Device id | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GpioRequest.msg) + +::: details Click here to see original file ```c # Request GPIO mask to be read uint64 timestamp # time since system start (microseconds) uint32 device_id # Device id - ``` + +::: diff --git a/docs/en/msg_docs/GpsDump.md b/docs/en/msg_docs/GpsDump.md index 03910da906..888a0a825f 100644 --- a/docs/en/msg_docs/GpsDump.md +++ b/docs/en/msg_docs/GpsDump.md @@ -1,8 +1,36 @@ +--- +pageClass: is-wide-page +--- + # GpsDump (UORB message) This message is used to dump the raw gps communication to the log. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GpsDump.msg) +**TOPICS:** gps_dump + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | ----------- | ------------ | ---------- | -------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| instance | `uint8` | | | Instance of GNSS receiver | +| device_id | `uint32` | | | +| len | `uint8` | | | length of data, MSB bit set = message to the gps device, | +| data | `uint8[79]` | | | data to write to the log | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------- | ------- | ----- | ----------- | +| INSTANCE_MAIN | `uint8` | 0 | +| INSTANCE_SECONDARY | `uint8` | 1 | +| ORB_QUEUE_LENGTH | `uint8` | 16 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GpsDump.msg) + +::: details Click here to see original file ```c # This message is used to dump the raw gps communication to the log. @@ -19,5 +47,6 @@ uint8 len # length of data, MSB bit set = message to the gps device, uint8[79] data # data to write to the log uint8 ORB_QUEUE_LENGTH = 16 - ``` + +::: diff --git a/docs/en/msg_docs/GpsInjectData.md b/docs/en/msg_docs/GpsInjectData.md index 0eefd1da40..62d3d356d0 100644 --- a/docs/en/msg_docs/GpsInjectData.md +++ b/docs/en/msg_docs/GpsInjectData.md @@ -1,8 +1,33 @@ +--- +pageClass: is-wide-page +--- + # GpsInjectData (UORB message) +**TOPICS:** gps_injectdata +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GpsInjectData.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | ------------ | ------------ | ---------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| len | `uint16` | | | length of data | +| flags | `uint8` | | | LSB: 1=fragmented | +| data | `uint8[300]` | | | data to write to GPS device (RTCM message) | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | ------- | ----- | ----------- | +| ORB_QUEUE_LENGTH | `uint8` | 8 | +| MAX_INSTANCES | `uint8` | 2 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GpsInjectData.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -16,5 +41,6 @@ uint8[300] data # data to write to GPS device (RTCM message) uint8 ORB_QUEUE_LENGTH = 8 uint8 MAX_INSTANCES = 2 - ``` + +::: diff --git a/docs/en/msg_docs/Gripper.md b/docs/en/msg_docs/Gripper.md index eb888e2017..8fcda0cacc 100644 --- a/docs/en/msg_docs/Gripper.md +++ b/docs/en/msg_docs/Gripper.md @@ -1,8 +1,32 @@ +--- +pageClass: is-wide-page +--- + # Gripper (UORB message) -# Used to command an actuation in the gripper, which is mapped to a specific output in the control allocation module +# Used to command an actuation in the gripper, which is mapped to a specific output in the control allocation module. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Gripper.msg) +**TOPICS:** gripper + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | -------- | ------------ | ---------- | ------------------------------- | +| timestamp | `uint64` | | | +| command | `int8` | | | Commanded state for the gripper | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | ------ | ----- | ----------- | +| COMMAND_GRAB | `int8` | 0 | +| COMMAND_RELEASE | `int8` | 1 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Gripper.msg) + +::: details Click here to see original file ```c ## Used to command an actuation in the gripper, which is mapped to a specific output in the control allocation module @@ -12,5 +36,6 @@ uint64 timestamp int8 command # Commanded state for the gripper int8 COMMAND_GRAB = 0 int8 COMMAND_RELEASE = 1 - ``` + +::: diff --git a/docs/en/msg_docs/HealthReport.md b/docs/en/msg_docs/HealthReport.md index 447d9da621..608fbecfc1 100644 --- a/docs/en/msg_docs/HealthReport.md +++ b/docs/en/msg_docs/HealthReport.md @@ -1,8 +1,29 @@ +--- +pageClass: is-wide-page +--- + # HealthReport (UORB message) +**TOPICS:** health_report +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/HealthReport.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------------- | -------- | ------------ | ---------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| can_arm_mode_flags | `uint64` | | | bitfield for each flight mode (NAVIGATION*STATE*\*) if arming is possible | +| can_run_mode_flags | `uint64` | | | bitfield for each flight mode if it can run | +| health_is_present_flags | `uint64` | | | flags for each health_component_t | +| health_warning_flags | `uint64` | | | +| health_error_flags | `uint64` | | | +| arming_check_warning_flags | `uint64` | | | +| arming_check_error_flags | `uint64` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/HealthReport.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -17,5 +38,6 @@ uint64 health_error_flags uint64 arming_check_warning_flags uint64 arming_check_error_flags - ``` + +::: diff --git a/docs/en/msg_docs/HeaterStatus.md b/docs/en/msg_docs/HeaterStatus.md index 3917f02428..431b621226 100644 --- a/docs/en/msg_docs/HeaterStatus.md +++ b/docs/en/msg_docs/HeaterStatus.md @@ -1,8 +1,40 @@ +--- +pageClass: is-wide-page +--- + # HeaterStatus (UORB message) +**TOPICS:** heater_status +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/HeaterStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------------- | --------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| device_id | `uint32` | | | +| heater_on | `bool` | | | +| temperature_target_met | `bool` | | | +| temperature_sensor | `float32` | | | +| temperature_target | `float32` | | | +| controller_period_usec | `uint32` | | | +| controller_time_on_usec | `uint32` | | | +| proportional_value | `float32` | | | +| integrator_value | `float32` | | | +| feed_forward_value | `float32` | | | +| mode | `uint8` | | | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------- | ------- | ----- | ----------- | +| MODE_GPIO | `uint8` | 1 | +| MODE_PX4IO | `uint8` | 2 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/HeaterStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -25,5 +57,6 @@ float32 feed_forward_value uint8 MODE_GPIO = 1 uint8 MODE_PX4IO = 2 uint8 mode - ``` + +::: diff --git a/docs/en/msg_docs/HomePosition.md b/docs/en/msg_docs/HomePosition.md index b48528de7e..ed5b43dc3c 100644 --- a/docs/en/msg_docs/HomePosition.md +++ b/docs/en/msg_docs/HomePosition.md @@ -1,8 +1,44 @@ +--- +pageClass: is-wide-page +--- + # HomePosition (UORB message) GPS home position in WGS84 coordinates. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/HomePosition.msg) +**TOPICS:** home_position + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------ | --------- | ------------ | ---------- | -------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| lat | `float64` | | | Latitude in degrees | +| lon | `float64` | | | Longitude in degrees | +| alt | `float32` | | | Altitude in meters (AMSL) | +| x | `float32` | | | X coordinate in meters | +| y | `float32` | | | Y coordinate in meters | +| z | `float32` | | | Z coordinate in meters | +| roll | `float32` | | | Pitch angle in radians | +| pitch | `float32` | | | Roll angle in radians | +| yaw | `float32` | | | Yaw angle in radians | +| valid_alt | `bool` | | | true when the altitude has been set | +| valid_hpos | `bool` | | | true when the latitude and longitude have been set | +| valid_lpos | `bool` | | | true when the local position (xyz) has been set | +| manual_home | `bool` | | | true when home position was set manually | +| update_count | `uint32` | | | update counter of the home position | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 1 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/HomePosition.msg) + +::: details Click here to see original file ```c # GPS home position in WGS84 coordinates. @@ -30,5 +66,6 @@ bool valid_lpos # true when the local position (xyz) has been set bool manual_home # true when home position was set manually uint32 update_count # update counter of the home position - ``` + +::: diff --git a/docs/en/msg_docs/HomePositionV0.md b/docs/en/msg_docs/HomePositionV0.md index 270d752337..c95ba3d44a 100644 --- a/docs/en/msg_docs/HomePositionV0.md +++ b/docs/en/msg_docs/HomePositionV0.md @@ -1,8 +1,42 @@ +--- +pageClass: is-wide-page +--- + # HomePositionV0 (UORB message) GPS home position in WGS84 coordinates. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/HomePositionV0.msg) +**TOPICS:** home_positionv0 + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------ | --------- | ------------ | ---------- | -------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| lat | `float64` | | | Latitude in degrees | +| lon | `float64` | | | Longitude in degrees | +| alt | `float32` | | | Altitude in meters (AMSL) | +| x | `float32` | | | X coordinate in meters | +| y | `float32` | | | Y coordinate in meters | +| z | `float32` | | | Z coordinate in meters | +| yaw | `float32` | | | Yaw angle in radians | +| valid_alt | `bool` | | | true when the altitude has been set | +| valid_hpos | `bool` | | | true when the latitude and longitude have been set | +| valid_lpos | `bool` | | | true when the local position (xyz) has been set | +| manual_home | `bool` | | | true when home position was set manually | +| update_count | `uint32` | | | update counter of the home position | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/HomePositionV0.msg) + +::: details Click here to see original file ```c # GPS home position in WGS84 coordinates. @@ -28,5 +62,6 @@ bool valid_lpos # true when the local position (xyz) has been set bool manual_home # true when home position was set manually uint32 update_count # update counter of the home position - ``` + +::: diff --git a/docs/en/msg_docs/HoverThrustEstimate.md b/docs/en/msg_docs/HoverThrustEstimate.md index 8c0aa1eb83..c892718d22 100644 --- a/docs/en/msg_docs/HoverThrustEstimate.md +++ b/docs/en/msg_docs/HoverThrustEstimate.md @@ -1,8 +1,30 @@ +--- +pageClass: is-wide-page +--- + # HoverThrustEstimate (UORB message) +**TOPICS:** hover_thrustestimate +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/HoverThrustEstimate.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------- | --------- | ------------ | ---------- | ----------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | time of corresponding sensor data last used for this estimate | +| hover_thrust | `float32` | | | estimated hover thrust [0.1, 0.9] | +| hover_thrust_var | `float32` | | | estimated hover thrust variance | +| accel_innov | `float32` | | | innovation of the last acceleration fusion | +| accel_innov_var | `float32` | | | innovation variance of the last acceleration fusion | +| accel_innov_test_ratio | `float32` | | | normalized innovation squared test ratio | +| accel_noise_var | `float32` | | | vertical acceleration noise variance estimated form innovation residual | +| valid | `bool` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/HoverThrustEstimate.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -18,5 +40,6 @@ float32 accel_innov_test_ratio # normalized innovation squared test ratio float32 accel_noise_var # vertical acceleration noise variance estimated form innovation residual bool valid - ``` + +::: diff --git a/docs/en/msg_docs/InputRc.md b/docs/en/msg_docs/InputRc.md index fbae6e0254..9ad672ebc8 100644 --- a/docs/en/msg_docs/InputRc.md +++ b/docs/en/msg_docs/InputRc.md @@ -1,6 +1,59 @@ +--- +pageClass: is-wide-page +--- + # InputRc (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/InputRc.msg) +**TOPICS:** input_rc + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------------- | ------------ | ------------ | ---------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_last_signal | `uint64` | | | last valid reception time | +| channel_count | `uint8` | | | number of channels actually being seen | +| rssi | `int32` | | | receive signal strength indicator (RSSI): < 0: Undefined, 0: no signal, 100: full reception | +| rc_failsafe | `bool` | | | explicit failsafe flag: true on TX failure or TX out of range , false otherwise. Only the true state is reliable, as there are some (PPM) receivers on the market going into failsafe without telling us explicitly. | +| rc_lost | `bool` | | | RC receiver connection status: True,if no frame has arrived in the expected time, false otherwise. True usually means that the receiver has been disconnected, but can also indicate a radio link loss on "stupid" systems. Will remain false, if a RX with failsafe option continues to transmit frames after a link loss. | +| rc_lost_frame_count | `uint16` | | | Number of lost RC frames. Note: intended purpose: observe the radio link quality if RSSI is not available. This value must not be used to trigger any failsafe-alike functionality. | +| rc_total_frame_count | `uint16` | | | Number of total RC frames. Note: intended purpose: observe the radio link quality if RSSI is not available. This value must not be used to trigger any failsafe-alike functionality. | +| rc_ppm_frame_length | `uint16` | | | Length of a single PPM frame. Zero for non-PPM systems | +| rc_frame_rate | `uint16` | | | RC frame rate in msg/second. 0 = invalid | +| input_source | `uint8` | | | Input source | +| values | `uint16[18]` | | | measured pulse widths for each of the supported channels | +| link_quality | `int8` | | | link quality. Percentage 0-100%. -1 = invalid | +| rssi_dbm | `float32` | | | Actual rssi in units of dBm. NaN = invalid | +| link_snr | `int8` | | | link signal to noise ratio in units of dB. -1 = invalid | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------------------------------------- | ------- | ----- | -------------------------------------------------------------------------------- | +| RC_INPUT_SOURCE_UNKNOWN | `uint8` | 0 | +| RC_INPUT_SOURCE_PX4FMU_PPM | `uint8` | 1 | +| RC_INPUT_SOURCE_PX4IO_PPM | `uint8` | 2 | +| RC_INPUT_SOURCE_PX4IO_SPEKTRUM | `uint8` | 3 | +| RC_INPUT_SOURCE_PX4IO_SBUS | `uint8` | 4 | +| RC_INPUT_SOURCE_PX4IO_ST24 | `uint8` | 5 | +| RC_INPUT_SOURCE_MAVLINK | `uint8` | 6 | +| RC_INPUT_SOURCE_QURT | `uint8` | 7 | +| RC_INPUT_SOURCE_PX4FMU_SPEKTRUM | `uint8` | 8 | +| RC_INPUT_SOURCE_PX4FMU_SBUS | `uint8` | 9 | +| RC_INPUT_SOURCE_PX4FMU_ST24 | `uint8` | 10 | +| RC_INPUT_SOURCE_PX4FMU_SUMD | `uint8` | 11 | +| RC_INPUT_SOURCE_PX4FMU_DSM | `uint8` | 12 | +| RC_INPUT_SOURCE_PX4IO_SUMD | `uint8` | 13 | +| RC_INPUT_SOURCE_PX4FMU_CRSF | `uint8` | 14 | +| RC_INPUT_SOURCE_PX4FMU_GHST | `uint8` | 15 | +| RC_INPUT_MAX_CHANNELS | `uint8` | 18 | Maximum number of R/C input channels in the system. S.Bus has up to 18 channels. | +| RSSI_MAX | `int8` | 100 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/InputRc.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -45,5 +98,6 @@ uint16[18] values # measured pulse widths for each of the supported channels int8 link_quality # link quality. Percentage 0-100%. -1 = invalid float32 rssi_dbm # Actual rssi in units of dBm. NaN = invalid int8 link_snr # link signal to noise ratio in units of dB. -1 = invalid - ``` + +::: diff --git a/docs/en/msg_docs/InternalCombustionEngineControl.md b/docs/en/msg_docs/InternalCombustionEngineControl.md index aacacd8973..02af18d879 100644 --- a/docs/en/msg_docs/InternalCombustionEngineControl.md +++ b/docs/en/msg_docs/InternalCombustionEngineControl.md @@ -1,6 +1,27 @@ +--- +pageClass: is-wide-page +--- + # InternalCombustionEngineControl (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/InternalCombustionEngineControl.msg) +**TOPICS:** internal_combustionengine_control + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------- | --------- | ------------ | ---------- | ----------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| ignition_on | `bool` | | | activate/deactivate ignition (spark plug) | +| throttle_control | `float32` | | | setpoint for throttle actuator, with slew rate if enabled, idles with 0 [norm] [@range 0,1] [@uncontrolled NAN to stop motor] | +| choke_control | `float32` | | | setpoint for choke actuator, 1: fully closed [norm] [@range 0,1] | +| starter_engine_control | `float32` | | | setpoint for (electric) starter motor [norm] [@range 0,1] | +| user_request | `uint8` | | | user intent for the ICE being on/off | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/InternalCombustionEngineControl.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -11,5 +32,6 @@ float32 choke_control # setpoint for choke actuator, 1: fully closed [norm] [@ float32 starter_engine_control # setpoint for (electric) starter motor [norm] [@range 0,1] uint8 user_request # user intent for the ICE being on/off - ``` + +::: diff --git a/docs/en/msg_docs/InternalCombustionEngineStatus.md b/docs/en/msg_docs/InternalCombustionEngineStatus.md index 32642ea23e..33f25cfb7a 100644 --- a/docs/en/msg_docs/InternalCombustionEngineStatus.md +++ b/docs/en/msg_docs/InternalCombustionEngineStatus.md @@ -1,8 +1,77 @@ +--- +pageClass: is-wide-page +--- + # InternalCombustionEngineStatus (UORB message) +**TOPICS:** internal_combustionengine_status +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/InternalCombustionEngineStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------------------- | --------- | ------------ | ---------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| state | `uint8` | | | +| flags | `uint32` | | | +| engine_load_percent | `uint8` | | | Engine load estimate, percent, [0, 127] | +| engine_speed_rpm | `uint32` | | | Engine speed, revolutions per minute | +| spark_dwell_time_ms | `float32` | | | Spark dwell time, millisecond | +| atmospheric_pressure_kpa | `float32` | | | Atmospheric (barometric) pressure, kilopascal | +| intake_manifold_pressure_kpa | `float32` | | | Engine intake manifold pressure, kilopascal | +| intake_manifold_temperature | `float32` | | | Engine intake manifold temperature, kelvin | +| coolant_temperature | `float32` | | | Engine coolant temperature, kelvin | +| oil_pressure | `float32` | | | Oil pressure, kilopascal | +| oil_temperature | `float32` | | | Oil temperature, kelvin | +| fuel_pressure | `float32` | | | Fuel pressure, kilopascal | +| fuel_consumption_rate_cm3pm | `float32` | | | Instant fuel consumption estimate, (centimeter^3)/minute | +| estimated_consumed_fuel_volume_cm3 | `float32` | | | Estimate of the consumed fuel since the start of the engine, centimeter^3 | +| throttle_position_percent | `uint8` | | | Throttle position, percent | +| ecu_index | `uint8` | | | The index of the publishing ECU | +| spark_plug_usage | `uint8` | | | Spark plug activity report. | +| ignition_timing_deg | `float32` | | | Cylinder ignition timing, angular degrees of the crankshaft | +| injection_time_ms | `float32` | | | Fuel injection time, millisecond | +| cylinder_head_temperature | `float32` | | | Cylinder head temperature (CHT), kelvin | +| exhaust_gas_temperature | `float32` | | | Exhaust gas temperature (EGT), kelvin | +| lambda_coefficient | `float32` | | | Estimated lambda coefficient, dimensionless ratio | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------------------------------------- | -------- | ------ | ------------------------------------------------------ | +| STATE_STOPPED | `uint8` | 0 | The engine is not running. This is the default state. | +| STATE_STARTING | `uint8` | 1 | The engine is starting. This is a transient state. | +| STATE_RUNNING | `uint8` | 2 | The engine is running normally. | +| STATE_FAULT | `uint8` | 3 | The engine can no longer function. | +| FLAG_GENERAL_ERROR | `uint32` | 1 | General error. | +| FLAG_CRANKSHAFT_SENSOR_ERROR_SUPPORTED | `uint32` | 2 | Error of the crankshaft sensor. This flag is optional. | +| FLAG_CRANKSHAFT_SENSOR_ERROR | `uint32` | 4 | +| FLAG_TEMPERATURE_SUPPORTED | `uint32` | 8 | Temperature levels. These flags are optional | +| FLAG_TEMPERATURE_BELOW_NOMINAL | `uint32` | 16 | Under-temperature warning | +| FLAG_TEMPERATURE_ABOVE_NOMINAL | `uint32` | 32 | Over-temperature warning | +| FLAG_TEMPERATURE_OVERHEATING | `uint32` | 64 | Critical overheating | +| FLAG_TEMPERATURE_EGT_ABOVE_NOMINAL | `uint32` | 128 | Exhaust gas over-temperature warning | +| FLAG_FUEL_PRESSURE_SUPPORTED | `uint32` | 256 | Fuel pressure. These flags are optional | +| FLAG_FUEL_PRESSURE_BELOW_NOMINAL | `uint32` | 512 | Under-pressure warning | +| FLAG_FUEL_PRESSURE_ABOVE_NOMINAL | `uint32` | 1024 | Over-pressure warning | +| FLAG_DETONATION_SUPPORTED | `uint32` | 2048 | Detonation warning. This flag is optional. | +| FLAG_DETONATION_OBSERVED | `uint32` | 4096 | Detonation condition observed warning | +| FLAG_MISFIRE_SUPPORTED | `uint32` | 8192 | Misfire warning. This flag is optional. | +| FLAG_MISFIRE_OBSERVED | `uint32` | 16384 | Misfire condition observed warning | +| FLAG_OIL_PRESSURE_SUPPORTED | `uint32` | 32768 | Oil pressure. These flags are optional | +| FLAG_OIL_PRESSURE_BELOW_NOMINAL | `uint32` | 65536 | Under-pressure warning | +| FLAG_OIL_PRESSURE_ABOVE_NOMINAL | `uint32` | 131072 | Over-pressure warning | +| FLAG_DEBRIS_SUPPORTED | `uint32` | 262144 | Debris warning. This flag is optional | +| FLAG_DEBRIS_DETECTED | `uint32` | 524288 | Detection of debris warning | +| SPARK_PLUG_SINGLE | `uint8` | 0 | +| SPARK_PLUG_FIRST_ACTIVE | `uint8` | 1 | +| SPARK_PLUG_SECOND_ACTIVE | `uint8` | 2 | +| SPARK_PLUG_BOTH_ACTIVE | `uint8` | 3 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/InternalCombustionEngineStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -69,5 +138,6 @@ float32 injection_time_ms # Fuel injection time, millisecond float32 cylinder_head_temperature # Cylinder head temperature (CHT), kelvin float32 exhaust_gas_temperature # Exhaust gas temperature (EGT), kelvin float32 lambda_coefficient # Estimated lambda coefficient, dimensionless ratio - ``` + +::: diff --git a/docs/en/msg_docs/IridiumsbdStatus.md b/docs/en/msg_docs/IridiumsbdStatus.md index f2b76adc24..02263b6922 100644 --- a/docs/en/msg_docs/IridiumsbdStatus.md +++ b/docs/en/msg_docs/IridiumsbdStatus.md @@ -1,8 +1,36 @@ +--- +pageClass: is-wide-page +--- + # IridiumsbdStatus (UORB message) +**TOPICS:** iridiumsbd_status +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/IridiumsbdStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------------- | -------- | ------------ | ---------- | ------------------------------------------------------------------------------------ | +| timestamp | `uint64` | | | time since system start (microseconds) | +| last_at_ok_timestamp | `uint64` | | | timestamp of the last "OK" received after the "AT" command | +| tx_buf_write_index | `uint16` | | | current size of the tx buffer | +| rx_buf_read_index | `uint16` | | | the rx buffer is parsed up to that index | +| rx_buf_end_index | `uint16` | | | current size of the rx buffer | +| failed_sbd_sessions | `uint16` | | | number of failed sbd sessions | +| successful_sbd_sessions | `uint16` | | | number of successful sbd sessions | +| num_tx_buf_reset | `uint16` | | | number of times the tx buffer was reset | +| signal_quality | `uint8` | | | current signal quality, 0 is no signal, 5 the best | +| state | `uint8` | | | current state of the driver, see the satcom_state of IridiumSBD.h for the definition | +| ring_pending | `bool` | | | indicates if a ring call is pending | +| tx_buf_write_pending | `bool` | | | indicates if a tx buffer write is pending | +| tx_session_pending | `bool` | | | indicates if a tx session is pending | +| rx_read_pending | `bool` | | | indicates if a rx read is pending | +| rx_session_pending | `bool` | | | indicates if a rx session is pending | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/IridiumsbdStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -20,5 +48,6 @@ bool tx_buf_write_pending # indicates if a tx buffer write is pending bool tx_session_pending # indicates if a tx session is pending bool rx_read_pending # indicates if a rx read is pending bool rx_session_pending # indicates if a rx session is pending - ``` + +::: diff --git a/docs/en/msg_docs/IrlockReport.md b/docs/en/msg_docs/IrlockReport.md index d850a0bb1e..fbe26d9649 100644 --- a/docs/en/msg_docs/IrlockReport.md +++ b/docs/en/msg_docs/IrlockReport.md @@ -1,8 +1,29 @@ +--- +pageClass: is-wide-page +--- + # IrlockReport (UORB message) -IRLOCK_REPORT message data +IRLOCK_REPORT message data. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/IrlockReport.msg) +**TOPICS:** irlock_report + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | --------- | ------------ | ---------- | ------------------------------------------------------------------------------------------------------------ | +| timestamp | `uint64` | | | time since system start (microseconds) | +| signature | `uint16` | | | +| pos_x | `float32` | | | tan(theta), where theta is the angle between the target and the camera center of projection in camera x-axis | +| pos_y | `float32` | | | tan(theta), where theta is the angle between the target and the camera center of projection in camera y-axis | +| size_x | `float32` | | | /** size of target along camera x-axis in units of tan(theta) **/ | +| size_y | `float32` | | | /** size of target along camera y-axis in units of tan(theta) **/ | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/IrlockReport.msg) + +::: details Click here to see original file ```c # IRLOCK_REPORT message data @@ -16,5 +37,6 @@ float32 pos_x # tan(theta), where theta is the angle between the target and the float32 pos_y # tan(theta), where theta is the angle between the target and the camera center of projection in camera y-axis float32 size_x #/** size of target along camera x-axis in units of tan(theta) **/ float32 size_y #/** size of target along camera y-axis in units of tan(theta) **/ - ``` + +::: diff --git a/docs/en/msg_docs/LandingGear.md b/docs/en/msg_docs/LandingGear.md index 89b79a8b2c..0abcc5b2b2 100644 --- a/docs/en/msg_docs/LandingGear.md +++ b/docs/en/msg_docs/LandingGear.md @@ -1,8 +1,31 @@ +--- +pageClass: is-wide-page +--- + # LandingGear (UORB message) +**TOPICS:** landing_gear +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LandingGear.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------ | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| landing_gear | `int8` | | | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------- | ------ | ----- | ---------------------- | +| GEAR_UP | `int8` | 1 | landing gear up | +| GEAR_DOWN | `int8` | -1 | landing gear down | +| GEAR_KEEP | `int8` | 0 | keep the current state | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LandingGear.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -12,5 +35,6 @@ int8 GEAR_DOWN = -1 # landing gear down int8 GEAR_KEEP = 0 # keep the current state int8 landing_gear - ``` + +::: diff --git a/docs/en/msg_docs/LandingGearWheel.md b/docs/en/msg_docs/LandingGearWheel.md index 1c04a448bd..d220ba4101 100644 --- a/docs/en/msg_docs/LandingGearWheel.md +++ b/docs/en/msg_docs/LandingGearWheel.md @@ -1,12 +1,28 @@ +--- +pageClass: is-wide-page +--- + # LandingGearWheel (UORB message) +**TOPICS:** landing_gearwheel +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LandingGearWheel.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------------- | --------- | ------------ | ---------- | -------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| normalized_wheel_setpoint | `float32` | | | negative is turning left, positive turning right [-1, 1] | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LandingGearWheel.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) float32 normalized_wheel_setpoint # negative is turning left, positive turning right [-1, 1] - ``` + +::: diff --git a/docs/en/msg_docs/LandingTargetInnovations.md b/docs/en/msg_docs/LandingTargetInnovations.md index 29bc06bbc2..0bf0dc7bc4 100644 --- a/docs/en/msg_docs/LandingTargetInnovations.md +++ b/docs/en/msg_docs/LandingTargetInnovations.md @@ -1,8 +1,26 @@ +--- +pageClass: is-wide-page +--- + # LandingTargetInnovations (UORB message) +**TOPICS:** landing_targetinnovations +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LandingTargetInnovations.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------- | --------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| innov_x | `float32` | | | +| innov_y | `float32` | | | +| innov_cov_x | `float32` | | | +| innov_cov_y | `float32` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LandingTargetInnovations.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -13,5 +31,6 @@ float32 innov_y # Innovation covariance of landing target position estimator float32 innov_cov_x float32 innov_cov_y - ``` + +::: diff --git a/docs/en/msg_docs/LandingTargetPose.md b/docs/en/msg_docs/LandingTargetPose.md index b4a76aeda7..e06e7157a3 100644 --- a/docs/en/msg_docs/LandingTargetPose.md +++ b/docs/en/msg_docs/LandingTargetPose.md @@ -1,8 +1,40 @@ +--- +pageClass: is-wide-page +--- + # LandingTargetPose (UORB message) -Relative position of precision land target in navigation (body fixed, north aligned, NED) and inertial (world fixed, north aligned, NED) frames +Relative position of precision land target in navigation (body fixed, north aligned, NED) and inertial (world fixed, north aligned, NED) frames. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LandingTargetPose.msg) +**TOPICS:** landing_targetpose + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------- | --------- | ------------ | ---------- | ----------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| is_static | `bool` | | | Flag indicating whether the landing target is static or moving with respect to the ground | +| rel_pos_valid | `bool` | | | Flag showing whether relative position is valid | +| rel_vel_valid | `bool` | | | Flag showing whether relative velocity is valid | +| x_rel | `float32` | | | X/north position of target, relative to vehicle (navigation frame) [meters] | +| y_rel | `float32` | | | Y/east position of target, relative to vehicle (navigation frame) [meters] | +| z_rel | `float32` | | | Z/down position of target, relative to vehicle (navigation frame) [meters] | +| vx_rel | `float32` | | | X/north velocity of target, relative to vehicle (navigation frame) [meters/second] | +| vy_rel | `float32` | | | Y/east velocity of target, relative to vehicle (navigation frame) [meters/second] | +| cov_x_rel | `float32` | | | X/north position variance [meters^2] | +| cov_y_rel | `float32` | | | Y/east position variance [meters^2] | +| cov_vx_rel | `float32` | | | X/north velocity variance [(meters/second)^2] | +| cov_vy_rel | `float32` | | | Y/east velocity variance [(meters/second)^2] | +| abs_pos_valid | `bool` | | | Flag showing whether absolute position is valid | +| x_abs | `float32` | | | X/north position of target, relative to origin (navigation frame) [meters] | +| y_abs | `float32` | | | Y/east position of target, relative to origin (navigation frame) [meters] | +| z_abs | `float32` | | | Z/down position of target, relative to origin (navigation frame) [meters] | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LandingTargetPose.msg) + +::: details Click here to see original file ```c # Relative position of precision land target in navigation (body fixed, north aligned, NED) and inertial (world fixed, north aligned, NED) frames @@ -31,5 +63,6 @@ bool abs_pos_valid # Flag showing whether absolute position is valid float32 x_abs # X/north position of target, relative to origin (navigation frame) [meters] float32 y_abs # Y/east position of target, relative to origin (navigation frame) [meters] float32 z_abs # Z/down position of target, relative to origin (navigation frame) [meters] - ``` + +::: diff --git a/docs/en/msg_docs/LateralControlConfiguration.md b/docs/en/msg_docs/LateralControlConfiguration.md index b0a03a6378..36f7724a09 100644 --- a/docs/en/msg_docs/LateralControlConfiguration.md +++ b/docs/en/msg_docs/LateralControlConfiguration.md @@ -1,9 +1,31 @@ +--- +pageClass: is-wide-page +--- + # LateralControlConfiguration (UORB message) -Fixed Wing Lateral Control Configuration message -Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages. +Fixed Wing Lateral Control Configuration message. Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/LateralControlConfiguration.msg) +**TOPICS:** lateral_controlconfiguration + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------- | --------- | ------------ | ---------- | ---------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| lateral_accel_max | `float32` | m/s^2 | | currently maps to a maximum roll angle, accel_max = tan(roll_max) \* GRAVITY | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/LateralControlConfiguration.msg) + +::: details Click here to see original file ```c # Fixed Wing Lateral Control Configuration message @@ -14,5 +36,6 @@ uint32 MESSAGE_VERSION = 0 uint64 timestamp # time since system start (microseconds) float32 lateral_accel_max # [m/s^2] currently maps to a maximum roll angle, accel_max = tan(roll_max) * GRAVITY - ``` + +::: diff --git a/docs/en/msg_docs/LaunchDetectionStatus.md b/docs/en/msg_docs/LaunchDetectionStatus.md index a85c63e4e8..49067ef229 100644 --- a/docs/en/msg_docs/LaunchDetectionStatus.md +++ b/docs/en/msg_docs/LaunchDetectionStatus.md @@ -1,8 +1,33 @@ +--- +pageClass: is-wide-page +--- + # LaunchDetectionStatus (UORB message) -Status of the launch detection state machine (fixed-wing only) +Status of the launch detection state machine (fixed-wing only). -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LaunchDetectionStatus.msg) +**TOPICS:** launch_detectionstatus + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------- | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| launch_detection_state | `uint8` | | | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------------------------- | ------- | ----- | ------------------------------------------------------------------------------------------------- | +| STATE_WAITING_FOR_LAUNCH | `uint8` | 0 | waiting for launch | +| STATE_LAUNCH_DETECTED_DISABLED_MOTOR | `uint8` | 1 | launch detected, but keep motor(s) disabled (e.g. because it can't spin freely while on catapult) | +| STATE_FLYING | `uint8` | 2 | launch detected, use normal takeoff/flying configuration | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LaunchDetectionStatus.msg) + +::: details Click here to see original file ```c # Status of the launch detection state machine (fixed-wing only) @@ -14,5 +39,6 @@ uint8 STATE_LAUNCH_DETECTED_DISABLED_MOTOR = 1 # launch detected, but keep moto uint8 STATE_FLYING = 2 # launch detected, use normal takeoff/flying configuration uint8 launch_detection_state - ``` + +::: diff --git a/docs/en/msg_docs/LedControl.md b/docs/en/msg_docs/LedControl.md index 69590eb8a5..0b066b2b90 100644 --- a/docs/en/msg_docs/LedControl.md +++ b/docs/en/msg_docs/LedControl.md @@ -1,9 +1,53 @@ +--- +pageClass: is-wide-page +--- + # LedControl (UORB message) -LED control: control a single or multiple LED's. -These are the externally visible LED's, not the board LED's +LED control: control a single or multiple LED's. These are the externally visible LED's, not the board LED's. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LedControl.msg) +**TOPICS:** led_control + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------- | -------- | ------------ | ---------- | --------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| led_mask | `uint8` | | | bitmask which LED(s) to control, set to 0xff for all | +| color | `uint8` | | | see COLOR\_\* | +| mode | `uint8` | | | see MODE\_\* | +| num_blinks | `uint8` | | | how many times to blink (number of on-off cycles if mode is one of MODE*BLINK*\*) . Set to 0 for infinite | +| priority | `uint8` | | | priority: higher priority events will override current lower priority events (see MAX_PRIORITY) | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------- | ------- | ----- | --------------------------------------------------------------------------------------- | +| COLOR_OFF | `uint8` | 0 | this is only used in the drivers | +| COLOR_RED | `uint8` | 1 | +| COLOR_GREEN | `uint8` | 2 | +| COLOR_BLUE | `uint8` | 3 | +| COLOR_YELLOW | `uint8` | 4 | +| COLOR_PURPLE | `uint8` | 5 | +| COLOR_AMBER | `uint8` | 6 | +| COLOR_CYAN | `uint8` | 7 | +| COLOR_WHITE | `uint8` | 8 | +| MODE_OFF | `uint8` | 0 | turn LED off | +| MODE_ON | `uint8` | 1 | turn LED on | +| MODE_DISABLED | `uint8` | 2 | disable this priority (switch to lower priority setting) | +| MODE_BLINK_SLOW | `uint8` | 3 | +| MODE_BLINK_NORMAL | `uint8` | 4 | +| MODE_BLINK_FAST | `uint8` | 5 | +| MODE_BREATHE | `uint8` | 6 | continuously increase & decrease brightness (solid color if driver does not support it) | +| MODE_FLASH | `uint8` | 7 | two fast blinks (on/off) with timing as in MODE_BLINK_FAST and then off for a while | +| MAX_PRIORITY | `uint8` | 2 | maximum priority (minimum is 0) | +| ORB_QUEUE_LENGTH | `uint8` | 8 | needs to match BOARD_MAX_LEDS | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LedControl.msg) + +::: details Click here to see original file ```c # LED control: control a single or multiple LED's. @@ -43,5 +87,6 @@ uint8 num_blinks # how many times to blink (number of on-off cycles if mode is o uint8 priority # priority: higher priority events will override current lower priority events (see MAX_PRIORITY) uint8 ORB_QUEUE_LENGTH = 8 # needs to match BOARD_MAX_LEDS - ``` + +::: diff --git a/docs/en/msg_docs/LogMessage.md b/docs/en/msg_docs/LogMessage.md index 5f640bae18..c9cd50cdb3 100644 --- a/docs/en/msg_docs/LogMessage.md +++ b/docs/en/msg_docs/LogMessage.md @@ -1,8 +1,32 @@ +--- +pageClass: is-wide-page +--- + # LogMessage (UORB message) -A logging message, output with PX4_WARN, PX4_ERR, PX4_INFO +A logging message, output with PX4_WARN, PX4_ERR, PX4_INFO. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LogMessage.msg) +**TOPICS:** log_message + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | ----------- | ------------ | ---------- | -------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| severity | `uint8` | | | log level (same as in the linux kernel, starting with 0) | +| text | `char[127]` | | | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | ------- | ----- | ----------- | +| ORB_QUEUE_LENGTH | `uint8` | 4 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LogMessage.msg) + +::: details Click here to see original file ```c # A logging message, output with PX4_WARN, PX4_ERR, PX4_INFO @@ -13,5 +37,6 @@ uint8 severity # log level (same as in the linux kernel, starting with 0) char[127] text uint8 ORB_QUEUE_LENGTH = 4 - ``` + +::: diff --git a/docs/en/msg_docs/LoggerStatus.md b/docs/en/msg_docs/LoggerStatus.md index 63ca114851..48d3a54b2e 100644 --- a/docs/en/msg_docs/LoggerStatus.md +++ b/docs/en/msg_docs/LoggerStatus.md @@ -1,8 +1,42 @@ +--- +pageClass: is-wide-page +--- + # LoggerStatus (UORB message) +**TOPICS:** logger_status +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LoggerStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------- | --------- | ------------ | ---------- | ----------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| type | `uint8` | | | +| backend | `uint8` | | | +| is_logging | `bool` | | | +| total_written_kb | `float32` | | | total written to log in kiloBytes | +| write_rate_kb_s | `float32` | | | write rate in kiloBytes/s | +| dropouts | `uint32` | | | number of failed buffer writes due to buffer overflow | +| message_gaps | `uint32` | | | messages misssed | +| buffer_used_bytes | `uint32` | | | current buffer fill in Bytes | +| buffer_size_bytes | `uint32` | | | total buffer size in Bytes | +| num_messages | `uint8` | | | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------------- | ------- | ----- | ----------------------------------------- | +| LOGGER_TYPE_FULL | `uint8` | 0 | Normal, full size log | +| LOGGER_TYPE_MISSION | `uint8` | 1 | reduced mission log (e.g. for geotagging) | +| BACKEND_FILE | `uint8` | 1 | +| BACKEND_MAVLINK | `uint8` | 2 | +| BACKEND_ALL | `uint8` | 3 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LoggerStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -28,5 +62,6 @@ uint32 buffer_used_bytes # current buffer fill in Bytes uint32 buffer_size_bytes # total buffer size in Bytes uint8 num_messages - ``` + +::: diff --git a/docs/en/msg_docs/LongitudinalControlConfiguration.md b/docs/en/msg_docs/LongitudinalControlConfiguration.md index 901d5c23bc..92d81b624c 100644 --- a/docs/en/msg_docs/LongitudinalControlConfiguration.md +++ b/docs/en/msg_docs/LongitudinalControlConfiguration.md @@ -1,10 +1,39 @@ +--- +pageClass: is-wide-page +--- + # LongitudinalControlConfiguration (UORB message) -Fixed Wing Longitudinal Control Configuration message -Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages -and configure the resultant setpoints. +Fixed Wing Longitudinal Control Configuration message. Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages. and configure the resultant setpoints. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/LongitudinalControlConfiguration.msg) +**TOPICS:** longitudinal_controlconfiguration + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------------------- | --------- | ------------ | ---------- | ------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| pitch_min | `float32` | rad | [-pi : pi] | defaults to FW_P_LIM_MIN if NAN. | +| pitch_max | `float32` | rad | [-pi : pi] | defaults to FW_P_LIM_MAX if NAN. | +| throttle_min | `float32` | norm | [0 : 1] | deaults to FW_THR_MIN if NAN. | +| throttle_max | `float32` | norm | [0 : 1] | defaults to FW_THR_MAX if NAN. | +| climb_rate_target | `float32` | m/s | | target climbrate to change altitude. Defaults to FW_T_CLIMB_MAX if NAN. Not used if height_rate is directly set in FixedWingLongitudinalSetpoint. | +| sink_rate_target | `float32` | m/s | | target sinkrate to change altitude. Defaults to FW_T_SINK_MAX if NAN. Not used if height_rate is directly set in FixedWingLongitudinalSetpoint. | +| speed_weight | `float32` | | [0 : 2] | , 0=pitch controls altitude only, 2=pitch controls airspeed only | +| enforce_low_height_condition | `bool` | boolean | | if true, the altitude controller is configured with an alternative timeconstant for tighter altitude tracking | +| disable_underspeed_protection | `bool` | boolean | | if true, underspeed handling is disabled in the altitude controller | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/LongitudinalControlConfiguration.msg) + +::: details Click here to see original file ```c # Fixed Wing Longitudinal Control Configuration message @@ -24,5 +53,6 @@ float32 sink_rate_target # [m/s] target sinkrate to change altitude. Defaults float32 speed_weight # [@range 0,2], 0=pitch controls altitude only, 2=pitch controls airspeed only bool enforce_low_height_condition # [boolean] if true, the altitude controller is configured with an alternative timeconstant for tighter altitude tracking bool disable_underspeed_protection # [boolean] if true, underspeed handling is disabled in the altitude controller - ``` + +::: diff --git a/docs/en/msg_docs/MagWorkerData.md b/docs/en/msg_docs/MagWorkerData.md index cb7103aaea..cd6d8964d9 100644 --- a/docs/en/msg_docs/MagWorkerData.md +++ b/docs/en/msg_docs/MagWorkerData.md @@ -1,8 +1,37 @@ +--- +pageClass: is-wide-page +--- + # MagWorkerData (UORB message) +**TOPICS:** mag_workerdata +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MagWorkerData.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------------------- | ------------ | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | +| done_count | `uint32` | | | +| calibration_points_perside | `uint32` | | | +| calibration_interval_perside_us | `uint64` | | | +| calibration_counter_total | `uint32[4]` | | | +| side_data_collected | `bool[4]` | | | +| x | `float32[4]` | | | +| y | `float32[4]` | | | +| z | `float32[4]` | | | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------- | ------- | ----- | ----------- | +| MAX_MAGS | `uint8` | 4 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MagWorkerData.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -18,5 +47,6 @@ bool[4] side_data_collected float32[4] x float32[4] y float32[4] z - ``` + +::: diff --git a/docs/en/msg_docs/MagnetometerBiasEstimate.md b/docs/en/msg_docs/MagnetometerBiasEstimate.md index 08f4011497..fafb6dc4df 100644 --- a/docs/en/msg_docs/MagnetometerBiasEstimate.md +++ b/docs/en/msg_docs/MagnetometerBiasEstimate.md @@ -1,8 +1,27 @@ +--- +pageClass: is-wide-page +--- + # MagnetometerBiasEstimate (UORB message) +**TOPICS:** magnetometer_biasestimate +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MagnetometerBiasEstimate.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | ------------ | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| bias_x | `float32[4]` | | | estimated X-bias of all the sensors | +| bias_y | `float32[4]` | | | estimated Y-bias of all the sensors | +| bias_z | `float32[4]` | | | estimated Z-bias of all the sensors | +| valid | `bool[4]` | | | true if the estimator has converged | +| stable | `bool[4]` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MagnetometerBiasEstimate.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -13,5 +32,6 @@ float32[4] bias_z # estimated Z-bias of all the sensors bool[4] valid # true if the estimator has converged bool[4] stable - ``` + +::: diff --git a/docs/en/msg_docs/ManualControlSetpoint.md b/docs/en/msg_docs/ManualControlSetpoint.md index a4f70d6738..5d85d3d27f 100644 --- a/docs/en/msg_docs/ManualControlSetpoint.md +++ b/docs/en/msg_docs/ManualControlSetpoint.md @@ -1,8 +1,52 @@ +--- +pageClass: is-wide-page +--- + # ManualControlSetpoint (UORB message) +**TOPICS:** manual_control_setpoint manual_control_input +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ManualControlSetpoint.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | --------- | ------------ | ---------- | ------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| valid | `bool` | | | +| data_source | `uint8` | | | +| roll | `float32` | | | move right, positive roll rotation, right side down | +| pitch | `float32` | | | move forward, negative pitch rotation, nose down | +| yaw | `float32` | | | positive yaw rotation, clockwise when seen top down | +| throttle | `float32` | | | move up, positive thrust, -1 is minimum available 0% or -100% +1 is 100% thrust | +| flaps | `float32` | | | position of flaps switch/knob/lever [-1, 1] | +| aux1 | `float32` | | | +| aux2 | `float32` | | | +| aux3 | `float32` | | | +| aux4 | `float32` | | | +| aux5 | `float32` | | | +| aux6 | `float32` | | | +| sticks_moving | `bool` | | | +| buttons | `uint16` | | | From uint16 buttons field of Mavlink manual_control message | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | -------- | ----- | ------------------------ | +| MESSAGE_VERSION | `uint32` | 0 | +| SOURCE_UNKNOWN | `uint8` | 0 | +| SOURCE_RC | `uint8` | 1 | radio control (input_rc) | +| SOURCE_MAVLINK_0 | `uint8` | 2 | mavlink instance 0 | +| SOURCE_MAVLINK_1 | `uint8` | 3 | mavlink instance 1 | +| SOURCE_MAVLINK_2 | `uint8` | 4 | mavlink instance 2 | +| SOURCE_MAVLINK_3 | `uint8` | 5 | mavlink instance 3 | +| SOURCE_MAVLINK_4 | `uint8` | 6 | mavlink instance 4 | +| SOURCE_MAVLINK_5 | `uint8` | 7 | mavlink instance 5 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ManualControlSetpoint.msg) + +::: details Click here to see original file ```c uint32 MESSAGE_VERSION = 0 @@ -53,5 +97,6 @@ uint16 buttons # From uint16 buttons field of Mavlink manual_control message # DEPRECATED: float32 y # DEPRECATED: float32 z # DEPRECATED: float32 r - ``` + +::: diff --git a/docs/en/msg_docs/ManualControlSwitches.md b/docs/en/msg_docs/ManualControlSwitches.md index 189682730f..9d2b661535 100644 --- a/docs/en/msg_docs/ManualControlSwitches.md +++ b/docs/en/msg_docs/ManualControlSwitches.md @@ -1,6 +1,54 @@ +--- +pageClass: is-wide-page +--- + # ManualControlSwitches (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ManualControlSwitches.msg) +**TOPICS:** manual_controlswitches + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------------ | -------- | ------------ | ---------- | ------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| mode_slot | `uint8` | | | the slot a specific model selector is in | +| arm_switch | `uint8` | | | arm/disarm switch: _DISARMED_, ARMED | +| return_switch | `uint8` | | | return to launch 2 position switch (mandatory): _NORMAL_, RTL | +| loiter_switch | `uint8` | | | loiter 2 position switch (optional): _MISSION_, LOITER | +| offboard_switch | `uint8` | | | offboard 2 position switch (optional): _NORMAL_, OFFBOARD | +| kill_switch | `uint8` | | | throttle kill: _NORMAL_, KILL | +| termination_switch | `uint8` | | | trigger termination which cannot be undone | +| gear_switch | `uint8` | | | landing gear switch: _DOWN_, UP | +| transition_switch | `uint8` | | | VTOL transition switch: \_HOVER, FORWARD_FLIGHT | +| photo_switch | `uint8` | | | Photo trigger switch | +| video_switch | `uint8` | | | Photo trigger switch | +| engage_main_motor_switch | `uint8` | | | Engage the main motor (for helicopters) | +| payload_power_switch | `uint8` | | | Payload power switch | +| switch_changes | `uint32` | | | number of switch changes | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------- | ------- | ----- | --------------------------------- | +| SWITCH_POS_NONE | `uint8` | 0 | switch is not mapped | +| SWITCH_POS_ON | `uint8` | 1 | switch activated (value = 1) | +| SWITCH_POS_MIDDLE | `uint8` | 2 | middle position (value = 0) | +| SWITCH_POS_OFF | `uint8` | 3 | switch not activated (value = -1) | +| MODE_SLOT_NONE | `uint8` | 0 | no mode slot assigned | +| MODE_SLOT_1 | `uint8` | 1 | mode slot 1 selected | +| MODE_SLOT_2 | `uint8` | 2 | mode slot 2 selected | +| MODE_SLOT_3 | `uint8` | 3 | mode slot 3 selected | +| MODE_SLOT_4 | `uint8` | 4 | mode slot 4 selected | +| MODE_SLOT_5 | `uint8` | 5 | mode slot 5 selected | +| MODE_SLOT_6 | `uint8` | 6 | mode slot 6 selected | +| MODE_SLOT_NUM | `uint8` | 6 | number of slots | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ManualControlSwitches.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -40,5 +88,6 @@ uint8 engage_main_motor_switch # Engage the main motor (for helicopters) uint8 payload_power_switch # Payload power switch uint32 switch_changes # number of switch changes - ``` + +::: diff --git a/docs/en/msg_docs/MavlinkLog.md b/docs/en/msg_docs/MavlinkLog.md index 91900aea1b..b95bdc65ff 100644 --- a/docs/en/msg_docs/MavlinkLog.md +++ b/docs/en/msg_docs/MavlinkLog.md @@ -1,8 +1,30 @@ +--- +pageClass: is-wide-page +--- + # MavlinkLog (UORB message) +**TOPICS:** mavlink_log +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MavlinkLog.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | ----------- | ------------ | ---------- | -------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| text | `char[127]` | | | +| severity | `uint8` | | | log level (same as in the linux kernel, starting with 0) | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | ------- | ----- | ----------- | +| ORB_QUEUE_LENGTH | `uint8` | 8 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MavlinkLog.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -11,5 +33,6 @@ char[127] text uint8 severity # log level (same as in the linux kernel, starting with 0) uint8 ORB_QUEUE_LENGTH = 8 - ``` + +::: diff --git a/docs/en/msg_docs/MavlinkTunnel.md b/docs/en/msg_docs/MavlinkTunnel.md index 8775e82ae4..ca6556b13b 100644 --- a/docs/en/msg_docs/MavlinkTunnel.md +++ b/docs/en/msg_docs/MavlinkTunnel.md @@ -1,8 +1,45 @@ +--- +pageClass: is-wide-page +--- + # MavlinkTunnel (UORB message) -MAV_TUNNEL_PAYLOAD_TYPE enum +MAV_TUNNEL_PAYLOAD_TYPE enum. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MavlinkTunnel.msg) +**TOPICS:** mavlink_tunnel esc_serial_passthru io_serial_passthru + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ------------ | ------------ | ---------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | Time since system start (microseconds) | +| payload_type | `uint16` | | | A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase. | +| target_system | `uint8` | | | System ID (can be 0 for broadcast, but this is discouraged) | +| target_component | `uint8` | | | Component ID (can be 0 for broadcast, but this is discouraged) | +| payload_length | `uint8` | | | Length of the data transported in payload | +| payload | `uint8[128]` | | | Data itself | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------------------------------------------- | ------- | ----- | ---------------------------------------- | +| MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN | `uint8` | 0 | Encoding of payload unknown | +| MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED0 | `uint8` | 200 | Registered for STorM32 gimbal controller | +| MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED1 | `uint8` | 201 | Registered for STorM32 gimbal controller | +| MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED2 | `uint8` | 202 | Registered for STorM32 gimbal controller | +| MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED3 | `uint8` | 203 | Registered for STorM32 gimbal controller | +| MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED4 | `uint8` | 204 | Registered for STorM32 gimbal controller | +| MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED5 | `uint8` | 205 | Registered for STorM32 gimbal controller | +| MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED6 | `uint8` | 206 | Registered for STorM32 gimbal controller | +| MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED7 | `uint8` | 207 | Registered for STorM32 gimbal controller | +| MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED8 | `uint8` | 208 | Registered for STorM32 gimbal controller | +| MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED9 | `uint8` | 209 | Registered for STorM32 gimbal controller | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MavlinkTunnel.msg) + +::: details Click here to see original file ```c # MAV_TUNNEL_PAYLOAD_TYPE enum @@ -27,6 +64,7 @@ uint8 payload_length # Length of the data transported in payload uint8[128] payload # Data itself # Topic aliases for known payload types -# TOPICS mavlink_tunnel esc_serial_passthru - +# TOPICS mavlink_tunnel esc_serial_passthru io_serial_passthru ``` + +::: diff --git a/docs/en/msg_docs/MessageFormatRequest.md b/docs/en/msg_docs/MessageFormatRequest.md index 7c4675e3f6..0f6acac371 100644 --- a/docs/en/msg_docs/MessageFormatRequest.md +++ b/docs/en/msg_docs/MessageFormatRequest.md @@ -1,8 +1,30 @@ +--- +pageClass: is-wide-page +--- + # MessageFormatRequest (UORB message) +**TOPICS:** message_formatrequest +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MessageFormatRequest.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ---------- | ------------ | ---------- | ---------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| protocol_version | `uint16` | | | Must be set to LATEST_PROTOCOL_VERSION. Do not change this field, it must be the first field after the timestamp | +| topic_name | `char[50]` | | | E.g. /fmu/in/vehicle_command | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------- | -------- | ----- | ------------------------------------------------------------------------------------------------------------------- | +| LATEST_PROTOCOL_VERSION | `uint16` | 1 | Current version of this protocol. Increase this whenever the MessageFormatRequest or MessageFormatResponse changes. | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MessageFormatRequest.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -14,5 +36,6 @@ uint16 LATEST_PROTOCOL_VERSION = 1 # Current version of this protocol. Increase uint16 protocol_version # Must be set to LATEST_PROTOCOL_VERSION. Do not change this field, it must be the first field after the timestamp char[50] topic_name # E.g. /fmu/in/vehicle_command - ``` + +::: diff --git a/docs/en/msg_docs/MessageFormatResponse.md b/docs/en/msg_docs/MessageFormatResponse.md index 3a537289a0..5e11481d34 100644 --- a/docs/en/msg_docs/MessageFormatResponse.md +++ b/docs/en/msg_docs/MessageFormatResponse.md @@ -1,8 +1,26 @@ +--- +pageClass: is-wide-page +--- + # MessageFormatResponse (UORB message) +**TOPICS:** message_formatresponse +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MessageFormatResponse.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ---------- | ------------ | ---------- | ---------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| protocol_version | `uint16` | | | Must be set to LATEST_PROTOCOL_VERSION. Do not change this field, it must be the first field after the timestamp | +| topic_name | `char[50]` | | | E.g. /fmu/in/vehicle_command | +| success | `bool` | | | +| message_hash | `uint32` | | | hash over all message fields | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MessageFormatResponse.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -15,5 +33,6 @@ char[50] topic_name # E.g. /fmu/in/vehicle_command bool success uint32 message_hash # hash over all message fields - ``` + +::: diff --git a/docs/en/msg_docs/Mission.md b/docs/en/msg_docs/Mission.md index 139b2e8914..69771d01c0 100644 --- a/docs/en/msg_docs/Mission.md +++ b/docs/en/msg_docs/Mission.md @@ -1,8 +1,32 @@ +--- +pageClass: is-wide-page +--- + # Mission (UORB message) +**TOPICS:** mission +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Mission.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------- | -------- | ------------ | ---------- | ----------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| mission_dataman_id | `uint8` | | | default 0, there are two offboard storage places in the dataman: 0 or 1 | +| fence_dataman_id | `uint8` | | | default 0, there are two offboard storage places in the dataman: 0 or 1 | +| safepoint_dataman_id | `uint8` | | | default 0, there are two offboard storage places in the dataman: 0 or 1 | +| count | `uint16` | | | count of the missions stored in the dataman | +| current_seq | `int32` | | | default -1, start at the one changed latest | +| land_start_index | `int32` | | | Index of the land start marker, if unavailable index of the land item, -1 otherwise | +| land_index | `int32` | | | Index of the land item, -1 otherwise | +| mission_id | `uint32` | | | indicates updates to the mission, reload from dataman if changed | +| geofence_id | `uint32` | | | indicates updates to the geofence, reload from dataman if changed | +| safe_points_id | `uint32` | | | indicates updates to the safe points, reload from dataman if changed | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Mission.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -19,5 +43,6 @@ int32 land_index # Index of the land item, -1 otherwise uint32 mission_id # indicates updates to the mission, reload from dataman if changed uint32 geofence_id # indicates updates to the geofence, reload from dataman if changed uint32 safe_points_id # indicates updates to the safe points, reload from dataman if changed - ``` + +::: diff --git a/docs/en/msg_docs/MissionResult.md b/docs/en/msg_docs/MissionResult.md index 325dc0e438..05be6aea8a 100644 --- a/docs/en/msg_docs/MissionResult.md +++ b/docs/en/msg_docs/MissionResult.md @@ -1,8 +1,36 @@ +--- +pageClass: is-wide-page +--- + # MissionResult (UORB message) +**TOPICS:** mission_result +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MissionResult.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------- | -------- | ------------ | ---------- | --------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| mission_id | `uint32` | | | Id for the mission for which the result was generated | +| geofence_id | `uint32` | | | Id for the corresponding geofence for which the result was generated (used for mission feasibility) | +| home_position_counter | `uint32` | | | Counter of the home position for which the result was generated (used for mission feasibility) | +| seq_reached | `int32` | | | Sequence of the mission item which has been reached, default -1 | +| seq_current | `uint16` | | | Sequence of the current mission item | +| seq_total | `uint16` | | | Total number of mission items | +| valid | `bool` | | | true if mission is valid | +| warning | `bool` | | | true if mission is valid, but has potentially problematic items leading to safety warnings | +| finished | `bool` | | | true if mission has been completed | +| failure | `bool` | | | true if the mission cannot continue or be completed for some reason | +| item_do_jump_changed | `bool` | | | true if the number of do jumps remaining has changed | +| item_changed_index | `uint16` | | | indicate which item has changed | +| item_do_jump_remaining | `uint16` | | | set to the number of do jumps remaining for that item | +| execution_mode | `uint8` | | | indicates the mode in which the mission is executed | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MissionResult.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -25,5 +53,6 @@ uint16 item_changed_index # indicate which item has changed uint16 item_do_jump_remaining # set to the number of do jumps remaining for that item uint8 execution_mode # indicates the mode in which the mission is executed - ``` + +::: diff --git a/docs/en/msg_docs/ModeCompleted.md b/docs/en/msg_docs/ModeCompleted.md index 76c0c297e6..2b223136fc 100644 --- a/docs/en/msg_docs/ModeCompleted.md +++ b/docs/en/msg_docs/ModeCompleted.md @@ -1,11 +1,34 @@ +--- +pageClass: is-wide-page +--- + # ModeCompleted (UORB message) -Mode completion result, published by an active mode. -The possible values of nav_state are defined in the VehicleStatus msg. -Note that this is not always published (e.g. when a user switches modes or on -failsafe activation) +Mode completion result, published by an active mode. The possible values of nav_state are defined in the VehicleStatus msg. Note that this is not always published (e.g. when a user switches modes or on. failsafe activation). -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ModeCompleted.msg) +**TOPICS:** mode_completed + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| result | `uint8` | | | One of RESULT\_\* | +| nav_state | `uint8` | | | Source mode (values in VehicleStatus) | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------- | -------- | ----- | --------------------------- | +| MESSAGE_VERSION | `uint32` | 0 | +| RESULT_SUCCESS | `uint8` | 0 | +| RESULT_FAILURE_OTHER | `uint8` | 100 | Mode failed (generic error) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ModeCompleted.msg) + +::: details Click here to see original file ```c # Mode completion result, published by an active mode. @@ -25,5 +48,6 @@ uint8 RESULT_FAILURE_OTHER = 100 # Mode failed (generic error) uint8 result # One of RESULT_* uint8 nav_state # Source mode (values in VehicleStatus) - ``` + +::: diff --git a/docs/en/msg_docs/MountOrientation.md b/docs/en/msg_docs/MountOrientation.md index dc676cb94b..1928e141cc 100644 --- a/docs/en/msg_docs/MountOrientation.md +++ b/docs/en/msg_docs/MountOrientation.md @@ -1,11 +1,27 @@ +--- +pageClass: is-wide-page +--- + # MountOrientation (UORB message) +**TOPICS:** mount_orientation +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MountOrientation.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------- | ------------ | ------------ | ---------- | ------------------------------------------------------ | +| timestamp | `uint64` | | | time since system start (microseconds) | +| attitude_euler_angle | `float32[3]` | | | Attitude/direction of the mount as euler angles in rad | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MountOrientation.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) float32[3] attitude_euler_angle # Attitude/direction of the mount as euler angles in rad - ``` + +::: diff --git a/docs/en/msg_docs/NavigatorMissionItem.md b/docs/en/msg_docs/NavigatorMissionItem.md index 3c3bc3f58c..92fab1ba15 100644 --- a/docs/en/msg_docs/NavigatorMissionItem.md +++ b/docs/en/msg_docs/NavigatorMissionItem.md @@ -1,8 +1,38 @@ +--- +pageClass: is-wide-page +--- + # NavigatorMissionItem (UORB message) +**TOPICS:** navigator_missionitem +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/NavigatorMissionItem.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------- | --------- | ------------ | ---------- | ------------------------------------------------------------------------------ | +| timestamp | `uint64` | | | time since system start (microseconds) | +| sequence_current | `uint16` | | | Sequence of the current mission item | +| nav_cmd | `uint16` | | | +| latitude | `float32` | | | +| longitude | `float32` | | | +| time_inside | `float32` | | | time that the MAV should stay inside the radius before advancing in seconds | +| acceptance_radius | `float32` | | | default radius in which the mission is accepted as reached in meters | +| loiter_radius | `float32` | | | loiter radius in meters, 0 for a VTOL to hover, negative for counter-clockwise | +| yaw | `float32` | | | in radians NED -PI..+PI, NAN means don't change yaw | +| altitude | `float32` | | | altitude in meters (AMSL) | +| frame | `uint8` | | | mission frame | +| origin | `uint8` | | | mission item origin (onboard or mavlink) | +| loiter_exit_xtrack | `bool` | | | exit xtrack location: 0 for center of loiter wp, 1 for exit location | +| force_heading | `bool` | | | heading needs to be reached | +| altitude_is_relative | `bool` | | | true if altitude is relative from start point | +| autocontinue | `bool` | | | true if next waypoint should follow after this one | +| vtol_back_transition | `bool` | | | part of the vtol back transition sequence | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/NavigatorMissionItem.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -28,5 +58,6 @@ bool force_heading # heading needs to be reached bool altitude_is_relative # true if altitude is relative from start point bool autocontinue # true if next waypoint should follow after this one bool vtol_back_transition # part of the vtol back transition sequence - ``` + +::: diff --git a/docs/en/msg_docs/NavigatorStatus.md b/docs/en/msg_docs/NavigatorStatus.md index 4eb53a56c8..18fe9235d4 100644 --- a/docs/en/msg_docs/NavigatorStatus.md +++ b/docs/en/msg_docs/NavigatorStatus.md @@ -1,9 +1,33 @@ +--- +pageClass: is-wide-page +--- + # NavigatorStatus (UORB message) -Current status of a Navigator mode -The possible values of nav_state are defined in the VehicleStatus msg. +Current status of a Navigator mode. The possible values of nav_state are defined in the VehicleStatus msg. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/NavigatorStatus.msg) +**TOPICS:** navigator_status + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| nav_state | `uint8` | | | Source mode (values in VehicleStatus) | +| failure | `uint8` | | | Navigator failure enum | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------- | ------- | ----- | --------------------------------------------------- | +| FAILURE_NONE | `uint8` | 0 | +| FAILURE_HAGL | `uint8` | 1 | Target altitude exceeds maximum height above ground | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/NavigatorStatus.msg) + +::: details Click here to see original file ```c # Current status of a Navigator mode @@ -15,5 +39,6 @@ uint8 failure # Navigator failure enum uint8 FAILURE_NONE = 0 uint8 FAILURE_HAGL = 1 # Target altitude exceeds maximum height above ground - ``` + +::: diff --git a/docs/en/msg_docs/NeuralControl.md b/docs/en/msg_docs/NeuralControl.md index 3e99004fbc..bb62fdb33b 100644 --- a/docs/en/msg_docs/NeuralControl.md +++ b/docs/en/msg_docs/NeuralControl.md @@ -1,12 +1,32 @@ +--- +pageClass: is-wide-page +--- + # NeuralControl (UORB message) -Neural control +Neural control. Debugging topic for the Neural controller, logs the inputs and output vectors of the neural network, and the time it takes to run Publisher: mc_nn_control Subscriber: logger -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/NeuralControl.msg) +**TOPICS:** neural_control + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------- | ------------- | ------------ | ---------- | ---------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| observation | `float32[15]` | | | Observation vector (pos error (3), att (6d), lin vel (3), ang vel (3)) | +| network_output | `float32[4]` | | | Output from neural network | +| controller_time | `int32` | us | | Time spent from input to output | +| inference_time | `int32` | us | | Time spent for NN inference | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/NeuralControl.msg) + +::: details Click here to see original file ```c # Neural control @@ -22,5 +42,6 @@ float32[4] network_output # Output from neural network int32 controller_time # [us] Time spent from input to output int32 inference_time # [us] Time spent for NN inference - ``` + +::: diff --git a/docs/en/msg_docs/NormalizedUnsignedSetpoint.md b/docs/en/msg_docs/NormalizedUnsignedSetpoint.md index 025a5fae76..521881a0a9 100644 --- a/docs/en/msg_docs/NormalizedUnsignedSetpoint.md +++ b/docs/en/msg_docs/NormalizedUnsignedSetpoint.md @@ -1,8 +1,23 @@ +--- +pageClass: is-wide-page +--- + # NormalizedUnsignedSetpoint (UORB message) +**TOPICS:** flaps_setpoint spoilers_setpoint +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------- | --------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| normalized_setpoint | `float32` | 0, 1 | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -10,5 +25,6 @@ uint64 timestamp # time since system start (microseconds) float32 normalized_setpoint # [0, 1] # TOPICS flaps_setpoint spoilers_setpoint - ``` + +::: diff --git a/docs/en/msg_docs/ObstacleDistance.md b/docs/en/msg_docs/ObstacleDistance.md index 622ba0a2ba..59b6eef1e6 100644 --- a/docs/en/msg_docs/ObstacleDistance.md +++ b/docs/en/msg_docs/ObstacleDistance.md @@ -1,8 +1,43 @@ +--- +pageClass: is-wide-page +--- + # ObstacleDistance (UORB message) Obstacle distances in front of the sensor. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg) +**TOPICS:** obstacle_distance obstacle_distance_fused + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------ | ------------ | ------------ | ---------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| frame | `uint8` | | | Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is North aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned. | +| sensor_type | `uint8` | | | Type from MAV_DISTANCE_SENSOR enum. | +| distances | `uint16[72]` | | | Distance of obstacles around the UAV with index 0 corresponding to local North. A value of 0 means that the obstacle is right in front of the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm. | +| increment | `float32` | | | Angular width in degrees of each array element. | +| min_distance | `uint16` | | | Minimum distance the sensor can measure in centimeters. | +| max_distance | `uint16` | | | Maximum distance the sensor can measure in centimeters. | +| angle_offset | `float32` | | | Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise. | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------------- | ------- | ----- | ----------- | +| MAV_FRAME_GLOBAL | `uint8` | 0 | +| MAV_FRAME_LOCAL_NED | `uint8` | 1 | +| MAV_FRAME_BODY_FRD | `uint8` | 12 | +| MAV_DISTANCE_SENSOR_LASER | `uint8` | 0 | +| MAV_DISTANCE_SENSOR_ULTRASOUND | `uint8` | 1 | +| MAV_DISTANCE_SENSOR_INFRARED | `uint8` | 2 | +| MAV_DISTANCE_SENSOR_RADAR | `uint8` | 3 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg) + +::: details Click here to see original file ```c # Obstacle distances in front of the sensor. @@ -29,5 +64,6 @@ uint16 max_distance # Maximum distance the sensor can measure in centimeters. float32 angle_offset # Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise. # TOPICS obstacle_distance obstacle_distance_fused - ``` + +::: diff --git a/docs/en/msg_docs/OffboardControlMode.md b/docs/en/msg_docs/OffboardControlMode.md index 4499912d95..16bcb63ebf 100644 --- a/docs/en/msg_docs/OffboardControlMode.md +++ b/docs/en/msg_docs/OffboardControlMode.md @@ -1,8 +1,31 @@ +--- +pageClass: is-wide-page +--- + # OffboardControlMode (UORB message) -Off-board control mode +Off-board control mode. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OffboardControlMode.msg) +**TOPICS:** offboard_controlmode + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------- | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| position | `bool` | | | +| velocity | `bool` | | | +| acceleration | `bool` | | | +| attitude | `bool` | | | +| body_rate | `bool` | | | +| thrust_and_torque | `bool` | | | +| direct_actuator | `bool` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OffboardControlMode.msg) + +::: details Click here to see original file ```c # Off-board control mode @@ -16,5 +39,6 @@ bool attitude bool body_rate bool thrust_and_torque bool direct_actuator - ``` + +::: diff --git a/docs/en/msg_docs/OnboardComputerStatus.md b/docs/en/msg_docs/OnboardComputerStatus.md index fc60e6f789..73aa9f30cf 100644 --- a/docs/en/msg_docs/OnboardComputerStatus.md +++ b/docs/en/msg_docs/OnboardComputerStatus.md @@ -1,8 +1,43 @@ +--- +pageClass: is-wide-page +--- + # OnboardComputerStatus (UORB message) -ONBOARD_COMPUTER_STATUS message data +ONBOARD_COMPUTER_STATUS message data. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OnboardComputerStatus.msg) +**TOPICS:** onboard_computerstatus + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------- | ----------- | ------------ | ---------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | time since system start (microseconds) | +| uptime | `uint32` | ms | | time since system boot of the companion (milliseconds) | +| type | `uint8` | | | type of onboard computer 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers. | +| cpu_cores | `uint8[8]` | | | CPU usage on the component in percent | +| cpu_combined | `uint8[10]` | | | Combined CPU usage as the last 10 slices of 100 MS | +| gpu_cores | `uint8[4]` | | | GPU usage on the component in percent | +| gpu_combined | `uint8[10]` | | | Combined GPU usage as the last 10 slices of 100 MS | +| temperature_board | `int8` | degC | | Temperature of the board | +| temperature_core | `int8[8]` | degC | | Temperature of the CPU core | +| fan_speed | `int16[4]` | rpm | | Fan speeds | +| ram_usage | `uint32` | MB | | Amount of used RAM on the component system | +| ram_total | `uint32` | MB | | Total amount of RAM on the component system | +| storage_type | `uint32[4]` | | | Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable) | +| storage_usage | `uint32[4]` | MB | | Amount of used storage space on the component system | +| storage_total | `uint32[4]` | MB | | Total amount of storage space on the component system | +| link_type | `uint32[6]` | Kb/s | | Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary | +| link_tx_rate | `uint32[6]` | Kb/s | | Network traffic from the component system | +| link_rx_rate | `uint32[6]` | Kb/s | | Network traffic to the component system | +| link_tx_max | `uint32[6]` | Kb/s | | Network capacity from the component system | +| link_rx_max | `uint32[6]` | Kb/s | | Network capacity to the component system | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OnboardComputerStatus.msg) + +::: details Click here to see original file ```c # ONBOARD_COMPUTER_STATUS message data @@ -28,5 +63,6 @@ uint32[6] link_tx_rate # [Kb/s] Network traffic from the component system uint32[6] link_rx_rate # [Kb/s] Network traffic to the component system uint32[6] link_tx_max # [Kb/s] Network capacity from the component system uint32[6] link_rx_max # [Kb/s] Network capacity to the component system - ``` + +::: diff --git a/docs/en/msg_docs/OpenDroneIdArmStatus.md b/docs/en/msg_docs/OpenDroneIdArmStatus.md index 78c7992a11..ba5fceb5b6 100644 --- a/docs/en/msg_docs/OpenDroneIdArmStatus.md +++ b/docs/en/msg_docs/OpenDroneIdArmStatus.md @@ -1,12 +1,29 @@ +--- +pageClass: is-wide-page +--- + # OpenDroneIdArmStatus (UORB message) +**TOPICS:** open_droneid_armstatus +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OpenDroneIdArmStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | ---------- | ------------ | ---------- | ----------- | +| timestamp | `uint64` | | | +| status | `uint8` | | | +| error | `char[50]` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OpenDroneIdArmStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp uint8 status char[50] error - ``` + +::: diff --git a/docs/en/msg_docs/OpenDroneIdOperatorId.md b/docs/en/msg_docs/OpenDroneIdOperatorId.md index e30192ea97..2e3b5fb3e1 100644 --- a/docs/en/msg_docs/OpenDroneIdOperatorId.md +++ b/docs/en/msg_docs/OpenDroneIdOperatorId.md @@ -1,13 +1,31 @@ +--- +pageClass: is-wide-page +--- + # OpenDroneIdOperatorId (UORB message) +**TOPICS:** open_droneid_operatorid +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OpenDroneIdOperatorId.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ----------- | ------------ | ---------- | ----------- | +| timestamp | `uint64` | | | +| id_or_mac | `uint8[20]` | | | +| operator_id_type | `uint8` | | | +| operator_id | `char[20]` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OpenDroneIdOperatorId.msg) + +::: details Click here to see original file ```c uint64 timestamp uint8[20] id_or_mac uint8 operator_id_type char[20] operator_id - ``` + +::: diff --git a/docs/en/msg_docs/OpenDroneIdSelfId.md b/docs/en/msg_docs/OpenDroneIdSelfId.md index e14e7746f4..d6fa45edce 100644 --- a/docs/en/msg_docs/OpenDroneIdSelfId.md +++ b/docs/en/msg_docs/OpenDroneIdSelfId.md @@ -1,13 +1,31 @@ +--- +pageClass: is-wide-page +--- + # OpenDroneIdSelfId (UORB message) +**TOPICS:** open_droneid_selfid +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OpenDroneIdSelfId.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ----------- | ------------ | ---------- | ----------- | +| timestamp | `uint64` | | | +| id_or_mac | `uint8[20]` | | | +| description_type | `uint8` | | | +| description | `char[23]` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OpenDroneIdSelfId.msg) + +::: details Click here to see original file ```c uint64 timestamp uint8[20] id_or_mac uint8 description_type char[23] description - ``` + +::: diff --git a/docs/en/msg_docs/OpenDroneIdSystem.md b/docs/en/msg_docs/OpenDroneIdSystem.md index 2fb1943c79..702221d403 100644 --- a/docs/en/msg_docs/OpenDroneIdSystem.md +++ b/docs/en/msg_docs/OpenDroneIdSystem.md @@ -1,8 +1,34 @@ +--- +pageClass: is-wide-page +--- + # OpenDroneIdSystem (UORB message) +**TOPICS:** open_droneid_system +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OpenDroneIdSystem.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------- | ----------- | ------------ | ---------- | ----------- | +| timestamp | `uint64` | | | +| id_or_mac | `uint8[20]` | | | +| operator_location_type | `uint8` | | | +| classification_type | `uint8` | | | +| operator_latitude | `int32` | | | +| operator_longitude | `int32` | | | +| area_count | `uint16` | | | +| area_radius | `uint16` | | | +| area_ceiling | `float32` | | | +| area_floor | `float32` | | | +| category_eu | `uint8` | | | +| class_eu | `uint8` | | | +| operator_altitude_geo | `float32` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OpenDroneIdSystem.msg) + +::: details Click here to see original file ```c uint64 timestamp @@ -18,5 +44,6 @@ float32 area_floor uint8 category_eu uint8 class_eu float32 operator_altitude_geo - ``` + +::: diff --git a/docs/en/msg_docs/OrbTest.md b/docs/en/msg_docs/OrbTest.md index d833eb9ba3..5e6ea41cc9 100644 --- a/docs/en/msg_docs/OrbTest.md +++ b/docs/en/msg_docs/OrbTest.md @@ -1,8 +1,23 @@ +--- +pageClass: is-wide-page +--- + # OrbTest (UORB message) +**TOPICS:** orb_test orb_multitest +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OrbTest.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| val | `int32` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OrbTest.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -10,5 +25,6 @@ uint64 timestamp # time since system start (microseconds) int32 val # TOPICS orb_test orb_multitest - ``` + +::: diff --git a/docs/en/msg_docs/OrbTestLarge.md b/docs/en/msg_docs/OrbTestLarge.md index 8fb96f757f..b78f964662 100644 --- a/docs/en/msg_docs/OrbTestLarge.md +++ b/docs/en/msg_docs/OrbTestLarge.md @@ -1,8 +1,24 @@ +--- +pageClass: is-wide-page +--- + # OrbTestLarge (UORB message) +**TOPICS:** orb_testlarge +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OrbTestLarge.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | ------------ | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| val | `int32` | | | +| junk | `uint8[512]` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OrbTestLarge.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -10,5 +26,6 @@ uint64 timestamp # time since system start (microseconds) int32 val uint8[512] junk - ``` + +::: diff --git a/docs/en/msg_docs/OrbTestMedium.md b/docs/en/msg_docs/OrbTestMedium.md index a5484401c7..52d8736a09 100644 --- a/docs/en/msg_docs/OrbTestMedium.md +++ b/docs/en/msg_docs/OrbTestMedium.md @@ -1,8 +1,30 @@ +--- +pageClass: is-wide-page +--- + # OrbTestMedium (UORB message) +**TOPICS:** orb_test_medium orb_test_medium_multi orb_test_medium_wrap_around orb_test_medium_queue orb_test_medium_queue_poll +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OrbTestMedium.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | ----------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| val | `int32` | | | +| junk | `uint8[64]` | | | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | ------- | ----- | ----------- | +| ORB_QUEUE_LENGTH | `uint8` | 16 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OrbTestMedium.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -14,5 +36,6 @@ uint8[64] junk uint8 ORB_QUEUE_LENGTH = 16 # TOPICS orb_test_medium orb_test_medium_multi orb_test_medium_wrap_around orb_test_medium_queue orb_test_medium_queue_poll - ``` + +::: diff --git a/docs/en/msg_docs/OrbitStatus.md b/docs/en/msg_docs/OrbitStatus.md index 2cbeeec36b..79f8cdd6f4 100644 --- a/docs/en/msg_docs/OrbitStatus.md +++ b/docs/en/msg_docs/OrbitStatus.md @@ -1,8 +1,41 @@ +--- +pageClass: is-wide-page +--- + # OrbitStatus (UORB message) -ORBIT_YAW_BEHAVIOUR +ORBIT_YAW_BEHAVIOUR. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OrbitStatus.msg) +**TOPICS:** orbit_status + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------- | --------- | ------------ | ---------- | ----------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| radius | `float32` | | | Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise. [m] | +| frame | `uint8` | | | The coordinate system of the fields: x, y, z. | +| x | `float64` | | | X coordinate of center point. Coordinate system depends on frame field: local = x position in meters _ 1e4, global = latitude in degrees _ 1e7. | +| y | `float64` | | | Y coordinate of center point. Coordinate system depends on frame field: local = y position in meters _ 1e4, global = latitude in degrees _ 1e7. | +| z | `float32` | | | Altitude of center point. Coordinate system depends on frame field. | +| yaw_behaviour | `uint8` | | | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------------------------------------------------- | ------- | ----- | ----------- | +| ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER | `uint8` | 0 | +| ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING | `uint8` | 1 | +| ORBIT_YAW_BEHAVIOUR_UNCONTROLLED | `uint8` | 2 | +| ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE | `uint8` | 3 | +| ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED | `uint8` | 4 | +| ORBIT_YAW_BEHAVIOUR_UNCHANGED | `uint8` | 5 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OrbitStatus.msg) + +::: details Click here to see original file ```c # ORBIT_YAW_BEHAVIOUR @@ -20,5 +53,6 @@ float64 x # X coordinate of center point. Coordinate system depends on fr float64 y # Y coordinate of center point. Coordinate system depends on frame field: local = y position in meters * 1e4, global = latitude in degrees * 1e7. float32 z # Altitude of center point. Coordinate system depends on frame field. uint8 yaw_behaviour - ``` + +::: diff --git a/docs/en/msg_docs/ParameterResetRequest.md b/docs/en/msg_docs/ParameterResetRequest.md index 3c776a0faf..b0c92c37db 100644 --- a/docs/en/msg_docs/ParameterResetRequest.md +++ b/docs/en/msg_docs/ParameterResetRequest.md @@ -1,8 +1,32 @@ +--- +pageClass: is-wide-page +--- + # ParameterResetRequest (UORB message) -ParameterResetRequest : Used by the primary to reset one or all parameter value(s) on the remote +ParameterResetRequest : Used by the primary to reset one or all parameter value(s) on the remote. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ParameterResetRequest.msg) +**TOPICS:** parameter_resetrequest + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------- | -------- | ------------ | ---------- | ------------------------------------------- | +| timestamp | `uint64` | | | +| parameter_index | `uint16` | | | +| reset_all | `bool` | | | If this is true then ignore parameter_index | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | ------- | ----- | ----------- | +| ORB_QUEUE_LENGTH | `uint8` | 4 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ParameterResetRequest.msg) + +::: details Click here to see original file ```c # ParameterResetRequest : Used by the primary to reset one or all parameter value(s) on the remote @@ -13,5 +37,6 @@ uint16 parameter_index bool reset_all # If this is true then ignore parameter_index uint8 ORB_QUEUE_LENGTH = 4 - ``` + +::: diff --git a/docs/en/msg_docs/ParameterSetUsedRequest.md b/docs/en/msg_docs/ParameterSetUsedRequest.md index 14684c0eed..c2afd68aa0 100644 --- a/docs/en/msg_docs/ParameterSetUsedRequest.md +++ b/docs/en/msg_docs/ParameterSetUsedRequest.md @@ -1,8 +1,31 @@ +--- +pageClass: is-wide-page +--- + # ParameterSetUsedRequest (UORB message) -ParameterSetUsedRequest : Used by a remote to update the used flag for a parameter on the primary +ParameterSetUsedRequest : Used by a remote to update the used flag for a parameter on the primary. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ParameterSetUsedRequest.msg) +**TOPICS:** parameter_setused_request + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------- | -------- | ------------ | ---------- | ----------- | +| timestamp | `uint64` | | | +| parameter_index | `uint16` | | | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | ------- | ----- | ----------- | +| ORB_QUEUE_LENGTH | `uint8` | 64 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ParameterSetUsedRequest.msg) + +::: details Click here to see original file ```c # ParameterSetUsedRequest : Used by a remote to update the used flag for a parameter on the primary @@ -11,5 +34,6 @@ uint64 timestamp uint16 parameter_index uint8 ORB_QUEUE_LENGTH = 64 - ``` + +::: diff --git a/docs/en/msg_docs/ParameterSetValueRequest.md b/docs/en/msg_docs/ParameterSetValueRequest.md index b8322a952e..f229c6076e 100644 --- a/docs/en/msg_docs/ParameterSetValueRequest.md +++ b/docs/en/msg_docs/ParameterSetValueRequest.md @@ -1,8 +1,33 @@ +--- +pageClass: is-wide-page +--- + # ParameterSetValueRequest (UORB message) -ParameterSetValueRequest : Used by a remote or primary to update the value for a parameter at the other end +ParameterSetValueRequest : Used by a remote or primary to update the value for a parameter at the other end. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ParameterSetValueRequest.msg) +**TOPICS:** parameter_set_value_request parameter_remote_set_value_request parameter_primary_set_value_request + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------- | --------- | ------------ | ---------- | --------------------------------------- | +| timestamp | `uint64` | | | +| parameter_index | `uint16` | | | +| int_value | `int32` | | | Optional value for an integer parameter | +| float_value | `float32` | | | Optional value for a float parameter | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | ------- | ----- | ----------- | +| ORB_QUEUE_LENGTH | `uint8` | 32 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ParameterSetValueRequest.msg) + +::: details Click here to see original file ```c # ParameterSetValueRequest : Used by a remote or primary to update the value for a parameter at the other end @@ -16,5 +41,6 @@ float32 float_value # Optional value for a float parameter uint8 ORB_QUEUE_LENGTH = 32 # TOPICS parameter_set_value_request parameter_remote_set_value_request parameter_primary_set_value_request - ``` + +::: diff --git a/docs/en/msg_docs/ParameterSetValueResponse.md b/docs/en/msg_docs/ParameterSetValueResponse.md index dbb44d46ea..f0a0bf4051 100644 --- a/docs/en/msg_docs/ParameterSetValueResponse.md +++ b/docs/en/msg_docs/ParameterSetValueResponse.md @@ -1,8 +1,32 @@ +--- +pageClass: is-wide-page +--- + # ParameterSetValueResponse (UORB message) -ParameterSetValueResponse : Response to a set value request by either primary or secondary +ParameterSetValueResponse : Response to a set value request by either primary or secondary. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ParameterSetValueResponse.msg) +**TOPICS:** parameter_set_value_response parameter_remote_set_value_response parameter_primary_set_value_response + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------- | -------- | ------------ | ---------- | ----------- | +| timestamp | `uint64` | | | +| request_timestamp | `uint64` | | | +| parameter_index | `uint16` | | | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | ------- | ----- | ----------- | +| ORB_QUEUE_LENGTH | `uint8` | 4 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ParameterSetValueResponse.msg) + +::: details Click here to see original file ```c # ParameterSetValueResponse : Response to a set value request by either primary or secondary @@ -14,5 +38,6 @@ uint16 parameter_index uint8 ORB_QUEUE_LENGTH = 4 # TOPICS parameter_set_value_response parameter_remote_set_value_response parameter_primary_set_value_response - ``` + +::: diff --git a/docs/en/msg_docs/ParameterUpdate.md b/docs/en/msg_docs/ParameterUpdate.md index 29148e2b5b..47df977aa4 100644 --- a/docs/en/msg_docs/ParameterUpdate.md +++ b/docs/en/msg_docs/ParameterUpdate.md @@ -1,8 +1,32 @@ +--- +pageClass: is-wide-page +--- + # ParameterUpdate (UORB message) -This message is used to notify the system about one or more parameter changes +This message is used to notify the system about one or more parameter changes. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ParameterUpdate.msg) +**TOPICS:** parameter_update + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------- | -------- | ------------ | ---------- | ---------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| instance | `uint32` | | | Instance count - constantly incrementing | +| get_count | `uint32` | | | +| set_count | `uint32` | | | +| find_count | `uint32` | | | +| export_count | `uint32` | | | +| active | `uint16` | | | +| changed | `uint16` | | | +| custom_default | `uint16` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ParameterUpdate.msg) + +::: details Click here to see original file ```c # This message is used to notify the system about one or more parameter changes @@ -19,5 +43,6 @@ uint32 export_count uint16 active uint16 changed uint16 custom_default - ``` + +::: diff --git a/docs/en/msg_docs/Ping.md b/docs/en/msg_docs/Ping.md index 1d68cebad1..c27bfbac41 100644 --- a/docs/en/msg_docs/Ping.md +++ b/docs/en/msg_docs/Ping.md @@ -1,8 +1,28 @@ +--- +pageClass: is-wide-page +--- + # Ping (UORB message) +**TOPICS:** ping +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Ping.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------- | --------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| ping_time | `uint64` | | | Timestamp of the ping packet | +| ping_sequence | `uint32` | | | Sequence number of the ping packet | +| dropped_packets | `uint32` | | | Number of dropped ping packets | +| rtt_ms | `float32` | | | Round trip time (in ms) | +| system_id | `uint8` | | | System ID of the remote system | +| component_id | `uint8` | | | Component ID of the remote system | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Ping.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -12,5 +32,6 @@ uint32 dropped_packets # Number of dropped ping packets float32 rtt_ms # Round trip time (in ms) uint8 system_id # System ID of the remote system uint8 component_id # Component ID of the remote system - ``` + +::: diff --git a/docs/en/msg_docs/PositionControllerLandingStatus.md b/docs/en/msg_docs/PositionControllerLandingStatus.md index 0e7ce90a2e..a2265e80ae 100644 --- a/docs/en/msg_docs/PositionControllerLandingStatus.md +++ b/docs/en/msg_docs/PositionControllerLandingStatus.md @@ -1,8 +1,35 @@ +--- +pageClass: is-wide-page +--- + # PositionControllerLandingStatus (UORB message) +**TOPICS:** position_controllerlanding_status +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PositionControllerLandingStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------------ | --------- | ------------ | ---------- | ------------------------------------------------------------------- | +| timestamp | `uint64` | us | | time since system start | +| lateral_touchdown_offset | `float32` | m | | lateral touchdown position offset manually commanded during landing | +| flaring | `bool` | | | true if the aircraft is flaring | +| abort_status | `uint8` | | | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------- | ------- | ----- | --------------------- | +| NOT_ABORTED | `uint8` | 0 | +| ABORTED_BY_OPERATOR | `uint8` | 1 | +| TERRAIN_NOT_FOUND | `uint8` | 2 | FW_LND_ABORT (1 << 0) | +| TERRAIN_TIMEOUT | `uint8` | 3 | FW_LND_ABORT (1 << 1) | +| UNKNOWN_ABORT_CRITERION | `uint8` | 4 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PositionControllerLandingStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # [us] time since system start @@ -21,5 +48,6 @@ uint8 ABORTED_BY_OPERATOR = 1 uint8 TERRAIN_NOT_FOUND = 2 # FW_LND_ABORT (1 << 0) uint8 TERRAIN_TIMEOUT = 3 # FW_LND_ABORT (1 << 1) uint8 UNKNOWN_ABORT_CRITERION = 4 - ``` + +::: diff --git a/docs/en/msg_docs/PositionControllerStatus.md b/docs/en/msg_docs/PositionControllerStatus.md index 95f0ec0926..40b2d40a82 100644 --- a/docs/en/msg_docs/PositionControllerStatus.md +++ b/docs/en/msg_docs/PositionControllerStatus.md @@ -1,8 +1,30 @@ +--- +pageClass: is-wide-page +--- + # PositionControllerStatus (UORB message) +**TOPICS:** position_controllerstatus +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PositionControllerStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------- | --------- | ------------ | ---------- | ------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| nav_roll | `float32` | | | Roll setpoint [rad] | +| nav_pitch | `float32` | | | Pitch setpoint [rad] | +| nav_bearing | `float32` | | | Bearing angle[rad] | +| target_bearing | `float32` | | | Bearing angle from aircraft to current target [rad] | +| xtrack_error | `float32` | | | Signed track error [m] | +| wp_dist | `float32` | | | Distance to active (next) waypoint [m] | +| acceptance_radius | `float32` | | | Current horizontal acceptance radius [m] | +| type | `uint8` | | | Current (applied) position setpoint type (see PositionSetpoint.msg) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PositionControllerStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -15,5 +37,6 @@ float32 xtrack_error # Signed track error [m] float32 wp_dist # Distance to active (next) waypoint [m] float32 acceptance_radius # Current horizontal acceptance radius [m] uint8 type # Current (applied) position setpoint type (see PositionSetpoint.msg) - ``` + +::: diff --git a/docs/en/msg_docs/PositionSetpoint.md b/docs/en/msg_docs/PositionSetpoint.md index b4e16681b7..2ed4747470 100644 --- a/docs/en/msg_docs/PositionSetpoint.md +++ b/docs/en/msg_docs/PositionSetpoint.md @@ -1,8 +1,56 @@ +--- +pageClass: is-wide-page +--- + # PositionSetpoint (UORB message) -this file is only used in the position_setpoint triple as a dependency +this file is only used in the position_setpoint triple as a dependency. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PositionSetpoint.msg) +**TOPICS:** position_setpoint + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------------------- | --------- | ------------ | ---------- | ------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| valid | `bool` | | | true if setpoint is valid | +| type | `uint8` | | | setpoint type to adjust behavior of position controller | +| vx | `float32` | | | local velocity setpoint in m/s in NED | +| vy | `float32` | | | local velocity setpoint in m/s in NED | +| vz | `float32` | | | local velocity setpoint in m/s in NED | +| lat | `float64` | | | latitude, in deg | +| lon | `float64` | | | longitude, in deg | +| alt | `float32` | | | altitude AMSL, in m | +| yaw | `float32` | | | yaw (only in hover), in rad [-PI..PI), NaN = leave to flight task | +| loiter_radius | `float32` | m | [0 : INF] | loiter major axis radius | +| loiter_minor_radius | `float32` | m | [0 : INF] | loiter minor axis radius (used for non-circular loiter shapes) | +| loiter_direction_counter_clockwise | `bool` | | | loiter direction is clockwise by default and can be changed using this field | +| loiter_orientation | `float32` | rad | [-pi : pi] | orientation of the major axis with respect to true north | +| loiter_pattern | `uint8` | | | loitern pattern to follow | +| acceptance_radius | `float32` | | | horizontal acceptance_radius (meters) | +| alt_acceptance_radius | `float32` | | | vertical acceptance radius, only used for fixed wing guidance, NAN = let guidance choose (meters) | +| cruising_speed | `float32` | | | the generally desired cruising speed (not a hard constraint) | +| gliding_enabled | `bool` | | | commands the vehicle to glide if the capability is available (fixed wing only) | +| cruising_throttle | `float32` | | | the generally desired cruising throttle (not a hard constraint), only has an effect for rover | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------- | ------- | ----- | -------------------------------------------------------------- | +| SETPOINT_TYPE_POSITION | `uint8` | 0 | position setpoint | +| SETPOINT_TYPE_VELOCITY | `uint8` | 1 | velocity setpoint | +| SETPOINT_TYPE_LOITER | `uint8` | 2 | loiter setpoint | +| SETPOINT_TYPE_TAKEOFF | `uint8` | 3 | takeoff setpoint | +| SETPOINT_TYPE_LAND | `uint8` | 4 | land setpoint, altitude must be ignored, descend until landing | +| SETPOINT_TYPE_IDLE | `uint8` | 5 | do nothing, switch off motors or keep at idle speed (MC) | +| LOITER_TYPE_ORBIT | `uint8` | 0 | Circular pattern | +| LOITER_TYPE_FIGUREEIGHT | `uint8` | 1 | Pattern resembling an 8 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PositionSetpoint.msg) + +::: details Click here to see original file ```c # this file is only used in the position_setpoint triple as a dependency @@ -43,5 +91,6 @@ float32 alt_acceptance_radius # vertical acceptance radius, only used for fixed float32 cruising_speed # the generally desired cruising speed (not a hard constraint) bool gliding_enabled # commands the vehicle to glide if the capability is available (fixed wing only) float32 cruising_throttle # the generally desired cruising throttle (not a hard constraint), only has an effect for rover - ``` + +::: diff --git a/docs/en/msg_docs/PositionSetpointTriplet.md b/docs/en/msg_docs/PositionSetpointTriplet.md index d4de724bdd..4aea2917fe 100644 --- a/docs/en/msg_docs/PositionSetpointTriplet.md +++ b/docs/en/msg_docs/PositionSetpointTriplet.md @@ -1,9 +1,27 @@ +--- +pageClass: is-wide-page +--- + # PositionSetpointTriplet (UORB message) -Global position setpoint triplet in WGS84 coordinates. -This are the three next waypoints (or just the next two or one). +Global position setpoint triplet in WGS84 coordinates. This are the three next waypoints (or just the next two or one). -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PositionSetpointTriplet.msg) +**TOPICS:** position_setpointtriplet + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | ------------------ | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| previous | `PositionSetpoint` | | | +| current | `PositionSetpoint` | | | +| next | `PositionSetpoint` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PositionSetpointTriplet.msg) + +::: details Click here to see original file ```c # Global position setpoint triplet in WGS84 coordinates. @@ -14,5 +32,6 @@ uint64 timestamp # time since system start (microseconds) PositionSetpoint previous PositionSetpoint current PositionSetpoint next - ``` + +::: diff --git a/docs/en/msg_docs/PowerButtonState.md b/docs/en/msg_docs/PowerButtonState.md index 8d6f38461e..f43ec7dce6 100644 --- a/docs/en/msg_docs/PowerButtonState.md +++ b/docs/en/msg_docs/PowerButtonState.md @@ -1,8 +1,34 @@ +--- +pageClass: is-wide-page +--- + # PowerButtonState (UORB message) -power button state notification message +power button state notification message. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PowerButtonState.msg) +**TOPICS:** power_buttonstate + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| event | `uint8` | | | one of PWR*BUTTON_STATE*\* | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------------------- | ------- | ----- | ----------------------------------------------------------------------- | +| PWR_BUTTON_STATE_IDEL | `uint8` | 0 | Button went up without meeting shutdown button down time (delete event) | +| PWR_BUTTON_STATE_DOWN | `uint8` | 1 | Button went Down | +| PWR_BUTTON_STATE_UP | `uint8` | 2 | Button went Up | +| PWR_BUTTON_STATE_REQUEST_SHUTDOWN | `uint8` | 3 | Button went Up after meeting shutdown button down time | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PowerButtonState.msg) + +::: details Click here to see original file ```c # power button state notification message @@ -15,5 +41,6 @@ uint8 PWR_BUTTON_STATE_UP = 2 # Button went Up uint8 PWR_BUTTON_STATE_REQUEST_SHUTDOWN = 3 # Button went Up after meeting shutdown button down time uint8 event # one of PWR_BUTTON_STATE_* - ``` + +::: diff --git a/docs/en/msg_docs/PowerMonitor.md b/docs/en/msg_docs/PowerMonitor.md index 5f38bb3d56..082a23b3d8 100644 --- a/docs/en/msg_docs/PowerMonitor.md +++ b/docs/en/msg_docs/PowerMonitor.md @@ -1,8 +1,35 @@ +--- +pageClass: is-wide-page +--- + # PowerMonitor (UORB message) -power monitor message +power monitor message. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PowerMonitor.msg) +**TOPICS:** power_monitor + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | --------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | Time since system start (microseconds) | +| voltage_v | `float32` | | | Voltage in volts, 0 if unknown | +| current_a | `float32` | | | Current in amperes, -1 if unknown | +| power_w | `float32` | | | power in watts, -1 if unknown | +| rconf | `int16` | | | +| rsv | `int16` | | | +| rbv | `int16` | | | +| rp | `int16` | | | +| rc | `int16` | | | +| rcal | `int16` | | | +| me | `int16` | | | +| al | `int16` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PowerMonitor.msg) + +::: details Click here to see original file ```c # power monitor message @@ -20,5 +47,6 @@ int16 rc int16 rcal int16 me int16 al - ``` + +::: diff --git a/docs/en/msg_docs/PpsCapture.md b/docs/en/msg_docs/PpsCapture.md index ffe87fd2dc..5d1a14348d 100644 --- a/docs/en/msg_docs/PpsCapture.md +++ b/docs/en/msg_docs/PpsCapture.md @@ -1,12 +1,29 @@ +--- +pageClass: is-wide-page +--- + # PpsCapture (UORB message) +**TOPICS:** pps_capture +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PpsCapture.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------- | -------- | ------------ | ----------------------------- | ----------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) at PPS capture event | +| rtc_timestamp | `uint64` | | | Corrected GPS UTC timestamp at PPS capture event | +| `uint8` | | | Increments when PPS dt < 50ms | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PpsCapture.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) at PPS capture event uint64 rtc_timestamp # Corrected GPS UTC timestamp at PPS capture event uint8 pps_rate_exceeded_counter # Increments when PPS dt < 50ms - ``` + +::: diff --git a/docs/en/msg_docs/PurePursuitStatus.md b/docs/en/msg_docs/PurePursuitStatus.md index 8d54ba473e..fa442729b1 100644 --- a/docs/en/msg_docs/PurePursuitStatus.md +++ b/docs/en/msg_docs/PurePursuitStatus.md @@ -1,8 +1,29 @@ +--- +pageClass: is-wide-page +--- + # PurePursuitStatus (UORB message) -Pure pursuit status +Pure pursuit status. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PurePursuitStatus.msg) +**TOPICS:** pure_pursuitstatus + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------- | --------- | ------------ | --------------------------------------------------- | -------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| lookahead_distance | `float32` | m | [0 : inf] | Lookahead distance of pure the pursuit controller | +| target_bearing | `float32` | rad [NED] | [-pi : pi] | Target bearing calculated by the pure pursuit controller | +| crosstrack_error | `float32` | m | [-inf (Left of the path) : inf (Right of the path)] | Shortest distance from the vehicle to the path | +| distance_to_waypoint | `float32` | m | [-inf : inf] | Distance from the vehicle to the current waypoint | +| bearing_to_waypoint | `float32` | rad [NED] | [-pi : pi] | Bearing towards current waypoint | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PurePursuitStatus.msg) + +::: details Click here to see original file ```c # Pure pursuit status @@ -13,5 +34,6 @@ float32 target_bearing # [rad] [@range -pi, pi] [@frame NED] Target beari float32 crosstrack_error # [m] [@range -inf (Left of the path), inf (Right of the path)] Shortest distance from the vehicle to the path float32 distance_to_waypoint # [m] [@range -inf, inf]Distance from the vehicle to the current waypoint float32 bearing_to_waypoint # [rad] [@range -pi, pi] [@frame NED]Bearing towards current waypoint - ``` + +::: diff --git a/docs/en/msg_docs/PwmInput.md b/docs/en/msg_docs/PwmInput.md index dbf078955b..ca4d9ed41f 100644 --- a/docs/en/msg_docs/PwmInput.md +++ b/docs/en/msg_docs/PwmInput.md @@ -1,13 +1,31 @@ +--- +pageClass: is-wide-page +--- + # PwmInput (UORB message) +**TOPICS:** pwm_input +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PwmInput.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------- | -------- | ------------ | ---------- | -------------------------------------------- | +| timestamp | `uint64` | | | Time since system start (microseconds) | +| error_count | `uint64` | | | Timer overcapture error flag (AUX5 or MAIN5) | +| pulse_width | `uint32` | | | Pulse width, timer counts (microseconds) | +| period | `uint32` | | | Period, timer counts (microseconds) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PwmInput.msg) + +::: details Click here to see original file ```c uint64 timestamp # Time since system start (microseconds) uint64 error_count # Timer overcapture error flag (AUX5 or MAIN5) uint32 pulse_width # Pulse width, timer counts (microseconds) uint32 period # Period, timer counts (microseconds) - ``` + +::: diff --git a/docs/en/msg_docs/Px4ioStatus.md b/docs/en/msg_docs/Px4ioStatus.md index 4b1fbb1314..cbc5e0f339 100644 --- a/docs/en/msg_docs/Px4ioStatus.md +++ b/docs/en/msg_docs/Px4ioStatus.md @@ -1,6 +1,53 @@ +--- +pageClass: is-wide-page +--- + # Px4ioStatus (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Px4ioStatus.msg) +**TOPICS:** px4io_status + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------------------- | ------------ | ------------ | ---------- | -------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| free_memory_bytes | `uint16` | | | +| voltage_v | `float32` | | | Servo rail voltage in volts | +| rssi_v | `float32` | | | RSSI pin voltage in volts | +| status_arm_sync | `bool` | | | +| status_failsafe | `bool` | | | +| status_fmu_initialized | `bool` | | | +| status_fmu_ok | `bool` | | | +| status_init_ok | `bool` | | | +| status_outputs_armed | `bool` | | | +| status_raw_pwm | `bool` | | | +| status_rc_ok | `bool` | | | +| status_rc_dsm | `bool` | | | +| status_rc_ppm | `bool` | | | +| status_rc_sbus | `bool` | | | +| status_rc_st24 | `bool` | | | +| status_rc_sumd | `bool` | | | +| status_safety_button_event | `bool` | | | px4io safety button was pressed for longer than 1 second | +| alarm_pwm_error | `bool` | | | +| alarm_rc_lost | `bool` | | | +| arming_failsafe_custom | `bool` | | | +| arming_fmu_armed | `bool` | | | +| arming_fmu_prearmed | `bool` | | | +| arming_termination | `bool` | | | +| arming_io_arm_ok | `bool` | | | +| arming_lockdown | `bool` | | | +| arming_termination_failsafe | `bool` | | | +| pwm | `uint16[8]` | | | +| pwm_disarmed | `uint16[8]` | | | +| pwm_failsafe | `uint16[8]` | | | +| pwm_rate_hz | `uint16[8]` | | | +| raw_inputs | `uint16[18]` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Px4ioStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -46,5 +93,6 @@ uint16[8] pwm_failsafe uint16[8] pwm_rate_hz uint16[18] raw_inputs - ``` + +::: diff --git a/docs/en/msg_docs/QshellReq.md b/docs/en/msg_docs/QshellReq.md index 99cb82472b..346717a999 100644 --- a/docs/en/msg_docs/QshellReq.md +++ b/docs/en/msg_docs/QshellReq.md @@ -1,8 +1,31 @@ +--- +pageClass: is-wide-page +--- + # QshellReq (UORB message) +**TOPICS:** qshell_req +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/QshellReq.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ----------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| cmd | `char[100]` | | | +| strlen | `uint32` | | | +| request_sequence | `uint32` | | | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------- | -------- | ----- | ----------- | +| MAX_STRLEN | `uint32` | 100 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/QshellReq.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -10,5 +33,6 @@ char[100] cmd uint32 MAX_STRLEN = 100 uint32 strlen uint32 request_sequence - ``` + +::: diff --git a/docs/en/msg_docs/QshellRetval.md b/docs/en/msg_docs/QshellRetval.md index 53cf5063f9..c37afd652e 100644 --- a/docs/en/msg_docs/QshellRetval.md +++ b/docs/en/msg_docs/QshellRetval.md @@ -1,12 +1,29 @@ +--- +pageClass: is-wide-page +--- + # QshellRetval (UORB message) +**TOPICS:** qshell_retval +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/QshellRetval.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------- | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| return_value | `int32` | | | +| return_sequence | `uint32` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/QshellRetval.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) int32 return_value uint32 return_sequence - ``` + +::: diff --git a/docs/en/msg_docs/RadioStatus.md b/docs/en/msg_docs/RadioStatus.md index 64e69beba4..2712fdea13 100644 --- a/docs/en/msg_docs/RadioStatus.md +++ b/docs/en/msg_docs/RadioStatus.md @@ -1,11 +1,31 @@ +--- +pageClass: is-wide-page +--- + # RadioStatus (UORB message) +**TOPICS:** radio_status +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RadioStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------ | -------- | ------------ | ---------- | ----------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| rssi | `uint8` | | | local signal strength | +| remote_rssi | `uint8` | | | remote signal strength | +| txbuf | `uint8` | | | how full the tx buffer is as a percentage | +| noise | `uint8` | | | background noise level | +| remote_noise | `uint8` | | | remote background noise level | +| rxerrors | `uint16` | | | receive errors | +| fix | `uint16` | | | count of error corrected packets | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RadioStatus.msg) + +::: details Click here to see original file ```c - uint64 timestamp # time since system start (microseconds) uint8 rssi # local signal strength @@ -18,5 +38,6 @@ uint8 remote_noise # remote background noise level uint16 rxerrors # receive errors uint16 fix # count of error corrected packets - ``` + +::: diff --git a/docs/en/msg_docs/RaptorInput.md b/docs/en/msg_docs/RaptorInput.md new file mode 100644 index 0000000000..e18b7531ef --- /dev/null +++ b/docs/en/msg_docs/RaptorInput.md @@ -0,0 +1,58 @@ +--- +pageClass: is-wide-page +--- + +# RaptorInput (UORB message) + +Raptor Input. + +**TOPICS:** raptor_input + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ------------ | ------------ | ---------- | -------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| timestamp_sample | `uint64` | us | | Sampling timestamp of the data this control response is based on | +| active | `bool` | | | Signals if the policy is active (aka publishing actuator_motors) | +| position | `float32[3]` | m [FLU] | | Position of the vehicle_local_position frame | +| orientation | `float32[4]` | | | Orientation in the vehicle_attitude frame but using the FLU convention as a unit quaternion (w, x, y, z) | +| linear_velocity | `float32[3]` | m/s [FLU] | | Linear velocity in the vehicle_local_position frame | +| angular_velocity | `float32[3]` | rad/s [FLU] | | Angular velocity in the body frame | +| previous_action | `float32[4]` | | [-1 : 1] | Previous action. Motor commands normalized to [-1, 1] | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | --------------------------------------------- | +| MESSAGE_VERSION | `uint32` | 0 | +| ACTION_DIM | `uint8` | 4 | Policy output dimensionality (for quadrotors) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/RaptorInput.msg) + +::: details Click here to see original file + +```c +# Raptor Input + +# The exact inputs to the Raptor foundation policy. +# Having access to the exact inputs helps with debugging and post-hoc analysis. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on +bool active # Signals if the policy is active (aka publishing actuator_motors) +float32[3] position # [m] [@frame FLU] Position of the vehicle_local_position frame +float32[4] orientation # [-] Orientation in the vehicle_attitude frame but using the FLU convention as a unit quaternion (w, x, y, z) +float32[3] linear_velocity # [m/s] [@frame FLU] Linear velocity in the vehicle_local_position frame +float32[3] angular_velocity # [rad/s] [@frame FLU] Angular velocity in the body frame +uint8 ACTION_DIM = 4 # Policy output dimensionality (for quadrotors) +float32[4] previous_action # [@range -1, 1] Previous action. Motor commands normalized to [-1, 1] + +# TOPICS raptor_input +``` + +::: diff --git a/docs/en/msg_docs/RaptorStatus.md b/docs/en/msg_docs/RaptorStatus.md new file mode 100644 index 0000000000..945dbd521b --- /dev/null +++ b/docs/en/msg_docs/RaptorStatus.md @@ -0,0 +1,108 @@ +--- +pageClass: is-wide-page +--- + +# RaptorStatus (UORB message) + +Raptor Status. + +**TOPICS:** raptor_status + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------------------------------- | ------------ | ------------ | ---------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| timestamp_sample | `uint64` | us | | Sampling timestamp of the data this control response is based on | +| subscription_update_angular_velocity | `bool` | bool | | Flag signalling if the vehicle_angular_velocity was updated | +| subscription_update_local_position | `bool` | bool | | Flag signalling if the vehicle_local_position was updated | +| subscription_update_attitude | `bool` | bool | | Flag signalling if the vehicle_attitude was updated | +| subscription_update_trajectory_setpoint | `bool` | bool | | Flag signalling if the trajectory_setpoint was updated | +| subscription_update_vehicle_status | `bool` | bool | | Flag signalling if the vehicle_status was updated | +| exit_reason | `uint8` | enum | | Exit reason identifier. Representing conditions that lead to the Raptor policy not being executed | +| timestamp_last_vehicle_angular_velocity | `uint32` | us | | Timestamp of the last received vehicle_angular_velocity message | +| timestamp_last_vehicle_local_position | `uint32` | us | | Timestamp of the last received vehicle_local_position message | +| timestamp_last_vehicle_attitude | `uint32` | us | | Timestamp of the last received vehicle_attitude message | +| timestamp_last_trajectory_setpoint | `uint32` | us | | Timestamp of the last received trajectory_setpoint message | +| vehicle_angular_velocity_stale | `bool` | bool | | True if vehicle_angular_velocity data is considered stale (exceeded timeout) | +| vehicle_local_position_stale | `bool` | bool | | True if vehicle_local_position data is considered stale (exceeded timeout) | +| vehicle_attitude_stale | `bool` | bool | | True if vehicle_attitude data is considered stale (exceeded timeout) | +| trajectory_setpoint_stale | `bool` | bool | | True if trajectory_setpoint data is considered stale (exceeded timeout) | +| active | `bool` | bool | | True if the Raptor policy is currently active (publishing actuator_motors) | +| substep | `uint8` | | | The policy is trained at a fixed frequency (e.g. 100 Hz) but we might want to use it for control at higher frequencies (e.g. 400 Hz), which leads to a number of intermediate steps before the actual policy state is advanced (in this case 4 = 400 Hz / 100 Hz). This field provides the current substep (e.g. 0-3). | +| control_interval | `float32` | s | | Time interval between control updates | +| trajectory_setpoint_dt_mean | `float32` | us | | The average trajectory setpoint arrival time interval (since Raptor mode activation within NUM_TRAJECTORY_SETPOINT_DTS received trajectory_setpoint messages) | +| trajectory_setpoint_dt_max | `float32` | us | | The max trajectory setpoint arrival time interval (since Raptor mode activation and within NUM_TRAJECTORY_SETPOINT_DTS received trajectory_setpoint messages) | +| trajectory_setpoint_dt_max_since_activation | `float32` | us | | The max trajectory setpoint arrival time interval (since Raptor mode activation) | +| internal_reference_position | `float32[3]` | m [FLU] | | Internal reference position | +| internal_reference_linear_velocity | `float32[3]` | m/s [FLU] | | Internal reference linear velocity | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------------------------------------------------------------------- | -------- | ----- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| MESSAGE_VERSION | `uint32` | 0 | +| EXIT_REASON_NONE | `uint8` | 0 | No exit reason => Raptor control step was executed (actuator_motors should have been published) | +| EXIT_REASON_NO_ANGULAR_VELOCITY_UPDATE | `uint8` | 1 | We synchronize the control onto the input observation with the highest update frequency, which is vehicle_angular_velocity. If there was no update, we do not need to execute the policy again | +| EXIT_REASON_NOT_ALL_OBSERVATIONS_SET | `uint8` | 2 | We can not execute the policy if not all observations are available | +| EXIT_REASON_ANGULAR_VELOCITY_STALE | `uint8` | 3 | If OBSERVATION_TIMEOUT_ANGULAR_VELOCITY is exceeded, we treat the vehicle_angular_velocity as stale and can not run the policy | +| EXIT_REASON_LOCAL_POSITION_STALE | `uint8` | 4 | If OBSERVATION_TIMEOUT_LOCAL_POSITION is exceeded, we treat the vehicle_local_position as stale and can not run the policy | +| EXIT_REASON_ATTITUDE_STALE | `uint8` | 5 | If OBSERVATION_TIMEOUT_ATTITUDE is exceeded, we treat the vehicle_attitude as stale and can not run the policy | +| EXIT_REASON_EXECUTOR_STATUS_SOURCE_NOT_CONTROL | `uint8` | 6 | The executor that runs the policy can run in oversampling mode, where it decides if the policy should be ran based on the timestamp and not based on fixed synchronization onto the vehicle_angular_velocity. In this case the executor can decide to skip running the policy if the interval is too small, in which case this flag is set. | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/RaptorStatus.msg) + +::: details Click here to see original file + +```c +# Raptor Status + +# Diagnostic messages for the Raptor foundation policy. +# This diagnostic data is useful for debugging (e.g. identifying missing input information). + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on +bool subscription_update_angular_velocity # [bool] Flag signalling if the vehicle_angular_velocity was updated +bool subscription_update_local_position # [bool] Flag signalling if the vehicle_local_position was updated +bool subscription_update_attitude # [bool] Flag signalling if the vehicle_attitude was updated +bool subscription_update_trajectory_setpoint # [bool] Flag signalling if the trajectory_setpoint was updated +bool subscription_update_vehicle_status # [bool] Flag signalling if the vehicle_status was updated + +uint8 exit_reason # [enum] Exit reason identifier. Representing conditions that lead to the Raptor policy not being executed +uint8 EXIT_REASON_NONE = 0 # No exit reason => Raptor control step was executed (actuator_motors should have been published) +uint8 EXIT_REASON_NO_ANGULAR_VELOCITY_UPDATE = 1 # We synchronize the control onto the input observation with the highest update frequency, which is vehicle_angular_velocity. If there was no update, we do not need to execute the policy again +uint8 EXIT_REASON_NOT_ALL_OBSERVATIONS_SET = 2 # We can not execute the policy if not all observations are available +uint8 EXIT_REASON_ANGULAR_VELOCITY_STALE = 3 # If OBSERVATION_TIMEOUT_ANGULAR_VELOCITY is exceeded, we treat the vehicle_angular_velocity as stale and can not run the policy +uint8 EXIT_REASON_LOCAL_POSITION_STALE = 4 # If OBSERVATION_TIMEOUT_LOCAL_POSITION is exceeded, we treat the vehicle_local_position as stale and can not run the policy +uint8 EXIT_REASON_ATTITUDE_STALE = 5 # If OBSERVATION_TIMEOUT_ATTITUDE is exceeded, we treat the vehicle_attitude as stale and can not run the policy +uint8 EXIT_REASON_EXECUTOR_STATUS_SOURCE_NOT_CONTROL = 6 # The executor that runs the policy can run in oversampling mode, where it decides if the policy should be ran based on the timestamp and not based on fixed synchronization onto the vehicle_angular_velocity. In this case the executor can decide to skip running the policy if the interval is too small, in which case this flag is set. + +uint32 timestamp_last_vehicle_angular_velocity # [us] Timestamp of the last received vehicle_angular_velocity message +uint32 timestamp_last_vehicle_local_position # [us] Timestamp of the last received vehicle_local_position message +uint32 timestamp_last_vehicle_attitude # [us] Timestamp of the last received vehicle_attitude message +uint32 timestamp_last_trajectory_setpoint # [us] Timestamp of the last received trajectory_setpoint message + +bool vehicle_angular_velocity_stale # [bool] True if vehicle_angular_velocity data is considered stale (exceeded timeout) +bool vehicle_local_position_stale # [bool] True if vehicle_local_position data is considered stale (exceeded timeout) +bool vehicle_attitude_stale # [bool] True if vehicle_attitude data is considered stale (exceeded timeout) +bool trajectory_setpoint_stale # [bool] True if trajectory_setpoint data is considered stale (exceeded timeout) + +bool active # [bool] True if the Raptor policy is currently active (publishing actuator_motors) +uint8 substep # [-] The policy is trained at a fixed frequency (e.g. 100 Hz) but we might want to use it for control at higher frequencies (e.g. 400 Hz), which leads to a number of intermediate steps before the actual policy state is advanced (in this case 4 = 400 Hz / 100 Hz). This field provides the current substep (e.g. 0-3). +float32 control_interval # [s] Time interval between control updates + +float32 trajectory_setpoint_dt_mean # [us] The average trajectory setpoint arrival time interval (since Raptor mode activation within NUM_TRAJECTORY_SETPOINT_DTS received trajectory_setpoint messages) +float32 trajectory_setpoint_dt_max # [us] The max trajectory setpoint arrival time interval (since Raptor mode activation and within NUM_TRAJECTORY_SETPOINT_DTS received trajectory_setpoint messages) +float32 trajectory_setpoint_dt_max_since_activation # [us] The max trajectory setpoint arrival time interval (since Raptor mode activation) + +float32[3] internal_reference_position # [m] [@frame FLU] Internal reference position +float32[3] internal_reference_linear_velocity # [m/s] [@frame FLU] Internal reference linear velocity + +# TOPICS raptor_status +``` + +::: diff --git a/docs/en/msg_docs/RateCtrlStatus.md b/docs/en/msg_docs/RateCtrlStatus.md index 28adaafbbd..e6caf8764a 100644 --- a/docs/en/msg_docs/RateCtrlStatus.md +++ b/docs/en/msg_docs/RateCtrlStatus.md @@ -1,8 +1,25 @@ +--- +pageClass: is-wide-page +--- + # RateCtrlStatus (UORB message) +**TOPICS:** rate_ctrlstatus +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RateCtrlStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | --------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| rollspeed_integ | `float32` | | | +| pitchspeed_integ | `float32` | | | +| yawspeed_integ | `float32` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RateCtrlStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -11,5 +28,6 @@ uint64 timestamp # time since system start (microseconds) float32 rollspeed_integ float32 pitchspeed_integ float32 yawspeed_integ - ``` + +::: diff --git a/docs/en/msg_docs/RcChannels.md b/docs/en/msg_docs/RcChannels.md index 7abb87c0bc..04894fd4c3 100644 --- a/docs/en/msg_docs/RcChannels.md +++ b/docs/en/msg_docs/RcChannels.md @@ -1,6 +1,65 @@ +--- +pageClass: is-wide-page +--- + # RcChannels (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RcChannels.msg) +**TOPICS:** rc_channels + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------- | ------------- | ------------ | ---------- | ------------------------------------------------------------------ | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_last_valid | `uint64` | | | Timestamp of last valid RC signal | +| channels | `float32[18]` | | | Scaled to -1..1 (throttle: 0..1) | +| channel_count | `uint8` | | | Number of valid channels | +| function | `int8[30]` | | | Functions mapping | +| rssi | `uint8` | | | Receive signal strength index | +| signal_lost | `bool` | | | Control signal lost, should be checked together with topic timeout | +| frame_drop_count | `uint32` | | | Number of dropped frames | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------------- | ------- | ----- | ----------- | +| FUNCTION_THROTTLE | `uint8` | 0 | +| FUNCTION_ROLL | `uint8` | 1 | +| FUNCTION_PITCH | `uint8` | 2 | +| FUNCTION_YAW | `uint8` | 3 | +| FUNCTION_RETURN | `uint8` | 4 | +| FUNCTION_LOITER | `uint8` | 5 | +| FUNCTION_OFFBOARD | `uint8` | 6 | +| FUNCTION_FLAPS | `uint8` | 7 | +| FUNCTION_AUX_1 | `uint8` | 8 | +| FUNCTION_AUX_2 | `uint8` | 9 | +| FUNCTION_AUX_3 | `uint8` | 10 | +| FUNCTION_AUX_4 | `uint8` | 11 | +| FUNCTION_AUX_5 | `uint8` | 12 | +| FUNCTION_AUX_6 | `uint8` | 13 | +| FUNCTION_PARAM_1 | `uint8` | 14 | +| FUNCTION_PARAM_2 | `uint8` | 15 | +| FUNCTION_PARAM_3_5 | `uint8` | 16 | +| FUNCTION_KILLSWITCH | `uint8` | 17 | +| FUNCTION_TRANSITION | `uint8` | 18 | +| FUNCTION_GEAR | `uint8` | 19 | +| FUNCTION_ARMSWITCH | `uint8` | 20 | +| FUNCTION_FLTBTN_SLOT_1 | `uint8` | 21 | +| FUNCTION_FLTBTN_SLOT_2 | `uint8` | 22 | +| FUNCTION_FLTBTN_SLOT_3 | `uint8` | 23 | +| FUNCTION_FLTBTN_SLOT_4 | `uint8` | 24 | +| FUNCTION_FLTBTN_SLOT_5 | `uint8` | 25 | +| FUNCTION_FLTBTN_SLOT_6 | `uint8` | 26 | +| FUNCTION_ENGAGE_MAIN_MOTOR | `uint8` | 27 | +| FUNCTION_PAYLOAD_POWER | `uint8` | 28 | +| FUNCTION_TERMINATION | `uint8` | 29 | +| FUNCTION_FLTBTN_SLOT_COUNT | `uint8` | 6 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RcChannels.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -45,5 +104,6 @@ int8[30] function # Functions mapping uint8 rssi # Receive signal strength index bool signal_lost # Control signal lost, should be checked together with topic timeout uint32 frame_drop_count # Number of dropped frames - ``` + +::: diff --git a/docs/en/msg_docs/RcParameterMap.md b/docs/en/msg_docs/RcParameterMap.md index a371149b15..6aff36b48e 100644 --- a/docs/en/msg_docs/RcParameterMap.md +++ b/docs/en/msg_docs/RcParameterMap.md @@ -1,8 +1,36 @@ +--- +pageClass: is-wide-page +--- + # RcParameterMap (UORB message) +**TOPICS:** rc_parametermap +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RcParameterMap.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------- | ------------ | ------------ | ---------- | ------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| valid | `bool[3]` | | | true for RC-Param channels which are mapped to a param | +| param_index | `int32[3]` | | | corresponding param index, this field is ignored if set to -1, in this case param_id will be used | +| param_id | `char[51]` | | | MAP_NCHAN \* (ID_LEN + 1) chars, corresponding param id, null terminated | +| scale | `float32[3]` | | | scale to map the RC input [-1, 1] to a parameter value | +| value0 | `float32[3]` | | | initial value around which the parameter value is changed | +| value_min | `float32[3]` | | | minimal parameter value | +| value_max | `float32[3]` | | | minimal parameter value | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------- | ------- | ----- | ------------------------------------------------------------------------------ | +| RC_PARAM_MAP_NCHAN | `uint8` | 3 | This limit is also hardcoded in the enum RC_CHANNELS_FUNCTION in rc_channels.h | +| PARAM_ID_LEN | `uint8` | 16 | corresponds to MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RcParameterMap.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -16,5 +44,6 @@ float32[3] scale # scale to map the RC input [-1, 1] to a parameter value float32[3] value0 # initial value around which the parameter value is changed float32[3] value_min # minimal parameter value float32[3] value_max # minimal parameter value - ``` + +::: diff --git a/docs/en/msg_docs/RegisterExtComponentReply.md b/docs/en/msg_docs/RegisterExtComponentReply.md index 119703472a..09fc14ab9e 100644 --- a/docs/en/msg_docs/RegisterExtComponentReply.md +++ b/docs/en/msg_docs/RegisterExtComponentReply.md @@ -1,6 +1,37 @@ +--- +pageClass: is-wide-page +--- + # RegisterExtComponentReply (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/RegisterExtComponentReply.msg) +**TOPICS:** register_extcomponent_reply + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------- | ---------- | ------------ | ---------- | -------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| request_id | `uint64` | | | ID from the request | +| name | `char[25]` | | | name from the request | +| px4_ros2_api_version | `uint16` | | | +| success | `bool` | | | +| arming_check_id | `int8` | | | arming check registration ID (-1 if invalid) | +| mode_id | `int8` | | | assigned mode ID (-1 if invalid) | +| mode_executor_id | `int8` | | | assigned mode executor ID (-1 if invalid) | +| not_user_selectable | `bool` | | | mode cannot be selected by the user | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 1 | +| ORB_QUEUE_LENGTH | `uint8` | 2 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/RegisterExtComponentReply.msg) + +::: details Click here to see original file ```c uint32 MESSAGE_VERSION = 1 @@ -20,5 +51,6 @@ int8 mode_executor_id # assigned mode executor ID (-1 if invalid) bool not_user_selectable # mode cannot be selected by the user uint8 ORB_QUEUE_LENGTH = 2 - ``` + +::: diff --git a/docs/en/msg_docs/RegisterExtComponentReplyV0.md b/docs/en/msg_docs/RegisterExtComponentReplyV0.md index cceec88d5c..c1b28811df 100644 --- a/docs/en/msg_docs/RegisterExtComponentReplyV0.md +++ b/docs/en/msg_docs/RegisterExtComponentReplyV0.md @@ -1,6 +1,36 @@ +--- +pageClass: is-wide-page +--- + # RegisterExtComponentReplyV0 (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/RegisterExtComponentReplyV0.msg) +**TOPICS:** register_extcomponent_replyv0 + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------- | ---------- | ------------ | ---------- | -------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| request_id | `uint64` | | | ID from the request | +| name | `char[25]` | | | name from the request | +| px4_ros2_api_version | `uint16` | | | +| success | `bool` | | | +| arming_check_id | `int8` | | | arming check registration ID (-1 if invalid) | +| mode_id | `int8` | | | assigned mode ID (-1 if invalid) | +| mode_executor_id | `int8` | | | assigned mode executor ID (-1 if invalid) | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | +| ORB_QUEUE_LENGTH | `uint8` | 2 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/RegisterExtComponentReplyV0.msg) + +::: details Click here to see original file ```c uint32 MESSAGE_VERSION = 0 @@ -18,5 +48,6 @@ int8 mode_id # assigned mode ID (-1 if invalid) int8 mode_executor_id # assigned mode executor ID (-1 if invalid) uint8 ORB_QUEUE_LENGTH = 2 - ``` + +::: diff --git a/docs/en/msg_docs/RegisterExtComponentRequest.md b/docs/en/msg_docs/RegisterExtComponentRequest.md index 814ea6e51b..4ac2f32e57 100644 --- a/docs/en/msg_docs/RegisterExtComponentRequest.md +++ b/docs/en/msg_docs/RegisterExtComponentRequest.md @@ -1,8 +1,42 @@ +--- +pageClass: is-wide-page +--- + # RegisterExtComponentRequest (UORB message) -Request to register an external component +Request to register an external component. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/RegisterExtComponentRequest.msg) +**TOPICS:** register_extcomponent_request + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------------- | ---------- | ------------ | ---------- | ------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| request_id | `uint64` | | | ID, set this to a random value | +| name | `char[25]` | | | either the requested mode name, or component name | +| px4_ros2_api_version | `uint16` | | | Set to LATEST_PX4_ROS2_API_VERSION | +| register_arming_check | `bool` | | | +| register_mode | `bool` | | | registering a mode also requires arming_check to be set | +| register_mode_executor | `bool` | | | registering an executor also requires a mode to be registered (which is the owned mode by the executor) | +| enable_replace_internal_mode | `bool` | | | set to true if an internal mode should be replaced | +| replace_internal_mode | `uint8` | | | vehicle*status::NAVIGATION_STATE*\* | +| activate_mode_immediately | `bool` | | | switch to the registered mode (can only be set in combination with an executor) | +| not_user_selectable | `bool` | | | mode cannot be selected by the user | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------- | -------- | ----- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| MESSAGE_VERSION | `uint32` | 1 | +| LATEST_PX4_ROS2_API_VERSION | `uint16` | 1 | API version compatibility. Increase this on a breaking semantic change. Changes to any message field are detected separately and do not require an API version change. | +| ORB_QUEUE_LENGTH | `uint8` | 2 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/RegisterExtComponentRequest.msg) + +::: details Click here to see original file ```c # Request to register an external component @@ -29,5 +63,6 @@ bool activate_mode_immediately # switch to the registered mode (can only be bool not_user_selectable # mode cannot be selected by the user uint8 ORB_QUEUE_LENGTH = 2 - ``` + +::: diff --git a/docs/en/msg_docs/RegisterExtComponentRequestV0.md b/docs/en/msg_docs/RegisterExtComponentRequestV0.md index 58e99a484e..469bfdd70b 100644 --- a/docs/en/msg_docs/RegisterExtComponentRequestV0.md +++ b/docs/en/msg_docs/RegisterExtComponentRequestV0.md @@ -1,8 +1,41 @@ +--- +pageClass: is-wide-page +--- + # RegisterExtComponentRequestV0 (UORB message) -Request to register an external component +Request to register an external component. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/RegisterExtComponentRequestV0.msg) +**TOPICS:** register_extcomponent_requestv0 + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------------- | ---------- | ------------ | ---------- | ------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| request_id | `uint64` | | | ID, set this to a random value | +| name | `char[25]` | | | either the requested mode name, or component name | +| px4_ros2_api_version | `uint16` | | | Set to LATEST_PX4_ROS2_API_VERSION | +| register_arming_check | `bool` | | | +| register_mode | `bool` | | | registering a mode also requires arming_check to be set | +| register_mode_executor | `bool` | | | registering an executor also requires a mode to be registered (which is the owned mode by the executor) | +| enable_replace_internal_mode | `bool` | | | set to true if an internal mode should be replaced | +| replace_internal_mode | `uint8` | | | vehicle*status::NAVIGATION_STATE*\* | +| activate_mode_immediately | `bool` | | | switch to the registered mode (can only be set in combination with an executor) | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------- | -------- | ----- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| MESSAGE_VERSION | `uint32` | 0 | +| LATEST_PX4_ROS2_API_VERSION | `uint16` | 1 | API version compatibility. Increase this on a breaking semantic change. Changes to any message field are detected separately and do not require an API version change. | +| ORB_QUEUE_LENGTH | `uint8` | 2 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/RegisterExtComponentRequestV0.msg) + +::: details Click here to see original file ```c # Request to register an external component @@ -29,5 +62,6 @@ bool activate_mode_immediately # switch to the registered mode (can only be uint8 ORB_QUEUE_LENGTH = 2 - ``` + +::: diff --git a/docs/en/msg_docs/RoverAttitudeSetpoint.md b/docs/en/msg_docs/RoverAttitudeSetpoint.md index ca75a6e3e2..8049e8bfe3 100644 --- a/docs/en/msg_docs/RoverAttitudeSetpoint.md +++ b/docs/en/msg_docs/RoverAttitudeSetpoint.md @@ -1,13 +1,31 @@ +--- +pageClass: is-wide-page +--- + # RoverAttitudeSetpoint (UORB message) -Rover Attitude Setpoint +Rover Attitude Setpoint. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverAttitudeSetpoint.msg) +**TOPICS:** rover_attitudesetpoint + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------ | --------- | ------------ | ------------ | ----------------------- | +| timestamp | `uint64` | us | | Time since system start | +| yaw_setpoint | `float32` | rad [NED] | [-inf : inf] | Yaw setpoint | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverAttitudeSetpoint.msg) + +::: details Click here to see original file ```c # Rover Attitude Setpoint uint64 timestamp # [us] Time since system start float32 yaw_setpoint # [rad] [@range -inf, inf] [@frame NED] Yaw setpoint - ``` + +::: diff --git a/docs/en/msg_docs/RoverAttitudeStatus.md b/docs/en/msg_docs/RoverAttitudeStatus.md index f5a9ce1f02..a012cd2e17 100644 --- a/docs/en/msg_docs/RoverAttitudeStatus.md +++ b/docs/en/msg_docs/RoverAttitudeStatus.md @@ -1,8 +1,26 @@ +--- +pageClass: is-wide-page +--- + # RoverAttitudeStatus (UORB message) -Rover Attitude Status +Rover Attitude Status. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverAttitudeStatus.msg) +**TOPICS:** rover_attitudestatus + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------------- | --------- | ------------ | ---------- | ------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| measured_yaw | `float32` | rad [NED] | [-pi : pi] | Measured yaw | +| adjusted_yaw_setpoint | `float32` | rad [NED] | [-pi : pi] | Yaw setpoint that is being tracked (Applied slew rates) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverAttitudeStatus.msg) + +::: details Click here to see original file ```c # Rover Attitude Status @@ -10,5 +28,6 @@ Rover Attitude Status uint64 timestamp # [us] Time since system start float32 measured_yaw # [rad] [@range -pi, pi] [@frame NED]Measured yaw float32 adjusted_yaw_setpoint # [rad] [@range -pi, pi] [@frame NED] Yaw setpoint that is being tracked (Applied slew rates) - ``` + +::: diff --git a/docs/en/msg_docs/RoverPositionSetpoint.md b/docs/en/msg_docs/RoverPositionSetpoint.md index 751536e7f9..2a3835c984 100644 --- a/docs/en/msg_docs/RoverPositionSetpoint.md +++ b/docs/en/msg_docs/RoverPositionSetpoint.md @@ -1,8 +1,29 @@ +--- +pageClass: is-wide-page +--- + # RoverPositionSetpoint (UORB message) -Rover Position Setpoint +Rover Position Setpoint. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverPositionSetpoint.msg) +**TOPICS:** rover_positionsetpoint + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------- | ------------ | ------------ | ------------ | -------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| position_ned | `float32[2]` | m [NED] | [-inf : inf] | Target position | +| start_ned | `float32[2]` | m [NED] | [-inf : inf] | Start position which specifies a line for the rover to track (Invalid: NaN Defaults to vehicle position) | +| cruising_speed | `float32` | m/s | [0 : inf] | Cruising speed (Invalid: NaN Defaults to maximum speed) | +| arrival_speed | `float32` | m/s | [0 : inf] | Speed the rover should arrive at the target with (Invalid: NaN Defaults to 0) | +| yaw | `float32` | rad [NED] | [-pi : pi] | Mecanum only: Specify vehicle yaw during travel (Invalid: NaN Defaults to vehicle yaw) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverPositionSetpoint.msg) + +::: details Click here to see original file ```c # Rover Position Setpoint @@ -13,5 +34,6 @@ float32[2] start_ned # [m] [@range -inf, inf] [@frame NED] [@invalid NaN Def float32 cruising_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to maximum speed] Cruising speed float32 arrival_speed # [m/s] [@range 0, inf] [@invalid NaN Defaults to 0] Speed the rover should arrive at the target with float32 yaw # [rad] [@range -pi,pi] [@frame NED] [@invalid NaN Defaults to vehicle yaw] Mecanum only: Specify vehicle yaw during travel - ``` + +::: diff --git a/docs/en/msg_docs/RoverRateSetpoint.md b/docs/en/msg_docs/RoverRateSetpoint.md index 9bb844e802..79a2746bcc 100644 --- a/docs/en/msg_docs/RoverRateSetpoint.md +++ b/docs/en/msg_docs/RoverRateSetpoint.md @@ -1,13 +1,31 @@ +--- +pageClass: is-wide-page +--- + # RoverRateSetpoint (UORB message) -Rover Rate setpoint +Rover Rate setpoint. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverRateSetpoint.msg) +**TOPICS:** rover_ratesetpoint + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------- | --------- | ------------ | ------------ | ----------------------- | +| timestamp | `uint64` | us | | Time since system start | +| yaw_rate_setpoint | `float32` | rad/s [NED] | [-inf : inf] | Yaw rate setpoint | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverRateSetpoint.msg) + +::: details Click here to see original file ```c # Rover Rate setpoint uint64 timestamp # [us] Time since system start float32 yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint - ``` + +::: diff --git a/docs/en/msg_docs/RoverRateStatus.md b/docs/en/msg_docs/RoverRateStatus.md index 70345fe315..27cb672a32 100644 --- a/docs/en/msg_docs/RoverRateStatus.md +++ b/docs/en/msg_docs/RoverRateStatus.md @@ -1,8 +1,27 @@ +--- +pageClass: is-wide-page +--- + # RoverRateStatus (UORB message) -Rover Rate Status +Rover Rate Status. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverRateStatus.msg) +**TOPICS:** rover_ratestatus + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------------- | --------- | ------------ | ------------ | ------------------------------------------------------------ | +| timestamp | `uint64` | us | | Time since system start | +| measured_yaw_rate | `float32` | rad/s [NED] | [-inf : inf] | Measured yaw rate | +| adjusted_yaw_rate_setpoint | `float32` | rad/s [NED] | [-inf : inf] | Yaw rate setpoint that is being tracked (Applied slew rates) | +| pid_yaw_rate_integral | `float32` | | [-1 : 1] | Integral of the PID for the closed loop yaw rate controller | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverRateStatus.msg) + +::: details Click here to see original file ```c # Rover Rate Status @@ -11,5 +30,6 @@ uint64 timestamp # [us] Time since system start float32 measured_yaw_rate # [rad/s] [@range -inf, inf] [@frame NED] Measured yaw rate float32 adjusted_yaw_rate_setpoint # [rad/s] [@range -inf, inf] [@frame NED] Yaw rate setpoint that is being tracked (Applied slew rates) float32 pid_yaw_rate_integral # [-] [@range -1, 1] Integral of the PID for the closed loop yaw rate controller - ``` + +::: diff --git a/docs/en/msg_docs/RoverSpeedSetpoint.md b/docs/en/msg_docs/RoverSpeedSetpoint.md index 84176cd1c3..63c9e6aeba 100644 --- a/docs/en/msg_docs/RoverSpeedSetpoint.md +++ b/docs/en/msg_docs/RoverSpeedSetpoint.md @@ -1,8 +1,26 @@ +--- +pageClass: is-wide-page +--- + # RoverSpeedSetpoint (UORB message) -Rover Speed Setpoint +Rover Speed Setpoint. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverSpeedSetpoint.msg) +**TOPICS:** rover_speedsetpoint + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------ | --------- | ------------ | ----------------------------------- | ------------------------------------------------------------------------------ | +| timestamp | `uint64` | us | | Time since system start | +| speed_body_x | `float32` | m/s [Body] | [-inf (Backwards) : inf (Forwards)] | Speed setpoint in body x direction | +| speed_body_y | `float32` | m/s [Body] | [-inf (Left) : inf (Right)] | Mecanum only: Speed setpoint in body y direction (Invalid: NaN If not mecanum) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverSpeedSetpoint.msg) + +::: details Click here to see original file ```c # Rover Speed Setpoint @@ -10,5 +28,6 @@ Rover Speed Setpoint uint64 timestamp # [us] Time since system start float32 speed_body_x # [m/s] [@range -inf (Backwards), inf (Forwards)] [@frame Body] Speed setpoint in body x direction float32 speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction - ``` + +::: diff --git a/docs/en/msg_docs/RoverSpeedStatus.md b/docs/en/msg_docs/RoverSpeedStatus.md index 4213e1e5df..c0790eb03d 100644 --- a/docs/en/msg_docs/RoverSpeedStatus.md +++ b/docs/en/msg_docs/RoverSpeedStatus.md @@ -1,8 +1,30 @@ +--- +pageClass: is-wide-page +--- + # RoverSpeedStatus (UORB message) -Rover Velocity Status +Rover Velocity Status. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverSpeedStatus.msg) +**TOPICS:** rover_speedstatus + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------------------ | --------- | ------------ | ----------------------------------- | ------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| measured_speed_body_x | `float32` | m/s [Body] | [-inf (Backwards) : inf (Forwards)] | Measured speed in body x direction | +| adjusted_speed_body_x_setpoint | `float32` | m/s [Body] | [-inf (Backwards) : inf (Forwards)] | Speed setpoint in body x direction that is being tracked (Applied slew rates) | +| pid_throttle_body_x_integral | `float32` | | [-1 : 1] | Integral of the PID for the closed loop controller of the speed in body x direction | +| measured_speed_body_y | `float32` | m/s [Body] | [-inf (Left) : inf (Right)] | Mecanum only: Measured speed in body y direction (Invalid: NaN If not mecanum) | +| adjusted_speed_body_y_setpoint | `float32` | m/s [Body] | [-inf (Left) : inf (Right)] | Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates) (Invalid: NaN If not mecanum) | +| pid_throttle_body_y_integral | `float32` | | [-1 : 1] | Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction (Invalid: NaN If not mecanum) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverSpeedStatus.msg) + +::: details Click here to see original file ```c # Rover Velocity Status @@ -14,5 +36,6 @@ float32 pid_throttle_body_x_integral # [-] [@range -1, 1] Integral of the PID float32 measured_speed_body_y # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Measured speed in body y direction float32 adjusted_speed_body_y_setpoint # [m/s] [@range -inf (Left), inf (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Speed setpoint in body y direction that is being tracked (Applied slew rates) float32 pid_throttle_body_y_integral # [-] [@range -1, 1] [@invalid NaN If not mecanum] Mecanum only: Integral of the PID for the closed loop controller of the speed in body y direction - ``` + +::: diff --git a/docs/en/msg_docs/RoverSteeringSetpoint.md b/docs/en/msg_docs/RoverSteeringSetpoint.md index 974f3fc4c9..b87ea4c311 100644 --- a/docs/en/msg_docs/RoverSteeringSetpoint.md +++ b/docs/en/msg_docs/RoverSteeringSetpoint.md @@ -1,13 +1,31 @@ +--- +pageClass: is-wide-page +--- + # RoverSteeringSetpoint (UORB message) -Rover Steering setpoint +Rover Steering setpoint. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverSteeringSetpoint.msg) +**TOPICS:** rover_steeringsetpoint + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------------- | --------- | ------------ | ----------------------- | ------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| normalized_steering_setpoint | `float32` | [Body] | [-1 (Left) : 1 (Right)] | Ackermann: Normalized steering angle, Differential/Mecanum: Normalized speed difference between the left and right wheels | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverSteeringSetpoint.msg) + +::: details Click here to see original file ```c # Rover Steering setpoint uint64 timestamp # [us] Time since system start float32 normalized_steering_setpoint # [-] [@range -1 (Left), 1 (Right)] [@frame Body] Ackermann: Normalized steering angle, Differential/Mecanum: Normalized speed difference between the left and right wheels - ``` + +::: diff --git a/docs/en/msg_docs/RoverThrottleSetpoint.md b/docs/en/msg_docs/RoverThrottleSetpoint.md index bd5ee93d55..22a459eb82 100644 --- a/docs/en/msg_docs/RoverThrottleSetpoint.md +++ b/docs/en/msg_docs/RoverThrottleSetpoint.md @@ -1,8 +1,26 @@ +--- +pageClass: is-wide-page +--- + # RoverThrottleSetpoint (UORB message) -Rover Throttle setpoint +Rover Throttle setpoint. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverThrottleSetpoint.msg) +**TOPICS:** rover_throttlesetpoint + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------- | --------- | ------------ | ------------------------------- | ------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| throttle_body_x | `float32` | [Body] | [-1 (Backwards) : 1 (Forwards)] | Throttle setpoint along body X axis | +| throttle_body_y | `float32` | [Body] | [-1 (Left) : 1 (Right)] | Mecanum only: Throttle setpoint along body Y axis (Invalid: NaN If not mecanum) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RoverThrottleSetpoint.msg) + +::: details Click here to see original file ```c # Rover Throttle setpoint @@ -10,5 +28,6 @@ Rover Throttle setpoint uint64 timestamp # [us] Time since system start float32 throttle_body_x # [-] [@range -1 (Backwards), 1 (Forwards)] [@frame Body] Throttle setpoint along body X axis float32 throttle_body_y # [-] [@range -1 (Left), 1 (Right)] [@frame Body] [@invalid NaN If not mecanum] Mecanum only: Throttle setpoint along body Y axis - ``` + +::: diff --git a/docs/en/msg_docs/Rpm.md b/docs/en/msg_docs/Rpm.md index edf6c37e19..a2ad43c153 100644 --- a/docs/en/msg_docs/Rpm.md +++ b/docs/en/msg_docs/Rpm.md @@ -1,8 +1,24 @@ +--- +pageClass: is-wide-page +--- + # Rpm (UORB message) +**TOPICS:** rpm +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Rpm.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------ | --------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| rpm_estimate | `float32` | | | filtered revolutions per minute | +| rpm_raw | `float32` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Rpm.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -10,5 +26,6 @@ uint64 timestamp # time since system start (microseconds) # rpm values of 0.0 mean within a timeout there is no movement measured float32 rpm_estimate # filtered revolutions per minute float32 rpm_raw - ``` + +::: diff --git a/docs/en/msg_docs/RtlStatus.md b/docs/en/msg_docs/RtlStatus.md index 299b6f4b16..ea1da9648c 100644 --- a/docs/en/msg_docs/RtlStatus.md +++ b/docs/en/msg_docs/RtlStatus.md @@ -1,8 +1,37 @@ +--- +pageClass: is-wide-page +--- + # RtlStatus (UORB message) +**TOPICS:** rtl_status +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RtlStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------------- | -------- | ------------ | ---------- | -------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| safe_points_id | `uint32` | | | unique ID of active set of safe_point_items | +| is_evaluation_pending | `bool` | | | flag if the RTL point needs reevaluation (e.g. new safe points available, but need loading). | +| has_vtol_approach | `bool` | | | flag if approaches are defined for current RTL_TYPE parameter setting | +| rtl_type | `uint8` | | | Type of RTL chosen | +| safe_point_index | `uint8` | | | index of the chosen safe point, if in RTL_STATUS_TYPE_DIRECT_SAFE_POINT mode | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------------------------------------- | ------- | ----- | ----------------------------------------------------------------------------------------------------------------------------------------------------------- | +| RTL_STATUS_TYPE_NONE | `uint8` | 0 | pending if evaluation can't pe performed currently e.g. when it is still loading the safe points | +| RTL_STATUS_TYPE_DIRECT_SAFE_POINT | `uint8` | 1 | chosen to directly go to a safe point or home position | +| RTL_STATUS_TYPE_DIRECT_MISSION_LAND | `uint8` | 2 | going straight to the beginning of the mission landing | +| RTL_STATUS_TYPE_FOLLOW_MISSION | `uint8` | 3 | Following the mission from start index to mission landing. Start index is current WP if in Mission mode, and closest WP otherwise. | +| RTL_STATUS_TYPE_FOLLOW_MISSION_REVERSE | `uint8` | 4 | Following the mission in reverse from start index to the beginning of the mission. Start index is previous WP if in Mission mode, and closest WP otherwise. | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RtlStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -20,5 +49,6 @@ uint8 RTL_STATUS_TYPE_DIRECT_SAFE_POINT=1 # chosen to directly go to a safe poi uint8 RTL_STATUS_TYPE_DIRECT_MISSION_LAND=2 # going straight to the beginning of the mission landing uint8 RTL_STATUS_TYPE_FOLLOW_MISSION=3 # Following the mission from start index to mission landing. Start index is current WP if in Mission mode, and closest WP otherwise. uint8 RTL_STATUS_TYPE_FOLLOW_MISSION_REVERSE=4 # Following the mission in reverse from start index to the beginning of the mission. Start index is previous WP if in Mission mode, and closest WP otherwise. - ``` + +::: diff --git a/docs/en/msg_docs/RtlTimeEstimate.md b/docs/en/msg_docs/RtlTimeEstimate.md index 14dbe31594..894fe4589c 100644 --- a/docs/en/msg_docs/RtlTimeEstimate.md +++ b/docs/en/msg_docs/RtlTimeEstimate.md @@ -1,8 +1,25 @@ +--- +pageClass: is-wide-page +--- + # RtlTimeEstimate (UORB message) +**TOPICS:** rtl_timeestimate +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RtlTimeEstimate.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------ | --------- | ------------ | ---------- | --------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| valid | `bool` | | | Flag indicating whether the time estiamtes are valid | +| time_estimate | `float32` | s | | Estimated time for RTL | +| safe_time_estimate | `float32` | s | | Same as time_estimate, but with safety factor and safety margin included (factor\*t + margin) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RtlTimeEstimate.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -10,5 +27,6 @@ uint64 timestamp # time since system start (microseconds) bool valid # Flag indicating whether the time estiamtes are valid float32 time_estimate # [s] Estimated time for RTL float32 safe_time_estimate # [s] Same as time_estimate, but with safety factor and safety margin included (factor*t + margin) - ``` + +::: diff --git a/docs/en/msg_docs/SatelliteInfo.md b/docs/en/msg_docs/SatelliteInfo.md index c040856148..af1587d7a6 100644 --- a/docs/en/msg_docs/SatelliteInfo.md +++ b/docs/en/msg_docs/SatelliteInfo.md @@ -1,6 +1,35 @@ +--- +pageClass: is-wide-page +--- + # SatelliteInfo (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SatelliteInfo.msg) +**TOPICS:** satellite_info + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | ----------- | ------------ | ---------- | -------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| count | `uint8` | | | Number of satellites visible to the receiver | +| svid | `uint8[40]` | | | Space vehicle ID [1..255], see scheme below | +| used | `uint8[40]` | | | 0: Satellite not used, 1: used for navigation | +| elevation | `uint8[40]` | | | Elevation (0: right on top of receiver, 90: on the horizon) of satellite | +| azimuth | `uint8[40]` | | | Direction of satellite, 0: 0 deg, 255: 360 deg. | +| snr | `uint8[40]` | | | dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. | +| prn | `uint8[40]` | | | Satellite PRN code assignment, (psuedorandom number SBAS, valid codes are 120-144) | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------- | ------- | ----- | ----------- | +| SAT_INFO_MAX_SATELLITES | `uint8` | 40 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SatelliteInfo.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -13,5 +42,6 @@ uint8[40] elevation # Elevation (0: right on top of receiver, 90: on the horizo uint8[40] azimuth # Direction of satellite, 0: 0 deg, 255: 360 deg. uint8[40] snr # dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. uint8[40] prn # Satellite PRN code assignment, (psuedorandom number SBAS, valid codes are 120-144) - ``` + +::: diff --git a/docs/en/msg_docs/SensorAccel.md b/docs/en/msg_docs/SensorAccel.md index 50e0c9f240..5c34986404 100644 --- a/docs/en/msg_docs/SensorAccel.md +++ b/docs/en/msg_docs/SensorAccel.md @@ -1,8 +1,37 @@ +--- +pageClass: is-wide-page +--- + # SensorAccel (UORB message) +**TOPICS:** sensor_accel +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorAccel.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ---------- | ------------ | ---------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| x | `float32` | | | acceleration in the FRD board frame X-axis in m/s^2 | +| y | `float32` | | | acceleration in the FRD board frame Y-axis in m/s^2 | +| z | `float32` | | | acceleration in the FRD board frame Z-axis in m/s^2 | +| temperature | `float32` | | | temperature in degrees Celsius | +| error_count | `uint32` | | | +| clip_counter | `uint8[3]` | | | clip count per axis in the sample period | +| samples | `uint8` | | | number of raw samples that went into this message | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | ------- | ----- | ----------- | +| ORB_QUEUE_LENGTH | `uint8` | 8 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorAccel.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -23,5 +52,6 @@ uint8[3] clip_counter # clip count per axis in the sample period uint8 samples # number of raw samples that went into this message uint8 ORB_QUEUE_LENGTH = 8 - ``` + +::: diff --git a/docs/en/msg_docs/SensorAccelFifo.md b/docs/en/msg_docs/SensorAccelFifo.md index b624951f07..beebee2315 100644 --- a/docs/en/msg_docs/SensorAccelFifo.md +++ b/docs/en/msg_docs/SensorAccelFifo.md @@ -1,8 +1,30 @@ +--- +pageClass: is-wide-page +--- + # SensorAccelFifo (UORB message) +**TOPICS:** sensor_accelfifo +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorAccelFifo.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ----------- | ------------ | ---------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| dt | `float32` | | | delta time between samples (microseconds) | +| scale | `float32` | | | +| samples | `uint8` | | | number of valid samples | +| x | `int16[32]` | | | acceleration in the FRD board frame X-axis in m/s^2 | +| y | `int16[32]` | | | acceleration in the FRD board frame Y-axis in m/s^2 | +| z | `int16[32]` | | | acceleration in the FRD board frame Z-axis in m/s^2 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorAccelFifo.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -18,5 +40,6 @@ uint8 samples # number of valid samples int16[32] x # acceleration in the FRD board frame X-axis in m/s^2 int16[32] y # acceleration in the FRD board frame Y-axis in m/s^2 int16[32] z # acceleration in the FRD board frame Z-axis in m/s^2 - ``` + +::: diff --git a/docs/en/msg_docs/SensorAirflow.md b/docs/en/msg_docs/SensorAirflow.md index 72bdd43e2c..05b066c70e 100644 --- a/docs/en/msg_docs/SensorAirflow.md +++ b/docs/en/msg_docs/SensorAirflow.md @@ -1,8 +1,26 @@ +--- +pageClass: is-wide-page +--- + # SensorAirflow (UORB message) +**TOPICS:** sensor_airflow +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorAirflow.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | --------- | ------------ | ---------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| speed | `float32` | | | the speed being reported by the wind / airflow sensor | +| direction | `float32` | | | the direction being reported by the wind / airflow sensor | +| status | `uint8` | | | Status code from the sensor | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorAirflow.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -10,5 +28,6 @@ uint32 device_id # unique device ID for the sensor that does not float32 speed # the speed being reported by the wind / airflow sensor float32 direction # the direction being reported by the wind / airflow sensor uint8 status # Status code from the sensor - ``` + +::: diff --git a/docs/en/msg_docs/SensorBaro.md b/docs/en/msg_docs/SensorBaro.md index ef4d7a8f28..22038554af 100644 --- a/docs/en/msg_docs/SensorBaro.md +++ b/docs/en/msg_docs/SensorBaro.md @@ -1,11 +1,38 @@ +--- +pageClass: is-wide-page +--- + # SensorBaro (UORB message) -Barometer sensor +Barometer sensor. This is populated by barometer drivers and used by the EKF2 estimator. The information is published in the `SCALED_PRESSURE_n` MAVLink messages (along with information from a corresponding `DifferentialPressure` instance). -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorBaro.msg) +**TOPICS:** sensor_baro + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | --------- | ------------ | ---------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time of publication (since system start) | +| timestamp_sample | `uint64` | us | | Time of raw data capture | +| device_id | `uint32` | | | Unique device ID for the sensor that does not change between power cycles | +| pressure | `float32` | Pa | | Static pressure measurement | +| temperature | `float32` | degC | | Temperature. | +| error_count | `uint32` | | | Number of errors detected by driver. | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | ------- | ----- | ----------- | +| ORB_QUEUE_LENGTH | `uint8` | 4 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorBaro.msg) + +::: details Click here to see original file ```c # Barometer sensor @@ -22,5 +49,6 @@ float32 temperature # [degC] Temperature. uint32 error_count # [-] Number of errors detected by driver. uint8 ORB_QUEUE_LENGTH = 4 - ``` + +::: diff --git a/docs/en/msg_docs/SensorCombined.md b/docs/en/msg_docs/SensorCombined.md index 29a22b6326..e04c3fcab4 100644 --- a/docs/en/msg_docs/SensorCombined.md +++ b/docs/en/msg_docs/SensorCombined.md @@ -1,10 +1,42 @@ +--- +pageClass: is-wide-page +--- + # SensorCombined (UORB message) -Sensor readings in SI-unit form. -These fields are scaled and offset-compensated where possible and do not -change with board revisions and sensor updates. +Sensor readings in SI-unit form. These fields are scaled and offset-compensated where possible and do not. change with board revisions and sensor updates. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorCombined.msg) +**TOPICS:** sensor_combined + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------------------- | ------------ | ------------ | ---------- | ----------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| gyro_rad | `float32[3]` | | | average angular rate measured in the FRD body frame XYZ-axis in rad/s over the last gyro sampling period | +| gyro_integral_dt | `uint32` | | | gyro measurement sampling period in microseconds | +| accelerometer_timestamp_relative | `int32` | | | timestamp + accelerometer_timestamp_relative = Accelerometer timestamp | +| accelerometer_m_s2 | `float32[3]` | | | average value acceleration measured in the FRD body frame XYZ-axis in m/s^2 over the last accelerometer sampling period | +| accelerometer_integral_dt | `uint32` | | | accelerometer measurement sampling period in microseconds | +| accelerometer_clipping | `uint8` | | | bitfield indicating if there was any accelerometer clipping (per axis) during the integration time frame | +| gyro_clipping | `uint8` | | | bitfield indicating if there was any gyro clipping (per axis) during the integration time frame | +| accel_calibration_count | `uint8` | | | Calibration changed counter. Monotonically increases whenever accelermeter calibration changes. | +| gyro_calibration_count | `uint8` | | | Calibration changed counter. Monotonically increases whenever rate gyro calibration changes. | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------------- | ------- | ---------- | ---------------------------------------------------------------------------------------------------------------------- | +| RELATIVE_TIMESTAMP_INVALID | `int32` | 2147483647 | (0x7fffffff) If one of the relative timestamps is set to this value, it means the associated sensor values are invalid | +| CLIPPING_X | `uint8` | 1 | +| CLIPPING_Y | `uint8` | 2 | +| CLIPPING_Z | `uint8` | 4 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorCombined.msg) + +::: details Click here to see original file ```c # Sensor readings in SI-unit form. @@ -32,5 +64,6 @@ uint8 gyro_clipping # bitfield indicating if there was any gyro clip uint8 accel_calibration_count # Calibration changed counter. Monotonically increases whenever accelermeter calibration changes. uint8 gyro_calibration_count # Calibration changed counter. Monotonically increases whenever rate gyro calibration changes. - ``` + +::: diff --git a/docs/en/msg_docs/SensorCorrection.md b/docs/en/msg_docs/SensorCorrection.md index 8c9cfbb9d2..649fbf5714 100644 --- a/docs/en/msg_docs/SensorCorrection.md +++ b/docs/en/msg_docs/SensorCorrection.md @@ -1,8 +1,48 @@ +--- +pageClass: is-wide-page +--- + # SensorCorrection (UORB message) -Sensor corrections in SI-unit form for the voted sensor +Sensor corrections in SI-unit form for the voted sensor. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorCorrection.msg) +**TOPICS:** sensor_correction + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------- | ------------ | ------------ | ---------- | ---------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| accel_device_ids | `uint32[4]` | | | +| accel_temperature | `float32[4]` | | | +| accel_offset_0 | `float32[3]` | | | accelerometer 0 offsets in the FRD board frame XYZ-axis in m/s^s | +| accel_offset_1 | `float32[3]` | | | accelerometer 1 offsets in the FRD board frame XYZ-axis in m/s^s | +| accel_offset_2 | `float32[3]` | | | accelerometer 2 offsets in the FRD board frame XYZ-axis in m/s^s | +| accel_offset_3 | `float32[3]` | | | accelerometer 3 offsets in the FRD board frame XYZ-axis in m/s^s | +| gyro_device_ids | `uint32[4]` | | | +| gyro_temperature | `float32[4]` | | | +| gyro_offset_0 | `float32[3]` | | | gyro 0 XYZ offsets in the sensor frame in rad/s | +| gyro_offset_1 | `float32[3]` | | | gyro 1 XYZ offsets in the sensor frame in rad/s | +| gyro_offset_2 | `float32[3]` | | | gyro 2 XYZ offsets in the sensor frame in rad/s | +| gyro_offset_3 | `float32[3]` | | | gyro 3 XYZ offsets in the sensor frame in rad/s | +| mag_device_ids | `uint32[4]` | | | +| mag_temperature | `float32[4]` | | | +| mag_offset_0 | `float32[3]` | | | magnetometer 0 offsets in the FRD board frame XYZ-axis in m/s^s | +| mag_offset_1 | `float32[3]` | | | magnetometer 1 offsets in the FRD board frame XYZ-axis in m/s^s | +| mag_offset_2 | `float32[3]` | | | magnetometer 2 offsets in the FRD board frame XYZ-axis in m/s^s | +| mag_offset_3 | `float32[3]` | | | magnetometer 3 offsets in the FRD board frame XYZ-axis in m/s^s | +| baro_device_ids | `uint32[4]` | | | +| baro_temperature | `float32[4]` | | | +| baro_offset_0 | `float32` | | | barometric pressure 0 offsets in the sensor frame in Pascals | +| baro_offset_1 | `float32` | | | barometric pressure 1 offsets in the sensor frame in Pascals | +| baro_offset_2 | `float32` | | | barometric pressure 2 offsets in the sensor frame in Pascals | +| baro_offset_3 | `float32` | | | barometric pressure 3 offsets in the sensor frame in Pascals | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorCorrection.msg) + +::: details Click here to see original file ```c # @@ -46,5 +86,6 @@ float32 baro_offset_0 # barometric pressure 0 offsets in the sensor frame in Pa float32 baro_offset_1 # barometric pressure 1 offsets in the sensor frame in Pascals float32 baro_offset_2 # barometric pressure 2 offsets in the sensor frame in Pascals float32 baro_offset_3 # barometric pressure 3 offsets in the sensor frame in Pascals - ``` + +::: diff --git a/docs/en/msg_docs/SensorGnssRelative.md b/docs/en/msg_docs/SensorGnssRelative.md index 639e7897f5..e00e872113 100644 --- a/docs/en/msg_docs/SensorGnssRelative.md +++ b/docs/en/msg_docs/SensorGnssRelative.md @@ -1,8 +1,44 @@ +--- +pageClass: is-wide-page +--- + # SensorGnssRelative (UORB message) GNSS relative positioning information in NED frame. The NED frame is defined as the local topological system at the reference station. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGnssRelative.msg) +**TOPICS:** sensor_gnssrelative + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------------- | ------------ | ------------ | ---------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | time since system start (microseconds) | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| time_utc_usec | `uint64` | | | Timestamp (microseconds, UTC), this is the timestamp which comes from the gps module. It might be unavailable right after cold start, indicated by a value of 0 | +| reference_station_id | `uint16` | | | Reference Station ID | +| position | `float32[3]` | | | GPS NED relative position vector (m) | +| position_accuracy | `float32[3]` | | | Accuracy of relative position (m) | +| heading | `float32` | | | Heading of the relative position vector (radians) | +| heading_accuracy | `float32` | | | Accuracy of heading of the relative position vector (radians) | +| position_length | `float32` | | | Length of the position vector (m) | +| accuracy_length | `float32` | | | Accuracy of the position length (m) | +| gnss_fix_ok | `bool` | | | GNSS valid fix (i.e within DOP & accuracy masks) | +| differential_solution | `bool` | | | differential corrections were applied | +| relative_position_valid | `bool` | | | +| carrier_solution_floating | `bool` | | | carrier phase range solution with floating ambiguities | +| carrier_solution_fixed | `bool` | | | carrier phase range solution with fixed ambiguities | +| moving_base_mode | `bool` | | | if the receiver is operating in moving base mode | +| reference_position_miss | `bool` | | | extrapolated reference position was used to compute moving base solution this epoch | +| reference_observations_miss | `bool` | | | extrapolated reference observations were used to compute moving base solution this epoch | +| heading_valid | `bool` | | | +| relative_position_normalized | `bool` | | | the components of the relative position vector (including the high-precision parts) are normalized | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGnssRelative.msg) + +::: details Click here to see original file ```c # GNSS relative positioning information in NED frame. The NED frame is defined as the local topological system at the reference station. @@ -35,5 +71,6 @@ bool reference_position_miss # extrapolated reference position was used to bool reference_observations_miss # extrapolated reference observations were used to compute moving base solution this epoch bool heading_valid bool relative_position_normalized # the components of the relative position vector (including the high-precision parts) are normalized - ``` + +::: diff --git a/docs/en/msg_docs/SensorGnssStatus.md b/docs/en/msg_docs/SensorGnssStatus.md index 70602b85fc..e4e40b948d 100644 --- a/docs/en/msg_docs/SensorGnssStatus.md +++ b/docs/en/msg_docs/SensorGnssStatus.md @@ -1,8 +1,30 @@ +--- +pageClass: is-wide-page +--- + # SensorGnssStatus (UORB message) -Gnss quality indicators +Gnss quality indicators. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGnssStatus.msg) +**TOPICS:** sensor_gnssstatus + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------------- | -------- | ------------ | ----------------------------------------------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| `bool` | | | Set to true if quality indicators are available | +| quality_corrections | `uint8` | | | Corrections quality from 0 to 10, or 255 if not available | +| quality_receiver | `uint8` | | | Overall receiver operating status from 0 to 10, or 255 if not available | +| quality_gnss_signals | `uint8` | | | Quality of GNSS signals from 0 to 10, or 255 if not available | +| quality_post_processing | `uint8` | | | Expected post processing quality from 0 to 10, or 255 if not available | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGnssStatus.msg) + +::: details Click here to see original file ```c # Gnss quality indicators @@ -15,5 +37,6 @@ uint8 quality_corrections # Corrections quality from 0 to 10, or 255 if no uint8 quality_receiver # Overall receiver operating status from 0 to 10, or 255 if not available uint8 quality_gnss_signals # Quality of GNSS signals from 0 to 10, or 255 if not available uint8 quality_post_processing # Expected post processing quality from 0 to 10, or 255 if not available - ``` + +::: diff --git a/docs/en/msg_docs/SensorGps.md b/docs/en/msg_docs/SensorGps.md index 1b5fb3cf41..4c8b3c58ab 100644 --- a/docs/en/msg_docs/SensorGps.md +++ b/docs/en/msg_docs/SensorGps.md @@ -1,9 +1,96 @@ +--- +pageClass: is-wide-page +--- + # SensorGps (UORB message) -GPS position in WGS84 coordinates. -the field 'timestamp' is for the position & velocity (microseconds) +GPS position in WGS84 coordinates. the field 'timestamp' is for the position & velocity (microseconds). -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg) +**TOPICS:** sensor_gps vehicle_gps_position + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------------- | --------- | ------------ | ---------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| latitude_deg | `float64` | | | Latitude in degrees, allows centimeter level RTK precision | +| longitude_deg | `float64` | | | Longitude in degrees, allows centimeter level RTK precision | +| altitude_msl_m | `float64` | | | Altitude above MSL, meters | +| altitude_ellipsoid_m | `float64` | | | Altitude above Ellipsoid, meters | +| s_variance_m_s | `float32` | | | GPS speed accuracy estimate, (metres/sec) | +| c_variance_rad | `float32` | | | GPS course accuracy estimate, (radians) | +| fix_type | `uint8` | | | Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. | +| eph | `float32` | | | GPS horizontal position accuracy (metres) | +| epv | `float32` | | | GPS vertical position accuracy (metres) | +| hdop | `float32` | | | Horizontal dilution of precision | +| vdop | `float32` | | | Vertical dilution of precision | +| noise_per_ms | `int32` | | | GPS noise per millisecond | +| automatic_gain_control | `uint16` | | | Automatic gain control monitor | +| jamming_state | `uint8` | | | indicates whether jamming has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Mitigated, 3: Detected | +| jamming_indicator | `int32` | | | indicates jamming is occurring | +| spoofing_state | `uint8` | | | indicates whether spoofing has been detected or suspected by the receivers. O: Unknown, 1: OK, 2: Mitigated, 3: Detected | +| authentication_state | `uint8` | | | GPS signal authentication state | +| vel_m_s | `float32` | | | GPS ground speed, (metres/sec) | +| vel_n_m_s | `float32` | | | GPS North velocity, (metres/sec) | +| vel_e_m_s | `float32` | | | GPS East velocity, (metres/sec) | +| vel_d_m_s | `float32` | | | GPS Down velocity, (metres/sec) | +| cog_rad | `float32` | | | Course over ground (NOT heading, but direction of movement), -PI..PI, (radians) | +| vel_ned_valid | `bool` | | | True if NED velocity is valid | +| timestamp_time_relative | `int32` | | | timestamp + timestamp_time_relative = Time of the UTC timestamp since system start, (microseconds) | +| time_utc_usec | `uint64` | | | Timestamp (microseconds, UTC), this is the timestamp which comes from the gps module. It might be unavailable right after cold start, indicated by a value of 0 | +| satellites_used | `uint8` | | | Number of satellites used | +| system_error | `uint32` | | | General errors with the connected GPS receiver | +| heading | `float32` | | | heading angle of XYZ body frame rel to NED. Set to NaN if not available and updated (used for dual antenna GPS), (rad, [-PI, PI]) | +| heading_offset | `float32` | | | heading offset of dual antenna array in body frame. Set to NaN if not applicable. (rad, [-PI, PI]) | +| heading_accuracy | `float32` | | | heading accuracy (rad, [0, 2PI]) | +| rtcm_injection_rate | `float32` | | | RTCM message injection rate Hz | +| selected_rtcm_instance | `uint8` | | | uorb instance that is being used for RTCM corrections | +| rtcm_crc_failed | `bool` | | | RTCM message CRC failure detected | +| rtcm_msg_used | `uint8` | | | Indicates if the RTCM message was used successfully by the receiver | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------------------- | -------- | ----- | ------------------------------------------ | +| FIX_TYPE_NONE | `uint8` | 1 | Value 0 is also valid to represent no fix. | +| FIX_TYPE_2D | `uint8` | 2 | +| FIX_TYPE_3D | `uint8` | 3 | +| FIX_TYPE_RTCM_CODE_DIFFERENTIAL | `uint8` | 4 | +| FIX_TYPE_RTK_FLOAT | `uint8` | 5 | +| FIX_TYPE_RTK_FIXED | `uint8` | 6 | +| FIX_TYPE_EXTRAPOLATED | `uint8` | 8 | +| JAMMING_STATE_UNKNOWN | `uint8` | 0 | default | +| JAMMING_STATE_OK | `uint8` | 1 | +| JAMMING_STATE_MITIGATED | `uint8` | 2 | +| JAMMING_STATE_DETECTED | `uint8` | 3 | +| SPOOFING_STATE_UNKNOWN | `uint8` | 0 | default | +| SPOOFING_STATE_OK | `uint8` | 1 | +| SPOOFING_STATE_MITIGATED | `uint8` | 2 | +| SPOOFING_STATE_DETECTED | `uint8` | 3 | +| AUTHENTICATION_STATE_UNKNOWN | `uint8` | 0 | default | +| AUTHENTICATION_STATE_INITIALIZING | `uint8` | 1 | +| AUTHENTICATION_STATE_ERROR | `uint8` | 2 | +| AUTHENTICATION_STATE_OK | `uint8` | 3 | +| AUTHENTICATION_STATE_DISABLED | `uint8` | 4 | +| SYSTEM_ERROR_OK | `uint32` | 0 | default | +| SYSTEM_ERROR_INCOMING_CORRECTIONS | `uint32` | 1 | +| SYSTEM_ERROR_CONFIGURATION | `uint32` | 2 | +| SYSTEM_ERROR_SOFTWARE | `uint32` | 4 | +| SYSTEM_ERROR_ANTENNA | `uint32` | 8 | +| SYSTEM_ERROR_EVENT_CONGESTION | `uint32` | 16 | +| SYSTEM_ERROR_CPU_OVERLOAD | `uint32` | 32 | +| SYSTEM_ERROR_OUTPUT_CONGESTION | `uint32` | 64 | +| RTCM_MSG_USED_UNKNOWN | `uint8` | 0 | +| RTCM_MSG_USED_NOT_USED | `uint8` | 1 | +| RTCM_MSG_USED_USED | `uint8` | 2 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg) + +::: details Click here to see original file ```c # GPS position in WGS84 coordinates. @@ -96,5 +183,6 @@ uint8 RTCM_MSG_USED_USED = 2 uint8 rtcm_msg_used # Indicates if the RTCM message was used successfully by the receiver # TOPICS sensor_gps vehicle_gps_position - ``` + +::: diff --git a/docs/en/msg_docs/SensorGyro.md b/docs/en/msg_docs/SensorGyro.md index d55d2f44c2..aea82546dd 100644 --- a/docs/en/msg_docs/SensorGyro.md +++ b/docs/en/msg_docs/SensorGyro.md @@ -1,8 +1,37 @@ +--- +pageClass: is-wide-page +--- + # SensorGyro (UORB message) +**TOPICS:** sensor_gyro +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGyro.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ---------- | ------------ | ---------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| x | `float32` | | | angular velocity in the FRD board frame X-axis in rad/s | +| y | `float32` | | | angular velocity in the FRD board frame Y-axis in rad/s | +| z | `float32` | | | angular velocity in the FRD board frame Z-axis in rad/s | +| temperature | `float32` | | | temperature in degrees Celsius | +| error_count | `uint32` | | | +| clip_counter | `uint8[3]` | | | clip count per axis in the sample period | +| samples | `uint8` | | | number of raw samples that went into this message | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | ------- | ----- | ----------- | +| ORB_QUEUE_LENGTH | `uint8` | 8 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGyro.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -23,5 +52,6 @@ uint8[3] clip_counter # clip count per axis in the sample period uint8 samples # number of raw samples that went into this message uint8 ORB_QUEUE_LENGTH = 8 - ``` + +::: diff --git a/docs/en/msg_docs/SensorGyroFft.md b/docs/en/msg_docs/SensorGyroFft.md index 279c2428ae..b3edd2e04c 100644 --- a/docs/en/msg_docs/SensorGyroFft.md +++ b/docs/en/msg_docs/SensorGyroFft.md @@ -1,8 +1,32 @@ +--- +pageClass: is-wide-page +--- + # SensorGyroFft (UORB message) +**TOPICS:** sensor_gyrofft +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGyroFft.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------------- | ------------ | ------------ | ---------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| sensor_sample_rate_hz | `float32` | | | +| resolution_hz | `float32` | | | +| peak_frequencies_x | `float32[3]` | | | x axis peak frequencies | +| peak_frequencies_y | `float32[3]` | | | y axis peak frequencies | +| peak_frequencies_z | `float32[3]` | | | z axis peak frequencies | +| peak_snr_x | `float32[3]` | | | x axis peak SNR | +| peak_snr_y | `float32[3]` | | | y axis peak SNR | +| peak_snr_z | `float32[3]` | | | z axis peak SNR | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGyroFft.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -20,5 +44,6 @@ float32[3] peak_frequencies_z # z axis peak frequencies float32[3] peak_snr_x # x axis peak SNR float32[3] peak_snr_y # y axis peak SNR float32[3] peak_snr_z # z axis peak SNR - ``` + +::: diff --git a/docs/en/msg_docs/SensorGyroFifo.md b/docs/en/msg_docs/SensorGyroFifo.md index 3de5eff4d8..34bf270e90 100644 --- a/docs/en/msg_docs/SensorGyroFifo.md +++ b/docs/en/msg_docs/SensorGyroFifo.md @@ -1,8 +1,36 @@ +--- +pageClass: is-wide-page +--- + # SensorGyroFifo (UORB message) +**TOPICS:** sensor_gyrofifo +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGyroFifo.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ----------- | ------------ | ---------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| dt | `float32` | | | delta time between samples (microseconds) | +| scale | `float32` | | | +| samples | `uint8` | | | number of valid samples | +| x | `int16[32]` | | | angular velocity in the FRD board frame X-axis in rad/s | +| y | `int16[32]` | | | angular velocity in the FRD board frame Y-axis in rad/s | +| z | `int16[32]` | | | angular velocity in the FRD board frame Z-axis in rad/s | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | ------- | ----- | ----------- | +| ORB_QUEUE_LENGTH | `uint8` | 4 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGyroFifo.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -20,5 +48,6 @@ int16[32] y # angular velocity in the FRD board frame Y-axis in ra int16[32] z # angular velocity in the FRD board frame Z-axis in rad/s uint8 ORB_QUEUE_LENGTH = 4 - ``` + +::: diff --git a/docs/en/msg_docs/SensorHygrometer.md b/docs/en/msg_docs/SensorHygrometer.md index 34bedf9ae9..0d86c2d9ba 100644 --- a/docs/en/msg_docs/SensorHygrometer.md +++ b/docs/en/msg_docs/SensorHygrometer.md @@ -1,8 +1,26 @@ +--- +pageClass: is-wide-page +--- + # SensorHygrometer (UORB message) +**TOPICS:** sensor_hygrometer +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorHygrometer.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | --------- | ------------ | ---------------------------------------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| `float32` | | | Temperature provided by sensor (Celsius) | +| humidity | `float32` | | | Humidity provided by sensor | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorHygrometer.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -13,5 +31,6 @@ uint32 device_id # unique device ID for the sensor that does not change float32 temperature # Temperature provided by sensor (Celsius) float32 humidity # Humidity provided by sensor - ``` + +::: diff --git a/docs/en/msg_docs/SensorMag.md b/docs/en/msg_docs/SensorMag.md index d574b95e1f..06f95d0fab 100644 --- a/docs/en/msg_docs/SensorMag.md +++ b/docs/en/msg_docs/SensorMag.md @@ -1,8 +1,35 @@ +--- +pageClass: is-wide-page +--- + # SensorMag (UORB message) +**TOPICS:** sensor_mag +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorMag.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | --------- | ------------ | ---------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| x | `float32` | | | magnetic field in the FRD board frame X-axis in Gauss | +| y | `float32` | | | magnetic field in the FRD board frame Y-axis in Gauss | +| z | `float32` | | | magnetic field in the FRD board frame Z-axis in Gauss | +| temperature | `float32` | | | temperature in degrees Celsius | +| error_count | `uint32` | | | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | ------- | ----- | ----------- | +| ORB_QUEUE_LENGTH | `uint8` | 4 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorMag.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -19,5 +46,6 @@ float32 temperature # temperature in degrees Celsius uint32 error_count uint8 ORB_QUEUE_LENGTH = 4 - ``` + +::: diff --git a/docs/en/msg_docs/SensorOpticalFlow.md b/docs/en/msg_docs/SensorOpticalFlow.md index d4ea32da34..bc0b36ddc4 100644 --- a/docs/en/msg_docs/SensorOpticalFlow.md +++ b/docs/en/msg_docs/SensorOpticalFlow.md @@ -1,8 +1,45 @@ +--- +pageClass: is-wide-page +--- + # SensorOpticalFlow (UORB message) +**TOPICS:** sensor_opticalflow +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorOpticalFlow.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------------- | ------------ | ------------ | ---------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| pixel_flow | `float32[2]` | | | (radians) optical flow in radians where a positive value is produced by a RH rotation of the sensor about the body axis | +| delta_angle | `float32[3]` | | | (radians) accumulated gyro radians where a positive value is produced by a RH rotation about the body axis. Set to NaN if flow sensor does not have 3-axis gyro data. | +| delta_angle_available | `bool` | | | +| distance_m | `float32` | | | (meters) Distance to the center of the flow field | +| distance_available | `bool` | | | +| integration_timespan_us | `uint32` | | | (microseconds) accumulation timespan in microseconds | +| quality | `uint8` | | | quality, 0: bad quality, 255: maximum quality | +| error_count | `uint32` | | | +| max_flow_rate | `float32` | | | (radians/s) Magnitude of maximum angular which the optical flow sensor can measure reliably | +| min_ground_distance | `float32` | | | (meters) Minimum distance from ground at which the optical flow sensor operates reliably | +| max_ground_distance | `float32` | | | (meters) Maximum distance from ground at which the optical flow sensor operates reliably | +| mode | `uint8` | | | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------------- | ------- | ----- | ----------- | +| MODE_UNKNOWN | `uint8` | 0 | +| MODE_BRIGHT | `uint8` | 1 | +| MODE_LOWLIGHT | `uint8` | 2 | +| MODE_SUPER_LOWLIGHT | `uint8` | 3 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorOpticalFlow.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -35,5 +72,6 @@ uint8 MODE_LOWLIGHT = 2 uint8 MODE_SUPER_LOWLIGHT = 3 uint8 mode - ``` + +::: diff --git a/docs/en/msg_docs/SensorPreflightMag.md b/docs/en/msg_docs/SensorPreflightMag.md index 7d5a933bc7..a5eba92824 100644 --- a/docs/en/msg_docs/SensorPreflightMag.md +++ b/docs/en/msg_docs/SensorPreflightMag.md @@ -1,9 +1,25 @@ +--- +pageClass: is-wide-page +--- + # SensorPreflightMag (UORB message) -Pre-flight sensor check metrics. -The topic will not be updated when the vehicle is armed +Pre-flight sensor check metrics. The topic will not be updated when the vehicle is armed. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorPreflightMag.msg) +**TOPICS:** sensor_preflightmag + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------------- | --------- | ------------ | ---------- | --------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| mag_inconsistency_angle | `float32` | | | maximum angle between magnetometer instance field vectors in radians. | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorPreflightMag.msg) + +::: details Click here to see original file ```c # @@ -13,5 +29,6 @@ The topic will not be updated when the vehicle is armed uint64 timestamp # time since system start (microseconds) float32 mag_inconsistency_angle # maximum angle between magnetometer instance field vectors in radians. - ``` + +::: diff --git a/docs/en/msg_docs/SensorSelection.md b/docs/en/msg_docs/SensorSelection.md index 58fb6be289..d2f0ee5546 100644 --- a/docs/en/msg_docs/SensorSelection.md +++ b/docs/en/msg_docs/SensorSelection.md @@ -1,9 +1,26 @@ +--- +pageClass: is-wide-page +--- + # SensorSelection (UORB message) -Sensor ID's for the voted sensors output on the sensor_combined topic. -Will be updated on startup of the sensor module and when sensor selection changes +Sensor ID's for the voted sensors output on the sensor_combined topic. Will be updated on startup of the sensor module and when sensor selection changes. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorSelection.msg) +**TOPICS:** sensor_selection + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------- | -------- | ------------ | ---------- | ------------------------------------------------ | +| timestamp | `uint64` | | | time since system start (microseconds) | +| accel_device_id | `uint32` | | | unique device ID for the selected accelerometers | +| gyro_device_id | `uint32` | | | unique device ID for the selected rate gyros | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorSelection.msg) + +::: details Click here to see original file ```c # @@ -13,5 +30,6 @@ Will be updated on startup of the sensor module and when sensor selection change uint64 timestamp # time since system start (microseconds) uint32 accel_device_id # unique device ID for the selected accelerometers uint32 gyro_device_id # unique device ID for the selected rate gyros - ``` + +::: diff --git a/docs/en/msg_docs/SensorTemp.md b/docs/en/msg_docs/SensorTemp.md index 5ed50541fe..8c68e73dd9 100644 --- a/docs/en/msg_docs/SensorTemp.md +++ b/docs/en/msg_docs/SensorTemp.md @@ -1,11 +1,30 @@ +--- +pageClass: is-wide-page +--- + # SensorTemp (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorTemp.msg) +**TOPICS:** sensor_temp + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------- | -------- | ------------ | ---------------------------------------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| `float32` | | | Temperature provided by sensor (Celsius) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorTemp.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) uint32 device_id # unique device ID for the sensor that does not change between power cycles float32 temperature # Temperature provided by sensor (Celsius) - ``` + +::: diff --git a/docs/en/msg_docs/SensorUwb.md b/docs/en/msg_docs/SensorUwb.md index 544bc60e7a..afd888517a 100644 --- a/docs/en/msg_docs/SensorUwb.md +++ b/docs/en/msg_docs/SensorUwb.md @@ -1,9 +1,44 @@ +--- +pageClass: is-wide-page +--- + # SensorUwb (UORB message) -UWB distance contains the distance information measured by an ultra-wideband positioning system, -such as Pozyx or NXP Rddrone. +UWB distance contains the distance information measured by an ultra-wideband positioning system,. such as Pozyx or NXP Rddrone. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorUwb.msg) +**TOPICS:** sensor_uwb + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------- | --------- | ------------ | ---------- | ----------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| sessionid | `uint32` | | | UWB SessionID | +| time_offset | `uint32` | | | Time between Ranging Rounds in ms | +| counter | `uint32` | | | Number of Ranges since last Start of Ranging | +| mac | `uint16` | | | MAC adress of Initiator (controller) | +| mac_dest | `uint16` | | | MAC adress of Responder (Controlee) | +| status | `uint16` | | | status feedback # | +| nlos | `uint8` | | | None line of site condition y/n | +| distance | `float32` | | | distance in m to the UWB receiver | +| aoa_azimuth_dev | `float32` | | | Angle of arrival of first incomming RX msg | +| aoa_elevation_dev | `float32` | | | Angle of arrival of first incomming RX msg | +| aoa_azimuth_resp | `float32` | | | Angle of arrival of first incomming RX msg at the responder | +| aoa_elevation_resp | `float32` | | | Angle of arrival of first incomming RX msg at the responder | +| aoa_azimuth_fom | `uint8` | | | AOA Azimuth FOM | +| aoa_elevation_fom | `uint8` | | | AOA Elevation FOM | +| aoa_dest_azimuth_fom | `uint8` | | | AOA Azimuth FOM | +| aoa_dest_elevation_fom | `uint8` | | | AOA Elevation FOM | +| orientation | `uint8` | | | Direction the sensor faces from MAV_SENSOR_ORIENTATION enum | +| offset_x | `float32` | | | UWB initiator offset in X axis (NED drone frame) | +| offset_y | `float32` | | | UWB initiator offset in Y axis (NED drone frame) | +| offset_z | `float32` | | | UWB initiator offset in Z axis (NED drone frame) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorUwb.msg) + +::: details Click here to see original file ```c # UWB distance contains the distance information measured by an ultra-wideband positioning system, @@ -40,5 +75,6 @@ uint8 orientation # Direction the sensor faces from MAV_SENSOR_ORIENTATION enum float32 offset_x # UWB initiator offset in X axis (NED drone frame) float32 offset_y # UWB initiator offset in Y axis (NED drone frame) float32 offset_z # UWB initiator offset in Z axis (NED drone frame) - ``` + +::: diff --git a/docs/en/msg_docs/SensorsStatus.md b/docs/en/msg_docs/SensorsStatus.md index 996d7107fb..cdac839723 100644 --- a/docs/en/msg_docs/SensorsStatus.md +++ b/docs/en/msg_docs/SensorsStatus.md @@ -1,8 +1,31 @@ +--- +pageClass: is-wide-page +--- + # SensorsStatus (UORB message) Sensor check metrics. This will be zero for a sensor that's primary or unpopulated. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorsStatus.msg) +**TOPICS:** sensors_status_baro sensors_status_mag + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------- | ------------ | ------------ | ---------- | -------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| device_id_primary | `uint32` | | | current primary device id for reference | +| device_ids | `uint32[4]` | | | +| inconsistency | `float32[4]` | | | magnitude of difference between sensor instance and mean | +| healthy | `bool[4]` | | | sensor healthy | +| priority | `uint8[4]` | | | +| enabled | `bool[4]` | | | +| external | `bool[4]` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorsStatus.msg) + +::: details Click here to see original file ```c # @@ -20,5 +43,6 @@ bool[4] enabled bool[4] external # TOPICS sensors_status_baro sensors_status_mag - ``` + +::: diff --git a/docs/en/msg_docs/SensorsStatusImu.md b/docs/en/msg_docs/SensorsStatusImu.md index a25b5d1c01..13b2b2420b 100644 --- a/docs/en/msg_docs/SensorsStatusImu.md +++ b/docs/en/msg_docs/SensorsStatusImu.md @@ -1,8 +1,34 @@ +--- +pageClass: is-wide-page +--- + # SensorsStatusImu (UORB message) Sensor check metrics. This will be zero for a sensor that's primary or unpopulated. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorsStatusImu.msg) +**TOPICS:** sensors_statusimu + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------------- | ------------ | ------------ | ---------- | ------------------------------------------------------------------------------ | +| timestamp | `uint64` | | | time since system start (microseconds) | +| accel_device_id_primary | `uint32` | | | current primary accel device id for reference | +| accel_device_ids | `uint32[4]` | | | +| accel_inconsistency_m_s_s | `float32[4]` | | | magnitude of acceleration difference between IMU instance and mean in m/s^2. | +| accel_healthy | `bool[4]` | | | +| accel_priority | `uint8[4]` | | | +| gyro_device_id_primary | `uint32` | | | current primary gyro device id for reference | +| gyro_device_ids | `uint32[4]` | | | +| gyro_inconsistency_rad_s | `float32[4]` | | | magnitude of angular rate difference between IMU instance and mean in (rad/s). | +| gyro_healthy | `bool[4]` | | | +| gyro_priority | `uint8[4]` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorsStatusImu.msg) + +::: details Click here to see original file ```c # @@ -23,5 +49,6 @@ uint32[4] gyro_device_ids float32[4] gyro_inconsistency_rad_s # magnitude of angular rate difference between IMU instance and mean in (rad/s). bool[4] gyro_healthy uint8[4] gyro_priority - ``` + +::: diff --git a/docs/en/msg_docs/SystemPower.md b/docs/en/msg_docs/SystemPower.md index c33cffca77..2fe83124d2 100644 --- a/docs/en/msg_docs/SystemPower.md +++ b/docs/en/msg_docs/SystemPower.md @@ -1,8 +1,48 @@ +--- +pageClass: is-wide-page +--- + # SystemPower (UORB message) +**TOPICS:** system_power +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SystemPower.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------ | ------------ | ------------ | ---------- | --------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| voltage5v_v | `float32` | | | peripheral 5V rail voltage | +| voltage_payload_v | `float32` | | | payload rail voltage | +| sensors3v3 | `float32[4]` | | | Sensors 3V3 rail voltage | +| sensors3v3_valid | `uint8` | | | Sensors 3V3 rail voltage was read (bitfield). | +| usb_connected | `uint8` | | | USB is connected when 1 | +| brick_valid | `uint8` | | | brick bits power is good when bit 1 | +| usb_valid | `uint8` | | | USB is valid when 1 | +| servo_valid | `uint8` | | | servo power is good when 1 | +| periph_5v_oc | `uint8` | | | peripheral overcurrent when 1 | +| hipower_5v_oc | `uint8` | | | high power peripheral overcurrent when 1 | +| comp_5v_valid | `uint8` | | | 5V to companion valid | +| can1_gps1_5v_valid | `uint8` | | | 5V for CAN1/GPS1 valid | +| payload_v_valid | `uint8` | | | payload rail voltage is valid | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------------- | ------- | ----- | ----------- | +| BRICK1_VALID_SHIFTS | `uint8` | 0 | +| BRICK1_VALID_MASK | `uint8` | 1 | +| BRICK2_VALID_SHIFTS | `uint8` | 1 | +| BRICK2_VALID_MASK | `uint8` | 2 | +| BRICK3_VALID_SHIFTS | `uint8` | 2 | +| BRICK3_VALID_MASK | `uint8` | 4 | +| BRICK4_VALID_SHIFTS | `uint8` | 3 | +| BRICK4_VALID_MASK | `uint8` | 8 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SystemPower.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -28,5 +68,6 @@ uint8 BRICK3_VALID_SHIFTS=2 uint8 BRICK3_VALID_MASK=4 uint8 BRICK4_VALID_SHIFTS=3 uint8 BRICK4_VALID_MASK=8 - ``` + +::: diff --git a/docs/en/msg_docs/TakeoffStatus.md b/docs/en/msg_docs/TakeoffStatus.md index 45540a74b4..8567effe40 100644 --- a/docs/en/msg_docs/TakeoffStatus.md +++ b/docs/en/msg_docs/TakeoffStatus.md @@ -1,8 +1,37 @@ +--- +pageClass: is-wide-page +--- + # TakeoffStatus (UORB message) -Status of the takeoff state machine currently just available for multicopters +Status of the takeoff state machine currently just available for multicopters. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TakeoffStatus.msg) +**TOPICS:** takeoff_status + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------- | --------- | ------------ | ---------- | ------------------------------------------------------------------------ | +| timestamp | `uint64` | | | time since system start (microseconds) | +| takeoff_state | `uint8` | | | +| tilt_limit | `float32` | | | limited tilt feasibility during takeoff, contains maximum tilt otherwise | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------------------------------------- | ------- | ----- | ----------- | +| TAKEOFF_STATE_UNINITIALIZED | `uint8` | 0 | +| TAKEOFF_STATE_DISARMED | `uint8` | 1 | +| TAKEOFF_STATE_SPOOLUP | `uint8` | 2 | +| TAKEOFF_STATE_READY_FOR_TAKEOFF | `uint8` | 3 | +| TAKEOFF_STATE_RAMPUP | `uint8` | 4 | +| TAKEOFF_STATE_FLIGHT | `uint8` | 5 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TakeoffStatus.msg) + +::: details Click here to see original file ```c # Status of the takeoff state machine currently just available for multicopters @@ -19,5 +48,6 @@ uint8 TAKEOFF_STATE_FLIGHT = 5 uint8 takeoff_state float32 tilt_limit # limited tilt feasibility during takeoff, contains maximum tilt otherwise - ``` + +::: diff --git a/docs/en/msg_docs/TaskStackInfo.md b/docs/en/msg_docs/TaskStackInfo.md index fde6ed7585..3ffa39b3bb 100644 --- a/docs/en/msg_docs/TaskStackInfo.md +++ b/docs/en/msg_docs/TaskStackInfo.md @@ -1,8 +1,32 @@ +--- +pageClass: is-wide-page +--- + # TaskStackInfo (UORB message) -stack information for a single running process +stack information for a single running process. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TaskStackInfo.msg) +**TOPICS:** task_stackinfo + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------- | ---------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| stack_free | `uint16` | | | +| task_name | `char[24]` | | | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | ------- | ----- | ----------- | +| ORB_QUEUE_LENGTH | `uint8` | 2 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TaskStackInfo.msg) + +::: details Click here to see original file ```c # stack information for a single running process @@ -13,5 +37,6 @@ uint16 stack_free char[24] task_name uint8 ORB_QUEUE_LENGTH = 2 - ``` + +::: diff --git a/docs/en/msg_docs/TecsStatus.md b/docs/en/msg_docs/TecsStatus.md index 96643b3d44..a225729f52 100644 --- a/docs/en/msg_docs/TecsStatus.md +++ b/docs/en/msg_docs/TecsStatus.md @@ -1,8 +1,46 @@ +--- +pageClass: is-wide-page +--- + # TecsStatus (UORB message) +**TOPICS:** tecs_status +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TecsStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------------- | --------- | ------------ | ---------- | -------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| altitude_sp | `float32` | | | Altitude setpoint AMSL [m] | +| altitude_reference | `float32` | | | Altitude setpoint reference AMSL [m] | +| altitude_time_constant | `float32` | | | Time constant of the altitude tracker [s] | +| height_rate_reference | `float32` | | | Height rate setpoint reference [m/s] | +| height_rate_direct | `float32` | | | Direct height rate setpoint from velocity reference generator [m/s] | +| height_rate_setpoint | `float32` | | | Height rate setpoint [m/s] | +| height_rate | `float32` | | | Height rate [m/s] | +| equivalent_airspeed_sp | `float32` | | | Equivalent airspeed setpoint [m/s] | +| true_airspeed_sp | `float32` | | | True airspeed setpoint [m/s] | +| true_airspeed_filtered | `float32` | | | True airspeed filtered [m/s] | +| true_airspeed_derivative_sp | `float32` | | | True airspeed derivative setpoint [m/s^2] | +| true_airspeed_derivative | `float32` | | | True airspeed derivative [m/s^2] | +| true_airspeed_derivative_raw | `float32` | | | True airspeed derivative raw [m/s^2] | +| total_energy_rate_sp | `float32` | | | Total energy rate setpoint [m^2/s^3] | +| total_energy_rate | `float32` | | | Total energy rate estimate [m^2/s^3] | +| total_energy_balance_rate_sp | `float32` | | | Energy balance rate setpoint [m^2/s^3] | +| total_energy_balance_rate | `float32` | | | Energy balance rate estimate [m^2/s^3] | +| throttle_integ | `float32` | | | Throttle integrator value [-] | +| pitch_integ | `float32` | | | Pitch integrator value [rad] | +| throttle_sp | `float32` | | | Current throttle setpoint [-] | +| pitch_sp_rad | `float32` | | | Current pitch setpoint [rad] | +| throttle_trim | `float32` | | | estimated throttle value [0,1] required to fly level at equivalent_airspeed_sp in the current atmospheric conditions | +| underspeed_ratio | `float32` | | | 0: no underspeed, 1: maximal underspeed. Controller takes measures to avoid stall proportional to ratio if >0. | +| fast_descend_ratio | `float32` | | | value indicating if fast descend mode is enabled with ramp up and ramp down [0-1] | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TecsStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -36,5 +74,6 @@ float32 throttle_trim # estimated throttle value [0,1] required to fly level a float32 underspeed_ratio # 0: no underspeed, 1: maximal underspeed. Controller takes measures to avoid stall proportional to ratio if >0. float32 fast_descend_ratio # value indicating if fast descend mode is enabled with ramp up and ramp down [0-1] - ``` + +::: diff --git a/docs/en/msg_docs/TelemetryStatus.md b/docs/en/msg_docs/TelemetryStatus.md index 87ca267be6..011293bf23 100644 --- a/docs/en/msg_docs/TelemetryStatus.md +++ b/docs/en/msg_docs/TelemetryStatus.md @@ -1,8 +1,70 @@ +--- +pageClass: is-wide-page +--- + # TelemetryStatus (UORB message) +**TOPICS:** telemetry_status +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TelemetryStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------------------------- | --------- | ------------ | ---------- | ----------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| type | `uint8` | | | type of the radio hardware (LINK*TYPE*\*) | +| mode | `uint8` | | | +| flow_control | `bool` | | | +| forwarding | `bool` | | | +| mavlink_v2 | `bool` | | | +| ftp | `bool` | | | +| streams | `uint8` | | | +| data_rate | `float32` | | | configured maximum data rate (Bytes/s) | +| rate_multiplier | `float32` | | | +| tx_rate_avg | `float32` | | | transmit rate average (Bytes/s) | +| tx_error_rate_avg | `float32` | | | transmit error rate average (Bytes/s) | +| tx_message_count | `uint32` | | | total message sent count | +| tx_buffer_overruns | `uint32` | | | number of TX buffer overruns | +| rx_rate_avg | `float32` | | | transmit rate average (Bytes/s) | +| rx_message_count | `uint32` | | | count of total messages received | +| rx_message_lost_count | `uint32` | | | +| rx_buffer_overruns | `uint32` | | | number of RX buffer overruns | +| rx_parse_errors | `uint32` | | | number of parse errors | +| rx_packet_drop_count | `uint32` | | | number of packet drops | +| rx_message_lost_rate | `float32` | | | +| heartbeat_type_antenna_tracker | `bool` | | | MAV_TYPE_ANTENNA_TRACKER | +| heartbeat_type_gcs | `bool` | | | MAV_TYPE_GCS | +| heartbeat_type_onboard_controller | `bool` | | | MAV_TYPE_ONBOARD_CONTROLLER | +| heartbeat_type_gimbal | `bool` | | | MAV_TYPE_GIMBAL | +| heartbeat_type_adsb | `bool` | | | MAV_TYPE_ADSB | +| heartbeat_type_camera | `bool` | | | MAV_TYPE_CAMERA | +| heartbeat_type_parachute | `bool` | | | MAV_TYPE_PARACHUTE | +| heartbeat_type_open_drone_id | `bool` | | | MAV_TYPE_ODID | +| heartbeat_component_telemetry_radio | `bool` | | | MAV_COMP_ID_TELEMETRY_RADIO | +| heartbeat_component_log | `bool` | | | MAV_COMP_ID_LOG | +| heartbeat_component_osd | `bool` | | | MAV_COMP_ID_OSD | +| heartbeat_component_vio | `bool` | | | MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY | +| heartbeat_component_pairing_manager | `bool` | | | MAV_COMP_ID_PAIRING_MANAGER | +| heartbeat_component_udp_bridge | `bool` | | | MAV_COMP_ID_UDP_BRIDGE | +| heartbeat_component_uart_bridge | `bool` | | | MAV_COMP_ID_UART_BRIDGE | +| open_drone_id_system_healthy | `bool` | | | +| parachute_system_healthy | `bool` | | | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------------------------- | -------- | ------- | ----------------------------------------------- | +| LINK_TYPE_GENERIC | `uint8` | 0 | +| LINK_TYPE_UBIQUITY_BULLET | `uint8` | 1 | +| LINK_TYPE_WIRE | `uint8` | 2 | +| LINK_TYPE_USB | `uint8` | 3 | +| LINK_TYPE_IRIDIUM | `uint8` | 4 | +| HEARTBEAT_TIMEOUT_US | `uint64` | 2500000 | Heartbeat timeout (tolerate missing 1 + jitter) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TelemetryStatus.msg) + +::: details Click here to see original file ```c uint8 LINK_TYPE_GENERIC = 0 @@ -66,5 +128,6 @@ bool heartbeat_component_uart_bridge # MAV_COMP_ID_UART_BRIDGE # Misc component health bool open_drone_id_system_healthy bool parachute_system_healthy - ``` + +::: diff --git a/docs/en/msg_docs/TiltrotorExtraControls.md b/docs/en/msg_docs/TiltrotorExtraControls.md index 80a1bd7ac1..d5be191d3c 100644 --- a/docs/en/msg_docs/TiltrotorExtraControls.md +++ b/docs/en/msg_docs/TiltrotorExtraControls.md @@ -1,13 +1,30 @@ +--- +pageClass: is-wide-page +--- + # TiltrotorExtraControls (UORB message) +**TOPICS:** tiltrotor_extracontrols +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TiltrotorExtraControls.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------------------------- | --------- | ------------ | ---------- | ------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| collective_tilt_normalized_setpoint | `float32` | | | Collective tilt angle of motors of tiltrotor, 0: vertical, 1: horizontal [0, 1] | +| collective_thrust_normalized_setpoint | `float32` | | | Collective thrust setpoint [0, 1] | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TiltrotorExtraControls.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) float32 collective_tilt_normalized_setpoint # Collective tilt angle of motors of tiltrotor, 0: vertical, 1: horizontal [0, 1] float32 collective_thrust_normalized_setpoint # Collective thrust setpoint [0, 1] - ``` + +::: diff --git a/docs/en/msg_docs/TimesyncStatus.md b/docs/en/msg_docs/TimesyncStatus.md index 2488b8c577..7344f7c5b8 100644 --- a/docs/en/msg_docs/TimesyncStatus.md +++ b/docs/en/msg_docs/TimesyncStatus.md @@ -1,8 +1,35 @@ +--- +pageClass: is-wide-page +--- + # TimesyncStatus (UORB message) +**TOPICS:** timesync_status +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TimesyncStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | -------- | ------------ | ---------- | -------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| source_protocol | `uint8` | | | timesync source | +| remote_timestamp | `uint64` | | | remote system timestamp (microseconds) | +| observed_offset | `int64` | | | raw time offset directly observed from this timesync packet (microseconds) | +| estimated_offset | `int64` | | | smoothed time offset between companion system and PX4 (microseconds) | +| round_trip_time | `uint32` | | | round trip time of this timesync packet (microseconds) | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------- | ------- | ----- | ----------- | +| SOURCE_PROTOCOL_UNKNOWN | `uint8` | 0 | +| SOURCE_PROTOCOL_MAVLINK | `uint8` | 1 | +| SOURCE_PROTOCOL_DDS | `uint8` | 2 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TimesyncStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -16,5 +43,6 @@ uint64 remote_timestamp # remote system timestamp (microseconds) int64 observed_offset # raw time offset directly observed from this timesync packet (microseconds) int64 estimated_offset # smoothed time offset between companion system and PX4 (microseconds) uint32 round_trip_time # round trip time of this timesync packet (microseconds) - ``` + +::: diff --git a/docs/en/msg_docs/TrajectorySetpoint.md b/docs/en/msg_docs/TrajectorySetpoint.md index 06e44bcf11..a778ddcf0b 100644 --- a/docs/en/msg_docs/TrajectorySetpoint.md +++ b/docs/en/msg_docs/TrajectorySetpoint.md @@ -1,11 +1,36 @@ +--- +pageClass: is-wide-page +--- + # TrajectorySetpoint (UORB message) -Trajectory setpoint in NED frame -Input to PID position controller. -Needs to be kinematically consistent and feasible for smooth flight. -setting a value to NaN means the state should not be controlled +Trajectory setpoint in NED frame. Input to PID position controller. Needs to be kinematically consistent and feasible for smooth flight. setting a value to NaN means the state should not be controlled. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/TrajectorySetpoint.msg) +**TOPICS:** trajectory_setpoint + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------ | ------------ | ------------ | ---------- | ---------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| position | `float32[3]` | | | in meters | +| velocity | `float32[3]` | | | in meters/second | +| acceleration | `float32[3]` | | | in meters/second^2 | +| jerk | `float32[3]` | | | in meters/second^3 (for logging only) | +| yaw | `float32` | | | euler angle of desired attitude in radians -PI..+PI | +| yawspeed | `float32` | | | angular velocity around NED frame z-axis in radians/second | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/TrajectorySetpoint.msg) + +::: details Click here to see original file ```c # Trajectory setpoint in NED frame @@ -25,5 +50,6 @@ float32[3] jerk # in meters/second^3 (for logging only) float32 yaw # euler angle of desired attitude in radians -PI..+PI float32 yawspeed # angular velocity around NED frame z-axis in radians/second - ``` + +::: diff --git a/docs/en/msg_docs/TrajectorySetpoint6dof.md b/docs/en/msg_docs/TrajectorySetpoint6dof.md index f2629e19c4..4b6b4e820c 100644 --- a/docs/en/msg_docs/TrajectorySetpoint6dof.md +++ b/docs/en/msg_docs/TrajectorySetpoint6dof.md @@ -1,9 +1,30 @@ +--- +pageClass: is-wide-page +--- + # TrajectorySetpoint6dof (UORB message) -Trajectory setpoint in NED frame -Input to position controller. +Trajectory setpoint in NED frame. Input to position controller. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TrajectorySetpoint6dof.msg) +**TOPICS:** trajectory_setpoint6dof + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ------------ | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| position | `float32[3]` | | | in meters | +| velocity | `float32[3]` | | | in meters/second | +| acceleration | `float32[3]` | | | in meters/second^2 | +| jerk | `float32[3]` | | | in meters/second^3 (for logging only) | +| quaternion | `float32[4]` | | | unit quaternion | +| angular_velocity | `float32[3]` | | | angular velocity in radians/second | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TrajectorySetpoint6dof.msg) + +::: details Click here to see original file ```c # Trajectory setpoint in NED frame @@ -19,5 +40,6 @@ float32[3] jerk # in meters/second^3 (for logging only) float32[4] quaternion # unit quaternion float32[3] angular_velocity # angular velocity in radians/second - ``` + +::: diff --git a/docs/en/msg_docs/TransponderReport.md b/docs/en/msg_docs/TransponderReport.md index 9bab882b02..6d1aba922f 100644 --- a/docs/en/msg_docs/TransponderReport.md +++ b/docs/en/msg_docs/TransponderReport.md @@ -1,6 +1,70 @@ +--- +pageClass: is-wide-page +--- + # TransponderReport (UORB message) -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TransponderReport.msg) +**TOPICS:** transponder_report + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------- | ----------- | ------------ | ---------- | -------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| icao_address | `uint32` | | | ICAO address | +| lat | `float64` | | | Latitude, expressed as degrees | +| lon | `float64` | | | Longitude, expressed as degrees | +| altitude_type | `uint8` | | | Type from ADSB_ALTITUDE_TYPE enum | +| altitude | `float32` | | | Altitude(ASL) in meters | +| heading | `float32` | | | Course over ground in radians, 0 to 2pi, 0 is north | +| hor_velocity | `float32` | | | The horizontal velocity in m/s | +| ver_velocity | `float32` | | | The vertical velocity in m/s, positive is up | +| callsign | `char[9]` | | | The callsign, 8+null | +| emitter_type | `uint8` | | | Type from ADSB_EMITTER_TYPE enum | +| tslc | `uint8` | | | Time since last communication in seconds | +| flags | `uint16` | | | Flags to indicate various statuses including valid data fields | +| squawk | `uint16` | | | Squawk code | +| uas_id | `uint8[18]` | | | Unique UAS ID | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------------------------------- | -------- | ----- | ----------- | +| PX4_ADSB_FLAGS_VALID_COORDS | `uint16` | 1 | +| PX4_ADSB_FLAGS_VALID_ALTITUDE | `uint16` | 2 | +| PX4_ADSB_FLAGS_VALID_HEADING | `uint16` | 4 | +| PX4_ADSB_FLAGS_VALID_VELOCITY | `uint16` | 8 | +| PX4_ADSB_FLAGS_VALID_CALLSIGN | `uint16` | 16 | +| PX4_ADSB_FLAGS_VALID_SQUAWK | `uint16` | 32 | +| PX4_ADSB_FLAGS_RETRANSLATE | `uint16` | 256 | +| ADSB_EMITTER_TYPE_NO_INFO | `uint16` | 0 | +| ADSB_EMITTER_TYPE_LIGHT | `uint16` | 1 | +| ADSB_EMITTER_TYPE_SMALL | `uint16` | 2 | +| ADSB_EMITTER_TYPE_LARGE | `uint16` | 3 | +| ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE | `uint16` | 4 | +| ADSB_EMITTER_TYPE_HEAVY | `uint16` | 5 | +| ADSB_EMITTER_TYPE_HIGHLY_MANUV | `uint16` | 6 | +| ADSB_EMITTER_TYPE_ROTOCRAFT | `uint16` | 7 | +| ADSB_EMITTER_TYPE_UNASSIGNED | `uint16` | 8 | +| ADSB_EMITTER_TYPE_GLIDER | `uint16` | 9 | +| ADSB_EMITTER_TYPE_LIGHTER_AIR | `uint16` | 10 | +| ADSB_EMITTER_TYPE_PARACHUTE | `uint16` | 11 | +| ADSB_EMITTER_TYPE_ULTRA_LIGHT | `uint16` | 12 | +| ADSB_EMITTER_TYPE_UNASSIGNED2 | `uint16` | 13 | +| ADSB_EMITTER_TYPE_UAV | `uint16` | 14 | +| ADSB_EMITTER_TYPE_SPACE | `uint16` | 15 | +| ADSB_EMITTER_TYPE_UNASSGINED3 | `uint16` | 16 | +| ADSB_EMITTER_TYPE_EMERGENCY_SURFACE | `uint16` | 17 | +| ADSB_EMITTER_TYPE_SERVICE_SURFACE | `uint16` | 18 | +| ADSB_EMITTER_TYPE_POINT_OBSTACLE | `uint16` | 19 | +| ADSB_EMITTER_TYPE_ENUM_END | `uint16` | 20 | +| ORB_QUEUE_LENGTH | `uint8` | 16 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TransponderReport.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -53,5 +117,6 @@ uint16 ADSB_EMITTER_TYPE_POINT_OBSTACLE=19 uint16 ADSB_EMITTER_TYPE_ENUM_END=20 uint8 ORB_QUEUE_LENGTH = 16 - ``` + +::: diff --git a/docs/en/msg_docs/TuneControl.md b/docs/en/msg_docs/TuneControl.md index b6e96771ad..25a79645d4 100644 --- a/docs/en/msg_docs/TuneControl.md +++ b/docs/en/msg_docs/TuneControl.md @@ -1,9 +1,60 @@ +--- +pageClass: is-wide-page +--- + # TuneControl (UORB message) -This message is used to control the tunes, when the tune_id is set to CUSTOM -then the frequency, duration are used otherwise those values are ignored. +This message is used to control the tunes, when the tune_id is set to CUSTOM. then the frequency, duration are used otherwise those values are ignored. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TuneControl.msg) +**TOPICS:** tune_control + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------- | -------- | ------------ | ---------- | --------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| tune_id | `uint8` | | | tune_id corresponding to TuneID::\* from the tune_defaults.h in the tunes library | +| tune_override | `bool` | | | if true the tune which is playing will be stopped and the new started | +| frequency | `uint16` | | | in Hz | +| duration | `uint32` | | | in us | +| silence | `uint32` | | | in us | +| volume | `uint8` | | | value between 0-100 if supported by backend | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------------------------------- | ------- | ----- | ----------- | +| TUNE_ID_STOP | `uint8` | 0 | +| TUNE_ID_STARTUP | `uint8` | 1 | +| TUNE_ID_ERROR | `uint8` | 2 | +| TUNE_ID_NOTIFY_POSITIVE | `uint8` | 3 | +| TUNE_ID_NOTIFY_NEUTRAL | `uint8` | 4 | +| TUNE_ID_NOTIFY_NEGATIVE | `uint8` | 5 | +| TUNE_ID_ARMING_WARNING | `uint8` | 6 | +| TUNE_ID_BATTERY_WARNING_SLOW | `uint8` | 7 | +| TUNE_ID_BATTERY_WARNING_FAST | `uint8` | 8 | +| TUNE_ID_GPS_WARNING | `uint8` | 9 | +| TUNE_ID_ARMING_FAILURE | `uint8` | 10 | +| TUNE_ID_PARACHUTE_RELEASE | `uint8` | 11 | +| TUNE_ID_SINGLE_BEEP | `uint8` | 12 | +| TUNE_ID_HOME_SET | `uint8` | 13 | +| TUNE_ID_SD_INIT | `uint8` | 14 | +| TUNE_ID_SD_ERROR | `uint8` | 15 | +| TUNE_ID_PROG_PX4IO | `uint8` | 16 | +| TUNE_ID_PROG_PX4IO_OK | `uint8` | 17 | +| TUNE_ID_PROG_PX4IO_ERR | `uint8` | 18 | +| TUNE_ID_POWER_OFF | `uint8` | 19 | +| NUMBER_OF_TUNES | `uint8` | 20 | +| VOLUME_LEVEL_MIN | `uint8` | 0 | +| VOLUME_LEVEL_DEFAULT | `uint8` | 20 | +| VOLUME_LEVEL_MAX | `uint8` | 100 | +| ORB_QUEUE_LENGTH | `uint8` | 4 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TuneControl.msg) + +::: details Click here to see original file ```c # This message is used to control the tunes, when the tune_id is set to CUSTOM @@ -45,5 +96,6 @@ uint8 VOLUME_LEVEL_DEFAULT = 20 uint8 VOLUME_LEVEL_MAX = 100 uint8 ORB_QUEUE_LENGTH = 4 - ``` + +::: diff --git a/docs/en/msg_docs/UavcanParameterRequest.md b/docs/en/msg_docs/UavcanParameterRequest.md index 681c8aa8c9..1abc63360e 100644 --- a/docs/en/msg_docs/UavcanParameterRequest.md +++ b/docs/en/msg_docs/UavcanParameterRequest.md @@ -1,8 +1,44 @@ +--- +pageClass: is-wide-page +--- + # UavcanParameterRequest (UORB message) -UAVCAN-MAVLink parameter bridge request type +UAVCAN-MAVLink parameter bridge request type. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/UavcanParameterRequest.msg) +**TOPICS:** uavcan_parameterrequest + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------ | ---------- | ------------ | ---------- | ----------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| message_type | `uint8` | | | MAVLink message type: PARAM_REQUEST_READ, PARAM_REQUEST_LIST, PARAM_SET | +| node_id | `uint8` | | | UAVCAN node ID mapped from MAVLink component ID | +| param_id | `char[17]` | | | MAVLink/UAVCAN parameter name | +| param_index | `int16` | | | -1 if the param_id field should be used as identifier | +| param_type | `uint8` | | | MAVLink parameter type | +| int_value | `int64` | | | current value if param_type is int-like | +| real_value | `float32` | | | current value if param_type is float-like | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------------------------------------- | ------- | ----- | --------------------------------- | +| MESSAGE_TYPE_PARAM_REQUEST_READ | `uint8` | 20 | MAVLINK_MSG_ID_PARAM_REQUEST_READ | +| MESSAGE_TYPE_PARAM_REQUEST_LIST | `uint8` | 21 | MAVLINK_MSG_ID_PARAM_REQUEST_LIST | +| MESSAGE_TYPE_PARAM_SET | `uint8` | 23 | MAVLINK_MSG_ID_PARAM_SET | +| NODE_ID_ALL | `uint8` | 0 | MAV_COMP_ID_ALL | +| PARAM_TYPE_UINT8 | `uint8` | 1 | MAV_PARAM_TYPE_UINT8 | +| PARAM_TYPE_INT64 | `uint8` | 8 | MAV_PARAM_TYPE_INT64 | +| PARAM_TYPE_REAL32 | `uint8` | 9 | MAV_PARAM_TYPE_REAL32 | +| ORB_QUEUE_LENGTH | `uint8` | 4 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/UavcanParameterRequest.msg) + +::: details Click here to see original file ```c # UAVCAN-MAVLink parameter bridge request type @@ -28,5 +64,6 @@ int64 int_value # current value if param_type is int-like float32 real_value # current value if param_type is float-like uint8 ORB_QUEUE_LENGTH = 4 - ``` + +::: diff --git a/docs/en/msg_docs/UavcanParameterValue.md b/docs/en/msg_docs/UavcanParameterValue.md index f77444727a..fec16df590 100644 --- a/docs/en/msg_docs/UavcanParameterValue.md +++ b/docs/en/msg_docs/UavcanParameterValue.md @@ -1,8 +1,31 @@ +--- +pageClass: is-wide-page +--- + # UavcanParameterValue (UORB message) -UAVCAN-MAVLink parameter bridge response type +UAVCAN-MAVLink parameter bridge response type. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/UavcanParameterValue.msg) +**TOPICS:** uavcan_parametervalue + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------- | ---------- | ------------ | ---------- | ----------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| node_id | `uint8` | | | UAVCAN node ID mapped from MAVLink component ID | +| param_id | `char[17]` | | | MAVLink/UAVCAN parameter name | +| param_index | `int16` | | | parameter index, if known | +| param_count | `uint16` | | | number of parameters exposed by the node | +| param_type | `uint8` | | | MAVLink parameter type | +| int_value | `int64` | | | current value if param_type is int-like | +| real_value | `float32` | | | current value if param_type is float-like | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/UavcanParameterValue.msg) + +::: details Click here to see original file ```c # UAVCAN-MAVLink parameter bridge response type @@ -14,5 +37,6 @@ uint16 param_count # number of parameters exposed by the node uint8 param_type # MAVLink parameter type int64 int_value # current value if param_type is int-like float32 real_value # current value if param_type is float-like - ``` + +::: diff --git a/docs/en/msg_docs/UlogStream.md b/docs/en/msg_docs/UlogStream.md index 8aba8063c8..f52c44da41 100644 --- a/docs/en/msg_docs/UlogStream.md +++ b/docs/en/msg_docs/UlogStream.md @@ -1,9 +1,36 @@ +--- +pageClass: is-wide-page +--- + # UlogStream (UORB message) -Message to stream ULog data from the logger. Corresponds to the LOGGING_DATA -mavlink message +Message to stream ULog data from the logger. Corresponds to the LOGGING_DATA. mavlink message. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/UlogStream.msg) +**TOPICS:** ulog_stream + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------- | ------------ | ------------ | ---------- | ------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| length | `uint8` | | | length of data | +| first_message_offset | `uint8` | | | offset into data where first message starts. This | +| msg_sequence | `uint16` | | | allows determine drops | +| flags | `uint8` | | | see FLAGS\_\* | +| data | `uint8[249]` | | | ulog data | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------- | ------- | ----- | -------------------------------------------------------------------- | +| FLAGS_NEED_ACK | `uint8` | 1 | if set, this message requires to be acked. | +| ORB_QUEUE_LENGTH | `uint8` | 16 | TODO: we might be able to reduce this if mavlink polled on the topic | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/UlogStream.msg) + +::: details Click here to see original file ```c # Message to stream ULog data from the logger. Corresponds to the LOGGING_DATA @@ -25,5 +52,6 @@ uint8 flags # see FLAGS_* uint8[249] data # ulog data uint8 ORB_QUEUE_LENGTH = 16 # TODO: we might be able to reduce this if mavlink polled on the topic - ``` + +::: diff --git a/docs/en/msg_docs/UlogStreamAck.md b/docs/en/msg_docs/UlogStreamAck.md index 4bef62c4f5..ea874882fd 100644 --- a/docs/en/msg_docs/UlogStreamAck.md +++ b/docs/en/msg_docs/UlogStreamAck.md @@ -1,9 +1,32 @@ +--- +pageClass: is-wide-page +--- + # UlogStreamAck (UORB message) -Ack a previously sent ulog_stream message that had -the NEED_ACK flag set +Ack a previously sent ulog_stream message that had. the NEED_ACK flag set. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/UlogStreamAck.msg) +**TOPICS:** ulog_streamack + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------ | -------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| msg_sequence | `uint16` | | | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------- | ------- | ----- | -------------------------------------------------------------------------------- | +| ACK_TIMEOUT | `int32` | 50 | timeout waiting for an ack until we retry to send the message [ms] | +| ACK_MAX_TRIES | `int32` | 50 | maximum amount of tries to (re-)send a message, each time waiting ACK_TIMEOUT ms | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/UlogStreamAck.msg) + +::: details Click here to see original file ```c # Ack a previously sent ulog_stream message that had @@ -14,5 +37,6 @@ int32 ACK_TIMEOUT = 50 # timeout waiting for an ack until we retry to send the int32 ACK_MAX_TRIES = 50 # maximum amount of tries to (re-)send a message, each time waiting ACK_TIMEOUT ms uint16 msg_sequence - ``` + +::: diff --git a/docs/en/msg_docs/UnregisterExtComponent.md b/docs/en/msg_docs/UnregisterExtComponent.md index 5a36c85613..a3e7a4d6da 100644 --- a/docs/en/msg_docs/UnregisterExtComponent.md +++ b/docs/en/msg_docs/UnregisterExtComponent.md @@ -1,8 +1,32 @@ +--- +pageClass: is-wide-page +--- + # UnregisterExtComponent (UORB message) +**TOPICS:** unregister_extcomponent +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/UnregisterExtComponent.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ---------- | ------------ | ---------- | --------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| name | `char[25]` | | | either the mode name, or component name | +| arming_check_id | `int8` | | | arming check registration ID (-1 if not registered) | +| mode_id | `int8` | | | assigned mode ID (-1 if not registered) | +| mode_executor_id | `int8` | | | assigned mode executor ID (-1 if not registered) | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/UnregisterExtComponent.msg) + +::: details Click here to see original file ```c uint32 MESSAGE_VERSION = 0 @@ -14,5 +38,6 @@ char[25] name # either the mode name, or component name int8 arming_check_id # arming check registration ID (-1 if not registered) int8 mode_id # assigned mode ID (-1 if not registered) int8 mode_executor_id # assigned mode executor ID (-1 if not registered) - ``` + +::: diff --git a/docs/en/msg_docs/VehicleAcceleration.md b/docs/en/msg_docs/VehicleAcceleration.md index 1fb3d0880c..e463dedd18 100644 --- a/docs/en/msg_docs/VehicleAcceleration.md +++ b/docs/en/msg_docs/VehicleAcceleration.md @@ -1,15 +1,31 @@ +--- +pageClass: is-wide-page +--- + # VehicleAcceleration (UORB message) +**TOPICS:** vehicle_acceleration +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleAcceleration.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ------------ | ------------ | ---------- | --------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| xyz | `float32[3]` | | | Bias corrected acceleration (including gravity) in the FRD body frame XYZ-axis in m/s^2 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleAcceleration.msg) + +::: details Click here to see original file ```c - uint64 timestamp # time since system start (microseconds) uint64 timestamp_sample # the timestamp of the raw data (microseconds) float32[3] xyz # Bias corrected acceleration (including gravity) in the FRD body frame XYZ-axis in m/s^2 - ``` + +::: diff --git a/docs/en/msg_docs/VehicleAirData.md b/docs/en/msg_docs/VehicleAirData.md index dccfefc095..020b706c27 100644 --- a/docs/en/msg_docs/VehicleAirData.md +++ b/docs/en/msg_docs/VehicleAirData.md @@ -1,11 +1,35 @@ +--- +pageClass: is-wide-page +--- + # VehicleAirData (UORB message) -Vehicle air data +Vehicle air data. Data from the currently selected barometer (plus ambient temperature from the source specified in temperature_source). Includes calculated data such as barometric altitude and air density. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleAirData.msg) +**TOPICS:** vehicle_airdata + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------- | --------- | ------------ | ---------- | --------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| timestamp_sample | `uint64` | us | | Timestamp of the raw data | +| baro_device_id | `uint32` | | | Unique device ID for the selected barometer | +| baro_alt_meter | `float32` | m [MSL] | | Altitude above MSL calculated from temperature compensated baro sensor data using an ISA corrected for sea level pressure SENS_BARO_QNH | +| baro_pressure_pa | `float32` | Pa | | Absolute pressure | +| ambient_temperature | `float32` | degC | | Ambient temperature | +| temperature_source | `uint8` | | | Source of temperature data: 0: Default Temperature (15°C), 1: External Baro, 2: Airspeed | +| rho | `float32` | kg/m^3 | | Air density | +| calibration_count | `uint8` | | | Calibration changed counter. Monotonically increases whenever calibration changes. | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleAirData.msg) + +::: details Click here to see original file ```c # Vehicle air data @@ -22,5 +46,6 @@ float32 ambient_temperature # [degC] Ambient temperature uint8 temperature_source # Source of temperature data: 0: Default Temperature (15°C), 1: External Baro, 2: Airspeed float32 rho # [kg/m^3] Air density uint8 calibration_count # Calibration changed counter. Monotonically increases whenever calibration changes. - ``` + +::: diff --git a/docs/en/msg_docs/VehicleAngularAccelerationSetpoint.md b/docs/en/msg_docs/VehicleAngularAccelerationSetpoint.md index d10cabdb55..f098855945 100644 --- a/docs/en/msg_docs/VehicleAngularAccelerationSetpoint.md +++ b/docs/en/msg_docs/VehicleAngularAccelerationSetpoint.md @@ -1,14 +1,30 @@ +--- +pageClass: is-wide-page +--- + # VehicleAngularAccelerationSetpoint (UORB message) +**TOPICS:** vehicle_angularacceleration_setpoint +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleAngularAccelerationSetpoint.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ------------ | ------------ | ---------- | -------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | timestamp of the data sample on which this message is based (microseconds) | +| xyz | `float32[3]` | | | angular acceleration about X, Y, Z body axis in rad/s^2 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleAngularAccelerationSetpoint.msg) + +::: details Click here to see original file ```c - uint64 timestamp # time since system start (microseconds) uint64 timestamp_sample # timestamp of the data sample on which this message is based (microseconds) float32[3] xyz # angular acceleration about X, Y, Z body axis in rad/s^2 - ``` + +::: diff --git a/docs/en/msg_docs/VehicleAngularVelocity.md b/docs/en/msg_docs/VehicleAngularVelocity.md index 2c94cb706a..81fa680129 100644 --- a/docs/en/msg_docs/VehicleAngularVelocity.md +++ b/docs/en/msg_docs/VehicleAngularVelocity.md @@ -1,8 +1,31 @@ +--- +pageClass: is-wide-page +--- + # VehicleAngularVelocity (UORB message) +**TOPICS:** vehicle_angular_velocity vehicle_angular_velocity_groundtruth +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAngularVelocity.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ------------ | ------------ | ---------- | -------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | timestamp of the data sample on which this message is based (microseconds) | +| xyz | `float32[3]` | | | Bias corrected angular velocity about the FRD body frame XYZ-axis in rad/s | +| xyz_derivative | `float32[3]` | | | angular acceleration about the FRD body frame XYZ-axis in rad/s^2 | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAngularVelocity.msg) + +::: details Click here to see original file ```c uint32 MESSAGE_VERSION = 0 @@ -15,5 +38,6 @@ float32[3] xyz # Bias corrected angular velocity about the FRD body frame XYZ float32[3] xyz_derivative # angular acceleration about the FRD body frame XYZ-axis in rad/s^2 # TOPICS vehicle_angular_velocity vehicle_angular_velocity_groundtruth - ``` + +::: diff --git a/docs/en/msg_docs/VehicleAttitude.md b/docs/en/msg_docs/VehicleAttitude.md index 856fe6d5a6..526e299db5 100644 --- a/docs/en/msg_docs/VehicleAttitude.md +++ b/docs/en/msg_docs/VehicleAttitude.md @@ -1,9 +1,34 @@ +--- +pageClass: is-wide-page +--- + # VehicleAttitude (UORB message) -This is similar to the mavlink message ATTITUDE_QUATERNION, but for onboard use -The quaternion uses the Hamilton convention, and the order is q(w, x, y, z) +This is similar to the mavlink message ATTITUDE_QUATERNION, but for onboard use. The quaternion uses the Hamilton convention, and the order is q(w, x, y, z). -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAttitude.msg) +**TOPICS:** vehicle_attitude vehicle_attitude_groundtruth external_ins_attitude estimator_attitude + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------ | ------------ | ------------ | ---------- | ------------------------------------------------------------------ | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| q | `float32[4]` | | | Quaternion rotation from the FRD body frame to the NED earth frame | +| delta_q_reset | `float32[4]` | | | Amount by which quaternion has changed during last reset | +| quat_reset_counter | `uint8` | | | Quaternion reset counter | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAttitude.msg) + +::: details Click here to see original file ```c # This is similar to the mavlink message ATTITUDE_QUATERNION, but for onboard use @@ -21,5 +46,6 @@ uint8 quat_reset_counter # Quaternion reset counter # TOPICS vehicle_attitude vehicle_attitude_groundtruth external_ins_attitude # TOPICS estimator_attitude - ``` + +::: diff --git a/docs/en/msg_docs/VehicleAttitudeSetpoint.md b/docs/en/msg_docs/VehicleAttitudeSetpoint.md index 69552e23ef..7bc0940ba3 100644 --- a/docs/en/msg_docs/VehicleAttitudeSetpoint.md +++ b/docs/en/msg_docs/VehicleAttitudeSetpoint.md @@ -1,8 +1,31 @@ +--- +pageClass: is-wide-page +--- + # VehicleAttitudeSetpoint (UORB message) +**TOPICS:** vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAttitudeSetpoint.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ------------ | ------------ | ---------- | -------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| yaw_sp_move_rate | `float32` | | | rad/s (commanded by user) | +| q_d | `float32[4]` | | | Desired quaternion for quaternion control | +| thrust_body | `float32[3]` | | | Normalized thrust command in body FRD frame [-1,1] | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 1 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAttitudeSetpoint.msg) + +::: details Click here to see original file ```c uint32 MESSAGE_VERSION = 1 @@ -19,5 +42,6 @@ float32[4] q_d # Desired quaternion for quaternion control float32[3] thrust_body # Normalized thrust command in body FRD frame [-1,1] # TOPICS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint - ``` + +::: diff --git a/docs/en/msg_docs/VehicleAttitudeSetpointV0.md b/docs/en/msg_docs/VehicleAttitudeSetpointV0.md index 9b3a8c655e..9a53c593f9 100644 --- a/docs/en/msg_docs/VehicleAttitudeSetpointV0.md +++ b/docs/en/msg_docs/VehicleAttitudeSetpointV0.md @@ -1,8 +1,33 @@ +--- +pageClass: is-wide-page +--- + # VehicleAttitudeSetpointV0 (UORB message) +**TOPICS:** vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/VehicleAttitudeSetpointV0.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------- | ------------ | ------------ | ---------- | --------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| yaw_sp_move_rate | `float32` | | | rad/s (commanded by user) | +| q_d | `float32[4]` | | | Desired quaternion for quaternion control | +| thrust_body | `float32[3]` | | | Normalized thrust command in body FRD frame [-1,1] | +| reset_integral | `bool` | | | Reset roll/pitch/yaw integrals (navigation logic change) | +| fw_control_yaw_wheel | `bool` | | | control heading with steering wheel (used for auto takeoff on runway) | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/VehicleAttitudeSetpointV0.msg) + +::: details Click here to see original file ```c uint32 MESSAGE_VERSION = 0 @@ -23,5 +48,6 @@ bool reset_integral # Reset roll/pitch/yaw integrals (navigation logic change) bool fw_control_yaw_wheel # control heading with steering wheel (used for auto takeoff on runway) # TOPICS vehicle_attitude_setpoint mc_virtual_attitude_setpoint fw_virtual_attitude_setpoint - ``` + +::: diff --git a/docs/en/msg_docs/VehicleCommand.md b/docs/en/msg_docs/VehicleCommand.md index 225f680857..32b719e7b7 100644 --- a/docs/en/msg_docs/VehicleCommand.md +++ b/docs/en/msg_docs/VehicleCommand.md @@ -1,9 +1,1581 @@ +--- +pageClass: is-wide-page +--- + # VehicleCommand (UORB message) -Vehicle Command uORB message. Used for commanding a mission / action / etc. -Follows the MAVLink COMMAND_INT / COMMAND_LONG definition +Vehicle Command uORB message. Used for commanding a mission / action / etc. Follows the MAVLink COMMAND_INT / COMMAND_LONG definition. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleCommand.msg) +**TOPICS:** vehicle_command gimbal_v1_command vehicle_command_mode_executor + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | --------- | ------------ | ---------- | ------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start. | +| param1 | `float32` | | | Parameter 1, as defined by MAVLink uint16 VEHICLE_CMD enum. | +| param2 | `float32` | | | Parameter 2, as defined by MAVLink uint16 VEHICLE_CMD enum. | +| param3 | `float32` | | | Parameter 3, as defined by MAVLink uint16 VEHICLE_CMD enum. | +| param4 | `float32` | | | Parameter 4, as defined by MAVLink uint16 VEHICLE_CMD enum. | +| param5 | `float64` | | | Parameter 5, as defined by MAVLink uint16 VEHICLE_CMD enum. | +| param6 | `float64` | | | Parameter 6, as defined by MAVLink uint16 VEHICLE_CMD enum. | +| param7 | `float32` | | | Parameter 7, as defined by MAVLink uint16 VEHICLE_CMD enum. | +| command | `uint32` | | | Command ID. | +| target_system | `uint8` | | | System which should execute the command. | +| target_component | `uint8` | | | Component which should execute the command, 0 for all components. | +| source_system | `uint8` | | | System sending the command. | +| source_component | `uint16` | | | Component / mode executor sending the command. | +| confirmation | `uint8` | | | 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command). | +| from_external | `bool` | | | + +## Commands + +### VEHICLE_CMD_CUSTOM_0 (0) + +Test command. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_CUSTOM_1 (1) + +Test command. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_CUSTOM_2 (2) + +Test command. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_NAV_WAYPOINT (16) + +Navigate to MISSION. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| 1 | s | | (decimal) Hold time. (ignored by fixed wing, time to stay at MISSION for rotary wing) | +| 2 | m | | Acceptance radius (if the sphere with this radius is hit, the MISSION counts as reached) | +| 3 | | | 0 to pass through the WP, if > 0 radius [m] to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control. | +| 4 | | | Desired yaw angle at MISSION (rotary wing) | +| 5 | | | Latitude | +| 6 | | | Longitude | +| 7 | | | Altitude | + +### VEHICLE_CMD_NAV_LOITER_UNLIM (17) + +Loiter around this MISSION an unlimited amount of time. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | --------------------------------------------------------------------------- | +| 1 | | | Unused | +| 2 | | | Unused | +| 3 | m | | Radius around MISSION. If positive loiter clockwise, else counter-clockwise | +| 4 | | | Desired yaw angle. | +| 5 | | | Latitude | +| 6 | | | Longitude | +| 7 | | | Altitude | + +### VEHICLE_CMD_NAV_LOITER_TURNS (18) + +Loiter around this MISSION for X turns. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------------------------------------------------------------------- | +| 1 | | | Turns | +| 2 | | | Unused | +| 3 | | | Radius around MISSION [m]. If positive loiter clockwise, else counter-clockwise | +| 4 | | | Desired yaw angle. | +| 5 | | | Latitude | +| 6 | | | Longitude | +| 7 | | | Altitude | + +### VEHICLE_CMD_NAV_LOITER_TIME (19) + +Loiter around this MISSION for time. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------------------------------------------------------------------- | +| 1 | s | | Seconds (decimal) | +| 2 | | | Unused | +| 3 | | | Radius around MISSION [m]. If positive loiter clockwise, else counter-clockwise | +| 4 | | | Desired yaw angle. | +| 5 | | | Latitude | +| 6 | | | Longitude | +| 7 | | | Altitude | + +### VEHICLE_CMD_NAV_RETURN_TO_LAUNCH (20) + +Return to launch location. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | Unused | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_NAV_LAND (21) + +Land at location. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------ | +| 1 | | | Unused | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Desired yaw angle. | +| 5 | | | Latitude | +| 6 | | | Longitude | +| 7 | | | Altitude | + +### VEHICLE_CMD_NAV_TAKEOFF (22) + +Takeoff from ground / hand. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------------------------------------------------------- | +| 1 | | | Unused (FW pitch from FW_TKO_PITCH_MIN) | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | deg | [0 : 360] | Yaw angle in NED if yaw source available, ignored otherwise | +| 5 | | | Latitude (WGS-84) | +| 6 | | | Longitude (WGS-84) | +| 7 | m | | Altitude AMSL | + +### VEHICLE_CMD_NAV_PRECLAND (23) + +Attempt a precision landing. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_DO_ORBIT (34) + +Start orbiting on the circumference of a circle defined by the parameters. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ------------------------------------------- | ------------- | +| 1 | m | | Radius | +| 2 | m/s | | Velocity | +| 3 | | [ORBIT_YAW_BEHAVIOUR](#ORBIT_YAW_BEHAVIOUR) | Yaw behaviour | +| 4 | | | Unused | +| 5 | | | Latitude/X | +| 6 | | | Longitude/Y | +| 7 | | | Altitude/Z | + +### VEHICLE_CMD_DO_FIGUREEIGHT (35) + +Start flying on the outline of a figure eight defined by the parameters. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------ | +| 1 | m | | Major radius | +| 2 | m | | Minor radius | +| 3 | m/s | | Velocity | +| 4 | | | Orientation | +| 5 | | | Latitude/X | +| 6 | | | Longitude/Y | +| 7 | | | Altitude/Z | + +### VEHICLE_CMD_NAV_ROI (80) + +Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | --------------------------- | ----------------------------------------------------- | +| 1 | | [VEHICLE_ROI](#VEHICLE_ROI) | Region of interest mode. | +| 2 | | | MISSION index/ target ID. | +| 3 | | | ROI index (allows a vehicle to manage multiple ROI's) | +| 4 | | | Unused | +| 5 | | | x the location of the fixed ROI (see MAV_FRAME) | +| 6 | | | y | +| 7 | | | z | + +### VEHICLE_CMD_NAV_PATHPLANNING (81) + +Control autonomous path planning on the MAV. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| 1 | | | 0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning | +| 2 | | | 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid | +| 3 | | | Unused | +| 4 | deg | [0 : 360] | Yaw angle at goal, in compass degrees | +| 5 | | | Latitude/X of goal | +| 6 | | | Longitude/Y of goal | +| 7 | | | Altitude/Z of goal | + +### VEHICLE_CMD_NAV_VTOL_TAKEOFF (84) + +Takeoff from ground / hand and transition to fixed wing. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------------------------------------------------------------ | +| 1 | | | Minimum pitch (if airspeed sensor present), desired pitch without sensor | +| 2 | | | Transition heading, 0: Default, 3: Use specified transition heading | +| 3 | | | Unused | +| 4 | | | Yaw angle (if magnetometer present), ignored without magnetometer | +| 5 | | | Latitude | +| 6 | | | Longitude | +| 7 | | | Altitude | + +### VEHICLE_CMD_NAV_VTOL_LAND (85) + +Transition to MC and land at location. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------ | +| 1 | | | Unused | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Desired yaw angle. | +| 5 | | | Latitude | +| 6 | | | Longitude | +| 7 | | | Altitude | + +### VEHICLE_CMD_NAV_GUIDED_LIMITS (90) + +Set limits for external control. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| 1 | s | | Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout | +| 2 | m | | Absolute altitude min AMSL - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit | +| 3 | m | | Absolute altitude max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit | +| 4 | m | | Horizontal move limit (AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_NAV_GUIDED_MASTER (91) + +Set id of master controller. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------ | +| 1 | | | System ID | +| 2 | | | Component ID | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_NAV_DELAY (93) + +Delay the next navigation command a number of seconds or until a specified time. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------------------------------------ | +| 1 | s | | Delay (decimal, -1 to enable time-of-day fields) | +| 2 | h | | hour (24h format, UTC, -1 to ignore) | +| 3 | | | minute (24h format, UTC, -1 to ignore) | +| 4 | | | second (24h format, UTC) | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_NAV_LAST (95) + +NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | Unused | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_CONDITION_DELAY (112) + +Delay mission state machine. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------------------- | +| 1 | s | | Delay (decimal seconds) | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_CONDITION_CHANGE_ALT (113) + +Ascend/descend at rate. Delay mission state machine until desired altitude reached. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | --------------------------- | +| 1 | | | Descent / Ascend rate (m/s) | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Finish Altitude | + +### VEHICLE_CMD_CONDITION_DISTANCE (114) + +Delay mission state machine until within desired distance of next NAV point. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------ | +| 1 | | | Distance [m] | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_CONDITION_YAW (115) + +Reach a certain target angle. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------------------------------------------------------- | +| 1 | deg | [0 : 360] | Target angle. 0 is north | +| 2 | deg/s | | Speed during yaw change | +| 3 | | [-1 : 1] | Direction: negative: counter clockwise, positive: clockwise | +| 4 | 1,0 | | Relative offset or absolute angle | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_CONDITION_LAST (159) + +NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | Unused | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_CONDITION_GATE (4501) + +Wait until passing a threshold. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | --------------------------------------------- | +| 1 | | | 2D coord mode: 0: Orthogonal to planned route | +| 2 | | | Altitude mode: 0: Ignore altitude | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Lat | +| 6 | | | Lon | +| 7 | | | Alt | + +### VEHICLE_CMD_DO_SET_MODE (176) + +Set system mode. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | --------------------------------- | +| 1 | | | Mode, as defined by ENUM MAV_MODE | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_JUMP (177) + +Jump to the desired command in the mission list. Repeat this action only the specified number of times. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | --------------- | +| 1 | | | Sequence number | +| 2 | | | Repeat count | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_CHANGE_SPEED (178) + +Change speed and/or throttle set points. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ------------------------- | ------------------------------------------- | +| 1 | | [SPEED_TYPE](#SPEED_TYPE) | Speed type (0=Airspeed, 1=Ground Speed) | +| 2 | | | Speed (m/s, -1 indicates no change) | +| 3 | % | | Throttle ( Percent, -1 indicates no change) | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_SET_HOME (179) + +Changes the home location either to the current location or a specified location. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | -------------------------------------------------------------- | +| 1 | | | Use current (1=use current location, 0=use specified location) | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Latitude | +| 6 | | | Longitude | +| 7 | | | Altitude | + +### VEHICLE_CMD_DO_SET_PARAMETER (180) + +Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ---------------- | +| 1 | | | Parameter number | +| 2 | | | Parameter value | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_SET_RELAY (181) + +Set a relay to a condition. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------------------------------------------------------- | +| 1 | | | Relay number | +| 2 | | | Setting (1=on, 0=off, others possible depending on system hardware) | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_REPEAT_RELAY (182) + +Cycle a relay on and off for a desired number of cycles with a desired period. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ---------------------------- | +| 1 | | | Relay number | +| 2 | | | Cycle count | +| 3 | s | | Cycle time (decimal seconds) | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_REPEAT_SERVO (184) + +Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------------------- | +| 1 | | | Servo number | +| 2 | us | | PWM rate (1000 to 2000 typical) | +| 3 | | | Cycle count | +| 4 | s | | Cycle time | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_FLIGHTTERMINATION (185) + +Terminate flight immediately. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------------------------- | +| 1 | | | Flight termination activated if > 0.5 | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_CHANGE_ALTITUDE (186) + +Set the vehicle to Loiter mode and change the altitude to specified value. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | --------------------- | +| 1 | | | Altitude | +| 2 | | | Frame of new altitude | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_SET_ACTUATOR (187) + +Sets actuators (e.g. servos) to a desired value. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | Actuator 1 | +| 2 | | | Actuator 2 | +| 3 | | | Actuator 3 | +| 4 | | | Actuator 4 | +| 5 | | | Actuator 5 | +| 6 | | | Actuator 6 | +| 7 | | | Index | + +### VEHICLE_CMD_DO_LAND_START (189) + +Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | Unused | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Latitude | +| 6 | | | Longitude | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_GO_AROUND (191) + +Mission command to safely abort an autonomous landing. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | m | | Altitude | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_REPOSITION (192) + +Reposition to specific WGS84 GPS position. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------------ | +| 1 | m/s | | Ground speed | +| 2 | | | Bitmask | +| 3 | m | | Loiter radius for planes | +| 4 | deg | | Yaw | +| 5 | | | Latitude | +| 6 | | | Longitude | +| 7 | | | Altitude | + +### VEHICLE_CMD_DO_PAUSE_CONTINUE (193) + +None + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_DO_SET_ROI_LOCATION (195) + +Sets the region of interest (ROI) to a location. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | Unused | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Latitude | +| 6 | | | Longitude | +| 7 | | | Altitude | + +### VEHICLE_CMD_DO_SET_ROI_WPNEXT_OFFSET (196) + +Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------------------- | +| 1 | | | Unused | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Pitch offset from next waypoint | +| 6 | | | Roll offset from next waypoint | +| 7 | | | Yaw offset from next waypoint | + +### VEHICLE_CMD_DO_SET_ROI_NONE (197) + +Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | Unused | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_CONTROL_VIDEO (200) + +Control onboard camera system. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | --------------------------------------------------------------------------------------- | +| 1 | | | Camera ID (-1 for all) | +| 2 | | | Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw | +| 3 | | | Transmission mode: 0: video stream, >0: single images every n seconds (decimal seconds) | +| 4 | | | Recording: 0: disabled, 1: enabled compressed, 2: enabled raw | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_SET_ROI (201) + +Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | --------------------------- | ----------------------------------------------------- | +| 1 | | [VEHICLE_ROI](#VEHICLE_ROI) | Region of interest mode. | +| 2 | | | MISSION index/ target ID. | +| 3 | | | ROI index (allows a vehicle to manage multiple ROI's) | +| 4 | | | Unused | +| 5 | | | x the location of the fixed ROI (see MAV_FRAME) | +| 6 | | | y | +| 7 | | | z | + +### VEHICLE_CMD_DO_DIGICAM_CONTROL (203) + +None + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_DO_MOUNT_CONFIGURE (204) + +Mission command to configure a camera or antenna mount. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | --------------------------------- | ---------------------------------- | +| 1 | | [MAV_MOUNT_MODE](#MAV_MOUNT_MODE) | Mount operation mode | +| 2 | | | Stabilize roll? (1 = yes, 0 = no) | +| 3 | | | Stabilize pitch? (1 = yes, 0 = no) | +| 4 | | | stabilize yaw? (1 = yes, 0 = no) | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_MOUNT_CONTROL (205) + +Mission command to control a camera or antenna mount. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | --------------------------------- | --------------------------------------- | +| 1 | deg | | Pitch or lat, depending on mount mode. | +| 2 | deg | | Roll or lon depending on mount mode | +| 3 | deg | | /[m] Yaw or alt depending on mount mode | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | [MAV_MOUNT_MODE](#MAV_MOUNT_MODE) | + +### VEHICLE_CMD_DO_SET_CAM_TRIGG_DIST (206) + +Mission command to set TRIG_DIST for this flight. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------------ | +| 1 | m | | Camera trigger distance | +| 2 | ms | | Shutter integration time | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_FENCE_ENABLE (207) + +Mission command to enable the geofence. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------------------------- | +| 1 | | | enable? (0=disable, 1=enable) | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_PARACHUTE (208) + +Mission command to trigger a parachute. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | -------------------------------------------------------------------------------------------------------------------------------------------- | +| 1 | | | action [@enum PARACHUTE_ACTION] (0=disable, 1=enable, 2=release, for some systems see [@enum PARACHUTE_ACTION], not in general message set.) | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_MOTOR_TEST (209) + +Motor test command. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | --------------------- | +| 1 | | | Instance (@range 1, ) | +| 2 | | | throttle type | +| 3 | | | throttle | +| 4 | | | timeout [s] | +| 5 | | | Motor count | +| 6 | | | Test order | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_INVERTED_FLIGHT (210) + +Change to/from inverted flight. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------------------- | +| 1 | | | inverted (0=normal, 1=inverted) | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_GRIPPER (211) + +Command to operate a gripper. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_DO_AUTOTUNE_ENABLE (212) + +Enable autotune module. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | 1 to enable | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_SET_CAM_TRIGG_INTERVAL (214) + +Mission command to set TRIG_INTERVAL for this flight. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------------------------- | +| 1 | m | | Camera trigger distance | +| 2 | | | Shutter integration time (ms) | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_MOUNT_CONTROL_QUAT (220) + +Mission command to control a camera or antenna mount, using a quaternion as reference. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------------------------------------ | +| 1 | | | q1 - quaternion param #1, w (1 in null-rotation) | +| 2 | | | q2 - quaternion param #2, x (0 in null-rotation) | +| 3 | | | q3 - quaternion param #3, y (0 in null-rotation) | +| 4 | | | q4 - quaternion param #4, z (0 in null-rotation) | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_GUIDED_MASTER (221) + +Set id of master controller. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------ | +| 1 | | | System ID | +| 2 | | | Component ID | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_GUIDED_LIMITS (222) + +Set limits for external control. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| 1 | s | | Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout | +| 2 | m | | Absolute altitude min(AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit | +| 3 | m | | Absolute altitude max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit | +| 4 | m | | Horizontal move limit (AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_LAST (240) + +NOP - This command is only used to mark the upper limit of the DO commands in the enumeration. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | Unused | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_PREFLIGHT_CALIBRATION (241) + +Trigger calibration. This command will be only accepted if in pre-flight mode. See MAVLink spec MAV_CMD_PREFLIGHT_CALIBRATION. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS (242) + +Set sensor offsets. This command will be only accepted if in pre-flight mode. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------------------------------------------------------------------------------------------------ | +| 1 | | | Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow | +| 2 | | | X axis offset (or generic dimension 1), in the sensor's raw units | +| 3 | | | Y axis offset (or generic dimension 2), in the sensor's raw units | +| 4 | | | Z axis offset (or generic dimension 3), in the sensor's raw units | +| 5 | | | Generic dimension 4, in the sensor's raw units | +| 6 | | | Generic dimension 5, in the sensor's raw units | +| 7 | | | Generic dimension 6, in the sensor's raw units | + +### VEHICLE_CMD_PREFLIGHT_UAVCAN (243) + +UAVCAN configuration. If param 1 == 1 actuator mapping and direction assignment should be started. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_PREFLIGHT_STORAGE (245) + +Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------------------------------------------------------------------ | +| 1 | | | Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM | +| 2 | | | Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN (246) + +Request the reboot or shutdown of system components. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | --------------------------------------------------------------------------------------------- | +| 1 | | | 0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot. | +| 2 | | | 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer. | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_OBLIQUE_SURVEY (260) + +Mission command to set a Camera Auto Mount Pivoting Oblique Survey for this flight. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------------------- | +| 1 | m | | Camera trigger distance | +| 2 | ms | | Shutter integration time | +| 3 | | | Camera minimum trigger interval | +| 4 | | | Number of positions | +| 5 | | | Roll | +| 6 | | | Pitch | +| 7 | | | Unused | + +### VEHICLE_CMD_DO_SET_STANDARD_MODE (262) + +Enable the specified standard MAVLink mode. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------------- | +| 1 | | | MAV_STANDARD_MODE | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_GIMBAL_DEVICE_INFORMATION (283) + +Command to ask information about a low level gimbal. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_MISSION_START (300) + +Start running a mission. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ---------------------------------------------------------------------------------- | +| 1 | | | first_item: the first mission item to run | +| 2 | | | last_item: the last mission item to run (after this item is run, the mission ends) | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_ACTUATOR_TEST (310) + +Actuator testing command. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | --------------- | +| 1 | | [-1 : 1] | value | +| 2 | s | | timeout | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | output function | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_CONFIGURE_ACTUATOR (311) + +Actuator configuration command. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | --------------- | +| 1 | | | configuration | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | output function | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_COMPONENT_ARM_DISARM (400) + +Arms / Disarms a component. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ---------------------- | +| 1 | | | 1 to arm, 0 to disarm. | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_RUN_PREARM_CHECKS (401) + +Instructs a target system to run pre-arm checks. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_INJECT_FAILURE (420) + +Inject artificial failure for testing purposes. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_START_RX_PAIR (500) + +Starts receiver pairing. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | -------------------------------- | +| 1 | | | 0:Spektrum | +| 2 | | | 0:Spektrum DSM2, 1:Spektrum DSMX | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_REQUEST_MESSAGE (512) + +Request to send a single instance of the specified message. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_REQUEST_CAMERA_INFORMATION (521) + +Request camera information (CAMERA_INFORMATION). + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------------------------------- | +| 1 | | | 0: No action 1: Request camera capabilities | +| 2 | | | Reserved (all remaining params) | +| 3 | | | Reserved (default:0) | +| 4 | | | Reserved (default:0) | +| 5 | | | Reserved (default:0) | +| 6 | | | Reserved (default:0) | +| 7 | | | Reserved (default:0) | + +### VEHICLE_CMD_SET_CAMERA_MODE (530) + +Set camera capture mode (photo, video, etc.). + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_SET_CAMERA_ZOOM (531) + +Set camera zoom. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_SET_CAMERA_FOCUS (532) + +None + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_EXTERNAL_ATTITUDE_ESTIMATE (620) + +Set an external estimate of vehicle attitude in degrees. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_DO_GIMBAL_MANAGER_PITCHYAW (1000) + +Setpoint to be sent to a gimbal manager to set a gimbal pitch and yaw. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_DO_GIMBAL_MANAGER_CONFIGURE (1001) + +Gimbal configuration to set which sysid/compid is in primary and secondary control. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_IMAGE_START_CAPTURE (2000) + +Start image capture sequence. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_DO_TRIGGER_CONTROL (2003) + +Enable or disable on-board camera triggering system. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_VIDEO_START_CAPTURE (2500) + +Start a video capture. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_VIDEO_STOP_CAPTURE (2501) + +Stop the current video capture. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_LOGGING_START (2510) + +Start streaming ULog data. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_LOGGING_STOP (2511) + +Stop streaming ULog data. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_CONTROL_HIGH_LATENCY (2600) + +Control starting/stopping transmitting data over the high latency link. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_DO_VTOL_TRANSITION (3000) + +Command VTOL transition. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_DO_SET_SAFETY_SWITCH_STATE (5300) + +Command safety on/off. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | -------------------------------------------------------------------------------- | +| 1 | | | 1 to activate safety, 0 to deactivate safety and allow control surface movements | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +### VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST (3001) + +Request arm authorization. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_PAYLOAD_PREPARE_DEPLOY (30001) + +Prepare a payload deployment in the flight plan. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_PAYLOAD_CONTROL_DEPLOY (30002) + +Control a pre-programmed payload deployment. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_FIXED_MAG_CAL_YAW (42006) + +Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_DO_WINCH (42600) + +Command to operate winch. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE (43003) + +External reset of estimator global position when dead reckoning. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_EXTERNAL_WIND_ESTIMATE (43004) + +None + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_PX4_INTERNAL_START (65537) + +Start of PX4 internal only vehicle commands (> UINT16_MAX). + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | ? | +| 2 | | | ? | +| 3 | | | ? | +| 4 | | | ? | +| 5 | | | ? | +| 6 | | | ? | +| 7 | | | ? | + +### VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN (100000) + +Sets the GPS coordinates of the vehicle local origin (0,0,0) position. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ------------------------------------------------ | +| 1 | | | Unused | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Latitude (WGS-84) | +| 6 | | | Longitude (WGS-84) | +| 7 | m | | Altitude (AMSL from GNSS, positive above ground) | + +### VEHICLE_CMD_SET_NAV_STATE (100001) + +Change mode by specifying nav_state directly. + +| Param | Units | Range/Enum | Description | +| ----- | ----- | ---------- | ----------- | +| 1 | | | nav_state | +| 2 | | | Unused | +| 3 | | | Unused | +| 4 | | | Unused | +| 5 | | | Unused | +| 6 | | | Unused | +| 7 | | | Unused | + +## Enums + +### ORBIT_YAW_BEHAVIOUR {#ORBIT_YAW_BEHAVIOUR} + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------------------------------------------------- | ------- | ----- | ----------- | +| ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER | `uint8` | 0 | +| ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING | `uint8` | 1 | +| ORBIT_YAW_BEHAVIOUR_UNCONTROLLED | `uint8` | 2 | +| ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE | `uint8` | 3 | +| ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED | `uint8` | 4 | +| ORBIT_YAW_BEHAVIOUR_UNCHANGED | `uint8` | 5 | + +### VEHICLE_ROI {#VEHICLE_ROI} + +| Name | Type | Value | Description | +| --------------------------------------------------------- | ------- | ----- | ---------------------------- | +| VEHICLE_ROI_NONE | `uint8` | 0 | No region of interest. | +| VEHICLE_ROI_WPNEXT | `uint8` | 1 | Point toward next MISSION. | +| VEHICLE_ROI_WPINDEX | `uint8` | 2 | Point toward given MISSION. | +| VEHICLE_ROI_LOCATION | `uint8` | 3 | Point toward fixed location. | +| VEHICLE_ROI_TARGET | `uint8` | 4 | Point toward target. | +| VEHICLE_ROI_ENUM_END | `uint8` | 5 | + +### SPEED_TYPE {#SPEED_TYPE} + +| Name | Type | Value | Description | +| ----------------------------------------------------------------- | ------- | ----- | ----------- | +| SPEED_TYPE_AIRSPEED | `uint8` | 0 | +| SPEED_TYPE_GROUNDSPEED | `uint8` | 1 | +| SPEED_TYPE_CLIMB_SPEED | `uint8` | 2 | +| SPEED_TYPE_DESCEND_SPEED | `uint8` | 3 | + +### MAV_MOUNT_MODE {#MAV_MOUNT_MODE} + +| Name | Type | Value | Description | +| ---- | ---- | ----- | ----------- | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------------------------------------------- | -------- | ----- | ------------------------------------------------------------------------------------------ | +| MESSAGE_VERSION | `uint32` | 0 | +| PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION | `uint16` | 3 | Param value for VEHICLE_CMD_PREFLIGHT_CALIBRATION to start temperature calibration. | +| VEHICLE_MOUNT_MODE_RETRACT | `uint8` | 0 | Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization. | +| VEHICLE_MOUNT_MODE_NEUTRAL | `uint8` | 1 | Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | +| VEHICLE_MOUNT_MODE_MAVLINK_TARGETING | `uint8` | 2 | Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization. | +| VEHICLE_MOUNT_MODE_RC_TARGETING | `uint8` | 3 | Load neutral position and start RC Roll,Pitch,Yaw control with stabilization. | +| VEHICLE_MOUNT_MODE_GPS_POINT | `uint8` | 4 | Load neutral position and start to point to Lat,Lon,Alt. | +| VEHICLE_MOUNT_MODE_ENUM_END | `uint8` | 5 | +| PARACHUTE_ACTION_DISABLE | `uint8` | 0 | +| PARACHUTE_ACTION_ENABLE | `uint8` | 1 | +| PARACHUTE_ACTION_RELEASE | `uint8` | 2 | +| FAILURE_UNIT_SENSOR_GYRO | `uint8` | 0 | +| FAILURE_UNIT_SENSOR_ACCEL | `uint8` | 1 | +| FAILURE_UNIT_SENSOR_MAG | `uint8` | 2 | +| FAILURE_UNIT_SENSOR_BARO | `uint8` | 3 | +| FAILURE_UNIT_SENSOR_GPS | `uint8` | 4 | +| FAILURE_UNIT_SENSOR_OPTICAL_FLOW | `uint8` | 5 | +| FAILURE_UNIT_SENSOR_VIO | `uint8` | 6 | +| FAILURE_UNIT_SENSOR_DISTANCE_SENSOR | `uint8` | 7 | +| FAILURE_UNIT_SENSOR_AIRSPEED | `uint8` | 8 | +| FAILURE_UNIT_SYSTEM_BATTERY | `uint8` | 100 | +| FAILURE_UNIT_SYSTEM_MOTOR | `uint8` | 101 | +| FAILURE_UNIT_SYSTEM_SERVO | `uint8` | 102 | +| FAILURE_UNIT_SYSTEM_AVOIDANCE | `uint8` | 103 | +| FAILURE_UNIT_SYSTEM_RC_SIGNAL | `uint8` | 104 | +| FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL | `uint8` | 105 | +| FAILURE_TYPE_OK | `uint8` | 0 | +| FAILURE_TYPE_OFF | `uint8` | 1 | +| FAILURE_TYPE_STUCK | `uint8` | 2 | +| FAILURE_TYPE_GARBAGE | `uint8` | 3 | +| FAILURE_TYPE_WRONG | `uint8` | 4 | +| FAILURE_TYPE_SLOW | `uint8` | 5 | +| FAILURE_TYPE_DELAYED | `uint8` | 6 | +| FAILURE_TYPE_INTERMITTENT | `uint8` | 7 | +| ARMING_ACTION_DISARM | `int8` | 0 | +| ARMING_ACTION_ARM | `int8` | 1 | +| GRIPPER_ACTION_RELEASE | `uint8` | 0 | +| GRIPPER_ACTION_GRAB | `uint8` | 1 | +| SAFETY_OFF | `uint8` | 0 | +| SAFETY_ON | `uint8` | 1 | +| ORB_QUEUE_LENGTH | `uint8` | 8 | +| COMPONENT_MODE_EXECUTOR_START | `uint16` | 1000 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleCommand.msg) + +::: details Click here to see original file ```c # Vehicle Command uORB message. Used for commanding a mission / action / etc. @@ -212,5 +1784,6 @@ bool from_external uint16 COMPONENT_MODE_EXECUTOR_START = 1000 # TOPICS vehicle_command gimbal_v1_command vehicle_command_mode_executor - ``` + +::: diff --git a/docs/en/msg_docs/VehicleCommandAck.md b/docs/en/msg_docs/VehicleCommandAck.md index e40b7bc87c..a06d896283 100644 --- a/docs/en/msg_docs/VehicleCommandAck.md +++ b/docs/en/msg_docs/VehicleCommandAck.md @@ -1,10 +1,51 @@ +--- +pageClass: is-wide-page +--- + # VehicleCommandAck (UORB message) -Vehicle Command Ackonwledgement uORB message. -Used for acknowledging the vehicle command being received. -Follows the MAVLink COMMAND_ACK message definition +Vehicle Command Ackonwledgement uORB message. Used for acknowledging the vehicle command being received. Follows the MAVLink COMMAND_ACK message definition. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleCommandAck.msg) +**TOPICS:** vehicle_commandack + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | -------- | ------------ | ---------- | ---------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| command | `uint32` | | | Command that is being acknowledged | +| result | `uint8` | | | Command result | +| result_param1 | `uint8` | | | Also used as progress[%], it can be set with the reason why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS | +| result_param2 | `int32` | | | Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied. | +| target_system | `uint8` | | | +| target_component | `uint16` | | | Target component / mode executor | +| from_external | `bool` | | | Indicates if the command came from an external source | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------------------------------- | -------- | ----- | --------------------------------- | +| MESSAGE_VERSION | `uint32` | 0 | +| VEHICLE_CMD_RESULT_ACCEPTED | `uint8` | 0 | Command ACCEPTED and EXECUTED | +| VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED | `uint8` | 1 | Command TEMPORARY REJECTED/DENIED | +| VEHICLE_CMD_RESULT_DENIED | `uint8` | 2 | Command PERMANENTLY DENIED | +| VEHICLE_CMD_RESULT_UNSUPPORTED | `uint8` | 3 | Command UNKNOWN/UNSUPPORTED | +| VEHICLE_CMD_RESULT_FAILED | `uint8` | 4 | Command executed, but failed | +| VEHICLE_CMD_RESULT_IN_PROGRESS | `uint8` | 5 | Command being executed | +| VEHICLE_CMD_RESULT_CANCELLED | `uint8` | 6 | Command Canceled | +| ARM_AUTH_DENIED_REASON_GENERIC | `uint16` | 0 | +| ARM_AUTH_DENIED_REASON_NONE | `uint16` | 1 | +| ARM_AUTH_DENIED_REASON_INVALID_WAYPOINT | `uint16` | 2 | +| ARM_AUTH_DENIED_REASON_TIMEOUT | `uint16` | 3 | +| ARM_AUTH_DENIED_REASON_AIRSPACE_IN_USE | `uint16` | 4 | +| ARM_AUTH_DENIED_REASON_BAD_WEATHER | `uint16` | 5 | +| ORB_QUEUE_LENGTH | `uint8` | 8 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleCommandAck.msg) + +::: details Click here to see original file ```c # Vehicle Command Ackonwledgement uORB message. @@ -32,7 +73,7 @@ uint16 ARM_AUTH_DENIED_REASON_TIMEOUT = 3 uint16 ARM_AUTH_DENIED_REASON_AIRSPACE_IN_USE = 4 uint16 ARM_AUTH_DENIED_REASON_BAD_WEATHER = 5 -uint8 ORB_QUEUE_LENGTH = 4 +uint8 ORB_QUEUE_LENGTH = 8 uint32 command # Command that is being acknowledged uint8 result # Command result @@ -42,5 +83,6 @@ uint8 target_system uint16 target_component # Target component / mode executor bool from_external # Indicates if the command came from an external source - ``` + +::: diff --git a/docs/en/msg_docs/VehicleConstraints.md b/docs/en/msg_docs/VehicleConstraints.md index 266ac8911f..ecca9d3576 100644 --- a/docs/en/msg_docs/VehicleConstraints.md +++ b/docs/en/msg_docs/VehicleConstraints.md @@ -1,9 +1,27 @@ +--- +pageClass: is-wide-page +--- + # VehicleConstraints (UORB message) -Local setpoint constraints in NED frame -setting something to NaN means that no limit is provided +Local setpoint constraints in NED frame. setting something to NaN means that no limit is provided. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleConstraints.msg) +**TOPICS:** vehicle_constraints + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------ | --------- | ------------ | ---------- | --------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| speed_up | `float32` | | | in meters/sec | +| speed_down | `float32` | | | in meters/sec | +| want_takeoff | `bool` | | | tell the controller to initiate takeoff when idling (ignored during flight) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleConstraints.msg) + +::: details Click here to see original file ```c # Local setpoint constraints in NED frame @@ -15,5 +33,6 @@ float32 speed_up # in meters/sec float32 speed_down # in meters/sec bool want_takeoff # tell the controller to initiate takeoff when idling (ignored during flight) - ``` + +::: diff --git a/docs/en/msg_docs/VehicleControlMode.md b/docs/en/msg_docs/VehicleControlMode.md index 0c6d062938..e122049c8c 100644 --- a/docs/en/msg_docs/VehicleControlMode.md +++ b/docs/en/msg_docs/VehicleControlMode.md @@ -1,8 +1,43 @@ +--- +pageClass: is-wide-page +--- + # VehicleControlMode (UORB message) +**TOPICS:** vehicle_control_mode config_control_setpoints +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleControlMode.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------------------------------- | -------- | ------------ | ---------- | ------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| flag_armed | `bool` | | | synonym for actuator_armed.armed | +| flag_multicopter_position_control_enabled | `bool` | | | +| flag_control_manual_enabled | `bool` | | | true if manual input is mixed in | +| flag_control_auto_enabled | `bool` | | | true if onboard autopilot should act | +| flag_control_offboard_enabled | `bool` | | | true if offboard control should be used | +| flag_control_position_enabled | `bool` | | | true if position is controlled | +| flag_control_velocity_enabled | `bool` | | | true if horizontal velocity (implies direction) is controlled | +| flag_control_altitude_enabled | `bool` | | | true if altitude is controlled | +| flag_control_climb_rate_enabled | `bool` | | | true if climb rate is controlled | +| flag_control_acceleration_enabled | `bool` | | | true if acceleration is controlled | +| flag_control_attitude_enabled | `bool` | | | true if attitude stabilization is mixed in | +| flag_control_rates_enabled | `bool` | | | true if rates are stabilized | +| flag_control_allocation_enabled | `bool` | | | true if control allocation is enabled | +| flag_control_termination_enabled | `bool` | | | true if flighttermination is enabled | +| source_id | `uint8` | | | Mode ID (nav_state) | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleControlMode.msg) + +::: details Click here to see original file ```c uint32 MESSAGE_VERSION = 0 @@ -29,5 +64,6 @@ bool flag_control_termination_enabled # true if flighttermination is enabled uint8 source_id # Mode ID (nav_state) # TOPICS vehicle_control_mode config_control_setpoints - ``` + +::: diff --git a/docs/en/msg_docs/VehicleGlobalPosition.md b/docs/en/msg_docs/VehicleGlobalPosition.md index c3e4147201..67ed199cd2 100644 --- a/docs/en/msg_docs/VehicleGlobalPosition.md +++ b/docs/en/msg_docs/VehicleGlobalPosition.md @@ -1,12 +1,47 @@ +--- +pageClass: is-wide-page +--- + # VehicleGlobalPosition (UORB message) -Fused global position in WGS84. -This struct contains global position estimation. It is not the raw GPS -measurement (@see vehicle_gps_position). This topic is usually published by the position -estimator, which will take more sources of information into account than just GPS, -e.g. control inputs of the vehicle in a Kalman-filter implementation. +Fused global position in WGS84. This struct contains global position estimation. It is not the raw GPS. measurement (@see vehicle_gps_position). This topic is usually published by the position. estimator, which will take more sources of information into account than just GPS,. e.g. control inputs of the vehicle in a Kalman-filter implementation. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleGlobalPosition.msg) +**TOPICS:** vehicle_global_position vehicle_global_position_groundtruth external_ins_global_position estimator_global_position aux_global_position + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------------- | --------- | ------------ | ---------- | ----------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| lat | `float64` | | | Latitude, (degrees) | +| lon | `float64` | | | Longitude, (degrees) | +| alt | `float32` | | | Altitude AMSL, (meters) | +| alt_ellipsoid | `float32` | | | Altitude above ellipsoid, (meters) | +| lat_lon_valid | `bool` | | | +| alt_valid | `bool` | | | +| delta_alt | `float32` | | | Reset delta for altitude | +| delta_terrain | `float32` | | | Reset delta for terrain | +| lat_lon_reset_counter | `uint8` | | | Counter for reset events on horizontal position coordinates | +| alt_reset_counter | `uint8` | | | Counter for reset events on altitude | +| terrain_reset_counter | `uint8` | | | Counter for reset events on terrain | +| eph | `float32` | | | Standard deviation of horizontal position error, (metres) | +| epv | `float32` | | | Standard deviation of vertical position error, (metres) | +| terrain_alt | `float32` | | | Terrain altitude WGS84, (metres) | +| terrain_alt_valid | `bool` | | | Terrain altitude estimate is valid | +| dead_reckoning | `bool` | | | True if this position is estimated through dead-reckoning | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleGlobalPosition.msg) + +::: details Click here to see original file ```c # Fused global position in WGS84. @@ -46,5 +81,6 @@ bool dead_reckoning # True if this position is estimated through dead-reckoning # TOPICS vehicle_global_position vehicle_global_position_groundtruth external_ins_global_position # TOPICS estimator_global_position # TOPICS aux_global_position - ``` + +::: diff --git a/docs/en/msg_docs/VehicleImu.md b/docs/en/msg_docs/VehicleImu.md index 5c3856f190..005cf34ae6 100644 --- a/docs/en/msg_docs/VehicleImu.md +++ b/docs/en/msg_docs/VehicleImu.md @@ -1,8 +1,43 @@ +--- +pageClass: is-wide-page +--- + # VehicleImu (UORB message) IMU readings in SI-unit form. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleImu.msg) +**TOPICS:** vehicle_imu + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------------- | ------------ | ------------ | ---------- | -------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | +| accel_device_id | `uint32` | | | Accelerometer unique device ID for the sensor that does not change between power cycles | +| gyro_device_id | `uint32` | | | Gyroscope unique device ID for the sensor that does not change between power cycles | +| delta_angle | `float32[3]` | | | delta angle about the FRD body frame XYZ-axis in rad over the integration time frame (delta_angle_dt) | +| delta_velocity | `float32[3]` | | | delta velocity in the FRD body frame XYZ-axis in m/s over the integration time frame (delta_velocity_dt) | +| delta_angle_dt | `uint32` | | | integration period in microseconds | +| delta_velocity_dt | `uint32` | | | integration period in microseconds | +| delta_angle_clipping | `uint8` | | | bitfield indicating if there was any gyro clipping (per axis) during the integration time frame | +| delta_velocity_clipping | `uint8` | | | bitfield indicating if there was any accelerometer clipping (per axis) during the integration time frame | +| accel_calibration_count | `uint8` | | | Calibration changed counter. Monotonically increases whenever accelermeter calibration changes. | +| gyro_calibration_count | `uint8` | | | Calibration changed counter. Monotonically increases whenever rate gyro calibration changes. | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------- | ------- | ----- | ----------- | +| CLIPPING_X | `uint8` | 1 | +| CLIPPING_Y | `uint8` | 2 | +| CLIPPING_Z | `uint8` | 4 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleImu.msg) + +::: details Click here to see original file ```c # IMU readings in SI-unit form. @@ -28,5 +63,6 @@ uint8 delta_velocity_clipping # bitfield indicating if there was any accelerom uint8 accel_calibration_count # Calibration changed counter. Monotonically increases whenever accelermeter calibration changes. uint8 gyro_calibration_count # Calibration changed counter. Monotonically increases whenever rate gyro calibration changes. - ``` + +::: diff --git a/docs/en/msg_docs/VehicleImuStatus.md b/docs/en/msg_docs/VehicleImuStatus.md index 1d26a7af36..bd7f1c89ec 100644 --- a/docs/en/msg_docs/VehicleImuStatus.md +++ b/docs/en/msg_docs/VehicleImuStatus.md @@ -1,8 +1,41 @@ +--- +pageClass: is-wide-page +--- + # VehicleImuStatus (UORB message) +**TOPICS:** vehicle_imustatus +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleImuStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------------- | ------------ | ------------ | ---------- | ------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| accel_device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| gyro_device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| accel_clipping | `uint32[3]` | | | total clipping per axis | +| gyro_clipping | `uint32[3]` | | | total clipping per axis | +| accel_error_count | `uint32` | | | +| gyro_error_count | `uint32` | | | +| accel_rate_hz | `float32` | | | +| gyro_rate_hz | `float32` | | | +| accel_raw_rate_hz | `float32` | | | full raw sensor sample rate (Hz) | +| gyro_raw_rate_hz | `float32` | | | full raw sensor sample rate (Hz) | +| accel_vibration_metric | `float32` | | | high frequency vibration level in the accelerometer data (m/s/s) | +| gyro_vibration_metric | `float32` | | | high frequency vibration level in the gyro data (rad/s) | +| delta_angle_coning_metric | `float32` | | | average IMU delta angle coning correction (rad^2) | +| mean_accel | `float32[3]` | | | average accelerometer readings since last publication | +| mean_gyro | `float32[3]` | | | average gyroscope readings since last publication | +| var_accel | `float32[3]` | | | accelerometer variance since last publication | +| var_gyro | `float32[3]` | | | gyroscope variance since last publication | +| temperature_accel | `float32` | | | +| temperature_gyro | `float32` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleImuStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -33,5 +66,6 @@ float32[3] var_gyro # gyroscope variance since last publication float32 temperature_accel float32 temperature_gyro - ``` + +::: diff --git a/docs/en/msg_docs/VehicleLandDetected.md b/docs/en/msg_docs/VehicleLandDetected.md index bd53ce680f..1756a382f1 100644 --- a/docs/en/msg_docs/VehicleLandDetected.md +++ b/docs/en/msg_docs/VehicleLandDetected.md @@ -1,8 +1,40 @@ +--- +pageClass: is-wide-page +--- + # VehicleLandDetected (UORB message) +**TOPICS:** vehicle_landdetected +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleLandDetected.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------------------- | -------- | ------------ | ---------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| freefall | `bool` | | | true if vehicle is currently in free-fall | +| ground_contact | `bool` | | | true if vehicle has ground contact but is not landed (1. stage) | +| maybe_landed | `bool` | | | true if the vehicle might have landed (2. stage) | +| landed | `bool` | | | true if vehicle is currently landed on the ground (3. stage) | +| in_ground_effect | `bool` | | | indicates if from the perspective of the landing detector the vehicle might be in ground effect (baro). This flag will become true if the vehicle is not moving horizontally and is descending (crude assumption that user is landing). | +| in_descend | `bool` | | | +| has_low_throttle | `bool` | | | +| vertical_movement | `bool` | | | +| horizontal_movement | `bool` | | | +| rotational_movement | `bool` | | | +| close_to_ground_or_skipped_check | `bool` | | | +| at_rest | `bool` | | | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleLandDetected.msg) + +::: details Click here to see original file ```c uint32 MESSAGE_VERSION = 0 @@ -26,5 +58,6 @@ bool rotational_movement bool close_to_ground_or_skipped_check bool at_rest - ``` + +::: diff --git a/docs/en/msg_docs/VehicleLocalPosition.md b/docs/en/msg_docs/VehicleLocalPosition.md index af84dc1ddb..855cb89910 100644 --- a/docs/en/msg_docs/VehicleLocalPosition.md +++ b/docs/en/msg_docs/VehicleLocalPosition.md @@ -1,9 +1,85 @@ +--- +pageClass: is-wide-page +--- + # VehicleLocalPosition (UORB message) -Fused local position in NED. -The coordinate system origin is the vehicle position at the time when the EKF2-module was started. +Fused local position in NED. The coordinate system origin is the vehicle position at the time when the EKF2-module was started. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleLocalPosition.msg) +**TOPICS:** vehicle_local_position vehicle_local_position_groundtruth external_ins_local_position estimator_local_position + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------------------- | ------------ | ------------ | ---------- | ----------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| xy_valid | `bool` | | | true if x and y are valid | +| z_valid | `bool` | | | true if z is valid | +| v_xy_valid | `bool` | | | true if vx and vy are valid | +| v_z_valid | `bool` | | | true if vz is valid | +| x | `float32` | | | North position in NED earth-fixed frame, (metres) | +| y | `float32` | | | East position in NED earth-fixed frame, (metres) | +| z | `float32` | | | Down position (negative altitude) in NED earth-fixed frame, (metres) | +| delta_xy | `float32[2]` | | | Amount of lateral shift of position estimate in latest reset (in x and y) [m] | +| xy_reset_counter | `uint8` | | | Index of latest lateral position estimate reset | +| delta_z | `float32` | | | Amount of vertical shift of position estimate in latest reset [m] | +| z_reset_counter | `uint8` | | | Index of latest vertical position estimate reset | +| vx | `float32` | | | North velocity in NED earth-fixed frame, (metres/sec) | +| vy | `float32` | | | East velocity in NED earth-fixed frame, (metres/sec) | +| vz | `float32` | | | Down velocity in NED earth-fixed frame, (metres/sec) | +| z_deriv | `float32` | | | Down position time derivative in NED earth-fixed frame, (metres/sec) | +| delta_vxy | `float32[2]` | | | Amount of lateral shift of velocity estimate in latest reset (in x and y) [m/s] | +| vxy_reset_counter | `uint8` | | | Index of latest vertical velocity estimate reset | +| delta_vz | `float32` | | | Amount of vertical shift of velocity estimate in latest reset [m/s] | +| vz_reset_counter | `uint8` | | | Index of latest vertical velocity estimate reset | +| ax | `float32` | | | North velocity derivative in NED earth-fixed frame, (metres/sec^2) | +| ay | `float32` | | | East velocity derivative in NED earth-fixed frame, (metres/sec^2) | +| az | `float32` | | | Down velocity derivative in NED earth-fixed frame, (metres/sec^2) | +| heading | `float32` | | | Euler yaw angle transforming the tangent plane relative to NED earth-fixed frame, -PI..+PI, (radians) | +| heading_var | `float32` | | | +| unaided_heading | `float32` | | | Same as heading but generated by integrating corrected gyro data only | +| delta_heading | `float32` | | | Heading delta caused by latest heading reset [rad] | +| heading_reset_counter | `uint8` | | | Index of latest heading reset | +| heading_good_for_control | `bool` | | | +| tilt_var | `float32` | | | +| xy_global | `bool` | | | true if position (x, y) has a valid global reference (ref_lat, ref_lon) | +| z_global | `bool` | | | true if z has a valid global reference (ref_alt) | +| ref_timestamp | `uint64` | | | Time when reference position was set since system start, (microseconds) | +| ref_lat | `float64` | | | Reference point latitude, (degrees) | +| ref_lon | `float64` | | | Reference point longitude, (degrees) | +| ref_alt | `float32` | | | Reference altitude AMSL, (metres) | +| dist_bottom_valid | `bool` | | | true if distance to bottom surface is valid | +| dist_bottom | `float32` | | | Distance from from bottom surface to ground, (metres) | +| dist_bottom_var | `float32` | | | terrain estimate variance (m^2) | +| delta_dist_bottom | `float32` | | | Amount of vertical shift of dist bottom estimate in latest reset [m] | +| dist_bottom_reset_counter | `uint8` | | | Index of latest dist bottom estimate reset | +| dist_bottom_sensor_bitfield | `uint8` | | | bitfield indicating what type of sensor is used to estimate dist_bottom | +| eph | `float32` | | | Standard deviation of horizontal position error, (metres) | +| epv | `float32` | | | Standard deviation of vertical position error, (metres) | +| evh | `float32` | | | Standard deviation of horizontal velocity error, (metres/sec) | +| evv | `float32` | | | Standard deviation of vertical velocity error, (metres/sec) | +| dead_reckoning | `bool` | | | True if this position is estimated through dead-reckoning | +| vxy_max | `float32` | | | maximum horizontal speed (meters/sec) | +| vz_max | `float32` | | | maximum vertical speed (meters/sec) | +| hagl_min | `float32` | | | minimum height above ground level (meters) | +| hagl_max_z | `float32` | | | maximum height above ground level for z-control (meters) | +| hagl_max_xy | `float32` | | | maximum height above ground level for xy-control (meters) | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------- | -------- | ----- | ----------------------------------------------------------------------------------------- | +| MESSAGE_VERSION | `uint32` | 1 | +| DIST_BOTTOM_SENSOR_NONE | `uint8` | 0 | +| DIST_BOTTOM_SENSOR_RANGE | `uint8` | 1 | (1 << 0) a range sensor is used to estimate dist_bottom field | +| DIST_BOTTOM_SENSOR_FLOW | `uint8` | 2 | (1 << 1) a flow sensor is used to estimate dist_bottom field (mostly fixed-wing use case) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleLocalPosition.msg) + +::: details Click here to see original file ```c # Fused local position in NED. @@ -94,5 +170,6 @@ float32 hagl_max_xy # maximum height above ground level for xy-control (meters # TOPICS vehicle_local_position vehicle_local_position_groundtruth external_ins_local_position # TOPICS estimator_local_position - ``` + +::: diff --git a/docs/en/msg_docs/VehicleLocalPositionSetpoint.md b/docs/en/msg_docs/VehicleLocalPositionSetpoint.md index 15f66292b3..e4fa76c086 100644 --- a/docs/en/msg_docs/VehicleLocalPositionSetpoint.md +++ b/docs/en/msg_docs/VehicleLocalPositionSetpoint.md @@ -1,10 +1,34 @@ +--- +pageClass: is-wide-page +--- + # VehicleLocalPositionSetpoint (UORB message) -Local position setpoint in NED frame -Telemetry of PID position controller to monitor tracking. -NaN means the state was not controlled +Local position setpoint in NED frame. Telemetry of PID position controller to monitor tracking. NaN means the state was not controlled. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleLocalPositionSetpoint.msg) +**TOPICS:** vehicle_localposition_setpoint + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------ | ------------ | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| x | `float32` | | | in meters NED | +| y | `float32` | | | in meters NED | +| z | `float32` | | | in meters NED | +| vx | `float32` | | | in meters/sec | +| vy | `float32` | | | in meters/sec | +| vz | `float32` | | | in meters/sec | +| acceleration | `float32[3]` | | | in meters/sec^2 | +| thrust | `float32[3]` | | | normalized thrust vector in NED | +| yaw | `float32` | | | in radians NED -PI..+PI | +| yawspeed | `float32` | | | in radians/sec | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleLocalPositionSetpoint.msg) + +::: details Click here to see original file ```c # Local position setpoint in NED frame @@ -26,5 +50,6 @@ float32[3] thrust # normalized thrust vector in NED float32 yaw # in radians NED -PI..+PI float32 yawspeed # in radians/sec - ``` + +::: diff --git a/docs/en/msg_docs/VehicleLocalPositionV0.md b/docs/en/msg_docs/VehicleLocalPositionV0.md index 05d9361dc1..1596c85b1b 100644 --- a/docs/en/msg_docs/VehicleLocalPositionV0.md +++ b/docs/en/msg_docs/VehicleLocalPositionV0.md @@ -1,9 +1,84 @@ +--- +pageClass: is-wide-page +--- + # VehicleLocalPositionV0 (UORB message) -Fused local position in NED. -The coordinate system origin is the vehicle position at the time when the EKF2-module was started. +Fused local position in NED. The coordinate system origin is the vehicle position at the time when the EKF2-module was started. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/VehicleLocalPositionV0.msg) +**TOPICS:** vehicle_local_position vehicle_local_position_groundtruth external_ins_local_position estimator_local_position + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------------------- | ------------ | ------------ | ---------- | ----------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| xy_valid | `bool` | | | true if x and y are valid | +| z_valid | `bool` | | | true if z is valid | +| v_xy_valid | `bool` | | | true if vx and vy are valid | +| v_z_valid | `bool` | | | true if vz is valid | +| x | `float32` | | | North position in NED earth-fixed frame, (metres) | +| y | `float32` | | | East position in NED earth-fixed frame, (metres) | +| z | `float32` | | | Down position (negative altitude) in NED earth-fixed frame, (metres) | +| delta_xy | `float32[2]` | | | Amount of lateral shift of position estimate in latest reset (in x and y) [m] | +| xy_reset_counter | `uint8` | | | Index of latest lateral position estimate reset | +| delta_z | `float32` | | | Amount of vertical shift of position estimate in latest reset [m] | +| z_reset_counter | `uint8` | | | Index of latest vertical position estimate reset | +| vx | `float32` | | | North velocity in NED earth-fixed frame, (metres/sec) | +| vy | `float32` | | | East velocity in NED earth-fixed frame, (metres/sec) | +| vz | `float32` | | | Down velocity in NED earth-fixed frame, (metres/sec) | +| z_deriv | `float32` | | | Down position time derivative in NED earth-fixed frame, (metres/sec) | +| delta_vxy | `float32[2]` | | | Amount of lateral shift of velocity estimate in latest reset (in x and y) [m/s] | +| vxy_reset_counter | `uint8` | | | Index of latest vertical velocity estimate reset | +| delta_vz | `float32` | | | Amount of vertical shift of velocity estimate in latest reset [m/s] | +| vz_reset_counter | `uint8` | | | Index of latest vertical velocity estimate reset | +| ax | `float32` | | | North velocity derivative in NED earth-fixed frame, (metres/sec^2) | +| ay | `float32` | | | East velocity derivative in NED earth-fixed frame, (metres/sec^2) | +| az | `float32` | | | Down velocity derivative in NED earth-fixed frame, (metres/sec^2) | +| heading | `float32` | | | Euler yaw angle transforming the tangent plane relative to NED earth-fixed frame, -PI..+PI, (radians) | +| heading_var | `float32` | | | +| unaided_heading | `float32` | | | Same as heading but generated by integrating corrected gyro data only | +| delta_heading | `float32` | | | Heading delta caused by latest heading reset [rad] | +| heading_reset_counter | `uint8` | | | Index of latest heading reset | +| heading_good_for_control | `bool` | | | +| tilt_var | `float32` | | | +| xy_global | `bool` | | | true if position (x, y) has a valid global reference (ref_lat, ref_lon) | +| z_global | `bool` | | | true if z has a valid global reference (ref_alt) | +| ref_timestamp | `uint64` | | | Time when reference position was set since system start, (microseconds) | +| ref_lat | `float64` | | | Reference point latitude, (degrees) | +| ref_lon | `float64` | | | Reference point longitude, (degrees) | +| ref_alt | `float32` | | | Reference altitude AMSL, (metres) | +| dist_bottom_valid | `bool` | | | true if distance to bottom surface is valid | +| dist_bottom | `float32` | | | Distance from from bottom surface to ground, (metres) | +| dist_bottom_var | `float32` | | | terrain estimate variance (m^2) | +| delta_dist_bottom | `float32` | | | Amount of vertical shift of dist bottom estimate in latest reset [m] | +| dist_bottom_reset_counter | `uint8` | | | Index of latest dist bottom estimate reset | +| dist_bottom_sensor_bitfield | `uint8` | | | bitfield indicating what type of sensor is used to estimate dist_bottom | +| eph | `float32` | | | Standard deviation of horizontal position error, (metres) | +| epv | `float32` | | | Standard deviation of vertical position error, (metres) | +| evh | `float32` | | | Standard deviation of horizontal velocity error, (metres/sec) | +| evv | `float32` | | | Standard deviation of vertical velocity error, (metres/sec) | +| dead_reckoning | `bool` | | | True if this position is estimated through dead-reckoning | +| vxy_max | `float32` | | | maximum horizontal speed - set to 0 when limiting not required (meters/sec) | +| vz_max | `float32` | | | maximum vertical speed - set to 0 when limiting not required (meters/sec) | +| hagl_min | `float32` | | | minimum height above ground level - set to 0 when limiting not required (meters) | +| hagl_max | `float32` | | | maximum height above ground level - set to 0 when limiting not required (meters) | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------- | -------- | ----- | ----------------------------------------------------------------------------------------- | +| MESSAGE_VERSION | `uint32` | 0 | +| DIST_BOTTOM_SENSOR_NONE | `uint8` | 0 | +| DIST_BOTTOM_SENSOR_RANGE | `uint8` | 1 | (1 << 0) a range sensor is used to estimate dist_bottom field | +| DIST_BOTTOM_SENSOR_FLOW | `uint8` | 2 | (1 << 1) a flow sensor is used to estimate dist_bottom field (mostly fixed-wing use case) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/VehicleLocalPositionV0.msg) + +::: details Click here to see original file ```c # Fused local position in NED. @@ -92,5 +167,6 @@ float32 hagl_max # maximum height above ground level - set to 0 when limiting # TOPICS vehicle_local_position vehicle_local_position_groundtruth external_ins_local_position # TOPICS estimator_local_position - ``` + +::: diff --git a/docs/en/msg_docs/VehicleMagnetometer.md b/docs/en/msg_docs/VehicleMagnetometer.md index 3d8f504fd4..23be7d6896 100644 --- a/docs/en/msg_docs/VehicleMagnetometer.md +++ b/docs/en/msg_docs/VehicleMagnetometer.md @@ -1,11 +1,28 @@ +--- +pageClass: is-wide-page +--- + # VehicleMagnetometer (UORB message) +**TOPICS:** vehicle_magnetometer +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleMagnetometer.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------- | ------------ | ------------ | ---------- | ---------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| device_id | `uint32` | | | unique device ID for the selected magnetometer | +| magnetometer_ga | `float32[3]` | | | Magnetic field in the FRD body frame XYZ-axis in Gauss | +| calibration_count | `uint8` | | | Calibration changed counter. Monotonically increases whenever calibration changes. | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleMagnetometer.msg) + +::: details Click here to see original file ```c - uint64 timestamp # time since system start (microseconds) uint64 timestamp_sample # the timestamp of the raw data (microseconds) @@ -15,5 +32,6 @@ uint32 device_id # unique device ID for the selected magnetometer float32[3] magnetometer_ga # Magnetic field in the FRD body frame XYZ-axis in Gauss uint8 calibration_count # Calibration changed counter. Monotonically increases whenever calibration changes. - ``` + +::: diff --git a/docs/en/msg_docs/VehicleOdometry.md b/docs/en/msg_docs/VehicleOdometry.md index 4213c23337..a89f94d675 100644 --- a/docs/en/msg_docs/VehicleOdometry.md +++ b/docs/en/msg_docs/VehicleOdometry.md @@ -1,10 +1,63 @@ +--- +pageClass: is-wide-page +--- + # VehicleOdometry (UORB message) -Vehicle odometry data +Vehicle odometry data. Fits ROS REP 147 for aerial vehicles -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleOdometry.msg) +**TOPICS:** vehicle_odometry vehicle_mocap_odometry vehicle_visual_odometry estimator_odometry + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------------- | ------------ | -------------------------------- | --------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| timestamp_sample | `uint64` | us | | Timestamp sample | +| pose_frame | `uint8` | | [POSE_FRAME](#POSE_FRAME) | Position and orientation frame of reference | +| position | `float32[3]` | m [local frame] | | Position. Origin is position of GC at startup. (Invalid: NaN If invalid/unknown) | +| q | `float32[4]` | | | Attitude (expressed as a quaternion) relative to pose reference frame at current location. Follows the Hamiltonian convention (w, x, y, z, right-handed, passive rotations from body to world) (Invalid: NaN First value if invalid/unknown) | +| velocity_frame | `uint8` | | [VELOCITY_FRAME](#VELOCITY_FRAME) | Reference frame of the velocity data | +| velocity | `float32[3]` | m/s [@velocity_frame] | | Velocity. (Invalid: NaN If invalid/unknown) | +| angular_velocity | `float32[3]` | rad/s [@VELOCITY_FRAME_BODY_FRD] | | Angular velocity in body-fixed frame (Invalid: NaN If invalid/unknown) | +| position_variance | `float32[3]` | m^2 | | Variance of position error | +| orientation_variance | `float32[3]` | rad^2 | | Variance of orientation/attitude error (expressed in body frame) | +| velocity_variance | `float32[3]` | m^2/s^2 | | Variance of velocity error | +| reset_counter | `uint8` | | | Reset counter. Counts reset events on attitude, velocity and position. | +| quality | `int8` | | | Quality. Unused. (Invalid: 0) | + +## Enums + +### POSE_FRAME {#POSE_FRAME} + +| Name | Type | Value | Description | +| ----------------------------------------------------- | ------- | ----- | --------------------------------------------------------------------------------------------- | +| POSE_FRAME_UNKNOWN | `uint8` | 0 | Unknown frame | +| POSE_FRAME_NED | `uint8` | 1 | North-East-Down (NED) navigation frame. Aligned with True North. | +| POSE_FRAME_FRD | `uint8` | 2 | Forward-Right-Down (FRD) frame. Constant arbitrary heading offset from True North. Z is down. | + +### VELOCITY_FRAME {#VELOCITY_FRAME} + +| Name | Type | Value | Description | +| --------------------------------------------------------------- | ------- | ----- | ------------------------------------------------------------------------------------------------------- | +| VELOCITY_FRAME_UNKNOWN | `uint8` | 0 | Unknown frame | +| VELOCITY_FRAME_NED | `uint8` | 1 | NED navigation frame at current position. | +| VELOCITY_FRAME_FRD | `uint8` | 2 | FRD navigation frame at current position. Constant arbitrary heading offset from True North. Z is down. | +| VELOCITY_FRAME_BODY_FRD | `uint8` | 3 | FRD body-fixed frame | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleOdometry.msg) + +::: details Click here to see original file ```c # Vehicle odometry data @@ -42,5 +95,6 @@ int8 quality # [-] [@invalid 0] Quality. Unused. # TOPICS vehicle_odometry vehicle_mocap_odometry vehicle_visual_odometry # TOPICS estimator_odometry - ``` + +::: diff --git a/docs/en/msg_docs/VehicleOpticalFlow.md b/docs/en/msg_docs/VehicleOpticalFlow.md index 21bd5ab438..298502f826 100644 --- a/docs/en/msg_docs/VehicleOpticalFlow.md +++ b/docs/en/msg_docs/VehicleOpticalFlow.md @@ -1,8 +1,34 @@ +--- +pageClass: is-wide-page +--- + # VehicleOpticalFlow (UORB message) Optical flow in XYZ body frame in SI units. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleOpticalFlow.msg) +**TOPICS:** vehicle_opticalflow + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------------- | ------------ | ------------ | ---------- | ---------------------------------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | +| device_id | `uint32` | | | unique device ID for the sensor that does not change between power cycles | +| pixel_flow | `float32[2]` | | | (radians) accumulated optical flow in radians where a positive value is produced by a RH rotation about the body axis | +| delta_angle | `float32[3]` | | | (radians) accumulated gyro radians where a positive value is produced by a RH rotation of the sensor about the body axis. (NAN if unavailable) | +| distance_m | `float32` | | | (meters) Distance to the center of the flow field (NAN if unavailable) | +| integration_timespan_us | `uint32` | | | (microseconds) accumulation timespan in microseconds | +| quality | `uint8` | | | Average of quality of accumulated frames, 0: bad quality, 255: maximum quality | +| max_flow_rate | `float32` | | | (radians/s) Magnitude of maximum angular which the optical flow sensor can measure reliably | +| min_ground_distance | `float32` | | | (meters) Minimum distance from ground at which the optical flow sensor operates reliably | +| max_ground_distance | `float32` | | | (meters) Maximum distance from ground at which the optical flow sensor operates reliably | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleOpticalFlow.msg) + +::: details Click here to see original file ```c # Optical flow in XYZ body frame in SI units. @@ -26,5 +52,6 @@ float32 max_flow_rate # (radians/s) Magnitude of maximum angular which float32 min_ground_distance # (meters) Minimum distance from ground at which the optical flow sensor operates reliably float32 max_ground_distance # (meters) Maximum distance from ground at which the optical flow sensor operates reliably - ``` + +::: diff --git a/docs/en/msg_docs/VehicleOpticalFlowVel.md b/docs/en/msg_docs/VehicleOpticalFlowVel.md index eec61e9ba9..7431dafc15 100644 --- a/docs/en/msg_docs/VehicleOpticalFlowVel.md +++ b/docs/en/msg_docs/VehicleOpticalFlowVel.md @@ -1,8 +1,32 @@ +--- +pageClass: is-wide-page +--- + # VehicleOpticalFlowVel (UORB message) +**TOPICS:** estimator_optical_flow_vel vehicle_optical_flow_vel +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleOpticalFlowVel.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------------------- | ------------ | ------------ | ---------- | --------------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| vel_body | `float32[2]` | | | velocity obtained from gyro-compensated and distance-scaled optical flow raw measurements in body frame(m/s) | +| vel_ne | `float32[2]` | | | same as vel_body but in local frame (m/s) | +| vel_body_filtered | `float32[2]` | | | filtered velocity obtained from gyro-compensated and distance-scaled optical flow raw measurements in body frame(m/s) | +| vel_ne_filtered | `float32[2]` | | | filtered same as vel_body_filtered but in local frame (m/s) | +| flow_rate_uncompensated | `float32[2]` | | | integrated optical flow measurement (rad/s) | +| flow_rate_compensated | `float32[2]` | | | integrated optical flow measurement compensated for angular motion (rad/s) | +| gyro_rate | `float32[3]` | | | gyro measurement synchronized with flow measurements (rad/s) | +| gyro_bias | `float32[3]` | | | +| ref_gyro | `float32[3]` | | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleOpticalFlowVel.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -23,5 +47,6 @@ float32[3] gyro_bias float32[3] ref_gyro # TOPICS estimator_optical_flow_vel vehicle_optical_flow_vel - ``` + +::: diff --git a/docs/en/msg_docs/VehicleRatesSetpoint.md b/docs/en/msg_docs/VehicleRatesSetpoint.md index ebc5827d68..89184ec42d 100644 --- a/docs/en/msg_docs/VehicleRatesSetpoint.md +++ b/docs/en/msg_docs/VehicleRatesSetpoint.md @@ -1,8 +1,33 @@ +--- +pageClass: is-wide-page +--- + # VehicleRatesSetpoint (UORB message) +**TOPICS:** vehicle_ratessetpoint +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleRatesSetpoint.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| -------------- | ------------ | ------------ | ---------- | -------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| roll | `float32` | rad/s | | roll rate setpoint | +| pitch | `float32` | rad/s | | pitch rate setpoint | +| yaw | `float32` | rad/s | | yaw rate setpoint | +| thrust_body | `float32[3]` | | | Normalized thrust command in body NED frame [-1,1] | +| reset_integral | `bool` | | | Reset roll/pitch/yaw integrals (navigation logic change) | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleRatesSetpoint.msg) + +::: details Click here to see original file ```c uint32 MESSAGE_VERSION = 0 @@ -19,5 +44,6 @@ float32 yaw # [rad/s] yaw rate setpoint float32[3] thrust_body # Normalized thrust command in body NED frame [-1,1] bool reset_integral # Reset roll/pitch/yaw integrals (navigation logic change) - ``` + +::: diff --git a/docs/en/msg_docs/VehicleRoi.md b/docs/en/msg_docs/VehicleRoi.md index 9f3533e29f..3ddf7ad10b 100644 --- a/docs/en/msg_docs/VehicleRoi.md +++ b/docs/en/msg_docs/VehicleRoi.md @@ -1,8 +1,42 @@ +--- +pageClass: is-wide-page +--- + # VehicleRoi (UORB message) -Vehicle Region Of Interest (ROI) +Vehicle Region Of Interest (ROI). -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleRoi.msg) +**TOPICS:** vehicle_roi + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------ | --------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| mode | `uint8` | | | ROI mode (see above) | +| lat | `float64` | | | Latitude to point to | +| lon | `float64` | | | Longitude to point to | +| alt | `float32` | | | Altitude to point to | +| roll_offset | `float32` | | | angle offset in rad | +| pitch_offset | `float32` | | | angle offset in rad | +| yaw_offset | `float32` | | | angle offset in rad | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------- | ------- | ----- | ---------------------------------------------- | +| ROI_NONE | `uint8` | 0 | No region of interest | +| ROI_WPNEXT | `uint8` | 1 | Point toward next MISSION with optional offset | +| ROI_WPINDEX | `uint8` | 2 | Point toward given MISSION | +| ROI_LOCATION | `uint8` | 3 | Point toward fixed location | +| ROI_TARGET | `uint8` | 4 | Point toward target | +| ROI_ENUM_END | `uint8` | 5 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleRoi.msg) + +::: details Click here to see original file ```c # Vehicle Region Of Interest (ROI) @@ -26,5 +60,6 @@ float32 alt # Altitude to point to float32 roll_offset # angle offset in rad float32 pitch_offset # angle offset in rad float32 yaw_offset # angle offset in rad - ``` + +::: diff --git a/docs/en/msg_docs/VehicleStatus.md b/docs/en/msg_docs/VehicleStatus.md index 05e3f98bbb..e9ea5416ff 100644 --- a/docs/en/msg_docs/VehicleStatus.md +++ b/docs/en/msg_docs/VehicleStatus.md @@ -1,8 +1,130 @@ +--- +pageClass: is-wide-page +--- + # VehicleStatus (UORB message) -Encodes the system state of the vehicle published by commander +Encodes the system state of the vehicle published by commander. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleStatus.msg) +**TOPICS:** vehicle_status + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------------- | -------- | ------------ | ---------- | ----------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| armed_time | `uint64` | | | Arming timestamp (microseconds) | +| takeoff_time | `uint64` | | | Takeoff timestamp (microseconds) | +| arming_state | `uint8` | | | +| latest_arming_reason | `uint8` | | | +| latest_disarming_reason | `uint8` | | | +| nav_state_timestamp | `uint64` | | | time when current nav_state activated | +| nav_state_user_intention | `uint8` | | | Mode that the user selected (might be different from nav_state in a failsafe situation) | +| nav_state | `uint8` | | | Currently active mode | +| executor_in_charge | `uint8` | | | Current mode executor in charge (0=Autopilot) | +| valid_nav_states_mask | `uint32` | | | Bitmask for all valid nav_state values | +| can_set_nav_states_mask | `uint32` | | | Bitmask for all modes that a user can select | +| failure_detector_status | `uint16` | | | +| hil_state | `uint8` | | | +| vehicle_type | `uint8` | | | +| failsafe | `bool` | | | true if system is in failsafe state (e.g.:RTL, Hover, Terminate, ...) | +| failsafe_and_user_took_over | `bool` | | | true if system is in failsafe state but the user took over control | +| failsafe_defer_state | `uint8` | | | one of FAILSAFE*DEFER_STATE*\* | +| gcs_connection_lost | `bool` | | | datalink to GCS lost | +| gcs_connection_lost_counter | `uint8` | | | counts unique GCS connection lost events | +| high_latency_data_link_lost | `bool` | | | Set to true if the high latency data link (eg. RockBlock Iridium 9603 telemetry module) is lost | +| is_vtol | `bool` | | | True if the system is VTOL capable | +| is_vtol_tailsitter | `bool` | | | True if the system performs a 90° pitch down rotation during transition from MC to FW | +| in_transition_mode | `bool` | | | True if VTOL is doing a transition | +| in_transition_to_fw | `bool` | | | True if VTOL is doing a transition from MC to FW | +| system_type | `uint8` | | | system type, contains mavlink MAV_TYPE | +| system_id | `uint8` | | | system id, contains MAVLink's system ID field | +| component_id | `uint8` | | | subsystem / component id, contains MAVLink's component ID field | +| safety_button_available | `bool` | | | Set to true if a safety button is connected | +| safety_off | `bool` | | | Set to true if safety is off | +| power_input_valid | `bool` | | | set if input power is valid | +| usb_connected | `bool` | | | set to true (never cleared) once telemetry received from usb link | +| open_drone_id_system_present | `bool` | | | +| open_drone_id_system_healthy | `bool` | | | +| parachute_system_present | `bool` | | | +| parachute_system_healthy | `bool` | | | +| rc_calibration_in_progress | `bool` | | | +| calibration_enabled | `bool` | | | +| pre_flight_checks_pass | `bool` | | | true if all checks necessary to arm pass | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------------------------- | -------- | ----- | ------------------------------------------------ | +| MESSAGE_VERSION | `uint32` | 1 | +| ARMING_STATE_DISARMED | `uint8` | 1 | +| ARMING_STATE_ARMED | `uint8` | 2 | +| ARM_DISARM_REASON_STICK_GESTURE | `uint8` | 1 | +| ARM_DISARM_REASON_RC_SWITCH | `uint8` | 2 | +| ARM_DISARM_REASON_COMMAND_INTERNAL | `uint8` | 3 | +| ARM_DISARM_REASON_COMMAND_EXTERNAL | `uint8` | 4 | +| ARM_DISARM_REASON_MISSION_START | `uint8` | 5 | +| ARM_DISARM_REASON_LANDING | `uint8` | 6 | +| ARM_DISARM_REASON_PREFLIGHT_INACTION | `uint8` | 7 | +| ARM_DISARM_REASON_KILL_SWITCH | `uint8` | 8 | +| ARM_DISARM_REASON_RC_BUTTON | `uint8` | 13 | +| ARM_DISARM_REASON_FAILSAFE | `uint8` | 14 | +| NAVIGATION_STATE_MANUAL | `uint8` | 0 | Manual mode | +| NAVIGATION_STATE_ALTCTL | `uint8` | 1 | Altitude control mode | +| NAVIGATION_STATE_POSCTL | `uint8` | 2 | Position control mode | +| NAVIGATION_STATE_AUTO_MISSION | `uint8` | 3 | Auto mission mode | +| NAVIGATION_STATE_AUTO_LOITER | `uint8` | 4 | Auto loiter mode | +| NAVIGATION_STATE_AUTO_RTL | `uint8` | 5 | Auto return to launch mode | +| NAVIGATION_STATE_POSITION_SLOW | `uint8` | 6 | +| NAVIGATION_STATE_FREE5 | `uint8` | 7 | +| NAVIGATION_STATE_ALTITUDE_CRUISE | `uint8` | 8 | Altitude with Cruise mode | +| NAVIGATION_STATE_FREE3 | `uint8` | 9 | +| NAVIGATION_STATE_ACRO | `uint8` | 10 | Acro mode | +| NAVIGATION_STATE_FREE2 | `uint8` | 11 | +| NAVIGATION_STATE_DESCEND | `uint8` | 12 | Descend mode (no position control) | +| NAVIGATION_STATE_TERMINATION | `uint8` | 13 | Termination mode | +| NAVIGATION_STATE_OFFBOARD | `uint8` | 14 | +| NAVIGATION_STATE_STAB | `uint8` | 15 | Stabilized mode | +| NAVIGATION_STATE_FREE1 | `uint8` | 16 | +| NAVIGATION_STATE_AUTO_TAKEOFF | `uint8` | 17 | Takeoff | +| NAVIGATION_STATE_AUTO_LAND | `uint8` | 18 | Land | +| NAVIGATION_STATE_AUTO_FOLLOW_TARGET | `uint8` | 19 | Auto Follow | +| NAVIGATION_STATE_AUTO_PRECLAND | `uint8` | 20 | Precision land with landing target | +| NAVIGATION_STATE_ORBIT | `uint8` | 21 | Orbit in a circle | +| NAVIGATION_STATE_AUTO_VTOL_TAKEOFF | `uint8` | 22 | Takeoff, transition, establish loiter | +| NAVIGATION_STATE_EXTERNAL1 | `uint8` | 23 | +| NAVIGATION_STATE_EXTERNAL2 | `uint8` | 24 | +| NAVIGATION_STATE_EXTERNAL3 | `uint8` | 25 | +| NAVIGATION_STATE_EXTERNAL4 | `uint8` | 26 | +| NAVIGATION_STATE_EXTERNAL5 | `uint8` | 27 | +| NAVIGATION_STATE_EXTERNAL6 | `uint8` | 28 | +| NAVIGATION_STATE_EXTERNAL7 | `uint8` | 29 | +| NAVIGATION_STATE_EXTERNAL8 | `uint8` | 30 | +| NAVIGATION_STATE_MAX | `uint8` | 31 | +| FAILURE_NONE | `uint16` | 0 | +| FAILURE_ROLL | `uint16` | 1 | (1 << 0) | +| FAILURE_PITCH | `uint16` | 2 | (1 << 1) | +| FAILURE_ALT | `uint16` | 4 | (1 << 2) | +| FAILURE_EXT | `uint16` | 8 | (1 << 3) | +| FAILURE_ARM_ESC | `uint16` | 16 | (1 << 4) | +| FAILURE_BATTERY | `uint16` | 32 | (1 << 5) | +| FAILURE_IMBALANCED_PROP | `uint16` | 64 | (1 << 6) | +| FAILURE_MOTOR | `uint16` | 128 | (1 << 7) | +| HIL_STATE_OFF | `uint8` | 0 | +| HIL_STATE_ON | `uint8` | 1 | +| VEHICLE_TYPE_UNSPECIFIED | `uint8` | 0 | +| VEHICLE_TYPE_ROTARY_WING | `uint8` | 1 | +| VEHICLE_TYPE_FIXED_WING | `uint8` | 2 | +| VEHICLE_TYPE_ROVER | `uint8` | 3 | +| FAILSAFE_DEFER_STATE_DISABLED | `uint8` | 0 | +| FAILSAFE_DEFER_STATE_ENABLED | `uint8` | 1 | +| FAILSAFE_DEFER_STATE_WOULD_FAILSAFE | `uint8` | 2 | Failsafes deferred, but would trigger a failsafe | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleStatus.msg) + +::: details Click here to see original file ```c # Encodes the system state of the vehicle published by commander @@ -137,5 +259,6 @@ bool rc_calibration_in_progress bool calibration_enabled bool pre_flight_checks_pass # true if all checks necessary to arm pass - ``` + +::: diff --git a/docs/en/msg_docs/VehicleStatusV0.md b/docs/en/msg_docs/VehicleStatusV0.md index 9a91186524..5c9b8c0ae5 100644 --- a/docs/en/msg_docs/VehicleStatusV0.md +++ b/docs/en/msg_docs/VehicleStatusV0.md @@ -1,8 +1,137 @@ +--- +pageClass: is-wide-page +--- + # VehicleStatusV0 (UORB message) -Encodes the system state of the vehicle published by commander +Encodes the system state of the vehicle published by commander. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/VehicleStatusV0.msg) +**TOPICS:** vehicle_statusv0 + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------------------- | -------- | ------------ | ---------- | ----------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| armed_time | `uint64` | | | Arming timestamp (microseconds) | +| takeoff_time | `uint64` | | | Takeoff timestamp (microseconds) | +| arming_state | `uint8` | | | +| latest_arming_reason | `uint8` | | | +| latest_disarming_reason | `uint8` | | | +| nav_state_timestamp | `uint64` | | | time when current nav_state activated | +| nav_state_user_intention | `uint8` | | | Mode that the user selected (might be different from nav_state in a failsafe situation) | +| nav_state | `uint8` | | | Currently active mode | +| executor_in_charge | `uint8` | | | Current mode executor in charge (0=Autopilot) | +| valid_nav_states_mask | `uint32` | | | Bitmask for all valid nav_state values | +| can_set_nav_states_mask | `uint32` | | | Bitmask for all modes that a user can select | +| failure_detector_status | `uint16` | | | +| hil_state | `uint8` | | | +| vehicle_type | `uint8` | | | +| failsafe | `bool` | | | true if system is in failsafe state (e.g.:RTL, Hover, Terminate, ...) | +| failsafe_and_user_took_over | `bool` | | | true if system is in failsafe state but the user took over control | +| failsafe_defer_state | `uint8` | | | one of FAILSAFE*DEFER_STATE*\* | +| gcs_connection_lost | `bool` | | | datalink to GCS lost | +| gcs_connection_lost_counter | `uint8` | | | counts unique GCS connection lost events | +| high_latency_data_link_lost | `bool` | | | Set to true if the high latency data link (eg. RockBlock Iridium 9603 telemetry module) is lost | +| is_vtol | `bool` | | | True if the system is VTOL capable | +| is_vtol_tailsitter | `bool` | | | True if the system performs a 90° pitch down rotation during transition from MC to FW | +| in_transition_mode | `bool` | | | True if VTOL is doing a transition | +| in_transition_to_fw | `bool` | | | True if VTOL is doing a transition from MC to FW | +| system_type | `uint8` | | | system type, contains mavlink MAV_TYPE | +| system_id | `uint8` | | | system id, contains MAVLink's system ID field | +| component_id | `uint8` | | | subsystem / component id, contains MAVLink's component ID field | +| safety_button_available | `bool` | | | Set to true if a safety button is connected | +| safety_off | `bool` | | | Set to true if safety is off | +| power_input_valid | `bool` | | | set if input power is valid | +| usb_connected | `bool` | | | set to true (never cleared) once telemetry received from usb link | +| open_drone_id_system_present | `bool` | | | +| open_drone_id_system_healthy | `bool` | | | +| parachute_system_present | `bool` | | | +| parachute_system_healthy | `bool` | | | +| avoidance_system_required | `bool` | | | Set to true if avoidance system is enabled via COM_OBS_AVOID parameter | +| avoidance_system_valid | `bool` | | | Status of the obstacle avoidance system | +| rc_calibration_in_progress | `bool` | | | +| calibration_enabled | `bool` | | | +| pre_flight_checks_pass | `bool` | | | true if all checks necessary to arm pass | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------------------------------------------------------- | -------- | ----- | ------------------------------------------------ | +| MESSAGE_VERSION | `uint32` | 0 | +| ARMING_STATE_DISARMED | `uint8` | 1 | +| ARMING_STATE_ARMED | `uint8` | 2 | +| ARM_DISARM_REASON_TRANSITION_TO_STANDBY | `uint8` | 0 | +| ARM_DISARM_REASON_STICK_GESTURE | `uint8` | 1 | +| ARM_DISARM_REASON_RC_SWITCH | `uint8` | 2 | +| ARM_DISARM_REASON_COMMAND_INTERNAL | `uint8` | 3 | +| ARM_DISARM_REASON_COMMAND_EXTERNAL | `uint8` | 4 | +| ARM_DISARM_REASON_MISSION_START | `uint8` | 5 | +| ARM_DISARM_REASON_SAFETY_BUTTON | `uint8` | 6 | +| ARM_DISARM_REASON_AUTO_DISARM_LAND | `uint8` | 7 | +| ARM_DISARM_REASON_AUTO_DISARM_PREFLIGHT | `uint8` | 8 | +| ARM_DISARM_REASON_KILL_SWITCH | `uint8` | 9 | +| ARM_DISARM_REASON_LOCKDOWN | `uint8` | 10 | +| ARM_DISARM_REASON_FAILURE_DETECTOR | `uint8` | 11 | +| ARM_DISARM_REASON_SHUTDOWN | `uint8` | 12 | +| ARM_DISARM_REASON_UNIT_TEST | `uint8` | 13 | +| NAVIGATION_STATE_MANUAL | `uint8` | 0 | Manual mode | +| NAVIGATION_STATE_ALTCTL | `uint8` | 1 | Altitude control mode | +| NAVIGATION_STATE_POSCTL | `uint8` | 2 | Position control mode | +| NAVIGATION_STATE_AUTO_MISSION | `uint8` | 3 | Auto mission mode | +| NAVIGATION_STATE_AUTO_LOITER | `uint8` | 4 | Auto loiter mode | +| NAVIGATION_STATE_AUTO_RTL | `uint8` | 5 | Auto return to launch mode | +| NAVIGATION_STATE_POSITION_SLOW | `uint8` | 6 | +| NAVIGATION_STATE_FREE5 | `uint8` | 7 | +| NAVIGATION_STATE_FREE4 | `uint8` | 8 | +| NAVIGATION_STATE_FREE3 | `uint8` | 9 | +| NAVIGATION_STATE_ACRO | `uint8` | 10 | Acro mode | +| NAVIGATION_STATE_FREE2 | `uint8` | 11 | +| NAVIGATION_STATE_DESCEND | `uint8` | 12 | Descend mode (no position control) | +| NAVIGATION_STATE_TERMINATION | `uint8` | 13 | Termination mode | +| NAVIGATION_STATE_OFFBOARD | `uint8` | 14 | +| NAVIGATION_STATE_STAB | `uint8` | 15 | Stabilized mode | +| NAVIGATION_STATE_FREE1 | `uint8` | 16 | +| NAVIGATION_STATE_AUTO_TAKEOFF | `uint8` | 17 | Takeoff | +| NAVIGATION_STATE_AUTO_LAND | `uint8` | 18 | Land | +| NAVIGATION_STATE_AUTO_FOLLOW_TARGET | `uint8` | 19 | Auto Follow | +| NAVIGATION_STATE_AUTO_PRECLAND | `uint8` | 20 | Precision land with landing target | +| NAVIGATION_STATE_ORBIT | `uint8` | 21 | Orbit in a circle | +| NAVIGATION_STATE_AUTO_VTOL_TAKEOFF | `uint8` | 22 | Takeoff, transition, establish loiter | +| NAVIGATION_STATE_EXTERNAL1 | `uint8` | 23 | +| NAVIGATION_STATE_EXTERNAL2 | `uint8` | 24 | +| NAVIGATION_STATE_EXTERNAL3 | `uint8` | 25 | +| NAVIGATION_STATE_EXTERNAL4 | `uint8` | 26 | +| NAVIGATION_STATE_EXTERNAL5 | `uint8` | 27 | +| NAVIGATION_STATE_EXTERNAL6 | `uint8` | 28 | +| NAVIGATION_STATE_EXTERNAL7 | `uint8` | 29 | +| NAVIGATION_STATE_EXTERNAL8 | `uint8` | 30 | +| NAVIGATION_STATE_MAX | `uint8` | 31 | +| FAILURE_NONE | `uint16` | 0 | +| FAILURE_ROLL | `uint16` | 1 | (1 << 0) | +| FAILURE_PITCH | `uint16` | 2 | (1 << 1) | +| FAILURE_ALT | `uint16` | 4 | (1 << 2) | +| FAILURE_EXT | `uint16` | 8 | (1 << 3) | +| FAILURE_ARM_ESC | `uint16` | 16 | (1 << 4) | +| FAILURE_BATTERY | `uint16` | 32 | (1 << 5) | +| FAILURE_IMBALANCED_PROP | `uint16` | 64 | (1 << 6) | +| FAILURE_MOTOR | `uint16` | 128 | (1 << 7) | +| HIL_STATE_OFF | `uint8` | 0 | +| HIL_STATE_ON | `uint8` | 1 | +| VEHICLE_TYPE_UNKNOWN | `uint8` | 0 | +| VEHICLE_TYPE_ROTARY_WING | `uint8` | 1 | +| VEHICLE_TYPE_FIXED_WING | `uint8` | 2 | +| VEHICLE_TYPE_ROVER | `uint8` | 3 | +| VEHICLE_TYPE_AIRSHIP | `uint8` | 4 | +| FAILSAFE_DEFER_STATE_DISABLED | `uint8` | 0 | +| FAILSAFE_DEFER_STATE_ENABLED | `uint8` | 1 | +| FAILSAFE_DEFER_STATE_WOULD_FAILSAFE | `uint8` | 2 | Failsafes deferred, but would trigger a failsafe | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/VehicleStatusV0.msg) + +::: details Click here to see original file ```c # Encodes the system state of the vehicle published by commander @@ -145,5 +274,6 @@ bool rc_calibration_in_progress bool calibration_enabled bool pre_flight_checks_pass # true if all checks necessary to arm pass - ``` + +::: diff --git a/docs/en/msg_docs/VehicleThrustSetpoint.md b/docs/en/msg_docs/VehicleThrustSetpoint.md index 6bcf6e9d13..2b5324b098 100644 --- a/docs/en/msg_docs/VehicleThrustSetpoint.md +++ b/docs/en/msg_docs/VehicleThrustSetpoint.md @@ -1,11 +1,26 @@ +--- +pageClass: is-wide-page +--- + # VehicleThrustSetpoint (UORB message) +**TOPICS:** vehicle_thrust_setpoint vehicle_thrust_setpoint_virtual_fw vehicle_thrust_setpoint_virtual_mc +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ------------ | ------------ | ---------- | -------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | timestamp of the data sample on which this message is based (microseconds) | +| xyz | `float32[3]` | | | thrust setpoint along X, Y, Z body axis [-1, 1] | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg) + +::: details Click here to see original file ```c - uint64 timestamp # time since system start (microseconds) uint64 timestamp_sample # timestamp of the data sample on which this message is based (microseconds) @@ -13,5 +28,6 @@ float32[3] xyz # thrust setpoint along X, Y, Z body axis [-1, 1] # TOPICS vehicle_thrust_setpoint # TOPICS vehicle_thrust_setpoint_virtual_fw vehicle_thrust_setpoint_virtual_mc - ``` + +::: diff --git a/docs/en/msg_docs/VehicleTorqueSetpoint.md b/docs/en/msg_docs/VehicleTorqueSetpoint.md index d67e37b3a3..a0449a4711 100644 --- a/docs/en/msg_docs/VehicleTorqueSetpoint.md +++ b/docs/en/msg_docs/VehicleTorqueSetpoint.md @@ -1,11 +1,26 @@ +--- +pageClass: is-wide-page +--- + # VehicleTorqueSetpoint (UORB message) +**TOPICS:** vehicle_torque_setpoint vehicle_torque_setpoint_virtual_fw vehicle_torque_setpoint_virtual_mc +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | ------------ | ------------ | ---------- | -------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | timestamp of the data sample on which this message is based (microseconds) | +| xyz | `float32[3]` | | | torque setpoint about X, Y, Z body axis (normalized) | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg) + +::: details Click here to see original file ```c - uint64 timestamp # time since system start (microseconds) uint64 timestamp_sample # timestamp of the data sample on which this message is based (microseconds) @@ -13,5 +28,6 @@ float32[3] xyz # torque setpoint about X, Y, Z body axis (normalized) # TOPICS vehicle_torque_setpoint # TOPICS vehicle_torque_setpoint_virtual_fw vehicle_torque_setpoint_virtual_mc - ``` + +::: diff --git a/docs/en/msg_docs/VelocityLimits.md b/docs/en/msg_docs/VelocityLimits.md index 6a86fdc977..007088412a 100644 --- a/docs/en/msg_docs/VelocityLimits.md +++ b/docs/en/msg_docs/VelocityLimits.md @@ -1,8 +1,27 @@ +--- +pageClass: is-wide-page +--- + # VelocityLimits (UORB message) -Velocity and yaw rate limits for a multicopter position slow mode only +Velocity and yaw rate limits for a multicopter position slow mode only. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VelocityLimits.msg) +**TOPICS:** velocity_limits + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------- | --------- | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| horizontal_velocity | `float32` | m/s | | +| vertical_velocity | `float32` | m/s | | +| yaw_rate | `float32` | rad/s | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VelocityLimits.msg) + +::: details Click here to see original file ```c # Velocity and yaw rate limits for a multicopter position slow mode only @@ -13,5 +32,6 @@ uint64 timestamp # time since system start (microseconds) float32 horizontal_velocity # [m/s] float32 vertical_velocity # [m/s] float32 yaw_rate # [rad/s] - ``` + +::: diff --git a/docs/en/msg_docs/VtolVehicleStatus.md b/docs/en/msg_docs/VtolVehicleStatus.md index a271005673..0e6a351aac 100644 --- a/docs/en/msg_docs/VtolVehicleStatus.md +++ b/docs/en/msg_docs/VtolVehicleStatus.md @@ -1,8 +1,37 @@ +--- +pageClass: is-wide-page +--- + # VtolVehicleStatus (UORB message) -VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE +VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VtolVehicleStatus.msg) +**TOPICS:** vtol_vehiclestatus + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------------- | -------- | ------------ | ---------- | --------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| vehicle_vtol_state | `uint8` | | | current state of the vtol, see VEHICLE_VTOL_STATE | +| fixed_wing_system_failure | `bool` | | | vehicle in fixed-wing system failure failsafe mode (after quad-chute) | + +## Constants + +| Name | Type | Value | Description | +| --------------------------------------------------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | +| VEHICLE_VTOL_STATE_UNDEFINED | `uint8` | 0 | +| VEHICLE_VTOL_STATE_TRANSITION_TO_FW | `uint8` | 1 | +| VEHICLE_VTOL_STATE_TRANSITION_TO_MC | `uint8` | 2 | +| VEHICLE_VTOL_STATE_MC | `uint8` | 3 | +| VEHICLE_VTOL_STATE_FW | `uint8` | 4 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VtolVehicleStatus.msg) + +::: details Click here to see original file ```c # VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE @@ -20,5 +49,6 @@ uint64 timestamp # time since system start (microseconds) uint8 vehicle_vtol_state # current state of the vtol, see VEHICLE_VTOL_STATE bool fixed_wing_system_failure # vehicle in fixed-wing system failure failsafe mode (after quad-chute) - ``` + +::: diff --git a/docs/en/msg_docs/Vtx.md b/docs/en/msg_docs/Vtx.md new file mode 100644 index 0000000000..7cf2657bf0 --- /dev/null +++ b/docs/en/msg_docs/Vtx.md @@ -0,0 +1,83 @@ +--- +pageClass: is-wide-page +--- + +# Vtx (UORB message) + +**TOPICS:** vtx + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------- | ----------- | ------------ | ---------- | -------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| protocol | `uint8` | | | +| device | `uint8` | | | +| mode | `uint8` | | | +| band | `int8` | | | Band number (0-23), negative values indicate frequency mode | +| channel | `int8` | | | Channel number (0-15), negative values indicate frequency mode | +| frequency | `uint16` | | | Frequency in MHz, zero indicates unknown | +| band_letter | `uint8` | | | Band letter as ASCII | +| band_name | `uint8[12]` | | | Band name in ASCII without null termination | +| power_level | `int8` | | | Current power level (0-15), negative values indicate unknown | +| power_label | `uint8[4]` | | | Current power label in ASCII without null termination | + +## Constants + +| Name | Type | Value | Description | +| ------------------------------------------------------------------- | ------- | ----- | ----------------------------------------- | +| BAND_NAME_LENGTH | `uint8` | 12 | +| POWER_LABEL_LENGTH | `uint8` | 4 | +| PROTOCOL_NONE | `uint8` | 0 | No protocol is detected, usually an error | +| PROTOCOL_SMART_AUDIO_V1 | `uint8` | 10 | +| PROTOCOL_SMART_AUDIO_V2 | `uint8` | 20 | +| PROTOCOL_SMART_AUDIO_V2_1 | `uint8` | 21 | +| PROTOCOL_TRAMP | `uint8` | 100 | +| DEVICE_UNKNOWN | `uint8` | 0 | +| DEVICE_PEAK_THOR_T67 | `uint8` | 20 | +| DEVICE_RUSH_MAX_SOLO | `uint8` | 40 | +| MODE_NORMAL | `uint8` | 0 | +| MODE_PIT | `uint8` | 1 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Vtx.msg) + +::: details Click here to see original file + +```c +uint64 timestamp # time since system start (microseconds) + +uint8 BAND_NAME_LENGTH = 12 +uint8 POWER_LABEL_LENGTH = 4 + +uint8 PROTOCOL_NONE = 0 # No protocol is detected, usually an error +uint8 PROTOCOL_SMART_AUDIO_V1 = 10 +uint8 PROTOCOL_SMART_AUDIO_V2 = 20 +uint8 PROTOCOL_SMART_AUDIO_V2_1 = 21 +uint8 PROTOCOL_TRAMP = 100 +uint8 protocol + +uint8 DEVICE_UNKNOWN = 0 +uint8 DEVICE_PEAK_THOR_T67 = 20 +uint8 DEVICE_RUSH_MAX_SOLO = 40 +uint8 device + +uint8 MODE_NORMAL = 0 +uint8 MODE_PIT = 1 +uint8 mode + +# Band and Channel are 0-indexed! But the user expects a 1-indexed display! +int8 band # Band number (0-23), negative values indicate frequency mode +int8 channel # Channel number (0-15), negative values indicate frequency mode +uint16 frequency # Frequency in MHz, zero indicates unknown + +uint8 band_letter # Band letter as ASCII +uint8[12] band_name # Band name in ASCII without null termination + +# Also 0-indexed, but the user expects a 1-indexed display! +int8 power_level # Current power level (0-15), negative values indicate unknown +uint8[4] power_label # Current power label in ASCII without null termination +``` + +::: diff --git a/docs/en/msg_docs/WheelEncoders.md b/docs/en/msg_docs/WheelEncoders.md index 8a10dc11ad..d5ae526c7a 100644 --- a/docs/en/msg_docs/WheelEncoders.md +++ b/docs/en/msg_docs/WheelEncoders.md @@ -1,8 +1,24 @@ +--- +pageClass: is-wide-page +--- + # WheelEncoders (UORB message) +**TOPICS:** wheel_encoders +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/WheelEncoders.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ----------- | ------------ | ------------ | ---------- | -------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| wheel_speed | `float32[2]` | rad/s | | +| wheel_angle | `float32[2]` | rad | | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/WheelEncoders.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -10,5 +26,6 @@ uint64 timestamp # time since system start (microseconds) # Two wheels: 0 right, 1 left float32[2] wheel_speed # [rad/s] float32[2] wheel_angle # [rad] - ``` + +::: diff --git a/docs/en/msg_docs/Wind.md b/docs/en/msg_docs/Wind.md index 7ddb2e62eb..c30a092752 100644 --- a/docs/en/msg_docs/Wind.md +++ b/docs/en/msg_docs/Wind.md @@ -1,11 +1,42 @@ +--- +pageClass: is-wide-page +--- + # Wind (UORB message) -Wind estimate (from EKF2) +Wind estimate (from EKF2). Contains the system-wide estimate of horizontal wind velocity and its variance. Published by the navigation filter (EKF2) for use by other flight modules and libraries. -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/Wind.msg) +**TOPICS:** wind estimator_wind + +## Fields + +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ---------------- | --------- | ------------ | ---------- | --------------------------------------------------------------------------------- | +| timestamp | `uint64` | us | | Time since system start | +| timestamp_sample | `uint64` | us | | Timestamp of the raw data | +| windspeed_north | `float32` | m/s | | Wind component in north / X direction | +| windspeed_east | `float32` | m/s | | Wind component in east / Y direction | +| variance_north | `float32` | (m/s)^2 | | Wind estimate error variance in north / X direction (Invalid: 0 if not estimated) | +| variance_east | `float32` | (m/s)^2 | | Wind estimate error variance in east / Y direction (Invalid: 0 if not estimated) | +| tas_innov | `float32` | m/s | | True airspeed innovation | +| tas_innov_var | `float32` | (m/s)^2 | | True airspeed innovation variance | +| beta_innov | `float32` | rad | | Sideslip measurement innovation | +| beta_innov_var | `float32` | rad^2 | | Sideslip measurement innovation variance | + +## Constants + +| Name | Type | Value | Description | +| ----------------------------------------------- | -------- | ----- | ----------- | +| MESSAGE_VERSION | `uint32` | 0 | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/Wind.msg) + +::: details Click here to see original file ```c # Wind estimate (from EKF2) @@ -31,5 +62,6 @@ float32 beta_innov # [rad] Sideslip measurement innovation float32 beta_innov_var # [rad^2] Sideslip measurement innovation variance # TOPICS wind estimator_wind - ``` + +::: diff --git a/docs/en/msg_docs/YawEstimatorStatus.md b/docs/en/msg_docs/YawEstimatorStatus.md index 888f7628ba..d167a6f0be 100644 --- a/docs/en/msg_docs/YawEstimatorStatus.md +++ b/docs/en/msg_docs/YawEstimatorStatus.md @@ -1,8 +1,30 @@ +--- +pageClass: is-wide-page +--- + # YawEstimatorStatus (UORB message) +**TOPICS:** yaw_estimatorstatus +## Fields -[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/YawEstimatorStatus.msg) +| Name | Type | Unit [Frame] | Range/Enum | Description | +| ------------------- | ------------ | ------------ | ---------- | ----------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| timestamp_sample | `uint64` | | | the timestamp of the raw data (microseconds) | +| yaw_composite | `float32` | | | composite yaw from GSF (rad) | +| yaw_variance | `float32` | | | composite yaw variance from GSF (rad^2) | +| yaw_composite_valid | `bool` | | | +| yaw | `float32[5]` | | | yaw estimate for each model in the filter bank (rad) | +| innov_vn | `float32[5]` | | | North velocity innovation for each model in the filter bank (m/s) | +| innov_ve | `float32[5]` | | | East velocity innovation for each model in the filter bank (m/s) | +| weight | `float32[5]` | | | weighting for each model in the filter bank | + +## Source Message + +[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/YawEstimatorStatus.msg) + +::: details Click here to see original file ```c uint64 timestamp # time since system start (microseconds) @@ -16,5 +38,6 @@ float32[5] yaw # yaw estimate for each model in the filter bank (rad) float32[5] innov_vn # North velocity innovation for each model in the filter bank (m/s) float32[5] innov_ve # East velocity innovation for each model in the filter bank (m/s) float32[5] weight # weighting for each model in the filter bank - ``` + +::: diff --git a/docs/en/msg_docs/index.md b/docs/en/msg_docs/index.md index 359abfc67f..e9c41e150c 100644 --- a/docs/en/msg_docs/index.md +++ b/docs/en/msg_docs/index.md @@ -13,90 +13,63 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m ## Versioned Messages -- [ActuatorMotors](ActuatorMotors.md) — Motor control message -- [ActuatorServos](ActuatorServos.md) — Servo control message -- [AirspeedValidated](AirspeedValidated.md) — Validated airspeed -- [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply -- [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request -- [BatteryStatus](BatteryStatus.md) — Battery status -- [ConfigOverrides](ConfigOverrides.md) — Configurable overrides by (external) modes or mode executors -- [Event](Event.md) — Events interface -- [FixedWingLateralSetpoint](FixedWingLateralSetpoint.md) — Fixed Wing Lateral Setpoint message - Used by the fw_lateral_longitudinal_control module - At least one of course, airspeed_direction, or lateral_acceleration must be finite. -- [FixedWingLongitudinalSetpoint](FixedWingLongitudinalSetpoint.md) — Fixed Wing Longitudinal Setpoint message - Used by the fw_lateral_longitudinal_control module - If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion. - If both altitude and height_rate are NAN, the controller maintains the current altitude. -- [GotoSetpoint](GotoSetpoint.md) — Position and (optional) heading setpoints with corresponding speed constraints - Setpoints are intended as inputs to position and heading smoothers, respectively - Setpoints do not need to be kinematically consistent - Optional heading setpoints may be specified as controlled by the respective flag - Unset optional setpoints are not controlled - Unset optional constraints default to vehicle specifications +- [ActuatorMotors](ActuatorMotors.md) — Motor control message. +- [ActuatorServos](ActuatorServos.md) — Servo control message. +- [AirspeedValidated](AirspeedValidated.md) — Validated airspeed. +- [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply. +- [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request. +- [BatteryStatus](BatteryStatus.md) — Battery status. +- [ConfigOverrides](ConfigOverrides.md) — Configurable overrides by (external) modes or mode executors. +- [Event](Event.md) — Events interface. +- [FixedWingLateralSetpoint](FixedWingLateralSetpoint.md) — Fixed Wing Lateral Setpoint message. Used by the fw_lateral_longitudinal_control module. At least one of course, airspeed_direction, or lateral_acceleration must be finite. +- [FixedWingLongitudinalSetpoint](FixedWingLongitudinalSetpoint.md) — Fixed Wing Longitudinal Setpoint message. Used by the fw_lateral_longitudinal_control module. If pitch_direct and throttle_direct are not both finite, then the controller relies on altitude/height_rate and equivalent_airspeed to control vertical motion. If both altitude and height_rate are NAN, the controller maintains the current altitude. +- [GotoSetpoint](GotoSetpoint.md) — Position and (optional) heading setpoints with corresponding speed constraints. Setpoints are intended as inputs to position and heading smoothers, respectively. Setpoints do not need to be kinematically consistent. Optional heading setpoints may be specified as controlled by the respective flag. Unset optional setpoints are not controlled. Unset optional constraints default to vehicle specifications. - [HomePosition](HomePosition.md) — GPS home position in WGS84 coordinates. -- [LateralControlConfiguration](LateralControlConfiguration.md) — Fixed Wing Lateral Control Configuration message - Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages. -- [LongitudinalControlConfiguration](LongitudinalControlConfiguration.md) — Fixed Wing Longitudinal Control Configuration message - Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages - and configure the resultant setpoints. +- [LateralControlConfiguration](LateralControlConfiguration.md) — Fixed Wing Lateral Control Configuration message. Used by the fw_lateral_longitudinal_control module to constrain FixedWingLateralSetpoint messages. +- [LongitudinalControlConfiguration](LongitudinalControlConfiguration.md) — Fixed Wing Longitudinal Control Configuration message. Used by the fw_lateral_longitudinal_control module and TECS to constrain FixedWingLongitudinalSetpoint messages. and configure the resultant setpoints. - [ManualControlSetpoint](ManualControlSetpoint.md) -- [ModeCompleted](ModeCompleted.md) — Mode completion result, published by an active mode. - The possible values of nav_state are defined in the VehicleStatus msg. - Note that this is not always published (e.g. when a user switches modes or on - failsafe activation) +- [ModeCompleted](ModeCompleted.md) — Mode completion result, published by an active mode. The possible values of nav_state are defined in the VehicleStatus msg. Note that this is not always published (e.g. when a user switches modes or on. failsafe activation). +- [RaptorInput](RaptorInput.md) — Raptor Input. +- [RaptorStatus](RaptorStatus.md) — Raptor Status. - [RegisterExtComponentReply](RegisterExtComponentReply.md) -- [RegisterExtComponentRequest](RegisterExtComponentRequest.md) — Request to register an external component -- [TrajectorySetpoint](TrajectorySetpoint.md) — Trajectory setpoint in NED frame - Input to PID position controller. - Needs to be kinematically consistent and feasible for smooth flight. - setting a value to NaN means the state should not be controlled +- [RegisterExtComponentRequest](RegisterExtComponentRequest.md) — Request to register an external component. +- [TrajectorySetpoint](TrajectorySetpoint.md) — Trajectory setpoint in NED frame. Input to PID position controller. Needs to be kinematically consistent and feasible for smooth flight. setting a value to NaN means the state should not be controlled. - [UnregisterExtComponent](UnregisterExtComponent.md) - [VehicleAngularVelocity](VehicleAngularVelocity.md) -- [VehicleAttitude](VehicleAttitude.md) — This is similar to the mavlink message ATTITUDE_QUATERNION, but for onboard use - The quaternion uses the Hamilton convention, and the order is q(w, x, y, z) +- [VehicleAttitude](VehicleAttitude.md) — This is similar to the mavlink message ATTITUDE_QUATERNION, but for onboard use. The quaternion uses the Hamilton convention, and the order is q(w, x, y, z). - [VehicleAttitudeSetpoint](VehicleAttitudeSetpoint.md) -- [VehicleCommand](VehicleCommand.md) — Vehicle Command uORB message. Used for commanding a mission / action / etc. - Follows the MAVLink COMMAND_INT / COMMAND_LONG definition -- [VehicleCommandAck](VehicleCommandAck.md) — Vehicle Command Ackonwledgement uORB message. - Used for acknowledging the vehicle command being received. - Follows the MAVLink COMMAND_ACK message definition +- [VehicleCommand](VehicleCommand.md) — Vehicle Command uORB message. Used for commanding a mission / action / etc. Follows the MAVLink COMMAND_INT / COMMAND_LONG definition. +- [VehicleCommandAck](VehicleCommandAck.md) — Vehicle Command Ackonwledgement uORB message. Used for acknowledging the vehicle command being received. Follows the MAVLink COMMAND_ACK message definition. - [VehicleControlMode](VehicleControlMode.md) -- [VehicleGlobalPosition](VehicleGlobalPosition.md) — Fused global position in WGS84. - This struct contains global position estimation. It is not the raw GPS - measurement (@see vehicle_gps_position). This topic is usually published by the position - estimator, which will take more sources of information into account than just GPS, - e.g. control inputs of the vehicle in a Kalman-filter implementation. +- [VehicleGlobalPosition](VehicleGlobalPosition.md) — Fused global position in WGS84. This struct contains global position estimation. It is not the raw GPS. measurement (@see vehicle_gps_position). This topic is usually published by the position. estimator, which will take more sources of information into account than just GPS,. e.g. control inputs of the vehicle in a Kalman-filter implementation. - [VehicleLandDetected](VehicleLandDetected.md) -- [VehicleLocalPosition](VehicleLocalPosition.md) — Fused local position in NED. - The coordinate system origin is the vehicle position at the time when the EKF2-module was started. -- [VehicleOdometry](VehicleOdometry.md) — Vehicle odometry data +- [VehicleLocalPosition](VehicleLocalPosition.md) — Fused local position in NED. The coordinate system origin is the vehicle position at the time when the EKF2-module was started. +- [VehicleOdometry](VehicleOdometry.md) — Vehicle odometry data. - [VehicleRatesSetpoint](VehicleRatesSetpoint.md) -- [VehicleStatus](VehicleStatus.md) — Encodes the system state of the vehicle published by commander -- [VtolVehicleStatus](VtolVehicleStatus.md) — VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE -- [Wind](Wind.md) — Wind estimate (from EKF2) +- [VehicleStatus](VehicleStatus.md) — Encodes the system state of the vehicle published by commander. +- [VtolVehicleStatus](VtolVehicleStatus.md) — VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE. +- [Wind](Wind.md) — Wind estimate (from EKF2). ## Unversioned Messages -- [ActionRequest](ActionRequest.md) — Action request for the vehicle's main state +- [ActionRequest](ActionRequest.md) — Action request for the vehicle's main state. - [ActuatorArmed](ActuatorArmed.md) - [ActuatorControlsStatus](ActuatorControlsStatus.md) - [ActuatorOutputs](ActuatorOutputs.md) -- [ActuatorServosTrim](ActuatorServosTrim.md) — Servo trims, added as offset to servo outputs +- [ActuatorServosTrim](ActuatorServosTrim.md) — Servo trims, added as offset to servo outputs. - [ActuatorTest](ActuatorTest.md) - [AdcReport](AdcReport.md) — ADC raw data. -- [Airspeed](Airspeed.md) — Airspeed data from sensors -- [AirspeedWind](AirspeedWind.md) — Wind estimate (from airspeed_selector) -- [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md) — Autotune attitude control status -- [BatteryInfo](BatteryInfo.md) — Battery information +- [Airspeed](Airspeed.md) — Airspeed data from sensors. +- [AirspeedWind](AirspeedWind.md) — Wind estimate (from airspeed_selector). +- [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md) — Autotune attitude control status. +- [BatteryInfo](BatteryInfo.md) — Battery information. - [ButtonEvent](ButtonEvent.md) - [CameraCapture](CameraCapture.md) - [CameraStatus](CameraStatus.md) - [CameraTrigger](CameraTrigger.md) - [CanInterfaceStatus](CanInterfaceStatus.md) -- [CellularStatus](CellularStatus.md) — Cellular status -- [CollisionConstraints](CollisionConstraints.md) — Local setpoint constraints in NED frame - setting something to NaN means that no limit is provided +- [CellularStatus](CellularStatus.md) — Cellular status. +- [CollisionConstraints](CollisionConstraints.md) — Local setpoint constraints in NED frame. setting something to NaN means that no limit is provided. - [ControlAllocatorStatus](ControlAllocatorStatus.md) - [Cpuload](Cpuload.md) - [DatamanRequest](DatamanRequest.md) @@ -105,13 +78,12 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [DebugKeyValue](DebugKeyValue.md) - [DebugValue](DebugValue.md) - [DebugVect](DebugVect.md) -- [DeviceInformation](DeviceInformation.md) — Device information -- [DifferentialPressure](DifferentialPressure.md) — Differential-pressure (airspeed) sensor -- [DistanceSensor](DistanceSensor.md) — DISTANCE_SENSOR message data +- [DeviceInformation](DeviceInformation.md) — Device information. +- [DifferentialPressure](DifferentialPressure.md) — Differential-pressure (airspeed) sensor. +- [DistanceSensor](DistanceSensor.md) — DISTANCE_SENSOR message data. - [DistanceSensorModeChangeRequest](DistanceSensorModeChangeRequest.md) - [DronecanNodeStatus](DronecanNodeStatus.md) -- [Ekf2Timestamps](Ekf2Timestamps.md) — this message contains the (relative) timestamps of the sensor inputs used by EKF2. - It can be used for reproducible replay. +- [Ekf2Timestamps](Ekf2Timestamps.md) — this message contains the (relative) timestamps of the sensor inputs used by EKF2. It can be used for reproducible replay. - [EscReport](EscReport.md) - [EscStatus](EscStatus.md) - [EstimatorAidSource1d](EstimatorAidSource1d.md) @@ -123,19 +95,16 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [EstimatorGpsStatus](EstimatorGpsStatus.md) - [EstimatorInnovations](EstimatorInnovations.md) - [EstimatorSelectorStatus](EstimatorSelectorStatus.md) -- [EstimatorSensorBias](EstimatorSensorBias.md) — Sensor readings and in-run biases in SI-unit form. Sensor readings are compensated for static offsets, - scale errors, in-run bias and thermal drift (if thermal compensation is enabled and available). +- [EstimatorSensorBias](EstimatorSensorBias.md) — Sensor readings and in-run biases in SI-unit form. Sensor readings are compensated for static offsets,. scale errors, in-run bias and thermal drift (if thermal compensation is enabled and available). - [EstimatorStates](EstimatorStates.md) - [EstimatorStatus](EstimatorStatus.md) - [EstimatorStatusFlags](EstimatorStatusFlags.md) - [FailsafeFlags](FailsafeFlags.md) — Input flags for the failsafe state machine set by the arming & health checks. - [FailureDetectorStatus](FailureDetectorStatus.md) - [FigureEightStatus](FigureEightStatus.md) -- [FixedWingLateralGuidanceStatus](FixedWingLateralGuidanceStatus.md) — Fixed Wing Lateral Guidance Status message - Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs -- [FixedWingLateralStatus](FixedWingLateralStatus.md) — Fixed Wing Lateral Status message - Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint -- [FixedWingRunwayControl](FixedWingRunwayControl.md) — Auxiliary control fields for fixed-wing runway takeoff/landing +- [FixedWingLateralGuidanceStatus](FixedWingLateralGuidanceStatus.md) — Fixed Wing Lateral Guidance Status message. Published by fw_pos_control module to report the resultant lateral setpoints and NPFG debug outputs. +- [FixedWingLateralStatus](FixedWingLateralStatus.md) — Fixed Wing Lateral Status message. Published by the fw_lateral_longitudinal_control module to report the resultant lateral setpoint. +- [FixedWingRunwayControl](FixedWingRunwayControl.md) — Auxiliary control fields for fixed-wing runway takeoff/landing. - [FlightPhaseEstimation](FlightPhaseEstimation.md) - [FollowTarget](FollowTarget.md) - [FollowTargetEstimator](FollowTargetEstimator.md) @@ -153,13 +122,13 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [GimbalManagerSetAttitude](GimbalManagerSetAttitude.md) - [GimbalManagerSetManualControl](GimbalManagerSetManualControl.md) - [GimbalManagerStatus](GimbalManagerStatus.md) -- [GpioConfig](GpioConfig.md) — GPIO configuration -- [GpioIn](GpioIn.md) — GPIO mask and state -- [GpioOut](GpioOut.md) — GPIO mask and state -- [GpioRequest](GpioRequest.md) — Request GPIO mask to be read +- [GpioConfig](GpioConfig.md) — GPIO configuration. +- [GpioIn](GpioIn.md) — GPIO mask and state. +- [GpioOut](GpioOut.md) — GPIO mask and state. +- [GpioRequest](GpioRequest.md) — Request GPIO mask to be read. - [GpsDump](GpsDump.md) — This message is used to dump the raw gps communication to the log. - [GpsInjectData](GpsInjectData.md) -- [Gripper](Gripper.md) — # Used to command an actuation in the gripper, which is mapped to a specific output in the control allocation module +- [Gripper](Gripper.md) — # Used to command an actuation in the gripper, which is mapped to a specific output in the control allocation module. - [HealthReport](HealthReport.md) - [HeaterStatus](HeaterStatus.md) - [HoverThrustEstimate](HoverThrustEstimate.md) @@ -167,34 +136,32 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [InternalCombustionEngineControl](InternalCombustionEngineControl.md) - [InternalCombustionEngineStatus](InternalCombustionEngineStatus.md) - [IridiumsbdStatus](IridiumsbdStatus.md) -- [IrlockReport](IrlockReport.md) — IRLOCK_REPORT message data +- [IrlockReport](IrlockReport.md) — IRLOCK_REPORT message data. - [LandingGear](LandingGear.md) - [LandingGearWheel](LandingGearWheel.md) - [LandingTargetInnovations](LandingTargetInnovations.md) -- [LandingTargetPose](LandingTargetPose.md) — Relative position of precision land target in navigation (body fixed, north aligned, NED) and inertial (world fixed, north aligned, NED) frames -- [LaunchDetectionStatus](LaunchDetectionStatus.md) — Status of the launch detection state machine (fixed-wing only) -- [LedControl](LedControl.md) — LED control: control a single or multiple LED's. - These are the externally visible LED's, not the board LED's -- [LogMessage](LogMessage.md) — A logging message, output with PX4_WARN, PX4_ERR, PX4_INFO +- [LandingTargetPose](LandingTargetPose.md) — Relative position of precision land target in navigation (body fixed, north aligned, NED) and inertial (world fixed, north aligned, NED) frames. +- [LaunchDetectionStatus](LaunchDetectionStatus.md) — Status of the launch detection state machine (fixed-wing only). +- [LedControl](LedControl.md) — LED control: control a single or multiple LED's. These are the externally visible LED's, not the board LED's. +- [LogMessage](LogMessage.md) — A logging message, output with PX4_WARN, PX4_ERR, PX4_INFO. - [LoggerStatus](LoggerStatus.md) - [MagWorkerData](MagWorkerData.md) - [MagnetometerBiasEstimate](MagnetometerBiasEstimate.md) - [ManualControlSwitches](ManualControlSwitches.md) - [MavlinkLog](MavlinkLog.md) -- [MavlinkTunnel](MavlinkTunnel.md) — MAV_TUNNEL_PAYLOAD_TYPE enum +- [MavlinkTunnel](MavlinkTunnel.md) — MAV_TUNNEL_PAYLOAD_TYPE enum. - [MessageFormatRequest](MessageFormatRequest.md) - [MessageFormatResponse](MessageFormatResponse.md) - [Mission](Mission.md) - [MissionResult](MissionResult.md) - [MountOrientation](MountOrientation.md) - [NavigatorMissionItem](NavigatorMissionItem.md) -- [NavigatorStatus](NavigatorStatus.md) — Current status of a Navigator mode - The possible values of nav_state are defined in the VehicleStatus msg. -- [NeuralControl](NeuralControl.md) — Neural control +- [NavigatorStatus](NavigatorStatus.md) — Current status of a Navigator mode. The possible values of nav_state are defined in the VehicleStatus msg. +- [NeuralControl](NeuralControl.md) — Neural control. - [NormalizedUnsignedSetpoint](NormalizedUnsignedSetpoint.md) - [ObstacleDistance](ObstacleDistance.md) — Obstacle distances in front of the sensor. -- [OffboardControlMode](OffboardControlMode.md) — Off-board control mode -- [OnboardComputerStatus](OnboardComputerStatus.md) — ONBOARD_COMPUTER_STATUS message data +- [OffboardControlMode](OffboardControlMode.md) — Off-board control mode. +- [OnboardComputerStatus](OnboardComputerStatus.md) — ONBOARD_COMPUTER_STATUS message data. - [OpenDroneIdArmStatus](OpenDroneIdArmStatus.md) - [OpenDroneIdOperatorId](OpenDroneIdOperatorId.md) - [OpenDroneIdSelfId](OpenDroneIdSelfId.md) @@ -202,22 +169,21 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [OrbTest](OrbTest.md) - [OrbTestLarge](OrbTestLarge.md) - [OrbTestMedium](OrbTestMedium.md) -- [OrbitStatus](OrbitStatus.md) — ORBIT_YAW_BEHAVIOUR -- [ParameterResetRequest](ParameterResetRequest.md) — ParameterResetRequest : Used by the primary to reset one or all parameter value(s) on the remote -- [ParameterSetUsedRequest](ParameterSetUsedRequest.md) — ParameterSetUsedRequest : Used by a remote to update the used flag for a parameter on the primary -- [ParameterSetValueRequest](ParameterSetValueRequest.md) — ParameterSetValueRequest : Used by a remote or primary to update the value for a parameter at the other end -- [ParameterSetValueResponse](ParameterSetValueResponse.md) — ParameterSetValueResponse : Response to a set value request by either primary or secondary -- [ParameterUpdate](ParameterUpdate.md) — This message is used to notify the system about one or more parameter changes +- [OrbitStatus](OrbitStatus.md) — ORBIT_YAW_BEHAVIOUR. +- [ParameterResetRequest](ParameterResetRequest.md) — ParameterResetRequest : Used by the primary to reset one or all parameter value(s) on the remote. +- [ParameterSetUsedRequest](ParameterSetUsedRequest.md) — ParameterSetUsedRequest : Used by a remote to update the used flag for a parameter on the primary. +- [ParameterSetValueRequest](ParameterSetValueRequest.md) — ParameterSetValueRequest : Used by a remote or primary to update the value for a parameter at the other end. +- [ParameterSetValueResponse](ParameterSetValueResponse.md) — ParameterSetValueResponse : Response to a set value request by either primary or secondary. +- [ParameterUpdate](ParameterUpdate.md) — This message is used to notify the system about one or more parameter changes. - [Ping](Ping.md) - [PositionControllerLandingStatus](PositionControllerLandingStatus.md) - [PositionControllerStatus](PositionControllerStatus.md) -- [PositionSetpoint](PositionSetpoint.md) — this file is only used in the position_setpoint triple as a dependency -- [PositionSetpointTriplet](PositionSetpointTriplet.md) — Global position setpoint triplet in WGS84 coordinates. - This are the three next waypoints (or just the next two or one). -- [PowerButtonState](PowerButtonState.md) — power button state notification message -- [PowerMonitor](PowerMonitor.md) — power monitor message +- [PositionSetpoint](PositionSetpoint.md) — this file is only used in the position_setpoint triple as a dependency. +- [PositionSetpointTriplet](PositionSetpointTriplet.md) — Global position setpoint triplet in WGS84 coordinates. This are the three next waypoints (or just the next two or one). +- [PowerButtonState](PowerButtonState.md) — power button state notification message. +- [PowerMonitor](PowerMonitor.md) — power monitor message. - [PpsCapture](PpsCapture.md) -- [PurePursuitStatus](PurePursuitStatus.md) — Pure pursuit status +- [PurePursuitStatus](PurePursuitStatus.md) — Pure pursuit status. - [PwmInput](PwmInput.md) - [Px4ioStatus](Px4ioStatus.md) - [QshellReq](QshellReq.md) @@ -226,15 +192,15 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [RateCtrlStatus](RateCtrlStatus.md) - [RcChannels](RcChannels.md) - [RcParameterMap](RcParameterMap.md) -- [RoverAttitudeSetpoint](RoverAttitudeSetpoint.md) — Rover Attitude Setpoint -- [RoverAttitudeStatus](RoverAttitudeStatus.md) — Rover Attitude Status -- [RoverPositionSetpoint](RoverPositionSetpoint.md) — Rover Position Setpoint -- [RoverRateSetpoint](RoverRateSetpoint.md) — Rover Rate setpoint -- [RoverRateStatus](RoverRateStatus.md) — Rover Rate Status -- [RoverSpeedSetpoint](RoverSpeedSetpoint.md) — Rover Speed Setpoint -- [RoverSpeedStatus](RoverSpeedStatus.md) — Rover Velocity Status -- [RoverSteeringSetpoint](RoverSteeringSetpoint.md) — Rover Steering setpoint -- [RoverThrottleSetpoint](RoverThrottleSetpoint.md) — Rover Throttle setpoint +- [RoverAttitudeSetpoint](RoverAttitudeSetpoint.md) — Rover Attitude Setpoint. +- [RoverAttitudeStatus](RoverAttitudeStatus.md) — Rover Attitude Status. +- [RoverPositionSetpoint](RoverPositionSetpoint.md) — Rover Position Setpoint. +- [RoverRateSetpoint](RoverRateSetpoint.md) — Rover Rate setpoint. +- [RoverRateStatus](RoverRateStatus.md) — Rover Rate Status. +- [RoverSpeedSetpoint](RoverSpeedSetpoint.md) — Rover Speed Setpoint. +- [RoverSpeedStatus](RoverSpeedStatus.md) — Rover Velocity Status. +- [RoverSteeringSetpoint](RoverSteeringSetpoint.md) — Rover Steering setpoint. +- [RoverThrottleSetpoint](RoverThrottleSetpoint.md) — Rover Throttle setpoint. - [Rpm](Rpm.md) - [RtlStatus](RtlStatus.md) - [RtlTimeEstimate](RtlTimeEstimate.md) @@ -242,78 +208,64 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [SensorAccel](SensorAccel.md) - [SensorAccelFifo](SensorAccelFifo.md) - [SensorAirflow](SensorAirflow.md) -- [SensorBaro](SensorBaro.md) — Barometer sensor -- [SensorCombined](SensorCombined.md) — Sensor readings in SI-unit form. - These fields are scaled and offset-compensated where possible and do not - change with board revisions and sensor updates. -- [SensorCorrection](SensorCorrection.md) — Sensor corrections in SI-unit form for the voted sensor +- [SensorBaro](SensorBaro.md) — Barometer sensor. +- [SensorCombined](SensorCombined.md) — Sensor readings in SI-unit form. These fields are scaled and offset-compensated where possible and do not. change with board revisions and sensor updates. +- [SensorCorrection](SensorCorrection.md) — Sensor corrections in SI-unit form for the voted sensor. - [SensorGnssRelative](SensorGnssRelative.md) — GNSS relative positioning information in NED frame. The NED frame is defined as the local topological system at the reference station. -- [SensorGnssStatus](SensorGnssStatus.md) — Gnss quality indicators -- [SensorGps](SensorGps.md) — GPS position in WGS84 coordinates. - the field 'timestamp' is for the position & velocity (microseconds) +- [SensorGnssStatus](SensorGnssStatus.md) — Gnss quality indicators. +- [SensorGps](SensorGps.md) — GPS position in WGS84 coordinates. the field 'timestamp' is for the position & velocity (microseconds). - [SensorGyro](SensorGyro.md) - [SensorGyroFft](SensorGyroFft.md) - [SensorGyroFifo](SensorGyroFifo.md) - [SensorHygrometer](SensorHygrometer.md) - [SensorMag](SensorMag.md) - [SensorOpticalFlow](SensorOpticalFlow.md) -- [SensorPreflightMag](SensorPreflightMag.md) — Pre-flight sensor check metrics. - The topic will not be updated when the vehicle is armed -- [SensorSelection](SensorSelection.md) — Sensor ID's for the voted sensors output on the sensor_combined topic. - Will be updated on startup of the sensor module and when sensor selection changes +- [SensorPreflightMag](SensorPreflightMag.md) — Pre-flight sensor check metrics. The topic will not be updated when the vehicle is armed. +- [SensorSelection](SensorSelection.md) — Sensor ID's for the voted sensors output on the sensor_combined topic. Will be updated on startup of the sensor module and when sensor selection changes. - [SensorTemp](SensorTemp.md) -- [SensorUwb](SensorUwb.md) — UWB distance contains the distance information measured by an ultra-wideband positioning system, - such as Pozyx or NXP Rddrone. +- [SensorUwb](SensorUwb.md) — UWB distance contains the distance information measured by an ultra-wideband positioning system,. such as Pozyx or NXP Rddrone. - [SensorsStatus](SensorsStatus.md) — Sensor check metrics. This will be zero for a sensor that's primary or unpopulated. - [SensorsStatusImu](SensorsStatusImu.md) — Sensor check metrics. This will be zero for a sensor that's primary or unpopulated. - [SystemPower](SystemPower.md) -- [TakeoffStatus](TakeoffStatus.md) — Status of the takeoff state machine currently just available for multicopters -- [TaskStackInfo](TaskStackInfo.md) — stack information for a single running process +- [TakeoffStatus](TakeoffStatus.md) — Status of the takeoff state machine currently just available for multicopters. +- [TaskStackInfo](TaskStackInfo.md) — stack information for a single running process. - [TecsStatus](TecsStatus.md) - [TelemetryStatus](TelemetryStatus.md) - [TiltrotorExtraControls](TiltrotorExtraControls.md) - [TimesyncStatus](TimesyncStatus.md) -- [TrajectorySetpoint6dof](TrajectorySetpoint6dof.md) — Trajectory setpoint in NED frame - Input to position controller. +- [TrajectorySetpoint6dof](TrajectorySetpoint6dof.md) — Trajectory setpoint in NED frame. Input to position controller. - [TransponderReport](TransponderReport.md) -- [TuneControl](TuneControl.md) — This message is used to control the tunes, when the tune_id is set to CUSTOM - then the frequency, duration are used otherwise those values are ignored. -- [UavcanParameterRequest](UavcanParameterRequest.md) — UAVCAN-MAVLink parameter bridge request type -- [UavcanParameterValue](UavcanParameterValue.md) — UAVCAN-MAVLink parameter bridge response type -- [UlogStream](UlogStream.md) — Message to stream ULog data from the logger. Corresponds to the LOGGING_DATA - mavlink message -- [UlogStreamAck](UlogStreamAck.md) — Ack a previously sent ulog_stream message that had - the NEED_ACK flag set +- [TuneControl](TuneControl.md) — This message is used to control the tunes, when the tune_id is set to CUSTOM. then the frequency, duration are used otherwise those values are ignored. +- [UavcanParameterRequest](UavcanParameterRequest.md) — UAVCAN-MAVLink parameter bridge request type. +- [UavcanParameterValue](UavcanParameterValue.md) — UAVCAN-MAVLink parameter bridge response type. +- [UlogStream](UlogStream.md) — Message to stream ULog data from the logger. Corresponds to the LOGGING_DATA. mavlink message. +- [UlogStreamAck](UlogStreamAck.md) — Ack a previously sent ulog_stream message that had. the NEED_ACK flag set. - [VehicleAcceleration](VehicleAcceleration.md) -- [VehicleAirData](VehicleAirData.md) — Vehicle air data +- [VehicleAirData](VehicleAirData.md) — Vehicle air data. - [VehicleAngularAccelerationSetpoint](VehicleAngularAccelerationSetpoint.md) -- [VehicleConstraints](VehicleConstraints.md) — Local setpoint constraints in NED frame - setting something to NaN means that no limit is provided +- [VehicleConstraints](VehicleConstraints.md) — Local setpoint constraints in NED frame. setting something to NaN means that no limit is provided. - [VehicleImu](VehicleImu.md) — IMU readings in SI-unit form. - [VehicleImuStatus](VehicleImuStatus.md) -- [VehicleLocalPositionSetpoint](VehicleLocalPositionSetpoint.md) — Local position setpoint in NED frame - Telemetry of PID position controller to monitor tracking. - NaN means the state was not controlled +- [VehicleLocalPositionSetpoint](VehicleLocalPositionSetpoint.md) — Local position setpoint in NED frame. Telemetry of PID position controller to monitor tracking. NaN means the state was not controlled. - [VehicleMagnetometer](VehicleMagnetometer.md) - [VehicleOpticalFlow](VehicleOpticalFlow.md) — Optical flow in XYZ body frame in SI units. - [VehicleOpticalFlowVel](VehicleOpticalFlowVel.md) -- [VehicleRoi](VehicleRoi.md) — Vehicle Region Of Interest (ROI) +- [VehicleRoi](VehicleRoi.md) — Vehicle Region Of Interest (ROI). - [VehicleThrustSetpoint](VehicleThrustSetpoint.md) - [VehicleTorqueSetpoint](VehicleTorqueSetpoint.md) -- [VelocityLimits](VelocityLimits.md) — Velocity and yaw rate limits for a multicopter position slow mode only +- [VelocityLimits](VelocityLimits.md) — Velocity and yaw rate limits for a multicopter position slow mode only. +- [Vtx](Vtx.md) - [WheelEncoders](WheelEncoders.md) - [YawEstimatorStatus](YawEstimatorStatus.md) - [AirspeedValidatedV0](AirspeedValidatedV0.md) - [ArmingCheckReplyV0](ArmingCheckReplyV0.md) - [ArmingCheckRequestV0](ArmingCheckRequestV0.md) — Arming check request. -- [BatteryStatusV0](BatteryStatusV0.md) — Battery status -- [ConfigOverridesV0](ConfigOverridesV0.md) — Configurable overrides by (external) modes or mode executors -- [EventV0](EventV0.md) — this message is required here in the msg_old folder because other msg are depending on it - Events interface +- [BatteryStatusV0](BatteryStatusV0.md) — Battery status. +- [ConfigOverridesV0](ConfigOverridesV0.md) — Configurable overrides by (external) modes or mode executors. +- [EventV0](EventV0.md) — this message is required here in the msg_old folder because other msg are depending on it. Events interface. - [HomePositionV0](HomePositionV0.md) — GPS home position in WGS84 coordinates. - [RegisterExtComponentReplyV0](RegisterExtComponentReplyV0.md) -- [RegisterExtComponentRequestV0](RegisterExtComponentRequestV0.md) — Request to register an external component +- [RegisterExtComponentRequestV0](RegisterExtComponentRequestV0.md) — Request to register an external component. - [VehicleAttitudeSetpointV0](VehicleAttitudeSetpointV0.md) -- [VehicleLocalPositionV0](VehicleLocalPositionV0.md) — Fused local position in NED. - The coordinate system origin is the vehicle position at the time when the EKF2-module was started. -- [VehicleStatusV0](VehicleStatusV0.md) — Encodes the system state of the vehicle published by commander +- [VehicleLocalPositionV0](VehicleLocalPositionV0.md) — Fused local position in NED. The coordinate system origin is the vehicle position at the time when the EKF2-module was started. +- [VehicleStatusV0](VehicleStatusV0.md) — Encodes the system state of the vehicle published by commander. diff --git a/docs/en/payloads/generic_actuator_control.md b/docs/en/payloads/generic_actuator_control.md index 46b0248bf1..82bd1f4df9 100644 --- a/docs/en/payloads/generic_actuator_control.md +++ b/docs/en/payloads/generic_actuator_control.md @@ -56,7 +56,6 @@ To use a generic actuator in a mission: 1. Change the waypoint mission item to a "Set actuator" mission item: ![Set actuator mission item](../../assets/qgc/plan/mission_item_editors/mission_item_select_set_actuator.png) - - Select the header on the waypoint mission editor to open the **Select Mission Command** editor. - Select the category **Advanced**, and then the **Set actuator** item (if the item is not present, try a more recent version of _QGroundControl_ or a daily build). This will change the mission item type to "Set actuator". diff --git a/docs/en/peripherals/gripper.md b/docs/en/peripherals/gripper.md index 07886d70ca..da62f315d2 100644 --- a/docs/en/peripherals/gripper.md +++ b/docs/en/peripherals/gripper.md @@ -72,7 +72,6 @@ To set the actuation timeout: There are two easy ways to open and close the gripper. While the drone is on a bench and the propellers are removed: - - Run the `payload_deliverer` test in the QGC [MAVLink Shell](../debug/mavlink_shell.md): ```sh diff --git a/docs/en/peripherals/mavlink_peripherals.md b/docs/en/peripherals/mavlink_peripherals.md index 111d723ffd..9a790a9218 100644 --- a/docs/en/peripherals/mavlink_peripherals.md +++ b/docs/en/peripherals/mavlink_peripherals.md @@ -28,7 +28,6 @@ The parameters for each instance are: For more information see [Serial Port Configuration](../peripherals/serial_configuration.md). - [MAV_X_MODE](../advanced_config/parameter_reference.md#MAV_0_MODE) - Specify the telemetry mode/target (the set of messages to stream for the current instance and their rate). The default values are: - - _Normal_: Standard set of messages for a GCS. - _Custom_ or _Magic_: Nothing (in the default PX4 implementation). Modes may be used for testing when developing a new mode. diff --git a/docs/en/peripherals/remote_id.md b/docs/en/peripherals/remote_id.md index 399b2cf973..60d3413661 100644 --- a/docs/en/peripherals/remote_id.md +++ b/docs/en/peripherals/remote_id.md @@ -165,7 +165,6 @@ PX4 v1.14 streams these messages by default (in streaming modes: normal, onboard - [OPEN_DRONE_ID_LOCATION](https://mavlink.io/en/messages/common.html#OPEN_DRONE_ID_LOCATION) (1 Hz) - UAV location, altitude, direction, and speed. - [OPEN_DRONE_ID_SYSTEM](https://mavlink.io/en/messages/common.html#OPEN_DRONE_ID_SYSTEM) (1 Hz) Operator location/altitude, multiple aircraft information (group/swarm, if applicable), full timestamp and possible category/class information. - - Implementation assumes operator is located at vehicle home position (does not yet support getting operator position from GCS). This is believed to be compliant for broadcast-only Remote IDs. @@ -243,7 +242,7 @@ If the Remote ID CAN node is present and the messages are not being received, th 2. Navigate to the [Application settings](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/settings_view/general.html): **Application Settings > General > Miscellaneous**. 3. Select `Enable Remote ID`. The Remote ID tab should appear. - + ::: info If this option is not present you may be in a very recent version of QGC. In that case, open the view at: **Application Settings > Remote ID**. diff --git a/docs/en/peripherals/serial_configuration.md b/docs/en/peripherals/serial_configuration.md index 9228a0ad5a..65650feef5 100644 --- a/docs/en/peripherals/serial_configuration.md +++ b/docs/en/peripherals/serial_configuration.md @@ -106,7 +106,6 @@ The following ports are commonly mapped to specific functions on all boards: This is configured by default as a MAVLink port the onboard profile (for companion computers). The configuration for MAVLink is unique to this port (it doesn't use the `MAV_X_CONFIG` parameters). - - [SYS_USB_AUTO](../advanced_config/parameter_reference.md#SYS_USB_AUTO) sets whether the port is set to no partiular protocol, autodetects the protocol, or sets the comms link to MAVLink. - [USB_MAV_MODE](../advanced_config/parameter_reference.md#USB_MAV_MODE) sets the MAVLink profile that is used if MAVLink is set or detected. diff --git a/docs/en/power_module/ark_12s_pab_power_module.md b/docs/en/power_module/ark_12s_pab_power_module.md index 77c33cf32e..63c6223758 100644 --- a/docs/en/power_module/ark_12s_pab_power_module.md +++ b/docs/en/power_module/ark_12s_pab_power_module.md @@ -13,25 +13,21 @@ Order this module from: ## Hardware Specifications - **TI INA238 Digital Power Monitor** - - 0.0001 Ohm Shunt - I2C Interface - **5.2V 6A Step-Down Regulator** - - 66V Maximum Input Voltage - 10V Minimum Input Voltage at 6A Out - Output Over-Current Protection - **Connections** - - Solder Pads Battery Input - Solder Pads Battery Output - 6 Pin Molex CLIK-Mate Output - [Matches ARK PAB Carrier Power Pinout](https://arkelectron.gitbook.io/ark-documentation/flight-controllers/ark-pixhawk-autopilot-bus-carrier/pinout) - **Other** - - USA Built - Includes 6 Pin Molex CLIK-Mate Cable diff --git a/docs/en/power_module/cuav_hv_pm.md b/docs/en/power_module/cuav_hv_pm.md index 7093c588ed..48e169a7f8 100644 --- a/docs/en/power_module/cuav_hv_pm.md +++ b/docs/en/power_module/cuav_hv_pm.md @@ -1,9 +1,9 @@ # CUAV HV PM (High-Voltage Power Module) -The CUAV® *HV_PM* power module is a "high voltage" power module independently developed by CUAV. +The CUAV® _HV_PM_ power module is a "high voltage" power module independently developed by CUAV. :::tip -The *HV_PM* is included in the CUAV V5+/V5 nano kit, but is also be sold separately. +The _HV_PM_ is included in the CUAV V5+/V5 nano kit, but is also be sold separately. There are different cables depending on the flight controller (Pixhack v3, V5+/V5 nano, Pixhawk). It can be used with other flight controllers, but you may need to modify the cable pin. ::: @@ -12,7 +12,7 @@ It can be used with other flight controllers, but you may need to modify the cab - **Higher voltage input:** 10V-60V (3s~14s battery) - **Accurate battery monitor:** - - **Voltage detection accuracy:** +-0.1v; + - **Voltage detection accuracy:** +-0.1v; - **Current detection accuracy:** +-0.2A - **BEC (5v) max current:** 5A - **Max (detection) current:** 60A @@ -31,5 +31,6 @@ It can be used with other flight controllers, but you may need to modify the cab [Battery Estimation Tuning](../config/battery.md) describes how to configure the battery and power module. The key configuration settings for `HV_PM` are: + - **Voltage divider:** 18 - **Amps per volt:** 24 A/V diff --git a/docs/en/power_module/holybro_pm02.md b/docs/en/power_module/holybro_pm02.md index 0f88cabf20..adb6447710 100644 --- a/docs/en/power_module/holybro_pm02.md +++ b/docs/en/power_module/holybro_pm02.md @@ -9,7 +9,6 @@ The module can be used with other flight controllers that require an analog powe ![Holybro PM02](../../assets/hardware/power_module/holybro_pm02/pm02.jpg) - ## Specifications - **Rated current**: 60A diff --git a/docs/en/power_module/holybro_pm03d.md b/docs/en/power_module/holybro_pm03d.md index 7f6825a0c2..526beebf69 100644 --- a/docs/en/power_module/holybro_pm03d.md +++ b/docs/en/power_module/holybro_pm03d.md @@ -31,13 +31,13 @@ The PM is **NOT** compatible with flight controllers that require an analog powe - **Mounting**: 45 x 45mm - **Weight**: 59g - **Connections**: - - XT-60 for battery - - XT-30 for motor & peripheral device (battery voltage) - - Solder pads in each corner (battery voltage) - - CLIK-Mate 2.0mm for flight controller (5.2V/3A standalone BEC) - - JST GH 4pin (5.2V/3A, BEC shared with 5.2V triple row pin header) - - 2x Triple row pin header (5.2V/3A, BEC shared with JST GH 4pin) - - 2x Triple row pin header (8V or 12V selectable by moving header jumper, 3A) +- XT-60 for battery +- XT-30 for motor & peripheral device (battery voltage) +- Solder pads in each corner (battery voltage) +- CLIK-Mate 2.0mm for flight controller (5.2V/3A standalone BEC) +- JST GH 4pin (5.2V/3A, BEC shared with 5.2V triple row pin header) +- 2x Triple row pin header (5.2V/3A, BEC shared with JST GH 4pin) +- 2x Triple row pin header (8V or 12V selectable by moving header jumper, 3A) ## Package Contents @@ -46,8 +46,8 @@ The PM is **NOT** compatible with flight controllers that require an analog powe - 1x Electrolytic capacitor: 220uF 63V (pre-soldered) - 1x 2.0mm pitch CLIK-Mate 6pin cable (To power flight controller) - 4pin JST GH to USB Type C -- 4pin JST GH to barrel plug (2.1*5.5mm) -- 4pin JST GH to barrel plug (2.5*5.5mm) +- 4pin JST GH to barrel plug (2.1\*5.5mm) +- 4pin JST GH to barrel plug (2.5\*5.5mm) - 4pin Pin Dupont Cable (2pc) - Nylon standoffs & nuts diff --git a/docs/en/power_module/holybro_pm06_pixhawk4mini_power_module.md b/docs/en/power_module/holybro_pm06_pixhawk4mini_power_module.md index ea8ac4f99a..9821c35cea 100644 --- a/docs/en/power_module/holybro_pm06_pixhawk4mini_power_module.md +++ b/docs/en/power_module/holybro_pm06_pixhawk4mini_power_module.md @@ -4,7 +4,6 @@ This power module has integrated power distribution board and provides regulated ![PM06](../../assets/hardware/power_module/holybro_pm06_14s/pm06v2_pm06v2-14s.jpg) - ## Specifications - **PCB Current:** 120A continued @@ -18,7 +17,7 @@ This power module has integrated power distribution board and provides regulated ## Mechanical Specifications - **Dimensions:** 35x35x5mm -- **Mounting hole:** 30.5mm*30.5mm +- **Mounting hole:** 30.5mm\*30.5mm - **Weight:** 24g ## Where to Buy diff --git a/docs/en/power_module/holybro_pm07_pixhawk4_power_module.md b/docs/en/power_module/holybro_pm07_pixhawk4_power_module.md index a1791ff177..0e7f7414fe 100644 --- a/docs/en/power_module/holybro_pm07_pixhawk4_power_module.md +++ b/docs/en/power_module/holybro_pm07_pixhawk4_power_module.md @@ -33,14 +33,12 @@ This module can be purchased as bundle with [Pixhawk 4](../assembly/quick_start_ [Pixhawk 4 Power Module (PM07)](https://holybro.com/collections/power-modules-pdbs/products/pixhawk-4-power-module-pm07) - ## Wiring/Connections Wiring and connection information can be found in: [Pixhawk 4 > Power](../assembly/quick_start_pixhawk4.md#power). ![Pixhawk 4 - Power Management Board](../../assets/hardware/power_module/holybro_pm07/pixhawk4_power_management_board.png) - ## Further Information [Quick Start Guide](https://docs.holybro.com/power-module-and-pdb/power-module/pm07-quick-start-guide) (Holybro) diff --git a/docs/en/power_module/sky-drones_smartap-pdb.md b/docs/en/power_module/sky-drones_smartap-pdb.md index 6447feff24..3ea985b7b4 100644 --- a/docs/en/power_module/sky-drones_smartap-pdb.md +++ b/docs/en/power_module/sky-drones_smartap-pdb.md @@ -21,7 +21,6 @@ SmartAP PDB makes connecting high-power lines easier and much more reliable. - Integrated electromagnetic sounder (buzzer) - Power output for the flight controller (both 5V regulated and battery voltage level output) - ## Size and Weight - Length: 65mm @@ -38,12 +37,10 @@ The key configuration settings are: - Voltage divider: 15.51 - Amps per volt: 36.00 - ## Where to buy [SmartAP PDB](https://sky-drones.com/parts/smartap-pdb.html) - ## Wiring / Pinout SmartAP Power Distribution Board pinout diagram is shown below. @@ -61,7 +58,6 @@ The current sensor is located on the bottom side of the PDB. ![SmartAP PDB](../../assets/hardware/power_module/sky-drones_smartap-pdb/smartap-pdb-current-sensor.png) - ## Further Information - [Buy SmartAP PDB](https://sky-drones.com/power/smartap-pdb.html) diff --git a/docs/en/releases/1.13.md b/docs/en/releases/1.13.md index fdda97c87f..7357fe68cd 100644 --- a/docs/en/releases/1.13.md +++ b/docs/en/releases/1.13.md @@ -24,7 +24,6 @@ ### Common - **Explicit Joystick source selection ([PR#17404](https://github.com/PX4/PX4-Autopilot/pull/17404))** - - Possibility to: - Explicitly allow just one source - Fall back to other source in air diff --git a/docs/en/ros/mavros_custom_messages.md b/docs/en/ros/mavros_custom_messages.md index 5f18636ad6..3549abea35 100644 --- a/docs/en/ros/mavros_custom_messages.md +++ b/docs/en/ros/mavros_custom_messages.md @@ -2,6 +2,7 @@ :::warning This article has been tested against: + - **Ubuntu:** 20.04 - **ROS:** Noetic - **PX4 Firmware:** v1.13 @@ -13,13 +14,14 @@ However these steps are fairly general and so it should work with other distros/ ## MAVROS Installation -Follow *Source Installation* instructions from [mavlink/mavros](https://github.com/mavlink/mavros/blob/master/mavros/index.md) to install "ROS Kinetic". +Follow _Source Installation_ instructions from [mavlink/mavros](https://github.com/mavlink/mavros/blob/master/mavros/index.md) to install "ROS Kinetic". ## MAVROS 1. We start by creating a new MAVROS plugin, in this example named **keyboard_command.cpp** (in **workspace/src/mavros/mavros_extras/src/plugins**) by using the code below: The code subscribes a 'char' message from ROS topic `/mavros/keyboard_command/keyboard_sub` and sends it as a MAVLink message. + ```c #include #include @@ -66,6 +68,7 @@ Follow *Source Installation* instructions from [mavlink/mavros](https://github.c ``` 1. Edit **mavros_plugins.xml** (in **workspace/src/mavros/mavros_extras**) and add the following lines: + ```xml Accepts keyboard command. @@ -73,10 +76,11 @@ Follow *Source Installation* instructions from [mavlink/mavros](https://github.c ``` 1. Edit **CMakeLists.txt** (in **workspace/src/mavros/mavros_extras**) and add the following line in `add_library`. + ```cmake - add_library( + add_library( ... - src/plugins/keyboard_command.cpp + src/plugins/keyboard_command.cpp ) ``` @@ -93,6 +97,7 @@ Follow *Source Installation* instructions from [mavlink/mavros](https://github.c ## PX4 Changes 1. Inside **common.xml** (in **PX4-Autopilot/src/modules/mavlink/mavlink/message_definitions/v1.0**), add your MAVLink message as following (same procedure as for MAVROS section above): + ```xml ... @@ -106,10 +111,11 @@ Follow *Source Installation* instructions from [mavlink/mavros](https://github.c Make sure that the **common.xml** files in the following directories are exactly the same: - `PX4-Autopilot/src/modules/mavlink/mavlink/message_definitions/v1.0` - `workspace/src/mavlink/message_definitions/v1.0` - are exactly the same. - ::: + are exactly the same. + ::: 1. Make your own uORB message file **key_command.msg** in (PX4-Autopilot/msg). For this example the "key_command.msg" has only the code: + ``` uint64 timestamp # time since system start (microseconds) char cmd @@ -142,6 +148,7 @@ Follow *Source Installation* instructions from [mavlink/mavros](https://github.c 1. Edit **mavlink_receiver.cpp** (in **PX4-Autopilot/src/modules/mavlink**). This is where PX4 receives the MAVLink message sent from ROS, and publishes it as a uORB topic. + ```cpp ... void MavlinkReceiver::handle_message(mavlink_message_t *msg) @@ -221,7 +228,7 @@ Follow *Source Installation* instructions from [mavlink/mavros](https://github.c int error_counter = 0; - for (int i = 0; i < 10; i++) + for (int i = 0; i < 10; i++) { int poll_ret = px4_poll(fds, 1, 1000); @@ -258,10 +265,10 @@ Follow *Source Installation* instructions from [mavlink/mavros](https://github.c ``` menuconfig MODULES_KEY_RECEIVER - bool "key_receiver" - default n - ---help--- - Enable support for key_receiver + bool "key_receiver" + default n + ---help--- + Enable support for key_receiver ``` @@ -283,7 +290,7 @@ Now you are ready to build all your work! ### Build for ROS 1. In your workspace enter: `catkin build`. -1. Beforehand, you have to set your "px4.launch" in (/workspace/src/mavros/mavros/launch). +1. Beforehand, you have to set your "px4.launch" in (/workspace/src/mavros/mavros/launch). Edit "px4.launch" as below. If you are using USB to connect your computer with Pixhawk, you have to set "fcu_url" as shown below. But, if you are using CP2102 to connect your computer with Pixhawk, you have to replace "ttyACM0" with "ttyUSB0". @@ -301,22 +308,25 @@ Now you are ready to build all your work! ### Build for PX4 1. Clean the previously built PX4-Autopilot directory. In the root of **PX4-Autopilot** directory: - ```sh - make clean - ``` -1. Build PX4-Autopilot and upload [in the normal way](../dev_setup/building_px4.md#nuttx-pixhawk-based-boards). + ```sh + make clean + ``` - For example: - - - to build for Pixhawk 4/FMUv5 execute the following command in the root of the PX4-Autopilot directory: - ```sh - make px4_fmu-v5_default upload - ``` - - to build for SITL execute the following command in the root of the PX4-Autopilot directory (using jmavsim simulation): - ```sh - make px4_sitl jmavsim - ``` +1. Build PX4-Autopilot and upload [in the normal way](../dev_setup/building_px4.md#nuttx-pixhawk-based-boards). + + For example: + - to build for Pixhawk 4/FMUv5 execute the following command in the root of the PX4-Autopilot directory: + + ```sh + make px4_fmu-v5_default upload + ``` + + - to build for SITL execute the following command in the root of the PX4-Autopilot directory (using jmavsim simulation): + + ```sh + make px4_sitl jmavsim + ``` ## Running the Code @@ -338,6 +348,7 @@ Next test if the MAVROS message is sent to PX4. 1. Enter the Pixhawk nutshell through UDP. Replace xxx.xx.xxx.xxx with your IP. + ```sh cd PX4-Autopilot/Tools ./mavlink_shell.py xxx.xx.xxx.xxx:14557 --baudrate 57600 diff --git a/docs/en/ros2/multi_vehicle.md b/docs/en/ros2/multi_vehicle.md index e295d49932..abed4ee206 100644 --- a/docs/en/ros2/multi_vehicle.md +++ b/docs/en/ros2/multi_vehicle.md @@ -38,12 +38,12 @@ This mismatch can be fixed by manually using `PX4_UXRCE_DDS_NS` on the first ins The default client configuration in simulation is summarized as follows: -| `PX4_UXRCE_DDS_NS` | `px4_instance` | `UXRCE_DDS_KEY` | client namespace | -|-------------------|----------------|------------------|-----------------------| -| not provided | 0 | `px4_instance+1` | none | -| provided | 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | -| not provided | >0 | `px4_instance+1` | `px4_${px4_instance}` | -| provided | >0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | +| `PX4_UXRCE_DDS_NS` | `px4_instance` | `UXRCE_DDS_KEY` | client namespace | +| ------------------ | -------------- | ---------------- | --------------------- | +| not provided | 0 | `px4_instance+1` | none | +| provided | 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | +| not provided | >0 | `px4_instance+1` | `px4_${px4_instance}` | +| provided | >0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | ## Adjusting the `target_system` value diff --git a/docs/en/ros2/px4_ros2_msg_translation_node.md b/docs/en/ros2/px4_ros2_msg_translation_node.md index f9dab8a42a..5587c4fdbb 100644 --- a/docs/en/ros2/px4_ros2_msg_translation_node.md +++ b/docs/en/ros2/px4_ros2_msg_translation_node.md @@ -305,7 +305,6 @@ The example describes the process of updating the `VehicleAttitude` message defi Update the existing translations header files `msg/translation_node/translations/*.h` to reference the newly archived message definition. For example, update references in those files:
- - Replace `px4_msgs::msg::VehicleAttitude` → `px4_msgs_old::msg::VehicleAttitudeV3` - Replace `#include ` → `#include ` @@ -386,7 +385,6 @@ The example describes the process of updating the `VehicleAttitude` message defi ``` Version translation templates are provided here: - - [Direct Topic Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_direct_v1.h) - [Generic Topic Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_multi_v2.h) - [Direct Service Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_service_v1.h) @@ -440,7 +438,7 @@ For translations with multiple input topics, the translation continues once all - Services messages only support a linear history, i.e. no message splitting or merging. - Having both publishers and subscribers for two different versions of the same topic is currently not handled by the translation node and would trigger infinite circular publications. This refers to the following problematic configuration: - + ``` app 1: pub topic_v1, sub topic_v1 app 2: pub topic_v2, sub topic_v2 diff --git a/docs/en/sensor/inertiallabs.md b/docs/en/sensor/inertiallabs.md index c86ab79e64..2d677e0d53 100644 --- a/docs/en/sensor/inertiallabs.md +++ b/docs/en/sensor/inertiallabs.md @@ -5,7 +5,6 @@ A universal protocol is used for [all Inertial Labs sensors](https://inertiallab ![INS-U](../../assets/hardware/sensors/inertial/ilabs-ins-u.png) - Benefits to PX4 users: - Higher accuracy heading, pitch, and roll estimates diff --git a/docs/en/sensor/microstrain.md b/docs/en/sensor/microstrain.md index c4aad808eb..9a6964180d 100644 --- a/docs/en/sensor/microstrain.md +++ b/docs/en/sensor/microstrain.md @@ -40,14 +40,11 @@ To use the MicroStrain driver: 1. Include the module in firmware in the [kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) by setting the kconfig variables: `CONFIG_DRIVERS_INS_MICROSTRAIN` or `CONFIG_COMMON_INS`. 2. Configure the driver mode by setting [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) - - To use the MicroStrain sensor to provide raw IMU data to EKF2 - 1. Set [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) to 0 2. Update the [EKF2_MULTI_IMU](../advanced_config/parameter_reference.md#EKF2_MULTI_IMU) parameter to account for the added MicroStrain sensor. 3. Enable EKF2 by setting [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN) to 1 4. To prioritize MicroStrain sensor output, adjust the priority level of individual sensors from 0-100 using the following parameters: - - [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO) - [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO) - [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO) @@ -57,7 +54,6 @@ To use the MicroStrain driver: ::: tip Sensors can be identified by their device id, which can be found by checking the parameters: - - [CAL_ACCn_ID](../advanced_config/parameter_reference.md#CAL_ACC0_ID) - [CAL_GYROn_ID](../advanced_config/parameter_reference.md#CAL_GYRO0_ID) - [CAL_MAGn_ID](../advanced_config/parameter_reference.md#CAL_MAG0_ID) @@ -76,32 +72,26 @@ To use the MicroStrain driver: ## MicroStrain Configuration 1. Rates: - - By default, accel and gyro data are published at 500 Hz, magnetometer at 50 Hz, and barometric pressure at 50 Hz. This can be changed by adjusting the following parameters: - - [MS_IMU_RATE_HZ](../advanced_config/parameter_reference.md#MS_IMU_RATE_HZ) - [MS_MAG_RATE_HZ](../advanced_config/parameter_reference.md#MS_MAG_RATE_HZ) - [MS_BARO_RATE_HZ](../advanced_config/parameter_reference.md#MS_BARO_RATE_HZ) - Global position, local position, attitude and odometry will be published at 250 Hz by default. This can be configured via: - - [MS_FILT_RATE_HZ](../advanced_config/parameter_reference.md#MS_FILT_RATE_HZ) - For the CV7-GNSS/INS, the GNSS receiver 1 and 2 will publish data at 5Hz by default. This can be changed using: - - [MS_GNSS_RATE_HZ](../advanced_config/parameter_reference.md#MS_GNSS_RATE_HZ) - The driver will automatically configure data outputs based on the specific sensor model and available data streams. - The driver is scheduled to run at twice the fastest configured data rate. 2. Aiding measurements: - - If supported, GNSS position and velocity aiding are always enabled. - Internal/external magnetometer and heading aiding, as well as optical flow aiding, are disabled by default. They can be enabled using the following parameters: - - [MS_INT_MAG_EN](../advanced_config/parameter_reference.md#MS_INT_MAG_EN) - [MS_INT_HEAD_EN](../advanced_config/parameter_reference.md#MS_INT_HEAD_EN) - [MS_EXT_HEAD_EN](../advanced_config/parameter_reference.md#MS_EXT_HEAD_EN) @@ -109,7 +99,6 @@ To use the MicroStrain driver: - [MS_OPT_FLOW_EN](../advanced_config/parameter_reference.md#MS_OPT_FLOW_EN) - The aiding frames for external sources can be configured using the following parameters: - - [MS_EHEAD_YAW](../advanced_config/parameter_reference.md#MS_EHEAD_YAW) - [MS_EMAG_ROLL](../advanced_config/parameter_reference.md#MS_EMAG_ROLL) - [MS_EMAG_PTCH](../advanced_config/parameter_reference.md#MS_EMAG_PTCH) @@ -120,7 +109,6 @@ To use the MicroStrain driver: - [SENS_FLOW_ROT](../advanced_config/parameter_reference.md#SENS_FLOW_ROT) - The uncertainty for optical flow and external magnetometer aiding must be specified using the following parameters: - - [MS_EMAG_UNCERT](../advanced_config/parameter_reference.md#MS_EMAG_UNCERT) - [MS_OFLW_UNCERT](../advanced_config/parameter_reference.md#MS_OFLW_UNCERT) @@ -131,33 +119,24 @@ To use the MicroStrain driver: ::: 3. Initial heading alignment: - - Initial heading alignment is set to kinematic by default. This can be changed by adjusting - - [MS_ALIGNMENT](../advanced_config/parameter_reference.md#MS_ALIGNMENT) 4. GNSS Aiding Source Control (GNSS/INS only) - - The Source of the GNSS aiding data can be configured using: - - [MS_GNSS_AID_SRC](../advanced_config/parameter_reference.md#MS_GNSS_AID_SRC) 5. Sensor to vehicle transform: - - If the sensor is mounted in an orientation different from the vehicle frame. A sensor to vehicle transform can be enabled using - - [MS_SVT_EN](../advanced_config/parameter_reference.md#MS_SVT_EN) - The transform is defined using the following parameters - - [MS_SENSOR_ROLL](../advanced_config/parameter_reference.md#MS_SENSOR_ROLL) - [MS_SENSOR_PTCH](../advanced_config/parameter_reference.md#MS_SENSOR_PTCH) - [MS_SENSOR_YAW](../advanced_config/parameter_reference.md#MS_SENSOR_YAW) 6. IMU ranges: - - The accelerometer and gyroscope ranges on the device are configurable using: - - [MS_ACCEL_RANGE](../advanced_config/parameter_reference.md#MS_ACCEL_RANGE) - [MS_GYRO_RANGE](../advanced_config/parameter_reference.md#MS_GYRO_RANGE) @@ -168,15 +147,12 @@ To use the MicroStrain driver: ::: 7. GNSS Lever arm offsets: - - The lever arm offset for the external GNSS receiver can be configured using: - - [MS_GNSS_OFF1_X](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_X) - [MS_GNSS_OFF1_Y](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_Y) - [MS_GNSS_OFF1_Z](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_Z) - For dual-antenna configurations, the second GNSS receiver’s offset is configured using: - - [MS_GNSS_OFF2_X](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_X) - [MS_GNSS_OFF2_Y](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_Y) - [MS_GNSS_OFF2_Z](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_Z) diff --git a/docs/en/sensor/optical_flow.md b/docs/en/sensor/optical_flow.md index f4fa4fcf0c..f76a40b4bb 100644 --- a/docs/en/sensor/optical_flow.md +++ b/docs/en/sensor/optical_flow.md @@ -55,7 +55,7 @@ Reducing the optical flow scale factor can improve the situation. It has a PAW3902 optical flow sensor, Broadcom AFBR-S50LV85D 30 meter distance sensor, and Invensense ICM-42688-P 6-Axis IMU. [ARK Flow MR](../dronecan/ark_flow_mr.md) is a [DroneCAN](../dronecan/index.md) optical flow sensor, [distance sensor](../sensor/rangefinders.md), and IMU, for mid-range applications. -It has a PixArt PAA3905 optical flow sensor, Broadcom AFBR-S50LX85D 50 meter distance sensor, and Invensense IIM-42653 6-Axis IMU. +It has a PixArt PAA3905 optical flow sensor, Broadcom AFBR-S50LX85D 50 meter distance sensor, and Invensense IIM-42653 6-Axis IMU. ### Holybro H-Flow diff --git a/docs/en/sensor/sbgecom.md b/docs/en/sensor/sbgecom.md index 508024bbd0..2115f1f4c1 100644 --- a/docs/en/sensor/sbgecom.md +++ b/docs/en/sensor/sbgecom.md @@ -76,8 +76,7 @@ To use the sbgECom driver: In this case, MAVLink messages will be updated with the newly selected sensor. If you don't want to have this fallback mechanism, you must disable unwanted sensors. - ::: - 4. If using the sbgECom as an INS, disable EKF2 using [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN). + ::: 4. If using the sbgECom as an INS, disable EKF2 using [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN). 6. Restart PX4. diff --git a/docs/en/sensor/sfxx_lidar.md b/docs/en/sensor/sfxx_lidar.md index d9838ee45e..40d21ada31 100644 --- a/docs/en/sensor/sfxx_lidar.md +++ b/docs/en/sensor/sfxx_lidar.md @@ -15,8 +15,8 @@ The following models are supported by PX4, and can be connected to either the I2 | [LW20/C](https://lightware.co.za/products/lw20-c-100-m) | 100 | I2C bus | Waterproofed (IP67) with servo for sense-and-avoid applications | | [SF30/D](https://lightwarelidar.com/shop/sf30-d-200-m/) | 200 | I2C bus | Waterproofed (IP67) | | [SF45/B](../sensor/sf45_rotating_lidar.md) | 50 | Serial | Rotary Lidar (Used for [Collision Prevention](../computer_vision/collision_prevention.md)) | -| [GRF250](https://lightwarelidar.com/shop/grf-250/) | 250 | I2C | Gimbal Range Finder -| [GRF500](https://lightwarelidar.com/shop/grf-500/) | 500 | I2C | Gimbal Range Finder +| [GRF250](https://lightwarelidar.com/shop/grf-250/) | 250 | I2C | Gimbal Range Finder | +| [GRF500](https://lightwarelidar.com/shop/grf-500/) | 500 | I2C | Gimbal Range Finder | ::: details Discontinued diff --git a/docs/en/sensor/vectornav.md b/docs/en/sensor/vectornav.md index b6291f4e4e..cbe8f7b53a 100644 --- a/docs/en/sensor/vectornav.md +++ b/docs/en/sensor/vectornav.md @@ -55,11 +55,9 @@ To use the VectorNav driver: 1. Disable magnetometer preflight checks by setting [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG) to `0`. 1. Allow the VectorNav driver to initialize by restarting PX4. 1. Configure driver as either an external INS or to provide raw data: - - If using the VectorNav as an external INS, set [VN_MODE](../advanced_config/parameter_reference.md#VN_MODE) to `INS`. This disables EKF2. - If using the VectorNav as external inertial sensors: - 1. Set [VN_MODE](../advanced_config/parameter_reference.md#VN_MODE) to `Sensors Only` 1. If internal sensors are enabled, prioritize VectorNav sensors using [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO), [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO), [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO), [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO), where _n_ is the instance number of the IMU component (0, 1, etc.). diff --git a/docs/en/sensor_bus/i2c_development.md b/docs/en/sensor_bus/i2c_development.md index b1ddfa21bf..0a0ccf07e7 100644 --- a/docs/en/sensor_bus/i2c_development.md +++ b/docs/en/sensor_bus/i2c_development.md @@ -4,9 +4,10 @@ I2C is a packet-switched serial communication protocol that allows multiple mast It is intended for attaching lower-speed peripheral ICs to processors and microcontrollers in short-distance, intra-board communication. Pixhawk/PX4 support it for: -* Connecting off board components that require higher data rates than provided by a strict serial UART, such as rangefinders. -* Compatibility with peripheral devices that only support I2C. -* Allowing multiple devices to attach to a single bus (useful for conserving ports). + +- Connecting off board components that require higher data rates than provided by a strict serial UART, such as rangefinders. +- Compatibility with peripheral devices that only support I2C. +- Allowing multiple devices to attach to a single bus (useful for conserving ports). For example, LEDs, Compass, rangefinders etc. ::: info @@ -22,15 +23,17 @@ The bus is not fast enough even with a single device attached to allow vibration Drivers should `#include ` and then provide an implementation of the abstract base class `I2C` defined in **I2C.hpp** for the target hardware (i.e. for NuttX [here](https://github.com/PX4/PX4-Autopilot/blob/main/src/lib/drivers/device/nuttx/I2C.hpp)). -A small number of drivers will also need to include headers for their type of device (**drv_*.h**) in [/src/drivers/](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers) - e.g. [drv_led.h](https://github.com/PX4/PX4-Autopilot/blob/main/src/drivers/drv_led.h). +A small number of drivers will also need to include headers for their type of device (**drv\_\*.h**) in [/src/drivers/](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers) - e.g. [drv_led.h](https://github.com/PX4/PX4-Autopilot/blob/main/src/drivers/drv_led.h). To include a driver in firmware you must add the driver to the board-specific cmake file that corresponds to the target you want to build for. You can do this for a single driver: + ``` CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_I2C=y ``` You can also include all drivers of a particular type. + ``` CONFIG_COMMON_DISTANCE_SENSOR=y ``` @@ -44,12 +47,13 @@ For example, you can see/search for `CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LA To find I2C driver examples, search for **i2c.h** in [/src/drivers/](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers). Just a few examples are: -* [drivers/distance_sensor/lightware_laser_i2c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/lightware_laser_i2c) - I2C driver for [Lightware SF1XX LIDAR](../sensor/sfxx_lidar.md). -* [drivers/distance_sensor/lightware_laser_serial](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/lightware_laser_serial) - Serial driver for [Lightware SF1XX LIDAR](../sensor/sfxx_lidar.md). -* [drivers/ms5611](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/ms5611) - I2C Driver for the MS5611 and MS6507 barometric pressure sensor connected via I2C (or SPI). + +- [drivers/distance_sensor/lightware_laser_i2c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/lightware_laser_i2c) - I2C driver for [Lightware SF1XX LIDAR](../sensor/sfxx_lidar.md). +- [drivers/distance_sensor/lightware_laser_serial](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/lightware_laser_serial) - Serial driver for [Lightware SF1XX LIDAR](../sensor/sfxx_lidar.md). +- [drivers/ms5611](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/ms5611) - I2C Driver for the MS5611 and MS6507 barometric pressure sensor connected via I2C (or SPI). ## Further Information -* [I2C](https://en.wikipedia.org/wiki/I%C2%B2C) (Wikipedia) -* [I2C Comparative Overview](https://learn.sparkfun.com/tutorials/i2c) (learn.sparkfun.com) -* [Driver Framework](../middleware/drivers.md) +- [I2C](https://en.wikipedia.org/wiki/I%C2%B2C) (Wikipedia) +- [I2C Comparative Overview](https://learn.sparkfun.com/tutorials/i2c) (learn.sparkfun.com) +- [Driver Framework](../middleware/drivers.md) diff --git a/docs/en/sensor_bus/i2c_general.md b/docs/en/sensor_bus/i2c_general.md index 2715b604e3..9242b7c70b 100644 --- a/docs/en/sensor_bus/i2c_general.md +++ b/docs/en/sensor_bus/i2c_general.md @@ -4,9 +4,9 @@ It is recommended for: -* Connecting offboard components that require low bandwidth and low latency communication, e.g. [rangefinders](../sensor/rangefinders.md), [magnetometers](../gps_compass/magnetometer.md), [airspeed sensors](../sensor/airspeed.md) and [tachometers](../sensor/tachometers.md). -* Compatibility with peripheral devices that only support I2C. -* Allowing multiple devices to attach to a single bus, which is useful for conserving ports. +- Connecting offboard components that require low bandwidth and low latency communication, e.g. [rangefinders](../sensor/rangefinders.md), [magnetometers](../gps_compass/magnetometer.md), [airspeed sensors](../sensor/airspeed.md) and [tachometers](../sensor/tachometers.md). +- Compatibility with peripheral devices that only support I2C. +- Allowing multiple devices to attach to a single bus, which is useful for conserving ports. I2C allows multiple master devices to connect to multiple slave devices using only 2 wires per connection (SDA, SCL). in theory, a bus can support 128 devices, each accessed via its unique address. @@ -15,7 +15,6 @@ in theory, a bus can support 128 devices, each accessed via its unique address. UAVCAN would normally be preferred where higher data rates are required, and on larger vehicles where sensors are mounted further from the flight controller. ::: - ## Wiring I2C uses a pair of wires: SDA (serial data) and SCL (serial clock). @@ -29,7 +28,6 @@ To ensure reliable communication and to reduce crosstalk it is advised to apply ![Cable twisting](../../assets/hardware/cables/i2c_jst-gh_cable.jpg) - ## Checking the Bus and Device Status A useful tool for bus analysis is [i2cdetect](../modules/modules_command.md#i2cdetect). @@ -41,8 +39,8 @@ The tool can be run in the PX4 terminal with the following command: ``` i2cdetect -b 1 ``` -where the bus number is specified after `-b` parameter +where the bus number is specified after `-b` parameter ## Common problems @@ -62,8 +60,9 @@ The bandwidth available for each device generally decreases as more devices are If too many devices are added, it can cause transmission errors and network unreliability. There are several ways to reduce the problem: -* Dividing the devices into groups, each with approximately the same number of devices, and connecting each group to one autopilot port -* Increase bus speed limit (usually set to 100kHz for external I2C bus) + +- Dividing the devices into groups, each with approximately the same number of devices, and connecting each group to one autopilot port +- Increase bus speed limit (usually set to 100kHz for external I2C bus) ### Excessive Wiring Capacitance @@ -71,9 +70,10 @@ The electrical capacity of bus wiring increases as more devices/wires are added. The problem can be analyzed using an oscilloscope, where we see that the edges of SDA/SCL signals are no longer sharp. There are several ways to reduce the problem: -* Dividing the devices into groups, each with approximately the same number of devices, and connecting each group to one autopilot port -* Using the shorter and higher quality I2C cables, see the [cable wiring page](../assembly/cable_wiring.md#i2c-cables) for details -* Separating the devices with a weak open-drain driver to smaller buses with lower capacitance by using [I2C Bus Accelerators](#i2c-bus-accelerators) + +- Dividing the devices into groups, each with approximately the same number of devices, and connecting each group to one autopilot port +- Using the shorter and higher quality I2C cables, see the [cable wiring page](../assembly/cable_wiring.md#i2c-cables) for details +- Separating the devices with a weak open-drain driver to smaller buses with lower capacitance by using [I2C Bus Accelerators](#i2c-bus-accelerators) ## I2C Bus Accelerators @@ -81,6 +81,7 @@ I2C bus accelerators are separate circuits that can be used to support longer wi They work by physically dividing an I2C network into 2 parts and using their own transistors to amplify I2C signals. Available accelerators include: + - [Thunderfly TFI2CEXT01](https://docs.thunderfly.cz/avionics/TFI2CEXT01/): ![I2C bus extender](../../assets/peripherals/i2c_tfi2cext/tfi2cext01a_bottom.jpg) - This has Dronecode connectors and is hence very easy to add to a Pixhawk I2C setup. @@ -89,7 +90,7 @@ Available accelerators include: ### I2C Level Converter function Some I2C devices have 5V on the data lines, while the Pixhawk connector standard port expects these lines to be 3.3 V. -You can use the TFI2CEXT01 as a level converter to connect 5V devices to a Pixhawk I2C port. This feature is possible because the SCL and SDA lines of TFI2CEXT01 are 5V tolerant. +You can use the TFI2CEXT01 as a level converter to connect 5V devices to a Pixhawk I2C port. This feature is possible because the SCL and SDA lines of TFI2CEXT01 are 5V tolerant. ## I2C Address Translators @@ -112,6 +113,6 @@ Software development for I2C devices is described in [I2C Bus (Development Overv ## Further Information -* [I2C](https://en.wikipedia.org/wiki/I%C2%B2C) (Wikipedia) -* [I2C Comparative Overview](https://learn.sparkfun.com/tutorials/i2c) (learn.sparkfun.com) -* [Driver Framework](../middleware/drivers.md) +- [I2C](https://en.wikipedia.org/wiki/I%C2%B2C) (Wikipedia) +- [I2C Comparative Overview](https://learn.sparkfun.com/tutorials/i2c) (learn.sparkfun.com) +- [Driver Framework](../middleware/drivers.md) diff --git a/docs/en/sensor_bus/translator_tfi2cadt.md b/docs/en/sensor_bus/translator_tfi2cadt.md index 0f00b6a610..0c12106d78 100644 --- a/docs/en/sensor_bus/translator_tfi2cadt.md +++ b/docs/en/sensor_bus/translator_tfi2cadt.md @@ -28,7 +28,7 @@ If you need your own value for address translation, changing the configuration r ## Example of Use The tachometer sensor [TFRPM01](../sensor/thunderfly_tachometer.md) can be set to two different addresses using a solder jumper. -If the autopilot has three buses, only 6 sensors can be connected and no bus remains free (2 available addresses * 3 I2C ports). +If the autopilot has three buses, only 6 sensors can be connected and no bus remains free (2 available addresses \* 3 I2C ports). In some multicopters or VTOL solutions, there is a need to measure the RPM of 8 or more elements. The [TFI2CADT01](https://www.tindie.com/products/26353/) is highly recommended in this case. @@ -39,7 +39,6 @@ By adding another TFI2CADT01, 4 more devices can be connected to the same bus. [![Connection of multiple sensors](https://mermaid.ink/img/pako:eNptkd9rwjAQx_-VcE8dtJB2ukEfBLEWfJCJy8CHvgRznQH7gzSBDfF_33VZB2oCyf3I576XcBc4dgohh08j-xMTRdUyWuX2I6LNErY7zJh0tuv1ubNP_7csSRZsudlHS22GHlGxAduhM3fEfrdNI1GS4emK8a85fwSyGyC9A0S5yVbrg_DZKfLtCxH9JsjhaU7VvI7pfK3_NCg_NXmO3pwl5uYt9D0yAXoWoFNP4yM9H-kspJ0FtF8CdObpURtiaNA0UisaymWsrsCesMEKcnIV1tKdbQVVeyXU9UpaXCttOwO5NQ5jGKf1_t0ep9gzhZY04sYnrz9BI4mU)](https://mermaid-js.github.io/mermaid-live-editor/edit#pako:eNptkd9rwjAQx_-VcE8dtJB2ukEfBLEWfJCJy8CHvgRznQH7gzSBDfF_33VZB2oCyf3I576XcBc4dgohh08j-xMTRdUyWuX2I6LNErY7zJh0tuv1ubNP_7csSRZsudlHS22GHlGxAduhM3fEfrdNI1GS4emK8a85fwSyGyC9A0S5yVbrg_DZKfLtCxH9JsjhaU7VvI7pfK3_NCg_NXmO3pwl5uYt9D0yAXoWoFNP4yM9H-kspJ0FtF8CdObpURtiaNA0UisaymWsrsCesMEKcnIV1tKdbQVVeyXU9UpaXCttOwO5NQ5jGKf1_t0ep9gzhZY04sYnrz9BI4mU) - - ::: info TFI2CADT01 does not contain any I2C buffer or accelerator. As it adds additional capacitance on the bus, we advise combining it with some bus booster, e.g. [TFI2CEXT01](https://docs.thunderfly.cz/avionics/TFI2CEXT01/). @@ -62,4 +60,4 @@ As it adds additional capacitance on the bus, we advise combining it with some b ### Other Resources -* Datasheet of [LTC4317](https://www.analog.com/media/en/technical-documentation/data-sheets/4317fa.pdf) +- Datasheet of [LTC4317](https://www.analog.com/media/en/technical-documentation/data-sheets/4317fa.pdf) diff --git a/docs/en/sim_gazebo_gz/index.md b/docs/en/sim_gazebo_gz/index.md index 6f5dead778..8f4ed2fee8 100644 --- a/docs/en/sim_gazebo_gz/index.md +++ b/docs/en/sim_gazebo_gz/index.md @@ -68,7 +68,6 @@ Note that all gazebo make targets have the prefix `gz_`. | [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) | `make px4_sitl gz_rover_ackermann` | 51000 | | [Mecanum Rover](../sim_gazebo_gz/vehicles.md#mecanum-rover) | `make px4_sitl gz_rover_mecanum` | 52000 | - All [vehicle models](../sim_gazebo_gz/vehicles.md) (and [worlds](#specify-world)) are included as a submodule from the [Gazebo Models Repository](../sim_gazebo_gz/gazebo_models.md) repository. The commands above launch a single vehicle with the full UI. @@ -136,6 +135,7 @@ HEADLESS=1 make px4_sitl gz_x500 ``` ### Set Custom Takeoff Location + The takeoff location in Gazebo Classic can be set using environment variables. The variables to set are: PX4_HOME_LAT, PX4_HOME_LON, and PX4_HOME_ALT. @@ -254,13 +254,11 @@ where `ARGS` is a list of environment variables including: - `PX4_GZ_MODEL_NAME`: Sets the name of an _existing_ model in the gazebo simulation. If provided, the startup script tries to bind a new PX4 instance to the Gazebo resource matching exactly that name. - - The setting is mutually exclusive with `PX4_SIM_MODEL`. - `PX4_SIM_MODEL`: Sets the name of a new Gazebo model to be spawned in the simulator. If provided, the startup script looks for a model in the Gazebo resource path that matches the given variable, spawns it and binds a new PX4 instance to it. - - The setting is mutually exclusive with `PX4_GZ_MODEL_NAME`. ::: info @@ -270,7 +268,6 @@ where `ARGS` is a list of environment variables including: - `PX4_GZ_MODEL_POSE`: Sets the spawning position and orientation of the model when `PX4_SIM_MODEL` is adopted. If provided, the startup script spawns the model at a pose following the syntax `"x,y,z,roll,pitch,yaw"`, where the positions are given in metres and the angles are in radians. - - If omitted, the zero pose `[0,0,0,0,0,0]` is used. - If less then 6 values are provided, the missing ones are fixed to zero. - This can only be used with `PX4_SIM_MODEL` (not `PX4_GZ_MODEL_NAME`). @@ -278,7 +275,6 @@ where `ARGS` is a list of environment variables including: - `PX4_GZ_WORLD`: Sets the Gazebo world file for a new simulation. If it is not given, then [default](https://github.com/PX4/PX4-gazebo-models/blob/main/worlds/default.sdf) is used. - - This variable is ignored if an existing simulation is already running. - This value should be [specified for the selected airframe](#adding-new-worlds-and-models) but may be overridden using this argument. - If the [moving platform world](../sim_gazebo_gz/worlds.md#moving-platform) is selected using `PX4_GZ_WORLD=moving_platform` (or any world using the moving platform plugin), the platform can be configured using environment variables: @@ -287,7 +283,6 @@ where `ARGS` is a list of environment variables including: - `PX4_SIMULATOR=GZ`: Sets the simulator, which for Gazebo must be `gz`. - - This value should be [set for the selected airframe](#adding-new-worlds-and-models), in which case it does not need to be set as an argument. - `PX4_GZ_STANDALONE`: @@ -375,7 +370,6 @@ To add a new model: ``` 1. Add CMake Target for the [airframe](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt). - - If you plan to use "regular" mode, add your model SDF to `Tools/simulation/gz/models/`. - If you plan to use _standalone_ mode, add your model SDF to `~/.simulation-gazebo/models/` @@ -387,7 +381,6 @@ To add a new world: 1. Add your world to the list of worlds found in the [`CMakeLists.txt` here](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/gz_bridge/CMakeLists.txt). This is required in order to allow `CMake` to generate correct targets. - - If you plan to use "normal" mode, add your world sdf to `Tools/simulation/gz/worlds/`. - If you plan to use _standalone_ mode, add your world SDF to `~/.simulation-gazebo/worlds/` diff --git a/docs/en/sim_gazebo_gz/worlds.md b/docs/en/sim_gazebo_gz/worlds.md index 5f72e222b2..8d10d50754 100644 --- a/docs/en/sim_gazebo_gz/worlds.md +++ b/docs/en/sim_gazebo_gz/worlds.md @@ -85,8 +85,8 @@ PX4_GZ_MODEL_POSE=0,0,2.2 PX4_GZ_WORLD=moving_platform make px4_sitl gz_standard The plugin can be configured with the following environment variables: - - `PX4_GZ_PLATFORM_VEL`: Platform speed (m/s). - - `PX4_GZ_PLATFORM_HEADING_DEG`: Platform heading and direction of velocity (degrees). 0 = east, positive direction is counterclockwise. +- `PX4_GZ_PLATFORM_VEL`: Platform speed (m/s). +- `PX4_GZ_PLATFORM_HEADING_DEG`: Platform heading and direction of velocity (degrees). 0 = east, positive direction is counterclockwise. [PX4-gazebo-models/main/worlds/moving_platform.sdf](https://github.com/PX4/PX4-gazebo-models/blob/main/worlds/moving_platform.sdf) diff --git a/docs/en/simulation/community_supported_simulators.md b/docs/en/simulation/community_supported_simulators.md index 6e201601c2..a7bbda97c0 100644 --- a/docs/en/simulation/community_supported_simulators.md +++ b/docs/en/simulation/community_supported_simulators.md @@ -12,10 +12,10 @@ See [Toolchain Installation](../dev_setup/dev_env.md) for information about the The tools have variable levels of support from their communities (some are well supported and others are not). Questions about these tools should be raised on the [discussion forums](../contribute/support.md#forums-and-chat) -| Simulator | Description | -| --------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [Simulation-In-Hardware](../sim_sih/index.md) (SIH) |

A simulator implemented in C++ as a PX4 module directly in the Firmware [code](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/simulator_sih). It can be ran in SITL directly on the computer or as an alternative to HITL offering a hard real-time simulation directly on the hardware autopilot.

Supported Vehicles: Quad, Hexa, Plane, Tailsitter, Standard VTOL, Ackermann Rover

| -| [FlightGear](../sim_flightgear/index.md) |

A simulator that provides physically and visually realistic simulations. In particular it can simulate many weather conditions, including thunderstorms, snow, rain and hail, and can also simulate thermals and different types of atmospheric flows. [Multi-vehicle simulation](../sim_flightgear/multi_vehicle.md) is also supported.

Supported Vehicles: Plane, Autogyro, Rover

| -| [JMAVSim](../sim_jmavsim/index.md) |

A simple multirotor/quad simulator. This was previously part of the PX4 development toolchain but was removed in favour of [Gazebo](../sim_gazebo_gz/index.md).

Supported Vehicles: Quad

| -| [JSBSim](../sim_jsbsim/index.md) |

A simulator that provides advanced flight dynamics models. This can be used to model realistic flight dynamics based on wind tunnel data.

Supported Vehicles: Plane, Quad, Hex

| -| [AirSim](../sim_airsim/index.md) |

A cross platform simulator that provides physically and visually realistic simulations. This simulator is resource intensive, and requires a significantly more powerful computer than the other simulators described here.

Supported Vehicles: Iris (MultiRotor model and a configuration for PX4 QuadRotor in the X configuration).

| +| Simulator | Description | +| --------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| [Simulation-In-Hardware](../sim_sih/index.md) (SIH) |

A simulator implemented in C++ as a PX4 module directly in the Firmware [code](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/simulator_sih). It can be ran in SITL directly on the computer or as an alternative to HITL offering a hard real-time simulation directly on the hardware autopilot.

Supported Vehicles: Quad, Hexa, Plane, Tailsitter, Standard VTOL, Ackermann Rover

| +| [FlightGear](../sim_flightgear/index.md) |

A simulator that provides physically and visually realistic simulations. In particular it can simulate many weather conditions, including thunderstorms, snow, rain and hail, and can also simulate thermals and different types of atmospheric flows. [Multi-vehicle simulation](../sim_flightgear/multi_vehicle.md) is also supported.

Supported Vehicles: Plane, Autogyro, Rover

| +| [JMAVSim](../sim_jmavsim/index.md) |

A simple multirotor/quad simulator. This was previously part of the PX4 development toolchain but was removed in favour of [Gazebo](../sim_gazebo_gz/index.md).

Supported Vehicles: Quad

| +| [JSBSim](../sim_jsbsim/index.md) |

A simulator that provides advanced flight dynamics models. This can be used to model realistic flight dynamics based on wind tunnel data.

Supported Vehicles: Plane, Quad, Hex

| +| [AirSim](../sim_airsim/index.md) |

A cross platform simulator that provides physically and visually realistic simulations. This simulator is resource intensive, and requires a significantly more powerful computer than the other simulators described here.

Supported Vehicles: Iris (MultiRotor model and a configuration for PX4 QuadRotor in the X configuration).

| diff --git a/docs/en/smart_batteries/index.md b/docs/en/smart_batteries/index.md index 6ddc032842..805ad60619 100644 --- a/docs/en/smart_batteries/index.md +++ b/docs/en/smart_batteries/index.md @@ -5,7 +5,8 @@ This allows for more more reliable flight planning notification of failure condi The information may include some of: remaining charge, time-to-empty (estimated), cell voltages (rated max/min, current voltage, etc.), temperature, currents, fault information, battery vendor, chemistry, etc. PX4 supports (at least) following smart batteries: -* [Rotoye Batmon](../smart_batteries/rotoye_batmon.md) + +- [Rotoye Batmon](../smart_batteries/rotoye_batmon.md) ### Further Information diff --git a/docs/en/smart_batteries/rotoye_batmon.md b/docs/en/smart_batteries/rotoye_batmon.md index 64120b5da8..a50eba58e2 100644 --- a/docs/en/smart_batteries/rotoye_batmon.md +++ b/docs/en/smart_batteries/rotoye_batmon.md @@ -7,12 +7,10 @@ It can be purchased as a standalone unit or as part of a factory-assembled smart ![Pre-assembled Rotoye smart battery](../../assets/hardware/smart_batteries/rotoye_batmon/smart-battery-rotoye-pack.jpg) - ## Where to Buy [Rotoye Store](https://rotoye.com/batmon/): Batmon kits, custom smart-batteries, and accessories - ## Wiring/Connections The Rotoye Batmon system uses an XT-90 battery connector with I2C pins, and an opti-isolator board to transmit data. @@ -21,7 +19,6 @@ The Rotoye Batmon system uses an XT-90 battery connector with I2C pins, and an o More details can be found [here](https://github.com/rotoye/batmon_reader) - ## Software Setup ### Build PX4 Firmware @@ -31,7 +28,7 @@ More details can be found [here](https://github.com/rotoye/batmon_reader) git clone https://github.com/rotoye/PX4-Autopilot.git cd PX4-Autopilot ``` -1. Checkout the *batmon_4.03* branch +1. Checkout the _batmon_4.03_ branch ```sh git fetch origin batmon_4.03 git checkout batmon_4.03 @@ -40,16 +37,17 @@ More details can be found [here](https://github.com/rotoye/batmon_reader) ### Configure Parameters -In *QGroundControl*: +In _QGroundControl_: + 1. Set the following [parameters](../advanced_config/parameters.md): - `BATx_SOURCE` to `External`, - - `SENS_EN_BAT` to `true`, + - `SENS_EN_BAT` to `true`, - `BAT_SMBUS_MODEL` to `3:Rotoye` 1. Open the [MAVLink Console](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/analyze_view/mavlink_console.html) 1. Start the [batt_smbus driver](../modules/modules_driver.md) in the console. For example, to run two BatMons on the same bus: - ```sh - batt_smbus start -X -b 1 -a 11 # External bus 1, address 0x0b + ```sh + batt_smbus start -X -b 1 -a 11 # External bus 1, address 0x0b batt_smbus start -X -b 1 -a 12 # External bus 1, address 0x0c ``` diff --git a/docs/en/test_and_ci/continous_integration.md b/docs/en/test_and_ci/continous_integration.md index a8409d2400..86033febbc 100644 --- a/docs/en/test_and_ci/continous_integration.md +++ b/docs/en/test_and_ci/continous_integration.md @@ -16,14 +16,14 @@ Jobs are organized in tiers, where each tier depends on the previous one complet #### Tier Structure -| Tier | Job | PR | Push / Dispatch | Description | -| ---- | -------------- | ----------------- | --------------- | ------------------------------------------------------------- | -| T1 | Detect Changes | Yes | — | Checks if source code files changed (triggers metadata regen) | -| T2 | PR Metadata | Yes (conditional) | — | Builds PX4 SITL and regenerates all auto-generated docs | -| T2 | Metadata Sync | — | Yes | Builds PX4 SITL, regenerates metadata, auto-commits | -| T2 | Link Check | Yes | — | Checks for broken links in changed files, posts PR comment | +| Tier | Job | PR | Push / Dispatch | Description | +| ---- | -------------- | ---------------------------- | --------------- | ------------------------------------------------------------- | +| T1 | Detect Changes | Yes | — | Checks if source code files changed (triggers metadata regen) | +| T2 | PR Metadata | Yes (conditional) | — | Builds PX4 SITL and regenerates all auto-generated docs | +| T2 | Metadata Sync | — | Yes | Builds PX4 SITL, regenerates metadata, auto-commits | +| T2 | Link Check | Yes | — | Checks for broken links in changed files, posts PR comment | | T3 | Build Site | Yes (if docs/source changed) | Yes (after T2) | Builds the VitePress documentation site | -| T4 | Deploy | — | Yes | Deploys to AWS S3 | +| T4 | Deploy | — | Yes | Deploys to AWS S3 | #### Pull Request Flow @@ -63,11 +63,11 @@ PR Event DONE ``` -| Job | Duration | Description | -| ---------------------- | -------- | ------------------------------------------------------------------------------------------- | -| **T1: Detect Changes** | ~10s | Determines if metadata regeneration is needed | -| **T2: PR Metadata** | ~10-15m | Rebuilds PX4 SITL and regenerates all metadata (only if source files changed) | -| **T2: Link Check** | ~30s | Checks for broken links in changed markdown files and posts a sticky comment to the PR (skipped on fork PRs) | +| Job | Duration | Description | +| ---------------------- | -------- | --------------------------------------------------------------------------------------------------------------------------------------- | +| **T1: Detect Changes** | ~10s | Determines if metadata regeneration is needed | +| **T2: PR Metadata** | ~10-15m | Rebuilds PX4 SITL and regenerates all metadata (only if source files changed) | +| **T2: Link Check** | ~30s | Checks for broken links in changed markdown files and posts a sticky comment to the PR (skipped on fork PRs) | | **T3: Build Site** | ~7-10m | Builds the VitePress site to verify there are no build errors. Skipped when only the workflow YAML changed (no docs or source changes). | #### Push / Dispatch Flow (main/release branches) diff --git a/docs/en/test_and_ci/index.md b/docs/en/test_and_ci/index.md index a906ed8f46..dbb1aa7c11 100644 --- a/docs/en/test_and_ci/index.md +++ b/docs/en/test_and_ci/index.md @@ -9,8 +9,8 @@ Test topics include: - [Unit Tests](../test_and_ci/unit_tests.md) - [Continuous Integration (CI)](../test_and_ci/continous_integration.md) - [Integration Testing](../test_and_ci/integration_testing.md) - - [MAVSDK Integration Testing](../test_and_ci/integration_testing_mavsdk.md) - - [PX4 ROS2 Interface Library Integration Testing](../test_and_ci/integration_testing_px4_ros2_interface.md) - - [ROS 1 Integration Testing](../test_and_ci/integration_testing_ros1_mavros.md) (Deprecated) + - [MAVSDK Integration Testing](../test_and_ci/integration_testing_mavsdk.md) + - [PX4 ROS2 Interface Library Integration Testing](../test_and_ci/integration_testing_px4_ros2_interface.md) + - [ROS 1 Integration Testing](../test_and_ci/integration_testing_ros1_mavros.md) (Deprecated) - [Docker](../test_and_ci/docker.md) - [Maintenance](../test_and_ci/maintenance.md) diff --git a/docs/en/test_cards/mc_04_failsafe_testing.md b/docs/en/test_cards/mc_04_failsafe_testing.md index 4042e094d2..3947be6b2e 100644 --- a/docs/en/test_cards/mc_04_failsafe_testing.md +++ b/docs/en/test_cards/mc_04_failsafe_testing.md @@ -9,10 +9,10 @@ Test RC loss, data link loss, and low battery failsafes. - Verify RC Loss action is Return to Land - Verify Data Link Loss action is Return to Land and the timeout is 10 seconds - Verify Battery failsafe - - Action is Return to Land - - Battery Warn Level is 25% - - Battery Failsafe Level is 20% - - Battery Emergency Level is 15% + - Action is Return to Land + - Battery Warn Level is 25% + - Battery Failsafe Level is 20% + - Battery Emergency Level is 15% ## Flight Tests @@ -28,7 +28,6 @@ Test RC loss, data link loss, and low battery failsafes.     ❏ Disconnect telemetry, vehicle should return to home position after 10 seconds, wait for the descent and reconnect the telemetry radio - ❏ Battery Failsafe     ❏ Confirm the warning message is received in QGC diff --git a/docs/en/uart/user_configurable_serial_driver.md b/docs/en/uart/user_configurable_serial_driver.md index 9fbe168a66..3809ad25a6 100644 --- a/docs/en/uart/user_configurable_serial_driver.md +++ b/docs/en/uart/user_configurable_serial_driver.md @@ -24,7 +24,6 @@ where, To make driver configurable: 1. Create a YAML module configuration file: - - Add a new file in the driver's source directory named **module.yaml** - Insert the following text and adjust as needed: diff --git a/docs/public/config/failsafe/index.js b/docs/public/config/failsafe/index.js index 58904fd091..1d4ce8cd21 100644 --- a/docs/public/config/failsafe/index.js +++ b/docs/public/config/failsafe/index.js @@ -1 +1 @@ -var Module=typeof Module!="undefined"?Module:{};var ENVIRONMENT_IS_WEB=typeof window=="object";var ENVIRONMENT_IS_WORKER=typeof WorkerGlobalScope!="undefined";var ENVIRONMENT_IS_NODE=typeof process=="object"&&process.versions?.node&&process.type!="renderer";var arguments_=[];var thisProgram="./this.program";var quit_=(status,toThrow)=>{throw toThrow};var _scriptName=typeof document!="undefined"?document.currentScript?.src:undefined;if(typeof __filename!="undefined"){_scriptName=__filename}else if(ENVIRONMENT_IS_WORKER){_scriptName=self.location.href}var scriptDirectory="";function locateFile(path){if(Module["locateFile"]){return Module["locateFile"](path,scriptDirectory)}return scriptDirectory+path}var readAsync,readBinary;if(ENVIRONMENT_IS_NODE){var fs=require("fs");scriptDirectory=__dirname+"/";readBinary=filename=>{filename=isFileURI(filename)?new URL(filename):filename;var ret=fs.readFileSync(filename);return ret};readAsync=async(filename,binary=true)=>{filename=isFileURI(filename)?new URL(filename):filename;var ret=fs.readFileSync(filename,binary?undefined:"utf8");return ret};if(process.argv.length>1){thisProgram=process.argv[1].replace(/\\/g,"/")}arguments_=process.argv.slice(2);if(typeof module!="undefined"){module["exports"]=Module}quit_=(status,toThrow)=>{process.exitCode=status;throw toThrow}}else if(ENVIRONMENT_IS_WEB||ENVIRONMENT_IS_WORKER){try{scriptDirectory=new URL(".",_scriptName).href}catch{}{if(ENVIRONMENT_IS_WORKER){readBinary=url=>{var xhr=new XMLHttpRequest;xhr.open("GET",url,false);xhr.responseType="arraybuffer";xhr.send(null);return new Uint8Array(xhr.response)}}readAsync=async url=>{if(isFileURI(url)){return new Promise((resolve,reject)=>{var xhr=new XMLHttpRequest;xhr.open("GET",url,true);xhr.responseType="arraybuffer";xhr.onload=()=>{if(xhr.status==200||xhr.status==0&&xhr.response){resolve(xhr.response);return}reject(xhr.status)};xhr.onerror=reject;xhr.send(null)})}var response=await fetch(url,{credentials:"same-origin"});if(response.ok){return response.arrayBuffer()}throw new Error(response.status+" : "+response.url)}}}else{}var out=console.log.bind(console);var err=console.error.bind(console);var wasmBinary;var ABORT=false;var isFileURI=filename=>filename.startsWith("file://");var wasmMemory;var HEAP8,HEAPU8,HEAP16,HEAPU16,HEAP32,HEAPU32,HEAPF32,HEAPF64;var HEAP64,HEAPU64;var runtimeInitialized=false;function updateMemoryViews(){var b=wasmMemory.buffer;HEAP8=new Int8Array(b);HEAP16=new Int16Array(b);HEAPU8=new Uint8Array(b);HEAPU16=new Uint16Array(b);HEAP32=new Int32Array(b);HEAPU32=new Uint32Array(b);HEAPF32=new Float32Array(b);HEAPF64=new Float64Array(b);HEAP64=new BigInt64Array(b);HEAPU64=new BigUint64Array(b)}function preRun(){if(Module["preRun"]){if(typeof Module["preRun"]=="function")Module["preRun"]=[Module["preRun"]];while(Module["preRun"].length){addOnPreRun(Module["preRun"].shift())}}callRuntimeCallbacks(onPreRuns)}function initRuntime(){runtimeInitialized=true;wasmExports["v"]()}function postRun(){if(Module["postRun"]){if(typeof Module["postRun"]=="function")Module["postRun"]=[Module["postRun"]];while(Module["postRun"].length){addOnPostRun(Module["postRun"].shift())}}callRuntimeCallbacks(onPostRuns)}var runDependencies=0;var dependenciesFulfilled=null;function addRunDependency(id){runDependencies++;Module["monitorRunDependencies"]?.(runDependencies)}function removeRunDependency(id){runDependencies--;Module["monitorRunDependencies"]?.(runDependencies);if(runDependencies==0){if(dependenciesFulfilled){var callback=dependenciesFulfilled;dependenciesFulfilled=null;callback()}}}function abort(what){Module["onAbort"]?.(what);what="Aborted("+what+")";err(what);ABORT=true;what+=". Build with -sASSERTIONS for more info.";var e=new WebAssembly.RuntimeError(what);throw e}var wasmBinaryFile;function findWasmBinary(){return locateFile("index.wasm")}function getBinarySync(file){if(file==wasmBinaryFile&&wasmBinary){return new Uint8Array(wasmBinary)}if(readBinary){return readBinary(file)}throw"both async and sync fetching of the wasm failed"}async function getWasmBinary(binaryFile){if(!wasmBinary){try{var response=await readAsync(binaryFile);return new Uint8Array(response)}catch{}}return getBinarySync(binaryFile)}async function instantiateArrayBuffer(binaryFile,imports){try{var binary=await getWasmBinary(binaryFile);var instance=await WebAssembly.instantiate(binary,imports);return instance}catch(reason){err(`failed to asynchronously prepare wasm: ${reason}`);abort(reason)}}async function instantiateAsync(binary,binaryFile,imports){if(!binary&&typeof WebAssembly.instantiateStreaming=="function"&&!isFileURI(binaryFile)&&!ENVIRONMENT_IS_NODE){try{var response=fetch(binaryFile,{credentials:"same-origin"});var instantiationResult=await WebAssembly.instantiateStreaming(response,imports);return instantiationResult}catch(reason){err(`wasm streaming compile failed: ${reason}`);err("falling back to ArrayBuffer instantiation")}}return instantiateArrayBuffer(binaryFile,imports)}function getWasmImports(){return{a:wasmImports}}async function createWasm(){function receiveInstance(instance,module){wasmExports=instance.exports;wasmMemory=wasmExports["u"];updateMemoryViews();wasmTable=wasmExports["A"];assignWasmExports(wasmExports);removeRunDependency("wasm-instantiate");return wasmExports}addRunDependency("wasm-instantiate");function receiveInstantiationResult(result){return receiveInstance(result["instance"])}var info=getWasmImports();if(Module["instantiateWasm"]){return new Promise((resolve,reject)=>{Module["instantiateWasm"](info,(mod,inst)=>{resolve(receiveInstance(mod,inst))})})}wasmBinaryFile??=findWasmBinary();var result=await instantiateAsync(wasmBinary,wasmBinaryFile,info);var exports=receiveInstantiationResult(result);return exports}class ExitStatus{name="ExitStatus";constructor(status){this.message=`Program terminated with exit(${status})`;this.status=status}}var callRuntimeCallbacks=callbacks=>{while(callbacks.length>0){callbacks.shift()(Module)}};var onPostRuns=[];var addOnPostRun=cb=>onPostRuns.push(cb);var onPreRuns=[];var addOnPreRun=cb=>onPreRuns.push(cb);var noExitRuntime=true;class ExceptionInfo{constructor(excPtr){this.excPtr=excPtr;this.ptr=excPtr-24}set_type(type){HEAPU32[this.ptr+4>>2]=type}get_type(){return HEAPU32[this.ptr+4>>2]}set_destructor(destructor){HEAPU32[this.ptr+8>>2]=destructor}get_destructor(){return HEAPU32[this.ptr+8>>2]}set_caught(caught){caught=caught?1:0;HEAP8[this.ptr+12]=caught}get_caught(){return HEAP8[this.ptr+12]!=0}set_rethrown(rethrown){rethrown=rethrown?1:0;HEAP8[this.ptr+13]=rethrown}get_rethrown(){return HEAP8[this.ptr+13]!=0}init(type,destructor){this.set_adjusted_ptr(0);this.set_type(type);this.set_destructor(destructor)}set_adjusted_ptr(adjustedPtr){HEAPU32[this.ptr+16>>2]=adjustedPtr}get_adjusted_ptr(){return HEAPU32[this.ptr+16>>2]}}var exceptionLast=0;var uncaughtExceptionCount=0;var ___cxa_throw=(ptr,type,destructor)=>{var info=new ExceptionInfo(ptr);info.init(type,destructor);exceptionLast=ptr;uncaughtExceptionCount++;throw exceptionLast};var __abort_js=()=>abort("");var AsciiToString=ptr=>{var str="";while(1){var ch=HEAPU8[ptr++];if(!ch)return str;str+=String.fromCharCode(ch)}};var awaitingDependencies={};var registeredTypes={};var typeDependencies={};var BindingError=class BindingError extends Error{constructor(message){super(message);this.name="BindingError"}};var throwBindingError=message=>{throw new BindingError(message)};function sharedRegisterType(rawType,registeredInstance,options={}){var name=registeredInstance.name;if(!rawType){throwBindingError(`type "${name}" must have a positive integer typeid pointer`)}if(registeredTypes.hasOwnProperty(rawType)){if(options.ignoreDuplicateRegistrations){return}else{throwBindingError(`Cannot register type '${name}' twice`)}}registeredTypes[rawType]=registeredInstance;delete typeDependencies[rawType];if(awaitingDependencies.hasOwnProperty(rawType)){var callbacks=awaitingDependencies[rawType];delete awaitingDependencies[rawType];callbacks.forEach(cb=>cb())}}function registerType(rawType,registeredInstance,options={}){return sharedRegisterType(rawType,registeredInstance,options)}var integerReadValueFromPointer=(name,width,signed)=>{switch(width){case 1:return signed?pointer=>HEAP8[pointer]:pointer=>HEAPU8[pointer];case 2:return signed?pointer=>HEAP16[pointer>>1]:pointer=>HEAPU16[pointer>>1];case 4:return signed?pointer=>HEAP32[pointer>>2]:pointer=>HEAPU32[pointer>>2];case 8:return signed?pointer=>HEAP64[pointer>>3]:pointer=>HEAPU64[pointer>>3];default:throw new TypeError(`invalid integer width (${width}): ${name}`)}};var __embind_register_bigint=(primitiveType,name,size,minRange,maxRange)=>{name=AsciiToString(name);const isUnsignedType=minRange===0n;let fromWireType=value=>value;if(isUnsignedType){const bitSize=size*8;fromWireType=value=>BigInt.asUintN(bitSize,value);maxRange=fromWireType(maxRange)}registerType(primitiveType,{name,fromWireType,toWireType:(destructors,value)=>{if(typeof value=="number"){value=BigInt(value)}return value},argPackAdvance:GenericWireTypeSize,readValueFromPointer:integerReadValueFromPointer(name,size,!isUnsignedType),destructorFunction:null})};var GenericWireTypeSize=8;var __embind_register_bool=(rawType,name,trueValue,falseValue)=>{name=AsciiToString(name);registerType(rawType,{name,fromWireType:function(wt){return!!wt},toWireType:function(destructors,o){return o?trueValue:falseValue},argPackAdvance:GenericWireTypeSize,readValueFromPointer:function(pointer){return this["fromWireType"](HEAPU8[pointer])},destructorFunction:null})};var shallowCopyInternalPointer=o=>({count:o.count,deleteScheduled:o.deleteScheduled,preservePointerOnDelete:o.preservePointerOnDelete,ptr:o.ptr,ptrType:o.ptrType,smartPtr:o.smartPtr,smartPtrType:o.smartPtrType});var throwInstanceAlreadyDeleted=obj=>{function getInstanceTypeName(handle){return handle.$$.ptrType.registeredClass.name}throwBindingError(getInstanceTypeName(obj)+" instance already deleted")};var finalizationRegistry=false;var detachFinalizer=handle=>{};var runDestructor=$$=>{if($$.smartPtr){$$.smartPtrType.rawDestructor($$.smartPtr)}else{$$.ptrType.registeredClass.rawDestructor($$.ptr)}};var releaseClassHandle=$$=>{$$.count.value-=1;var toDelete=0===$$.count.value;if(toDelete){runDestructor($$)}};var attachFinalizer=handle=>{if("undefined"===typeof FinalizationRegistry){attachFinalizer=handle=>handle;return handle}finalizationRegistry=new FinalizationRegistry(info=>{releaseClassHandle(info.$$)});attachFinalizer=handle=>{var $$=handle.$$;var hasSmartPtr=!!$$.smartPtr;if(hasSmartPtr){var info={$$};finalizationRegistry.register(handle,info,handle)}return handle};detachFinalizer=handle=>finalizationRegistry.unregister(handle);return attachFinalizer(handle)};var deletionQueue=[];var flushPendingDeletes=()=>{while(deletionQueue.length){var obj=deletionQueue.pop();obj.$$.deleteScheduled=false;obj["delete"]()}};var delayFunction;var init_ClassHandle=()=>{let proto=ClassHandle.prototype;Object.assign(proto,{isAliasOf(other){if(!(this instanceof ClassHandle)){return false}if(!(other instanceof ClassHandle)){return false}var leftClass=this.$$.ptrType.registeredClass;var left=this.$$.ptr;other.$$=other.$$;var rightClass=other.$$.ptrType.registeredClass;var right=other.$$.ptr;while(leftClass.baseClass){left=leftClass.upcast(left);leftClass=leftClass.baseClass}while(rightClass.baseClass){right=rightClass.upcast(right);rightClass=rightClass.baseClass}return leftClass===rightClass&&left===right},clone(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.preservePointerOnDelete){this.$$.count.value+=1;return this}else{var clone=attachFinalizer(Object.create(Object.getPrototypeOf(this),{$$:{value:shallowCopyInternalPointer(this.$$)}}));clone.$$.count.value+=1;clone.$$.deleteScheduled=false;return clone}},delete(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.deleteScheduled&&!this.$$.preservePointerOnDelete){throwBindingError("Object already scheduled for deletion")}detachFinalizer(this);releaseClassHandle(this.$$);if(!this.$$.preservePointerOnDelete){this.$$.smartPtr=undefined;this.$$.ptr=undefined}},isDeleted(){return!this.$$.ptr},deleteLater(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.deleteScheduled&&!this.$$.preservePointerOnDelete){throwBindingError("Object already scheduled for deletion")}deletionQueue.push(this);if(deletionQueue.length===1&&delayFunction){delayFunction(flushPendingDeletes)}this.$$.deleteScheduled=true;return this}});const symbolDispose=Symbol.dispose;if(symbolDispose){proto[symbolDispose]=proto["delete"]}};function ClassHandle(){}var createNamedFunction=(name,func)=>Object.defineProperty(func,"name",{value:name});var registeredPointers={};var ensureOverloadTable=(proto,methodName,humanName)=>{if(undefined===proto[methodName].overloadTable){var prevFunc=proto[methodName];proto[methodName]=function(...args){if(!proto[methodName].overloadTable.hasOwnProperty(args.length)){throwBindingError(`Function '${humanName}' called with an invalid number of arguments (${args.length}) - expects one of (${proto[methodName].overloadTable})!`)}return proto[methodName].overloadTable[args.length].apply(this,args)};proto[methodName].overloadTable=[];proto[methodName].overloadTable[prevFunc.argCount]=prevFunc}};var exposePublicSymbol=(name,value,numArguments)=>{if(Module.hasOwnProperty(name)){if(undefined===numArguments||undefined!==Module[name].overloadTable&&undefined!==Module[name].overloadTable[numArguments]){throwBindingError(`Cannot register public name '${name}' twice`)}ensureOverloadTable(Module,name,name);if(Module[name].overloadTable.hasOwnProperty(numArguments)){throwBindingError(`Cannot register multiple overloads of a function with the same number of arguments (${numArguments})!`)}Module[name].overloadTable[numArguments]=value}else{Module[name]=value;Module[name].argCount=numArguments}};var char_0=48;var char_9=57;var makeLegalFunctionName=name=>{name=name.replace(/[^a-zA-Z0-9_]/g,"$");var f=name.charCodeAt(0);if(f>=char_0&&f<=char_9){return`_${name}`}return name};function RegisteredClass(name,constructor,instancePrototype,rawDestructor,baseClass,getActualType,upcast,downcast){this.name=name;this.constructor=constructor;this.instancePrototype=instancePrototype;this.rawDestructor=rawDestructor;this.baseClass=baseClass;this.getActualType=getActualType;this.upcast=upcast;this.downcast=downcast;this.pureVirtualFunctions=[]}var upcastPointer=(ptr,ptrClass,desiredClass)=>{while(ptrClass!==desiredClass){if(!ptrClass.upcast){throwBindingError(`Expected null or instance of ${desiredClass.name}, got an instance of ${ptrClass.name}`)}ptr=ptrClass.upcast(ptr);ptrClass=ptrClass.baseClass}return ptr};var embindRepr=v=>{if(v===null){return"null"}var t=typeof v;if(t==="object"||t==="array"||t==="function"){return v.toString()}else{return""+v}};function constNoSmartPtrRawPointerToWireType(destructors,handle){if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}return 0}if(!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;var ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);return ptr}function genericPointerToWireType(destructors,handle){var ptr;if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}if(this.isSmartPointer){ptr=this.rawConstructor();if(destructors!==null){destructors.push(this.rawDestructor,ptr)}return ptr}else{return 0}}if(!handle||!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}if(!this.isConst&&handle.$$.ptrType.isConst){throwBindingError(`Cannot convert argument of type ${handle.$$.smartPtrType?handle.$$.smartPtrType.name:handle.$$.ptrType.name} to parameter type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);if(this.isSmartPointer){if(undefined===handle.$$.smartPtr){throwBindingError("Passing raw pointer to smart pointer is illegal")}switch(this.sharingPolicy){case 0:if(handle.$$.smartPtrType===this){ptr=handle.$$.smartPtr}else{throwBindingError(`Cannot convert argument of type ${handle.$$.smartPtrType?handle.$$.smartPtrType.name:handle.$$.ptrType.name} to parameter type ${this.name}`)}break;case 1:ptr=handle.$$.smartPtr;break;case 2:if(handle.$$.smartPtrType===this){ptr=handle.$$.smartPtr}else{var clonedHandle=handle["clone"]();ptr=this.rawShare(ptr,Emval.toHandle(()=>clonedHandle["delete"]()));if(destructors!==null){destructors.push(this.rawDestructor,ptr)}}break;default:throwBindingError("Unsupporting sharing policy")}}return ptr}function nonConstNoSmartPtrRawPointerToWireType(destructors,handle){if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}return 0}if(!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}if(handle.$$.ptrType.isConst){throwBindingError(`Cannot convert argument of type ${handle.$$.ptrType.name} to parameter type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;var ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);return ptr}function readPointer(pointer){return this["fromWireType"](HEAPU32[pointer>>2])}var downcastPointer=(ptr,ptrClass,desiredClass)=>{if(ptrClass===desiredClass){return ptr}if(undefined===desiredClass.baseClass){return null}var rv=downcastPointer(ptr,ptrClass,desiredClass.baseClass);if(rv===null){return null}return desiredClass.downcast(rv)};var registeredInstances={};var getBasestPointer=(class_,ptr)=>{if(ptr===undefined){throwBindingError("ptr should not be undefined")}while(class_.baseClass){ptr=class_.upcast(ptr);class_=class_.baseClass}return ptr};var getInheritedInstance=(class_,ptr)=>{ptr=getBasestPointer(class_,ptr);return registeredInstances[ptr]};var InternalError=class InternalError extends Error{constructor(message){super(message);this.name="InternalError"}};var throwInternalError=message=>{throw new InternalError(message)};var makeClassHandle=(prototype,record)=>{if(!record.ptrType||!record.ptr){throwInternalError("makeClassHandle requires ptr and ptrType")}var hasSmartPtrType=!!record.smartPtrType;var hasSmartPtr=!!record.smartPtr;if(hasSmartPtrType!==hasSmartPtr){throwInternalError("Both smartPtrType and smartPtr must be specified")}record.count={value:1};return attachFinalizer(Object.create(prototype,{$$:{value:record,writable:true}}))};function RegisteredPointer_fromWireType(ptr){var rawPointer=this.getPointee(ptr);if(!rawPointer){this.destructor(ptr);return null}var registeredInstance=getInheritedInstance(this.registeredClass,rawPointer);if(undefined!==registeredInstance){if(0===registeredInstance.$$.count.value){registeredInstance.$$.ptr=rawPointer;registeredInstance.$$.smartPtr=ptr;return registeredInstance["clone"]()}else{var rv=registeredInstance["clone"]();this.destructor(ptr);return rv}}function makeDefaultHandle(){if(this.isSmartPointer){return makeClassHandle(this.registeredClass.instancePrototype,{ptrType:this.pointeeType,ptr:rawPointer,smartPtrType:this,smartPtr:ptr})}else{return makeClassHandle(this.registeredClass.instancePrototype,{ptrType:this,ptr})}}var actualType=this.registeredClass.getActualType(rawPointer);var registeredPointerRecord=registeredPointers[actualType];if(!registeredPointerRecord){return makeDefaultHandle.call(this)}var toType;if(this.isConst){toType=registeredPointerRecord.constPointerType}else{toType=registeredPointerRecord.pointerType}var dp=downcastPointer(rawPointer,this.registeredClass,toType.registeredClass);if(dp===null){return makeDefaultHandle.call(this)}if(this.isSmartPointer){return makeClassHandle(toType.registeredClass.instancePrototype,{ptrType:toType,ptr:dp,smartPtrType:this,smartPtr:ptr})}else{return makeClassHandle(toType.registeredClass.instancePrototype,{ptrType:toType,ptr:dp})}}var init_RegisteredPointer=()=>{Object.assign(RegisteredPointer.prototype,{getPointee(ptr){if(this.rawGetPointee){ptr=this.rawGetPointee(ptr)}return ptr},destructor(ptr){this.rawDestructor?.(ptr)},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,fromWireType:RegisteredPointer_fromWireType})};function RegisteredPointer(name,registeredClass,isReference,isConst,isSmartPointer,pointeeType,sharingPolicy,rawGetPointee,rawConstructor,rawShare,rawDestructor){this.name=name;this.registeredClass=registeredClass;this.isReference=isReference;this.isConst=isConst;this.isSmartPointer=isSmartPointer;this.pointeeType=pointeeType;this.sharingPolicy=sharingPolicy;this.rawGetPointee=rawGetPointee;this.rawConstructor=rawConstructor;this.rawShare=rawShare;this.rawDestructor=rawDestructor;if(!isSmartPointer&®isteredClass.baseClass===undefined){if(isConst){this["toWireType"]=constNoSmartPtrRawPointerToWireType;this.destructorFunction=null}else{this["toWireType"]=nonConstNoSmartPtrRawPointerToWireType;this.destructorFunction=null}}else{this["toWireType"]=genericPointerToWireType}}var replacePublicSymbol=(name,value,numArguments)=>{if(!Module.hasOwnProperty(name)){throwInternalError("Replacing nonexistent public symbol")}if(undefined!==Module[name].overloadTable&&undefined!==numArguments){Module[name].overloadTable[numArguments]=value}else{Module[name]=value;Module[name].argCount=numArguments}};var wasmTableMirror=[];var wasmTable;var getWasmTableEntry=funcPtr=>{var func=wasmTableMirror[funcPtr];if(!func){wasmTableMirror[funcPtr]=func=wasmTable.get(funcPtr)}return func};var embind__requireFunction=(signature,rawFunction,isAsync=false)=>{signature=AsciiToString(signature);function makeDynCaller(){var rtn=getWasmTableEntry(rawFunction);return rtn}var fp=makeDynCaller();if(typeof fp!="function"){throwBindingError(`unknown function pointer with signature ${signature}: ${rawFunction}`)}return fp};class UnboundTypeError extends Error{}var getTypeName=type=>{var ptr=___getTypeName(type);var rv=AsciiToString(ptr);_free(ptr);return rv};var throwUnboundTypeError=(message,types)=>{var unboundTypes=[];var seen={};function visit(type){if(seen[type]){return}if(registeredTypes[type]){return}if(typeDependencies[type]){typeDependencies[type].forEach(visit);return}unboundTypes.push(type);seen[type]=true}types.forEach(visit);throw new UnboundTypeError(`${message}: `+unboundTypes.map(getTypeName).join([", "]))};var whenDependentTypesAreResolved=(myTypes,dependentTypes,getTypeConverters)=>{myTypes.forEach(type=>typeDependencies[type]=dependentTypes);function onComplete(typeConverters){var myTypeConverters=getTypeConverters(typeConverters);if(myTypeConverters.length!==myTypes.length){throwInternalError("Mismatched type converter count")}for(var i=0;i{if(registeredTypes.hasOwnProperty(dt)){typeConverters[i]=registeredTypes[dt]}else{unregisteredTypes.push(dt);if(!awaitingDependencies.hasOwnProperty(dt)){awaitingDependencies[dt]=[]}awaitingDependencies[dt].push(()=>{typeConverters[i]=registeredTypes[dt];++registered;if(registered===unregisteredTypes.length){onComplete(typeConverters)}})}});if(0===unregisteredTypes.length){onComplete(typeConverters)}};var __embind_register_class=(rawType,rawPointerType,rawConstPointerType,baseClassRawType,getActualTypeSignature,getActualType,upcastSignature,upcast,downcastSignature,downcast,name,destructorSignature,rawDestructor)=>{name=AsciiToString(name);getActualType=embind__requireFunction(getActualTypeSignature,getActualType);upcast&&=embind__requireFunction(upcastSignature,upcast);downcast&&=embind__requireFunction(downcastSignature,downcast);rawDestructor=embind__requireFunction(destructorSignature,rawDestructor);var legalFunctionName=makeLegalFunctionName(name);exposePublicSymbol(legalFunctionName,function(){throwUnboundTypeError(`Cannot construct ${name} due to unbound types`,[baseClassRawType])});whenDependentTypesAreResolved([rawType,rawPointerType,rawConstPointerType],baseClassRawType?[baseClassRawType]:[],base=>{base=base[0];var baseClass;var basePrototype;if(baseClassRawType){baseClass=base.registeredClass;basePrototype=baseClass.instancePrototype}else{basePrototype=ClassHandle.prototype}var constructor=createNamedFunction(name,function(...args){if(Object.getPrototypeOf(this)!==instancePrototype){throw new BindingError(`Use 'new' to construct ${name}`)}if(undefined===registeredClass.constructor_body){throw new BindingError(`${name} has no accessible constructor`)}var body=registeredClass.constructor_body[args.length];if(undefined===body){throw new BindingError(`Tried to invoke ctor of ${name} with invalid number of parameters (${args.length}) - expected (${Object.keys(registeredClass.constructor_body).toString()}) parameters instead!`)}return body.apply(this,args)});var instancePrototype=Object.create(basePrototype,{constructor:{value:constructor}});constructor.prototype=instancePrototype;var registeredClass=new RegisteredClass(name,constructor,instancePrototype,rawDestructor,baseClass,getActualType,upcast,downcast);if(registeredClass.baseClass){registeredClass.baseClass.__derivedClasses??=[];registeredClass.baseClass.__derivedClasses.push(registeredClass)}var referenceConverter=new RegisteredPointer(name,registeredClass,true,false,false);var pointerConverter=new RegisteredPointer(name+"*",registeredClass,false,false,false);var constPointerConverter=new RegisteredPointer(name+" const*",registeredClass,false,true,false);registeredPointers[rawType]={pointerType:pointerConverter,constPointerType:constPointerConverter};replacePublicSymbol(legalFunctionName,constructor);return[referenceConverter,pointerConverter,constPointerConverter]})};var heap32VectorToArray=(count,firstElement)=>{var array=[];for(var i=0;i>2])}return array};var runDestructors=destructors=>{while(destructors.length){var ptr=destructors.pop();var del=destructors.pop();del(ptr)}};function usesDestructorStack(argTypes){for(var i=1;i{var rawArgTypes=heap32VectorToArray(argCount,rawArgTypesAddr);invoker=embind__requireFunction(invokerSignature,invoker);whenDependentTypesAreResolved([],[rawClassType],classType=>{classType=classType[0];var humanName=`constructor ${classType.name}`;if(undefined===classType.registeredClass.constructor_body){classType.registeredClass.constructor_body=[]}if(undefined!==classType.registeredClass.constructor_body[argCount-1]){throw new BindingError(`Cannot register multiple constructors with identical number of parameters (${argCount-1}) for class '${classType.name}'! Overload resolution is currently only performed using the parameter count, not actual type info!`)}classType.registeredClass.constructor_body[argCount-1]=()=>{throwUnboundTypeError(`Cannot construct ${classType.name} due to unbound types`,rawArgTypes)};whenDependentTypesAreResolved([],rawArgTypes,argTypes=>{argTypes.splice(1,0,null);classType.registeredClass.constructor_body[argCount-1]=craftInvokerFunction(humanName,argTypes,null,invoker,rawConstructor);return[]});return[]})};var getFunctionName=signature=>{signature=signature.trim();const argsIndex=signature.indexOf("(");if(argsIndex===-1)return signature;return signature.slice(0,argsIndex)};var __embind_register_class_function=(rawClassType,methodName,argCount,rawArgTypesAddr,invokerSignature,rawInvoker,context,isPureVirtual,isAsync,isNonnullReturn)=>{var rawArgTypes=heap32VectorToArray(argCount,rawArgTypesAddr);methodName=AsciiToString(methodName);methodName=getFunctionName(methodName);rawInvoker=embind__requireFunction(invokerSignature,rawInvoker,isAsync);whenDependentTypesAreResolved([],[rawClassType],classType=>{classType=classType[0];var humanName=`${classType.name}.${methodName}`;if(methodName.startsWith("@@")){methodName=Symbol[methodName.substring(2)]}if(isPureVirtual){classType.registeredClass.pureVirtualFunctions.push(methodName)}function unboundTypesHandler(){throwUnboundTypeError(`Cannot call ${humanName} due to unbound types`,rawArgTypes)}var proto=classType.registeredClass.instancePrototype;var method=proto[methodName];if(undefined===method||undefined===method.overloadTable&&method.className!==classType.name&&method.argCount===argCount-2){unboundTypesHandler.argCount=argCount-2;unboundTypesHandler.className=classType.name;proto[methodName]=unboundTypesHandler}else{ensureOverloadTable(proto,methodName,humanName);proto[methodName].overloadTable[argCount-2]=unboundTypesHandler}whenDependentTypesAreResolved([],rawArgTypes,argTypes=>{var memberFunction=craftInvokerFunction(humanName,argTypes,classType,rawInvoker,context,isAsync);if(undefined===proto[methodName].overloadTable){memberFunction.argCount=argCount-2;proto[methodName]=memberFunction}else{proto[methodName].overloadTable[argCount-2]=memberFunction}return[]});return[]})};var validateThis=(this_,classType,humanName)=>{if(!(this_ instanceof Object)){throwBindingError(`${humanName} with invalid "this": ${this_}`)}if(!(this_ instanceof classType.registeredClass.constructor)){throwBindingError(`${humanName} incompatible with "this" of type ${this_.constructor.name}`)}if(!this_.$$.ptr){throwBindingError(`cannot call emscripten binding method ${humanName} on deleted object`)}return upcastPointer(this_.$$.ptr,this_.$$.ptrType.registeredClass,classType.registeredClass)};var __embind_register_class_property=(classType,fieldName,getterReturnType,getterSignature,getter,getterContext,setterArgumentType,setterSignature,setter,setterContext)=>{fieldName=AsciiToString(fieldName);getter=embind__requireFunction(getterSignature,getter);whenDependentTypesAreResolved([],[classType],classType=>{classType=classType[0];var humanName=`${classType.name}.${fieldName}`;var desc={get(){throwUnboundTypeError(`Cannot access ${humanName} due to unbound types`,[getterReturnType,setterArgumentType])},enumerable:true,configurable:true};if(setter){desc.set=()=>throwUnboundTypeError(`Cannot access ${humanName} due to unbound types`,[getterReturnType,setterArgumentType])}else{desc.set=v=>throwBindingError(humanName+" is a read-only property")}Object.defineProperty(classType.registeredClass.instancePrototype,fieldName,desc);whenDependentTypesAreResolved([],setter?[getterReturnType,setterArgumentType]:[getterReturnType],types=>{var getterReturnType=types[0];var desc={get(){var ptr=validateThis(this,classType,humanName+" getter");return getterReturnType["fromWireType"](getter(getterContext,ptr))},enumerable:true};if(setter){setter=embind__requireFunction(setterSignature,setter);var setterArgumentType=types[1];desc.set=function(v){var ptr=validateThis(this,classType,humanName+" setter");var destructors=[];setter(setterContext,ptr,setterArgumentType["toWireType"](destructors,v));runDestructors(destructors)}}Object.defineProperty(classType.registeredClass.instancePrototype,fieldName,desc);return[]});return[]})};var emval_freelist=[];var emval_handles=[0,1,,1,null,1,true,1,false,1];var __emval_decref=handle=>{if(handle>9&&0===--emval_handles[handle+1]){emval_handles[handle]=undefined;emval_freelist.push(handle)}};var Emval={toValue:handle=>{if(!handle){throwBindingError(`Cannot use deleted val. handle = ${handle}`)}return emval_handles[handle]},toHandle:value=>{switch(value){case undefined:return 2;case null:return 4;case true:return 6;case false:return 8;default:{const handle=emval_freelist.pop()||emval_handles.length;emval_handles[handle]=value;emval_handles[handle+1]=1;return handle}}}};var EmValType={name:"emscripten::val",fromWireType:handle=>{var rv=Emval.toValue(handle);__emval_decref(handle);return rv},toWireType:(destructors,value)=>Emval.toHandle(value),argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction:null};var __embind_register_emval=rawType=>registerType(rawType,EmValType);var floatReadValueFromPointer=(name,width)=>{switch(width){case 4:return function(pointer){return this["fromWireType"](HEAPF32[pointer>>2])};case 8:return function(pointer){return this["fromWireType"](HEAPF64[pointer>>3])};default:throw new TypeError(`invalid float width (${width}): ${name}`)}};var __embind_register_float=(rawType,name,size)=>{name=AsciiToString(name);registerType(rawType,{name,fromWireType:value=>value,toWireType:(destructors,value)=>value,argPackAdvance:GenericWireTypeSize,readValueFromPointer:floatReadValueFromPointer(name,size),destructorFunction:null})};var __embind_register_function=(name,argCount,rawArgTypesAddr,signature,rawInvoker,fn,isAsync,isNonnullReturn)=>{var argTypes=heap32VectorToArray(argCount,rawArgTypesAddr);name=AsciiToString(name);name=getFunctionName(name);rawInvoker=embind__requireFunction(signature,rawInvoker,isAsync);exposePublicSymbol(name,function(){throwUnboundTypeError(`Cannot call ${name} due to unbound types`,argTypes)},argCount-1);whenDependentTypesAreResolved([],argTypes,argTypes=>{var invokerArgsArray=[argTypes[0],null].concat(argTypes.slice(1));replacePublicSymbol(name,craftInvokerFunction(name,invokerArgsArray,null,rawInvoker,fn,isAsync),argCount-1);return[]})};var __embind_register_integer=(primitiveType,name,size,minRange,maxRange)=>{name=AsciiToString(name);const isUnsignedType=minRange===0;let fromWireType=value=>value;if(isUnsignedType){var bitshift=32-8*size;fromWireType=value=>value<>>bitshift;maxRange=fromWireType(maxRange)}registerType(primitiveType,{name,fromWireType,toWireType:(destructors,value)=>value,argPackAdvance:GenericWireTypeSize,readValueFromPointer:integerReadValueFromPointer(name,size,minRange!==0),destructorFunction:null})};var __embind_register_memory_view=(rawType,dataTypeIndex,name)=>{var typeMapping=[Int8Array,Uint8Array,Int16Array,Uint16Array,Int32Array,Uint32Array,Float32Array,Float64Array,BigInt64Array,BigUint64Array];var TA=typeMapping[dataTypeIndex];function decodeMemoryView(handle){var size=HEAPU32[handle>>2];var data=HEAPU32[handle+4>>2];return new TA(HEAP8.buffer,data,size)}name=AsciiToString(name);registerType(rawType,{name,fromWireType:decodeMemoryView,argPackAdvance:GenericWireTypeSize,readValueFromPointer:decodeMemoryView},{ignoreDuplicateRegistrations:true})};var stringToUTF8Array=(str,heap,outIdx,maxBytesToWrite)=>{if(!(maxBytesToWrite>0))return 0;var startIdx=outIdx;var endIdx=outIdx+maxBytesToWrite-1;for(var i=0;i=endIdx)break;heap[outIdx++]=u}else if(u<=2047){if(outIdx+1>=endIdx)break;heap[outIdx++]=192|u>>6;heap[outIdx++]=128|u&63}else if(u<=65535){if(outIdx+2>=endIdx)break;heap[outIdx++]=224|u>>12;heap[outIdx++]=128|u>>6&63;heap[outIdx++]=128|u&63}else{if(outIdx+3>=endIdx)break;heap[outIdx++]=240|u>>18;heap[outIdx++]=128|u>>12&63;heap[outIdx++]=128|u>>6&63;heap[outIdx++]=128|u&63;i++}}heap[outIdx]=0;return outIdx-startIdx};var stringToUTF8=(str,outPtr,maxBytesToWrite)=>stringToUTF8Array(str,HEAPU8,outPtr,maxBytesToWrite);var lengthBytesUTF8=str=>{var len=0;for(var i=0;i=55296&&c<=57343){len+=4;++i}else{len+=3}}return len};var UTF8Decoder=typeof TextDecoder!="undefined"?new TextDecoder:undefined;var UTF8ArrayToString=(heapOrArray,idx=0,maxBytesToRead=NaN)=>{var endIdx=idx+maxBytesToRead;var endPtr=idx;while(heapOrArray[endPtr]&&!(endPtr>=endIdx))++endPtr;if(endPtr-idx>16&&heapOrArray.buffer&&UTF8Decoder){return UTF8Decoder.decode(heapOrArray.subarray(idx,endPtr))}var str="";while(idx>10,56320|ch&1023)}}return str};var UTF8ToString=(ptr,maxBytesToRead)=>ptr?UTF8ArrayToString(HEAPU8,ptr,maxBytesToRead):"";var __embind_register_std_string=(rawType,name)=>{name=AsciiToString(name);var stdStringIsUTF8=true;registerType(rawType,{name,fromWireType(value){var length=HEAPU32[value>>2];var payload=value+4;var str;if(stdStringIsUTF8){var decodeStartPtr=payload;for(var i=0;i<=length;++i){var currentBytePtr=payload+i;if(i==length||HEAPU8[currentBytePtr]==0){var maxRead=currentBytePtr-decodeStartPtr;var stringSegment=UTF8ToString(decodeStartPtr,maxRead);if(str===undefined){str=stringSegment}else{str+=String.fromCharCode(0);str+=stringSegment}decodeStartPtr=currentBytePtr+1}}}else{var a=new Array(length);for(var i=0;i>2]=length;if(valueIsOfTypeString){if(stdStringIsUTF8){stringToUTF8(value,ptr,length+1)}else{for(var i=0;i255){_free(base);throwBindingError("String has UTF-16 code units that do not fit in 8 bits")}HEAPU8[ptr+i]=charCode}}}else{HEAPU8.set(value,ptr)}if(destructors!==null){destructors.push(_free,base)}return base},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction(ptr){_free(ptr)}})};var UTF16Decoder=typeof TextDecoder!="undefined"?new TextDecoder("utf-16le"):undefined;var UTF16ToString=(ptr,maxBytesToRead)=>{var idx=ptr>>1;var maxIdx=idx+maxBytesToRead/2;var endIdx=idx;while(!(endIdx>=maxIdx)&&HEAPU16[endIdx])++endIdx;if(endIdx-idx>16&&UTF16Decoder)return UTF16Decoder.decode(HEAPU16.subarray(idx,endIdx));var str="";for(var i=idx;!(i>=maxIdx);++i){var codeUnit=HEAPU16[i];if(codeUnit==0)break;str+=String.fromCharCode(codeUnit)}return str};var stringToUTF16=(str,outPtr,maxBytesToWrite)=>{maxBytesToWrite??=2147483647;if(maxBytesToWrite<2)return 0;maxBytesToWrite-=2;var startPtr=outPtr;var numCharsToWrite=maxBytesToWrite>1]=codeUnit;outPtr+=2}HEAP16[outPtr>>1]=0;return outPtr-startPtr};var lengthBytesUTF16=str=>str.length*2;var UTF32ToString=(ptr,maxBytesToRead)=>{var str="";for(var i=0;!(i>=maxBytesToRead/4);i++){var utf32=HEAP32[ptr+i*4>>2];if(!utf32)break;str+=String.fromCodePoint(utf32)}return str};var stringToUTF32=(str,outPtr,maxBytesToWrite)=>{maxBytesToWrite??=2147483647;if(maxBytesToWrite<4)return 0;var startPtr=outPtr;var endPtr=startPtr+maxBytesToWrite-4;for(var i=0;i65535){i++}HEAP32[outPtr>>2]=codePoint;outPtr+=4;if(outPtr+4>endPtr)break}HEAP32[outPtr>>2]=0;return outPtr-startPtr};var lengthBytesUTF32=str=>{var len=0;for(var i=0;i65535){i++}len+=4}return len};var __embind_register_std_wstring=(rawType,charSize,name)=>{name=AsciiToString(name);var decodeString,encodeString,readCharAt,lengthBytesUTF;if(charSize===2){decodeString=UTF16ToString;encodeString=stringToUTF16;lengthBytesUTF=lengthBytesUTF16;readCharAt=pointer=>HEAPU16[pointer>>1]}else if(charSize===4){decodeString=UTF32ToString;encodeString=stringToUTF32;lengthBytesUTF=lengthBytesUTF32;readCharAt=pointer=>HEAPU32[pointer>>2]}registerType(rawType,{name,fromWireType:value=>{var length=HEAPU32[value>>2];var str;var decodeStartPtr=value+4;for(var i=0;i<=length;++i){var currentBytePtr=value+4+i*charSize;if(i==length||readCharAt(currentBytePtr)==0){var maxReadBytes=currentBytePtr-decodeStartPtr;var stringSegment=decodeString(decodeStartPtr,maxReadBytes);if(str===undefined){str=stringSegment}else{str+=String.fromCharCode(0);str+=stringSegment}decodeStartPtr=currentBytePtr+charSize}}_free(value);return str},toWireType:(destructors,value)=>{if(!(typeof value=="string")){throwBindingError(`Cannot pass non-string to C++ string type ${name}`)}var length=lengthBytesUTF(value);var ptr=_malloc(4+length+charSize);HEAPU32[ptr>>2]=length/charSize;encodeString(value,ptr+4,length+charSize);if(destructors!==null){destructors.push(_free,ptr)}return ptr},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction(ptr){_free(ptr)}})};var __embind_register_void=(rawType,name)=>{name=AsciiToString(name);registerType(rawType,{isVoid:true,name,argPackAdvance:0,fromWireType:()=>undefined,toWireType:(destructors,o)=>undefined})};var requireRegisteredType=(rawType,humanName)=>{var impl=registeredTypes[rawType];if(undefined===impl){throwBindingError(`${humanName} has unknown type ${getTypeName(rawType)}`)}return impl};var __emval_take_value=(type,arg)=>{type=requireRegisteredType(type,"_emval_take_value");var v=type["readValueFromPointer"](arg);return Emval.toHandle(v)};var _emscripten_date_now=()=>Date.now();var abortOnCannotGrowMemory=requestedSize=>{abort("OOM")};var _emscripten_resize_heap=requestedSize=>{var oldSize=HEAPU8.length;requestedSize>>>=0;abortOnCannotGrowMemory(requestedSize)};var printCharBuffers=[null,[],[]];var printChar=(stream,curr)=>{var buffer=printCharBuffers[stream];if(curr===0||curr===10){(stream===1?out:err)(UTF8ArrayToString(buffer));buffer.length=0}else{buffer.push(curr)}};var _fd_write=(fd,iov,iovcnt,pnum)=>{var num=0;for(var i=0;i>2];var len=HEAPU32[iov+4>>2];iov+=8;for(var j=0;j>2]=num;return 0};init_ClassHandle();init_RegisteredPointer();{if(Module["noExitRuntime"])noExitRuntime=Module["noExitRuntime"];if(Module["print"])out=Module["print"];if(Module["printErr"])err=Module["printErr"];if(Module["wasmBinary"])wasmBinary=Module["wasmBinary"];if(Module["arguments"])arguments_=Module["arguments"];if(Module["thisProgram"])thisProgram=Module["thisProgram"]}var _param_get,_param_set_used,__Znwm,__ZdlPvm,_malloc,__ZNSt12length_errorD1Ev,___cxa_allocate_exception,__ZNSt20bad_array_new_lengthD1Ev,__ZNSt20bad_array_new_lengthC1Ev,__ZNSt12out_of_rangeD1Ev,___cxa_pure_virtual,___getTypeName,__ZNSt9exceptionD2Ev,__emscripten_memcpy_bulkmem,_emscripten_stack_get_end,_emscripten_stack_get_base,_free,_emscripten_stack_init,_emscripten_stack_set_limits,_emscripten_stack_get_free,__ZSt15get_new_handlerv,__Znam,__ZdlPv,__ZdaPv,__ZdaPvm,__ZnwmSt11align_val_t,__ZnamSt11align_val_t,__ZdlPvSt11align_val_t,__ZdlPvmSt11align_val_t,__ZdaPvSt11align_val_t,__ZdaPvmSt11align_val_t,__ZSt14set_unexpectedPFvvE,__ZSt13set_terminatePFvvE,__ZSt15set_new_handlerPFvvE,__ZSt14get_unexpectedv,__ZSt10unexpectedv,__ZSt13get_terminatev,__ZSt9terminatev,___cxa_current_primary_exception,___cxa_rethrow_primary_exception,___cxa_uncaught_exception,___cxa_uncaught_exceptions,___cxa_free_exception,___cxa_init_primary_exception,___cxa_deleted_virtual,___dynamic_cast,__ZNSt9type_infoD2Ev,__ZNSt9exceptionD0Ev,__ZNSt9exceptionD1Ev,__ZNKSt9exception4whatEv,__ZNSt13bad_exceptionD0Ev,__ZNSt13bad_exceptionD1Ev,__ZNKSt13bad_exception4whatEv,__ZNSt9bad_allocC2Ev,__ZNSt9bad_allocD0Ev,__ZNSt9bad_allocD1Ev,__ZNKSt9bad_alloc4whatEv,__ZNSt20bad_array_new_lengthC2Ev,__ZNSt20bad_array_new_lengthD0Ev,__ZNKSt20bad_array_new_length4whatEv,__ZNSt13bad_exceptionD2Ev,__ZNSt9bad_allocC1Ev,__ZNSt9bad_allocD2Ev,__ZNSt20bad_array_new_lengthD2Ev,__ZNSt11logic_errorD2Ev,__ZNSt11logic_errorD0Ev,__ZNSt11logic_errorD1Ev,__ZNKSt11logic_error4whatEv,__ZNSt13runtime_errorD2Ev,__ZNSt13runtime_errorD0Ev,__ZNSt13runtime_errorD1Ev,__ZNKSt13runtime_error4whatEv,__ZNSt12domain_errorD0Ev,__ZNSt12domain_errorD1Ev,__ZNSt16invalid_argumentD0Ev,__ZNSt16invalid_argumentD1Ev,__ZNSt12length_errorD0Ev,__ZNSt12out_of_rangeD0Ev,__ZNSt11range_errorD0Ev,__ZNSt11range_errorD1Ev,__ZNSt14overflow_errorD0Ev,__ZNSt14overflow_errorD1Ev,__ZNSt15underflow_errorD0Ev,__ZNSt15underflow_errorD1Ev,__ZNSt12domain_errorD2Ev,__ZNSt16invalid_argumentD2Ev,__ZNSt12length_errorD2Ev,__ZNSt12out_of_rangeD2Ev,__ZNSt11range_errorD2Ev,__ZNSt14overflow_errorD2Ev,__ZNSt15underflow_errorD2Ev,__ZNSt9type_infoD0Ev,__ZNSt9type_infoD1Ev,__ZNSt8bad_castC2Ev,__ZNSt8bad_castD2Ev,__ZNSt8bad_castD0Ev,__ZNSt8bad_castD1Ev,__ZNKSt8bad_cast4whatEv,__ZNSt10bad_typeidC2Ev,__ZNSt10bad_typeidD2Ev,__ZNSt10bad_typeidD0Ev,__ZNSt10bad_typeidD1Ev,__ZNKSt10bad_typeid4whatEv,__ZNSt8bad_castC1Ev,__ZNSt10bad_typeidC1Ev;function assignWasmExports(wasmExports){Module["_param_get"]=_param_get=wasmExports["w"];Module["_param_set_used"]=_param_set_used=wasmExports["x"];Module["__Znwm"]=__Znwm=wasmExports["y"];Module["__ZdlPvm"]=__ZdlPvm=wasmExports["z"];_malloc=wasmExports["B"];Module["__ZNSt12length_errorD1Ev"]=__ZNSt12length_errorD1Ev=wasmExports["C"];Module["___cxa_allocate_exception"]=___cxa_allocate_exception=wasmExports["D"];Module["__ZNSt20bad_array_new_lengthD1Ev"]=__ZNSt20bad_array_new_lengthD1Ev=wasmExports["E"];Module["__ZNSt20bad_array_new_lengthC1Ev"]=__ZNSt20bad_array_new_lengthC1Ev=wasmExports["F"];Module["__ZNSt12out_of_rangeD1Ev"]=__ZNSt12out_of_rangeD1Ev=wasmExports["G"];Module["___cxa_pure_virtual"]=___cxa_pure_virtual=wasmExports["H"];___getTypeName=wasmExports["I"];Module["__ZNSt9exceptionD2Ev"]=__ZNSt9exceptionD2Ev=wasmExports["J"];Module["__emscripten_memcpy_bulkmem"]=__emscripten_memcpy_bulkmem=wasmExports["K"];Module["_emscripten_stack_get_end"]=_emscripten_stack_get_end=wasmExports["L"];Module["_emscripten_stack_get_base"]=_emscripten_stack_get_base=wasmExports["M"];_free=wasmExports["N"];Module["_emscripten_stack_init"]=_emscripten_stack_init=wasmExports["O"];Module["_emscripten_stack_set_limits"]=_emscripten_stack_set_limits=wasmExports["P"];Module["_emscripten_stack_get_free"]=_emscripten_stack_get_free=wasmExports["Q"];Module["__ZSt15get_new_handlerv"]=__ZSt15get_new_handlerv=wasmExports["R"];Module["__Znam"]=__Znam=wasmExports["S"];Module["__ZdlPv"]=__ZdlPv=wasmExports["T"];Module["__ZdaPv"]=__ZdaPv=wasmExports["U"];Module["__ZdaPvm"]=__ZdaPvm=wasmExports["V"];Module["__ZnwmSt11align_val_t"]=__ZnwmSt11align_val_t=wasmExports["W"];Module["__ZnamSt11align_val_t"]=__ZnamSt11align_val_t=wasmExports["X"];Module["__ZdlPvSt11align_val_t"]=__ZdlPvSt11align_val_t=wasmExports["Y"];Module["__ZdlPvmSt11align_val_t"]=__ZdlPvmSt11align_val_t=wasmExports["Z"];Module["__ZdaPvSt11align_val_t"]=__ZdaPvSt11align_val_t=wasmExports["_"];Module["__ZdaPvmSt11align_val_t"]=__ZdaPvmSt11align_val_t=wasmExports["$"];Module["__ZSt14set_unexpectedPFvvE"]=__ZSt14set_unexpectedPFvvE=wasmExports["aa"];Module["__ZSt13set_terminatePFvvE"]=__ZSt13set_terminatePFvvE=wasmExports["ba"];Module["__ZSt15set_new_handlerPFvvE"]=__ZSt15set_new_handlerPFvvE=wasmExports["ca"];Module["__ZSt14get_unexpectedv"]=__ZSt14get_unexpectedv=wasmExports["da"];Module["__ZSt10unexpectedv"]=__ZSt10unexpectedv=wasmExports["ea"];Module["__ZSt13get_terminatev"]=__ZSt13get_terminatev=wasmExports["fa"];Module["__ZSt9terminatev"]=__ZSt9terminatev=wasmExports["ga"];Module["___cxa_current_primary_exception"]=___cxa_current_primary_exception=wasmExports["ha"];Module["___cxa_rethrow_primary_exception"]=___cxa_rethrow_primary_exception=wasmExports["ia"];Module["___cxa_uncaught_exception"]=___cxa_uncaught_exception=wasmExports["ja"];Module["___cxa_uncaught_exceptions"]=___cxa_uncaught_exceptions=wasmExports["ka"];Module["___cxa_free_exception"]=___cxa_free_exception=wasmExports["la"];Module["___cxa_init_primary_exception"]=___cxa_init_primary_exception=wasmExports["ma"];Module["___cxa_deleted_virtual"]=___cxa_deleted_virtual=wasmExports["na"];Module["___dynamic_cast"]=___dynamic_cast=wasmExports["oa"];Module["__ZNSt9type_infoD2Ev"]=__ZNSt9type_infoD2Ev=wasmExports["pa"];Module["__ZNSt9exceptionD0Ev"]=__ZNSt9exceptionD0Ev=wasmExports["qa"];Module["__ZNSt9exceptionD1Ev"]=__ZNSt9exceptionD1Ev=wasmExports["ra"];Module["__ZNKSt9exception4whatEv"]=__ZNKSt9exception4whatEv=wasmExports["sa"];Module["__ZNSt13bad_exceptionD0Ev"]=__ZNSt13bad_exceptionD0Ev=wasmExports["ta"];Module["__ZNSt13bad_exceptionD1Ev"]=__ZNSt13bad_exceptionD1Ev=wasmExports["ua"];Module["__ZNKSt13bad_exception4whatEv"]=__ZNKSt13bad_exception4whatEv=wasmExports["va"];Module["__ZNSt9bad_allocC2Ev"]=__ZNSt9bad_allocC2Ev=wasmExports["wa"];Module["__ZNSt9bad_allocD0Ev"]=__ZNSt9bad_allocD0Ev=wasmExports["xa"];Module["__ZNSt9bad_allocD1Ev"]=__ZNSt9bad_allocD1Ev=wasmExports["ya"];Module["__ZNKSt9bad_alloc4whatEv"]=__ZNKSt9bad_alloc4whatEv=wasmExports["za"];Module["__ZNSt20bad_array_new_lengthC2Ev"]=__ZNSt20bad_array_new_lengthC2Ev=wasmExports["Aa"];Module["__ZNSt20bad_array_new_lengthD0Ev"]=__ZNSt20bad_array_new_lengthD0Ev=wasmExports["Ba"];Module["__ZNKSt20bad_array_new_length4whatEv"]=__ZNKSt20bad_array_new_length4whatEv=wasmExports["Ca"];Module["__ZNSt13bad_exceptionD2Ev"]=__ZNSt13bad_exceptionD2Ev=wasmExports["Da"];Module["__ZNSt9bad_allocC1Ev"]=__ZNSt9bad_allocC1Ev=wasmExports["Ea"];Module["__ZNSt9bad_allocD2Ev"]=__ZNSt9bad_allocD2Ev=wasmExports["Fa"];Module["__ZNSt20bad_array_new_lengthD2Ev"]=__ZNSt20bad_array_new_lengthD2Ev=wasmExports["Ga"];Module["__ZNSt11logic_errorD2Ev"]=__ZNSt11logic_errorD2Ev=wasmExports["Ha"];Module["__ZNSt11logic_errorD0Ev"]=__ZNSt11logic_errorD0Ev=wasmExports["Ia"];Module["__ZNSt11logic_errorD1Ev"]=__ZNSt11logic_errorD1Ev=wasmExports["Ja"];Module["__ZNKSt11logic_error4whatEv"]=__ZNKSt11logic_error4whatEv=wasmExports["Ka"];Module["__ZNSt13runtime_errorD2Ev"]=__ZNSt13runtime_errorD2Ev=wasmExports["La"];Module["__ZNSt13runtime_errorD0Ev"]=__ZNSt13runtime_errorD0Ev=wasmExports["Ma"];Module["__ZNSt13runtime_errorD1Ev"]=__ZNSt13runtime_errorD1Ev=wasmExports["Na"];Module["__ZNKSt13runtime_error4whatEv"]=__ZNKSt13runtime_error4whatEv=wasmExports["Oa"];Module["__ZNSt12domain_errorD0Ev"]=__ZNSt12domain_errorD0Ev=wasmExports["Pa"];Module["__ZNSt12domain_errorD1Ev"]=__ZNSt12domain_errorD1Ev=wasmExports["Qa"];Module["__ZNSt16invalid_argumentD0Ev"]=__ZNSt16invalid_argumentD0Ev=wasmExports["Ra"];Module["__ZNSt16invalid_argumentD1Ev"]=__ZNSt16invalid_argumentD1Ev=wasmExports["Sa"];Module["__ZNSt12length_errorD0Ev"]=__ZNSt12length_errorD0Ev=wasmExports["Ta"];Module["__ZNSt12out_of_rangeD0Ev"]=__ZNSt12out_of_rangeD0Ev=wasmExports["Ua"];Module["__ZNSt11range_errorD0Ev"]=__ZNSt11range_errorD0Ev=wasmExports["Va"];Module["__ZNSt11range_errorD1Ev"]=__ZNSt11range_errorD1Ev=wasmExports["Wa"];Module["__ZNSt14overflow_errorD0Ev"]=__ZNSt14overflow_errorD0Ev=wasmExports["Xa"];Module["__ZNSt14overflow_errorD1Ev"]=__ZNSt14overflow_errorD1Ev=wasmExports["Ya"];Module["__ZNSt15underflow_errorD0Ev"]=__ZNSt15underflow_errorD0Ev=wasmExports["Za"];Module["__ZNSt15underflow_errorD1Ev"]=__ZNSt15underflow_errorD1Ev=wasmExports["_a"];Module["__ZNSt12domain_errorD2Ev"]=__ZNSt12domain_errorD2Ev=wasmExports["$a"];Module["__ZNSt16invalid_argumentD2Ev"]=__ZNSt16invalid_argumentD2Ev=wasmExports["ab"];Module["__ZNSt12length_errorD2Ev"]=__ZNSt12length_errorD2Ev=wasmExports["bb"];Module["__ZNSt12out_of_rangeD2Ev"]=__ZNSt12out_of_rangeD2Ev=wasmExports["cb"];Module["__ZNSt11range_errorD2Ev"]=__ZNSt11range_errorD2Ev=wasmExports["db"];Module["__ZNSt14overflow_errorD2Ev"]=__ZNSt14overflow_errorD2Ev=wasmExports["eb"];Module["__ZNSt15underflow_errorD2Ev"]=__ZNSt15underflow_errorD2Ev=wasmExports["fb"];Module["__ZNSt9type_infoD0Ev"]=__ZNSt9type_infoD0Ev=wasmExports["gb"];Module["__ZNSt9type_infoD1Ev"]=__ZNSt9type_infoD1Ev=wasmExports["hb"];Module["__ZNSt8bad_castC2Ev"]=__ZNSt8bad_castC2Ev=wasmExports["ib"];Module["__ZNSt8bad_castD2Ev"]=__ZNSt8bad_castD2Ev=wasmExports["jb"];Module["__ZNSt8bad_castD0Ev"]=__ZNSt8bad_castD0Ev=wasmExports["kb"];Module["__ZNSt8bad_castD1Ev"]=__ZNSt8bad_castD1Ev=wasmExports["lb"];Module["__ZNKSt8bad_cast4whatEv"]=__ZNKSt8bad_cast4whatEv=wasmExports["mb"];Module["__ZNSt10bad_typeidC2Ev"]=__ZNSt10bad_typeidC2Ev=wasmExports["nb"];Module["__ZNSt10bad_typeidD2Ev"]=__ZNSt10bad_typeidD2Ev=wasmExports["ob"];Module["__ZNSt10bad_typeidD0Ev"]=__ZNSt10bad_typeidD0Ev=wasmExports["pb"];Module["__ZNSt10bad_typeidD1Ev"]=__ZNSt10bad_typeidD1Ev=wasmExports["qb"];Module["__ZNKSt10bad_typeid4whatEv"]=__ZNKSt10bad_typeid4whatEv=wasmExports["rb"];Module["__ZNSt8bad_castC1Ev"]=__ZNSt8bad_castC1Ev=wasmExports["sb"];Module["__ZNSt10bad_typeidC1Ev"]=__ZNSt10bad_typeidC1Ev=wasmExports["tb"]}var __ZTIPK16failsafe_flags_s=Module["__ZTIPK16failsafe_flags_s"]=47432;var __ZTIP16failsafe_flags_s=Module["__ZTIP16failsafe_flags_s"]=47416;var __ZTI16failsafe_flags_s=Module["__ZTI16failsafe_flags_s"]=47408;var __ZTIb=Module["__ZTIb"]=30292;var __ZTIh=Module["__ZTIh"]=30448;var __ZTIPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTIPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=47580;var __ZTIPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTIPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=47564;var __ZTINSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTINSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=47512;var __ZTISt12length_error=Module["__ZTISt12length_error"]=32392;var __ZTVSt12length_error=Module["__ZTVSt12length_error"]=32372;var __ZTISt20bad_array_new_length=Module["__ZTISt20bad_array_new_length"]=32156;var __ZTINSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE=Module["__ZTINSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE"]=47500;var __ZTISt12out_of_range=Module["__ZTISt12out_of_range"]=32444;var __ZTVSt12out_of_range=Module["__ZTVSt12out_of_range"]=32424;var __ZTVN10__cxxabiv120__si_class_type_infoE=Module["__ZTVN10__cxxabiv120__si_class_type_infoE"]=31724;var __ZTVN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTVN10__cxxabiv121__vmi_class_type_infoE"]=31816;var __ZTVN10__cxxabiv117__class_type_infoE=Module["__ZTVN10__cxxabiv117__class_type_infoE"]=31684;var __ZTS16failsafe_flags_s=Module["__ZTS16failsafe_flags_s"]=28034;var __ZTVN10__cxxabiv119__pointer_type_infoE=Module["__ZTVN10__cxxabiv119__pointer_type_infoE"]=31936;var __ZTSP16failsafe_flags_s=Module["__ZTSP16failsafe_flags_s"]=28053;var __ZTSPK16failsafe_flags_s=Module["__ZTSPK16failsafe_flags_s"]=28073;var __ZTIi=Module["__ZTIi"]=30656;var __ZTSNSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE=Module["__ZTSNSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE"]=28122;var __ZTSNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=28189;var __ZTIv=Module["__ZTIv"]=30184;var __ZTIf=Module["__ZTIf"]=31128;var __ZTSPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=28287;var __ZTSPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=28374;var __ZTIm=Module["__ZTIm"]=30812;var __ZTIN10emscripten3valE=Module["__ZTIN10emscripten3valE"]=47652;var __ZTSN10emscripten3valE=Module["__ZTSN10emscripten3valE"]=28477;var __ZTIc=Module["__ZTIc"]=30396;var __ZTIa=Module["__ZTIa"]=30500;var __ZTIs=Module["__ZTIs"]=30552;var __ZTIt=Module["__ZTIt"]=30604;var __ZTIj=Module["__ZTIj"]=30708;var __ZTIl=Module["__ZTIl"]=30760;var __ZTIx=Module["__ZTIx"]=30864;var __ZTIy=Module["__ZTIy"]=30916;var __ZTId=Module["__ZTId"]=31180;var __ZTINSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE=Module["__ZTINSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE"]=28532;var __ZTINSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE=Module["__ZTINSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE"]=28604;var __ZTINSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE=Module["__ZTINSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE"]=28680;var __ZTIN10emscripten11memory_viewIcEE=Module["__ZTIN10emscripten11memory_viewIcEE"]=28756;var __ZTIN10emscripten11memory_viewIaEE=Module["__ZTIN10emscripten11memory_viewIaEE"]=28796;var __ZTIN10emscripten11memory_viewIhEE=Module["__ZTIN10emscripten11memory_viewIhEE"]=28836;var __ZTIN10emscripten11memory_viewIsEE=Module["__ZTIN10emscripten11memory_viewIsEE"]=28876;var __ZTIN10emscripten11memory_viewItEE=Module["__ZTIN10emscripten11memory_viewItEE"]=28916;var __ZTIN10emscripten11memory_viewIiEE=Module["__ZTIN10emscripten11memory_viewIiEE"]=28956;var __ZTIN10emscripten11memory_viewIjEE=Module["__ZTIN10emscripten11memory_viewIjEE"]=28996;var __ZTIN10emscripten11memory_viewIlEE=Module["__ZTIN10emscripten11memory_viewIlEE"]=29036;var __ZTIN10emscripten11memory_viewImEE=Module["__ZTIN10emscripten11memory_viewImEE"]=29076;var __ZTIN10emscripten11memory_viewIxEE=Module["__ZTIN10emscripten11memory_viewIxEE"]=29116;var __ZTIN10emscripten11memory_viewIyEE=Module["__ZTIN10emscripten11memory_viewIyEE"]=29156;var __ZTIN10emscripten11memory_viewIfEE=Module["__ZTIN10emscripten11memory_viewIfEE"]=29196;var __ZTIN10emscripten11memory_viewIdEE=Module["__ZTIN10emscripten11memory_viewIdEE"]=29236;var __ZTSNSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE=Module["__ZTSNSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE"]=28540;var __ZTSNSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE=Module["__ZTSNSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE"]=28612;var __ZTSNSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE=Module["__ZTSNSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE"]=28688;var __ZTSN10emscripten11memory_viewIcEE=Module["__ZTSN10emscripten11memory_viewIcEE"]=28764;var __ZTSN10emscripten11memory_viewIaEE=Module["__ZTSN10emscripten11memory_viewIaEE"]=28804;var __ZTSN10emscripten11memory_viewIhEE=Module["__ZTSN10emscripten11memory_viewIhEE"]=28844;var __ZTSN10emscripten11memory_viewIsEE=Module["__ZTSN10emscripten11memory_viewIsEE"]=28884;var __ZTSN10emscripten11memory_viewItEE=Module["__ZTSN10emscripten11memory_viewItEE"]=28924;var __ZTSN10emscripten11memory_viewIiEE=Module["__ZTSN10emscripten11memory_viewIiEE"]=28964;var __ZTSN10emscripten11memory_viewIjEE=Module["__ZTSN10emscripten11memory_viewIjEE"]=29004;var __ZTSN10emscripten11memory_viewIlEE=Module["__ZTSN10emscripten11memory_viewIlEE"]=29044;var __ZTSN10emscripten11memory_viewImEE=Module["__ZTSN10emscripten11memory_viewImEE"]=29084;var __ZTSN10emscripten11memory_viewIxEE=Module["__ZTSN10emscripten11memory_viewIxEE"]=29124;var __ZTSN10emscripten11memory_viewIyEE=Module["__ZTSN10emscripten11memory_viewIyEE"]=29164;var __ZTSN10emscripten11memory_viewIfEE=Module["__ZTSN10emscripten11memory_viewIfEE"]=29204;var __ZTSN10emscripten11memory_viewIdEE=Module["__ZTSN10emscripten11memory_viewIdEE"]=29244;var __ZTVSt11logic_error=Module["__ZTVSt11logic_error"]=32196;var __ZTVSt9exception=Module["__ZTVSt9exception"]=32032;var __ZTVSt13runtime_error=Module["__ZTVSt13runtime_error"]=32216;var __ZTISt9exception=Module["__ZTISt9exception"]=32052;var ___cxa_unexpected_handler=Module["___cxa_unexpected_handler"]=47880;var ___cxa_terminate_handler=Module["___cxa_terminate_handler"]=47876;var ___cxa_new_handler=Module["___cxa_new_handler"]=50124;var __ZTIN10__cxxabiv116__shim_type_infoE=Module["__ZTIN10__cxxabiv116__shim_type_infoE"]=29760;var __ZTIN10__cxxabiv117__class_type_infoE=Module["__ZTIN10__cxxabiv117__class_type_infoE"]=29808;var __ZTIN10__cxxabiv117__pbase_type_infoE=Module["__ZTIN10__cxxabiv117__pbase_type_infoE"]=29856;var __ZTIDn=Module["__ZTIDn"]=30236;var __ZTIN10__cxxabiv119__pointer_type_infoE=Module["__ZTIN10__cxxabiv119__pointer_type_infoE"]=29904;var __ZTIN10__cxxabiv120__function_type_infoE=Module["__ZTIN10__cxxabiv120__function_type_infoE"]=29952;var __ZTIN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTIN10__cxxabiv129__pointer_to_member_type_infoE"]=30004;var __ZTISt9type_info=Module["__ZTISt9type_info"]=32716;var __ZTSN10__cxxabiv116__shim_type_infoE=Module["__ZTSN10__cxxabiv116__shim_type_infoE"]=29772;var __ZTSN10__cxxabiv117__class_type_infoE=Module["__ZTSN10__cxxabiv117__class_type_infoE"]=29820;var __ZTSN10__cxxabiv117__pbase_type_infoE=Module["__ZTSN10__cxxabiv117__pbase_type_infoE"]=29868;var __ZTSN10__cxxabiv119__pointer_type_infoE=Module["__ZTSN10__cxxabiv119__pointer_type_infoE"]=29916;var __ZTSN10__cxxabiv120__function_type_infoE=Module["__ZTSN10__cxxabiv120__function_type_infoE"]=29964;var __ZTSN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTSN10__cxxabiv129__pointer_to_member_type_infoE"]=30016;var __ZTVN10__cxxabiv116__shim_type_infoE=Module["__ZTVN10__cxxabiv116__shim_type_infoE"]=30076;var __ZTVN10__cxxabiv123__fundamental_type_infoE=Module["__ZTVN10__cxxabiv123__fundamental_type_infoE"]=30104;var __ZTIN10__cxxabiv123__fundamental_type_infoE=Module["__ZTIN10__cxxabiv123__fundamental_type_infoE"]=30132;var __ZTSN10__cxxabiv123__fundamental_type_infoE=Module["__ZTSN10__cxxabiv123__fundamental_type_infoE"]=30144;var __ZTSv=Module["__ZTSv"]=30192;var __ZTIPv=Module["__ZTIPv"]=30196;var __ZTSPv=Module["__ZTSPv"]=30212;var __ZTIPKv=Module["__ZTIPKv"]=30216;var __ZTSPKv=Module["__ZTSPKv"]=30232;var __ZTSDn=Module["__ZTSDn"]=30244;var __ZTIPDn=Module["__ZTIPDn"]=30248;var __ZTSPDn=Module["__ZTSPDn"]=30264;var __ZTIPKDn=Module["__ZTIPKDn"]=30268;var __ZTSPKDn=Module["__ZTSPKDn"]=30284;var __ZTSb=Module["__ZTSb"]=30300;var __ZTIPb=Module["__ZTIPb"]=30304;var __ZTSPb=Module["__ZTSPb"]=30320;var __ZTIPKb=Module["__ZTIPKb"]=30324;var __ZTSPKb=Module["__ZTSPKb"]=30340;var __ZTIw=Module["__ZTIw"]=30344;var __ZTSw=Module["__ZTSw"]=30352;var __ZTIPw=Module["__ZTIPw"]=30356;var __ZTSPw=Module["__ZTSPw"]=30372;var __ZTIPKw=Module["__ZTIPKw"]=30376;var __ZTSPKw=Module["__ZTSPKw"]=30392;var __ZTSc=Module["__ZTSc"]=30404;var __ZTIPc=Module["__ZTIPc"]=30408;var __ZTSPc=Module["__ZTSPc"]=30424;var __ZTIPKc=Module["__ZTIPKc"]=30428;var __ZTSPKc=Module["__ZTSPKc"]=30444;var __ZTSh=Module["__ZTSh"]=30456;var __ZTIPh=Module["__ZTIPh"]=30460;var __ZTSPh=Module["__ZTSPh"]=30476;var __ZTIPKh=Module["__ZTIPKh"]=30480;var __ZTSPKh=Module["__ZTSPKh"]=30496;var __ZTSa=Module["__ZTSa"]=30508;var __ZTIPa=Module["__ZTIPa"]=30512;var __ZTSPa=Module["__ZTSPa"]=30528;var __ZTIPKa=Module["__ZTIPKa"]=30532;var __ZTSPKa=Module["__ZTSPKa"]=30548;var __ZTSs=Module["__ZTSs"]=30560;var __ZTIPs=Module["__ZTIPs"]=30564;var __ZTSPs=Module["__ZTSPs"]=30580;var __ZTIPKs=Module["__ZTIPKs"]=30584;var __ZTSPKs=Module["__ZTSPKs"]=30600;var __ZTSt=Module["__ZTSt"]=30612;var __ZTIPt=Module["__ZTIPt"]=30616;var __ZTSPt=Module["__ZTSPt"]=30632;var __ZTIPKt=Module["__ZTIPKt"]=30636;var __ZTSPKt=Module["__ZTSPKt"]=30652;var __ZTSi=Module["__ZTSi"]=30664;var __ZTIPi=Module["__ZTIPi"]=30668;var __ZTSPi=Module["__ZTSPi"]=30684;var __ZTIPKi=Module["__ZTIPKi"]=30688;var __ZTSPKi=Module["__ZTSPKi"]=30704;var __ZTSj=Module["__ZTSj"]=30716;var __ZTIPj=Module["__ZTIPj"]=30720;var __ZTSPj=Module["__ZTSPj"]=30736;var __ZTIPKj=Module["__ZTIPKj"]=30740;var __ZTSPKj=Module["__ZTSPKj"]=30756;var __ZTSl=Module["__ZTSl"]=30768;var __ZTIPl=Module["__ZTIPl"]=30772;var __ZTSPl=Module["__ZTSPl"]=30788;var __ZTIPKl=Module["__ZTIPKl"]=30792;var __ZTSPKl=Module["__ZTSPKl"]=30808;var __ZTSm=Module["__ZTSm"]=30820;var __ZTIPm=Module["__ZTIPm"]=30824;var __ZTSPm=Module["__ZTSPm"]=30840;var __ZTIPKm=Module["__ZTIPKm"]=30844;var __ZTSPKm=Module["__ZTSPKm"]=30860;var __ZTSx=Module["__ZTSx"]=30872;var __ZTIPx=Module["__ZTIPx"]=30876;var __ZTSPx=Module["__ZTSPx"]=30892;var __ZTIPKx=Module["__ZTIPKx"]=30896;var __ZTSPKx=Module["__ZTSPKx"]=30912;var __ZTSy=Module["__ZTSy"]=30924;var __ZTIPy=Module["__ZTIPy"]=30928;var __ZTSPy=Module["__ZTSPy"]=30944;var __ZTIPKy=Module["__ZTIPKy"]=30948;var __ZTSPKy=Module["__ZTSPKy"]=30964;var __ZTIn=Module["__ZTIn"]=30968;var __ZTSn=Module["__ZTSn"]=30976;var __ZTIPn=Module["__ZTIPn"]=30980;var __ZTSPn=Module["__ZTSPn"]=30996;var __ZTIPKn=Module["__ZTIPKn"]=31e3;var __ZTSPKn=Module["__ZTSPKn"]=31016;var __ZTIo=Module["__ZTIo"]=31020;var __ZTSo=Module["__ZTSo"]=31028;var __ZTIPo=Module["__ZTIPo"]=31032;var __ZTSPo=Module["__ZTSPo"]=31048;var __ZTIPKo=Module["__ZTIPKo"]=31052;var __ZTSPKo=Module["__ZTSPKo"]=31068;var __ZTIDh=Module["__ZTIDh"]=31072;var __ZTSDh=Module["__ZTSDh"]=31080;var __ZTIPDh=Module["__ZTIPDh"]=31084;var __ZTSPDh=Module["__ZTSPDh"]=31100;var __ZTIPKDh=Module["__ZTIPKDh"]=31104;var __ZTSPKDh=Module["__ZTSPKDh"]=31120;var __ZTSf=Module["__ZTSf"]=31136;var __ZTIPf=Module["__ZTIPf"]=31140;var __ZTSPf=Module["__ZTSPf"]=31156;var __ZTIPKf=Module["__ZTIPKf"]=31160;var __ZTSPKf=Module["__ZTSPKf"]=31176;var __ZTSd=Module["__ZTSd"]=31188;var __ZTIPd=Module["__ZTIPd"]=31192;var __ZTSPd=Module["__ZTSPd"]=31208;var __ZTIPKd=Module["__ZTIPKd"]=31212;var __ZTSPKd=Module["__ZTSPKd"]=31228;var __ZTIe=Module["__ZTIe"]=31232;var __ZTSe=Module["__ZTSe"]=31240;var __ZTIPe=Module["__ZTIPe"]=31244;var __ZTSPe=Module["__ZTSPe"]=31260;var __ZTIPKe=Module["__ZTIPKe"]=31264;var __ZTSPKe=Module["__ZTSPKe"]=31280;var __ZTIg=Module["__ZTIg"]=31284;var __ZTSg=Module["__ZTSg"]=31292;var __ZTIPg=Module["__ZTIPg"]=31296;var __ZTSPg=Module["__ZTSPg"]=31312;var __ZTIPKg=Module["__ZTIPKg"]=31316;var __ZTSPKg=Module["__ZTSPKg"]=31332;var __ZTIDu=Module["__ZTIDu"]=31336;var __ZTSDu=Module["__ZTSDu"]=31344;var __ZTIPDu=Module["__ZTIPDu"]=31348;var __ZTSPDu=Module["__ZTSPDu"]=31364;var __ZTIPKDu=Module["__ZTIPKDu"]=31368;var __ZTSPKDu=Module["__ZTSPKDu"]=31384;var __ZTIDs=Module["__ZTIDs"]=31392;var __ZTSDs=Module["__ZTSDs"]=31400;var __ZTIPDs=Module["__ZTIPDs"]=31404;var __ZTSPDs=Module["__ZTSPDs"]=31420;var __ZTIPKDs=Module["__ZTIPKDs"]=31424;var __ZTSPKDs=Module["__ZTSPKDs"]=31440;var __ZTIDi=Module["__ZTIDi"]=31448;var __ZTSDi=Module["__ZTSDi"]=31456;var __ZTIPDi=Module["__ZTIPDi"]=31460;var __ZTSPDi=Module["__ZTSPDi"]=31476;var __ZTIPKDi=Module["__ZTIPKDi"]=31480;var __ZTSPKDi=Module["__ZTSPKDi"]=31496;var __ZTVN10__cxxabiv117__array_type_infoE=Module["__ZTVN10__cxxabiv117__array_type_infoE"]=31504;var __ZTIN10__cxxabiv117__array_type_infoE=Module["__ZTIN10__cxxabiv117__array_type_infoE"]=31532;var __ZTSN10__cxxabiv117__array_type_infoE=Module["__ZTSN10__cxxabiv117__array_type_infoE"]=31544;var __ZTVN10__cxxabiv120__function_type_infoE=Module["__ZTVN10__cxxabiv120__function_type_infoE"]=31580;var __ZTVN10__cxxabiv116__enum_type_infoE=Module["__ZTVN10__cxxabiv116__enum_type_infoE"]=31608;var __ZTIN10__cxxabiv116__enum_type_infoE=Module["__ZTIN10__cxxabiv116__enum_type_infoE"]=31636;var __ZTSN10__cxxabiv116__enum_type_infoE=Module["__ZTSN10__cxxabiv116__enum_type_infoE"]=31648;var __ZTIN10__cxxabiv120__si_class_type_infoE=Module["__ZTIN10__cxxabiv120__si_class_type_infoE"]=31764;var __ZTSN10__cxxabiv120__si_class_type_infoE=Module["__ZTSN10__cxxabiv120__si_class_type_infoE"]=31776;var __ZTIN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTIN10__cxxabiv121__vmi_class_type_infoE"]=31856;var __ZTSN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTSN10__cxxabiv121__vmi_class_type_infoE"]=31868;var __ZTVN10__cxxabiv117__pbase_type_infoE=Module["__ZTVN10__cxxabiv117__pbase_type_infoE"]=31908;var __ZTVN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTVN10__cxxabiv129__pointer_to_member_type_infoE"]=31964;var __ZTVSt9bad_alloc=Module["__ZTVSt9bad_alloc"]=31992;var __ZTVSt20bad_array_new_length=Module["__ZTVSt20bad_array_new_length"]=32012;var __ZTISt9bad_alloc=Module["__ZTISt9bad_alloc"]=32128;var __ZTSSt9exception=Module["__ZTSSt9exception"]=32060;var __ZTVSt13bad_exception=Module["__ZTVSt13bad_exception"]=32076;var __ZTISt13bad_exception=Module["__ZTISt13bad_exception"]=32096;var __ZTSSt13bad_exception=Module["__ZTSSt13bad_exception"]=32108;var __ZTSSt9bad_alloc=Module["__ZTSSt9bad_alloc"]=32140;var __ZTSSt20bad_array_new_length=Module["__ZTSSt20bad_array_new_length"]=32168;var __ZTISt11logic_error=Module["__ZTISt11logic_error"]=32288;var __ZTISt13runtime_error=Module["__ZTISt13runtime_error"]=32524;var __ZTVSt12domain_error=Module["__ZTVSt12domain_error"]=32236;var __ZTISt12domain_error=Module["__ZTISt12domain_error"]=32256;var __ZTSSt12domain_error=Module["__ZTSSt12domain_error"]=32268;var __ZTSSt11logic_error=Module["__ZTSSt11logic_error"]=32300;var __ZTVSt16invalid_argument=Module["__ZTVSt16invalid_argument"]=32316;var __ZTISt16invalid_argument=Module["__ZTISt16invalid_argument"]=32336;var __ZTSSt16invalid_argument=Module["__ZTSSt16invalid_argument"]=32348;var __ZTSSt12length_error=Module["__ZTSSt12length_error"]=32404;var __ZTSSt12out_of_range=Module["__ZTSSt12out_of_range"]=32456;var __ZTVSt11range_error=Module["__ZTVSt11range_error"]=32476;var __ZTISt11range_error=Module["__ZTISt11range_error"]=32496;var __ZTSSt11range_error=Module["__ZTSSt11range_error"]=32508;var __ZTSSt13runtime_error=Module["__ZTSSt13runtime_error"]=32536;var __ZTVSt14overflow_error=Module["__ZTVSt14overflow_error"]=32556;var __ZTISt14overflow_error=Module["__ZTISt14overflow_error"]=32576;var __ZTSSt14overflow_error=Module["__ZTSSt14overflow_error"]=32588;var __ZTVSt15underflow_error=Module["__ZTVSt15underflow_error"]=32608;var __ZTISt15underflow_error=Module["__ZTISt15underflow_error"]=32628;var __ZTSSt15underflow_error=Module["__ZTSSt15underflow_error"]=32640;var __ZTVSt8bad_cast=Module["__ZTVSt8bad_cast"]=32660;var __ZTVSt10bad_typeid=Module["__ZTVSt10bad_typeid"]=32680;var __ZTISt8bad_cast=Module["__ZTISt8bad_cast"]=32740;var __ZTISt10bad_typeid=Module["__ZTISt10bad_typeid"]=32764;var __ZTVSt9type_info=Module["__ZTVSt9type_info"]=32700;var __ZTSSt9type_info=Module["__ZTSSt9type_info"]=32724;var __ZTSSt8bad_cast=Module["__ZTSSt8bad_cast"]=32752;var __ZTSSt10bad_typeid=Module["__ZTSSt10bad_typeid"]=32776;var wasmImports={f:___cxa_throw,p:__abort_js,k:__embind_register_bigint,m:__embind_register_bool,l:__embind_register_class,h:__embind_register_class_constructor,e:__embind_register_class_function,a:__embind_register_class_property,r:__embind_register_emval,j:__embind_register_float,c:__embind_register_function,d:__embind_register_integer,b:__embind_register_memory_view,s:__embind_register_std_string,g:__embind_register_std_wstring,n:__embind_register_void,o:__emval_take_value,t:_emscripten_date_now,q:_emscripten_resize_heap,i:_fd_write};var wasmExports;createWasm();function run(){if(runDependencies>0){dependenciesFulfilled=run;return}preRun();if(runDependencies>0){dependenciesFulfilled=run;return}function doRun(){Module["calledRun"]=true;if(ABORT)return;initRuntime();Module["onRuntimeInitialized"]?.();postRun()}if(Module["setStatus"]){Module["setStatus"]("Running...");setTimeout(()=>{setTimeout(()=>Module["setStatus"](""),1);doRun()},1)}else{doRun()}}function preInit(){if(Module["preInit"]){if(typeof Module["preInit"]=="function")Module["preInit"]=[Module["preInit"]];while(Module["preInit"].length>0){Module["preInit"].shift()()}}}preInit();run(); +var Module=typeof Module!="undefined"?Module:{};var ENVIRONMENT_IS_WEB=typeof window=="object";var ENVIRONMENT_IS_WORKER=typeof importScripts=="function";var ENVIRONMENT_IS_NODE=typeof process=="object"&&typeof process.versions=="object"&&typeof process.versions.node=="string";if(ENVIRONMENT_IS_NODE){}var moduleOverrides=Object.assign({},Module);var arguments_=[];var thisProgram="./this.program";var quit_=(status,toThrow)=>{throw toThrow};var scriptDirectory="";function locateFile(path){if(Module["locateFile"]){return Module["locateFile"](path,scriptDirectory)}return scriptDirectory+path}var readAsync,readBinary;if(ENVIRONMENT_IS_NODE){var fs=require("fs");var nodePath=require("path");scriptDirectory=__dirname+"/";readBinary=filename=>{filename=isFileURI(filename)?new URL(filename):nodePath.normalize(filename);var ret=fs.readFileSync(filename);return ret};readAsync=(filename,binary=true)=>{filename=isFileURI(filename)?new URL(filename):nodePath.normalize(filename);return new Promise((resolve,reject)=>{fs.readFile(filename,binary?undefined:"utf8",(err,data)=>{if(err)reject(err);else resolve(binary?data.buffer:data)})})};if(!Module["thisProgram"]&&process.argv.length>1){thisProgram=process.argv[1].replace(/\\/g,"/")}arguments_=process.argv.slice(2);if(typeof module!="undefined"){module["exports"]=Module}process.on("uncaughtException",ex=>{if(ex!=="unwind"&&!(ex instanceof ExitStatus)&&!(ex.context instanceof ExitStatus)){throw ex}});quit_=(status,toThrow)=>{process.exitCode=status;throw toThrow}}else if(ENVIRONMENT_IS_WEB||ENVIRONMENT_IS_WORKER){if(ENVIRONMENT_IS_WORKER){scriptDirectory=self.location.href}else if(typeof document!="undefined"&&document.currentScript){scriptDirectory=document.currentScript.src}if(scriptDirectory.startsWith("blob:")){scriptDirectory=""}else{scriptDirectory=scriptDirectory.substr(0,scriptDirectory.replace(/[?#].*/,"").lastIndexOf("/")+1)}{if(ENVIRONMENT_IS_WORKER){readBinary=url=>{var xhr=new XMLHttpRequest;xhr.open("GET",url,false);xhr.responseType="arraybuffer";xhr.send(null);return new Uint8Array(xhr.response)}}readAsync=url=>{if(isFileURI(url)){return new Promise((reject,resolve)=>{var xhr=new XMLHttpRequest;xhr.open("GET",url,true);xhr.responseType="arraybuffer";xhr.onload=()=>{if(xhr.status==200||xhr.status==0&&xhr.response){resolve(xhr.response)}reject(xhr.status)};xhr.onerror=reject;xhr.send(null)})}return fetch(url,{credentials:"same-origin"}).then(response=>{if(response.ok){return response.arrayBuffer()}return Promise.reject(new Error(response.status+" : "+response.url))})}}}else{}var out=Module["print"]||console.log.bind(console);var err=Module["printErr"]||console.error.bind(console);Object.assign(Module,moduleOverrides);moduleOverrides=null;if(Module["arguments"])arguments_=Module["arguments"];if(Module["thisProgram"])thisProgram=Module["thisProgram"];if(Module["quit"])quit_=Module["quit"];var wasmBinary;if(Module["wasmBinary"])wasmBinary=Module["wasmBinary"];var wasmMemory;var ABORT=false;var EXITSTATUS;var HEAP8,HEAPU8,HEAP16,HEAPU16,HEAP32,HEAPU32,HEAPF32,HEAPF64;function updateMemoryViews(){var b=wasmMemory.buffer;Module["HEAP8"]=HEAP8=new Int8Array(b);Module["HEAP16"]=HEAP16=new Int16Array(b);Module["HEAPU8"]=HEAPU8=new Uint8Array(b);Module["HEAPU16"]=HEAPU16=new Uint16Array(b);Module["HEAP32"]=HEAP32=new Int32Array(b);Module["HEAPU32"]=HEAPU32=new Uint32Array(b);Module["HEAPF32"]=HEAPF32=new Float32Array(b);Module["HEAPF64"]=HEAPF64=new Float64Array(b)}var __ATPRERUN__=[];var __ATINIT__=[];var __ATPOSTRUN__=[];var runtimeInitialized=false;function preRun(){if(Module["preRun"]){if(typeof Module["preRun"]=="function")Module["preRun"]=[Module["preRun"]];while(Module["preRun"].length){addOnPreRun(Module["preRun"].shift())}}callRuntimeCallbacks(__ATPRERUN__)}function initRuntime(){runtimeInitialized=true;callRuntimeCallbacks(__ATINIT__)}function postRun(){if(Module["postRun"]){if(typeof Module["postRun"]=="function")Module["postRun"]=[Module["postRun"]];while(Module["postRun"].length){addOnPostRun(Module["postRun"].shift())}}callRuntimeCallbacks(__ATPOSTRUN__)}function addOnPreRun(cb){__ATPRERUN__.unshift(cb)}function addOnInit(cb){__ATINIT__.unshift(cb)}function addOnPostRun(cb){__ATPOSTRUN__.unshift(cb)}var runDependencies=0;var runDependencyWatcher=null;var dependenciesFulfilled=null;function addRunDependency(id){runDependencies++;Module["monitorRunDependencies"]?.(runDependencies)}function removeRunDependency(id){runDependencies--;Module["monitorRunDependencies"]?.(runDependencies);if(runDependencies==0){if(runDependencyWatcher!==null){clearInterval(runDependencyWatcher);runDependencyWatcher=null}if(dependenciesFulfilled){var callback=dependenciesFulfilled;dependenciesFulfilled=null;callback()}}}function abort(what){Module["onAbort"]?.(what);what="Aborted("+what+")";err(what);ABORT=true;EXITSTATUS=1;what+=". Build with -sASSERTIONS for more info.";var e=new WebAssembly.RuntimeError(what);throw e}var dataURIPrefix="data:application/octet-stream;base64,";var isDataURI=filename=>filename.startsWith(dataURIPrefix);var isFileURI=filename=>filename.startsWith("file://");function findWasmBinary(){var f="index.wasm";if(!isDataURI(f)){return locateFile(f)}return f}var wasmBinaryFile;function getBinarySync(file){if(file==wasmBinaryFile&&wasmBinary){return new Uint8Array(wasmBinary)}if(readBinary){return readBinary(file)}throw"both async and sync fetching of the wasm failed"}function getBinaryPromise(binaryFile){if(!wasmBinary){return readAsync(binaryFile).then(response=>new Uint8Array(response),()=>getBinarySync(binaryFile))}return Promise.resolve().then(()=>getBinarySync(binaryFile))}function instantiateArrayBuffer(binaryFile,imports,receiver){return getBinaryPromise(binaryFile).then(binary=>WebAssembly.instantiate(binary,imports)).then(receiver,reason=>{err(`failed to asynchronously prepare wasm: ${reason}`);abort(reason)})}function instantiateAsync(binary,binaryFile,imports,callback){if(!binary&&typeof WebAssembly.instantiateStreaming=="function"&&!isDataURI(binaryFile)&&!isFileURI(binaryFile)&&!ENVIRONMENT_IS_NODE&&typeof fetch=="function"){return fetch(binaryFile,{credentials:"same-origin"}).then(response=>{var result=WebAssembly.instantiateStreaming(response,imports);return result.then(callback,function(reason){err(`wasm streaming compile failed: ${reason}`);err("falling back to ArrayBuffer instantiation");return instantiateArrayBuffer(binaryFile,imports,callback)})})}return instantiateArrayBuffer(binaryFile,imports,callback)}function getWasmImports(){return{a:wasmImports}}function createWasm(){var info=getWasmImports();function receiveInstance(instance,module){wasmExports=instance.exports;wasmMemory=wasmExports["w"];updateMemoryViews();wasmTable=wasmExports["C"];addOnInit(wasmExports["x"]);removeRunDependency("wasm-instantiate");return wasmExports}addRunDependency("wasm-instantiate");function receiveInstantiationResult(result){receiveInstance(result["instance"])}if(Module["instantiateWasm"]){try{return Module["instantiateWasm"](info,receiveInstance)}catch(e){err(`Module.instantiateWasm callback failed with error: ${e}`);return false}}if(!wasmBinaryFile)wasmBinaryFile=findWasmBinary();instantiateAsync(wasmBinary,wasmBinaryFile,info,receiveInstantiationResult);return{}}function ExitStatus(status){this.name="ExitStatus";this.message=`Program terminated with exit(${status})`;this.status=status}var callRuntimeCallbacks=callbacks=>{while(callbacks.length>0){callbacks.shift()(Module)}};var noExitRuntime=Module["noExitRuntime"]||true;class ExceptionInfo{constructor(excPtr){this.excPtr=excPtr;this.ptr=excPtr-24}set_type(type){HEAPU32[this.ptr+4>>2]=type}get_type(){return HEAPU32[this.ptr+4>>2]}set_destructor(destructor){HEAPU32[this.ptr+8>>2]=destructor}get_destructor(){return HEAPU32[this.ptr+8>>2]}set_caught(caught){caught=caught?1:0;HEAP8[this.ptr+12]=caught}get_caught(){return HEAP8[this.ptr+12]!=0}set_rethrown(rethrown){rethrown=rethrown?1:0;HEAP8[this.ptr+13]=rethrown}get_rethrown(){return HEAP8[this.ptr+13]!=0}init(type,destructor){this.set_adjusted_ptr(0);this.set_type(type);this.set_destructor(destructor)}set_adjusted_ptr(adjustedPtr){HEAPU32[this.ptr+16>>2]=adjustedPtr}get_adjusted_ptr(){return HEAPU32[this.ptr+16>>2]}get_exception_ptr(){var isPointer=___cxa_is_pointer_type(this.get_type());if(isPointer){return HEAPU32[this.excPtr>>2]}var adjusted=this.get_adjusted_ptr();if(adjusted!==0)return adjusted;return this.excPtr}}var exceptionLast=0;var uncaughtExceptionCount=0;var ___cxa_throw=(ptr,type,destructor)=>{var info=new ExceptionInfo(ptr);info.init(type,destructor);exceptionLast=ptr;uncaughtExceptionCount++;throw exceptionLast};var __abort_js=()=>{abort("")};var __embind_register_bigint=(primitiveType,name,size,minRange,maxRange)=>{};var embind_init_charCodes=()=>{var codes=new Array(256);for(var i=0;i<256;++i){codes[i]=String.fromCharCode(i)}embind_charCodes=codes};var embind_charCodes;var readLatin1String=ptr=>{var ret="";var c=ptr;while(HEAPU8[c]){ret+=embind_charCodes[HEAPU8[c++]]}return ret};var awaitingDependencies={};var registeredTypes={};var typeDependencies={};var BindingError;var throwBindingError=message=>{throw new BindingError(message)};var InternalError;var throwInternalError=message=>{throw new InternalError(message)};var whenDependentTypesAreResolved=(myTypes,dependentTypes,getTypeConverters)=>{myTypes.forEach(function(type){typeDependencies[type]=dependentTypes});function onComplete(typeConverters){var myTypeConverters=getTypeConverters(typeConverters);if(myTypeConverters.length!==myTypes.length){throwInternalError("Mismatched type converter count")}for(var i=0;i{if(registeredTypes.hasOwnProperty(dt)){typeConverters[i]=registeredTypes[dt]}else{unregisteredTypes.push(dt);if(!awaitingDependencies.hasOwnProperty(dt)){awaitingDependencies[dt]=[]}awaitingDependencies[dt].push(()=>{typeConverters[i]=registeredTypes[dt];++registered;if(registered===unregisteredTypes.length){onComplete(typeConverters)}})}});if(0===unregisteredTypes.length){onComplete(typeConverters)}};function sharedRegisterType(rawType,registeredInstance,options={}){var name=registeredInstance.name;if(!rawType){throwBindingError(`type "${name}" must have a positive integer typeid pointer`)}if(registeredTypes.hasOwnProperty(rawType)){if(options.ignoreDuplicateRegistrations){return}else{throwBindingError(`Cannot register type '${name}' twice`)}}registeredTypes[rawType]=registeredInstance;delete typeDependencies[rawType];if(awaitingDependencies.hasOwnProperty(rawType)){var callbacks=awaitingDependencies[rawType];delete awaitingDependencies[rawType];callbacks.forEach(cb=>cb())}}function registerType(rawType,registeredInstance,options={}){if(!("argPackAdvance"in registeredInstance)){throw new TypeError("registerType registeredInstance requires argPackAdvance")}return sharedRegisterType(rawType,registeredInstance,options)}var GenericWireTypeSize=8;var __embind_register_bool=(rawType,name,trueValue,falseValue)=>{name=readLatin1String(name);registerType(rawType,{name:name,fromWireType:function(wt){return!!wt},toWireType:function(destructors,o){return o?trueValue:falseValue},argPackAdvance:GenericWireTypeSize,readValueFromPointer:function(pointer){return this["fromWireType"](HEAPU8[pointer])},destructorFunction:null})};var shallowCopyInternalPointer=o=>({count:o.count,deleteScheduled:o.deleteScheduled,preservePointerOnDelete:o.preservePointerOnDelete,ptr:o.ptr,ptrType:o.ptrType,smartPtr:o.smartPtr,smartPtrType:o.smartPtrType});var throwInstanceAlreadyDeleted=obj=>{function getInstanceTypeName(handle){return handle.$$.ptrType.registeredClass.name}throwBindingError(getInstanceTypeName(obj)+" instance already deleted")};var finalizationRegistry=false;var detachFinalizer=handle=>{};var runDestructor=$$=>{if($$.smartPtr){$$.smartPtrType.rawDestructor($$.smartPtr)}else{$$.ptrType.registeredClass.rawDestructor($$.ptr)}};var releaseClassHandle=$$=>{$$.count.value-=1;var toDelete=0===$$.count.value;if(toDelete){runDestructor($$)}};var downcastPointer=(ptr,ptrClass,desiredClass)=>{if(ptrClass===desiredClass){return ptr}if(undefined===desiredClass.baseClass){return null}var rv=downcastPointer(ptr,ptrClass,desiredClass.baseClass);if(rv===null){return null}return desiredClass.downcast(rv)};var registeredPointers={};var getInheritedInstanceCount=()=>Object.keys(registeredInstances).length;var getLiveInheritedInstances=()=>{var rv=[];for(var k in registeredInstances){if(registeredInstances.hasOwnProperty(k)){rv.push(registeredInstances[k])}}return rv};var deletionQueue=[];var flushPendingDeletes=()=>{while(deletionQueue.length){var obj=deletionQueue.pop();obj.$$.deleteScheduled=false;obj["delete"]()}};var delayFunction;var setDelayFunction=fn=>{delayFunction=fn;if(deletionQueue.length&&delayFunction){delayFunction(flushPendingDeletes)}};var init_embind=()=>{Module["getInheritedInstanceCount"]=getInheritedInstanceCount;Module["getLiveInheritedInstances"]=getLiveInheritedInstances;Module["flushPendingDeletes"]=flushPendingDeletes;Module["setDelayFunction"]=setDelayFunction};var registeredInstances={};var getBasestPointer=(class_,ptr)=>{if(ptr===undefined){throwBindingError("ptr should not be undefined")}while(class_.baseClass){ptr=class_.upcast(ptr);class_=class_.baseClass}return ptr};var getInheritedInstance=(class_,ptr)=>{ptr=getBasestPointer(class_,ptr);return registeredInstances[ptr]};var makeClassHandle=(prototype,record)=>{if(!record.ptrType||!record.ptr){throwInternalError("makeClassHandle requires ptr and ptrType")}var hasSmartPtrType=!!record.smartPtrType;var hasSmartPtr=!!record.smartPtr;if(hasSmartPtrType!==hasSmartPtr){throwInternalError("Both smartPtrType and smartPtr must be specified")}record.count={value:1};return attachFinalizer(Object.create(prototype,{$$:{value:record,writable:true}}))};function RegisteredPointer_fromWireType(ptr){var rawPointer=this.getPointee(ptr);if(!rawPointer){this.destructor(ptr);return null}var registeredInstance=getInheritedInstance(this.registeredClass,rawPointer);if(undefined!==registeredInstance){if(0===registeredInstance.$$.count.value){registeredInstance.$$.ptr=rawPointer;registeredInstance.$$.smartPtr=ptr;return registeredInstance["clone"]()}else{var rv=registeredInstance["clone"]();this.destructor(ptr);return rv}}function makeDefaultHandle(){if(this.isSmartPointer){return makeClassHandle(this.registeredClass.instancePrototype,{ptrType:this.pointeeType,ptr:rawPointer,smartPtrType:this,smartPtr:ptr})}else{return makeClassHandle(this.registeredClass.instancePrototype,{ptrType:this,ptr:ptr})}}var actualType=this.registeredClass.getActualType(rawPointer);var registeredPointerRecord=registeredPointers[actualType];if(!registeredPointerRecord){return makeDefaultHandle.call(this)}var toType;if(this.isConst){toType=registeredPointerRecord.constPointerType}else{toType=registeredPointerRecord.pointerType}var dp=downcastPointer(rawPointer,this.registeredClass,toType.registeredClass);if(dp===null){return makeDefaultHandle.call(this)}if(this.isSmartPointer){return makeClassHandle(toType.registeredClass.instancePrototype,{ptrType:toType,ptr:dp,smartPtrType:this,smartPtr:ptr})}else{return makeClassHandle(toType.registeredClass.instancePrototype,{ptrType:toType,ptr:dp})}}var attachFinalizer=handle=>{if("undefined"===typeof FinalizationRegistry){attachFinalizer=handle=>handle;return handle}finalizationRegistry=new FinalizationRegistry(info=>{releaseClassHandle(info.$$)});attachFinalizer=handle=>{var $$=handle.$$;var hasSmartPtr=!!$$.smartPtr;if(hasSmartPtr){var info={$$:$$};finalizationRegistry.register(handle,info,handle)}return handle};detachFinalizer=handle=>finalizationRegistry.unregister(handle);return attachFinalizer(handle)};var init_ClassHandle=()=>{Object.assign(ClassHandle.prototype,{isAliasOf(other){if(!(this instanceof ClassHandle)){return false}if(!(other instanceof ClassHandle)){return false}var leftClass=this.$$.ptrType.registeredClass;var left=this.$$.ptr;other.$$=other.$$;var rightClass=other.$$.ptrType.registeredClass;var right=other.$$.ptr;while(leftClass.baseClass){left=leftClass.upcast(left);leftClass=leftClass.baseClass}while(rightClass.baseClass){right=rightClass.upcast(right);rightClass=rightClass.baseClass}return leftClass===rightClass&&left===right},clone(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.preservePointerOnDelete){this.$$.count.value+=1;return this}else{var clone=attachFinalizer(Object.create(Object.getPrototypeOf(this),{$$:{value:shallowCopyInternalPointer(this.$$)}}));clone.$$.count.value+=1;clone.$$.deleteScheduled=false;return clone}},delete(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.deleteScheduled&&!this.$$.preservePointerOnDelete){throwBindingError("Object already scheduled for deletion")}detachFinalizer(this);releaseClassHandle(this.$$);if(!this.$$.preservePointerOnDelete){this.$$.smartPtr=undefined;this.$$.ptr=undefined}},isDeleted(){return!this.$$.ptr},deleteLater(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.deleteScheduled&&!this.$$.preservePointerOnDelete){throwBindingError("Object already scheduled for deletion")}deletionQueue.push(this);if(deletionQueue.length===1&&delayFunction){delayFunction(flushPendingDeletes)}this.$$.deleteScheduled=true;return this}})};function ClassHandle(){}var createNamedFunction=(name,body)=>Object.defineProperty(body,"name",{value:name});var ensureOverloadTable=(proto,methodName,humanName)=>{if(undefined===proto[methodName].overloadTable){var prevFunc=proto[methodName];proto[methodName]=function(...args){if(!proto[methodName].overloadTable.hasOwnProperty(args.length)){throwBindingError(`Function '${humanName}' called with an invalid number of arguments (${args.length}) - expects one of (${proto[methodName].overloadTable})!`)}return proto[methodName].overloadTable[args.length].apply(this,args)};proto[methodName].overloadTable=[];proto[methodName].overloadTable[prevFunc.argCount]=prevFunc}};var exposePublicSymbol=(name,value,numArguments)=>{if(Module.hasOwnProperty(name)){if(undefined===numArguments||undefined!==Module[name].overloadTable&&undefined!==Module[name].overloadTable[numArguments]){throwBindingError(`Cannot register public name '${name}' twice`)}ensureOverloadTable(Module,name,name);if(Module.hasOwnProperty(numArguments)){throwBindingError(`Cannot register multiple overloads of a function with the same number of arguments (${numArguments})!`)}Module[name].overloadTable[numArguments]=value}else{Module[name]=value;if(undefined!==numArguments){Module[name].numArguments=numArguments}}};var char_0=48;var char_9=57;var makeLegalFunctionName=name=>{if(undefined===name){return"_unknown"}name=name.replace(/[^a-zA-Z0-9_]/g,"$");var f=name.charCodeAt(0);if(f>=char_0&&f<=char_9){return`_${name}`}return name};function RegisteredClass(name,constructor,instancePrototype,rawDestructor,baseClass,getActualType,upcast,downcast){this.name=name;this.constructor=constructor;this.instancePrototype=instancePrototype;this.rawDestructor=rawDestructor;this.baseClass=baseClass;this.getActualType=getActualType;this.upcast=upcast;this.downcast=downcast;this.pureVirtualFunctions=[]}var upcastPointer=(ptr,ptrClass,desiredClass)=>{while(ptrClass!==desiredClass){if(!ptrClass.upcast){throwBindingError(`Expected null or instance of ${desiredClass.name}, got an instance of ${ptrClass.name}`)}ptr=ptrClass.upcast(ptr);ptrClass=ptrClass.baseClass}return ptr};function constNoSmartPtrRawPointerToWireType(destructors,handle){if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}return 0}if(!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;var ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);return ptr}function genericPointerToWireType(destructors,handle){var ptr;if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}if(this.isSmartPointer){ptr=this.rawConstructor();if(destructors!==null){destructors.push(this.rawDestructor,ptr)}return ptr}else{return 0}}if(!handle||!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}if(!this.isConst&&handle.$$.ptrType.isConst){throwBindingError(`Cannot convert argument of type ${handle.$$.smartPtrType?handle.$$.smartPtrType.name:handle.$$.ptrType.name} to parameter type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);if(this.isSmartPointer){if(undefined===handle.$$.smartPtr){throwBindingError("Passing raw pointer to smart pointer is illegal")}switch(this.sharingPolicy){case 0:if(handle.$$.smartPtrType===this){ptr=handle.$$.smartPtr}else{throwBindingError(`Cannot convert argument of type ${handle.$$.smartPtrType?handle.$$.smartPtrType.name:handle.$$.ptrType.name} to parameter type ${this.name}`)}break;case 1:ptr=handle.$$.smartPtr;break;case 2:if(handle.$$.smartPtrType===this){ptr=handle.$$.smartPtr}else{var clonedHandle=handle["clone"]();ptr=this.rawShare(ptr,Emval.toHandle(()=>clonedHandle["delete"]()));if(destructors!==null){destructors.push(this.rawDestructor,ptr)}}break;default:throwBindingError("Unsupporting sharing policy")}}return ptr}function nonConstNoSmartPtrRawPointerToWireType(destructors,handle){if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}return 0}if(!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}if(handle.$$.ptrType.isConst){throwBindingError(`Cannot convert argument of type ${handle.$$.ptrType.name} to parameter type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;var ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);return ptr}function readPointer(pointer){return this["fromWireType"](HEAPU32[pointer>>2])}var init_RegisteredPointer=()=>{Object.assign(RegisteredPointer.prototype,{getPointee(ptr){if(this.rawGetPointee){ptr=this.rawGetPointee(ptr)}return ptr},destructor(ptr){this.rawDestructor?.(ptr)},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,fromWireType:RegisteredPointer_fromWireType})};function RegisteredPointer(name,registeredClass,isReference,isConst,isSmartPointer,pointeeType,sharingPolicy,rawGetPointee,rawConstructor,rawShare,rawDestructor){this.name=name;this.registeredClass=registeredClass;this.isReference=isReference;this.isConst=isConst;this.isSmartPointer=isSmartPointer;this.pointeeType=pointeeType;this.sharingPolicy=sharingPolicy;this.rawGetPointee=rawGetPointee;this.rawConstructor=rawConstructor;this.rawShare=rawShare;this.rawDestructor=rawDestructor;if(!isSmartPointer&®isteredClass.baseClass===undefined){if(isConst){this["toWireType"]=constNoSmartPtrRawPointerToWireType;this.destructorFunction=null}else{this["toWireType"]=nonConstNoSmartPtrRawPointerToWireType;this.destructorFunction=null}}else{this["toWireType"]=genericPointerToWireType}}var replacePublicSymbol=(name,value,numArguments)=>{if(!Module.hasOwnProperty(name)){throwInternalError("Replacing nonexistent public symbol")}if(undefined!==Module[name].overloadTable&&undefined!==numArguments){Module[name].overloadTable[numArguments]=value}else{Module[name]=value;Module[name].argCount=numArguments}};var dynCallLegacy=(sig,ptr,args)=>{sig=sig.replace(/p/g,"i");var f=Module["dynCall_"+sig];return f(ptr,...args)};var wasmTableMirror=[];var wasmTable;var getWasmTableEntry=funcPtr=>{var func=wasmTableMirror[funcPtr];if(!func){if(funcPtr>=wasmTableMirror.length)wasmTableMirror.length=funcPtr+1;wasmTableMirror[funcPtr]=func=wasmTable.get(funcPtr)}return func};var dynCall=(sig,ptr,args=[])=>{if(sig.includes("j")){return dynCallLegacy(sig,ptr,args)}var rtn=getWasmTableEntry(ptr)(...args);return rtn};var getDynCaller=(sig,ptr)=>(...args)=>dynCall(sig,ptr,args);var embind__requireFunction=(signature,rawFunction)=>{signature=readLatin1String(signature);function makeDynCaller(){if(signature.includes("j")){return getDynCaller(signature,rawFunction)}return getWasmTableEntry(rawFunction)}var fp=makeDynCaller();if(typeof fp!="function"){throwBindingError(`unknown function pointer with signature ${signature}: ${rawFunction}`)}return fp};var extendError=(baseErrorType,errorName)=>{var errorClass=createNamedFunction(errorName,function(message){this.name=errorName;this.message=message;var stack=new Error(message).stack;if(stack!==undefined){this.stack=this.toString()+"\n"+stack.replace(/^Error(:[^\n]*)?\n/,"")}});errorClass.prototype=Object.create(baseErrorType.prototype);errorClass.prototype.constructor=errorClass;errorClass.prototype.toString=function(){if(this.message===undefined){return this.name}else{return`${this.name}: ${this.message}`}};return errorClass};var UnboundTypeError;var getTypeName=type=>{var ptr=___getTypeName(type);var rv=readLatin1String(ptr);_free(ptr);return rv};var throwUnboundTypeError=(message,types)=>{var unboundTypes=[];var seen={};function visit(type){if(seen[type]){return}if(registeredTypes[type]){return}if(typeDependencies[type]){typeDependencies[type].forEach(visit);return}unboundTypes.push(type);seen[type]=true}types.forEach(visit);throw new UnboundTypeError(`${message}: `+unboundTypes.map(getTypeName).join([", "]))};var __embind_register_class=(rawType,rawPointerType,rawConstPointerType,baseClassRawType,getActualTypeSignature,getActualType,upcastSignature,upcast,downcastSignature,downcast,name,destructorSignature,rawDestructor)=>{name=readLatin1String(name);getActualType=embind__requireFunction(getActualTypeSignature,getActualType);upcast&&=embind__requireFunction(upcastSignature,upcast);downcast&&=embind__requireFunction(downcastSignature,downcast);rawDestructor=embind__requireFunction(destructorSignature,rawDestructor);var legalFunctionName=makeLegalFunctionName(name);exposePublicSymbol(legalFunctionName,function(){throwUnboundTypeError(`Cannot construct ${name} due to unbound types`,[baseClassRawType])});whenDependentTypesAreResolved([rawType,rawPointerType,rawConstPointerType],baseClassRawType?[baseClassRawType]:[],base=>{base=base[0];var baseClass;var basePrototype;if(baseClassRawType){baseClass=base.registeredClass;basePrototype=baseClass.instancePrototype}else{basePrototype=ClassHandle.prototype}var constructor=createNamedFunction(name,function(...args){if(Object.getPrototypeOf(this)!==instancePrototype){throw new BindingError("Use 'new' to construct "+name)}if(undefined===registeredClass.constructor_body){throw new BindingError(name+" has no accessible constructor")}var body=registeredClass.constructor_body[args.length];if(undefined===body){throw new BindingError(`Tried to invoke ctor of ${name} with invalid number of parameters (${args.length}) - expected (${Object.keys(registeredClass.constructor_body).toString()}) parameters instead!`)}return body.apply(this,args)});var instancePrototype=Object.create(basePrototype,{constructor:{value:constructor}});constructor.prototype=instancePrototype;var registeredClass=new RegisteredClass(name,constructor,instancePrototype,rawDestructor,baseClass,getActualType,upcast,downcast);if(registeredClass.baseClass){registeredClass.baseClass.__derivedClasses??=[];registeredClass.baseClass.__derivedClasses.push(registeredClass)}var referenceConverter=new RegisteredPointer(name,registeredClass,true,false,false);var pointerConverter=new RegisteredPointer(name+"*",registeredClass,false,false,false);var constPointerConverter=new RegisteredPointer(name+" const*",registeredClass,false,true,false);registeredPointers[rawType]={pointerType:pointerConverter,constPointerType:constPointerConverter};replacePublicSymbol(legalFunctionName,constructor);return[referenceConverter,pointerConverter,constPointerConverter]})};var heap32VectorToArray=(count,firstElement)=>{var array=[];for(var i=0;i>2])}return array};var runDestructors=destructors=>{while(destructors.length){var ptr=destructors.pop();var del=destructors.pop();del(ptr)}};function usesDestructorStack(argTypes){for(var i=1;i0?", ":"")+argsListWired}invokerFnBody+=(returns||isAsync?"var rv = ":"")+"invoker(fn"+(argsListWired.length>0?", ":"")+argsListWired+");\n";if(needsDestructorStack){invokerFnBody+="runDestructors(destructors);\n"}else{for(var i=isClassMethodFunc?1:2;i{var rawArgTypes=heap32VectorToArray(argCount,rawArgTypesAddr);invoker=embind__requireFunction(invokerSignature,invoker);whenDependentTypesAreResolved([],[rawClassType],classType=>{classType=classType[0];var humanName=`constructor ${classType.name}`;if(undefined===classType.registeredClass.constructor_body){classType.registeredClass.constructor_body=[]}if(undefined!==classType.registeredClass.constructor_body[argCount-1]){throw new BindingError(`Cannot register multiple constructors with identical number of parameters (${argCount-1}) for class '${classType.name}'! Overload resolution is currently only performed using the parameter count, not actual type info!`)}classType.registeredClass.constructor_body[argCount-1]=()=>{throwUnboundTypeError(`Cannot construct ${classType.name} due to unbound types`,rawArgTypes)};whenDependentTypesAreResolved([],rawArgTypes,argTypes=>{argTypes.splice(1,0,null);classType.registeredClass.constructor_body[argCount-1]=craftInvokerFunction(humanName,argTypes,null,invoker,rawConstructor);return[]});return[]})};var getFunctionName=signature=>{signature=signature.trim();const argsIndex=signature.indexOf("(");if(argsIndex!==-1){return signature.substr(0,argsIndex)}else{return signature}};var __embind_register_class_function=(rawClassType,methodName,argCount,rawArgTypesAddr,invokerSignature,rawInvoker,context,isPureVirtual,isAsync)=>{var rawArgTypes=heap32VectorToArray(argCount,rawArgTypesAddr);methodName=readLatin1String(methodName);methodName=getFunctionName(methodName);rawInvoker=embind__requireFunction(invokerSignature,rawInvoker);whenDependentTypesAreResolved([],[rawClassType],classType=>{classType=classType[0];var humanName=`${classType.name}.${methodName}`;if(methodName.startsWith("@@")){methodName=Symbol[methodName.substring(2)]}if(isPureVirtual){classType.registeredClass.pureVirtualFunctions.push(methodName)}function unboundTypesHandler(){throwUnboundTypeError(`Cannot call ${humanName} due to unbound types`,rawArgTypes)}var proto=classType.registeredClass.instancePrototype;var method=proto[methodName];if(undefined===method||undefined===method.overloadTable&&method.className!==classType.name&&method.argCount===argCount-2){unboundTypesHandler.argCount=argCount-2;unboundTypesHandler.className=classType.name;proto[methodName]=unboundTypesHandler}else{ensureOverloadTable(proto,methodName,humanName);proto[methodName].overloadTable[argCount-2]=unboundTypesHandler}whenDependentTypesAreResolved([],rawArgTypes,argTypes=>{var memberFunction=craftInvokerFunction(humanName,argTypes,classType,rawInvoker,context,isAsync);if(undefined===proto[methodName].overloadTable){memberFunction.argCount=argCount-2;proto[methodName]=memberFunction}else{proto[methodName].overloadTable[argCount-2]=memberFunction}return[]});return[]})};var validateThis=(this_,classType,humanName)=>{if(!(this_ instanceof Object)){throwBindingError(`${humanName} with invalid "this": ${this_}`)}if(!(this_ instanceof classType.registeredClass.constructor)){throwBindingError(`${humanName} incompatible with "this" of type ${this_.constructor.name}`)}if(!this_.$$.ptr){throwBindingError(`cannot call emscripten binding method ${humanName} on deleted object`)}return upcastPointer(this_.$$.ptr,this_.$$.ptrType.registeredClass,classType.registeredClass)};var __embind_register_class_property=(classType,fieldName,getterReturnType,getterSignature,getter,getterContext,setterArgumentType,setterSignature,setter,setterContext)=>{fieldName=readLatin1String(fieldName);getter=embind__requireFunction(getterSignature,getter);whenDependentTypesAreResolved([],[classType],classType=>{classType=classType[0];var humanName=`${classType.name}.${fieldName}`;var desc={get(){throwUnboundTypeError(`Cannot access ${humanName} due to unbound types`,[getterReturnType,setterArgumentType])},enumerable:true,configurable:true};if(setter){desc.set=()=>throwUnboundTypeError(`Cannot access ${humanName} due to unbound types`,[getterReturnType,setterArgumentType])}else{desc.set=v=>throwBindingError(humanName+" is a read-only property")}Object.defineProperty(classType.registeredClass.instancePrototype,fieldName,desc);whenDependentTypesAreResolved([],setter?[getterReturnType,setterArgumentType]:[getterReturnType],types=>{var getterReturnType=types[0];var desc={get(){var ptr=validateThis(this,classType,humanName+" getter");return getterReturnType["fromWireType"](getter(getterContext,ptr))},enumerable:true};if(setter){setter=embind__requireFunction(setterSignature,setter);var setterArgumentType=types[1];desc.set=function(v){var ptr=validateThis(this,classType,humanName+" setter");var destructors=[];setter(setterContext,ptr,setterArgumentType["toWireType"](destructors,v));runDestructors(destructors)}}Object.defineProperty(classType.registeredClass.instancePrototype,fieldName,desc);return[]});return[]})};var emval_freelist=[];var emval_handles=[];var __emval_decref=handle=>{if(handle>9&&0===--emval_handles[handle+1]){emval_handles[handle]=undefined;emval_freelist.push(handle)}};var count_emval_handles=()=>emval_handles.length/2-5-emval_freelist.length;var init_emval=()=>{emval_handles.push(0,1,undefined,1,null,1,true,1,false,1);Module["count_emval_handles"]=count_emval_handles};var Emval={toValue:handle=>{if(!handle){throwBindingError("Cannot use deleted val. handle = "+handle)}return emval_handles[handle]},toHandle:value=>{switch(value){case undefined:return 2;case null:return 4;case true:return 6;case false:return 8;default:{const handle=emval_freelist.pop()||emval_handles.length;emval_handles[handle]=value;emval_handles[handle+1]=1;return handle}}}};var EmValType={name:"emscripten::val",fromWireType:handle=>{var rv=Emval.toValue(handle);__emval_decref(handle);return rv},toWireType:(destructors,value)=>Emval.toHandle(value),argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction:null};var __embind_register_emval=rawType=>registerType(rawType,EmValType);var embindRepr=v=>{if(v===null){return"null"}var t=typeof v;if(t==="object"||t==="array"||t==="function"){return v.toString()}else{return""+v}};var floatReadValueFromPointer=(name,width)=>{switch(width){case 4:return function(pointer){return this["fromWireType"](HEAPF32[pointer>>2])};case 8:return function(pointer){return this["fromWireType"](HEAPF64[pointer>>3])};default:throw new TypeError(`invalid float width (${width}): ${name}`)}};var __embind_register_float=(rawType,name,size)=>{name=readLatin1String(name);registerType(rawType,{name:name,fromWireType:value=>value,toWireType:(destructors,value)=>value,argPackAdvance:GenericWireTypeSize,readValueFromPointer:floatReadValueFromPointer(name,size),destructorFunction:null})};var __embind_register_function=(name,argCount,rawArgTypesAddr,signature,rawInvoker,fn,isAsync)=>{var argTypes=heap32VectorToArray(argCount,rawArgTypesAddr);name=readLatin1String(name);name=getFunctionName(name);rawInvoker=embind__requireFunction(signature,rawInvoker);exposePublicSymbol(name,function(){throwUnboundTypeError(`Cannot call ${name} due to unbound types`,argTypes)},argCount-1);whenDependentTypesAreResolved([],argTypes,argTypes=>{var invokerArgsArray=[argTypes[0],null].concat(argTypes.slice(1));replacePublicSymbol(name,craftInvokerFunction(name,invokerArgsArray,null,rawInvoker,fn,isAsync),argCount-1);return[]})};var integerReadValueFromPointer=(name,width,signed)=>{switch(width){case 1:return signed?pointer=>HEAP8[pointer]:pointer=>HEAPU8[pointer];case 2:return signed?pointer=>HEAP16[pointer>>1]:pointer=>HEAPU16[pointer>>1];case 4:return signed?pointer=>HEAP32[pointer>>2]:pointer=>HEAPU32[pointer>>2];default:throw new TypeError(`invalid integer width (${width}): ${name}`)}};var __embind_register_integer=(primitiveType,name,size,minRange,maxRange)=>{name=readLatin1String(name);if(maxRange===-1){maxRange=4294967295}var fromWireType=value=>value;if(minRange===0){var bitshift=32-8*size;fromWireType=value=>value<>>bitshift}var isUnsignedType=name.includes("unsigned");var checkAssertions=(value,toTypeName)=>{};var toWireType;if(isUnsignedType){toWireType=function(destructors,value){checkAssertions(value,this.name);return value>>>0}}else{toWireType=function(destructors,value){checkAssertions(value,this.name);return value}}registerType(primitiveType,{name:name,fromWireType:fromWireType,toWireType:toWireType,argPackAdvance:GenericWireTypeSize,readValueFromPointer:integerReadValueFromPointer(name,size,minRange!==0),destructorFunction:null})};var __embind_register_memory_view=(rawType,dataTypeIndex,name)=>{var typeMapping=[Int8Array,Uint8Array,Int16Array,Uint16Array,Int32Array,Uint32Array,Float32Array,Float64Array];var TA=typeMapping[dataTypeIndex];function decodeMemoryView(handle){var size=HEAPU32[handle>>2];var data=HEAPU32[handle+4>>2];return new TA(HEAP8.buffer,data,size)}name=readLatin1String(name);registerType(rawType,{name:name,fromWireType:decodeMemoryView,argPackAdvance:GenericWireTypeSize,readValueFromPointer:decodeMemoryView},{ignoreDuplicateRegistrations:true})};var __embind_register_optional=(rawOptionalType,rawType)=>{__embind_register_emval(rawOptionalType)};var stringToUTF8Array=(str,heap,outIdx,maxBytesToWrite)=>{if(!(maxBytesToWrite>0))return 0;var startIdx=outIdx;var endIdx=outIdx+maxBytesToWrite-1;for(var i=0;i=55296&&u<=57343){var u1=str.charCodeAt(++i);u=65536+((u&1023)<<10)|u1&1023}if(u<=127){if(outIdx>=endIdx)break;heap[outIdx++]=u}else if(u<=2047){if(outIdx+1>=endIdx)break;heap[outIdx++]=192|u>>6;heap[outIdx++]=128|u&63}else if(u<=65535){if(outIdx+2>=endIdx)break;heap[outIdx++]=224|u>>12;heap[outIdx++]=128|u>>6&63;heap[outIdx++]=128|u&63}else{if(outIdx+3>=endIdx)break;heap[outIdx++]=240|u>>18;heap[outIdx++]=128|u>>12&63;heap[outIdx++]=128|u>>6&63;heap[outIdx++]=128|u&63}}heap[outIdx]=0;return outIdx-startIdx};var stringToUTF8=(str,outPtr,maxBytesToWrite)=>stringToUTF8Array(str,HEAPU8,outPtr,maxBytesToWrite);var lengthBytesUTF8=str=>{var len=0;for(var i=0;i=55296&&c<=57343){len+=4;++i}else{len+=3}}return len};var UTF8Decoder=typeof TextDecoder!="undefined"?new TextDecoder:undefined;var UTF8ArrayToString=(heapOrArray,idx,maxBytesToRead)=>{var endIdx=idx+maxBytesToRead;var endPtr=idx;while(heapOrArray[endPtr]&&!(endPtr>=endIdx))++endPtr;if(endPtr-idx>16&&heapOrArray.buffer&&UTF8Decoder){return UTF8Decoder.decode(heapOrArray.subarray(idx,endPtr))}var str="";while(idx>10,56320|ch&1023)}}return str};var UTF8ToString=(ptr,maxBytesToRead)=>ptr?UTF8ArrayToString(HEAPU8,ptr,maxBytesToRead):"";var __embind_register_std_string=(rawType,name)=>{name=readLatin1String(name);var stdStringIsUTF8=name==="std::string";registerType(rawType,{name:name,fromWireType(value){var length=HEAPU32[value>>2];var payload=value+4;var str;if(stdStringIsUTF8){var decodeStartPtr=payload;for(var i=0;i<=length;++i){var currentBytePtr=payload+i;if(i==length||HEAPU8[currentBytePtr]==0){var maxRead=currentBytePtr-decodeStartPtr;var stringSegment=UTF8ToString(decodeStartPtr,maxRead);if(str===undefined){str=stringSegment}else{str+=String.fromCharCode(0);str+=stringSegment}decodeStartPtr=currentBytePtr+1}}}else{var a=new Array(length);for(var i=0;i>2]=length;if(stdStringIsUTF8&&valueIsOfTypeString){stringToUTF8(value,ptr,length+1)}else{if(valueIsOfTypeString){for(var i=0;i255){_free(ptr);throwBindingError("String has UTF-16 code units that do not fit in 8 bits")}HEAPU8[ptr+i]=charCode}}else{for(var i=0;i{var endPtr=ptr;var idx=endPtr>>1;var maxIdx=idx+maxBytesToRead/2;while(!(idx>=maxIdx)&&HEAPU16[idx])++idx;endPtr=idx<<1;if(endPtr-ptr>32&&UTF16Decoder)return UTF16Decoder.decode(HEAPU8.subarray(ptr,endPtr));var str="";for(var i=0;!(i>=maxBytesToRead/2);++i){var codeUnit=HEAP16[ptr+i*2>>1];if(codeUnit==0)break;str+=String.fromCharCode(codeUnit)}return str};var stringToUTF16=(str,outPtr,maxBytesToWrite)=>{maxBytesToWrite??=2147483647;if(maxBytesToWrite<2)return 0;maxBytesToWrite-=2;var startPtr=outPtr;var numCharsToWrite=maxBytesToWrite>1]=codeUnit;outPtr+=2}HEAP16[outPtr>>1]=0;return outPtr-startPtr};var lengthBytesUTF16=str=>str.length*2;var UTF32ToString=(ptr,maxBytesToRead)=>{var i=0;var str="";while(!(i>=maxBytesToRead/4)){var utf32=HEAP32[ptr+i*4>>2];if(utf32==0)break;++i;if(utf32>=65536){var ch=utf32-65536;str+=String.fromCharCode(55296|ch>>10,56320|ch&1023)}else{str+=String.fromCharCode(utf32)}}return str};var stringToUTF32=(str,outPtr,maxBytesToWrite)=>{maxBytesToWrite??=2147483647;if(maxBytesToWrite<4)return 0;var startPtr=outPtr;var endPtr=startPtr+maxBytesToWrite-4;for(var i=0;i=55296&&codeUnit<=57343){var trailSurrogate=str.charCodeAt(++i);codeUnit=65536+((codeUnit&1023)<<10)|trailSurrogate&1023}HEAP32[outPtr>>2]=codeUnit;outPtr+=4;if(outPtr+4>endPtr)break}HEAP32[outPtr>>2]=0;return outPtr-startPtr};var lengthBytesUTF32=str=>{var len=0;for(var i=0;i=55296&&codeUnit<=57343)++i;len+=4}return len};var __embind_register_std_wstring=(rawType,charSize,name)=>{name=readLatin1String(name);var decodeString,encodeString,readCharAt,lengthBytesUTF;if(charSize===2){decodeString=UTF16ToString;encodeString=stringToUTF16;lengthBytesUTF=lengthBytesUTF16;readCharAt=pointer=>HEAPU16[pointer>>1]}else if(charSize===4){decodeString=UTF32ToString;encodeString=stringToUTF32;lengthBytesUTF=lengthBytesUTF32;readCharAt=pointer=>HEAPU32[pointer>>2]}registerType(rawType,{name:name,fromWireType:value=>{var length=HEAPU32[value>>2];var str;var decodeStartPtr=value+4;for(var i=0;i<=length;++i){var currentBytePtr=value+4+i*charSize;if(i==length||readCharAt(currentBytePtr)==0){var maxReadBytes=currentBytePtr-decodeStartPtr;var stringSegment=decodeString(decodeStartPtr,maxReadBytes);if(str===undefined){str=stringSegment}else{str+=String.fromCharCode(0);str+=stringSegment}decodeStartPtr=currentBytePtr+charSize}}_free(value);return str},toWireType:(destructors,value)=>{if(!(typeof value=="string")){throwBindingError(`Cannot pass non-string to C++ string type ${name}`)}var length=lengthBytesUTF(value);var ptr=_malloc(4+length+charSize);HEAPU32[ptr>>2]=length/charSize;encodeString(value,ptr+4,length+charSize);if(destructors!==null){destructors.push(_free,ptr)}return ptr},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction(ptr){_free(ptr)}})};var __embind_register_void=(rawType,name)=>{name=readLatin1String(name);registerType(rawType,{isVoid:true,name:name,argPackAdvance:0,fromWireType:()=>undefined,toWireType:(destructors,o)=>undefined})};var __emscripten_memcpy_js=(dest,src,num)=>HEAPU8.copyWithin(dest,src,src+num);var requireRegisteredType=(rawType,humanName)=>{var impl=registeredTypes[rawType];if(undefined===impl){throwBindingError(`${humanName} has unknown type ${getTypeName(rawType)}`)}return impl};var __emval_take_value=(type,arg)=>{type=requireRegisteredType(type,"_emval_take_value");var v=type["readValueFromPointer"](arg);return Emval.toHandle(v)};var _emscripten_date_now=()=>Date.now();var abortOnCannotGrowMemory=requestedSize=>{abort("OOM")};var _emscripten_resize_heap=requestedSize=>{var oldSize=HEAPU8.length;requestedSize>>>=0;abortOnCannotGrowMemory(requestedSize)};var printCharBuffers=[null,[],[]];var printChar=(stream,curr)=>{var buffer=printCharBuffers[stream];if(curr===0||curr===10){(stream===1?out:err)(UTF8ArrayToString(buffer,0));buffer.length=0}else{buffer.push(curr)}};var _fd_write=(fd,iov,iovcnt,pnum)=>{var num=0;for(var i=0;i>2];var len=HEAPU32[iov+4>>2];iov+=8;for(var j=0;j>2]=num;return 0};embind_init_charCodes();BindingError=Module["BindingError"]=class BindingError extends Error{constructor(message){super(message);this.name="BindingError"}};InternalError=Module["InternalError"]=class InternalError extends Error{constructor(message){super(message);this.name="InternalError"}};init_ClassHandle();init_embind();init_RegisteredPointer();UnboundTypeError=Module["UnboundTypeError"]=extendError(Error,"UnboundTypeError");init_emval();var wasmImports={f:___cxa_throw,q:__abort_js,p:__embind_register_bigint,u:__embind_register_bool,l:__embind_register_class,h:__embind_register_class_constructor,e:__embind_register_class_function,a:__embind_register_class_property,t:__embind_register_emval,k:__embind_register_float,c:__embind_register_function,d:__embind_register_integer,b:__embind_register_memory_view,o:__embind_register_optional,j:__embind_register_std_string,g:__embind_register_std_wstring,m:__embind_register_void,s:__emscripten_memcpy_js,n:__emval_take_value,v:_emscripten_date_now,r:_emscripten_resize_heap,i:_fd_write};var wasmExports=createWasm();var ___wasm_call_ctors=()=>(___wasm_call_ctors=wasmExports["x"])();var _param_get=Module["_param_get"]=(a0,a1)=>(_param_get=Module["_param_get"]=wasmExports["y"])(a0,a1);var _param_set_used=Module["_param_set_used"]=a0=>(_param_set_used=Module["_param_set_used"]=wasmExports["z"])(a0);var __Znwm=Module["__Znwm"]=a0=>(__Znwm=Module["__Znwm"]=wasmExports["A"])(a0);var __ZdlPvm=Module["__ZdlPvm"]=(a0,a1)=>(__ZdlPvm=Module["__ZdlPvm"]=wasmExports["B"])(a0,a1);var _malloc=a0=>(_malloc=wasmExports["D"])(a0);var __ZNSt12length_errorD1Ev=Module["__ZNSt12length_errorD1Ev"]=a0=>(__ZNSt12length_errorD1Ev=Module["__ZNSt12length_errorD1Ev"]=wasmExports["E"])(a0);var ___cxa_allocate_exception=Module["___cxa_allocate_exception"]=a0=>(___cxa_allocate_exception=Module["___cxa_allocate_exception"]=wasmExports["F"])(a0);var __ZNSt20bad_array_new_lengthD1Ev=Module["__ZNSt20bad_array_new_lengthD1Ev"]=a0=>(__ZNSt20bad_array_new_lengthD1Ev=Module["__ZNSt20bad_array_new_lengthD1Ev"]=wasmExports["G"])(a0);var __ZNSt20bad_array_new_lengthC1Ev=Module["__ZNSt20bad_array_new_lengthC1Ev"]=a0=>(__ZNSt20bad_array_new_lengthC1Ev=Module["__ZNSt20bad_array_new_lengthC1Ev"]=wasmExports["H"])(a0);var __ZNSt12out_of_rangeD1Ev=Module["__ZNSt12out_of_rangeD1Ev"]=a0=>(__ZNSt12out_of_rangeD1Ev=Module["__ZNSt12out_of_rangeD1Ev"]=wasmExports["I"])(a0);var ___cxa_pure_virtual=Module["___cxa_pure_virtual"]=()=>(___cxa_pure_virtual=Module["___cxa_pure_virtual"]=wasmExports["J"])();var ___getTypeName=a0=>(___getTypeName=wasmExports["K"])(a0);var __ZNSt9exceptionD2Ev=Module["__ZNSt9exceptionD2Ev"]=a0=>(__ZNSt9exceptionD2Ev=Module["__ZNSt9exceptionD2Ev"]=wasmExports["L"])(a0);var _free=a0=>(_free=wasmExports["M"])(a0);var _getTempRet0=Module["_getTempRet0"]=()=>(_getTempRet0=Module["_getTempRet0"]=wasmExports["N"])();var _setTempRet0=Module["_setTempRet0"]=a0=>(_setTempRet0=Module["_setTempRet0"]=wasmExports["O"])(a0);var __ZSt15get_new_handlerv=Module["__ZSt15get_new_handlerv"]=()=>(__ZSt15get_new_handlerv=Module["__ZSt15get_new_handlerv"]=wasmExports["P"])();var __Znam=Module["__Znam"]=a0=>(__Znam=Module["__Znam"]=wasmExports["Q"])(a0);var __ZdlPv=Module["__ZdlPv"]=a0=>(__ZdlPv=Module["__ZdlPv"]=wasmExports["R"])(a0);var __ZdaPv=Module["__ZdaPv"]=a0=>(__ZdaPv=Module["__ZdaPv"]=wasmExports["S"])(a0);var __ZdaPvm=Module["__ZdaPvm"]=(a0,a1)=>(__ZdaPvm=Module["__ZdaPvm"]=wasmExports["T"])(a0,a1);var __ZnwmSt11align_val_t=Module["__ZnwmSt11align_val_t"]=(a0,a1)=>(__ZnwmSt11align_val_t=Module["__ZnwmSt11align_val_t"]=wasmExports["U"])(a0,a1);var __ZnamSt11align_val_t=Module["__ZnamSt11align_val_t"]=(a0,a1)=>(__ZnamSt11align_val_t=Module["__ZnamSt11align_val_t"]=wasmExports["V"])(a0,a1);var __ZdlPvSt11align_val_t=Module["__ZdlPvSt11align_val_t"]=(a0,a1)=>(__ZdlPvSt11align_val_t=Module["__ZdlPvSt11align_val_t"]=wasmExports["W"])(a0,a1);var __ZdlPvmSt11align_val_t=Module["__ZdlPvmSt11align_val_t"]=(a0,a1,a2)=>(__ZdlPvmSt11align_val_t=Module["__ZdlPvmSt11align_val_t"]=wasmExports["X"])(a0,a1,a2);var __ZdaPvSt11align_val_t=Module["__ZdaPvSt11align_val_t"]=(a0,a1)=>(__ZdaPvSt11align_val_t=Module["__ZdaPvSt11align_val_t"]=wasmExports["Y"])(a0,a1);var __ZdaPvmSt11align_val_t=Module["__ZdaPvmSt11align_val_t"]=(a0,a1,a2)=>(__ZdaPvmSt11align_val_t=Module["__ZdaPvmSt11align_val_t"]=wasmExports["Z"])(a0,a1,a2);var __ZSt14set_unexpectedPFvvE=Module["__ZSt14set_unexpectedPFvvE"]=a0=>(__ZSt14set_unexpectedPFvvE=Module["__ZSt14set_unexpectedPFvvE"]=wasmExports["_"])(a0);var __ZSt13set_terminatePFvvE=Module["__ZSt13set_terminatePFvvE"]=a0=>(__ZSt13set_terminatePFvvE=Module["__ZSt13set_terminatePFvvE"]=wasmExports["$"])(a0);var __ZSt15set_new_handlerPFvvE=Module["__ZSt15set_new_handlerPFvvE"]=a0=>(__ZSt15set_new_handlerPFvvE=Module["__ZSt15set_new_handlerPFvvE"]=wasmExports["aa"])(a0);var __ZSt14get_unexpectedv=Module["__ZSt14get_unexpectedv"]=()=>(__ZSt14get_unexpectedv=Module["__ZSt14get_unexpectedv"]=wasmExports["ba"])();var __ZSt10unexpectedv=Module["__ZSt10unexpectedv"]=()=>(__ZSt10unexpectedv=Module["__ZSt10unexpectedv"]=wasmExports["ca"])();var __ZSt13get_terminatev=Module["__ZSt13get_terminatev"]=()=>(__ZSt13get_terminatev=Module["__ZSt13get_terminatev"]=wasmExports["da"])();var __ZSt9terminatev=Module["__ZSt9terminatev"]=()=>(__ZSt9terminatev=Module["__ZSt9terminatev"]=wasmExports["ea"])();var ___cxa_current_primary_exception=Module["___cxa_current_primary_exception"]=()=>(___cxa_current_primary_exception=Module["___cxa_current_primary_exception"]=wasmExports["fa"])();var ___cxa_rethrow_primary_exception=Module["___cxa_rethrow_primary_exception"]=a0=>(___cxa_rethrow_primary_exception=Module["___cxa_rethrow_primary_exception"]=wasmExports["ga"])(a0);var ___cxa_uncaught_exception=Module["___cxa_uncaught_exception"]=()=>(___cxa_uncaught_exception=Module["___cxa_uncaught_exception"]=wasmExports["ha"])();var ___cxa_uncaught_exceptions=Module["___cxa_uncaught_exceptions"]=()=>(___cxa_uncaught_exceptions=Module["___cxa_uncaught_exceptions"]=wasmExports["ia"])();var ___cxa_free_exception=Module["___cxa_free_exception"]=a0=>(___cxa_free_exception=Module["___cxa_free_exception"]=wasmExports["ja"])(a0);var ___cxa_init_primary_exception=Module["___cxa_init_primary_exception"]=(a0,a1,a2)=>(___cxa_init_primary_exception=Module["___cxa_init_primary_exception"]=wasmExports["ka"])(a0,a1,a2);var ___cxa_deleted_virtual=Module["___cxa_deleted_virtual"]=()=>(___cxa_deleted_virtual=Module["___cxa_deleted_virtual"]=wasmExports["la"])();var ___dynamic_cast=Module["___dynamic_cast"]=(a0,a1,a2,a3)=>(___dynamic_cast=Module["___dynamic_cast"]=wasmExports["ma"])(a0,a1,a2,a3);var __ZNSt9type_infoD2Ev=Module["__ZNSt9type_infoD2Ev"]=a0=>(__ZNSt9type_infoD2Ev=Module["__ZNSt9type_infoD2Ev"]=wasmExports["na"])(a0);var ___cxa_is_pointer_type=a0=>(___cxa_is_pointer_type=wasmExports["oa"])(a0);var __ZNSt9exceptionD0Ev=Module["__ZNSt9exceptionD0Ev"]=a0=>(__ZNSt9exceptionD0Ev=Module["__ZNSt9exceptionD0Ev"]=wasmExports["pa"])(a0);var __ZNSt9exceptionD1Ev=Module["__ZNSt9exceptionD1Ev"]=a0=>(__ZNSt9exceptionD1Ev=Module["__ZNSt9exceptionD1Ev"]=wasmExports["qa"])(a0);var __ZNKSt9exception4whatEv=Module["__ZNKSt9exception4whatEv"]=a0=>(__ZNKSt9exception4whatEv=Module["__ZNKSt9exception4whatEv"]=wasmExports["ra"])(a0);var __ZNSt13bad_exceptionD0Ev=Module["__ZNSt13bad_exceptionD0Ev"]=a0=>(__ZNSt13bad_exceptionD0Ev=Module["__ZNSt13bad_exceptionD0Ev"]=wasmExports["sa"])(a0);var __ZNSt13bad_exceptionD1Ev=Module["__ZNSt13bad_exceptionD1Ev"]=a0=>(__ZNSt13bad_exceptionD1Ev=Module["__ZNSt13bad_exceptionD1Ev"]=wasmExports["ta"])(a0);var __ZNKSt13bad_exception4whatEv=Module["__ZNKSt13bad_exception4whatEv"]=a0=>(__ZNKSt13bad_exception4whatEv=Module["__ZNKSt13bad_exception4whatEv"]=wasmExports["ua"])(a0);var __ZNSt9bad_allocC2Ev=Module["__ZNSt9bad_allocC2Ev"]=a0=>(__ZNSt9bad_allocC2Ev=Module["__ZNSt9bad_allocC2Ev"]=wasmExports["va"])(a0);var __ZNSt9bad_allocD0Ev=Module["__ZNSt9bad_allocD0Ev"]=a0=>(__ZNSt9bad_allocD0Ev=Module["__ZNSt9bad_allocD0Ev"]=wasmExports["wa"])(a0);var __ZNSt9bad_allocD1Ev=Module["__ZNSt9bad_allocD1Ev"]=a0=>(__ZNSt9bad_allocD1Ev=Module["__ZNSt9bad_allocD1Ev"]=wasmExports["xa"])(a0);var __ZNKSt9bad_alloc4whatEv=Module["__ZNKSt9bad_alloc4whatEv"]=a0=>(__ZNKSt9bad_alloc4whatEv=Module["__ZNKSt9bad_alloc4whatEv"]=wasmExports["ya"])(a0);var __ZNSt20bad_array_new_lengthC2Ev=Module["__ZNSt20bad_array_new_lengthC2Ev"]=a0=>(__ZNSt20bad_array_new_lengthC2Ev=Module["__ZNSt20bad_array_new_lengthC2Ev"]=wasmExports["za"])(a0);var __ZNSt20bad_array_new_lengthD0Ev=Module["__ZNSt20bad_array_new_lengthD0Ev"]=a0=>(__ZNSt20bad_array_new_lengthD0Ev=Module["__ZNSt20bad_array_new_lengthD0Ev"]=wasmExports["Aa"])(a0);var __ZNKSt20bad_array_new_length4whatEv=Module["__ZNKSt20bad_array_new_length4whatEv"]=a0=>(__ZNKSt20bad_array_new_length4whatEv=Module["__ZNKSt20bad_array_new_length4whatEv"]=wasmExports["Ba"])(a0);var __ZNSt13bad_exceptionD2Ev=Module["__ZNSt13bad_exceptionD2Ev"]=a0=>(__ZNSt13bad_exceptionD2Ev=Module["__ZNSt13bad_exceptionD2Ev"]=wasmExports["Ca"])(a0);var __ZNSt9bad_allocC1Ev=Module["__ZNSt9bad_allocC1Ev"]=a0=>(__ZNSt9bad_allocC1Ev=Module["__ZNSt9bad_allocC1Ev"]=wasmExports["Da"])(a0);var __ZNSt9bad_allocD2Ev=Module["__ZNSt9bad_allocD2Ev"]=a0=>(__ZNSt9bad_allocD2Ev=Module["__ZNSt9bad_allocD2Ev"]=wasmExports["Ea"])(a0);var __ZNSt20bad_array_new_lengthD2Ev=Module["__ZNSt20bad_array_new_lengthD2Ev"]=a0=>(__ZNSt20bad_array_new_lengthD2Ev=Module["__ZNSt20bad_array_new_lengthD2Ev"]=wasmExports["Fa"])(a0);var __ZNSt11logic_errorD2Ev=Module["__ZNSt11logic_errorD2Ev"]=a0=>(__ZNSt11logic_errorD2Ev=Module["__ZNSt11logic_errorD2Ev"]=wasmExports["Ga"])(a0);var __ZNSt11logic_errorD0Ev=Module["__ZNSt11logic_errorD0Ev"]=a0=>(__ZNSt11logic_errorD0Ev=Module["__ZNSt11logic_errorD0Ev"]=wasmExports["Ha"])(a0);var __ZNSt11logic_errorD1Ev=Module["__ZNSt11logic_errorD1Ev"]=a0=>(__ZNSt11logic_errorD1Ev=Module["__ZNSt11logic_errorD1Ev"]=wasmExports["Ia"])(a0);var __ZNKSt11logic_error4whatEv=Module["__ZNKSt11logic_error4whatEv"]=a0=>(__ZNKSt11logic_error4whatEv=Module["__ZNKSt11logic_error4whatEv"]=wasmExports["Ja"])(a0);var __ZNSt13runtime_errorD2Ev=Module["__ZNSt13runtime_errorD2Ev"]=a0=>(__ZNSt13runtime_errorD2Ev=Module["__ZNSt13runtime_errorD2Ev"]=wasmExports["Ka"])(a0);var __ZNSt13runtime_errorD0Ev=Module["__ZNSt13runtime_errorD0Ev"]=a0=>(__ZNSt13runtime_errorD0Ev=Module["__ZNSt13runtime_errorD0Ev"]=wasmExports["La"])(a0);var __ZNSt13runtime_errorD1Ev=Module["__ZNSt13runtime_errorD1Ev"]=a0=>(__ZNSt13runtime_errorD1Ev=Module["__ZNSt13runtime_errorD1Ev"]=wasmExports["Ma"])(a0);var __ZNKSt13runtime_error4whatEv=Module["__ZNKSt13runtime_error4whatEv"]=a0=>(__ZNKSt13runtime_error4whatEv=Module["__ZNKSt13runtime_error4whatEv"]=wasmExports["Na"])(a0);var __ZNSt12domain_errorD0Ev=Module["__ZNSt12domain_errorD0Ev"]=a0=>(__ZNSt12domain_errorD0Ev=Module["__ZNSt12domain_errorD0Ev"]=wasmExports["Oa"])(a0);var __ZNSt12domain_errorD1Ev=Module["__ZNSt12domain_errorD1Ev"]=a0=>(__ZNSt12domain_errorD1Ev=Module["__ZNSt12domain_errorD1Ev"]=wasmExports["Pa"])(a0);var __ZNSt16invalid_argumentD0Ev=Module["__ZNSt16invalid_argumentD0Ev"]=a0=>(__ZNSt16invalid_argumentD0Ev=Module["__ZNSt16invalid_argumentD0Ev"]=wasmExports["Qa"])(a0);var __ZNSt16invalid_argumentD1Ev=Module["__ZNSt16invalid_argumentD1Ev"]=a0=>(__ZNSt16invalid_argumentD1Ev=Module["__ZNSt16invalid_argumentD1Ev"]=wasmExports["Ra"])(a0);var __ZNSt12length_errorD0Ev=Module["__ZNSt12length_errorD0Ev"]=a0=>(__ZNSt12length_errorD0Ev=Module["__ZNSt12length_errorD0Ev"]=wasmExports["Sa"])(a0);var __ZNSt12out_of_rangeD0Ev=Module["__ZNSt12out_of_rangeD0Ev"]=a0=>(__ZNSt12out_of_rangeD0Ev=Module["__ZNSt12out_of_rangeD0Ev"]=wasmExports["Ta"])(a0);var __ZNSt11range_errorD0Ev=Module["__ZNSt11range_errorD0Ev"]=a0=>(__ZNSt11range_errorD0Ev=Module["__ZNSt11range_errorD0Ev"]=wasmExports["Ua"])(a0);var __ZNSt11range_errorD1Ev=Module["__ZNSt11range_errorD1Ev"]=a0=>(__ZNSt11range_errorD1Ev=Module["__ZNSt11range_errorD1Ev"]=wasmExports["Va"])(a0);var __ZNSt14overflow_errorD0Ev=Module["__ZNSt14overflow_errorD0Ev"]=a0=>(__ZNSt14overflow_errorD0Ev=Module["__ZNSt14overflow_errorD0Ev"]=wasmExports["Wa"])(a0);var __ZNSt14overflow_errorD1Ev=Module["__ZNSt14overflow_errorD1Ev"]=a0=>(__ZNSt14overflow_errorD1Ev=Module["__ZNSt14overflow_errorD1Ev"]=wasmExports["Xa"])(a0);var __ZNSt15underflow_errorD0Ev=Module["__ZNSt15underflow_errorD0Ev"]=a0=>(__ZNSt15underflow_errorD0Ev=Module["__ZNSt15underflow_errorD0Ev"]=wasmExports["Ya"])(a0);var __ZNSt15underflow_errorD1Ev=Module["__ZNSt15underflow_errorD1Ev"]=a0=>(__ZNSt15underflow_errorD1Ev=Module["__ZNSt15underflow_errorD1Ev"]=wasmExports["Za"])(a0);var __ZNSt12domain_errorD2Ev=Module["__ZNSt12domain_errorD2Ev"]=a0=>(__ZNSt12domain_errorD2Ev=Module["__ZNSt12domain_errorD2Ev"]=wasmExports["_a"])(a0);var __ZNSt16invalid_argumentD2Ev=Module["__ZNSt16invalid_argumentD2Ev"]=a0=>(__ZNSt16invalid_argumentD2Ev=Module["__ZNSt16invalid_argumentD2Ev"]=wasmExports["$a"])(a0);var __ZNSt12length_errorD2Ev=Module["__ZNSt12length_errorD2Ev"]=a0=>(__ZNSt12length_errorD2Ev=Module["__ZNSt12length_errorD2Ev"]=wasmExports["ab"])(a0);var __ZNSt12out_of_rangeD2Ev=Module["__ZNSt12out_of_rangeD2Ev"]=a0=>(__ZNSt12out_of_rangeD2Ev=Module["__ZNSt12out_of_rangeD2Ev"]=wasmExports["bb"])(a0);var __ZNSt11range_errorD2Ev=Module["__ZNSt11range_errorD2Ev"]=a0=>(__ZNSt11range_errorD2Ev=Module["__ZNSt11range_errorD2Ev"]=wasmExports["cb"])(a0);var __ZNSt14overflow_errorD2Ev=Module["__ZNSt14overflow_errorD2Ev"]=a0=>(__ZNSt14overflow_errorD2Ev=Module["__ZNSt14overflow_errorD2Ev"]=wasmExports["db"])(a0);var __ZNSt15underflow_errorD2Ev=Module["__ZNSt15underflow_errorD2Ev"]=a0=>(__ZNSt15underflow_errorD2Ev=Module["__ZNSt15underflow_errorD2Ev"]=wasmExports["eb"])(a0);var __ZNSt9type_infoD0Ev=Module["__ZNSt9type_infoD0Ev"]=a0=>(__ZNSt9type_infoD0Ev=Module["__ZNSt9type_infoD0Ev"]=wasmExports["fb"])(a0);var __ZNSt9type_infoD1Ev=Module["__ZNSt9type_infoD1Ev"]=a0=>(__ZNSt9type_infoD1Ev=Module["__ZNSt9type_infoD1Ev"]=wasmExports["gb"])(a0);var __ZNSt8bad_castC2Ev=Module["__ZNSt8bad_castC2Ev"]=a0=>(__ZNSt8bad_castC2Ev=Module["__ZNSt8bad_castC2Ev"]=wasmExports["hb"])(a0);var __ZNSt8bad_castD2Ev=Module["__ZNSt8bad_castD2Ev"]=a0=>(__ZNSt8bad_castD2Ev=Module["__ZNSt8bad_castD2Ev"]=wasmExports["ib"])(a0);var __ZNSt8bad_castD0Ev=Module["__ZNSt8bad_castD0Ev"]=a0=>(__ZNSt8bad_castD0Ev=Module["__ZNSt8bad_castD0Ev"]=wasmExports["jb"])(a0);var __ZNSt8bad_castD1Ev=Module["__ZNSt8bad_castD1Ev"]=a0=>(__ZNSt8bad_castD1Ev=Module["__ZNSt8bad_castD1Ev"]=wasmExports["kb"])(a0);var __ZNKSt8bad_cast4whatEv=Module["__ZNKSt8bad_cast4whatEv"]=a0=>(__ZNKSt8bad_cast4whatEv=Module["__ZNKSt8bad_cast4whatEv"]=wasmExports["lb"])(a0);var __ZNSt10bad_typeidC2Ev=Module["__ZNSt10bad_typeidC2Ev"]=a0=>(__ZNSt10bad_typeidC2Ev=Module["__ZNSt10bad_typeidC2Ev"]=wasmExports["mb"])(a0);var __ZNSt10bad_typeidD2Ev=Module["__ZNSt10bad_typeidD2Ev"]=a0=>(__ZNSt10bad_typeidD2Ev=Module["__ZNSt10bad_typeidD2Ev"]=wasmExports["nb"])(a0);var __ZNSt10bad_typeidD0Ev=Module["__ZNSt10bad_typeidD0Ev"]=a0=>(__ZNSt10bad_typeidD0Ev=Module["__ZNSt10bad_typeidD0Ev"]=wasmExports["ob"])(a0);var __ZNSt10bad_typeidD1Ev=Module["__ZNSt10bad_typeidD1Ev"]=a0=>(__ZNSt10bad_typeidD1Ev=Module["__ZNSt10bad_typeidD1Ev"]=wasmExports["pb"])(a0);var __ZNKSt10bad_typeid4whatEv=Module["__ZNKSt10bad_typeid4whatEv"]=a0=>(__ZNKSt10bad_typeid4whatEv=Module["__ZNKSt10bad_typeid4whatEv"]=wasmExports["qb"])(a0);var __ZNSt8bad_castC1Ev=Module["__ZNSt8bad_castC1Ev"]=a0=>(__ZNSt8bad_castC1Ev=Module["__ZNSt8bad_castC1Ev"]=wasmExports["rb"])(a0);var __ZNSt10bad_typeidC1Ev=Module["__ZNSt10bad_typeidC1Ev"]=a0=>(__ZNSt10bad_typeidC1Ev=Module["__ZNSt10bad_typeidC1Ev"]=wasmExports["sb"])(a0);var dynCall_jiji=Module["dynCall_jiji"]=(a0,a1,a2,a3,a4)=>(dynCall_jiji=Module["dynCall_jiji"]=wasmExports["tb"])(a0,a1,a2,a3,a4);var __ZTIPK16failsafe_flags_s=Module["__ZTIPK16failsafe_flags_s"]=48400;var __ZTIP16failsafe_flags_s=Module["__ZTIP16failsafe_flags_s"]=48384;var __ZTI16failsafe_flags_s=Module["__ZTI16failsafe_flags_s"]=48376;var __ZTIb=Module["__ZTIb"]=31224;var __ZTIh=Module["__ZTIh"]=31380;var __ZTINSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE=Module["__ZTINSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE"]=48476;var __ZTINSt3__28optionalINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEEEE=Module["__ZTINSt3__28optionalINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEEEE"]=48624;var __ZTIPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTIPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=48680;var __ZTIPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTIPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=48664;var __ZTINSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTINSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=48488;var __ZTISt12length_error=Module["__ZTISt12length_error"]=33340;var __ZTVSt12length_error=Module["__ZTVSt12length_error"]=33300;var __ZTISt20bad_array_new_length=Module["__ZTISt20bad_array_new_length"]=33112;var __ZTISt12out_of_range=Module["__ZTISt12out_of_range"]=33392;var __ZTVSt12out_of_range=Module["__ZTVSt12out_of_range"]=33352;var __ZTVN10__cxxabiv117__class_type_infoE=Module["__ZTVN10__cxxabiv117__class_type_infoE"]=32612;var __ZTVN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTVN10__cxxabiv121__vmi_class_type_infoE"]=32744;var __ZTVN10__cxxabiv120__si_class_type_infoE=Module["__ZTVN10__cxxabiv120__si_class_type_infoE"]=32652;var __ZTS16failsafe_flags_s=Module["__ZTS16failsafe_flags_s"]=28132;var __ZTSP16failsafe_flags_s=Module["__ZTSP16failsafe_flags_s"]=28151;var __ZTVN10__cxxabiv119__pointer_type_infoE=Module["__ZTVN10__cxxabiv119__pointer_type_infoE"]=32864;var __ZTSPK16failsafe_flags_s=Module["__ZTSPK16failsafe_flags_s"]=28171;var __ZTIi=Module["__ZTIi"]=31588;var __ZTSNSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE=Module["__ZTSNSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE"]=28220;var __ZTSNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=28287;var __ZTIv=Module["__ZTIv"]=31116;var __ZTIf=Module["__ZTIf"]=32060;var __ZTSNSt3__28optionalINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEEEE=Module["__ZTSNSt3__28optionalINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEEEE"]=28385;var __ZTSNSt3__227__optional_move_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTSNSt3__227__optional_move_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=28463;var __ZTSNSt3__227__optional_copy_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTSNSt3__227__optional_copy_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=28565;var __ZTSNSt3__220__optional_move_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTSNSt3__220__optional_move_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=28667;var __ZTSNSt3__220__optional_copy_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTSNSt3__220__optional_copy_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=28762;var __ZTSNSt3__223__optional_storage_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTSNSt3__223__optional_storage_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=28857;var __ZTSNSt3__224__optional_destruct_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTSNSt3__224__optional_destruct_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=28955;var __ZTINSt3__224__optional_destruct_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTINSt3__224__optional_destruct_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=48540;var __ZTINSt3__223__optional_storage_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTINSt3__223__optional_storage_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=48548;var __ZTINSt3__220__optional_copy_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTINSt3__220__optional_copy_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=48560;var __ZTINSt3__220__optional_move_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTINSt3__220__optional_move_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=48572;var __ZTINSt3__227__optional_copy_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTINSt3__227__optional_copy_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=48584;var __ZTINSt3__227__optional_move_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTINSt3__227__optional_move_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=48596;var __ZTSNSt3__218__sfinae_ctor_baseILb1ELb1EEE=Module["__ZTSNSt3__218__sfinae_ctor_baseILb1ELb1EEE"]=29054;var __ZTINSt3__218__sfinae_ctor_baseILb1ELb1EEE=Module["__ZTINSt3__218__sfinae_ctor_baseILb1ELb1EEE"]=48608;var __ZTSNSt3__220__sfinae_assign_baseILb1ELb1EEE=Module["__ZTSNSt3__220__sfinae_assign_baseILb1ELb1EEE"]=29093;var __ZTINSt3__220__sfinae_assign_baseILb1ELb1EEE=Module["__ZTINSt3__220__sfinae_assign_baseILb1ELb1EEE"]=48616;var __ZTSPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=29134;var __ZTSPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=29221;var __ZTIm=Module["__ZTIm"]=31744;var __ZTIc=Module["__ZTIc"]=31328;var __ZTIa=Module["__ZTIa"]=31432;var __ZTIs=Module["__ZTIs"]=31484;var __ZTIt=Module["__ZTIt"]=31536;var __ZTIj=Module["__ZTIj"]=31640;var __ZTIl=Module["__ZTIl"]=31692;var __ZTIx=Module["__ZTIx"]=31796;var __ZTIy=Module["__ZTIy"]=31848;var __ZTId=Module["__ZTId"]=32112;var __ZTINSt3__212basic_stringIhNS_11char_traitsIhEENS_9allocatorIhEEEE=Module["__ZTINSt3__212basic_stringIhNS_11char_traitsIhEENS_9allocatorIhEEEE"]=29424;var __ZTINSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE=Module["__ZTINSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE"]=29496;var __ZTINSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE=Module["__ZTINSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE"]=29572;var __ZTINSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE=Module["__ZTINSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE"]=29648;var __ZTSNSt3__212basic_stringIhNS_11char_traitsIhEENS_9allocatorIhEEEE=Module["__ZTSNSt3__212basic_stringIhNS_11char_traitsIhEENS_9allocatorIhEEEE"]=29360;var __ZTSNSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE=Module["__ZTSNSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE"]=29432;var __ZTSNSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE=Module["__ZTSNSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE"]=29504;var __ZTSNSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE=Module["__ZTSNSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE"]=29580;var __ZTVSt11logic_error=Module["__ZTVSt11logic_error"]=33124;var __ZTVSt9exception=Module["__ZTVSt9exception"]=32960;var __ZTVSt13runtime_error=Module["__ZTVSt13runtime_error"]=33144;var __ZTISt9exception=Module["__ZTISt9exception"]=32996;var ___cxa_unexpected_handler=Module["___cxa_unexpected_handler"]=48984;var ___cxa_terminate_handler=Module["___cxa_terminate_handler"]=48980;var ___cxa_new_handler=Module["___cxa_new_handler"]=51228;var __ZTIN10__cxxabiv116__shim_type_infoE=Module["__ZTIN10__cxxabiv116__shim_type_infoE"]=30724;var __ZTIN10__cxxabiv117__class_type_infoE=Module["__ZTIN10__cxxabiv117__class_type_infoE"]=30772;var __ZTIN10__cxxabiv117__pbase_type_infoE=Module["__ZTIN10__cxxabiv117__pbase_type_infoE"]=30820;var __ZTIDn=Module["__ZTIDn"]=31168;var __ZTIN10__cxxabiv119__pointer_type_infoE=Module["__ZTIN10__cxxabiv119__pointer_type_infoE"]=30868;var __ZTIN10__cxxabiv120__function_type_infoE=Module["__ZTIN10__cxxabiv120__function_type_infoE"]=30920;var __ZTIN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTIN10__cxxabiv129__pointer_to_member_type_infoE"]=30980;var __ZTSN10__cxxabiv116__shim_type_infoE=Module["__ZTSN10__cxxabiv116__shim_type_infoE"]=30688;var __ZTISt9type_info=Module["__ZTISt9type_info"]=33660;var __ZTSN10__cxxabiv117__class_type_infoE=Module["__ZTSN10__cxxabiv117__class_type_infoE"]=30736;var __ZTSN10__cxxabiv117__pbase_type_infoE=Module["__ZTSN10__cxxabiv117__pbase_type_infoE"]=30784;var __ZTSN10__cxxabiv119__pointer_type_infoE=Module["__ZTSN10__cxxabiv119__pointer_type_infoE"]=30832;var __ZTSN10__cxxabiv120__function_type_infoE=Module["__ZTSN10__cxxabiv120__function_type_infoE"]=30880;var __ZTSN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTSN10__cxxabiv129__pointer_to_member_type_infoE"]=30932;var __ZTVN10__cxxabiv116__shim_type_infoE=Module["__ZTVN10__cxxabiv116__shim_type_infoE"]=31004;var __ZTVN10__cxxabiv123__fundamental_type_infoE=Module["__ZTVN10__cxxabiv123__fundamental_type_infoE"]=31032;var __ZTIN10__cxxabiv123__fundamental_type_infoE=Module["__ZTIN10__cxxabiv123__fundamental_type_infoE"]=31100;var __ZTSN10__cxxabiv123__fundamental_type_infoE=Module["__ZTSN10__cxxabiv123__fundamental_type_infoE"]=31060;var __ZTSv=Module["__ZTSv"]=31112;var __ZTSPv=Module["__ZTSPv"]=31124;var __ZTIPv=Module["__ZTIPv"]=31128;var __ZTSPKv=Module["__ZTSPKv"]=31144;var __ZTIPKv=Module["__ZTIPKv"]=31148;var __ZTSDn=Module["__ZTSDn"]=31164;var __ZTSPDn=Module["__ZTSPDn"]=31176;var __ZTIPDn=Module["__ZTIPDn"]=31180;var __ZTSPKDn=Module["__ZTSPKDn"]=31196;var __ZTIPKDn=Module["__ZTIPKDn"]=31204;var __ZTSb=Module["__ZTSb"]=31220;var __ZTSPb=Module["__ZTSPb"]=31232;var __ZTIPb=Module["__ZTIPb"]=31236;var __ZTSPKb=Module["__ZTSPKb"]=31252;var __ZTIPKb=Module["__ZTIPKb"]=31256;var __ZTSw=Module["__ZTSw"]=31272;var __ZTIw=Module["__ZTIw"]=31276;var __ZTSPw=Module["__ZTSPw"]=31284;var __ZTIPw=Module["__ZTIPw"]=31288;var __ZTSPKw=Module["__ZTSPKw"]=31304;var __ZTIPKw=Module["__ZTIPKw"]=31308;var __ZTSc=Module["__ZTSc"]=31324;var __ZTSPc=Module["__ZTSPc"]=31336;var __ZTIPc=Module["__ZTIPc"]=31340;var __ZTSPKc=Module["__ZTSPKc"]=31356;var __ZTIPKc=Module["__ZTIPKc"]=31360;var __ZTSh=Module["__ZTSh"]=31376;var __ZTSPh=Module["__ZTSPh"]=31388;var __ZTIPh=Module["__ZTIPh"]=31392;var __ZTSPKh=Module["__ZTSPKh"]=31408;var __ZTIPKh=Module["__ZTIPKh"]=31412;var __ZTSa=Module["__ZTSa"]=31428;var __ZTSPa=Module["__ZTSPa"]=31440;var __ZTIPa=Module["__ZTIPa"]=31444;var __ZTSPKa=Module["__ZTSPKa"]=31460;var __ZTIPKa=Module["__ZTIPKa"]=31464;var __ZTSs=Module["__ZTSs"]=31480;var __ZTSPs=Module["__ZTSPs"]=31492;var __ZTIPs=Module["__ZTIPs"]=31496;var __ZTSPKs=Module["__ZTSPKs"]=31512;var __ZTIPKs=Module["__ZTIPKs"]=31516;var __ZTSt=Module["__ZTSt"]=31532;var __ZTSPt=Module["__ZTSPt"]=31544;var __ZTIPt=Module["__ZTIPt"]=31548;var __ZTSPKt=Module["__ZTSPKt"]=31564;var __ZTIPKt=Module["__ZTIPKt"]=31568;var __ZTSi=Module["__ZTSi"]=31584;var __ZTSPi=Module["__ZTSPi"]=31596;var __ZTIPi=Module["__ZTIPi"]=31600;var __ZTSPKi=Module["__ZTSPKi"]=31616;var __ZTIPKi=Module["__ZTIPKi"]=31620;var __ZTSj=Module["__ZTSj"]=31636;var __ZTSPj=Module["__ZTSPj"]=31648;var __ZTIPj=Module["__ZTIPj"]=31652;var __ZTSPKj=Module["__ZTSPKj"]=31668;var __ZTIPKj=Module["__ZTIPKj"]=31672;var __ZTSl=Module["__ZTSl"]=31688;var __ZTSPl=Module["__ZTSPl"]=31700;var __ZTIPl=Module["__ZTIPl"]=31704;var __ZTSPKl=Module["__ZTSPKl"]=31720;var __ZTIPKl=Module["__ZTIPKl"]=31724;var __ZTSm=Module["__ZTSm"]=31740;var __ZTSPm=Module["__ZTSPm"]=31752;var __ZTIPm=Module["__ZTIPm"]=31756;var __ZTSPKm=Module["__ZTSPKm"]=31772;var __ZTIPKm=Module["__ZTIPKm"]=31776;var __ZTSx=Module["__ZTSx"]=31792;var __ZTSPx=Module["__ZTSPx"]=31804;var __ZTIPx=Module["__ZTIPx"]=31808;var __ZTSPKx=Module["__ZTSPKx"]=31824;var __ZTIPKx=Module["__ZTIPKx"]=31828;var __ZTSy=Module["__ZTSy"]=31844;var __ZTSPy=Module["__ZTSPy"]=31856;var __ZTIPy=Module["__ZTIPy"]=31860;var __ZTSPKy=Module["__ZTSPKy"]=31876;var __ZTIPKy=Module["__ZTIPKy"]=31880;var __ZTSn=Module["__ZTSn"]=31896;var __ZTIn=Module["__ZTIn"]=31900;var __ZTSPn=Module["__ZTSPn"]=31908;var __ZTIPn=Module["__ZTIPn"]=31912;var __ZTSPKn=Module["__ZTSPKn"]=31928;var __ZTIPKn=Module["__ZTIPKn"]=31932;var __ZTSo=Module["__ZTSo"]=31948;var __ZTIo=Module["__ZTIo"]=31952;var __ZTSPo=Module["__ZTSPo"]=31960;var __ZTIPo=Module["__ZTIPo"]=31964;var __ZTSPKo=Module["__ZTSPKo"]=31980;var __ZTIPKo=Module["__ZTIPKo"]=31984;var __ZTSDh=Module["__ZTSDh"]=32e3;var __ZTIDh=Module["__ZTIDh"]=32004;var __ZTSPDh=Module["__ZTSPDh"]=32012;var __ZTIPDh=Module["__ZTIPDh"]=32016;var __ZTSPKDh=Module["__ZTSPKDh"]=32032;var __ZTIPKDh=Module["__ZTIPKDh"]=32040;var __ZTSf=Module["__ZTSf"]=32056;var __ZTSPf=Module["__ZTSPf"]=32068;var __ZTIPf=Module["__ZTIPf"]=32072;var __ZTSPKf=Module["__ZTSPKf"]=32088;var __ZTIPKf=Module["__ZTIPKf"]=32092;var __ZTSd=Module["__ZTSd"]=32108;var __ZTSPd=Module["__ZTSPd"]=32120;var __ZTIPd=Module["__ZTIPd"]=32124;var __ZTSPKd=Module["__ZTSPKd"]=32140;var __ZTIPKd=Module["__ZTIPKd"]=32144;var __ZTSe=Module["__ZTSe"]=32160;var __ZTIe=Module["__ZTIe"]=32164;var __ZTSPe=Module["__ZTSPe"]=32172;var __ZTIPe=Module["__ZTIPe"]=32176;var __ZTSPKe=Module["__ZTSPKe"]=32192;var __ZTIPKe=Module["__ZTIPKe"]=32196;var __ZTSg=Module["__ZTSg"]=32212;var __ZTIg=Module["__ZTIg"]=32216;var __ZTSPg=Module["__ZTSPg"]=32224;var __ZTIPg=Module["__ZTIPg"]=32228;var __ZTSPKg=Module["__ZTSPKg"]=32244;var __ZTIPKg=Module["__ZTIPKg"]=32248;var __ZTSDu=Module["__ZTSDu"]=32264;var __ZTIDu=Module["__ZTIDu"]=32268;var __ZTSPDu=Module["__ZTSPDu"]=32276;var __ZTIPDu=Module["__ZTIPDu"]=32280;var __ZTSPKDu=Module["__ZTSPKDu"]=32296;var __ZTIPKDu=Module["__ZTIPKDu"]=32304;var __ZTSDs=Module["__ZTSDs"]=32320;var __ZTIDs=Module["__ZTIDs"]=32324;var __ZTSPDs=Module["__ZTSPDs"]=32332;var __ZTIPDs=Module["__ZTIPDs"]=32336;var __ZTSPKDs=Module["__ZTSPKDs"]=32352;var __ZTIPKDs=Module["__ZTIPKDs"]=32360;var __ZTSDi=Module["__ZTSDi"]=32376;var __ZTIDi=Module["__ZTIDi"]=32380;var __ZTSPDi=Module["__ZTSPDi"]=32388;var __ZTIPDi=Module["__ZTIPDi"]=32392;var __ZTSPKDi=Module["__ZTSPKDi"]=32408;var __ZTIPKDi=Module["__ZTIPKDi"]=32416;var __ZTVN10__cxxabiv117__array_type_infoE=Module["__ZTVN10__cxxabiv117__array_type_infoE"]=32432;var __ZTIN10__cxxabiv117__array_type_infoE=Module["__ZTIN10__cxxabiv117__array_type_infoE"]=32496;var __ZTSN10__cxxabiv117__array_type_infoE=Module["__ZTSN10__cxxabiv117__array_type_infoE"]=32460;var __ZTVN10__cxxabiv120__function_type_infoE=Module["__ZTVN10__cxxabiv120__function_type_infoE"]=32508;var __ZTVN10__cxxabiv116__enum_type_infoE=Module["__ZTVN10__cxxabiv116__enum_type_infoE"]=32536;var __ZTIN10__cxxabiv116__enum_type_infoE=Module["__ZTIN10__cxxabiv116__enum_type_infoE"]=32600;var __ZTSN10__cxxabiv116__enum_type_infoE=Module["__ZTSN10__cxxabiv116__enum_type_infoE"]=32564;var __ZTIN10__cxxabiv120__si_class_type_infoE=Module["__ZTIN10__cxxabiv120__si_class_type_infoE"]=32732;var __ZTSN10__cxxabiv120__si_class_type_infoE=Module["__ZTSN10__cxxabiv120__si_class_type_infoE"]=32692;var __ZTIN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTIN10__cxxabiv121__vmi_class_type_infoE"]=32824;var __ZTSN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTSN10__cxxabiv121__vmi_class_type_infoE"]=32784;var __ZTVN10__cxxabiv117__pbase_type_infoE=Module["__ZTVN10__cxxabiv117__pbase_type_infoE"]=32836;var __ZTVN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTVN10__cxxabiv129__pointer_to_member_type_infoE"]=32892;var __ZTVSt9bad_alloc=Module["__ZTVSt9bad_alloc"]=32920;var __ZTVSt20bad_array_new_length=Module["__ZTVSt20bad_array_new_length"]=32940;var __ZTISt9bad_alloc=Module["__ZTISt9bad_alloc"]=33072;var __ZTSSt9exception=Module["__ZTSSt9exception"]=32980;var __ZTVSt13bad_exception=Module["__ZTVSt13bad_exception"]=33004;var __ZTISt13bad_exception=Module["__ZTISt13bad_exception"]=33044;var __ZTSSt13bad_exception=Module["__ZTSSt13bad_exception"]=33024;var __ZTSSt9bad_alloc=Module["__ZTSSt9bad_alloc"]=33056;var __ZTSSt20bad_array_new_length=Module["__ZTSSt20bad_array_new_length"]=33084;var __ZTISt11logic_error=Module["__ZTISt11logic_error"]=33220;var __ZTISt13runtime_error=Module["__ZTISt13runtime_error"]=33460;var __ZTVSt12domain_error=Module["__ZTVSt12domain_error"]=33164;var __ZTISt12domain_error=Module["__ZTISt12domain_error"]=33232;var __ZTSSt12domain_error=Module["__ZTSSt12domain_error"]=33184;var __ZTSSt11logic_error=Module["__ZTSSt11logic_error"]=33201;var __ZTVSt16invalid_argument=Module["__ZTVSt16invalid_argument"]=33244;var __ZTISt16invalid_argument=Module["__ZTISt16invalid_argument"]=33288;var __ZTSSt16invalid_argument=Module["__ZTSSt16invalid_argument"]=33264;var __ZTSSt12length_error=Module["__ZTSSt12length_error"]=33320;var __ZTSSt12out_of_range=Module["__ZTSSt12out_of_range"]=33372;var __ZTVSt11range_error=Module["__ZTVSt11range_error"]=33404;var __ZTISt11range_error=Module["__ZTISt11range_error"]=33472;var __ZTSSt11range_error=Module["__ZTSSt11range_error"]=33424;var __ZTSSt13runtime_error=Module["__ZTSSt13runtime_error"]=33440;var __ZTVSt14overflow_error=Module["__ZTVSt14overflow_error"]=33484;var __ZTISt14overflow_error=Module["__ZTISt14overflow_error"]=33524;var __ZTSSt14overflow_error=Module["__ZTSSt14overflow_error"]=33504;var __ZTVSt15underflow_error=Module["__ZTVSt15underflow_error"]=33536;var __ZTISt15underflow_error=Module["__ZTISt15underflow_error"]=33576;var __ZTSSt15underflow_error=Module["__ZTSSt15underflow_error"]=33556;var __ZTVSt8bad_cast=Module["__ZTVSt8bad_cast"]=33588;var __ZTVSt10bad_typeid=Module["__ZTVSt10bad_typeid"]=33608;var __ZTISt8bad_cast=Module["__ZTISt8bad_cast"]=33680;var __ZTISt10bad_typeid=Module["__ZTISt10bad_typeid"]=33708;var __ZTVSt9type_info=Module["__ZTVSt9type_info"]=33628;var __ZTSSt9type_info=Module["__ZTSSt9type_info"]=33644;var __ZTSSt8bad_cast=Module["__ZTSSt8bad_cast"]=33668;var __ZTSSt10bad_typeid=Module["__ZTSSt10bad_typeid"]=33692;var calledRun;dependenciesFulfilled=function runCaller(){if(!calledRun)run();if(!calledRun)dependenciesFulfilled=runCaller};function run(){if(runDependencies>0){return}preRun();if(runDependencies>0){return}function doRun(){if(calledRun)return;calledRun=true;Module["calledRun"]=true;if(ABORT)return;initRuntime();Module["onRuntimeInitialized"]?.();postRun()}if(Module["setStatus"]){Module["setStatus"]("Running...");setTimeout(function(){setTimeout(function(){Module["setStatus"]("")},1);doRun()},1)}else{doRun()}}if(Module["preInit"]){if(typeof Module["preInit"]=="function")Module["preInit"]=[Module["preInit"]];while(Module["preInit"].length>0){Module["preInit"].pop()()}}run(); diff --git a/docs/public/config/failsafe/index.wasm b/docs/public/config/failsafe/index.wasm index c76c7dbd3728ed155e216c03efa98567f71bbba1..6a5d0d87079bb2eb9b32eb9acf5c12b39e0bbb9d 100644 GIT binary patch literal 96677 zcmdSC511XrbuW0Ts{8(#zE{)2V`-!jc6B4$1J>9wh7lGdo|4c=vJjF%#=trmuA~8U z?;tUwk$^m4MnZ8!ti(!8^01e@C@)SRERK~tl8`KpWrvN4!*i4bJJ<_}vcbx}oCp z;A2;oMv-d%KsVI$H2%>Ir0zr`ci%0o-vtQoDi%>w`lrW(|GOD4rQB5_} zcIr|MHA-(%4Rs^Gzls0eOl8$jJ19~O)ud20REyt_QIBe+CwGPPK$%LQ)B?iX;15wnm2_yrS|zB^Jkk_ttxSbV#)MTx3oE^bDvPQW zMM_abs;nYi3aiz6Rn3p7TrPKoU0qt2N+qq8s#b$4Q8xjmvbt4Gt7#RMl-jTN>r!1$ zDR<;>Ihs#i5^gDGaXgxgS1m!MT^wcv`B5CtwZlzva?MuQ$zdTWFJi_+T~^t(!LZ_w{3J=&mE`o;!1 zeN%%ztMtuC?!cdBgMM4-R)apH^jL!i^(_s0tKQk5bM>wU{i@QpHfWI^$MZykw(8w@ zoW$dv1~v5F2Hl`=j(ls78pfZs4NCO72A!wZ zBlUp>y;pB&P^zzJ(A)J!q^`ufO~|qtSw4u=RY+Zp)E4~t5Heqb%pXSTTBNQ+>UyL` zka;QoG`3Qrx8l#Xt(5BR_%n(>H*Tdx`lhXPuD*FI{V#e4Qcb*TAvLy@uGhD0rR(%g zJnq7WTag;yO4sTMl-P~0lUwOis`@)hkyFvs$JEcN3lFNRue$oGpHaV}KC1qs`f0WI zfcmt$NBt+YU;Uxlr+!~uc)z;vlWJN`U3m9hcm9W;y5siS_Dt?h&ix~`<>%EkpHRP` z27gg~Tz%;0)Gw=FQunFD>X6!g>4&y&zIA-pV`}i+Yc9QX(T$5XE!wo`#zl{)BkI@H z|E3oGn)(g(uv+w=)o-fbQj6Zd=pnV}LA7XP(N8Sex~Os9d(*eS_q_AYJMZmpfBU(M zu0MCtwdXGC`iGbGZ>Z6XyCbTZDo3tA zzF@J{R`=_t)S!M+=^;m!taeYTrq%8^HLZ#_I9gXHcj$H9ugTFmckG86|MzQ3LpL%$ zs7X)hAwA?y^2;>=r`&NG)a0K1p>~`&{zJWrRv2Xwr&b7D=3Wb)U#f1*p(An{c zK}~gvFaWBFfpl?mDMgnmJ>`@oOHOUiGfs6j=;K z{Eo;{^v{thPw62`_)f0UN{uBKv`|L5+s9LCCLyYGYP?QXIX%9nuB@?Kt7@gjJ$?x3 z^>sj?nh9aV^^iNpudP`d3?XwZ(N?)rYGW{DHC|NGU~OHyM-CbMj~Tq%DrffIhIy-n z5%TmVC1mzhR8oa$sR_PRY60izNmVdqjq7QKC=#b?P2E`I;%1ZtX2=Ff*{W2#o@NpN zp?Xq

VN(j`1AXGS5xTL^kZ#L8_b?cV=zfxJM5e3p}x*RqpQbK^<5Ok(xj%8v-WJIzWfSwtZI%g-~ITqXsfm>WjCvFKI2yTUpTcO7-ZNq;j zZs}-N9LoDyGo5G?_MeV67{4D4ZNk~nM!Iu4+JwA9W<{F}>2rV!lTP_M>5eSgXY3l|bcs6K%^$;3|NQ+#;);+S_sp0i(tHHcfcxz#OgAgdr0jYVaug+@E%SN= zWo&}pP&PO`F(G!Arw$qX4{D-XDY+?2eS?~!s6>|H-e^*(DXZ6D&#&fq!R0gvl|XI&ef^#ypY7}V1lJkteu*5~kCF{n=}KRzc_KJ!-;;rU1h zJSUW&uM^0g&({Y#;JLO9&vgZOJ~F6}D?eYyxwy>NbvZmA8Pvxzc#gH<`A89-u?~2S zX7C*CfTz&`&&_Rkb`;&JK8{GkB&u-~lty zUVOK=;kly#&z*z%RzEx^slB}J$icaDP~YHZ>jW|g_T1^Ap?-ZxfdGYVbl&V|>p0gZ zYil3xV)^1asM^rns|w&8QiFQP!!y*%SNpxHR>Jb)<_7h0576=)oi1Whbw6TRbnynkr~V{FpE!+Qopa* z$iWow)C_tcC;q%wLTI>GDNlOdFO69%H29-*2}pIeE-_EsF=%t|l4oskq6SOvhsl

Gi9}#4tSLT_V^sjCl;%liNWf& zYPT~u0^mVXmIMWaU-tZ6qQU-J<*Azj!z=7>s!SdBzKB$*V>Y_n?k)$pe)R#!=vO#^BRc@%oeH&_}+J+msPud2X>L4@R z8bi;E9%B$NVMX7ua*PW=Iezk}@mF%xoot#;gy9 z&O9U5FoIZ$J{qc$mqnJBk}dOEN=vT7BCinRT()GxCT5|GZ2})K5oHjQ&}v8V;v~Rh zz#Bpk4B?@cR2(J2dBih|;|&(}mBElLK@w<9%T|W_5^UJkxVy1igdlZG=i(kVxS~x+sS1-d>A$c)+ydP`}MNA!V3%Dh*L{B z#kqR0LHQmLhQ7=qTN^|V;An2uB#zf0H3Kx{nX7*6C}5;L%^o0^f2qy*vO53LGvmwU z`Ip`qUxxE9OJ;mon}4x0zO2f>#52CE%fBq0@nwDfrGLhk59D8#QT> zP2fO1Ies%BolHrff^;l{irJtJsMKxaDflaa%L~;7E|3d>g>0#rmLZg%OqDIQ($Gu2 zA?If~ldS|pw$hgJc`0wA^^}F2uflRZ-cDK0XHJ*%LCnS+1WW0>Y#%?uBoL1hON`54 zg&~cHgsT=sncObIUK`z1?igZ+a57n%>GdRSb=SjXbJQY(d4Ls_#v zRedbF(pL3B$e7?57lEGkCRI^N)l$OZ2OpQJY+9N1>f($dH-^rE#WP+f0i8p{Om)aQ z34%_75168pAjrS?xl<=m6(Jb8&rfXtg?15?WVeqerECbwIElO!8<2FF+{<1tT5@j( zrtQ5cB@v8LCK#=-P(x$>ykdemY=~rusT|YQl3QdeUffyn;!e>o}=#$Jvtxd>Vl`6cSLDq!0H&?Aw<>j4I+$FDVQs1cuOQTLC_krPhQkk7LS= zrQ%F8{|{{lPAYAPztW20qQDD5HfEh&`zhuHS04+>7Kl=&ior`Ma!jca`q(qkn)tU_%Rb4C` zYzdr}%9mx>1W-78`ZbL84c%e3pum&0g=XW zwv}@BCk`2}ECLtaOu1+gq@0*!)p@jfcQZA5${k?!WH96oaRM6G!-vhPsTG>s!NX?N z^bv440Ui$=Hnz*vn(o$d_sqjzeK_0=f^h#~uWNeY<32HMqf|9)l93lvaw#Zp{=g3S0g=yiUx=r>jAPYBkLmyzxZ*JK=#cTL}>*x z!BXp>X~PY5oQgpg7_l71?@Tp>4p8rBisqD(bD>02x%-g!o-MDGBt%ckRE~t z;}9D*p>)YdAH5Rgv=9-iH}-+FJnm7PQPG|JxM5KP=9Mv@l_!v%yW@w9M^HSy;t>p_ zhPOoCU#;f?uqj#PP8>3RYb2+dDLIRS2QQky^+OeNyVWfRtZZ=^^vdu0T!U?IvbyQ| z2X)|{JY?K`j5yf%0+usutV5q1k_;4ItxKiV8w}zXdrYzQi0+)|y)RJ>Q z6mp`^hDvF+Mp-jSwGt0mdt9yFP#jOel2BHN#&OKA5oVSByr`OnLI{G1%J`bPiLwQS z0~0b)s<5PFPMc|nUdm2g;eF{$qsjci%+W08v~kwav>?*&upx%2>E7K+K|5hPu)Z%< zt`CPT~ z`Z5axg>#tp&@+of8nO#-L6P%Z)Yh!B0+Tr|ooiN=)vQ@%P7gB>C9uRCAlf=ZPNDpkrj2szATTuBH`Z&9Hd*ih8GXrCd{ZV_;gwW%cR zg~+IcP0F>Ynin>-sh}rnk{Ra^yacQ%;xuG=CLc)woEp@oZl%*O{fYk<>cOkgcE45K0zf`cg~vHoF#(t~|jtbY{v_n7x-k*F~DQMB8EOd`#Z z8^|cb?APPzb~}{!sbIGg%x-`o(6RvrLDIwh>lLX1dI4!5i^sDMWm|0~Wk^#P=>rxm zSjs6zM(T_$H~Fw+%YGWlXQCG6ADLRnn(^ism&WFvMVCOhz@l z8Aezz!w{;$YnQ1;c{Upi>>M)XIPdbIt_-TdHW)0Kg$)J>GN^`_zkq6ppv{xCUP$4A zX8a=tAA-aD))P)Zo$&wg;*)nY3ZX4$< z45ID|TYXhv^~L5pSavYcV{X0zX>V@6!zu_^ebFGWr)|E&A7J&xA6OdM4R$ZI28=ot z&ji9F%4UNF80J(bMBV`Q94wwNHfS>Ow#MU@ITLP~x#1S<L$tDw8krlUbD-ztohN~l6Wz4Dqvoz>Z2WC}SkHFAp%B?nLiRmQk_c2(r zU>1%J9hjvd9OK2v*uy=}F-s$FSir2%V^*h3iDf^$wAsj2BuZr~R$8zf3;awLI2>$N zti=*bV_5_E!MO9@$1)^7^nw$?fd=Cn*)9>!l86;k5i5oik5SZ83L?d6?Twev-76p@ zchkoLSnY(^7QnR`Hw_D@X$?^l1kwh+p-;nK;+K|aStcjOlnx{1^dhb$( zmAe*JX;3B+E1Fm?(hXS$)J^`A;!mP$5e$XyRk`W?2UyccscBg=;imWPKXCiF{J`7K^_03h(;<>o(BDHvmKvv8@~9n@Tk?^~D)cqR8UNWhoo6iP z8DWN z@R$P|t}wmwg9Q|>Fraba3WM#(ilWe>j<_4)KEELp!xJ_ z>HXy5NeF@|o)5e9oTHrTj!=cHX%#JGLk)5kJ1OHP#g{COqQ6l}x2^G67_ME!DmoZ{ z4^ZT$)i{nCG(NEs3U+yUipE!pMo+u%gC=i)x&y}O{dzv1zw#pK;4UB4#7?V(YXXo0s7akDSo#kg81E5#l5*5XocLb zcR^!PCQI|H^4qV2XuZPlu~5ZT_9P`{ub}FHd}2J9vL$Q?1etMYOOe%0EO{F`J>CcP z94q&rXN%@xC}5ZMHv9!KeFsG^sN5r@v=nMS+e!^5;><^cc`K&mO(26|^uPwisS1vt z;{O24h~6Z?&ypmR2~bNJR4^5x4O)=ffsWWPzLL?0#UxBOShvokpdXd?SS4Ekj91}K zV5!vcwf3xXCD z;!H^Kdg**k-C}j9`}Jmabg{hos>JYCVwyN#w;-wP!Wl`HoR_Yk9+TAr_HDh0i&%}{ zuX{ubO-bkob}R5>Q1M&5$4!sLh+}^@B8-f#gS9a4xlZmEIAI9}Ykb1I)&1);$||urL@6#3>i@~j5(t;K z?_d;wVFXB58B5obt}@Gf0*8+vT_Ug)yNT#i3baeDq>CZbfT6r*^GCe8NM6OMSOqx+ zD;qu^_6n}YSdwc+KD!*2We|J<6JbDuNN8(b3u{UW^8Hw3iom zzh0Ue_6OjzO4fzEU(^q)pdL??FhKl@hXYhn>_TBd0Y!wDS+FYzz{PnCq#LI>=|>d6 zm!X^7)4a*f4|rQRyhw*r>Mr-<>)uuF`Pbo_r`g0$5+`2Q?)X8F3RnWd^lwmO133(i zy0C+|L#KQl2Tu8-)2Fn1S&F_OoE8OBAf|k%6G0G|=MbMGWJfFaPa8*_Yj__UJ99h^2!AaVg-$FouyHF00gK0TS0dLk?J#q86u ztW-wC+#hA19?MESnw9$9?9E(- z$}>Pxsc`oQ~lw9EWKOB?(fX{RQIts9zIE|e#a>c8i&_4 zs{|z5hB~>&_Zcx;0PI%(F<95Y{T;iJ{{7dL4dMmJbAhI4H7%W7e_tA|CYm1k35#E% z8?Z@-pRK8A6-79Q2=C-x%=++rmUuQxJe?(;$`VgxiC3~AcsYB6we^6kty6e6=!fN@ zeO}>N7TvIWVIO=3ORP3I!D(o$$UVbp$iK-Q=d|JUlbqI^KE`Pf5OOE?d2QYEm3Rqr z+1?5mToMm9E9$%rw0pk7gU$OuHrOnp;k<0Rjlq7tg26tppA}I(UP)ox^A&b6!9W}D zV&Yz$Q@bzDt=$*7-GejReX+uhE7C4Iu0-x&Fqi%w4Cd6|g8}+`XlAa&gWbBxr7XSVyCVb>XHS6pY@y>sgCy>sjDz1-jXX1058zz#XmE<5Bz z?sKKN^!Ib6IgRt@N*L$+XSVyf(jYv0q+RjsaX&Yw{{GzD`ulU--v?&4`*Q)i1WCK% z66C%!r}_QP+~)T?JikX~w)-8!jz-chI~qmqyK`#yyK`&zyWH-lXSVxYGYF3*X;(a! z+!yE6?ic6Q?iab;hi10>MFUqSX;xgF+?VFm?3d=&?3cLNM`kwrB?AX4X_n6_k$Y)Q z&Av3ZW?$lFkIroNB{Qfu`)0)v%e_9QW?!FMv#)crkIroNbp!t`=`H(jxsT3i34L^K zOX#D#gdUsO>PG|kgh{J7N=5Dyb87Vyb8Gbz-0I^qTm3{ZsI6}m=dZ|pYfdBlt+|cx zw|In)&205sF!lDW;?Nek{d4N;{<-yaKlk;CnXT@JW=2|t?~{RR=u&b|?e~1xllzTZ zHmE7y!tb8m4^9I`p5AZp5y@xv8~1)Bp7o{T&7ADa{ETFNB$ z^x;rdrW|`zxnN^oVhZs#%4`n_t*cY;3OB9slpPCfc|%_U8#^UJsfxF=H_#RY*4$d> z_#|$*M*NBj&V@nzHt4;Uz^B>;h^b+a9Y1<6lqpWN#_P&0hf%pTtqpa(SWmeaYAzQ$ z$gzxzH}-K>{6hb!S}Xz9Y(2v&0yd%GQ<^xapfYN03WnOkWC$}Ix!4ABiZ)2~i#Vm41;|!T){TiEoLb(M$k19kn;t&rD93CKQjU&(q9xoEo2SFmZvjNy8eF6?CGlg!>@?$TLY5otcy^ z#lzkUGw{AUP$1k6!$Ei{Ze%qF96yR}g;0ws8$yboSyw_Q1E9So6-vB#7)SO>Gm7{C zz8IE*gSy5>msUma=!c%SW~ncMU!n*fRXcEt_}gcJTcAlo;1(4<5UCP`a*E@#c=-ej zhJak!hiPGJDvdnsWx&z`4I?x$|A5?(V6$Oz!y;yUXA8{&!y>V62w6;l@EJb33v0;P zU>kaK7<0o&jjdb*_H%@B2BZXOzy`c*oFP`RWmpWu3|fS%@cCf#D|wDNM8eF_EO4)C zhh|}Q4<<(pryz%v$!E8F3C-d)`t8sxCJ)WR!3Oe>5E7b&-Tv5^h^(0zn#J4mcZOym zs8U&@VOU9TBs2^687}ucDsbB}tOw?yVgEe-052~7kXf5Ti;uY!b@j|xEKK7HrhLFU zQKn>F&*yiJu~@jqLM)b9YJ|l0}_ixw=D*-jUndJWU2}lgCJ*Q z+3OVs3a}Vtr6P2g-t?VKu|&zvu~=Af>&-M&?sA~T{p6Q_FPMvx`8;lp4D<~MUU!s zY?#~vA1SL`wKeY?s#LowRi#bPRqg7kRKrpkrpK%Wf)A=EhQbYkV4e2qLIpwYte@U{ z=1L~eO2 zRjvy2Y_=G2QyhorsZaiw|3>gAnPMe+*H{Xd5gUryeK+`3P!~w)#iHFTBV~g`+b}Uw zXBQhS>*(We*5^#=yTwJb1hpqf&Skdb-qB3n%m)6+{A~UVoQe=mKqas)^J@OxAK;h} zwPsSwGFp{}2s2cL#SG7R6&4{W7#|z5E0$I6ZO}1Hy(67_!xbH7p@aT0*?n zw(8(bmsH)`Bn(k#Blulp&8G`KP_KG7`^biDfm1JM9bwy;&`l-Xz`SLo(Ep07!Uqd( z$!;mD7M*D(p;O5@wvu#5wgl6n%N!+LaMoFdu0Xl1+*_gG4HLF043i2wf2PXa`UjYI-sGLTJ*}M|x8R=2Q z_o&jZDN1sbC_B26VfTg^z;^TkIk*FexAZ3XJtTFvB&k@H#z2A4{eW6-czqqn%L5wP zx?4Hcbf5nx)dapnm+vaPv}BlpJ+2RU9j>X@Y`3_Q`#J1Jzr+u+29z_l8~tKRupGP% zt*OIue0dYBal9TdqlP*UFn?ti3>XL1VfA+E)PERHtF}vKXuL1!a+Gwt->W1&c79Uf z)#<~H_?6oEG-Q20uO5fPoa-KUW*FMkdS4p4XQ(wV2^RQ&@q%h8j^hO-JnPUbSkSdV zEm#o1$H#{53)Grdju%7=;y8wRuKQ~mu1B>uN49jnS)MF(zgMY++>eZA$giz~P|T|k zHiji(X-R}RS#E2P;`bFF7H1EStT0qtls#RlsMec3z?x@a_JA4|WDi{E&5^6vGAx}p z_9bQ8M5+B{h7_HMTGZPenUydRQ!hI_Rr(o?cm^6ay*+NQp=lE#kKqHg@h zc$X@7>}$%ZzBEe1wC=4qVI`|VU}Y#$iEGvq$(T(wm0-Nf)Q*90VJY$T^eE6=(d=zu!W7TiY~*8GlEfZd3{|) zk^3>Y?;>YSTDKuux1skhW(ikPVJL-{@D0H`lKm{XDY)8H;MoZlyKJL)S-Ul;?cmLZ zzM*#PZ@c4uehBTnb$v+)58(_Is|-@G8)7F`J-^z{7yaqWa#!x;s@%6yD`ry+YN8jGCG=ucEJbWmFlcTgh~uF z*&f>+FSF#9%R4tc9bkCyLLux2XNqitq7|MHmNKR=-VPkCgGRp0GCUj*Ibhh@ zq{0$jRuJdGtSHs-`5bo$&K?LAqirc>Sz*8Kkq}I5KdB`y4V+RCIty0#Y<$gTJr#cK zW79xuElI=1df_vgpn7po~Xdi5OndWGh1vQ#ri81V2;1Ymi z5NLuA&VyhY?B>TN%$_uGJYf_7Ct{fIO5qunF)MIo#*~#79+=Eq`LPI)2My2{DQQO9-|k#!E0fHZYTts7WwO$9M|+hrQ8rOps&4fd^y~ zdBx%#el2W-Z^mVu*NBfXgUSZwR)fJpMJ!6ka@Edkl=xsGq}JH|5b_LyFnpC&t=H5c zSi&20Tr%a+>?i^mD^%qVoM#(pZ847gJi8~5bDDEG1Ai~IgXxqI;f(RgFyUi%m29;-U-rl;?Ar})*; ze^u_Yc!fZ^CN}Q*e^u^FRTqdwwygKqxck4a+#lmLxvAK=r@pV;=W3_rntnyONAX&6 zJ^G4r(_Os%^S>$H+W8;FA9gRiqTH$KDq1xaf7m_#s&fBUbwS+aPQI$#C%auG?sCt* zs@)H3an+strgD#eUd2`S*nd+laQ{$?OYXq8l+*6sdR%hHzlFE=Bl+UDRQx7)-wWvW z_y1VM%015M=RS}0^Dii;+%IwZ(6>?kiT@q%AN{s+#{C1QpZzu}``F`nf8ZaL3*AGU ze&iqVe*ZDNf12MP;k4BM^Pg+i|KB;k)PJ1cOZ~siX{rBf44c&dD5qchN98K+6P*6^ zKPgvr-{t&I{gZMf_Z6=5<$qGH?7oI}qqh(QOqN)_^gt$GdOVXabwk$y3edEAB~ipy zu>3qg6#ae-qxe_;O}pt=wLAPOP~gb37@S{!7DFe0pR2pycvd+bN1Ro;Bd==CW?T@L zT@WvXDuJcPNGqR4wSUmf`1;VZ%3G^y~RH*6qGayzJB(CUn&%oGzxxd z{#i%$$wEO%qu^JB?!3`F{#l`*q*3rd^{g#^xlmBjDEP}~AJsoE6qGaye!Ftk7N05< zlr#!{_3Q=zYoVZ|QSiY!Q&|j7*%GILR%NKN*V=^p1t5-7Ya%m1s^**s81IPN*V=!BXD|3np`fHu@E^`z@au(wl19P*7@ZXX zzELPBX%zfn{S6BK_qwaPqpxcBJI`Xr>T(oocYl}D?&(*x`@yryMXts#4|c(0$?qR^ zH;-RF_hsz6CtuaPZn|B}Z~waLjC<`>?Y{b)a`W9e{PKHW#&&)12b!1Ln_LgS{WiFl z!#~jO8_y~CX19P}K3R9lefm}H{`NWL7P?-3`IlgY?*D%j5guVu0h|@%;vt z>f}!TK!fp!=SA*?SGBwUHSHdHE!!UZI=06z9aFqNE{P?ta*w?x`{TLpEpgdZcz={& zvF@#4aFO-=%B_Hx8T>I9Mgzw47~@0{TiP*K4<`I51eh7J7%9JSocI6w$BhnOGNclvHC%) zSJ{IPTJxYaNW|SyNbc!4S^ynq?j>~mqoPs6$6u??`1pAC@g3f|fn1GayY%Y{czJdX zR^A&B?rYN!(Wx4S2vs}>^qv$H7AdDA>E%w4V@RE38$SZ_+ zWLTzlbG&~TfWQ+Cp+(ulnq4aT;Ubl}X4=hL!^8RL7H0PvLa8LZWsAuCgaBLB6aO7yS8fCdMZYiniEuk^PvjOSmdFY0`2N z1={k?HE`c{u-$cR$Q-W~`d*SjiJc~=)BM})m%CX_0GaQHkk?OLu zI7|I2{8|p+3>YUfR}p`VXZ3&|b*>U>c#Y_c%g)# z@a9Tb0ncd_dZ`8C(c+*!wOjman;W6j!KplQ<-KC7!?QyXi{%0YFH`P&r%s(R>)Edf zx1PWevCQY$L5*m%vD~o**_JK4S~Km!ZA}S|u8db++`-yp!^ad=@%gEC^=7;f=qCQ9Y-A=* z1*`(C@qr(%%WvWNg6nEbQHAk2UL&S~3!{Kmk$5w`q(uNFzN}(OwFF@{WAv|wJ;dcE z8fZ%4$jZK{+2u@7BWiys4a-Il5Ea56TpeW%tnMnXfq{)4tPNOqP7%a3?9a*Jw&0YS zmSF8r67rUXW`|k{bfB^!twM?@L4+LHYF{g@z_Ni@ho@Z41-9DfP1(p+TCCbbU`e*( zy37Wtf>5xPmNTeI9;#9f)fyJGgoqQzPS$Ve2r9NFY)P?%eMb$#;eaMM@hQcef=)m` z2a}E#%t7I68!gS<{U|;kq9NRSrs0f^9VvcG=qQT*u84_WDdKtM z6@*rEd@>*@jCTgH;lbnpedPPkg3KHhH}8SAq#<1UIr_PBT_UavIRpUAQDzANz;WhO zd^6$_pyzCZqz9;5T;SpPj+$C9Muk{4#)i+tCI^M-9Icak2|!2TZQR!Z8NzFGMD{j0 zfRvWwhNClVd4h!rQ=S4ea9i$x22%1Cn`&~fwl}x4pth>Bi_Wewk$bLIaKl6BqXc|0+EdaRrgtfhqWwyaG2J(-ez1!gqs2C z39X9cE;gf1l_!DD&lhue`qi1=DQZw@`e}A*fImAevJQ{ z>TG!>Asp}{h+m2q!UWlt3W(33W4PJE6QOb-S?Xp?hlv;?zG9oEMsDm_h;cK8K|c@Y-0s5VkHQR~wUHh#5?5iOP=sd|?=Z zet3H?UVcd#!9|)95doAC$e3cI1H%h86I*z#l`6junGfMe{)#KF4$2fFCgw-9lJdZsL;nvUZ4 zP!z9Z>S312>P5uJ4B={waL5g9Ja!DvZ*qhoFqs+C#DQ@u{92eM!8j)TxsGBfMJ-w_o`ygnm{2Ou~1uNld(2v$-px|rE49!wy^ z9=2TpwO~$6+`qXR@BU5Ee4;4k%|=iS&_&O6ZWzA85?3f5v|V z_jb(o7TL&UQ=yKvg%GG5_rz~1Ov)s#y=*E>TCrKM`3-ha_6cY*9RUqivc6dJ#G6Vu zAAX&4*i^n)QWbwJ@DVpdUOs_kZH$(^fa7LZf(<1{xn`SWnlT4I>Wu(YR{YaZdqvEae*;@%g; zWL)28RleXQh!j%_Ecl8n_-bUUV1mcM-3ahyo+1FB<{T54Y_>(IjbSB+uC~*uCSnwI zaVQ#)N>iF!+nO9Zy~`Yu9*J3b^}_9l~tgn2vWth zgH)h)#a(C0#z&SQivG_wiC}HB(43G-ghb0ppnYc&Q38nwm_#6YFQ1v;kVJ%j`wa^u zBHw;7s)a2kmy2|F6h51GC2TqpM4oZ5Gg?5B(>djcWxl-J7z2!$n{ zQR;kq14we_=7R>7IBAS)-@Kt|(=Hn?kOio~ z+q}nnwl|*@?;(}w+}~lDCzM`-S#m$IzXN!7ZsLo`+RVh9@SfW#?D8;!%`hMFvLJhK zwM-b9af%iu!;lVn!2*OMfCr*F!x5Xawa4MMW?6gf)sd}n-fD%mFcZV88u6xB&KH$f z0va7vI+#*-wPh2iC^elc!pNp+{HBQ&fm@M^D}o~?;w7RP3;G!_q#OV*@UA#8cty-g zK8YbhoA3*=Oy+l!)%k|0c|G7X!u(TaX0eo_-)=8mw{ZFreDF^k$c zzJZKyP+&?pGH3_I3H|vhr#L~*@P{^FrUV2vXxf0s7vaZceEImREzOVTMsfZ>1o0ec zF#_*ywdn0hwLsp1X2VK#dm=Oa()jHeBHR(Eg1pB!O1|0UfdP=FgvKd z{ZUSRm8E>s#TxU|BWDp_!=S!Oh?i{ZHe_PN0WrN80JI59UM@RfCa-Y3fLVB9(dWkt zFt}JA21g&R6AK2eJ>Ex1RuMMfOu`s+GdXJIA>Xp`;xjg3z|lNoc6OL1#9t5KXUh8? zjCX=2H-$S8EcHpiGLE0j%Qh@DXjoc)9=Q|LN~;_Sj;}R<+>jZ-6BNHCRq(}}KOYCO z69ie(JQRo*I{vu;wpBqPPU2KMo(o*EIK&7-u^~VuWYV~1F~nsf90gCpxv)=>K~@O4 z4d-I_0SsdgVx)+)9ecXCIwOwDR3-xAD5RJoiP#5qT=WGI>5B>m>LUq;B&X$NZT$kf z*V<-k&a9AOeu)IWvcMmS{P0eC!$2kFyh-#K}3V*_S+!8-{&@39d@S;pL3&B5=$c+U3A8 zdAkSLO)DtIjR_=f%$(ar;FvkI%YkF^b`Sb?3vputi5oNLb`dyc4()Q_n7rLXzTHCH zm_Xvj%(-0zj+sNd95^O#_poob5H}`}xG{5X7lC8u&@Km#$=kipw_AuC6G+^cIk$_z zF>`2_1IOg;-tXHj#El6gZp@t9Mc|k@w9A2G@^&Ba?H1z31QIu9&g~*_%pBU~z%hBd zM|``5xG{mmjhS=12pltqb~$iN-tMP;yM?$hfy9lObGrx}GlzCLa7^CrL%!X1+?c?J zs}%Zpc5;QlF>`2^1IOgeKH{5g$BhYmjLW$;i@-5+XqE%Vvl1U@k4T$@GU zm^n1dfn)M!AN9?)FZ^F>`2@1IOg8 zKJHs>$BhXjZs%NEMc|k@w90{F@>Y-eR@-r7pwc??2($Y>PWaGMAZQFD*X=EdV%Zj3~K!2K5uZ#dge?05M|%cZB1qU-v)PY(=;vc*^2lVH5r7|DSoXLT3sb zuj%B=a*kKRn+wOwJXs(-S&&VYzyABQ2!=Uw2v24Tu?u~89}Zjn>k-_T;qIBhAC_?U zZ)i&^393N$0FDnVo+_0%n$_T9@B@rPNH@25KKDKbkOWf3OFvRjt zTpm+$1m{f}pqO<;p#--N@#dVB#8E!Tmiv+l-t$Rqpszr*LC5nbzRb~>x#Ut%RA~CI=!w{ zv(~k)UDrqQy0&!GwfXeAu9~&3Yuj~=<#lcEsOyH)>)JYNT{pMux-+k9vZJnBPp@lY z*1B$Q*L6tcl^swWwN0zjtJ|+;t?!_c3gJB^GR^_IM@vX{sEGLT2KG3EzX+o=-xcB1 z+LaUnZAIyhdvDaF`}Nv*T`gvRM8pSTvjov1oo|ll&G1+Rs_lbLLv5It;DA3aWSkEL z?Mi$V19DAkr#6fyAdXlIFiB~@gts`ZK1NgyRG3x}XUYZ>YwCP#@-MBK0IDh%w)k!a zILG82!+j-Fy8#6I=R3WU5UmBuIhKB3Di=p&#rErfUn3*|->3~r zh1?;(E+vY?*5t3x;n(FXL_wCj#;+?9*FbW+E>H_0M7}pXFfMG(i+2 z@Q^R9#r2aKtx0ekOaP-;N1hB&1c?sYd0toJg?#b^y`y$LsE-XPE+vYho3)x!cVRMq z6l+9F7wE^ek4~$7bXxrS=(J?@XIGf}HIxMiw0ysg-UX^{+?yrP0)mxU?W%%@ui)|& z_x-=7_+5_WPbPX)t3bTr)IfIqwCcy5_j_d_x-iksB%!M&0TzTSi62^yD%7tZg(_%X zIi!-(rW{1BJ1My!32}K_IWg`Wxh@m&Fao{}({&}r)e{XzSIstD@TinqRW`^i;h`)+ zDz=8U4su&1QaUt27@<-$Q%VfH9m|P9on2D6nlb;{{XmU#=x}Fnt*q6U9gcm0XC^&t z!U@s0ifu|9ug-NN#uzI#N>Ye}eFV|5b4__l-K7x9BhDo-yAPhql>M&IN zFIzbwG(>7VDPiH3ogQ~;Z&Jc?E#rC@jR%c~%D6LlP`sz5&3?2upj7;QN+mVt;la@fHA zv_^~qT=MEZ%1PY*>VAfkxW>W#Z0S;k(9Y1lpbvqof-d?Oj1(Z0_`sVPxjz?L&YDUa z#C?miaR%6jP3Hi&2RSYCFq;pJYEN0 z`#ps57P0r)PS71N-n8a`Nvohw@IOCi*p^+-@Wcc*r~$e{2KPm{E5E^L`T@^|Q+{pr z|H(ns;1I|?1$#wx`k*q~DP0u%0z|e6-2xCYWy48#|MWr441*ben8Y`pQfpcYi{tf+z#9{UHA7vCR`Nl$56rcdg*EYo(sECRzww}h@e1@byT zS0`0)Pv28X7w-s^l-ReP`t{=`tvKB2y=r>@eMgV{z2b;8pGj*6A56-trl$`aJZdc- z5PC;Xy8FMWGSi}&^n;jwh>nhz0WP><-Y<{?2)Vx|j>rL|_p93s&=#4*mqD9m);Y`U z1=0|?rxD^Qn?xoBo@yJ}kkv+5MGnx1r2c>LwC{;GpnV>3q4R1ZE>~TiSE3M+T$tK{ zXbIf|iz{TWgwz?R9?oBa+3@KBVt;j3Iv3iI`AYCsb;>B0Qi@>SI6&7(SN?Ujp*oFx z126J5_3tU1ufngjM;aAv7AQ{o0lmL-Krf|gVHde{<}QNsFK;3y2umRRJeHio*vP1I z%h(jKZ}6rf`^y=IH}55HBTQjvB~|#ICnoEK?Zgbwl>+}id-#ua!r!qOPS;K+WwH+% z(u&CzL(M6Hv9PO=`^wDr8JXyO^NLPuI6Q%Q(RYIteZY8DH1ez{emyH1`HK>4?au3k z@@Xxq$X-q|Xe1CPL)mxLh`R)CExp9W)#_MY`r@)@C$ofGHl z2vA4f8U{wzH4uWK!yzenHUMc;!LX4_!Sh(0nb9UIJxx`0qG`&v)_kJkFKZub>-ruiEA zw2_tai$BUz`7o@}2I%{^dO1f0k1cP|SNAt^g(jF#zi^5*QNMo3xYvHSjKl65SKHNI zfmW);_NTHvQ09LQ%nRf6EEVvgzD|1iZ+yXYzdmBlyv$~2&q{6fj7c)n+F6MklUvY( zuk#VS&=nxV^#aJN9*{=_kj~Ya4Z9FmbX}IEUz|)j0_?VJZjpBZ-fbB$A^9`OE}u65 z**8vuj4z-YKv>dTWFvq+q2UA9ua9Y1gU*--fl!37p7CH)8oo=8O)Zq8wZM^;^aLmk z3ypu7e>)Yxi5W9!7izL94yq~A984y2%dte?zDnpm$$atL%?>IAcmP~HWs0e zuFQidw!e^7;ATwmd0@c2r;m4f5a*pLxqbWKVH_=n3EniPQ*u>ANdAL*{4Qt^Ql;+3 zdHgfhd}fvX=mA)_%%4YT2dDFk}KgbUU8SeE*Z&7!96EF z`{?^|vnu3-)6?+;eCkS;-1Ky1f^90*FkEt`r%xavcn=E*1adBL7-8c%im((qfw;## zIGB}#AwOA8ZK$&?c)3pQ9-cpz?Baf?^9^wbx%~F12sxPb=3Aqtf9An?2+V3L`feLt zE+?3itGDH8q8s5r5dDta%Czc*^4%*8$z_;oDPK5tzM;**5Uw7x6(8pn7m^JS*@}yr zX)r*D;_h^OnN#s)KsTl)xYh8Jk}nt_wU%$G^T>z}Kpq@l7Wr-@RS<%_e~A24-OOQ# z4{|rtF0f7jz*cS7o!81(NJF3rRg8m*FcA3ve1o8;ho_O?Qg_{%cCF&F*Y{yWa9b2` z60^>C2KMWCehEFFHZ5G9+P>8>bW^w&^;6kpf^xm1_%9RAJ}0$%?d!NP_oT+n6ne;C z{21i@xu469XXilj7e)^1U;#fXl6t1;CGGfFH{Mm-{ARiR3Zup&ar$bync7tQ^!wGmwr7NWbMl!Y0?wbtLQQ z5$r+o}Gn18%v*lkbuexcM%r{9?T*zgbTYW%qS@xWAFXEf;qd;69qcE%!s| zA%CT30q$ptaCcPTTjATD1a5!Z)7LxTmb*jwZYF`7?`F!c5sdPC1ocpMO{jfm-fm&8|$0@;ejt zP;qp-a^g@sjN2og(1q0Wb&YZRQ(B@BFfCE`FoA3!519K8sSA%vNy=BQ~P0Ex{1d zh;wik;{EC{{DT&XSLN;`rw^uRp0GzQuK$OnwJmY*UJZLUOtc_ctY0}-qdhm zI4)@%pmQ<0cNbU$#k*iAH!p(0Py>YPUp+%;;84e!Q4%fE{+!XkX>5QNC&oQ07b%9p z5N@JmpF>3W@I#qYVJa?8qU=}2Hy*?3vAXKW7vFN{s$&O!Z2HG_&HceQl*Prl(lo5R zVb-7{w8?uJ*ajYT7&5B?>dQxb$^3{?991xv__PG+X-W4YU0_piy{0X(q4i>LEMP-W z)+)Ip+h24eH$b;NL9|tu=$gdiU>{s4{3^}(CT~m5abj4R4lN-^R=MxH99acd+Aj81 zCKVgTi`mhb&A#IwkD?W4`h!z@y1=lSV-^#3T zcpgNrgF(G4ir%SICt`^+qQY5bCRTln<0bq%JH=yg=035XcGf3!M&Ms2YC}Iq1r*c} zg5d=lI+QsM>cv8@6%>2Rc+Q~kW#vD2wmn)z$z)p^-k?+;?U?=?GpW0NEfO> zU~F5$l4MCNmbZifkjygApa?P=#!BmXv6_*H!l0t-IW;?LtTbTH?xHL8z$R>f6+hE+Cpt(lb`a~!`KSNFNOzG?a9GYQN zD2iNxki%`WXBY7eZ*YT>K*HigUI5weRA~u%ZMm%mk< z!|>x07u+487k6&GsEj?DD(FgugPO558%IdVpwxVe2euL9#y1(Sj$NDqKoNGa&$jq1 zcp8{mNZa~#E#3xG79B~Kq!U>-jB2|Rh!r3Oxc8Fv(UW;NHu+qHCHqL(Jh7m%(sbl5 zi7$Ygx^c92C0#1w%UHbX+L3{tz{RnP6V4@sQB*8XT5|Zp!;n4GB3j6p+A!p+Jsaj?{qN z7%M#<^{fS7PneR$-2zb*y(in=XKSj>Cbhd1_0C=*ihfhc7Ch8sbK)t!Gm~+&PK$BB z%Nqa7D42~pzr}r+`FL|=#!ImbAp0|5aB+VedrBG^Y#$l}iwb6x?eR7pL&LLr{)I~zk|QXbJPP#ujI!M zd-jR=SBm1tl6!(I@vJXpTRP!@6=x@-3iydG(6+qP$-vF(nLv0b;(P1|;lY}>VS=O`B$8QZmc zl5T12+|wAt>&b~-VW?2eu70o^5a?6h1<-m`5tHzw%D z?ISyG+1eOu?A!*JCU)IQA8t(SY>&q1?b}9g#mLL6!sF=J=(fqx?IY3yx_rm(#>6c& z+!!0%+St~zle?@Nn_N9PG1l>J^RC_eZtJdHV|44D-8YXQH(}r#6BCU)Ms|+gHZnH4 z^QOt0+n|o^+IbUAj!xXNVr@8@G>ao7geAV_Rda_-=Ifwvh&g>8AYcmAiJ1QnvcWcHK5IF?vg52Rb)0 zx#N~m+P-Vg*0E8#e02A=(Vg4ripI|E1k9qnyLN1+#?G7ej5Q`k_KuG2+O}izj*%TZ z_cq3MY^SkZX!;DV^VOQ=zG-aN*2dWB?{D69%joHE8>R!Q zR!07@JM6^hj%8{2Lk-A*@-?YQaYNuH09u^qSU znB-+Qx_xvz-L_-r_L=YUemBO(c5S1Ln^%vl+jPa{BOBedBiGZ_>o<;UbZbX84G&+v zX3NO+bj9X1BWpKbJ#sy**)V+J$eL?LHgC$G)^Ge!@e%pt>lItpT)k!F>NQtpFSzhk zSFSB)-!z=%-n?eyn)Rp^sjIKN%BQZlJWH)|NO2`sUw7pe22pYkU-4l8TPWLpLV0=O zlABj=T9akG!d-c}FXL9P=8mr$S${nSVBN_2>-_Jv?fzeLJ*{>lS8dv|>8kgQY;HeX zQhZoZd>AY~TwHv(sQB>S;=_f-hxc?mbUZEZ_{2|Fuh~4Z=|fvKkF2|%(^qU-i{w?C zMy_)o9=UqU`qdjoF85=&_R7mg)(j8hx!oz(ez>Igu%h@dSbVs+_;6A2;l0I&3yTl$ z>3HaPTHf)ApJt%rb#%>^k>L-IT)uvI%et#Zt{%Cr11tSghL!#?!^-PsVx|9{VWofc zSa}^r=IU!kR$skhWXn|_EIbd+c)obX^F=eB-#g>^!Wqx+nen{bKW|(;;#Oa^X=Kf{ zn>S^^tzs0;d$QVHv1a5tkF(cxuH|d5%h#??Vu|@AaK4b?8lUD>fd^g%*Iq}f+?Mx_ zTr;v}U*WD=FZtd(vf6EStNqi39Z&CRKdoMM)rOJvn?|m7 z!)vx&N2@n&92ws9f7kXUU~*K|{wM5703qxUVAvA~I6X7jNHX2kRn-gATdJyO3Be*H z6EcuxNG5@>HUtrbC-}f950z0sQ9)3H0ulyLFpuSd8WaT)1XKhuA}H(Q|DAJwx2k%C zy!ZXzd-Fl+{_a`sQum&F?zy+SJ=--ImS1zinpZ4ap1cn;{bDd9On~W0Ff9qDCP7CM zv?oDZ5~P|y6KZWD2{LcXuh;m6^--=Tw1Uv8)k=LrG-+v*zBwh`e^eiXRr8xVke#D+V)?V0scvOME z+#Zu5tC+#;{J6Dlp|L5nYjsJpF=m&imn_H6hNYsfNXAm!0ZQ-Eh7lRY|&C+TJH%d$MxnWaG?NwinxwW(GUEJuNho!Z(rzo zG2}(3P>rOy?W~A7O`6rr)m*H8wPaxm%9S82RUCtA%xQ;p5NkF&Jf2k#sv;`yq?!vW zQDMyORC_eTvqR7Ki(##Y9baiyEi8!_+$(Rvvy`CSI!^|QsdjH)1eKh~;EJ5!dR<0q z5cVc8C=UbYy7o~0R{C7o!X7S-Fw9cxMo?NT`_ z$g^kSIRnp>NlZ5xCNa%qn8Z|*VG8Yj+1_OD$Y(O_`B|)nIw%N5x*iD{; zks5fF(DAx4+TFRljO*fIW9MD%#`y8WVx>~;7A2)1w5#1DVG^h2xqj%m-QxF2LYJgs zMF3k-rh4`aJX0ny-DH@=G?QTxQ%#0RbeIg2Xg3)q(PlEDgvp2!t&+n|ay{D{mW!3p zExFygx;bt)1_XMgTrUMhcCckU$ZHG(t1e7|r1&jyPFY5rPl2w9R*#!`berQ+AWe#r%w{%#gY88Q*Ju4J8Ut(w3WnjhmoLD?| z(b$zUxZ4HhT^i@}#){vz0A2(OmLFE?WzFDDU@FI$go7h=K|Tl_U+dl$X1%KA*cNbV z6mCu6cyCC z=m!?a>|iQl*U2fBLbum;YdY#YJAyKNbERqzyX47@Bts!)tCr^oWNXB}d3%J!HZdoY zESu*k0Q0p)sBGn9VA(u<6MU%%m92aXEZdF&>uXK&#lW&{1yWt!Z*$|h01f=~ltaHz ztp>(eyOlf-*C>J(+SPhRpagIXtd_%Cwa1OH#M^?BAzPteYX!)1_@vv*hj!ib+)AK3 zp`yb{&kpT^RSE4%Ks@|8+!>T*dgW_=E-VF9spaya-@`*NESKV%%oHmV?X+h!!|Ba% zS~Hy53_F@(doyfnhN)3-6mA_wHkij*(Pw9-=H*J-S{<`q5L(<$%)L_J3FgV3vuZU( z-9goOQq0WL7>*M|_1k#nGK#DU1Mbzp>T=m^8A-?WZI|auNe!8JivU4b4D-Bj)rx@{ zpuFrTixq>d7#9LJECjMqOwcQN-Z@H!u^)wimj-^jJ#H~ykYa<-uQ`BK-wEwPScr%{ z#Y)~lF@tQ9*rzMxA;}=&d4g3A9XB3_GebKDGm>C>5=={isY%e01nmHRcNmlmkcrrq zq!=KSRFYzVQkqa}lFtC;6U0F`p1VA(YIcyY=YC(smL;ahhj0r!9j*q0(85> z!0$5dkBri`FkkUCnbKr;5N1QiwZpRSixXG2d_S72o*y{|`I;Y%{GO^n_F(G1TPT*8 z2oImPOFpl{HQ9plo7PqamK-v2iRu%w)56H|{F=Hj>T}jC&no+32mHQrwp#M_{Gt-t zZb?B~5~Ly^Q4psZ+6C9{@=XW$ffca9mE$xsu?0xzMW!`ZnAfIWmnjvFn&m^k=(zmO zWNTp%CcjiQIkt@AQnKCixSh!ZFE3hD^;jy#dMp)VJ(h~G z9!teokELR)$5JuYW2qSHv6RO{RpyY#O_v4MRC2D(>}V%8`pst5V+-!{oaH?~hw0*s zqHOHq49CqWM^k9A+AXDJF&3P<77kAqFxw2(%dNEuS&TTpBz_To5LZ}UT;RoB@0qhx z**e-)&x_m(*OS%TTh6kBswWc?0Z%bCx-YQUyN>t39D?;L%FJV%7bmNz zbt+WLZpf=~(UUc@dmbAeP4@Ol+UwC6rvSEs+_TJ-+%gnAA=zFr5E>6CbP3ZuTVAIx zK;}UYue?l>uF^@SIwRw1l)7ct%exi9xt=fxy;7--iE^-)tEi_$uMJ={T?ts{F<7FnqQMS*X-Y$}5s682bLMOIsmUpj7JSHfyVgEG->r&^Jz#m{_>_fbXUeVZDoWXMv8G7_xti+4DoMso}HelD;>^(9A`zd_#T&zUi zhDn#LN<@m!n2YE(JwsLvd0Q8AhD|5PO2!FtvBGD%vXFsb4uOjmUbS`6GNi6*BBL8e z+9MQoUpPN90;~8?gtEHN=-nfx^x?8L?9q3AxXNnF!Oi;{6vO<_{GE8Ec$uNnj zCc`8;OomCcn+%g^GZ|6BWJHNp$!R*0)po>3vPsNGvc*bdQvwF&2v(DF1gl9og4LuP z!Gf1hSiu`7

tMajqP}f|n0lH7Q51;Ei+T2o}72*b3e_DMzq8%xkV}^5!y-dFpm2 zKsBcTPOY59@+&eMjk4wCjTWoR4Xa*}u?e|2p2f(m@h-=eOAI<5*$bs|)(uOp&nbW7hs8+DFo_gW$<1G}OrFhwBuS)@G90`e6hf3pA!RstgD4zPB88OU;4PzYM2Qqq zhJ!be!Vx7>NEr^^RtiUyNFil7c%vyCaRMpB!COz|K#GqN_<$kc%U+D+xFJG(n*}J> z6MDiV(@{1CtV!?HJFd+;11>WD{e1Jtc`b@HL8{;022KB1Me&Dup6B@GS-<+19d~ z#0|9>ODsfBrVUPw!mXn)Z(yn{?x{TQV3L@(Fb1nN>{ez0>=TKoc16ukAii82)5Oxp zknaq{$niKF$W;(M)trL(>^WBwDi^^1e>JGu)sjGV>H!hPW^YfOS-vUBfCrwYIIzQ= zEZGdWk0ZccEPw-^B~5bw>SYz7Ake^vz@?HweAF8wKG2O3AKP+$qV>T7!bL@fy#DAd zK|f$@rp$C*B_cd+6rMT?cZ|aAqj1|OoEn8&fpZ-B@Vbk(8`^HMBn}O~ODLcQ<7eE6o`kh;HVvYGGltNK*!jNCvxK ze7m;fGC!YC#>ia%U^mBcOR+D@fX5o&s&V=%yera|%}c(m(A+%~qr$4>_#_Ofp>HQJ zZ;v@cE)ExMOY8^ZfbahDy?Gm*79ly(FIEEA>$Y^{Xt1hMw`45m<*IDOtp}b}(gPN; zm9AG&+%^iQlGv<%LBaLPRtdgXxh|fHZ8G@dUK~w`GQ@5nBXKjfOANQU7b{41OkzO0 zwAKFHy4BOA1#z#IEx#-3-de3o-h{R(IS2Flh zEOkFCpgWLTP+^&G3)x-r&dn{bgq`ApCWYKIg++IBg zEXMEBF4Zd4pcut&y)X#87}gXvg>DK(?G27X@>?oMzw^k;`JvlgVDpM=C1D^4cb6oM z`=JWtZm1@4y@5fQZ<2Vv%S#iemRI(BWP`2T?0+UQbb*(?VY*p*mA7W~m8ur+Sh!|# zXEZ42fGfF`u&3xW^OYro_d`5%rt_64Z6d>I&2VZn>}ZDV&9JQ*rkY`E49&^8ThoFW zbKlkqanCc587k}L+)AOzOmfH+OIxoF2eatO*ie$*`iL0i4v1aQMNrwyDi|YP24lqQ zpdwueH7!fCeBg%P7#2pp+$Att7@J^QGfXwZRzSY$!s`cLqLW$1UbTFn!^dr|4FYjaUvcxYob*WH1;?PWr6uy^Ku$}O^%f|@=#9;*I>i{bjl!u>xOEh6 z5Bo;RH{;YO+&T)khrOfZn{jFsZZ+5}&~`4*U6RxHU30x+)d~Hay2-c~StHU|v=AC~x(+H)CWaWZTn=+wt{u)} zPHANnInPb&a6ZH9}I?2x(n=P3@$v5t6z_ zNb4FwscVF!t`X9@Mo{V+A*pMGw5}19x<*LqDoAHQ7|adrdcd`fg5(M8u(D)^?!&<$ zS15um7M3Ah$Oob4=1eRZNsc8W$+2W4IhJgAIUu2897{I5agt-nhL=MV;Ej_UOGYlo zk_|6ME5I8kIhJgAkyPu-pAL_fFuU$`yRwq-eG9u#4_u+ueZFw%Miz{Xf*Jt5r5r(V z0tE8L#kbiXRLuP>>p()7mnva4aR4sP>Xr}ylDzv5+}L*TjR=F?ZXj890?SX(nh{%_ zT7v3!ClT)yW3AGJ7_$Gs5pGi`;}~%qGe+E=7*%r$__it^jtfPqnsoy!!5BkcZnLGZ zUUQ=Ic=OlodfBS4ucEgvw7q)KZ|ajuHOk;lNx-~k8H`)AN{qTJ!Rzwc6Kmo)Q33{h z$0vccPZJs3sR_uvnt;-+3C#VNfD%wiVD8FM&`oCO#}g791=n(tn0q`y)}U7+gA2$e zGgzQ0!|k>}k6&6sfxI=vxGI^oe3!j4-GT|?ofq%<_|qkIPe*sqS92xw%}?27yJfy; z#V~nn&R9-vI3bgjx8BO9bJxl%VyCwomoBc7_DCq>{apbsmwO%V}OE?Hn^QyUG$;AP-K?uhe9j4&gvsd?7<2 zkIhlA=DBPkg`3yEoMp?QYE+DV50TR4dj}*b^IJ2`9cn?g6`idLmfj1jtRi(ZgrJT_ zlx)>xbhA8Aip`Tilni8AJD4UFqRT-%~`f9EyOiZCkA~<&wWx)}wzXr-$5#s_eH+|8MNRU(O_TPET{!qFI*GH0qLT}m^UT23mHcr zi3HGKLD9h$O%wTcLzX1~tYZF^Au9}l&6~D_);0rJs{p=4WD@y^EDJ}h)i7jD!iqR` zmz$_-iUDgiiM%ARTt{hHYEW0hX+>1s5GS;@8m%Ugmjtv%X<4A4)o@x$u4Diij zcER%U3i-Rm5|F=L%s_FhB|gfRvZYMDR;1XIZ+el{S2NhW^MsC(oOCPX&m6E%U6SuJ z5y&e;0^&HqvvdL^U@Xf!VHIW{k<&a+3I>STl3fpLbn+0V3)i9n_ z@ojAfZ+`nc4v-t)f_Inoihnh6N5e~w2yGM*1v@yB;KEq%=wsETcNSo5;7SZkD6 zzN|4TbI+;rxqPvGxZjiG$!O$_B5Z(=Cldt<@fDpu6*=(e;8IbQU5Bg`N4 z&sW1rHFPXS_*}MJ=8U0S<&2?R)m-R1Ov2ty= zW}yGf+43F9ogYb#zH#`!;2T)}-%+wvF8K=Pt<+>-`Ou7TD-8b?ofV{}{TCXx&S1U? z`lD-!uZsR?23FDD_FvRu>kRzm&s!DKk&JG8gX#9!|G->8bR z>33w$)^BV6Xes?t;X1-A{HH|%kY9Jqo5&Wqa7$VRUOEWpY|M5$oh9oaFE<6)pxH6h z9faM{T=poK>d<{jd(yXWH*M8KTZlx;Bw9HU*QZ^qxh&jPDTpZY;lXyXO0`yr$CYAK z$+st4A%wUUF+?lcn_DporrNa?ZMs(3R;lC{^A*OtxzQa<8@H<59`?3tl1~(owBlr$ zTMLFbX~oGh_W~H=q!lO2+&f^1lUAJMI<&=gK$7c#B-g<(#7VA$VMs+uu7lAKC%Fzr zL!9I~7!B=VZz`?>l3WKQxekUQPI4U#Ln=yg9gK!J$#pOq;w0C>XlM_6TjM$)$#p=I z>tGn-B-g<(q@pC(!Dxt+TnD2ePI4WP%d<`f29I)0a4*UP;ND7%^0uZ?9#LeJw>6FO z7*+CZ$x+@GMTW9g-4V8U%*PO8zO8x8xA89$H2vm)tPlJf1s{?deI*r}#8jKkkJPC7 zkxI^wR6IW`PU`$n2AK)U5GQqhD1*!dWr&kHKa@dcf-=NOogc~|GeH^Rq|Ogz zkeQ$iaZ=}pGRRC&hB&G7Lm6ZyC_|jo`JoIl6Oikd!nF-1eCv|>EF3%55a3f_} zaAVB;NG0Y+s%d^i6qz5Xruh-0NVQ@T8PLiQCv`w8gA8b8h?6>?l|cryGQ>$8(8?eKS{dS`4rpbN0j&&i zQU|m$$beRcIH?0#8Du~!L!8tBtqd}tl_5^*fK~<>(8>@ebwDeF3}|JDlRBW4K?bxk z#7P~{${+(;8RDc4Xl0NAtqgHe2edNCfL4Y$sRLRWWI!uJoa6y5c|4#s!O~_xx9U~4 zD&M#d5};aXZ5qNcsSpz?`PSyqETnh<#}EU!b<~J$rAfn9{Pcf7yyP{6!7=3oqmTJ2I#D_YeMeMfj&q_!}V>ELxNl!S4cP>-pnb7Ofs! zI0*aP}E0!;k z9};RAS~+m)sr~Ym6sDnDZ(&qj?P>E%I}F$KM-`DD1Zp{AKz^8K@ru>U7d2^xu>5L| z{?1STqS3Oegv>t@G>+>03qZ?P3=J&iZWvgx{P_5HeWDh$Oj5OTju@DtKMoZAERSR@ zT(Ejoe@vWn#K5Y_<0#c;zMLbwU{yb*+R7^ytzOz+<6ksdMKekRtA;8o7WEfv%@mhr z7`cRspnug6rKWKo@sBu#i)|5ghhW^D4N#{4lbs}gIsG%EA?cYyWRbX&v2`|J_C;)k`D(ch$EiYQJh|#mWVz_Wv)J(2*!% zQU9u;m8%yH{qGi$nh}Pp77r|6&>!+ojj8g|DJhr#PmH?Oh%GtX5{$L~oB34h`oGb; zW>Brl;2`0DF*JjNMB9-5KL*cj@%(U`v*e#_&XUnKXNgz_T6zJ|?JMac^ql!mdd?iJ z=ge5oTOX;%S@lnfoK>SWagOVf)+w{wK#W-_ot~4H>>`w$3+T`0m*{-)V;L z#jW!#HGDg--fDZ78NQCK^POe*=5L*Et>L?P>wJq1-z{6`TV(h)uO|81kH*t}`|Zc+ z?KNjCKgMgCXg?Y^ZomEZ+jiWJG=|2G-8HfH=myE8%l89PCECJ_I(KN0P}|Ndk>@YTht)`C+8)}&I?!f@4+fo1YDc;UeE#VdHS(=`_m zJ$EM2x$9&kCHSX@;lia0R;_9lVE*0CBHHe(58)r=#q^)~Gat%7GYkh;3@jhwUrJm% zXsX2e2hSo}G+I9|H)aEq6hIq>Kdg+lWEm^MW&O)eX)aCMzgf$Z-?0AjULSn$!3V6B zTgY9MBcePJ6^JM$y-jrPTBQ{ev=eAlkFYbac=hr{3zqdSA6l?9S!r%%uvW`hLqwUi zM3=55s;wbf(jdBKtrm0z=XI@-yqnjOtUsLRELWL(nC>hW`XMGOI*p-*dDNIBy6tQ_dl(4XMlw$h2}^*O17RAj5eBkU5#@11hr= zGK)lJKx7(_;k?rza}Co^Q<-7Nd_iPR6PXQ=;k>1g*~IjvDzh0fkBZDvk@+KJIBywb z-edYQmD%ZB?E^ZO+p|n$CZ4N(z zGG{?%P-GT~%oUK~yne_GGreDBZh_2=BGWH2_d$m9PKC^7rk|=Z&q3xXkvUal-hd3} zIjglFb~>N?VYSfrJYV}^XU^+l4%Id3eC-F$cUGxfM&xwPlpyD*98WdTcQWKS-x*N3 zvqVnkz{QX|SLJx>h};(-$NBuX<$SffT?xBe8f|xZ<&u1E0H1;x^8_K&UWO`So0kpO%Q$*7~78 zMh(8%7it^$@5dJsP3F3g+FkzJaFN|S!)l9%yS8uN$d1Iu#W?osjHVSY7*jd_FNa2 zbJaRs3wdpWt3kJ{BjP2OmmHW|@u=Bs@sRR|W=6J%>&pB7rRz9<1`i|oF?lZM;&o>1 zrDS~JC#!|_MWtCk{?s<(H;&oqVxnV-=r|(!IL{b(r|hA&5m7rzxqTVYmJ5i!!mowY zdjD}9(Kg$u)_-OCI;G8q&JO6DN<`C$XgYMxz=(Tf84;JyeJ%R9s>`++zy6G2%@Q;!AGiaqJ6HT6f<(z9KYda60tnXne zuW7vVPHB1P9IVf=yqDsE#OowA(kJmgi-`6F{toZOn9ge|HPXN3^^u5v)vEG7^gIi> zA;`4>zX7>Rpl1m9GU&M;dX9mf??Enro*jWVL+(WA34q(7ryqK@g`P_x*8x4xKyCx% zT7f%&x5fK^UB<(G>D{L5`yYpX+aCOXM>!i%?mu`vC8B$f{|V&3jQop`zZ3GGMt%YL z?<4;Yz$c^rucH1LJg-6dUkCrK;GY5h`@y#to&(^Y3;tE$-wpih!S^Tdb>jIh`#?lA z6a0TXNZ<46;2#0s9(Ybh|5O~6+aBYqjV%xnEk}6=v-KpRb-c$XqIaS1V!WRV#U2p7 zfO%?zuL{2H!1r~~w*~zM)Z=2j$DgCUY1HQtwBvBpCx`m%hWf06o+nVwB9t?P`fNsd z?ch5cd@rKBFM$3xv13GMp+1X1KM(b3MSVVt`s|JR9EAFeL46jYoSRUNgZi9``aFp8 z4g=rYDDTH8?=sL|Kz+)fJD?wh`W%A#^q@XFp+0}d`+gmIe3WxG>T@{iGY|FoKKS+k z-+!RI8&Tfbp#L28ITZB6LBD>Aj)yyrB;qO9$G$%iy~RE|+w;?99&Y@^5~AnNzGlvx zew~-aQ`oM4t#jQ1e*V7m1gtMl9iwvlbGeNlI=iv|NsV+>Hkgg{aad1|$9gh^_2gDr z%!uaj3eVdgtcPQcP<$uv6^Lj^*DrdpTi2h@K<-*R*Wh_No&lb7@H`UFkKy?i^gWN~ z!+4J1*`dKrS}x&GqGu&Q+Zg%mVO*OhGGCpccK$30g%Vwgc7Z-Kr9dfqrx$MY2E*#>+Qz;`wDgwXRH&|d-lMCkbg^c)O5Z|VU8Z4bUnpr-~s z4;`%I^3SkmZ}Og%h>j9_v9rCS*o*o0A@G}@5qcxNAMDB79B-mVdJou>Hx4E_vb+fM zJH)eqX9~~#@!S^AS25q8#Pc}Vq2ItRAJ1Mt5skpUoqLqxm-G;Y&gA$B+e^qj2DyD9 zcN^rELheb(ErHx_klSe10p4j4(e;p<54i^+*9W;Vkh>Lfn;~~43y}L4$Xx}w6_A?(xz9mv3gk9J?mWmXhg=A`iIDpw%fqo9?FQGo)(R~s9Y&y}ozZyeN?LsuZn`mi9-}jd@L{DwE zE!_|Qz{WcGPEG6oN)HiFp@(Fi5uM4gBO>}283&E@F}x$D#>kJbZ#g%ka_^kT`?B`* zx1_%soqu(713Q0`uA`?y&vo!8t!|Y&75mZqj!^u%*!z34z3QiCJ~3VMcQ}O0ZLz*A z`$(ePM6KuaiJU*2@u4@nME%)4`t^D2Df&Ehfj-CMdE3c~-xT{sbP4>D!}ikrKgj-! zD43`riaVtoqVG)8`fQoRpJomtJJ3QaaD*g9( z{u0kkc>W9C+v`)c+y>e^2>pu$H`22>j!Q%}(L0>k;c&H68NrQ_Cl6Nno8Wg{0Qs}z zX!PFft?1YFzRIoC_NGq>RPGM3pIfYZWc)YMCqw>D?6W_{@lYDhydi#CBfU`0R2w5N zqJJ-y_uLqH?qlrFJlc85fz00+S%Go9tN4#wtVa(~|F451AhgLkT%MWC0S-HR|yr#HSn?HpbW^8}Yf>dNm>4Xj8pkK|M}IyMBsxZRybVPsDpJ!fxJ<{naes&jMTU zgC-n7wA)ccq1b^;=4P44!Op+KwRFfrvuc*R^E6#Ag~r=}UxO z>bzSnR19Y>k=qiDbQjvE7deJAm&v-4$@mx#wmci@>oAVD#k%vaXlF0l`2gCv5A4~? zp1hwqcl7Cd8YlH=q<<>%gVxPrf1b-s<|rspW=FL59gMrTWM9|lJYMLH&hLtSqI5~# z&v51v@tZbf-<9}bY0h%&16N>Oo50apBHAe9w#8b9=krqT&e>LtzjeMpk?4=x618I< z9|5@|`MTAPMDHG>>)=C{j^itiQv3tpizgGY>Ae*5f1}t%vhI?3+F`#h>mFJANjru! z-#9|w(+|Y1Y{)(c`@0OdD$kB=QN~vzJstM#FpgqVi*=ItInQMd5kF_p`VH#60rA%B zj?{7S2fUv#*k8AcKip!?ly$PjdcUIMaUrMBTtI1Gj3tGu?vu z_ZsT)8JP#ycJ3*B!}TwHu!Hlt9?voEq%XV*+-t8`D575+%V_6 zN~hCN-mT(?ZMpwnrCo#BKgswV%>HGb%KZ%SnxmnATj)O?`qzv8QfK-Y?a%XMJ`}R2 zO21r@{T1~5S;k9a*NA`B7-`GvytxJIRpmJCpBrWU9<*MNb~e)YOTP?f9@26% z@2MTk>@DkBBYm6B^UlZcysxft^ykse$54+O9PN*FuJrqCU*$&*5c~67W;y)Unesk~ z+Ock0(l43JJ2{c>Y(qa^j`uiS_Y>)_V7{It{k+9G6z}J+Ic?|BkZa)md>rq`7yd%_ zzLbue#cC&L4W7S(pLG$=CoY9O`yA}^dBB$dUxIziwtNyrM2BD=weWuU;%(__jGyJ$ z|GnO+{=hE})p0*g{9K|hV*T3z{=r=Mt9AIJU(^1fPh;JC2Jdk~ndqHApFZnGwey|h z<$bnTa=uHHDayIU7Hft)hpiCyVUpmM>?5+T9<(lp{rS;}I`6lY@wmy_2KgWGa~q

iVplDwW2q<=N0H%`al z`?5Y}GT%hIel2pD%n3I+A zAD#1C^%v3)&)0c#lI-J$GxxzyxK`$8i}mRfrT=Cfhw=HBl$LjotZ$9i93!~e|8Gy<%6@7??+vF zp6VY&^otophaE)p%nYJmVLrbEJx9RqejR!a2~__b&~qo|Sr+@Zz3}{Z=y?))_JN*j zp=WQ@=O*a66?#&T-x1H-d$hijkJaZ2%)@VBKe}a! zu>U%!=c69DV}whe3W7&q^v&)>w36zu#InRlJL9wYsf*+fpUm)o70nA_(N_0K-1`z^Xa<20E|VLvYwdy}yyOFXtQ@|Nx=XjdtB zLw2Ru;|&jNK)Y_ozIF%1YtQ9#a6V`3)AxG0@O5Orrq2gnzX?-&fsJ+fil>A0!rmy4tD7Am-6UWN?Pk%|{ zVwnxXN7nmtpQ^?Bjl_+IGylN(Qy}}?Yda5>ao-rZ5^=}Qc{(l^wyB>tOUm6jdzp;u zz3s;i(EO#o-hVh2^YmqnU!;E{{Ec)^o7mksr#afL=cFAS+1F%TXRIrwe=?a?@pJA= z7rV3{*1>KrM}5u~f4s%oPUAQubJY%yY}9ozGY#)`Gxm4ilkzF^($Ub`D+qwn)c*#BFk|68mZ#hve|3|# zqw^$3^{mu+X-yQq7VAQ>w~h3m*s~VP62GaDULpHDqE^}W5uFcwnVgdl4d9&Q2HZV7 z3eQLQULs$81m8UHT?6{Qc-{lPYw-Leo@?;@JLdgoQNOFCevOgeA#U)N>{A*eXQAC? z*;l^fJSX)(+qqiodLvzAzQzw72lQWp{%O!#L2n2BA<)-?zANa5f_?|+OF(~>_s@+V zI=h2@Bj`P#KMXp5n1tvZ=W5V%px+GoU!;BSI2VCF74%C$e-`vJKtCMxMW8U&@Tf0D75bw(C-EP4A8d+eSgqz1^r~uUx0r7)XY217eTLren04Mp?;Tx z-U<5kp#K5%vq3)=^z%Uf1?U5yPXzr$&>sZ77xeL<&jfuV=rz!{1-%t?U*hbU^no}p z+!pvmwXbwE@Iu3f=S-aA{T26Te=7E#=oO6f6Y=~2|& zoj;Igqw`AOsdz3!9N@$~iJsVz=u2%H2iqO=GgCxAxwEbF^ZWDjyK~;ezVHmp>ui?j zoIQ{0{5|p)ApZd#cYMzd&u8#FSnVcVg?-Xa;%_uY&d~LS9+LB)#>l#?`sLq&+|_vg z41VMGIM+K<>~|yG3w?hSKBAe>H>B;z%o?xyUV;4Wcu!+oy@+|G*wro8RO}zl#yavD z*x9x4hwH*On7u*b&R3*&o~l=}AA%j*N5)$t{asJjr)juX^BDG*HCaa*Bg2SK%~Su3 zPUunl{xhs^C+T`jPnx(G*3dpQXU_*^PDrpuNbyoNo)DPg8#n~e&Yf> zYj~c9_{R;v&%$m$ig?01cs`BiMm%4^^Wn6fv;AVembXaiwJG~U^=GZshpOLmiqz|h z>^-Q@4!BojXEYvh0>ysu5!SsJ&Z z_oe-fk>Bnn<8JmDvOgtSh5hlty8oShI`Bg5!@m!^cGG?;_ovf{+Q0XP{lICuKY#o* z-H-pnW_qdfwb}X{R(~}8vfP_}bk2Vwp78VmLZ9<0#^?LuhY^j#zT;^0!%yIMPm%dM zn7tk2>@JB%6|y(?={c=~`SCXT>on}IbBN1ch4*`h_?1Kx5Ep(B^X^-CzSK#?rfdD) zs&~H*-FMEyJi7zq{W|RP?)kfql#)lU42vsaGR? z0me`ISn1z;Pr!L|LG0$H>?4SK?<3=AlXW%jnLL2?;j6IEA47g8@()7($e)J%y^;S0?)gnb`PZZTSHv!CvR0y;ub`X@QO;}7cOdfLhrZL0e=W*c zi~QeXec227Z(@D%b2Ff`Z;He(;N9-B~)-@!ld@ccXcgICb5-J$Oq=zC7u)snp( z`hE+2BhdFN=qcj)XXyJJ^t~kgv_888`Zhq{*P-th(D!}ldjfhgc)kdIY3REP`esAl zrO@|f=z9$MZiT*|K+kkMpN78Qp&wh&k8K#wcZgo1F_=%6Lhlct_w&%Z9rD|ezX$Rg zc%Qf7eO`(8`5xZqF~}c}{D;x59Z>#dDE~=}r&CeRdX%#U<-CA$CLsTH=nIkm8I-de z`A?(#amfD@#?uhW|24+*NhtptC_jhtSEHOd%6|am{1y6sigG%UzYO_hY;i^Lv!@5Xxys{wc`MBL6m&|18SC7v=AT@^3)-N22_dD1U#HUqtznQT}?A z^B~H(3FS;czJ>flkpCH!zY*ns3FVJq99-M4{?gi0H1731u^Ypg1M2J-9ya?{@pmY* zR^nDI*6ny6hWO^=8n;U?M*iN2lbtX7mPUGa@wXZy`{?;v=OITDRTkVso8_x0h#uaJ zXea)@4BjUarN4#v)3?R{Zpl6-{@*6+=|JnZRO4pZs+`+5($B#U8HWFMS(@mX?TM~E zSnmZqfPL9U?8hd+f8Gw~ldmEE^^ZXPw5Ndo1pFi5m(`z}^St_VbIzY7{>hwnIaevo z$*aGXb~O&1*+cxcMka*c`v;B7&3Rhtvnjh->a!_3D1K0jb(GX=Q}%d~zc2lJ#H%0E z`lo-Q^-rIIau3jUq#stlIkOY)k3EF``1IjgziSWIIOXoB*Sp%D%UoXC9>el73h8HqzsE)^;wEa*1vc zdq#9F{N`cA?GKc4hBGDX|2Am+GV?n21Do;u%DzNDdh_Pa5b=VFJcq4|(NF7TKi^2- ziS}==pJ(g5QTOSYSyB$A>*DVYTGzv`UncM*VQ-13M@hHzNJ+ z3ZmPQ{@eRI?`<>wP;L-s@JC*`5&WEVFVPlOpxA1>zs-1ydkGoB zxOPXPZ*EWY-u6U)+@5IBPDHovNOb8eqMLUl8s3rU`R$2b;0s;yJwVo@?{71HOopr% z-`{5Zt{nQ{Fvp|^_%q~Wy~o5cWL@!}+l=3yKeRZGtSA0+oAF~?HjN>UzuNx~Kw~H_ literal 94322 zcmd444V+xXbthU?_ulT?bGtQHc#sB-Y^pC~7#xieAVyf=c#fnQY0#%70TSz%rX>xa zo40J7g_8;NXBA*}-p#7srZG zux!|9fB$pp-o8DO&?MRSdka5JSJkcWI(6#Q`6^YPxKk^o^q=Ylx9TZ9b*r9Iw|Y}k z2r3DwTg}vzy49bW!cPG|2pGwur)~{g3g^&Mx3)vqDJ!6-%-tQjuIs9->w3HLbzSdJ zb9G(sRBgJhhdKQ=PQRW1-l2-Ru6LzuN z$qPbXRg5v7_Crr&5frb4QYr`w#tSYC{V-6aQYrA}DPvS*j2~)M@cp2q)%>v2SK&n^ z9V)F=q*YNzrVx}$aeGiK7Tem|j42f66pYbImr7nqDdl;g_WYvWtEcs}4hmX7U>-1q z3%n^!#~vz1Q<{|gDL(9v>U~D({pz>1zDs>V>jP?mzFS?We_Aclq?KN-F3~I0`}9h6 zr5;dSdQffFtJM4SYIT(!QoHpHs!Oj?cj~ojSg%vJ>Gf)!-k^5rjp`2lQFXiCq&~0p zX0=mqQShyMfw(1*EO|BcdNRo*VPeiw%66KYqO)SeodR5 zb@i*-4A<3D+T2!G|52OU>*~Yij=H+u?5eB(piKk85&RjgtIuh3XI=f@+U%~YtIVFd zdav1AS6ybTuI8I@geK~0tC>V}AENu~>Sl9SUEO33Ank6X{d8SzF;rKZ&2przsH;t8 zB|Z!w-ylM(@Mm>hz0VBQl{GgYw5G1EFl+1TVzaKUy3KloHXv;yvV0U-HX*bbp)CmA zh(9+W^UcV-6`^ei-GWdJp>AZZZ&&X#+wo@y{_NbYE;hsXa~uBLzFo~XcWhT(X4iJL z(KHYmLE0!ncWzf3%1e9!A^mav!Gn5e z_0Z}E_5ZFP(4W@#>&a>Tn4bE#`o1Uiz5iZ+@KOE2U)1;f>kt0)-3RX4zi(oEZ10}; zJ*{u}8NK%B^dtJJf1`g^ulc0@1^x5-kp7f@Sl`&U=ElL1(Z+A+tGd?q_09j-{DJuc z^FKEK|I(k)kLxG&{9n@lr~a&-|9|Lzr+-DyUpD`+p8v~w{+9Wh=5L*Uv%TWt?klXd zw!6E#YyO6=`Rlsom-U5hZ-3W(R)522f9euN@kru#E9+a`XUdl-I;KYw)2*yQ!VB6O zI;Nea(_zjs;B$zMsXn9Vk$*76f$4uR%hgg((c_$}>LFlFpHXEU;cJgk z6&=wO>W;6e=mil%GrGflkC#VPWj&v>k|ITqa`CxFEkGxvK~(Rxbm1W9TF~r@3apA2 zGZ*_c0qAH4Bc*w(in1PD2 zX0C@ZMHW*LCy`are~)xHW%{kccSYey;#o!h2$!J)V~J{11JiE}=`qwmW^ACMt!KGb zeGwmVM6Ckr;o^e-l~d6uRZ8lz=;j4q5H=AjBhbT zdK{sEKea~!!dcHuM5?MITO6n;!^2;g_+%#OkxzJy1OR2dLBC&0DXS}*jz8$(pPL7n z1QVgKE%ulgxr^8)aT)a@)Dc-dP|=aqw%BJn-Qan8O`nOS^3HUQu)aKR9nB9m*icb2 zUZ3)kt`9np5Jrm0wjUVD1FuPq;vPowAu_UXWwRgEflJP%a?!<5zN>barn3=j$cW}($K0GOqf^feb# zKtjMQU@!|Dm>C=VGr`P6Hn9E~;FOKC>^TSu1%iT}Ga(3TGAjrQZ0H~;%pizEIS2{? zK{Bp0At>Nob5;mSH$v8P!0W1t%C=2=WR=_YiVlp?!Gm6-YRr_|^Z-1o$lE`eCRA&uf-Sn6cSe0>Rh=#B>9$*|ls?UV&5nWtGHK$LXE&{ezJj0>0uHUT5q{pYGSL?ZCUmCu$XeYFe#9>dNPr1aQs2f8e8CA`LYQ*tC~V| zP|-zJlioiY4oH2u54O9&>|n)MP4C?gJVY9~jP=PMYa|5#l+S1gmB*;u znyODcaxcjyBH_l%ZZfE|swk|2R;(6)C>z$tyt&EYH7VerdFMe7|A1WdNTO)Us;)kx zqNt#(iswa>T2EOsfSKztj3xa+ESzj6-5vpP`ibdPs;Y5XAm;TdmB_ha^{R^U`mO0z zx~i?$t2DmgMAwa~u^xV~u6nSdaQ;|582w5`d!Pyqdm~BE?T!spj&-n}bY@{vq^Uu_ zA1HN-2U%QI(WJ10%s?d&bcOQ{omx2Pa}B*}E(Q}|rKdgmwXbO#(6rZxJFKFqKC_V5 ztyf({z!sA4kVoICiy~CJ2;(!7?S!GX{u0%lFpao_>q#@9%p#mBs#jJ0 ze$rKg;N@u}fQdeH+_-j*qXO5?<&0%qj$_94_!x3nA3atPssllys(dV{9&moCDmir&S?Hn z+Weucd1^L4lxu!%pP5dZpUyQulr_J$&z#V17Eb7F-PY!s|JaP?k88Iu$B{q6%zw1m z{I*>4AL}#6v|EH@E;AN;Th{!?`pnU^`J>I|KbC8LbVl<>(&mq3&DWdF@5(hl+Gh@@ z%^%J+zbk8gw9gz$n?KZSel*woJu{l0PMe?3njdR6e|N6=d-}{?H~15(34wQKt>4pU zZgo?C92sQg@8QO=?vH4+9W>!?qnr3+uDV`zzsBzERiD(kh9A*=rr)*PKazp|Cv~~t zfDSnpyQUXsEkB~mfdjck4jYiJ7SLZUXN@jvm*M&}gK5ctjpKke&EU0U@UjdaOEdT_ z8T>56Xqq8t$q-~2?nyHgS~75ldHT}t#cBaGEDyp^F(QAmkraB>0s=b4{5=IymG`!# z=Nao*nHIfFJ!K+Wp!>~r>LOdPey>u?RBTO(r($~UWuU1TSc#`iMYg}M)8t6|08`Hq8X<%;}nAU5$k^)T)f-qIKAY-!rU~4WGLOIfc^^_&6jDNH<+ISgH@0XU&Q~f8m7>|I|Q50qJoc2?vN(mwSiJa@Csy~7wIh=PvDjRv4M1p;N6dO%7C)e&g!-p}d*5o(% zSeQ{ET1-q;N7NZ#m@pCE0b=Po9Si*v3jO2ADrLQ@qQg8w?lx}9Z!xK?K!B;LLJMvR ze5(c%y-byH?DDy?x86Y1HaLK5w!WpcqxSC=z zk&%1hBokF4jV&%RrAxtnYD#(I9P>nrCiUJzS)?n#DMe&kK ziy)j7FA^@7=m{uK+-}emI%EN#u443+o8S#>&{Li+zLf?beR!A{k!upf-XK~HTtcF( zzpA3kCSu$qYpwt%*<3K4#U$OoXd3)kOoNYUP#CWNFPR3%%n2iU@-2gZOmj9sz*rB& zXh#(J%Btvb(4rPpFhh*$Rs9a_^`TXtFDtVzoin}+W?vT0 z__8YdVrP6=o_&dDd|91+>7MarDErbgj8A5_BuT)&F`M zEWdwR{?kj%5{o;t->?N+AWec?dQ8XMBF+lF(k~>94gd}Jk8}eFq_aM*23pkuyt%x~?OZ%ddzT+4I)3wli2zY@@Tk6GAN z4I}Gw=WK{uTh_m3bId>R1@~~{KB+1gb{!2;bQ!ptX)k~cuFIO`Ns&f7=eD^^5t{9p zW0W=#f}PTlZcLN}Z8Nxtr;qUyI!hV|#qTkTDtsxm06h+MbBHVK0D5;LQkeQ8GZw8M zb$}`O!rM3>!4_=9AGJynkIzVqaFcxB0=`a$ik_>)t5j4_@o#Dsz0#v22hDBGi(Yzl zll@O8!5VCG1!AixYS1Zf41pmK72f_t?N2m$V|>fgG&O;{y=s74H<@VWEhM;vKXTBM z4mA-3?(Y*AFVb!>PVP8mJlr1!pqUBn( zEsP|AV?rvc8_2C}==a+&R)k+M~okZ~N4!bnOs$QSzB)?(V(jMTIk|Vq<$0ncGeBfhQHCV)LoUtR({**P$yE9<5 zXt0P4^X>w#-v(eaCkiZLzWjE8ZnFw3Vvff`#}$P|ToO)%qAyIX;cO9P76-(wQ z_N9w~X=TWYPCCX^fi4B4?Y})y!kAJiV=9bfKiDuoa~eEY#oL(?NP#Z0q2o1$!fP_Z z?$4$eEF!RVbv3Yl;xX~;F-gI6Bu};vlFAx-?|!hKct!@hz;^2bqYb<%1Ims$HNm*_ zAs}Nzz_YSyWZV|VuwjydDbmvfIvF8{*=`+?-4{6 zQ3L`?*^D1t7;$WB@M!~JN4Mb2tZiNJkootr;5lY3FSsyk4Tx>9;AFuKj@I0QbKEUB zqi9tw=C*tQBqgE^NIGo5ph_`cD6m1n;uF~bj%Oi4vptM`22oDBp@UZBf@=;74tQVj zr3CzOh@#xiE0@q0;k_qj$nQrOoXL@dv!8s>b1eHrdV`|*E@jAsH!@%u=Td>LXe6GQ zqNiC}xl1y?k% zW(>&4nh_x12E+MS1IM9{9(!qzF+Hxwf%SosgLM_(Dq9@F&CZW6OO!RB>;n`vBiJiQ zWzbU6u|Y6Lfm5q0 zCgM4NjE6+bK##1BF9S%$m+`)y8mt81=J1a->kzXB7^6TvjdhhE!ob|%Ff?3>=n&Uv z6`<|VLm~{r!iZ=n@p5Y*BgB^E+g<}4?`-xlDv=cm60v4o7f{O^4#XK0>F`4yGqJI* z4EfBw1_zX;4|)zj5qr`B7?xg+f1LW(Q2~4$YC41@4lB})M3G%pQ4wz%pL)OwKVZ!W z0V+qh3`PYQXz+f5R4Cicra?V@#-~#cdh{I62@XCVS59voSo_vnBjYVoIED}iPEhDv zsYeH_$4x1z9KCQ`8FOu{8WC9E#!$q%u=x)Zat3ZO9j3f7Y^fk&m@vEASpzk4N193wp3HHrHP5j{izHIk}Yiw z%aEAT!xTo4Tj3G~2_z(2RIVD9E78TgXH$`up-ZhfE9Jm9Yn2mesg#0{yLC#H1dy~% zCX7f~pyk_uJHrigj|^P|*ke(a67oX$5<(_1rvzuZ;f)PZ7VwFlWWqUMQI-#CBEUql zs48~ywoVEm2TF8RQ8^_y6DQ2$4uIsu4HgFybyf|PBM7wk>VbWLkFs?cWdkMi7Q*TJ z&piG7h+clsqs4$35Lv=#$}?|md;&Mux7%k@tKbIao2z{215c%0imZ7F}D;% zsY*bJ1MWFLYn8-^GilBWF3dV$>I2d)TM!{Q?z2e-+{~}y8FTy5nwe@8DjgH}9~MGZ zFz}d5%xV-Vzu2%Eg#ml2({-Cg>k4WVJkU62i(zMG{RA zGkl?aHxR?Eq6NeZ_-4F48H{-78HgF=4RRnBI1p=PH!)j?H#@5%3bUzbh28)b^WBm% zt`On}=NJ%{(+QQ$fFCRXAB#-A^L-dljk^veIH98GG;Kzb z0&|Rw_11z*Ow&jGF;>SjpyfQ8hF;3Ff!HnqUVun)nZi#9j-nosXh_~r`q4-prt92i zLng~u%rb(zixCcy*X#?HXd$q>`SgV-vi)GTiidA`4JJ?Jb_d4)|!FI%_ii*n2fYO-7Mpe`F z0|!HF3YB;x)*Gkk`yV)XU`&3Xk0jDp(NuCZfC^G0(I$ZMvTIKB6d|1V32CF|>sBTGd4cIS zQ&z>7g7s|DR8p&Dud^QV66{gTGL({+M2Q-#s09{R{#5{SI?5`=)HYaAPQ5r$PMO&y z@s*fQJ8D~|uqj1FTXlom)V55ugWclFFb7o!+}br2<5HuvYKY}$HpxrFgHG#5X{)Hc zLAt3J?POuSs(k_Y%dF8Hy;p&+j`8&v6@Neie*6Ke<9Si^TUwi@J~_(|3`IjIkYMMX zR%6Q;3ap_Yf&y9tkq2&ihN2D33J!TCp(m`N^6XJG*cDJ)M7k0G6llQm0^Hw0WAJIp z;WB~ybzmGjk;y_I$2N4_5;eeT#n9K_oANttie)MoPJ0w5kcFhOktf<98!0NQ=9c8Q z$N15Z#+ozVgu;E*0uxS}iFDQDeeX4J4;=wVuMKwznSaNHKs_Exq8<=6L&8=W zk;_4ch$U4uAXW8nS_f9gD;9_lpu5G?zW5fj zC0T2p{*c2~L92&(2Ycz!mo@e-G^S8cRQyaoz1mXA*K?J8Wo9L}x=L6{3k9=E-e{@h zZ*!G=Yi1=IT_vo$g@Rcn@3d6%qg*9_KeLj4R|&MbP%f+EksmVJbyM=mA2z4teh%lR zWU;FQdS57))$w>s9iPe7@$)n5u&xd$NugX;$5SnJ{D)i}zcRCq*wq2ODU{3Vc($dE z-^%Y|5P);ieWqLPNu2`JG4>wRT2+r(481CF0s)?^ z=e z7p$hEuWLH|x0+P^Uf~qDjHFgYaVHuy(SF{=J*GSHcqF*1W<$uvrFzV@eWt@9A50J@ z@pSZnHg=&-0%zXc-B~vs-Nki8YK5jU#u537RMf8MAa8@Y9wX5wBV7ba(QFhWGYngi z7TXwRu^QxI)fVIelRYJmf%OzPGkj99J&cEhF!9f@hcS737_1471+jR zVU~)|YHwh{VCad@VmfBQi0rEfxgc0D27uN96$WOqO57=;J7MS9?P2)*XxhU7i^}zr zbrqrW@ATA}mmi8fjF&NTps5Y$a`rILixwp?QLVS$Oh%5A+Kc9Kj*$ahdC)k+ezXHqBXD2=T`URBff0*CeYPxWW$(3sQR~V;&qmm@UX;1~4-~ zrfC4v3NmNwIT%2x0gPKQ?N~9;5;(&E#)BFhvto3nn4v8s#4QFed{YosjMH0T{;OP{ z*#HLekCfe~Gd+Wu1~AOy_L#I00~jyehhP<(jNJ!)5pOanX6(N7_U>*nf`_sBG+hL= z$y`5AxPDB;DFF-Si89E7A>)DT#|9yjRd57MlOe+jtwoFuOjlp_YC2d99cV?EevS*p z^P!-Xfdhd#R5Bk?^ckQOR$OS0*q#J@X-%iqI;g19Q*VPX=`o^zLeo=YH2no{umU}B zWMf7g!15zwG_A*%DI6J^3j66OVu~Q6#hKneM$<>VRR|vOHt?M;UyLbZD(|P`Tr905 ztCd8bm!_xv5juVPBP;;UHOn?LbisZ)an|x#_00e8*y@HbeY{0V zTfb^-Q1ztFHWosf=+K4cf+-KIto{Z#S)wq1y)DpXjp~Igu&>Td*Uy8J5Hy)|6};iH zYwrd&1}HbGEn zK1qOdV@m`%d9_6E7qhOwM$n^3n@{H5P$@ZO;>ZSI>jafzIuK^K1T(D4azr*FcdJDG+hj}`Jl>N+n^eX@t&qn ze#HmV$b;AiT~9*jq-xtXUTs5potC#7D%yr<3RZto5G*U6q7T5X3|48O>nGN}qHLJ< z6IXXor;tyZ$p*EtND=!ESlOGztv#x?gP9196f4|aP$@u{izQ(w%N7wB+6APl?X1@! z+Xo7>fOBw=tL-rMyC9v!c2etM4rkj(s_nLorjM%eY8%=u(DjX&l6Ks|+i?C}4{HG2 zou{fr1Dg-9y6A(ez&6rYFP4PfG?8MN;dz?~Zi@XvZj!g9ku5s=kL6_A0axM!U%zfIvWRs}UL;ssMO}GO`s~ zHrk+HeoZ$3@8CHw!!_jXB~uLuqAtL8Fis0q^H|GeCNOP`u`xDS4Dv+{ zR3Hsr+yEgQ_oLsap~92QUs#?L{+hmo-x~grYsxkd`SnaTLt0C`D zXKUhiYiq3E&f$?9P3F+%F+0Zw)ILVuV3(a^D_u!IFRPI`RezrQFP>K_#Bn^YfVc^~ zdGp%l>3Q>fsP5Q+{!op~DaP}nd2t*oh%f#^4OXJ^g^?{>?k%o%(r<_5fQOQz4*9i} zIibSYurMerjIb<=Z5g7Au6$%c8hL7|r^*+lvFo%dccu}r9OtJI)G#lNaG?t$0=v6N z;kvGB(Y8@IUTvdOsv1OgZdG$Plg?!RaJzpltxe zpv$f79P)>7REWT!!kSWG8ny@w!275G4_1&LwRMBAuQ4H@h4`Pyc6wFqoek|2&3RcU9HbAStA9mu{KKn=7A$mub_MM$!WERF-) z7QdeX3}kWH7VP|=G$ET?giLcR2L87}R4oa~fb$I_jaUK((}yVjND|@LXt!9eU<4;! z2}6cjW&}}S5h`F2eHi+<$XS-wZGhHo;1q_%S~=ui3Nhgtg1RFsPI6Naw}mzUj~?Qy zDDG*t7CNyI#)jH)z)i&O=SX1NS9etdsQji-SmG`fe!^P}oCag`k|S8kDuM}HrDQJ{ zsCc9q&|#xu_-uw!Co7+MlMP&LV%Qed2K7T9K3Kre z^MHALR>@80b>>|1tZH0bIb@b8SRm?NzM}(_AomR0&PyC&xNAd|L zzNhJDkO1wt*rS*KPSZ0bGBiDXAD!l;N4~G=*O3IzB3|s#(eG>e&n5Cj4k-II_UPpI zHT?mS6-~t+J$XXY&sWaK_38;t4KPsMHY+}~^Z2V_vo zr{Xqx>`hHSDv=+T=!G{meXpIuxI~Y;)x=MQwO=^YNg&EY4$rAgC^9DdsdOC*0{m2gtJ@W%Y&;J06{|B#NLjLd-Or8AwjXCtk zuW0h(h_h;X`3Hux`4q%O^5Y8=MMs&hi?DWKRQt0rL+YQtqN!jNhrjfSrlQrcas~e| zS5U$zI6e2g1^*~lP{Jtq^XD)4$GL(MM#0}de^;N&6_hXve);?@{zdePe#PX35QuzFGmw{ZK>lBH1tpAv zUu{2cSHGMqC}9+wK7Uum@1N{P38Ua&UvS* z&J~m}3jXf-3w}LUP{Jtqa&+EV{i|F-38Uaw-ffJ3IEPAf9JufmO>Gpx8)R(gGi_w( z;G2d%^QxvYRb2Av5>%qzlrv-wwY%iEzlhWK@SBErPfT-N`d^gDqo>|9^yaIYE}-|g z*xtD5G~e3$(A9Mbga4-CEYs-{l5$R+;*XsGAk zl;j1}<&qzJ)6ffV8hZ83^hjLTawLA|3!2Zw_r?+D)%1oN&->`&xJV(NiQ->^Ecm0S z@oQ!B=){|be(jr@su1RIbAD^~B+dSdb3j&|H1u2F)O5+YvUjK1|Lq(ybm*j^-}|N} zT#M4$<$%64&G%)@=VK=g9s8!H%g)Hxlji#~5P3&V8hYuQnl5kVi*9DFD7|<;tVcvI zpe$P6;tIw2H~~M`sTPaUAuBDixS3U9oYxUtULw{O^OTALMNiI+=0VjX)7(08TBsU) z{FTy-kB_GxFLSCBipp$C)nh_t?XVcpsS`qLv599`Vf!Wp_@$aVNV(Gpi@2<3LL z!lu$7)QD;*7A@rDRk&rz6-c_r_aS;rG^G?*kdB+@gVp)O^7PPK z2LG}-X^-OnO+}luhFC#VF>v(PT&gJQ?rf{NNi(y8Lks0zKqFuoEVAwZ8G`R|S%e>SDZI{{HTz7VF@ zkeEXO58EjEB~J%X^Ry#yf+CunFcPMziH0>BAdxhaAaGBiUssGZ5voLU0_Lm-C*0#r zPHz-$L0EhZ?dxI>7zzuy0UO3Yg@hOuIX$Lhfen~55)33Egh&jK1sgCY1rj5Fq*}la zL=%`~mXw#^p|al=nuQ=gFStTl)G15xJm$lQSQL%5sI0QF2&3R4JRr3*%f=RaRr@jp z8CH=ktnyRJrT|EZ7T6-$Oq=xqP7Ld9)Ta&@C_DRdTg9v#>yKNTq^eOAqrq6 zTVQ^2mI;?_c8ie9q-`PoNg!UvkHYB#Y#e}d0C;Iw$L3K`Fw3_Uz|aZo^UOU9)P-8y zvp}OH{z>su5=E?2xIpZ)%Hok(M^#Kg2t=y7;0`vFy{?MI*AIN&Q=N2jz7 zn`-9}lSb?tTR=*@r@3QGyqYNI01y}i{#n5*PgEBKmvFNhSk(nzfUCe9Kga0>U%D_T z@-Yfql+&xnbd?aF0;jpc;9(G0u)imrQ=m0623P?p*0oE61vv)WkPYO^# zDhS+(?PFi?9l5kB@>T>41q-?2cBnhE$q*(e6a^1JcAS90sM_4Ei7cWeXTyOnE zgPT8+6w`hcT)zrgzXq6o2;i}S_td+pnu`Zy)^J+L+UXutqj1oYXszSi0+9sCI&4oz zz$XWmj@~1VVe>5ds5{d=R`I0}hrvlayr=WY8?V5;MPJY@&idKfI-pZfU||k45JZ7_ zzX6OXAbTy2Cq)=eTnHCeVsv`CIFcC*Vpqa?iHQtILfYBK7A)>rUz5GPKr6;?xI>VA zr{IL*?mLfMa{-i#6f_#drB!(Wj~Pc^2CP*Teb2C*f~N_qHrjCRfv{gS(~%q&nHt2A93|b9ZJuvBY#|cOVJ|0i2F_v^_YD-nN#OQ>HIgpPQ|1cd|jyHBW zhyxc77|4OkNR`@9$p}snn7zfdl={f}fI||9!|QUr!I|0B(j|0}1uvlRS!g;2&x=rr z;q_uQvOWX)K@Wf+wfG16p|yAHLOS0&NY6$X=R$scMjs>6(Fe44NRf9ptZZ0UvB#*n zzT%z7+qGLozX;M)4rb&9#leV>5u_fW@}2C#f_0~`Z1NFwKh9LOItjYirYpWAVW(;W z;_R;tRiK|;)(NCU^BDYb9Q2KN4h~ln@u@{G{Fo^uV3BSWUBd(@W{P#W_pwF}7N4O{ zbn>}=r<1Ruxk^P}_OsJ~!9vI#R;q+Gh&vA06Xz#e`JmY!U)BDE76pzz8a!yrcN?kXv4?D{rUt%;nLB3Col;;2$o1 z5bA-HEVOtL1FeVasq4{-w{qq&9T1b+jwFfkj2-Q4AOqa1m%Y?H2FBvviA%p2YG=Ix~4Ezy>09 z_(6k6G$k#4DmTQRD4S<94h>=91yNXew1F`Pz-2-|;{skbQQWJd_-YuPW@rZ!w19C! zJP(__0H8^)jts}St78G5Lrz|0b+y2#UptuKh+H(QD71ne-JaSU5b9l;vd zZ&+vM22WRltqUxb^&3`W@6QHX{}sr5*?UYGsH7lJ!=`0GSRe)put!vb!XRs0DY9smxOlAV>k`xMhM?$7~FBS)GBoSV?m!fO#lj4h;@?jDRi#fVL>&R3JN$iA=um38C3P zS9ugXoC1}1CxJXo!Y8k8kT=GfWYGRR%SmPxZd{DVp}5f|U{|2-A(7RddG=+eAbYsr zlM(Lp9xuP`f;uZy5~fLjHqROZF|i+34FzpZSV11+Y;|?53V=BF%tFzPR4j%l-uNZ{|f7e9)_ z8<^b#WE+^(rr%`)7vyljcnWgh^WngU9ujf&#^idkfw5U(Yv0_!ta+c?z`onSZe#1Y zfr4_fBep<3FW@!6NaffRr1cG>3vT-|#T5=QYXgV2th%wc{MquJ4frB!4&UiC79|#^;&6n>4UYrEsjg=nivO%{07_T??Um*Lhz}Fwq zS84Xv%X;gfZ)tBilJ>TxYnas@hDrDr%^(r(nn4Bm=>ddR`6|sXnB-0)21h8<7^Y)$ z00|~Acw)SHX3UPi_EsT~(M zoY1I-OOtd!K2+W+6ZRPjzRC$4J4)Tr*M#tj|cn$6N<8*A8gmyiQJaKI@HDbK7T!6#kd%_bidw zlSUZMv3r(IKujy%f$R)46#q4#qgg5t;K!HKDu4q&517iG^?XV}`-9mjOoaEDkVzB> zGXy_ss~mn5n%p67p|Kg&06%J+;_yIG#_<~9n8D7#iN^O+=r#fwh~*WWe8J9?wUx_o zx(k)w?C8=d7Qo$}5jy8bom?3_N{VfjP`e)TIF`8I&Q$UKGbV~De1)0D#PFsBqXf6M zLRZ4Rqb~u4hq>TZ#LYZ|7Fc10u9TW|k|}AM4;|#L4a&$C z7oGt8NASw##!y;4u5iJ-5LooM5;Teua8}KZV;mU}J=ol7@H0M@d+!0he4lvBu>S&F z#vo(DV-Eq`5*vQ(A&|!&*no{6dtk8@KlT7cMSkwCqYspWP@gPKKK-(A+on?P1#s+< zADHM%BES)0qP2>Sb0CV@WczHwMLuQy49BNg`27jx%(deNpsWK< zHvZ?!FTXoi0Obe{@w2=B7Pj6${crjj1x^WGAPp0BmPpDX(KkF^C03?{Z~5FR=~TF= zaVh@>6cTaE?SVe%vv@7W`t%L24{spxI>{SIxh8dV_BP)LXW8Z(P;JiIJjjNJKD`n4 z;THcxx}dX==vuUE~Y&1VX;T+e3;`SpC-hgZU+NpVu+-u__^3y7SFZvSMqP5wzslSf>W zf8ycYF=je z&gyqsX7xGO;&=GbOc^6P?m44H_D})l0M7gSeSTE}k^y#0FNA@|1Tcz%d}CFj``!2; zaqTnDyVmY!DI>Rr=fZqEq1dgW+PQSVz{F%S?c7>m8KDLrQLS2FAk;vx;n^fFPpEoA zPo-nc2vv52nWusLu8an9&yu;f!`x8MNdtLI11TP=hoL%w$yfhZqEP=Q&F;Yn2L3RF zuEJ7W!Coe?1sKbyUNvo~4MP2ZUD<(E$WNh4MtC~H8)2GV*@+joh5TwMscJ!pes(&e zN!K5 z$Og8URg$3BMew#%uj;YkST(e8*Vx9I4v?H@buDSBYw?+NU6rrv+OyQPHmhr8OI`hE z*0nre*Xpy>^|7q3EiH9zJhQG%`MS2ArLNJeuAMD)-FjwS+w*nZahAI7$?BSHscY|< zb&coiI&hY{9?@B42X#wr)B4Qn9?<#v9@aA|#0{`lJ!r&xVkob7v!iSWlK?K#tCp!i zd}4_V2oEQ2#J!_e-7n9e!||pqP}@4fdu)YCI$R#>0xyUH0jmOR$kI&^431U9^yN#J z2xgNW!w2jEJX7W2v0C=}b-zhG=7WUe0~Nkkam$Hk!*OsM3lxZ5KBIM=K0+?+D33HA zcw){JnPm#TsNk*(R+suZh1-)6UNJ@kqtpM`7GDm#PeleM*YL2)rm9E-@?QSH1J52l zcJv_l``+ZQEFyA?~cMHY`n0NViB-TbiB~-=O;(;)F~quB)4-i9vThu$v!9Jc~O1^4X6mY15U=H zqC634@&%lXw?yGnDN8PMawr-|l1y#D41#ph*M=}L6pYM?wU_%(c?PbRsK8PtIEN^# z!b>U!t%=(wEI|7idD4zTuUQs}^ZcV8%he?@sJ|HMKz%Hpx=yJmTK&(^E{4dBUkg>; zlS7Zb6D;)}GtmceE_igI_z;24oi$VvSUUxnr{8=@#g~)M^5*E@nbe?B_off`=^hw* z;`wlJ7(6H-Rt=S)h1vWcaPtfVLvxA+hJ#`dp;BtE8aPlWR6PphMVDgLqYL=K7J|1I zziME*-B$IeA}>3esv%Q_Vi*2L&5wE5PNJhsZ|gC6A=MMb1k9WUEFjK^00#&(CIN5I zGxJDOJJj5G=eZhqMl2vyQIViddqJA}0%D~&c!VcthM9OFd#v%J?{t}>I984`Mh+B3 z*s}&|#2M*{A3SBnXU-{T6?wgC%`$aA6i~cgwQiYufQhI8>LSKw+pJ^RS0E8sHwX45#ADR2v>?yH3N!IBQ>WqVpk`jidxv1E>X_ zkN1V>;|6XuIQR(;;te8th=XvFN#_NsuwYySHV}3z%whDswD@X zay{mtm$U&%l<0y%TcVD^aro#Schl|ls&rJfFTJeF?itx}mn`AdkDN=qn0Z?gCInnwr2S zz)o4^OdAeDWllDCI()aXFW^{JJ?41>=apw4esjxYEyJBe)}n&u;S0cRy=rr{1W0>R zSKG+2JK-Xp6h{+By(A<&BDQ?`fk%%V{uaNQIQgqd^zi4Zh2_)J2OmCSEh0sEsqfWq ziqM`nVC%Xl-pfv>h7V@w+kl+%h45GO7mEG4U{|}H=Jl#AGQTHfep~B2%P4(mNYRVU z`E{`EkftZ+o?Zt(&b{hJssA6`h@bb)J*f_+M0cafO_$HaGI+dWWR9l{zfUW@X51ou z%$+cb{>#kv0aSRy{gg=}+)O|_*a#HeVK1fV?zu$}&j#t|_s_Q4>HOl>emS?+s>eL-!P=x(t%FWluX?~+(*+{{x8Vvh6B^{R>Qyfq^ti_y z1O9qy?OV+yzQtn!%^oO3Ik ztpeVd+hmkK;-|rS%oEyWd`J)F1sg{oumTIeZoqmBn$#*R<1+OeFeYolKhBI@VVtzB@u%oJ zFKH+RwU5C`@X?co{a7Ymd}(4@^^n*=5^rG?$D!Z|&2?yE`k8VfHkznjik+Vp?N$XJ zEbt1&>;O>t+`D)9`3$yS!|21g(Z32`e^)K2#ZQ_?CLt%8!+wPWf3ZKRtL62^O&h z3j0jAnS%Q;aD@wWEhHZAOvhD4)6=i>6_*ni(sP{n%=GIX*trFop4M<6Rank1={`8! zvD7R=?D&cMPdr>*YLi}x+{@KQaTrFJVi`a^TMr#AZi2-(m% zxiwQZ#B(e>jo^iw=6fB1yw~xi+yfWs+a2g8 zzYl-H&@X)*>Q^UBBkqXYgC4?gkY_*o%rQg1_BG@=hCJD$9+ttvTHbBYoyb+WZm8{&m+Vj*Mom z!|A9F^Qf{{M$nbCkM6k<*T?VX`j|dFlJ)UW+DF!HiQIc6et&CDS0k&X$P}?!N`ze8 zsPs|VWknL1c~Kxe||xf8#?HK(hQ)jOn* ztlkkJSFVrJE-Pe6A4MS}dn5&2N&DztOL2YtncNE_>B}iuACIJcWL=BMJ*VRLx8`&; zvYLeSk<}z37yt%WRI|*D`_9yYb>shzm)4^`Z7z_$LX|>tg{fg=UV*! z)|{?Js2fNZS=}H)rd$`LSttld4@E&Bd*THhNqgwtdT~Ace6EM-yDwP}H@byp*?;8T zg7N!XGr9^PwwDe~O)vmwSr+#?o_b@#T!0ae_j8jf>Yp{PdYlM#Zo+hWH)NFJ~CJb8beE-gnRPqX$1c{gb9lFMVBGyc{Hr zLUk7+VH2TIUMQTlJf~1b)xD}Ko6m)FBb9($!cyVWLWGY&G98qNV5h1Pc*pQ{;7iQ_{GoqMs9k6xO(yS*ytHuR->56*54zOkIPC zS|Z^k{Qew7vka`h4dQG0bJ8{rqy1iWO%jd6R11XcIZfCck(DNW$Yw*f$^mXS9D!64@fy-PNM&jtCpzTNiG9 z3l?ug@}q@C(qlX*mI*IYOQO%=ktmrCACnB#bwt@O4!oVBbF8G?XBI{f7E5;c%7Kp= z>;t@@1hWz;*}<|qemx2r-n!3NHl8x>`87CAWgGb(eoU!HYUmbGHBW~Kp>Rp-!>Ii} zvnYywmMyT^<;_36qhfV*&VKS^glRv~LFv;X5!1MN&w-Tz8zcu-y!PTjN8=8#h}Xf% z-`oIXOT%XYB!@C|1bN_`=pLVvfu9M-0>%75dQ=Sfx zurbv6u}c`Z3oz=1*#ahw1@3_@Yyiv%yu!AZot{`<_DdhW^{Q*I;*7wSxT#CG0%?|} zvMLO=#6Sh_pddBf4;7Daiz1JF>vct#@nR*wWm@JRA%1f=_3Vr-4JX(!wu9S0@nYQ2 z;L-)ccq)me>*06HE{sM{8fUTI?D8@9 z++2a3OT(fH4~_DIpkjW5AR7i;P4O^b{5dsYwG0EkzGZ*Fz?+?MVcQ@GZ^Say_=3*B z=T2^p2dV)B5WceM0(`f7oFnZTzkG@p^Y~aWQ(P6?)?oVa)C&wb4LHN7H!TItTv+t5 zbD5AGhT+L}cnf3uO>_&TbXv1~llf|`3LSvSC$ng98$>&)V>0oM!{6gu#2zk?^w)v9IcI$?d`4R4+I zID%to33H%eJqX`XnR_yL4Os|>OxS+xH>CqSefYq^VD%uw78VBLnEsJ&WrJvxwL3AL zp<7_ytMPS$$IGy161*wt|H^>7%0xl{zWyW|-~##JF&am_#Q#e00rp`C%P#i!9Yt5B zNA}s8YLY(9Aw}IrXLgwy7LHVISQYQE`U7woC+xk>vsW8MUv>}b9)krN-vOrB+ZMxe zMJ>QToJA51xa=F6qox$O9%?gN*}%fK9)gkDm^F>oY518ATlpNU1Qf z&U+j{Yf*D~ydF4TcPj(Ulw+{zYDeg={}a11^yt5`k1>xP1LneOw;}E`$CNlILLi-_%s!zu!^@r8$AAcv4V0*U7!AI?7qSxVzk2N;r)A3tp2C0t4= ziXW@!Ib{`t88a}YF8o+Uf1G{_6xt6|+%ChgI^G_AS2M@+E#pkI*qvZ%7e>#D141l@ z&@~|(?Y-p;ffYXR3FW(FRxzfhxsW1_U;Epah9cS*l>q45%j}VkLqc1Md!BpOt6xtH3|L9xnn1t=U;GrZx4{2Zf z4A^{!@vL|^LZYyQIg&b_PU~pSrs>aoI6{l?vA6hwC5IsQUW`0NKm5pB5CTNFGJ*Wz zOBG*5v&UYuJ2gG?L&HKjdisY3vI9lG>8{&!BrTqD2{I-DJ(-qzA}#gVwAA6WRLc6u zI3M&_TI$iX)Gwr^4yC11mQKdep@-8_2h&myq@||QQYo`4<5khAx7@f+zU9XC157Wj zm?sdxw4`jfj0;Dvr=?y?OMN>nbv!MVG8i-dBE6iJdND2a)wI;Hv{d?na>hBO=hITp zrKSETEp;?41&}y|)#S}WPfm027=}%+!AKN$cUjt$-2iTZq=3f`ZU-*=0$9h>lvmT6 z`pc&beT&JJZ+P(nRATOJT9)D<#pZGf`^qY@MI1^D6!sO{CK$0zVAwm0(IOZfK%E^4 z`fkl1fG85vMN!*_KR029L@769sRy|X1p(UO+J{@?B&fey_9u*a#k(FHgi@jvu!3lGqdHKai*7Y!5{KxGiF$5&Z=d$(4=Q) zwwyE3^n|k>(JS6;T85qGtXgI}O*%TW<(#3Wmoni$Ijb?lT60z{v$ZBYH?!rOxu%!$ z^H0xe%&^&UMgexlUX$kyUtlP%yyl0d}hNQwlQ};&_=w;mKQ{Cc1P-}U@gN6VGe07kpL*NS(-J)RHeRS=3)Jbi;cT~vN?!Z1 zp$~8iZyS2!q-!sVKJ$jTP|+%&y;K zZyO&Twzt)HjZV~W8@BZwle_lpw!3y7P`y84tzEoz@d34W&%`by*XlcV>>ID|xVtvG z=Pq^oj)~fiJ-c@gbCKHUo{33yXMOj+`Y4ho$M=lZCU)JvyFMzP_S|;c_C59SooD?x zF}ZWuvhDSqwH@_|Nwse`3J&kI6L;(x&qa6bo>UXVlj`NMbhti_add0AHhK5n;a$6L+w;L4d-tl_cGh;?xxGGG-@OB)8{e~6-CQ5v-JH(h z13QNIV(BC)7ablQ-Z446vnDg3R_>apkKd^V>!YLF>pMp5yyK3i|gR9O7}-?-`<`0a@)?@oqHztjMwmC-}tcF zUEja!_If@g9ZZ^I|Ky(0+HJcI4DYPnwQKk7HCgHG^KCn8JH~fS?%Giw&8H1d?5Nc- zO}A&M>-X#)R_Tr&-E&uMeE81#E)1?Vx$DkhwR6wD?W4nLcdFY)cin!+B(Fzpbl07`CV3|g?;PH#?%K6`=ghQh-1X7XJv-F8jVo%aH>_P* zTSr@Kx2VlS>uT$0Rc*uI;O2oXwOiEMjRUn+8#mW(Q3GoRuc{5)RNJ^Aiw&*2F&{-f z`MP$?z~(Kr%>(Px1TMU3{i=NS4TEX!jRUothEOX)o7Zo0p|va1&~ieEE7`nl{TA+` z_$ftl)vKt_|IS30Pel+U9<@HphR{EoueT zHf`9lVbh0d8=H}9^O2?bNMAm3O+KpxOJOaPFt?7-BcS`w{Z(cuF6NQ%pzMh4FRjH zrAD+PHD;HvX7~c}%i$^6|#481c%Ln`>(ZwyDi4*KSx<8`!#HbuNkzxsBS4TwBXU zmgXaU`N%c-$dY{I>U`v?eB{cONK0&S%O{Sd2h+-dwbTSWiSak=!sbVSV(uet-q;dd zl}1;j0j^^?ZQ9V1@1}vZ`8alRu2!6(x#)&L7u&RDtw6eboPlGuW@EuI>S8HManTf| zY@LZx-1iivxTr%ZE+%_8E6RI#tK!3Y(~4&3s@hh!4YxX2T1V?^bmP_>By4O(uFXf5 z<|BRi$Tj)Ml6>UqeB`QpB~p1$w!vtBUk4mSLGvD zwnSQDi(5W%47(CY^%merwRZi=!JBJOG^yLI99-Y+qfbZYu2+>J~Oy7 zcyUc>y<5}R#`U#Lwase>ZcY>UI7{Q8zy>zn#NU7uS8TkI!@$a*yS6G?xp{eQ?a*e4 zG3+$QvuT4QuU)@#-HI%h_IS(CTKNo^UbSu0hT7nuBnawRIkaiBw6SGNZTS#MB%O;* z{Am#V#t_h`i)@n^`nYmv^Onu)H%kKA-MXzdu&Eiv>9cx6RvKeRMVR3eHoUp8Kk>svOzLk)z#Gty{4+VXC_38kW9ir zmU)@U286UcL{NO9EQ%nGf+zwCnuj1uf@_or;tCiQl}+$zo-DHY_~d4I<;~+o?S0`Rv{$Ff?D=`uUJt9I#A7` z!wW0kjGI{&CC1V)A!7O7q73{#s@MH;tyVG%D#^X&)@@r+#qw)Trs(;OsRYNA4hWzY z+}F>Y5|ry(qO6-)E6^*0r}{jP7BW#40A&+;o>VKN^jGf~ovl9g1%8znPQ z(u|UoWW*aKGf~ovl9fcn8znPQ(nK=X>-YN(Ub{C;Ibn+DTdwTa!P4*e#eh3XI#IHY zWHfYyUw!%omS14$SQ82k%@mJnW^i}})&08J@4LML@*K13#&Ee-^lT?a$lGQdI=0tv zs}^hxb+^EE zD%&FJ%#D(B!lc`r9j2Wq={9FY-!LSe&s5LQ4T)$YY)|#TE?Dj#`mHJEuiP-@mNX!ZdL1Jb=2ol`^AxLxugdmX$2w@^1go%VuWC6?CP4qe%q0%UO zMfRVi)763U%!V*|lB%dDCG$jbIAX;fHUnLcGUW)cbzM;Q`hAaBo6OWaN4h*+?#yD@ zH?06>%YM1$y2vb)+i@)y&vmRgs%1jRtF~9F@v2|uhcx>V_Y$tyo?rW3hU*p?>bfi znMK#PYLyCy(u7+YtXeaRz|5YJ9JWPbCD|Kb#k{&ZmRP<*zw5>3l~-^Yu1EQt*f)07 z*rf|_(+1|<8Pj<~RVh{#@RCD1lpvbJ^;vnrhZBCpFEXLoe_7Syx{)T_AN4nVz((JGXX>J&HK$VLdKU*&IPT#HveGx*L1G#dom)-aHCX=CLW@@IB z708y0{rIjBi5+83&N3~Y(*Vqu3Q@((N5Hgrs>k?}A*z`92$+@?0oIp@^F_e4ECo_s z-i!0ga{(GH>aF;0p;q$(18!IIJm%TzN!ZP|YK^KuiTVVvR`Kh#UOU9X?UjRU(|79$ zfDFf6noi!g8jfREJ>4}Gvz&A+-zu0@->Q1VbBM#XUPU@DUw3nU*`sPbm-pRX9-4lo z9Mxp5n5u9WKBpbdZilnl;mmf}-446jVX7S_$G|Z-F(x~}JkE+PyEk7Dc zin$mrDCUKZtEY!O*n>AbD9tq9DCgV}K~D-LGHL3bQ<0k}=y zD+fR(UMijw0Le+la{{0_Z731v3xM(o;s6}aRUSrl%Zu4{x4&x1vQu~LY?0qLwjt$J zQV6-S=ShzQ1PzOD4}UhqK_>eSffFH_jumBw0~(rYnX)XQ zfD1V4fIfEZvV;vC6NZO-nkPfqR2PDu8gj|hY93cGzVuru>D|a}uKOB@V0g zYT%9SnRt_ItsH)r_}P{dE`@pm6=6Mrim;wQMOaUuBCID+5!Mr^2NrRhfDG@{(c}wN8av#rAm(EjqHYH5c+CqshL0 zNjtq7xfH;*j9ZqO;=6@{BUzSH^dyf56q>6(D21m)A?qlBUv$q&hd>TDE5O%1((c@--!m>~I~}eQ3D0#|77|AfS+Q7DTPi5ri>> zgb;$U%U+6OF9@+LvrG{8rBs78WrErCQ+}cB=K_>$Lx~V^d_p{#g??RX#?O%04`LrD zLTVoXy8`uKG}Z&(r4GwB)@iLjcGdazfP3|YFIdIhh_p=*6bqylrJjm87tG0yNUGc5)MQZ&+e~I~ z&~On5%*V6TQOH&#$Cb->Pv~pua7EFwqXX{JwVC zHkfRO2|!(r-F~;2_05X(EAO>KEUt+z2pqW47Os0%!Ot>eTtpM

R=}FggQP?KlH2 zR{2y`7A<51$GF8RTOD1Xf~-<4Mrh)YnontkBRt*Wvk!>q@mMy1!D(&uhI&3*thOD= zN|on|kQ}25=3`Vz%*Kw zQRA48QH#~khD^5^O3erjrk}m?hhO}B|CNqFF4oh_xg5K{D(q@&mRP`t(OB#&I|6Uh~1WvZdb)w zuw`)PdgYQv!}XZJl5$YN2Qc=SNz2OgEQ5=bNVt;hKF>EjH$bi>$+qpUU5&3tc2zf* z#VW^1_)cW3C|-wxcQW0AZo731xt>*O^*vtd4Mmc+>l$8##$fqkA|$mabDH?=xOycPEZ^G4CH@l6HY(dlaI*-k|| zS&rGX;I=o)`jv_-OW8)H&b}mPYjAI_Uy8t-IG7y=v*KW89CXJ)R~)3`AlU}mP@*kM zkVI_lDlcYku@XWvUynl`WN}IB0l}+EkcQC~sP>$1$_V5GTqNcM zi6m0-?OL%yj>Y>nNhFa9ICujm8DS!cRKUSoI^hTtNu&Y}-sA~Km`EZOaPYQIIKo5{ zsepqwg2E9dl1K#{yfqY#D1lVK!J9?pK#D{59LV?h(iI~K>xYQ%kpSg-eMgvN{)zj} zn)Dui*0$K6S3(SeIK45YvZoYmau6woYuHF~rfA9cJ3e3217xN7 zey0tamK9<-BU7v%lv&Q#oT68#h|!R(hvoE^WkS|#uH}{es@W{_+M!N((JRZgll>Zg zMT@b-E%X36z{xQu^iOdMuAG z`bL~$*(1mY{SnGK9LVDeiPl<90c&Sxz2?=dT3H}_;DB7D-V|YPE%1sZ9o!WWz{5{d zd}E~?ad5moWOwAUh(K)p`CzqN4iF!oMu-ndBg99c<#NpUn?Sf6$dK0*y_x5FjDzVh zTbF$|qoELyg2*~PNBAlzfTaw?E(gaU)rhNBxz z8=Vv!frJE(;WLPbhMR4KVzr&Xq2YE8v+fthinI|}Lp^eh40mT*NS1@rZPdU=N2tfECOSXFDCJA zbPG)rA~_5%Rz2HknmRr-NK|c@<>;imYBxN`EbBprSU=mTDo%~T$v6&HJFj3n6|)R4 zs?rc=!wLxe$u8d3hXk=iAjIyRmc$eXH%REuf zGz}x2#b7CtRihYhOaWnI3W^$2El8(-ySmoi4sC0p8w^Ml1ydFy6>xn}atgKH-DFTH{exUyaKdy835Ux7!>Y`%XK z!CCEaW;^U|hh6P3)ee*GFcHDv$l0!I!Hl^n>xHPH8OVf`g>FH$&}IiYG8tR2WGnN!wLK+hfGj&l@9Ik3@Fx3u|?JxnzcR$$p^VKw& zNbC*Ery-ntRH}Eq8{hwr1A-e506EfQ>mb<+9;kmF=`F17a6z)m%|3&$G%l zopQgG%f}+Db&s){55DN>*|Ap*A&$7Kc3xHpj+4p`4X9#jiF})m)6%tipORtNTMKL1 zVuVv;aB>VzjKN)g{}}mpoE(D_V{n(>H%7i4C&%DKfP*#H%H_F9a@zHE+bPzvzME5z z78eO?IWey_*LS^=&&|)+;Y*ilH*!MYk2`042dFv5J_D_q;>5JYA1CKk<>Lr zTGtRtT|*>w4UyJ0gi_ZKNnJyvbq%4^HAGTZK{~{JZ-H+$Jg#jRaE{?DD~l6!Hw+HB zdf=5{s+aoK>E!vZSCaoK=3N^)E_;N<`Tc%vl8WkKb* zY{1Jg1Mo&kj>`tTNUHhd4^W5elhtsVwr;0Q$FvF!&z8J~%hwBSoz!{_*9@R6-U4}l z;acp%DdwgX+pbWSdR}gXIoO7C31(Av;7Ic3+p{C{z?TOCY&U^qDe+7zI6&EICrujP02*#xamfH2tEm^VTX; z_8awV_}08>YuZkx=4yBJ_4}67D7todt^*jF)TUppalR0^(PA*~m;uJMQOyjSG{$T5 zdJ}2l08R{gd|f7nwasG$ZuA)BR*ykx_88_?h(U>P#4tDY7-+`{ddWY=QLxQy9CMGv zvNakNBX9wkIDrM)2zJv%e$=Tk1=6dEakDUEqLXx6CD1YBh>v)ASH~aOXgE39v-r2736()x9Q)$L>PQnT4YTi&QpU!SGuZTV3CayvVcl@$|5Tf8p8=Tb+XST!c zcG%SpQ|&O>4igH+n(`-f`39M8@a5AgjQBLgt=DShMqRU&Sw3~b`D}2qy*7J245Jey zf%*|ki6;cOV#TnYz&J(MZWH&iAq=lih`iV@8RCvq&g6hd&M_-?ur1*;BhM@AB;~=A zwXIsCUe-6^&3xUd<%(q+@yq}rR$k0<4le)NRWnnzWl@Qx^Ff*qx+0cLENup9+*lAb zQg<=jazGQF$tj9Fp$Mxl6k&CLBCHNjgw^MXuzEcaR!1ko>gq&Ty_*QDe-mMKX(Fsn zO@!5tiLiPy5mx6V!s@<6SUr{qtIrZ)byFg&j!J~pH;J%%ClOYMB*N;FC}uOv+e6uV z>L9N+viWdCE07t@Hqy<7BaUN@{AD5G=7IP7vShPUEkL@SmtsL20WMbS4NswdCsHUR zXJdf|-d!lDdK^zGRu%HN8UyQ&%{EN9^>jy~(MsS2EoWL1Toevmhv0H#b}ErS<;M0( zkY$GFk%A>w?wJ`y>N`k=`VL_-p~>*>w5K^1PgPCELRx%RId~hsbm=hWvrqZ>Kd+Nn zn=f>@wT5Ha8f%QwsaQH0q}dwFM@8hLZ2Ee9=gq8IKoZ)_nU*c@glm!62=vE69{_h| zR^x41wif-4J{>&k{Ny$g=S!2aJ@d2iO`U)+#3m@(#ARb~wJeqc{^)}jfm9qM;~>F6 zVi){D`mEjb-8i8Q)Fn2V)g@FWfM0b1<;o2s8SEj_4(H=})5)UG<0ug#7(L(3TFe@* zE_#q4RV>wFh&|gVk2je>JZgj8HZS(vj{1py%&hqKT+@vVcIyhuAw<|lxANSy727M+ zvg&r@?sK^+wF?io8SB?2@TAOF(ImJnA%x(rf2M3#vr^$Ke{jSqG3188!8jk3X@lBu z{QOE*hN=XqvaAT@N(@;l5`HqXP}Uab1}SQi?OvhpT%taMtZZx6~gBkYFSoNtcdf|aBU1G4leQrz_GJY zc$xveB+Dw8PF^8@O;!x@7i9%d+*=8h@{Ir~Q?K4AcI5j>WOY;m8*rY&5t4IYg?y); zJ=?N;?}k9O{V|A8y<_SGh`~sfx34P9J{+fco)iKgrb)Iwyh5ne<03pu)4UJWv=h=? z&kj+Ysq$e;vDV7U+kk%GwRkSZt`xbVlQSJo$8JvW*S&?AeD8(}7lVm=IE-<8nkxqk z5=ARGp2Y&P{x@#j@IEp5%= z>|)CD>rO`IUbe<3+nKiGP~VKLy%n=Bg7V!g5tMIciJ*KxiwTFSSXDoxX=;sgyv*_L zls}@Luld!QpEVib)53CrF@kb^F@kb=F@kc1(F{+xb0#fWj8CR4?p(5B@$hix`oWQN zR<9lDT)e7t_1WhREE!2t^c}yaowjmd*vW=9QXXw?C|@7{{`RRs{f6W z-Ezq{DDS2wgR4g7_`6~FSNW_UIqP3&*gXTQnAQC+RP3ICRdl8Pg^JxX@K-nQrk#Q> zuiiZyzTtZJO#IEs|BI58O~1f;o__D~KbO+42kwc!L?qX!T65dsoOU=n*ie{_zFA_X za=Npa)y_8tCTFp8km>UKW=bLzB$7cQ!3k_u%tqhLxbB(ly2rqzs_gRnx&z&sNCuPy zCnDY5aoycK^W{*UO_&uy-85L;?PZUF$!^_>bj4lxuHaoYk@As928jeGqWW}+y_U7x zEPG*&d_JyA3{yQJfw6Lgs`;+?TS!Lq77@f-bhW?57?|wRw@B&gWSQl%Tg+D(^BzVw zCMkZaN|)c)rAa>BL(+_r6@FVVL`gGBR=5?w5GBnhS>e_JLzFb5B-bGo)d5Ma1Cm^a zfFVk99Rh}AnB+PH8loiEAsq;e_WF{y>l+^j53^EgxAxi4}PzIR^$`B=Wekg;?1Z9YlIzN;_W`Z(ANu3|c zATvQ3qNL6bWssSm3{g_&hcd`aP=+X}^FtYACMZLc)cK(dG82>`O6vSj2AK)U5G8ef zD1*!dWr&hGKZMHjLlgXxGA;OJg87k*&5vZ;{0MVoek9xGM}(^Rr0i{i&o<_g@#!Lb z(FBPgCP;G3C?5l*mfVP4eu68k16qVQ@T8PLiQ zC3Qe6gA8b8h>|*>l|cryGDJxo(8?eKS{b6G4rpbN0j&&CQU|m$$beRcD5(Ql8Du~! zLzL73tqd}tl_5&%fK~<>(8>@cbwDeF3}|JDk~*N3K?bxkL`fac${+(;8KR^PXl0NA ztqf6;2ei<5Kx=}fg8`k;3uiTpzrrL2YSl#B5RS46QARbNXdlgz6%F7BVgM(`jMxO7 zxN7Z+6(`Y&_-%@lsJ?d1KmujpL1c9s67&633{RtzjXnz92c21W*!{&NP4 z8P{}9A3Uv7eg}k|^i|6Tmh!g^$ZuuL=v*_fa`ig?E&~1el!^Zvnezq)hW@uA{G%cK zr3Z_bE{%)eS9>yz{Ary_*AA^1T(WqCt2eOZyv}8-*XS#*@duZ7P9K~YaA(&J1wZS< z`_j&0R&rx+Dc`Zsxn%XKrSdaBog-@omoFcXZ(RspboXxjuJ#$j|k3 zP9KzC%~`g3?W(11S|KbysiQx_Gq7~5?673>Z~0852LC+Is?{Td%eWZ^SFbuP`q7>6 z4LVO$wezPB&d^`(34ilONJ|#49Uh1>=T9FTK4~H)Q^EI7WEKw(P%>3ny>#u0fja-* z&@jy@4-Su1S1%nX*4uMzniI&yRCoi!Bb1!QZNxvZ*LC`$cz_FPhg44K1T(LtJaB|KAi*Fa6)>T{ol+Jv2o8 ze>Itif;V037O&uDlNaNEX%Eu>JMi2S&m9*KUAUTp<{i_f>;IvL){pI>_0o=_=R5yY zPj>hp6lI6UYGR6Qlj@o>^v~*)9sEaKga4pwFs5q}>xwr|G8v0)@fg!GFWEic;(+h= z-SeFj@cnG}e8U0XTf65Q3HXltx81(SV8B=2J>R(j-^lLyRs?)E?4ECB!1tZq^KA(D z{9Ky-Hl`?@JlQhlw6DJ;W$RT@9+=n`7 z!lZ+VCXAcJ`QuoICC$5@>6mo%ev!bWeVM#3&#eheoia%{`R?!Nz)Eus{Auy zsxV9?no8zJpYNE|aUhx3J>N0uXM0TJ9QkL$fx>hk@qdYAs;hhEtl4wsni(r==U%>m zs60ZnW3%*<@9WRNtxG0n`Tp=ZgDd6dv3&j&IB9?8zi@=e7#Yhy+xI0P-7diVxBoN# zp|ckc>#xj(1u*~45u(w5&_CDrhgJ`+8sT41+c*?RF#qJW?@*sq!uJDrEG|GKGRE3> zC?gdwW3|6>VCC8ErJ1k2&@t)8X>Y&%_S>w88-ZITM?`rdDiBdp8k=a#TFooQ^3Fiv z+upIlT~gtti&qY;8d zTSt^#rTKFpbND)0GbvAhgmsA~Rz>(PGFLkU4HWQGKz>c#siVX|c$hwVr4gG9!@bW0_%=k@?gHB4*`rdOKvUWSI?0+Xfk-l{SdXjtxW`A@dYuzQZybRpw>L2(7eHWLSU) zESEEtg^B1jmce*Gaig|@&`PUBrh6mNYRD8IGh-uBeYNUY1R0@~R*TFz8;P{@AuPeDd#CFaz2_!7%u&fE{VQIQ)KxgSGLXeH)Uxu;kTbKqsj zJuY&CA~*g5eJ`Pvm{b2|T%dNh6tlZ!*xfl7yu(7l3zz<$Xlz-*A8dFfrmKpqt5HrZ zmRCnPqwiSGEZ-kkwRY@+%6~&xM;63%IYi_Vkw-)glsWZ6eYfTqzFs2gBcgtk-+7_x ztR`a%IxmRBgYUFPYaO6_;TYX#644?edLMLO_>Q`hzQ1neKUL0)Ij@uNkLmXDPCrK8 zS+P8})%@3u_UE-ISYLU);J?-;?SGyxJpTFb2GDrk@%ZMyZqRsQ@*v@@(!5PX?#SHe z7i#f$7I@jVo`?5cu}O8fBgroQ>DjmtJ0Dks`E%u$Y2`;XA^W9GT2FT*m3YUWt;JvG zMMNi)+Gn=6{5N^C+BddWL!c4({*BZwi}Q04iM%_KOf6l_KhEk8@b4|N2mQOQLM5LmxA9xy-*P(l-l1E`RZwHeh4IZNT+=>mqF%cO;nCazg+#OoFUU^!MMSh21?nShztocrr=+oC7(lh%6qJ7w6fig9b} zKHSRGN^jp!^;D(at@L}P-mP?>*tAyqhW#~yb4`Qjpl>`j=O-niy@+Ufg{Z6R>*-@p zCi>Bi$?2OL{M<4BIMGXFPi0)5zkpkthz{VE=J&^Yes+x zE!*DK){{?A`PW6hwe@|x&JfWR{rvtPFqZ5`v~1Zj;|lN}0scRNe}PBD+n`P0Z-W0K z@J|8%6X3VOzY6?C@Q;)J88Y8EiRh$7ADds3_b<=??Md1XKjw9fh<=#V@>-qxe2e#0 zMD#IUC#jXL1Md%fGw;PXpVw4srO$_+E1{{8fLaqv21Ac_pY$7@wdd5S~1<-RU^gIf=uR`uv;8TG!=>PZ2c-WS{Vz&1G z7f{dFc-b zz`qpy^TEFbeB<$41pYsv+>^mS4g8mb@7Lf<;(0CjccFg&b(Gfg{owx^_{QP+ouEEh zZJ+y5&PUh+5z#Qp`vvCTHN3|sqCZ35X7tZOu?Iw-244ew8SuT0etJLhry>7Z)MGR9 zSD`)))aPQg!8aXz523uzqP!&XpFw@5A^#}kFXPpUU4j#c zcnW&#`xDV!?6VWm1Lw*-eBiC+M87-#>iNG~s`K)>#cWq^={Z`S&-QG>`f}9_m3xf! zw(iS*g?&(JrTAI~bDv+?Z2a{``!g`QvG`5ip(!1MEXzO6A$>ecuseMMrWt*w_H$F=*h!JYuG zV~fGpC(%-(_aT1!C#=_#CDKZ?6ngH1o>A!87kXAf&j9qC3q5Z_&wnGo2tA|FvjKYk zI!Ei{g6|CIsX@<9=y@9X^PuM{=y^Z%JOe#B@Xd#w4D|d6dVY!gQ=#Wl=*dFQHVd$9wzGI>1MCkb{^gMw4Y0$F*dX9je2chRE@Er&} zhe6LM^xTR3@zCQ#&lKpn3wjO!-vsE{4|+ZhJvSl$P2@Y!vnTZ23_W{;?=A5+h&rI> zV(7UR`G1BU8+u+nR>$Edq31P;#1s7mdS0F=(};$l=W^)z9rVnBok4fOmRdY*)y2J}4KsrCCF?ATReCy2f)c4D&i1+f#0 ztgYBXpAS3o4cL)S!j9Yp`|)}w$tmIh=6MFs_ux4d&%a}SKa1z1c;18OE4;(t%>aAv zMD#`W_IdjQyEgko#s9glKCj@o2@yRDx#J=CLCBp8xf3Aw1;}lJ+%F+_Amo-nZXx6j zg4{KbTLro8kQ)a%6LM!jZXd{f5OO}`?uFc|SZ|Jk+-Z>e8~ok1kgG%P%aD5(a)0NY z5D}dWx#u7^067zK*F)|Xkoy(n4u#w=A=iLh3UXIK?t75C7jhFJ_kGCOkUJJ~_hVdL zb)4=ae#J2#+LEz3?!%!a#GuYY{to2NLVg+f3y}W+@=rj18u_!4{}tpPjQkYxUqC%p za6E)JgL8;3e4>NCv>(x=CeddNr9Wm6J-*kT^h@{ybFkjMQrG%l+DpV!=V6&&M5*_v zoF(gIEB$lXFSfQ`g!cHVp>nsJ$@{Rb^fDO-t)6$=x?w%&Bwas`fu32|KfcgVxp!gz z`N`uIKP>ClgPE5&R!3w!Ia}$Ij$zno-X!}*qH#xPJ^yw%(?^Xz!|!@(x%#hnE!F44 zi}krTp0}Q*xPs>k$LT!&0Q`{g2WtK|U`M7Np&^M4M@W5W7V2}`Ns13c`&DHhF>3ry z+Q~2`f$m$%SI5)DGll1|cuvK0Z#-YksN6R6+u$s12Se&HY79XCae`av_j25phmzttK1Kz|0$iS65Vor_VkXb!~=S6;%EsGeG}{I zWR7K%VO(61{dxMoMemOJNz9kiq<*93ZNk4j^Lu%Y8h6dp_x%a<94dN7jgNC|o6a&m zCF{=i%+JIwY|mVQ{Iew?=-p*zZk~2va0f4^Z!TsbJQ5F zDE^LM!+5={cm?#VLA~~bpWlOZ@I_fCiJp){exeU^#EFRB6#GH+5Z?bXS^rx`UgvxI zO@rv|J&8UvPvbcMA^LY_&V=6auz#;Y@1If6v*mp#y#@IBGRGmV>$wK|-|>>)N`Fl3 z#*lgO=^Ce)QYBh_z`vhnRfs z-KFC{eRNghL=#PwcP0KcYK}XJ+ppa78SMW%pzqO&)}w)OvQ65(JpUz}TTClyeLs`c z_PCoHO9>p(LZV~f!^a0hdWy48>MG;sooEx9<$ND)8W5- za;Db*yJ`>VC7hG5$3E&A;6C7MAos`VL>x={sLXrA_<+pUQR6t7kDccA$Lf1bIG$)6 z5gjP|woap{<0JhM$uIZZe=v`lQR8~4e=EIF?oYJR+wgvW#XPxE))T{+i}8OF_&~%XU2;dFAp4{ zM~q)a{td8m1)FHaK16rV(DiQbjE>vQe`XT!c+ zf;ejP1hq>)Mt^LA-G4^LK`Z@P_`i>d|2t}S%lg=99ss{5!;xz~8j|rqbSFo)+1~*k z1ug<#3A|e4nrR>N?>?#TsBzlS+CB@!e;6{aJwnGpLhRZu(}15a6>Ou5b_(`|P`?k`rqF=r$?@Kg1SL|7O z0{Z1LjK@XNE~Cchb(|XC5_@GBHSwcbTeEqcCwF08ns%zTk1y-(N*9WT$n#+G)U*QfGZzc2m%lyOi~ z`~4Z=Cz^xx@d0TU!4Py}>(b7<%pakD_QZR>4|2okpBKCMvaqlPE_aiH~Fmgx2Ui|OMVy1qRk zaWljCtd!GAFO~l2G-sn7w`2VNhu96nSmA0rJORJs?y1^O9T*Q6Rf(K?ZtU@4M_Qe@(`nwP{)HZ{B{G`fp1XX}vx?L+!!)k5Ih)FvS}oKYya?e~-+IR=RqM@_k147xNF0 z@^{SdQvUS1MLLd;lYRfFu|oWwR@#>N-)YV|Q`+zJL$FV}E~VvtLDtJw`gh{Lw9@Bd z{X7W%%-*Qaqetod{W9dPuj)K{PW_y%zc^CyqIt@<6Z_$z_oyHI49cB>`EzSY&s&Y7 zh<-7LXv$GUJLeF64|bspJ&zzBa5nTj>8k$2q31^NlZZ~mdcOyrcSFxS=-CE69`rnl z`b>tNtDxsd$iEEvQm?+(Q>W8#sG<8!2kZ3~vFGKUL4JS8-wydlApeT2*M{*eUANO;6u+rE^Hae@UxL3q3j9ID=brA- z^6$d)TA>@pTUbv{Kz**m`cy`J9+&zQtUXSVdDioT_eeV#6UDBQv9InYdbXi{FCbp> zL0(sk!*hopqyF7nh)-Oi@f^c~y|l!>80LE=UfbGw751qwNxyE%oGA8r%eQ`k_c|7F zy1yaLdJvzF^ZoID?ca~4G>&s8>M;@VE*o-_5eGg&=vy+5(6?l!3w?`qu+Vpz2P4kW zgLQBSPcm2uiKt`mMTuNObN z)4V|9%%jFNh%-MX`{e6-UYGsI`PnAoluz{QI6b6G{l=+M{^ZQrGTslgt~p%kNmuVl zbYi~Vtn)AZE#Ysa_w5pUJinFIadEx8Pj}{%GR_UNChcb!4@*2}TY6qe+xHCE&6%jr zz2cX5nzO~fXl;JPoI}X}mT4Md^>uhvqEO z@ph0rcl2!3b~m3nlh>hV)31uX9yO;3eJFDo^!){X#OHxOBIB%;zE1QS+fKyz+DD(p z4Km-ir9T0`^yljT8+U+y6X@OIA9b2D5bwI_2yKt!;8#8`?bK6cFPZtCB06y*9k;#r-{A`dpJ|ZrC~e_J3LA1J!;H{ z|7D0DUG5pqs=oDz%kGqM(rLaXcDj{rz^{B>=4~szuUzmYdIaY#hXbF0drJG@o|1|4 zm+$huM&4iI`6rndM6V$~h3DPKUx;T4&tvhNisz%4@8jh?Tj_t7`n9(1h5h1y*rnFi zkK(I|55AS)bHH~2 z`2LRbIQ_878`(wRGr`vnzCVL+FX$_QF9E*U;QKB3UXu5HBYPV7jso8_@ckHkzX#t* z;M)&;FY$h$bzk-&@I3~;gTeQAY2Q}*G4Op2eA~dc5BUBBzORCBsXt?r@1fqJn+p0UmbkUf$uHU&jR0x;CnCl9tYox;7ft; zAn;8F-w(j|B>0X7-#GBSfcO0-_=TUiF*py+03QguJP7=GJQv|P1Lu?vn18QhetiZ{ z6VE$v9`zI0;VtmzcEJzpK-^$5^q+?3o3bw@DgyW6c`M4l9Od7H@_!BfAHXj-4EzUS zoj(iliWkB6C-@6H@qUlsIfCaO;rAKSh<>~eQMOCZLF&jqIz{yTds00^hw<}k^H0P* zln-QxE|~h>o95b!IOwlnCx3!^+~Mdt_+NOB?bzSGF8heq*6R^(tEj(751p>-->q0j zXQ@9x_rX8^A>x#qF;4yi5?` z&$ID7P}X^(TY$eI^M>eTo;UpQ06gd7c^IBWJSXsZ$=h$geKGEl4obbYXV$5|ZJvLu z`e6mB*AM*X@~S(2n;=y;@thze~o~JQL@f-^af7FXE@}n70-98`zg$1Uq)wp(=OT zxkO!Gf7v?gT;0d7JXiPaf3ehGJ8ix`*UP+br5}-dxI5()_v;J*!OM1IP8R-Se4N6_Ys_5|Ik+41^x@MFa9p#TrXjs zUW&N#`=ws3^j?V1zbgBy9S=T(^X${bZf(!3L7Zly^zU{v2|wyA*hK?&@eX{TXD5G_ zgYSFea~~&x-Us>|(7ymb>}T-9w!jbj7|P!t<>yfTZ)E;%H>aTdG|E2;?+5*RDCZTF^K+Dw z0sY@VUjX_aVGnkq9TL(H*JhSWJB%7{OFcR>z37Ka(GJVd4=t>ZyRaT#jpwD%w-@xC z4t+m`zAE%>g1+}b-+JhK4thR6EI{@y6R8|6<$`5!Zlyam=S7l>cp%^H=Em3Cc->z6$gz==Y(V7f{X*QO<18mw}!G z{d*V(Uqd?_igB<2?eIs`<1qBY8EA)-(GQV*gWdu9D$qZJ@;9OUaVY;=DF1cz z!^ctn6DVgq%6}gE8lYc-a+ZSr7|M~)4ieE*D5nDYg(!a!=yzfqT#NF5gz^Va{yiw? zIh6B#l+z9R63{Ks??gGjMLAnh&J57c1pRc-zlm`$dqDlqgU;6Y*aER1qsI3<_ScS` zw^sZeJ~-jG>NMBm*+g7)i^loVr-1$!@oQS?H^eV!rSB7etF`qfdal>=+VMoy#rM+# z@8WN^Ao}{dh{kh#L;c8fFXBvx;R*D@~%Un_kb{E#8|Z`;#E zJNG8Ku~Y9OJdOQO0{fsn;n&^^`gqW1!9V#8_C;Uy)Ni{L@v_eYUj=*(@I}BAQIB1^ zzc3y_ocbBT+tQx{z6SS|9)h2GKltxfJ;w4=#c$fY7USa%>;s-XlIWgeh}Of8n~u+^ zTmirRLEMX+me6=qN%kwFnO~^?WxgQ(XQ%lC^?TD#qW{j-{iyMr&^yh&r5_FBH}I?b z5D&X;p~m0-6Zi?d_uXvpe?AJ%PU4ZA+hY)@Hl`r+o!hU(WJV(u=&@PwD{BUlhEB&yH>n$1nxbMaIx`J!)A;!eL`Z4xf zSE`T8c+R~fUuVHzv%p_#5&xgRN`n7qKBixBF9{#(esU$zr|#7cNglCEzmg-!=da@6 zG=IdO^#>R|kfRaz&}d9Ui@C(H03>txJdxxh4j?!1@ixNoWs#$2!Y z^5IdfFY5~Uf3y$Li+dBzA4hc3IHG&T6LpLy`pfA=Z|y_$@;*ezj3b)OAAaoQJ%jny z%X>`fFvz_6l|3fy$J=z?l0W_cUjicY_E+|p)X_oa{jcmXX>Z;@P9(GS>K>CO{P^1) J#AgrI{{s#wNlyR( diff --git a/docs/public/config/failsafe/parameters.json b/docs/public/config/failsafe/parameters.json index 4bf9a32275..193d313184 100644 --- a/docs/public/config/failsafe/parameters.json +++ b/docs/public/config/failsafe/parameters.json @@ -1 +1 @@ -{"parameters": [{"category": "Standard", "default": 75, "group": "UAVCAN Motor Parameters", "longDesc": "Speed controller bandwidth, in Hz. Higher values result in faster speed and current rise times, but may result in overshoot and higher current consumption. For fixed-wing aircraft, this value should be less than 50 Hz; for multirotors, values up to 100 Hz may provide improvements in responsiveness.", "max": 250, "min": 10, "name": "ctl_bw", "shortDesc": "Speed controller bandwidth", "type": "Int32", "units": "Hz"}, {"category": "Standard", "default": 1, "group": "UAVCAN Motor Parameters", "longDesc": "Motor spin direction as detected during initial enumeration. Use 0 or 1 to reverse direction.", "max": 1, "min": 0, "name": "ctl_dir", "shortDesc": "Reverse direction", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "UAVCAN Motor Parameters", "longDesc": "Speed (RPM) controller gain. Determines controller\n aggressiveness; units are amp-seconds per radian. Systems with\n higher rotational inertia (large props) will need gain increased;\n systems with low rotational inertia (small props) may need gain\n decreased. Higher values result in faster response, but may result\n in oscillation and excessive overshoot. Lower values result in a\n slower, smoother response.", "max": 1.0, "min": 0.0, "name": "ctl_gain", "shortDesc": "Speed (RPM) controller gain", "type": "Float", "units": "C/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 3.5, "group": "UAVCAN Motor Parameters", "longDesc": "Idle speed (e Hz)", "max": 100.0, "min": 0.0, "name": "ctl_hz_idle", "shortDesc": "Idle speed (e Hz)", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 25, "group": "UAVCAN Motor Parameters", "longDesc": "Spin-up rate (e Hz/s)", "max": 1000, "min": 5, "name": "ctl_start_rate", "shortDesc": "Spin-up rate (e Hz/s)", "type": "Int32", "units": "1/s^2"}, {"category": "Standard", "default": 0, "group": "UAVCAN Motor Parameters", "longDesc": "Index of this ESC in throttle command messages.", "max": 15, "min": 0, "name": "esc_index", "shortDesc": "Index of this ESC in throttle command messages.", "type": "Int32"}, {"category": "Standard", "default": 20034, "group": "UAVCAN Motor Parameters", "longDesc": "Extended status ID", "max": 1000000, "min": 1, "name": "id_ext_status", "shortDesc": "Extended status ID", "type": "Int32"}, {"category": "Standard", "default": 50000, "group": "UAVCAN Motor Parameters", "longDesc": "Extended status interval (\u00b5s)", "max": 1000000, "min": 0, "name": "int_ext_status", "shortDesc": "Extended status interval (\u00b5s)", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 50000, "group": "UAVCAN Motor Parameters", "longDesc": "ESC status interval (\u00b5s)", "max": 1000000, "name": "int_status", "shortDesc": "ESC status interval (\u00b5s)", "type": "Int32", "units": "us"}, {"category": "Standard", "decimalPlaces": 3, "default": 12.0, "group": "UAVCAN Motor Parameters", "longDesc": "Motor current limit in amps. This determines the maximum\n current controller setpoint, as well as the maximum allowable\n current setpoint slew rate. This value should generally be set to\n the continuous current rating listed in the motor\u2019s specification\n sheet, or set equal to the motor\u2019s specified continuous power\n divided by the motor voltage limit.", "max": 80.0, "min": 1.0, "name": "mot_i_max", "shortDesc": "Motor current limit in amps", "type": "Float", "units": "A"}, {"category": "Standard", "default": 2300, "group": "UAVCAN Motor Parameters", "longDesc": "Motor Kv in RPM per volt. This can be taken from the motor\u2019s\n specification sheet; accuracy will help control performance but\n some deviation from the specified value is acceptable.", "max": 4000, "min": 0, "name": "mot_kv", "shortDesc": "Motor Kv in RPM per volt", "type": "Int32", "units": "rpm/V"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "UAVCAN Motor Parameters", "longDesc": "READ ONLY: Motor inductance in henries. This is measured on start-up.", "name": "mot_ls", "shortDesc": "READ ONLY: Motor inductance in henries.", "type": "Float", "units": "H"}, {"category": "Standard", "default": 14, "group": "UAVCAN Motor Parameters", "longDesc": "Number of motor poles. Used to convert mechanical speeds to\n electrical speeds. This number should be taken from the motor\u2019s\n specification sheet.", "max": 40, "min": 2, "name": "mot_num_poles", "shortDesc": "Number of motor poles.", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "UAVCAN Motor Parameters", "longDesc": "READ ONLY: Motor resistance in ohms. This is measured on start-up. When\n tuning a new motor, check that this value is approximately equal\n to the value shown in the motor\u2019s specification sheet.", "name": "mot_rs", "shortDesc": "READ ONLY: Motor resistance in ohms", "type": "Float", "units": "Ohm"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "UAVCAN Motor Parameters", "longDesc": "Acceleration limit (V)", "max": 1.0, "min": 0.01, "name": "mot_v_accel", "shortDesc": "Acceleration limit (V)", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 3, "default": 14.8, "group": "UAVCAN Motor Parameters", "longDesc": "Motor voltage limit in volts. The current controller\u2019s\n commanded voltage will never exceed this value. Note that this may\n safely be above the nominal voltage of the motor; to determine the\n actual motor voltage limit, divide the motor\u2019s rated power by the\n motor current limit.", "min": 0.0, "name": "mot_v_max", "shortDesc": "Motor voltage limit in volts", "type": "Float", "units": "V"}, {"category": "Standard", "default": 2, "group": "UAVCAN GNSS", "longDesc": "Dynamic model used in the GNSS positioning engine. 0 \u2013\n Automotive, 1 \u2013 Sea, 2 \u2013 Airborne.\n ", "max": 2, "min": 0, "name": "gnss.dyn_model", "shortDesc": "GNSS dynamic model", "type": "Int32", "values": [{"description": "Automotive", "value": 0}, {"description": "Sea", "value": 1}, {"description": "Airborne", "value": 2}]}, {"category": "Standard", "default": 1, "group": "UAVCAN GNSS", "longDesc": "Broadcast the old (deprecated) GNSS fix message\n uavcan.equipment.gnss.Fix alongside the new alternative\n uavcan.equipment.gnss.Fix2. It is recommended to\n disable this feature to reduce the CAN bus traffic.\n ", "max": 1, "min": 0, "name": "gnss.old_fix_msg", "shortDesc": "Broadcast old GNSS fix message", "type": "Int32", "values": [{"description": "Fix2", "value": 0}, {"description": "Fix and Fix2", "value": 1}]}, {"category": "Standard", "default": 0, "group": "UAVCAN GNSS", "longDesc": "Set the device health to Warning if the dimensionality of\n the GNSS solution is less than this value. 3 for the full (3D)\n solution, 2 for planar (2D) solution, 1 for time-only solution,\n 0 disables the feature.\n ", "max": 3, "min": 0, "name": "gnss.warn_dimens", "shortDesc": "device health warning", "type": "Int32", "values": [{"description": "disables the feature", "value": 0}, {"description": "time-only solution", "value": 1}, {"description": "planar (2D) solution", "value": 2}, {"description": "full (3D) solution", "value": 3}]}, {"category": "Standard", "default": 0, "group": "UAVCAN GNSS", "longDesc": "Set the device health to Warning if the number of satellites\n used in the GNSS solution is below this threshold. Zero\n disables the feature\n ", "name": "gnss.warn_sats", "shortDesc": "", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "UAVCAN GNSS", "longDesc": "Set the device health to Warning if the number of satellites\n used in the GNSS solution is below this threshold. Zero\n disables the feature\n ", "max": 1000000, "min": 0, "name": "uavcan.pubp-pres", "shortDesc": "", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets first 4 characters of a total of 8. Valid characters are A-Z, 0-9, \" \". Example \"PX4 \" -> 1347957792\nFor CALLSIGN shorter than 8 characters use the null terminator at the end '\\0'.", "name": "ADSB_CALLSIGN_1", "rebootRequired": true, "shortDesc": "First 4 characters of CALLSIGN", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets second 4 characters of a total of 8. Valid characters are A-Z, 0-9, \" \" only. Example \"TEST\" -> 1413829460\nFor CALLSIGN shorter than 8 characters use the null terminator at the end '\\0'.", "name": "ADSB_CALLSIGN_2", "rebootRequired": true, "shortDesc": "Second 4 characters of CALLSIGN", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets the vehicle emergency state", "max": 6, "min": 0, "name": "ADSB_EMERGC", "rebootRequired": true, "shortDesc": "ADSB-Out Emergency State", "type": "Int32", "values": [{"description": "NoEmergency", "value": 0}, {"description": "General", "value": 1}, {"description": "Medical", "value": 2}, {"description": "LowFuel", "value": 3}, {"description": "NoCommunications", "value": 4}, {"description": "Interference", "value": 5}, {"description": "Downed", "value": 6}]}, {"category": "Standard", "default": 14, "group": "ADSB", "longDesc": "Configure the emitter type of the vehicle.", "max": 15, "min": 0, "name": "ADSB_EMIT_TYPE", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Emitter Type", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "Light", "value": 1}, {"description": "Small", "value": 2}, {"description": "Large", "value": 3}, {"description": "HighVortex", "value": 4}, {"description": "Heavy", "value": 5}, {"description": "Performance", "value": 6}, {"description": "Rotorcraft", "value": 7}, {"description": "RESERVED", "value": 8}, {"description": "Glider", "value": 9}, {"description": "LightAir", "value": 10}, {"description": "Parachute", "value": 11}, {"description": "UltraLight", "value": 12}, {"description": "RESERVED", "value": 13}, {"description": "UAV", "value": 14}, {"description": "Space", "value": 15}, {"description": "RESERVED", "value": 16}, {"description": "EmergencySurf", "value": 17}, {"description": "ServiceSurf", "value": 18}, {"description": "PointObstacle", "value": 19}]}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets GPS lataral offset encoding", "max": 7, "min": 0, "name": "ADSB_GPS_OFF_LAT", "rebootRequired": true, "shortDesc": "ADSB-Out GPS Offset lat", "type": "Int32", "values": [{"description": "NoData", "value": 0}, {"description": "LatLeft2M", "value": 1}, {"description": "LatLeft4M", "value": 2}, {"description": "LatLeft6M", "value": 3}, {"description": "LatRight0M", "value": 4}, {"description": "LatRight2M", "value": 5}, {"description": "LatRight4M", "value": 6}, {"description": "LatRight6M", "value": 7}]}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets GPS longitudinal offset encoding", "max": 1, "min": 0, "name": "ADSB_GPS_OFF_LON", "rebootRequired": true, "shortDesc": "ADSB-Out GPS Offset lon", "type": "Int32", "values": [{"description": "NoData", "value": 0}, {"description": "AppliedBySensor", "value": 1}]}, {"category": "Standard", "default": 1194684, "group": "ADSB", "longDesc": "Defines the ICAO ID of the vehicle", "max": 16777215, "min": -1, "name": "ADSB_ICAO_ID", "rebootRequired": true, "shortDesc": "ADSB-Out ICAO configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "This vehicle is always tracked. Use 0 to disable.", "max": 16777215, "min": 0, "name": "ADSB_ICAO_SPECL", "rebootRequired": true, "shortDesc": "ADSB-In Special ICAO configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Enable Identification of Position feature", "name": "ADSB_IDENT", "rebootRequired": true, "shortDesc": "ADSB-Out Ident Configuration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "ADSB", "longDesc": "Report the length and width of the vehicle in meters. In most cases, use '1' for the smallest vehicle size.", "max": 15, "min": 0, "name": "ADSB_LEN_WIDTH", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Size Configuration", "type": "Int32", "values": [{"description": "SizeUnknown", "value": 0}, {"description": "Len15_Wid23", "value": 1}, {"description": "Len25_Wid28", "value": 2}, {"description": "Len25_Wid34", "value": 3}, {"description": "Len35_Wid33", "value": 4}, {"description": "Len35_Wid38", "value": 5}, {"description": "Len45_Wid39", "value": 6}, {"description": "Len45_Wid45", "value": 7}, {"description": "Len55_Wid45", "value": 8}, {"description": "Len55_Wid52", "value": 9}, {"description": "Len65_Wid59", "value": 10}, {"description": "Len65_Wid67", "value": 11}, {"description": "Len75_Wid72", "value": 12}, {"description": "Len75_Wid80", "value": 13}, {"description": "Len85_Wid80", "value": 14}, {"description": "Len85_Wid90", "value": 15}]}, {"category": "Standard", "default": 25, "group": "ADSB", "longDesc": "Change number of targets to track", "max": 50, "min": 0, "name": "ADSB_LIST_MAX", "rebootRequired": true, "shortDesc": "ADSB-In Vehicle List Size", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Informs ADSB vehicles of this vehicle's max speed capability", "max": 6, "min": 0, "name": "ADSB_MAX_SPEED", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Max Speed", "type": "Int32", "values": [{"description": "UnknownMaxSpeed", "value": 0}, {"description": "75Kts", "value": 1}, {"description": "150Kts", "value": 2}, {"description": "300Kts", "value": 3}, {"description": "600Kts", "value": 4}, {"description": "1200Kts", "value": 5}, {"description": "Over1200Kts", "value": 6}]}, {"category": "Standard", "default": 1200, "group": "ADSB", "longDesc": "This parameter defines the squawk code. Value should be between 0000 and 7777.", "max": 7777, "min": 0, "name": "ADSB_SQUAWK", "rebootRequired": true, "shortDesc": "ADSB-Out squawk code configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 1.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC1", "shortDesc": "SIM Channel 1 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 10.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC10", "shortDesc": "SIM Channel 10 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 11.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC11", "shortDesc": "SIM Channel 11 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 12.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC12", "shortDesc": "SIM Channel 12 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 13.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC13", "shortDesc": "SIM Channel 13 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 14.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC14", "shortDesc": "SIM Channel 14 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 15.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC15", "shortDesc": "SIM Channel 15 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 16.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC16", "shortDesc": "SIM Channel 16 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 2.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC2", "shortDesc": "SIM Channel 2 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 3.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC3", "shortDesc": "SIM Channel 3 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 4.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC4", "shortDesc": "SIM Channel 4 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 5.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC5", "shortDesc": "SIM Channel 5 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 6.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC6", "shortDesc": "SIM Channel 6 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 7.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC7", "shortDesc": "SIM Channel 7 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 8.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC8", "shortDesc": "SIM Channel 8 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 9.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC9", "shortDesc": "SIM Channel 9 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"bitmask": [{"description": "SIM Channel 1", "index": 0}, {"description": "SIM Channel 2", "index": 1}, {"description": "SIM Channel 3", "index": 2}, {"description": "SIM Channel 4", "index": 3}, {"description": "SIM Channel 5", "index": 4}, {"description": "SIM Channel 6", "index": 5}, {"description": "SIM Channel 7", "index": 6}, {"description": "SIM Channel 8", "index": 7}, {"description": "SIM Channel 9", "index": 8}, {"description": "SIM Channel 10", "index": 9}, {"description": "SIM Channel 11", "index": 10}, {"description": "SIM Channel 12", "index": 11}, {"description": "SIM Channel 13", "index": 12}, {"description": "SIM Channel 14", "index": 13}, {"description": "SIM Channel 15", "index": 14}, {"description": "SIM Channel 16", "index": 15}], "category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Allows to reverse the output range for each channel.\nNote: this is only useful for servos.", "max": 65535, "min": 0, "name": "PWM_MAIN_REV", "shortDesc": "Reverse Output Range for SIM", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Airspeed Validator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 5, "min": 1, "name": "ASPD_BETA_GATE", "shortDesc": "Gate size for sideslip angle fusion", "type": "Int32", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Airspeed Validator", "longDesc": "Sideslip measurement noise of the internal wind estimator(s) of the airspeed selector.", "max": 1.0, "min": 0.0, "name": "ASPD_BETA_NOISE", "shortDesc": "Wind estimator sideslip measurement noise", "type": "Float", "units": "rad"}, {"bitmask": [{"description": "Only data missing check (triggers if more than 1s no data)", "index": 0}, {"description": "Data stuck (triggers if data is exactly constant for 2s in FW mode)", "index": 1}, {"description": "Innovation check (see ASPD_FS_INNOV)", "index": 2}, {"description": "Load factor check (triggers if measurement is below stall speed)", "index": 3}, {"description": "First principle check (airspeed change vs. throttle and pitch)", "index": 4}], "category": "Standard", "default": 7, "group": "Airspeed Validator", "longDesc": "Controls which checks are run to check airspeed data for validity. Only applied if ASPD_PRIMARY > 0.", "max": 31, "min": 0, "name": "ASPD_DO_CHECKS", "shortDesc": "Enable checks on airspeed sensors", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Airspeed Validator", "name": "ASPD_FALLBACK", "shortDesc": "Fallback options", "type": "Int32", "values": [{"description": "Fallback only to other airspeed sensors", "value": 0}, {"description": "Fallback to groundspeed-minus-windspeed airspeed estimation", "value": 1}, {"description": "Fallback to thrust based airspeed estimation", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Airspeed Validator", "longDesc": "Window for comparing airspeed change to throttle and pitch change.\nTriggers when the airspeed change within this window is negative while throttle increases\nand the vehicle pitches down.\nIs meant to catch degrading airspeed blockages as can happen when flying through icing conditions.\nRelies on FW_THR_TRIM being set accurately.", "min": 0.0, "name": "ASPD_FP_T_WINDOW", "shortDesc": "First principle airspeed check time window", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Airspeed Validator", "longDesc": "This specifies the minimum airspeed innovation required to trigger a failsafe. Larger values make the check less sensitive,\nsmaller values make it more sensitive. Large innovations indicate an inconsistency between predicted (groundspeed - windspeeed)\nand measured airspeed.\nThe time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the ASPD_FS_INTEG parameter.", "max": 10.0, "min": 0.5, "name": "ASPD_FS_INNOV", "shortDesc": "Airspeed failure innovation threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Airspeed Validator", "longDesc": "This sets the time integral of airspeed innovation exceedance above ASPD_FS_INNOV required to trigger a failsafe.\nLarger values make the check less sensitive, smaller positive values make it more sensitive.", "max": 50.0, "min": 0.0, "name": "ASPD_FS_INTEG", "shortDesc": "Airspeed failure innovation integral threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Airspeed Validator", "longDesc": "Delay before switching back to using airspeed sensor if checks indicate sensor is good.\nSet to a negative value to disable the re-enabling in flight.", "min": -1.0, "name": "ASPD_FS_T_START", "shortDesc": "Airspeed failsafe start delay", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Airspeed Validator", "longDesc": "Delay before stopping use of airspeed sensor if checks indicate sensor is bad.", "min": 0.0, "name": "ASPD_FS_T_STOP", "shortDesc": "Airspeed failsafe stop delay", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Airspeed Validator", "name": "ASPD_PRIMARY", "rebootRequired": true, "shortDesc": "Index or primary airspeed measurement source", "type": "Int32", "values": [{"description": "Groundspeed minus windspeed", "value": 0}, {"description": "First airspeed sensor", "value": 1}, {"description": "Second airspeed sensor", "value": 2}, {"description": "Third airspeed sensor", "value": 3}, {"description": "Thrust based airspeed", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the first airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_1", "rebootRequired": true, "shortDesc": "Scale of airspeed sensor 1", "type": "Float", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the second airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_2", "rebootRequired": true, "shortDesc": "Scale of airspeed sensor 2", "type": "Float", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the third airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_3", "rebootRequired": true, "shortDesc": "Scale of airspeed sensor 3", "type": "Float", "volatile": true}, {"category": "Standard", "default": 2, "group": "Airspeed Validator", "name": "ASPD_SCALE_APPLY", "shortDesc": "Controls when to apply the new estimated airspeed scale(s)", "type": "Int32", "values": [{"description": "Do not automatically apply the estimated scale", "value": 0}, {"description": "Apply the estimated scale after disarm", "value": 1}, {"description": "Apply the estimated scale in air", "value": 2}]}, {"category": "Standard", "decimalPlaces": 5, "default": 0.0001, "group": "Airspeed Validator", "longDesc": "Airspeed scale process noise of the internal wind estimator(s) of the airspeed selector.\nWhen unaided, the scale uncertainty (1-sigma, unitless) increases by this amount every second.", "max": 0.1, "min": 0.0, "name": "ASPD_SCALE_NSD", "shortDesc": "Wind estimator true airspeed scale process noise spectral density", "type": "Float", "units": "1/s/sqrt(Hz)"}, {"category": "Standard", "default": 4, "group": "Airspeed Validator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 5, "min": 1, "name": "ASPD_TAS_GATE", "shortDesc": "Gate size for true airspeed fusion", "type": "Int32", "units": "SD"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.4, "group": "Airspeed Validator", "longDesc": "True airspeed measurement noise of the internal wind estimator(s) of the airspeed selector.", "max": 4.0, "min": 0.0, "name": "ASPD_TAS_NOISE", "shortDesc": "Wind estimator true airspeed measurement noise", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.55, "group": "Airspeed Validator", "longDesc": "The synthetic airspeed estimate (from groundspeed and heading) will be declared valid\nas soon and as long the horizontal wind uncertainty is below this value.", "max": 5.0, "min": 0.001, "name": "ASPD_WERR_THR", "shortDesc": "Horizontal wind uncertainty threshold for synthetic airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Airspeed Validator", "longDesc": "Wind process noise of the internal wind estimator(s) of the airspeed selector.\nWhen unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second.", "max": 1.0, "min": 0.0, "name": "ASPD_WIND_NSD", "shortDesc": "Wind estimator wind process noise spectral density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "name": "ATT_ACC_COMP", "shortDesc": "Acceleration compensation based on GPS velocity", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Attitude Q estimator", "max": 2.0, "min": 0.0, "name": "ATT_BIAS_MAX", "shortDesc": "Gyro bias limit", "type": "Float", "units": "rad/s"}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "longDesc": "Enable standalone quaternion based attitude estimator.", "name": "ATT_EN", "shortDesc": "standalone attitude estimator enable (unsupported)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "longDesc": "Set to 1 to use heading estimate from vision.\nSet to 2 to use heading from motion capture.", "max": 2, "min": 0, "name": "ATT_EXT_HDG_M", "shortDesc": "External heading usage mode (from Motion capture/Vision)", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Vision", "value": 1}, {"description": "Motion Capture", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Attitude Q estimator", "longDesc": "This parameter is not used in normal operation,\nas the declination is looked up based on the\nGPS coordinates of the vehicle.", "name": "ATT_MAG_DECL", "shortDesc": "Magnetic declination, in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 1, "group": "Attitude Q estimator", "name": "ATT_MAG_DECL_A", "shortDesc": "Automatic GPS based declination compensation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_ACC", "shortDesc": "Complimentary filter accelerometer weight", "type": "Float"}, {"category": "Standard", "default": 0.1, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_EXT_HDG", "shortDesc": "Complimentary filter external heading weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_GYRO_BIAS", "shortDesc": "Complimentary filter gyroscope bias weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Attitude Q estimator", "longDesc": "Set to 0 to avoid using the magnetometer.", "max": 1.0, "min": 0.0, "name": "ATT_W_MAG", "shortDesc": "Complimentary filter magnetometer weight", "type": "Float"}, {"category": "Standard", "default": 2, "group": "Autotune", "longDesc": "After the auto-tuning sequence is completed,\na new set of gains is available and can be applied\nimmediately or after landing.", "name": "FW_AT_APPLY", "shortDesc": "Controls when to apply the new gains", "type": "Int32", "values": [{"description": "Do not apply the new gains (logging only)", "value": 0}, {"description": "Apply the new gains after disarm", "value": 1}, {"description": "Apply the new gains in air", "value": 2}]}, {"bitmask": [{"description": "roll", "index": 0}, {"description": "pitch", "index": 1}, {"description": "yaw", "index": 2}], "category": "Standard", "default": 3, "group": "Autotune", "longDesc": "Defines which axes will be tuned during the auto-tuning sequence\nSet bits in the following positions to enable:\n0 : Roll\n1 : Pitch\n2 : Yaw", "max": 7, "min": 1, "name": "FW_AT_AXES", "shortDesc": "Tuning axes selection", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "Defines which RC_MAP_AUXn parameter maps the RC channel used to enable/disable auto tuning.", "max": 6, "min": 0, "name": "FW_AT_MAN_AUX", "shortDesc": "Enable/disable auto tuning using an RC AUX input", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Aux1", "value": 1}, {"description": "Aux2", "value": 2}, {"description": "Aux3", "value": 3}, {"description": "Aux4", "value": 4}, {"description": "Aux5", "value": 5}, {"description": "Aux6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "WARNING: this will inject steps to the rate controller\nand can be dangerous. Only activate if you know what you\nare doing, and in a safe environment.\nAny motion of the remote stick will abort the signal\ninjection and reset this parameter\nBest is to perform the identification in position or\nhold mode.\nIncrease the amplitude of the injected signal using\nFW_AT_SYSID_AMP for more signal/noise ratio", "name": "FW_AT_START", "shortDesc": "Start the autotuning sequence", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Autotune", "longDesc": "This parameter scales the signal sent to the\nrate controller during system identification.", "max": 6.0, "min": 0.1, "name": "FW_AT_SYSID_AMP", "shortDesc": "Amplitude of the injected signal", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Autotune", "longDesc": "Can be set lower or higher than the end frequency", "max": 30.0, "min": 0.1, "name": "FW_AT_SYSID_F0", "shortDesc": "Start frequency of the injected signal", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Autotune", "longDesc": "Can be set lower or higher than the start frequency", "max": 30.0, "min": 0.1, "name": "FW_AT_SYSID_F1", "shortDesc": "End frequency of the injected signal", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 0, "default": 10.0, "group": "Autotune", "longDesc": "Duration of the input signal sent on each axis during system identification", "max": 120.0, "min": 5.0, "name": "FW_AT_SYSID_TIME", "shortDesc": "Maneuver time for each axis", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "Type of signal used during system identification to excite the system.", "name": "FW_AT_SYSID_TYPE", "shortDesc": "Input signal type", "type": "Int32", "values": [{"description": "Step", "value": 0}, {"description": "Linear sine sweep", "value": 1}, {"description": "Logarithmic sine sweep", "value": 2}]}, {"category": "Standard", "default": 1, "group": "Autotune", "longDesc": "After the auto-tuning sequence is completed,\na new set of gains is available and can be applied\nimmediately or after landing.\nWARNING Applying the gains in air is dangerous as there is no\nguarantee that those new gains will be able to stabilize\nthe drone properly.", "name": "MC_AT_APPLY", "shortDesc": "Controls when to apply the new gains", "type": "Int32", "values": [{"description": "Do not apply the new gains (logging only)", "value": 0}, {"description": "Apply the new gains after disarm", "value": 1}, {"description": "WARNING Apply the new gains in air", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Autotune", "name": "MC_AT_EN", "shortDesc": "Multicopter autotune module enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.14, "group": "Autotune", "max": 0.5, "min": 0.01, "name": "MC_AT_RISE_TIME", "shortDesc": "Desired angular rate closed-loop rise time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "WARNING: this will inject steps to the rate controller\nand can be dangerous. Only activate if you know what you\nare doing, and in a safe environment.\nAny motion of the remote stick will abort the signal\ninjection and reset this parameter\nBest is to perform the identification in position or\nhold mode.\nIncrease the amplitude of the injected signal using\nMC_AT_SYSID_AMP for more signal/noise ratio", "name": "MC_AT_START", "shortDesc": "Start the autotuning sequence", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.7, "group": "Autotune", "max": 6.0, "min": 0.1, "name": "MC_AT_SYSID_AMP", "shortDesc": "Amplitude of the injected signal", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 1 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT1_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 1 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT1_N_CELLS", "shortDesc": "Number of cells for battery 1", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT1_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 1", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module'\nmeans that measurements are expected to come from a power module. If the value is set to\n'External' then the system expects to receive mavlink battery status messages.\nIf the value is set to 'ESCs', the battery information are taken from the esc_status message.\nThis requires the ESC to provide both voltage as well as current.", "name": "BAT1_SOURCE", "rebootRequired": true, "shortDesc": "Battery 1 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full.\nFor a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT1_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty.\nThe voltage should be chosen above the steep dropoff at 3.5V. A typical\nlithium battery can only be discharged under high load down to 10% before\nit drops off to a voltage level damaging the cells.", "name": "BAT1_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 2 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT2_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 2 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT2_N_CELLS", "shortDesc": "Number of cells for battery 2", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT2_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 2", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": -1, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module'\nmeans that measurements are expected to come from a power module. If the value is set to\n'External' then the system expects to receive mavlink battery status messages.\nIf the value is set to 'ESCs', the battery information are taken from the esc_status message.\nThis requires the ESC to provide both voltage as well as current.", "name": "BAT2_SOURCE", "rebootRequired": true, "shortDesc": "Battery 2 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full.\nFor a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT2_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty.\nThe voltage should be chosen above the steep dropoff at 3.5V. A typical\nlithium battery can only be discharged under high load down to 10% before\nit drops off to a voltage level damaging the cells.", "name": "BAT2_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 3 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT3_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 3 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT3_N_CELLS", "shortDesc": "Number of cells for battery 3", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT3_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 3", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": -1, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module'\nmeans that measurements are expected to come from a power module. If the value is set to\n'External' then the system expects to receive mavlink battery status messages.\nIf the value is set to 'ESCs', the battery information are taken from the esc_status message.\nThis requires the ESC to provide both voltage as well as current.", "name": "BAT3_SOURCE", "rebootRequired": true, "shortDesc": "Battery 3 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full.\nFor a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT3_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty.\nThe voltage should be chosen above the steep dropoff at 3.5V. A typical\nlithium battery can only be discharged under high load down to 10% before\nit drops off to a voltage level damaging the cells.", "name": "BAT3_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 15.0, "group": "Battery Calibration", "increment": 0.1, "longDesc": "This value is used to initialize the in-flight average current estimation,\nwhich in turn is used for estimating remaining flight time and RTL triggering.", "max": 500.0, "min": 0.0, "name": "BAT_AVRG_CURRENT", "shortDesc": "Expected battery current in flight", "type": "Float", "units": "A"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.07, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as critically low.\nThis has to be lower than the low threshold. This threshold commonly\nwill trigger RTL.", "max": 0.5, "min": 0.05, "name": "BAT_CRIT_THR", "shortDesc": "Critical threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as dangerously low.\nThis has to be lower than the critical threshold. This threshold commonly\nwill trigger landing.", "max": 0.5, "min": 0.03, "name": "BAT_EMERGEN_THR", "shortDesc": "Emergency threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as low.\nThis has to be higher than the critical threshold.", "max": 0.5, "min": 0.12, "name": "BAT_LOW_THR", "shortDesc": "Low threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Camera trigger", "longDesc": "This parameter sets the time the trigger needs to pulled high or low.", "max": 3000.0, "min": 0.1, "name": "TRIG_ACT_TIME", "rebootRequired": true, "shortDesc": "Camera trigger activation time", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "Camera trigger", "increment": 1.0, "longDesc": "Sets the distance at which to trigger the camera.", "min": 0.0, "name": "TRIG_DISTANCE", "rebootRequired": true, "shortDesc": "Camera trigger distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 4, "group": "Camera trigger", "longDesc": "Selects the trigger interface", "name": "TRIG_INTERFACE", "rebootRequired": true, "shortDesc": "Camera trigger Interface", "type": "Int32", "values": [{"description": "GPIO", "value": 1}, {"description": "Seagull MAP2 (over PWM)", "value": 2}, {"description": "MAVLink (Camera Protocol v1)", "value": 3}, {"description": "Generic PWM (IR trigger, servo)", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Camera trigger", "longDesc": "This parameter sets the time between two consecutive trigger events", "max": 10000.0, "min": 4.0, "name": "TRIG_INTERVAL", "rebootRequired": true, "shortDesc": "Camera trigger interval", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Camera trigger", "longDesc": "This parameter sets the minimum time between two consecutive trigger events\nthe specific camera setup is supporting.", "max": 10000.0, "min": 1.0, "name": "TRIG_MIN_INTERVA", "rebootRequired": true, "shortDesc": "Minimum camera trigger interval", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "Camera trigger", "max": 4, "min": 0, "name": "TRIG_MODE", "rebootRequired": true, "shortDesc": "Camera trigger mode", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Time based, on command", "value": 1}, {"description": "Time based, always on", "value": 2}, {"description": "Distance based, always on", "value": 3}, {"description": "Distance based, on command (Survey mode)", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Camera trigger", "longDesc": "This parameter sets the polarity of the trigger (0 = active low, 1 = active high )", "max": 1, "min": 0, "name": "TRIG_POLARITY", "rebootRequired": true, "shortDesc": "Camera trigger polarity", "type": "Int32", "values": [{"description": "Active low", "value": 0}, {"description": "Active high", "value": 1}]}, {"category": "Standard", "default": 1500, "group": "Camera trigger", "max": 2000, "min": 1000, "name": "TRIG_PWM_NEUTRAL", "rebootRequired": true, "shortDesc": "PWM neutral output on trigger pin", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 1900, "group": "Camera trigger", "max": 2000, "min": 1000, "name": "TRIG_PWM_SHOOT", "rebootRequired": true, "shortDesc": "PWM output to trigger shot", "type": "Int32", "units": "us"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 782097 will disable the buzzer audio notification.\nSetting this parameter to 782090 will disable the startup tune, while keeping\nall others enabled.", "max": 782097, "min": 0, "name": "CBRK_BUZZER", "rebootRequired": true, "shortDesc": "Circuit breaker for disabling buzzer", "type": "Int32"}, {"category": "Developer", "default": 121212, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 121212 will disable the flight termination action if triggered\nby the FailureDetector logic or if FMU is lost.\nThis circuit breaker does not affect the RC loss, data link loss, geofence,\nand takeoff failure detection safety logic.", "max": 121212, "min": 0, "name": "CBRK_FLIGHTTERM", "rebootRequired": true, "shortDesc": "Circuit breaker for flight termination", "type": "Int32"}, {"category": "Developer", "default": 22027, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 22027 will disable IO safety.\nWARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 22027, "min": 0, "name": "CBRK_IO_SAFETY", "shortDesc": "Circuit breaker for IO safety", "type": "Int32"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 894281 will disable the power valid\nchecks in the commander.\nWARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 894281, "min": 0, "name": "CBRK_SUPPLY_CHK", "shortDesc": "Circuit breaker for power supply check", "type": "Int32"}, {"category": "Developer", "default": 197848, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 197848 will disable the USB connected\nchecks in the commander, setting it to 0 keeps them enabled (recommended).\nWe are generally recommending to not fly with the USB link\nconnected and production vehicles should set this parameter to\nzero to prevent users from flying USB powered. However, for R&D purposes\nit has proven over the years to work just fine.", "max": 197848, "min": 0, "name": "CBRK_USB_CHK", "shortDesc": "Circuit breaker for USB link check", "type": "Int32"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 159753 will enable arming in fixed-wing\nmode for VTOLs.\nWARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 159753, "min": 0, "name": "CBRK_VTOLARMING", "shortDesc": "Circuit breaker for arming in fixed-wing mode check", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Note: actuator failure needs to be enabled and configured via FD_ACT_*\nparameters.", "max": 3, "min": 0, "name": "COM_ACT_FAIL_ACT", "shortDesc": "Set the actuator failure failsafe mode", "type": "Int32", "values": [{"description": "Warning only", "value": 0}, {"description": "Hold mode", "value": 1}, {"description": "Land mode", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Terminate", "value": 4}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Set 0 to prevent accidental use of the vehicle e.g. for safety or maintenance reasons.", "name": "COM_ARMABLE", "shortDesc": "Flag to allow arming", "type": "Int32", "values": [{"description": "Disallow arming", "value": 0}, {"description": "Allow arming", "value": 1}]}, {"category": "Standard", "default": 10, "group": "Commander", "longDesc": "Used if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_ID", "shortDesc": "Arm authorizer system id", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Methods:\n- one arm: request authorization and arm when authorization is received\n- two step arm: 1st arm command request an authorization and\n2nd arm command arm the drone if authorized\nUsed if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_MET", "shortDesc": "Arm authorization method", "type": "Int32", "values": [{"description": "one arm", "value": 0}, {"description": "two step arm", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "By default off. The default allows to arm the vehicle without a arm authorization.", "name": "COM_ARM_AUTH_REQ", "shortDesc": "Require arm authorization to arm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "increment": 0.1, "longDesc": "Timeout for authorizer answer.\nUsed if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_TO", "shortDesc": "Arm authorization timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Commander", "increment": 0.01, "longDesc": "Threshold for battery percentage below arming is prohibited.\nA negative value means BAT_CRIT_THR is the threshold.", "max": 0.9, "min": -1.0, "name": "COM_ARM_BAT_MIN", "shortDesc": "Minimum battery level for arming", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "If this parameter is set, the system will check ESC's online status and failures.\nThis param is specific for ESCs reporting status. It shall be used only if ESCs support telemetry.", "name": "COM_ARM_CHK_ESCS", "shortDesc": "Enable checks on ESCs that report telemetry", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This check detects if there are hardfault files present on the\nSD card. If so, and the parameter is enabled, arming is prevented.", "name": "COM_ARM_HFLT_CHK", "shortDesc": "Enable FMU SD card hardfault detection check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "Commander", "increment": 0.05, "max": 1.0, "min": 0.1, "name": "COM_ARM_IMU_ACC", "shortDesc": "Maximum accelerometer inconsistency between IMU units that will allow arming", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Commander", "increment": 0.01, "max": 0.3, "min": 0.02, "name": "COM_ARM_IMU_GYR", "shortDesc": "Maximum rate gyro inconsistency between IMU units that will allow arming", "type": "Float", "units": "rad/s"}, {"category": "Standard", "default": 60, "group": "Commander", "longDesc": "Set -1 to disable the check.", "max": 180, "min": 3, "name": "COM_ARM_MAG_ANG", "shortDesc": "Maximum magnetic field inconsistency between units that will allow arming", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Commander", "longDesc": "Check if the estimator detects a strong magnetic\ndisturbance (check enabled by EKF2_MAG_CHECK)", "name": "COM_ARM_MAG_STR", "shortDesc": "Enable mag strength preflight check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Deny arming", "value": 1}, {"description": "Warning only", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The default allows to arm the vehicle without a valid mission.", "name": "COM_ARM_MIS_REQ", "shortDesc": "Require valid mission to arm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "This check detects if the Open Drone ID system is missing.\nDepending on the value of the parameter, the check can be\ndisabled, warn only or deny arming.", "name": "COM_ARM_ODID", "shortDesc": "Enable Drone ID system detection and health check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Enforce Open Drone ID system presence", "value": 2}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This check detects if the FMU SD card is missing.\nDepending on the value of the parameter, the check can be\ndisabled, warn only or deny arming.", "name": "COM_ARM_SDCARD", "shortDesc": "Enable FMU SD card detection check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Enforce SD card presence", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "0: Arming/disarming triggers on switch transition.\n1: Arming/disarming triggers when holding the momentary button down\nfor COM_RC_ARM_HYST like the stick gesture.", "name": "COM_ARM_SWISBTN", "shortDesc": "Arm switch is a momentary button", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Measures taken when a check defined by EKF2_GPS_CHECK is failing.", "name": "COM_ARM_WO_GPS", "shortDesc": "GPS preflight check", "type": "Int32", "values": [{"description": "Deny arming", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Disabled", "value": 2}]}, {"category": "Standard", "default": 95.0, "group": "Commander", "increment": 1.0, "longDesc": "The check fails if the CPU load is above this threshold for 2s.\nA negative value disables the check.", "max": 100.0, "min": -1.0, "name": "COM_CPU_MAX", "shortDesc": "Maximum allowed CPU load to still arm", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Commander", "increment": 0.1, "longDesc": "A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be\nautomatically disarmed in case a landing situation has been detected during this period.\nA zero or negative value means that automatic disarming triggered by landing detection is disabled.", "name": "COM_DISARM_LAND", "shortDesc": "Time-out for auto disarm after landing", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "0: Disallow disarming when not landed\n1: Allow disarming in multicopter flight in modes where\nthe thrust is directly controlled by thr throttle stick\ne.g. Stabilized, Acro", "name": "COM_DISARM_MAN", "shortDesc": "Allow disarming via switch/stick/button on multicopters in manual thrust modes", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Commander", "increment": 0.1, "longDesc": "A non-zero, positive value specifies the time in seconds, within which the\nvehicle is expected to take off after arming. In case the vehicle didn't takeoff\nwithin the timeout it disarms again.\nA negative value disables autmoatic disarming triggered by a pre-takeoff timeout.", "name": "COM_DISARM_PRFLT", "shortDesc": "Time-out for auto disarm if not taking off", "type": "Float", "units": "s"}, {"bitmask": [{"description": "Mission", "index": 0}, {"description": "Hold", "index": 1}, {"description": "Offboard", "index": 2}], "category": "Standard", "default": 0, "group": "Commander", "longDesc": "Specify modes in which datalink loss is ignored and the failsafe action not triggered.", "max": 7, "min": 0, "name": "COM_DLL_EXCEPT", "shortDesc": "Datalink loss exceptions", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10, "group": "Commander", "increment": 1, "longDesc": "After this amount of seconds without datalink, the GCS connection lost mode triggers", "max": 300, "min": 5, "name": "COM_DL_LOSS_T", "shortDesc": "GCS connection loss time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "longDesc": "Before entering failsafe (RTL, Land, Hold), wait COM_FAIL_ACT_T seconds in Hold mode\nfor the user to realize.\nDuring that time the user cannot take over control via the stick override feature (see COM_RC_OVERRIDE).\nAfterwards the configured failsafe action is triggered and the user may use stick override.\nA zero value disables the delay and the user cannot take over via stick movements (switching modes is still allowed).", "max": 25.0, "min": 0.0, "name": "COM_FAIL_ACT_T", "shortDesc": "Delay between failsafe condition triggered and failsafe reaction", "type": "Float", "units": "s"}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This number is incremented automatically after every flight on\ndisarming in order to remember the next flight UUID.\nThe first flight is 0.", "min": 0, "name": "COM_FLIGHT_UUID", "shortDesc": "Next flight UUID", "type": "Int32", "volatile": true}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE1", "shortDesc": "Mode slot 1", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE2", "shortDesc": "Mode slot 2", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE3", "shortDesc": "Mode slot 3", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE4", "shortDesc": "Mode slot 4", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE5", "shortDesc": "Mode slot 5", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE6", "shortDesc": "Mode slot 6", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": 3, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when the remaining flight time is below\nthe estimated time it takes to reach the RTL destination.", "name": "COM_FLTT_LOW_ACT", "shortDesc": "Remaining flight time low failsafe", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Return", "value": 3}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Describes the intended use of the vehicle.\nCan be used by ground control software or log post processing.\nThis param does not influence the behavior within the firmware. This means for example the control logic is independent of the setting of this param (but depends on other params).", "name": "COM_FLT_PROFILE", "shortDesc": "User Flight Profile", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Pro User", "value": 100}, {"description": "Flight Tester", "value": 200}, {"description": "Developer", "value": 300}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "The vehicle aborts the current operation and returns to launch when\nthe time since takeoff is above this value. It is not possible to resume the\nmission or switch to any auto mode other than RTL or Land. Taking over in any manual\nmode is still possible.\nStarting from 90% of the maximum flight time, a warning message will be sent\nevery 1 minute with the remaining time until automatic RTL.\nSet to -1 to disable.", "min": -1, "name": "COM_FLT_TIME_MAX", "shortDesc": "Maximum allowed flight time", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Force safety when the vehicle disarms", "name": "COM_FORCE_SAFETY", "shortDesc": "Enable force safety", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 120, "group": "Commander", "longDesc": "After this amount of seconds without datalink the data link lost mode triggers", "max": 3600, "min": 60, "name": "COM_HLDL_LOSS_T", "shortDesc": "High Latency Datalink loss time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "After a data link loss: after this number of seconds with a healthy datalink the 'datalink loss'\nflag is set back to false", "max": 60, "min": 0, "name": "COM_HLDL_REG_T", "shortDesc": "High Latency Datalink regain time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Set home position automatically if possible.\nDuring missions, the latitude/longitude of the home position is locked and will not reset during intermediate landings.\nIt will only update once the mission is complete or landed outside of a mission.\nHowever, the altitude is still being adjusted to correct for GNSS vertical drift in the first 2 minutes after takeoff.", "name": "COM_HOME_EN", "rebootRequired": true, "shortDesc": "Home position enabled", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "If set to true, the autopilot is allowed to set its home position after takeoff\nThe true home position is back-computed if a local position is estimate if available.\nIf no local position is available, home is set to the current position.", "name": "COM_HOME_IN_AIR", "shortDesc": "Allows setting the home position after takeoff", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when an imbalanced propeller is detected by the failure detector.\nSee also FD_IMB_PROP_THR to set the failure threshold.", "name": "COM_IMB_PROP_ACT", "shortDesc": "Imbalanced propeller failsafe mode", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Warning", "value": 0}, {"description": "Return", "value": 1}, {"description": "Land", "value": 2}]}, {"category": "Standard", "default": 5.0, "group": "Commander", "increment": 0.1, "max": 30.0, "min": 0.0, "name": "COM_KILL_DISARM", "shortDesc": "Timeout value for disarming when kill switch is engaged", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Commander", "longDesc": "A non-zero, positive value specifies the timeframe in seconds within failure detector is allowed to disarm the vehicle\nif attitude exceeds the limits defined in FD_FAIL_P and FD_FAIL_R.\nThe check is not executed for flight modes that do support acrobatic maneuvers, e.g: Acro (MC/FW) and Manual (FW).\nA zero or negative value means that the check is disabled.", "max": 5.0, "min": -1.0, "name": "COM_LKDOWN_TKO", "shortDesc": "Timeout for detecting a failure after takeoff", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Action the system takes at critical battery. See also BAT_CRIT_THR and BAT_EMERGEN_THR\nfor definition of battery states.", "name": "COM_LOW_BAT_ACT", "shortDesc": "Battery failsafe mode", "type": "Int32", "values": [{"description": "Warning", "value": 0}, {"description": "Land mode", "value": 2}, {"description": "Return at critical level, land at emergency level", "value": 3}]}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE0_HASH", "shortDesc": "External mode identifier 0", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE1_HASH", "shortDesc": "External mode identifier 1", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE2_HASH", "shortDesc": "External mode identifier 2", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE3_HASH", "shortDesc": "External mode identifier 3", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE4_HASH", "shortDesc": "External mode identifier 4", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE5_HASH", "shortDesc": "External mode identifier 5", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE6_HASH", "shortDesc": "External mode identifier 6", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE7_HASH", "shortDesc": "External mode identifier 7", "type": "Int32", "volatile": true}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "By default disabled for safety reasons", "name": "COM_MODE_ARM_CHK", "shortDesc": "Allow external mode registration while armed", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "If set, enables the actuator test interface via MAVLink (ACTUATOR_TEST), that\nallows spinning the motors and moving the servos for testing purposes.", "name": "COM_MOT_TEST_EN", "shortDesc": "Enable Actuator Testing", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 5.0, "group": "Commander", "increment": 0.01, "max": 60.0, "min": 0.0, "name": "COM_OBC_LOSS_T", "shortDesc": "Time-out to wait when onboard computer connection is lost before warning about loss connection", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The offboard loss failsafe will only be entered after a timeout,\nset by COM_OF_LOSS_T in seconds.", "name": "COM_OBL_RC_ACT", "shortDesc": "Set offboard loss failsafe mode", "type": "Int32", "values": [{"description": "Position mode", "value": 0}, {"description": "Altitude mode", "value": 1}, {"description": "Stabilized", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Land mode", "value": 4}, {"description": "Hold mode", "value": 5}, {"description": "Terminate", "value": 6}, {"description": "Disarm", "value": 7}]}, {"category": "Standard", "default": 1.0, "group": "Commander", "increment": 0.01, "longDesc": "See COM_OBL_RC_ACT to configure action.", "max": 60.0, "min": 0.0, "name": "COM_OF_LOSS_T", "shortDesc": "Time-out to wait when offboard connection is lost before triggering offboard lost action", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "name": "COM_PARACHUTE", "shortDesc": "Expect and require a healthy MAVLink parachute system", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control in manual Position mode.", "name": "COM_POSCTL_NAVL", "shortDesc": "Position mode navigation loss response", "type": "Int32", "values": [{"description": "Altitude mode", "value": 0}, {"description": "Land mode (descend)", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "longDesc": "This is the horizontal position error (EPH) threshold that will trigger a failsafe.\nIf the previous position error was below this threshold, there is an additional\nfactor of 2.5 applied (threshold for invalidation 2.5 times the one for validation).\nOnly used for multicopters and VTOLs in hover mode.\nIndependent from estimator positioning data timeout threshold (see EKF2_NOAID_TOUT).\nSet to -1 to disable.", "max": 400.0, "min": -1.0, "name": "COM_POS_FS_EPH", "shortDesc": "Horizontal position error threshold for hovering systems", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when the estimated position has an accuracy below the specified threshold.\nSee COM_POS_LOW_EPH to set the failsafe threshold.\nThe failsafe action is only executed if the vehicle is in auto mission or auto loiter mode,\notherwise it is only a warning.", "name": "COM_POS_LOW_ACT", "shortDesc": "Low position accuracy action", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold", "value": 2}, {"description": "Return", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land", "value": 5}]}, {"category": "Standard", "default": -1.0, "group": "Commander", "longDesc": "This triggers the action specified in COM_POS_LOW_ACT if the estimated position accuracy is below this threshold.\nLocal position has to be still declared valid, which requires some kind of velocity aiding or large dead-reckoning time (EKF2_NOAID_TOUT),\nand a high failsafe threshold (COM_POS_FS_EPH).\nSet to -1 to disable.", "max": 1000.0, "min": -1.0, "name": "COM_POS_LOW_EPH", "shortDesc": "Low position accuracy failsafe threshold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This configures a check to verify the expected number of 5V rail power supplies are present. By default only one is expected.\nNote: CBRK_SUPPLY_CHK disables all power checks including this one.", "max": 4, "min": 0, "name": "COM_POWER_COUNT", "shortDesc": "Required number of redundant power modules", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Condition to enter the prearmed state, an intermediate state between disarmed and armed\nin which non-throttling actuators are active.", "name": "COM_PREARM_MODE", "shortDesc": "Condition to enter prearmed mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Safety button", "value": 1}, {"description": "Always", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "name": "COM_QC_ACT", "shortDesc": "Set action after a quadchute", "type": "Int32", "values": [{"description": "Warning only", "value": -1}, {"description": "Return mode", "value": 0}, {"description": "Land mode", "value": 1}, {"description": "Hold mode", "value": 2}]}, {"category": "Standard", "default": 95.0, "group": "Commander", "increment": 1.0, "longDesc": "The check fails if the RAM usage is above this threshold.\nA negative value disables the check.", "max": 100.0, "min": -1.0, "name": "COM_RAM_MAX", "shortDesc": "Maximum allowed RAM usage to pass checks", "type": "Float", "units": "%"}, {"bitmask": [{"description": "Mission", "index": 0}, {"description": "Hold", "index": 1}, {"description": "Offboard", "index": 2}], "category": "Standard", "default": 0, "group": "Commander", "longDesc": "Specify modes in which RC loss is ignored and the failsafe action not triggered.", "max": 7, "min": 0, "name": "COM_RCL_EXCEPT", "shortDesc": "RC loss exceptions", "type": "Int32"}, {"category": "Standard", "default": 1000, "group": "Commander", "longDesc": "The default value of 1000 requires the stick to be held in the arm or disarm position for 1 second.", "max": 1500, "min": 100, "name": "COM_RC_ARM_HYST", "shortDesc": "RC input arm/disarm command duration", "type": "Int32", "units": "ms"}, {"category": "Standard", "default": 3, "group": "Commander", "longDesc": "A value of 0 enables RC transmitter control (only). A valid RC transmitter calibration is required.\nA value of 1 allows joystick control only. RC input handling and the associated checks are disabled.\nA value of 2 allows either RC Transmitter or Joystick input. The first valid input is used, will fallback to other sources if the input stream becomes invalid.\nA value of 3 allows either input from RC or joystick. The first available source is selected and used until reboot.\nA value of 4 ignores any stick input.", "max": 4, "min": 0, "name": "COM_RC_IN_MODE", "shortDesc": "RC control input mode", "type": "Int32", "values": [{"description": "RC Transmitter only", "value": 0}, {"description": "Joystick only", "value": 1}, {"description": "RC and Joystick with fallback", "value": 2}, {"description": "RC or Joystick keep first", "value": 3}, {"description": "Stick input disabled", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Commander", "increment": 0.1, "longDesc": "The time in seconds without a new setpoint from RC or Joystick, after which the connection is considered lost.\nThis must be kept short as the vehicle will use the last supplied setpoint until the timeout triggers.\nEnsure the value is not set lower than the update interval of the RC or Joystick.", "max": 35.0, "min": 0.0, "name": "COM_RC_LOSS_T", "shortDesc": "Manual control loss timeout", "type": "Float", "units": "s"}, {"bitmask": [{"description": "Enable override during auto modes (except for in critical battery reaction)", "index": 0}, {"description": "Enable override during offboard mode", "index": 1}], "category": "Standard", "default": 1, "group": "Commander", "longDesc": "When RC stick override is enabled, moving the RC sticks more than COM_RC_STICK_OV\nimmediately gives control back to the pilot by switching to Position mode and\nif position is unavailable Altitude mode.\nNote: Only has an effect on multicopters, and VTOLs in multicopter mode.", "max": 3, "min": 0, "name": "COM_RC_OVERRIDE", "shortDesc": "Enable RC stick override of auto and/or offboard modes", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 0, "default": 30.0, "group": "Commander", "increment": 0.05, "longDesc": "If COM_RC_OVERRIDE is enabled and the joystick input is moved more than this threshold\nthe autopilot the pilot takes over control.", "max": 80.0, "min": 5.0, "name": "COM_RC_STICK_OV", "shortDesc": "RC stick override threshold", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "increment": 0.1, "longDesc": "The minimal time from arming the motors until moving the vehicle is possible is COM_SPOOLUP_TIME seconds.\nGoal:\n- Motors and propellers spool up to idle speed before getting commanded to spin faster\n- Timeout for ESCs and smart batteries to successfulyy do failure checks\ne.g. for stuck rotors before the vehicle is off the ground", "max": 30.0, "min": 0.0, "name": "COM_SPOOLUP_TIME", "shortDesc": "Enforced delay between arming and further navigation", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The mode transition after TAKEOFF has completed successfully.", "name": "COM_TAKEOFF_ACT", "shortDesc": "Action after TAKEOFF has been accepted", "type": "Int32", "values": [{"description": "Hold", "value": 0}, {"description": "Mission (if valid)", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Allows to start the vehicle by throwing it into the air.", "name": "COM_THROW_EN", "shortDesc": "Enable throw-start", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "increment": 0.1, "longDesc": "When the throw launch is enabled, the drone will only allow motors to spin after this speed\nis exceeded before detecting the freefall. This is a safety feature to ensure the drone does\nnot turn on after accidental drop or a rapid movement before the throw.\nSet to 0 to disable.", "min": 0.0, "name": "COM_THROW_SPEED", "shortDesc": "Minimum speed for the throw start", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "longDesc": "This is the horizontal velocity error (EVH) threshold that will trigger a failsafe.\nThe default is appropriate for a multicopter. Can be increased for a fixed-wing.\nIf the previous velocity error was below this threshold, there is an additional\nfactor of 2.5 applied (threshold for invalidation 2.5 times the one for validation).", "min": 0.0, "name": "COM_VEL_FS_EVH", "shortDesc": "Horizontal velocity error threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Commander", "increment": 0.1, "longDesc": "Wind speed threshold above which an automatic failsafe action is triggered.\nFailsafe action can be specified with COM_WIND_MAX_ACT.", "min": -1.0, "name": "COM_WIND_MAX", "shortDesc": "High wind speed failsafe threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when a wind speed above the specified threshold is detected.\nSee COM_WIND_MAX to set the failsafe threshold.\nIf enabled, it is not possible to resume the mission or switch to any auto mode other than\nRTL or Land if this threshold is exceeded. Taking over in any manual\nmode is still possible.", "name": "COM_WIND_MAX_ACT", "shortDesc": "High wind failsafe mode", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold", "value": 2}, {"description": "Return", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Commander", "increment": 0.1, "longDesc": "A warning is triggered if the currently estimated wind speed is above this value.\nWarning is sent periodically (every 1 minute).\nSet to -1 to disable.", "min": -1.0, "name": "COM_WIND_WARN", "shortDesc": "Wind speed warning threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The GCS connection loss failsafe will only be entered after a timeout,\nset by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected\naction will be executed.", "max": 6, "min": 0, "name": "NAV_DLL_ACT", "shortDesc": "Set GCS connection loss failsafe mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Hold mode", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Terminate", "value": 5}, {"description": "Disarm", "value": 6}]}, {"category": "Standard", "default": 2, "group": "Commander", "longDesc": "The RC loss failsafe will only be entered after a timeout,\nset by COM_RC_LOSS_T in seconds. If RC input checks have been disabled\nby setting the COM_RC_IN_MODE param it will not be triggered.", "max": 6, "min": 1, "name": "NAV_RCL_ACT", "shortDesc": "Set RC loss failsafe mode", "type": "Int32", "values": [{"description": "Hold mode", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Terminate", "value": 5}, {"description": "Disarm", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "max": 0.5, "min": 0.0, "name": "EKF2_ABIAS_INIT", "rebootRequired": true, "shortDesc": "1-sigma IMU accelerometer switch-on bias", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "EKF2", "longDesc": "If the magnitude of the IMU accelerometer vector exceeds this value, the EKF accel bias state estimation will be inhibited. This reduces the adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale factor errors on the accel bias estimates.", "max": 200.0, "min": 20.0, "name": "EKF2_ABL_ACCLIM", "shortDesc": "Maximum IMU accel magnitude that allows IMU bias learning", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "If the magnitude of the IMU angular rate vector exceeds this value, the EKF accel bias state estimation will be inhibited. This reduces the adverse effect of rapid rotation rates and associated errors on the accel bias estimates.", "max": 20.0, "min": 2.0, "name": "EKF2_ABL_GYRLIM", "shortDesc": "Maximum IMU gyro angular rate magnitude that allows IMU bias learning", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "EKF2", "longDesc": "The ekf accel bias states will be limited to within a range equivalent to +- of this value.", "max": 0.8, "min": 0.0, "name": "EKF2_ABL_LIM", "shortDesc": "Accelerometer bias learning limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay. This parameter controls the time constant of the decay.", "max": 1.0, "min": 0.1, "name": "EKF2_ABL_TAU", "shortDesc": "Accel bias learning inhibit time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.003, "group": "EKF2", "max": 0.01, "min": 0.0, "name": "EKF2_ACC_B_NOISE", "shortDesc": "Process noise for IMU accelerometer bias prediction", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.35, "group": "EKF2", "max": 1.0, "min": 0.01, "name": "EKF2_ACC_NOISE", "shortDesc": "Accelerometer noise for covariance prediction", "type": "Float", "units": "m/s^2"}, {"bitmask": [{"description": "Horizontal position", "index": 0}, {"description": "Vertical position", "index": 1}], "category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Horizontal position fusion 1 : Vertical position fusion", "max": 3, "min": 0, "name": "EKF2_AGP_CTRL", "shortDesc": "Aux global position (AGP) sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_AGP_DELAY", "rebootRequired": true, "shortDesc": "Aux global position estimator delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_AGP_GATE", "shortDesc": "Gate size for aux global position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.9, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_AGP_NOISE", "shortDesc": "Measurement noise for aux global position measurements", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "EKF2", "max": 0.5, "min": 0.0, "name": "EKF2_ANGERR_INIT", "rebootRequired": true, "shortDesc": "1-sigma tilt angle uncertainty after gravity vector alignment", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "longDesc": "Airspeed data is fused for wind estimation if above this threshold. Set to 0 to disable airspeed fusion. For reliable wind estimation both sideslip (see EKF2_FUSE_BETA) and airspeed fusion should be enabled. Only applies to fixed-wing vehicles (or VTOLs in fixed-wing mode).", "min": 0.0, "name": "EKF2_ARSP_THR", "shortDesc": "Airspeed fusion threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "max": 50.0, "min": 5.0, "name": "EKF2_ASPD_MAX", "shortDesc": "Maximum airspeed used for baro static pressure compensation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_ASP_DELAY", "rebootRequired": true, "shortDesc": "Airspeed measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_AVEL_DELAY", "rebootRequired": true, "shortDesc": "Auxiliary Velocity Estimate delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "If this parameter is enabled then the estimator will make use of the barometric height measurements to estimate its height in addition to other height sources (if activated).", "name": "EKF2_BARO_CTRL", "shortDesc": "Barometric sensor height aiding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_BARO_DELAY", "rebootRequired": true, "shortDesc": "Barometer measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_BARO_GATE", "shortDesc": "Gate size for barometric and GPS height fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.5, "group": "EKF2", "max": 15.0, "min": 0.01, "name": "EKF2_BARO_NOISE", "shortDesc": "Measurement noise for barometric altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by bluff body drag along the forward/reverse axis when flying a multi-copter which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis.", "max": 200.0, "min": 0.0, "name": "EKF2_BCOEF_X", "shortDesc": "X-axis ballistic coefficient used for multi-rotor wind estimation", "type": "Float", "units": "kg/m^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by bluff body drag along the right/left axis when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis.", "max": 200.0, "min": 0.0, "name": "EKF2_BCOEF_Y", "shortDesc": "Y-axis ballistic coefficient used for multi-rotor wind estimation", "type": "Float", "units": "kg/m^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_BETA_GATE", "shortDesc": "Gate size for synthetic sideslip fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 1.0, "min": 0.1, "name": "EKF2_BETA_NOISE", "shortDesc": "Noise for synthetic sideslip fusion", "type": "Float", "units": "m/s"}, {"bitmask": [{"description": "use geo_lookup declination", "index": 0}, {"description": "save EKF2_MAG_DECL on disarm", "index": 1}], "category": "Standard", "default": 3, "group": "EKF2", "longDesc": "Set bits in the following positions to enable functions. 0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value. 1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms.", "max": 3, "min": 0, "name": "EKF2_DECL_TYPE", "rebootRequired": true, "shortDesc": "Integer bitmask controlling handling of magnetic declination", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 200.0, "group": "EKF2", "longDesc": "Defines the delay between the current time and the delayed-time horizon. This value should be at least as large as the largest EKF2_XXX_DELAY parameter.", "max": 1000.0, "min": 0.0, "name": "EKF2_DELAY_MAX", "rebootRequired": true, "shortDesc": "Maximum delay of all the aiding sensors", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Activate wind speed estimation using specific-force measurements and a drag model defined by EKF2_BCOEF_[XY] and EKF2_MCOEF. Only use on vehicles that have their thrust aligned with the Z axis and no thrust in the XY plane.", "name": "EKF2_DRAG_CTRL", "shortDesc": "Multirotor wind estimation selection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 2.5, "group": "EKF2", "longDesc": "Used by the multi-rotor specific drag force model. Increasing this makes the multi-rotor wind estimates adjust more slowly.", "max": 10.0, "min": 0.5, "name": "EKF2_DRAG_NOISE", "shortDesc": "Specific drag force observation noise variance", "type": "Float", "units": "(m/s^2)^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.4, "group": "EKF2", "max": 5.0, "min": 0.5, "name": "EKF2_EAS_NOISE", "shortDesc": "Measurement noise for airspeed fusion", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "EKF2", "name": "EKF2_EN", "shortDesc": "EKF2 enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.05, "name": "EKF2_EVA_NOISE", "shortDesc": "Measurement noise for vision angle measurements", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_EVP_GATE", "shortDesc": "Gate size for vision position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_EVP_NOISE", "shortDesc": "Measurement noise for vision position measurements", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_EVV_GATE", "shortDesc": "Gate size for vision velocity estimate fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_EVV_NOISE", "shortDesc": "Measurement noise for vision velocity measurements", "type": "Float", "units": "m/s"}, {"bitmask": [{"description": "Horizontal position", "index": 0}, {"description": "Vertical position", "index": 1}, {"description": "3D velocity", "index": 2}, {"description": "Yaw", "index": 3}], "category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Horizontal position fusion 1 : Vertical position fusion 2 : 3D velocity fusion 3 : Yaw", "max": 15, "min": 0, "name": "EKF2_EV_CTRL", "shortDesc": "External vision (EV) sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_EV_DELAY", "rebootRequired": true, "shortDesc": "Vision Position Estimator delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "If set to 0 (default) the measurement noise is taken from the vision message and the EV noise parameters are used as a lower bound. If set to 1 the observation noise is set from the parameters directly,", "name": "EKF2_EV_NOISE_MD", "shortDesc": "External vision (EV) noise mode", "type": "Int32", "values": [{"description": "EV reported variance (parameter lower bound)", "value": 0}, {"description": "EV noise parameters", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_X", "shortDesc": "X position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_Y", "shortDesc": "Y position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_Z", "shortDesc": "Z position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0, "group": "EKF2", "longDesc": "External vision will only be started and fused if the quality metric is above this threshold. The quality metric is a completely optional field provided by some VIO systems.", "max": 100, "min": 0, "name": "EKF2_EV_QMIN", "shortDesc": "External vision (EV) minimum quality (optional)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "For reliable wind estimation both sideslip and airspeed fusion (see EKF2_ARSP_THR) should be enabled. Only applies to vehicles in fixed-wing mode or with airspeed fusion active. Note: side slip fusion is currently not supported for tailsitters.", "name": "EKF2_FUSE_BETA", "shortDesc": "Enable synthetic sideslip fusion", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "max": 0.2, "min": 0.0, "name": "EKF2_GBIAS_INIT", "rebootRequired": true, "shortDesc": "1-sigma IMU gyro switch-on bias", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "EKF2", "longDesc": "Sets the value of deadzone applied to negative baro innovations. Deadzone is enabled when EKF2_GND_EFF_DZ > 0.", "max": 10.0, "min": 0.0, "name": "EKF2_GND_EFF_DZ", "shortDesc": "Baro deadzone range for height fusion", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "EKF2", "longDesc": "Sets the maximum distance to the ground level where negative baro innovations are expected.", "max": 5.0, "min": 0.0, "name": "EKF2_GND_MAX_HGT", "shortDesc": "Height above ground level for ground effect zone", "type": "Float", "units": "m"}, {"bitmask": [{"description": "Sat count (EKF2_REQ_NSATS)", "index": 0}, {"description": "PDOP (EKF2_REQ_PDOP)", "index": 1}, {"description": "EPH (EKF2_REQ_EPH)", "index": 2}, {"description": "EPV (EKF2_REQ_EPV)", "index": 3}, {"description": "Speed accuracy (EKF2_REQ_SACC)", "index": 4}, {"description": "Horizontal position drift (EKF2_REQ_HDRIFT)", "index": 5}, {"description": "Vertical position drift (EKF2_REQ_VDRIFT)", "index": 6}, {"description": "Horizontal speed offset (EKF2_REQ_HDRIFT)", "index": 7}, {"description": "Vertical speed offset (EKF2_REQ_VDRIFT)", "index": 8}, {"description": "Spoofing", "index": 9}], "category": "Standard", "default": 1023, "group": "EKF2", "longDesc": "Each threshold value is defined by the parameter indicated next to the check. Drift and offset checks only run when the vehicle is on ground and stationary.", "max": 1023, "min": 0, "name": "EKF2_GPS_CHECK", "shortDesc": "Integer bitmask controlling GPS checks", "type": "Int32"}, {"bitmask": [{"description": "Lon/lat", "index": 0}, {"description": "Altitude", "index": 1}, {"description": "3D velocity", "index": 2}, {"description": "Dual antenna heading", "index": 3}], "category": "Standard", "default": 7, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Longitude and latitude fusion 1 : Altitude fusion 2 : 3D velocity fusion 3 : Dual antenna heading fusion", "max": 15, "min": 0, "name": "EKF2_GPS_CTRL", "shortDesc": "GNSS sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 110.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_GPS_DELAY", "rebootRequired": true, "shortDesc": "GPS measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward (roll) axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_X", "shortDesc": "X position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Right (pitch) axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_Y", "shortDesc": "Y position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Down (yaw) axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_Z", "shortDesc": "Z position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_GPS_P_GATE", "shortDesc": "Gate size for GNSS position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "max": 10.0, "min": 0.01, "name": "EKF2_GPS_P_NOISE", "shortDesc": "Measurement noise for GNSS position", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_GPS_V_GATE", "shortDesc": "Gate size for GNSS velocity fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 5.0, "min": 0.01, "name": "EKF2_GPS_V_NOISE", "shortDesc": "Measurement noise for GNSS velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 360.0, "min": 0.0, "name": "EKF2_GPS_YAW_OFF", "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "EKF2", "max": 10.0, "min": 0.1, "name": "EKF2_GRAV_NOISE", "shortDesc": "Accelerometer measurement noise for gravity based observations", "type": "Float", "units": "g0"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "EKF2", "longDesc": "If no airspeed measurements are available, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes.", "max": 100.0, "min": 0.0, "name": "EKF2_GSF_TAS", "shortDesc": "Default value of true airspeed used in EKF-GSF AHRS calculation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "EKF2", "longDesc": "The ekf gyro bias states will be limited to within a range equivalent to +- of this value.", "max": 0.4, "min": 0.0, "name": "EKF2_GYR_B_LIM", "shortDesc": "Gyro bias learning limit", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.001, "group": "EKF2", "max": 0.01, "min": 0.0, "name": "EKF2_GYR_B_NOISE", "shortDesc": "Process noise for IMU rate gyro bias prediction", "type": "Float", "units": "rad/s^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.015, "group": "EKF2", "max": 0.1, "min": 0.0001, "name": "EKF2_GYR_NOISE", "shortDesc": "Rate gyro noise for covariance prediction", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.6, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_HDG_GATE", "shortDesc": "Gate size for heading fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 1.0, "min": 0.01, "name": "EKF2_HEAD_NOISE", "shortDesc": "Measurement noise for magnetic heading fusion", "type": "Float", "units": "rad"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "When multiple height sources are enabled at the same time, the height estimate will always converge towards the reference height source selected by this parameter. The range sensor and vision options should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level. If GPS is set as reference but altitude fusion is disabled in EKF2_GPS_CTRL, the GPS altitude is still used to initiaize the bias of the other height sensors.", "name": "EKF2_HGT_REF", "rebootRequired": true, "shortDesc": "Determines the reference source of height data used by the EKF", "type": "Int32", "values": [{"description": "Barometric pressure", "value": 0}, {"description": "GPS", "value": 1}, {"description": "Range sensor", "value": 2}, {"description": "Vision", "value": 3}]}, {"bitmask": [{"description": "Gyro Bias", "index": 0}, {"description": "Accel Bias", "index": 1}, {"description": "Gravity vector fusion", "index": 2}], "category": "Standard", "default": 7, "group": "EKF2", "max": 7, "min": 0, "name": "EKF2_IMU_CTRL", "shortDesc": "IMU control", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_X", "shortDesc": "X position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_Y", "shortDesc": "Y position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_Z", "shortDesc": "Z position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "EKF2", "name": "EKF2_LOG_VERBOSE", "shortDesc": "Verbose logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "The heading is assumed to be observable when the body acceleration is greater than this parameter when a global position/velocity aiding source is active.", "max": 5.0, "min": 0.0, "name": "EKF2_MAG_ACCLIM", "shortDesc": "Horizontal acceleration threshold used for heading observability check", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.0001, "group": "EKF2", "max": 0.1, "min": 0.0, "name": "EKF2_MAG_B_NOISE", "shortDesc": "Process noise for body magnetic field prediction", "type": "Float", "units": "gauss/s"}, {"bitmask": [{"description": "Strength (EKF2_MAG_CHK_STR)", "index": 0}, {"description": "Inclination (EKF2_MAG_CHK_INC)", "index": 1}, {"description": "Wait for WMM", "index": 2}], "category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Bitmask to set which check is used to decide whether the magnetometer data is valid. If GNSS data is received, the magnetic field is compared to a World Magnetic Model (WMM), otherwise an average value is used. This check is useful to reject occasional hard iron disturbance. Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Magnetic field strength. Set tolerance using EKF2_MAG_CHK_STR 1 : Magnetic field inclination. Set tolerance using EKF2_MAG_CHK_INC 2 : Wait for GNSS to find the theoretical strength and inclination using the WMM", "max": 7, "min": 0, "name": "EKF2_MAG_CHECK", "shortDesc": "Magnetic field strength test selection", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "longDesc": "Maximum allowed deviation from the expected magnetic field inclination to pass the check.", "max": 90.0, "min": 0.0, "name": "EKF2_MAG_CHK_INC", "shortDesc": "Magnetic field inclination check tolerance", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "longDesc": "Maximum allowed deviation from the expected magnetic field strength to pass the check.", "max": 1.0, "min": 0.0, "name": "EKF2_MAG_CHK_STR", "shortDesc": "Magnetic field strength check tolerance", "type": "Float", "units": "gauss"}, {"category": "System", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "name": "EKF2_MAG_DECL", "shortDesc": "Magnetic declination", "type": "Float", "units": "deg", "volatile": true}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_MAG_DELAY", "rebootRequired": true, "shortDesc": "Magnetometer measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.001, "group": "EKF2", "max": 0.1, "min": 0.0, "name": "EKF2_MAG_E_NOISE", "shortDesc": "Process noise for earth magnetic field prediction", "type": "Float", "units": "gauss/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_MAG_GATE", "shortDesc": "Gate size for magnetometer XYZ component fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "EKF2", "max": 1.0, "min": 0.001, "name": "EKF2_MAG_NOISE", "shortDesc": "Measurement noise for magnetometer 3-axis fusion", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. The fusion of magnetometer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight. If set to 'Magnetic heading' magnetic heading fusion is used at all times. If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GNSS velocity measurements to align the yaw angle. If set to 'Init' the magnetometer is only used to initalize the heading.", "name": "EKF2_MAG_TYPE", "rebootRequired": true, "shortDesc": "Type of magnetometer fusion", "type": "Int32", "values": [{"description": "Automatic", "value": 0}, {"description": "Magnetic heading", "value": 1}, {"description": "None", "value": 5}, {"description": "Init", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the propeller axis of rotation is lost when passing through the rotor disc. This changes the momentum of the flow which creates a drag reaction force. When comparing un-ducted propellers of the same diameter, the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with propeller selection. Momentum drag is significantly higher for ducted rotors. To account for the drag produced by the body which scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y parameters. Set this parameter to zero to turn off the momentum drag model for both axis.", "max": 1.0, "min": 0.0, "name": "EKF2_MCOEF", "shortDesc": "Propeller momentum drag coefficient for multi-rotor wind estimation", "type": "Float", "units": "1/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "If the vehicle is on ground, is not moving as determined by the motion test and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is available at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground.", "min": 0.01, "name": "EKF2_MIN_RNG", "shortDesc": "Expected range finder reading when on ground", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Maximum number of IMUs to use for Multi-EKF. Set 0 to disable. Requires SENS_IMU_MODE 0.", "max": 4, "min": 0, "name": "EKF2_MULTI_IMU", "rebootRequired": true, "shortDesc": "Multi-EKF IMUs", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Maximum number of magnetometers to use for Multi-EKF. Set 0 to disable. Requires SENS_MAG_MODE 0.", "max": 4, "min": 0, "name": "EKF2_MULTI_MAG", "rebootRequired": true, "shortDesc": "Multi-EKF Magnetometers", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "EKF2", "max": 50.0, "min": 0.5, "name": "EKF2_NOAID_NOISE", "shortDesc": "Measurement noise for non-aiding position hold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 5000000, "group": "EKF2", "longDesc": "Maximum lapsed time from last fusion of measurements that constrain velocity drift before the EKF will report the horizontal nav solution as invalid", "max": 10000000, "min": 500000, "name": "EKF2_NOAID_TOUT", "shortDesc": "Maximum inertial dead-reckoning time", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Enable optical flow fusion.", "name": "EKF2_OF_CTRL", "shortDesc": "Optical flow aiding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "longDesc": "Assumes measurement is timestamped at trailing edge of integration period", "max": 300.0, "min": 0.0, "name": "EKF2_OF_DELAY", "rebootRequired": true, "shortDesc": "Optical flow measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_OF_GATE", "shortDesc": "Gate size for optical flow fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Auto: use gyro from optical flow message if available, internal gyro otherwise. Internal: always use internal gyro", "name": "EKF2_OF_GYR_SRC", "shortDesc": "Optical flow angular rate compensation source", "type": "Int32", "values": [{"description": "Auto", "value": 0}, {"description": "Internal", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "Measurement noise for the optical flow sensor when it's reported quality metric is at the minimum", "min": 0.05, "name": "EKF2_OF_N_MAX", "shortDesc": "Optical flow maximum noise", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "EKF2", "longDesc": "Measurement noise for the optical flow sensor when it's reported quality metric is at the maximum", "min": 0.05, "name": "EKF2_OF_N_MIN", "shortDesc": "Optical flow minimum noise", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_X", "shortDesc": "X position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_Y", "shortDesc": "Y position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_Z", "shortDesc": "Z position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Optical Flow data will only be used in air if the sensor reports a quality metric >= EKF2_OF_QMIN", "max": 255, "min": 0, "name": "EKF2_OF_QMIN", "shortDesc": "In air optical flow minimum quality", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Optical Flow data will only be used on the ground if the sensor reports a quality metric >= EKF2_OF_QMIN_GND", "max": 255, "min": 0, "name": "EKF2_OF_QMIN_GND", "shortDesc": "On ground optical flow minimum quality", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_XN", "shortDesc": "Static pressure position error coefficient for the negative X axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forward flight, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_XP", "shortDesc": "Static pressure position error coefficient for the positive X axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the negative Y (LH) body axis. If the baro height estimate rises during sideways flight to the left, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_YN", "shortDesc": "Pressure position error coefficient for the negative Y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the positive Y (RH) body axis. If the baro height estimate rises during sideways flight to the right, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_YP", "shortDesc": "Pressure position error coefficient for the positive Y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the Z body axis.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_Z", "shortDesc": "Static pressure position error coefficient for the Z axis", "type": "Float"}, {"category": "Standard", "default": 10000, "group": "EKF2", "longDesc": "EKF prediction period in microseconds. This should ideally be an integer multiple of the IMU time delta. Actual filter update will be an integer multiple of IMU update.", "max": 20000, "min": 1000, "name": "EKF2_PREDICT_US", "shortDesc": "EKF prediction period", "type": "Int32", "units": "us"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "max": 100.0, "min": 2.0, "name": "EKF2_REQ_EPH", "shortDesc": "Required EPH to use GPS", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 100.0, "min": 2.0, "name": "EKF2_REQ_EPV", "shortDesc": "Required EPV to use GPS", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "EKF2", "longDesc": "Minimum continuous period without GPS failure required to mark a healthy GPS status. It can be reduced to speed up initialization, but it's recommended to keep this unchanged for a vehicle.", "min": 0.1, "name": "EKF2_REQ_GPS_H", "rebootRequired": true, "shortDesc": "Required GPS health time on startup", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "max": 1.0, "min": 0.1, "name": "EKF2_REQ_HDRIFT", "shortDesc": "Maximum horizontal drift speed to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 6, "group": "EKF2", "max": 12, "min": 4, "name": "EKF2_REQ_NSATS", "shortDesc": "Required satellite count to use GPS", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "EKF2", "max": 5.0, "min": 1.5, "name": "EKF2_REQ_PDOP", "shortDesc": "Maximum PDOP to use GPS", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "max": 5.0, "min": 0.5, "name": "EKF2_REQ_SACC", "shortDesc": "Required speed accuracy to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "max": 1.5, "min": 0.1, "name": "EKF2_REQ_VDRIFT", "shortDesc": "Maximum vertical drift speed to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 5.0, "group": "EKF2", "longDesc": "If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1).", "max": 10.0, "min": 1.0, "name": "EKF2_RNG_A_HMAX", "shortDesc": "Maximum height above ground allowed for conditional range aid mode", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "A lower value means HAGL needs to be more stable in order to use range finder for height estimation in range aid mode", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_A_IGATE", "shortDesc": "Gate size used for innovation consistency checks for range aid fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1).", "max": 2.0, "min": 0.1, "name": "EKF2_RNG_A_VMAX", "shortDesc": "Maximum horizontal velocity allowed for conditional range aid mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "WARNING: Range finder measurements are less reliable and can experience unexpected errors. For these reasons, if accurate control of height relative to ground is required, it is recommended to use the MPC_ALT_MODE parameter instead, unless baro errors are severe enough to cause problems with landing and takeoff. If this parameter is enabled then the estimator will make use of the range finder measurements to estimate its height in addition to other height sources (if activated). Range sensor aiding can be enabled (i.e.: always use) or set in \"conditional\" mode. Conditional mode: This enables the range finder to be used during low speed (< EKF2_RNG_A_VMAX) and low altitude (< EKF2_RNG_A_HMAX) operation, eg takeoff and landing, where baro interference from rotor wash is excessive and can corrupt EKF state estimates. It is intended to be used where a vertical takeoff and landing is performed, and horizontal flight does not occur until above EKF2_RNG_A_HMAX.", "name": "EKF2_RNG_CTRL", "shortDesc": "Range sensor height aiding", "type": "Int32", "values": [{"description": "Disable range fusion", "value": 0}, {"description": "Enabled (conditional mode)", "value": 1}, {"description": "Enabled", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_RNG_DELAY", "rebootRequired": true, "shortDesc": "Range finder measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Limit for fog detection. If the range finder measures a distance greater than this value, the measurement is considered to not be blocked by fog or rain. If there's a jump from larger than RNG_FOG to smaller than EKF2_RNG_FOG, the measurement may gets rejected. 0 - disabled", "max": 20.0, "min": 0.0, "name": "EKF2_RNG_FOG", "shortDesc": "Maximum distance at which the range finder could detect fog (m)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_RNG_GATE", "shortDesc": "Gate size for range finder fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "To be used, the time derivative of the distance sensor measurements projected on the vertical axis needs to be statistically consistent with the estimated vertical velocity of the drone. Decrease this value to make the filter more robust against range finder faulty data (stuck, reflections, ...). Note: tune the range finder noise parameters (EKF2_RNG_NOISE and EKF2_RNG_SFE) before tuning this gate.", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_K_GATE", "shortDesc": "Gate size used for range finder kinematic consistency check", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "min": 0.01, "name": "EKF2_RNG_NOISE", "shortDesc": "Measurement noise for range finder fusion", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "max": 0.75, "min": -0.75, "name": "EKF2_RNG_PITCH", "shortDesc": "Range sensor pitch offset", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_X", "shortDesc": "X position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_Y", "shortDesc": "Y position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_Z", "shortDesc": "Z position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "Minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (s)", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_QLTY_T", "shortDesc": "Minumum range validity period", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0.05, "group": "EKF2", "longDesc": "Specifies the increase in range finder noise with range.", "max": 0.2, "min": 0.0, "name": "EKF2_RNG_SFE", "shortDesc": "Range finder range dependent noise scaler", "type": "Float", "units": "m/m"}, {"category": "Standard", "default": 0.2, "group": "EKF2", "longDesc": "EKF2 instances have to be better than the selected by at least this amount before their relative score can be reduced.", "name": "EKF2_SEL_ERR_RED", "shortDesc": "Selector error reduce threshold", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "EKF2 selector acceleration error threshold for comparing accelerometers. Acceleration vector differences larger than this will result in accumulated velocity error.", "name": "EKF2_SEL_IMU_ACC", "shortDesc": "Selector acceleration threshold", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 15.0, "group": "EKF2", "longDesc": "EKF2 selector maximum accumulated angular error threshold for comparing gyros. Accumulated angular error larger than this will result in the sensor being declared faulty.", "name": "EKF2_SEL_IMU_ANG", "shortDesc": "Selector angular threshold", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 7.0, "group": "EKF2", "longDesc": "EKF2 selector angular rate error threshold for comparing gyros. Angular rate vector differences larger than this will result in accumulated angular error.", "name": "EKF2_SEL_IMU_RAT", "shortDesc": "Selector angular rate threshold", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 2.0, "group": "EKF2", "longDesc": "EKF2 selector maximum accumulated velocity threshold for comparing accelerometers. Accumulated velocity error larger than this will result in the sensor being declared faulty.", "name": "EKF2_SEL_IMU_VEL", "shortDesc": "Selector angular threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Use for vehicles where the measured body Z magnetic field is subject to strong magnetic interference. For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter will only have an effect if the global position of the drone is known. For 3D mag fusion the magnetometer Z measurement will simply be ignored instead of fusing the synthetic value.", "name": "EKF2_SYNT_MAG_Z", "shortDesc": "Enable synthetic magnetometer Z component measurement", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_TAS_GATE", "shortDesc": "Gate size for TAS fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "EKF2", "longDesc": "Controls how tightly the output track the EKF states", "max": 1.0, "min": 0.1, "name": "EKF2_TAU_POS", "shortDesc": "Output predictor position time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "EKF2", "max": 1.0, "name": "EKF2_TAU_VEL", "shortDesc": "Time constant of the velocity output prediction and smoothing filter", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "min": 0.0, "name": "EKF2_TERR_GRAD", "shortDesc": "Magnitude of terrain gradient", "type": "Float", "units": "m/m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "min": 0.5, "name": "EKF2_TERR_NOISE", "shortDesc": "Terrain altitude process noise", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "max": 299792458.0, "name": "EKF2_VEL_LIM", "shortDesc": "Velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "EKF2", "longDesc": "When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second.", "max": 1.0, "min": 0.0, "name": "EKF2_WIND_NSD", "shortDesc": "Process noise spectral density for wind velocity prediction", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "default": 0, "group": "Events", "longDesc": "Enable/disable event task for RC Loss. When enabled, an alarm tune will be\nplayed via buzzer or ESCs, if supported. The alarm will sound after a disarm,\nif the vehicle was previously armed and only if the vehicle had RC signal at\nsome point. Particularly useful for locating crashed drones without a GPS\nsensor.", "name": "EV_TSK_RC_LOSS", "rebootRequired": true, "shortDesc": "RC Loss Alarm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Events", "longDesc": "Enable/disable event task for displaying the vehicle status using arm-mounted\nLEDs. When enabled and if the vehicle supports it, LEDs will flash\nindicating various vehicle status changes. Currently PX4 has not implemented\nany specific status events.\n-", "name": "EV_TSK_STAT_DIS", "rebootRequired": true, "shortDesc": "Status Display", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "Applies to both directions in all manual modes with attitude stabilization but without altitude control", "max": 90.0, "min": 0.0, "name": "FW_MAN_P_MAX", "shortDesc": "Maximum manual pitch angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 45.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "Applies to both directions in all manual modes with attitude stabilization", "max": 90.0, "min": 0.0, "name": "FW_MAN_R_MAX", "shortDesc": "Maximum manual roll angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "This is the maximally added yaw rate setpoint from the yaw stick in any attitude controlled flight mode.\nIt is added to the yaw rate setpoint generated by the controller for turn coordination.", "min": 0.0, "name": "FW_MAN_YR_MAX", "shortDesc": "Maximum manually added yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "An airframe specific offset of the pitch setpoint in degrees, the value is\nadded to the pitch setpoint and should correspond to the pitch at\ntypical cruise speed of the airframe.", "max": 90.0, "min": -90.0, "name": "FW_PSP_OFF", "shortDesc": "Pitch setpoint offset (pitch at level flight)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 60.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_P_RMAX_NEG", "shortDesc": "Maximum negative / down pitch rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 60.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_P_RMAX_POS", "shortDesc": "Maximum positive / up pitch rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "longDesc": "This defines the latency between a pitch step input and the achieved setpoint\n(inverse to a P gain). Smaller systems may require smaller values.", "max": 1.0, "min": 0.2, "name": "FW_P_TC", "shortDesc": "Attitude pitch time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 70.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_R_RMAX", "shortDesc": "Maximum roll rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "longDesc": "This defines the latency between a roll step input and the achieved setpoint\n(inverse to a P gain). Smaller systems may require smaller values.", "max": 1.0, "min": 0.2, "name": "FW_R_TC", "shortDesc": "Attitude Roll Time Constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Attitude Control", "increment": 0.05, "max": 10.0, "min": 0.0, "name": "FW_WR_FF", "shortDesc": "Wheel steering rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "FW Attitude Control", "increment": 0.005, "longDesc": "This gain defines how much control response will result out of a steady\nstate error. It trims any constant error.", "max": 10.0, "min": 0.0, "name": "FW_WR_I", "shortDesc": "Wheel steering rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_WR_IMAX", "shortDesc": "Wheel steering rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "FW Attitude Control", "increment": 0.005, "longDesc": "This defines how much the wheel steering input will be commanded depending on the\ncurrent body angular rate error.", "max": 10.0, "min": 0.0, "name": "FW_WR_P", "shortDesc": "Wheel steering rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "FW Attitude Control", "longDesc": "Only enabled during automatic runway takeoff and landing.\nIn all manual modes the wheel is directly controlled with yaw stick.", "name": "FW_W_EN", "shortDesc": "Enable wheel steering controller", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "This limits the maximum wheel steering rate the controller will output (in degrees per\nsecond).", "max": 90.0, "min": 0.0, "name": "FW_W_RMAX", "shortDesc": "Maximum wheel steering rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 50.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_Y_RMAX", "shortDesc": "Maximum yaw rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Auto Landing", "increment": 0.01, "longDesc": "Sets a fraction of full flaps during landing.\nAlso applies to flaperons if enabled in the mixer/allocation.", "max": 1.0, "min": 0.0, "name": "FW_FLAPS_LND_SCL", "shortDesc": "Flaps setting during landing", "type": "Float", "units": "norm"}, {"bitmask": [{"description": "Abort if terrain is not found (only applies to mission landings)", "index": 0}, {"description": "Abort if terrain times out (after a first successful measurement)", "index": 1}], "category": "Standard", "default": 3, "group": "FW Auto Landing", "longDesc": "Terrain estimation:\nbit 0: Abort if terrain is not found\nbit 1: Abort if terrain times out (after a first successful measurement)\nThe last estimate is always used as ground, whether the last valid measurement or the land waypoint, depending on the\nselected abort criteria, until an abort condition is entered. If FW_LND_USETER == 0, these bits are ignored.\nTODO: Extend automatic abort conditions\ne.g. glide slope tracking error (horizontal and vertical)", "max": 3, "min": 0, "name": "FW_LND_ABORT", "shortDesc": "Bit mask to set the automatic landing abort conditions", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "The calibrated airspeed setpoint during landing.\nIf set <= 0, landing airspeed = FW_AIRSPD_MIN by default.", "min": -1.0, "name": "FW_LND_AIRSPD", "shortDesc": "Landing airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Typically the desired landing slope angle when landing configuration (flaps, airspeed) is enabled.\nSet this value within the vehicle's performance limits.", "max": 45.0, "min": 1.0, "name": "FW_LND_ANG", "shortDesc": "Maximum landing slope angle", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "FW Auto Landing", "longDesc": "Allows to deploy the landing configuration (flaps, landing airspeed, etc.) already in\nthe loiter-down waypoint before the final approach.\nOtherwise is enabled only in the final approach.", "name": "FW_LND_EARLYCFG", "shortDesc": "Early landing configuration deployment", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * |z-velocity|) is taken as the flare altitude", "min": 0.0, "name": "FW_LND_FLALT", "shortDesc": "Landing flare altitude (relative to landing altitude)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Maximum pitch during landing flare.", "max": 45.0, "min": 0.0, "name": "FW_LND_FL_PMAX", "shortDesc": "Flare, maximum pitch", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Minimum pitch during landing flare.", "max": 15.0, "min": -5.0, "name": "FW_LND_FL_PMIN", "shortDesc": "Flare, minimum pitch", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "TECS will attempt to control the aircraft to this sink rate via pitch angle (throttle killed during flare)", "max": 2.0, "min": 0.0, "name": "FW_LND_FL_SINK", "shortDesc": "Landing flare sink rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "Multiplied by the descent rate to calculate a dynamic altitude at which\nto trigger the flare.\nNOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * descent rate) is taken as the flare altitude", "max": 5.0, "min": 0.1, "name": "FW_LND_FL_TIME", "shortDesc": "Landing flare time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 2, "group": "FW Auto Landing", "longDesc": "Approach angle nudging: shifts the touchdown point laterally while keeping the approach entrance point constant\nApproach path nudging: shifts the touchdown point laterally along with the entire approach path\nThis is useful for manually adjusting the landing point in real time when map or GNSS errors cause an offset from the\ndesired landing vector. Nudging is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is\nrelative to the vehicle heading (stick deflection to the right = land point moves to the right as seen by the vehicle).", "max": 2, "min": 0, "name": "FW_LND_NUDGE", "shortDesc": "Landing touchdown nudging option", "type": "Int32", "values": [{"description": "Disable nudging", "value": 0}, {"description": "Nudge approach angle", "value": 1}, {"description": "Nudge approach path", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "FW Auto Landing", "increment": 1.0, "max": 10.0, "min": 0.0, "name": "FW_LND_TD_OFF", "shortDesc": "Maximum lateral position offset for the touchdown point", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "This is the time after the start of flaring that we expect the vehicle to touch the runway.\nAt this time, a 0.5s clamp down ramp will engage, constraining the pitch setpoint to RWTO_PSP.\nIf enabled, ensure that RWTO_PSP is configured appropriately for full gear contact on ground roll.\nSet to -1.0 to disable touchdown clamping. E.g. it may not be desirable to clamp on belly landings.\nThe touchdown time will be constrained to be greater than or equal to the flare time (FW_LND_FL_TIME).", "max": 5.0, "min": -1.0, "name": "FW_LND_TD_TIME", "shortDesc": "Landing touchdown time (since flare start)", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "The TECS altitude time constant (FW_T_ALT_TC) is multiplied by this value.", "max": 1.0, "min": 0.2, "name": "FW_LND_THRTC_SC", "shortDesc": "Altitude time constant factor for landing and low-height flight", "type": "Float", "units": ""}, {"category": "Standard", "default": 1, "group": "FW Auto Landing", "longDesc": "This is critical for detecting when to flare, and should be enabled if possible.\nIf enabled and no measurement is found within a given timeout, the landing waypoint altitude will be used OR the landing\nwill be aborted, depending on the criteria set in FW_LND_ABORT.\nIf disabled, FW_LND_ABORT terrain based criteria are ignored.", "max": 2, "min": 0, "name": "FW_LND_USETER", "shortDesc": "Use terrain estimation during landing", "type": "Int32", "values": [{"description": "Disable the terrain estimate", "value": 0}, {"description": "Use the terrain estimate to trigger the flare (only)", "value": 1}, {"description": "Calculate landing glide slope relative to the terrain estimate", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Auto Landing", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "FW_SPOILERS_LND", "shortDesc": "Spoiler landing setting", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Auto Takeoff", "increment": 0.01, "longDesc": "Sets a fraction of full flaps during take-off.\nAlso applies to flaperons if enabled in the mixer/allocation.", "max": 1.0, "min": 0.0, "name": "FW_FLAPS_TO_SCL", "shortDesc": "Flaps setting during take-off", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "FW Auto Takeoff", "increment": 0.05, "longDesc": "Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds.", "max": 5.0, "min": 0.0, "name": "FW_LAUN_AC_T", "shortDesc": "Trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Auto Takeoff", "increment": 0.5, "longDesc": "Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds.", "min": 0.0, "name": "FW_LAUN_AC_THLD", "shortDesc": "Trigger acceleration threshold", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 0, "group": "FW Auto Takeoff", "longDesc": "Enables automatic launch detection based on measured acceleration. Use for hand- or catapult-launched vehicles.\nNot compatible with runway takeoff.", "name": "FW_LAUN_DETCN_ON", "shortDesc": "Fixed-wing launch detection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Auto Takeoff", "increment": 0.5, "longDesc": "Start the motor(s) this amount of seconds after launch is detected.", "max": 10.0, "min": 0.0, "name": "FW_LAUN_MOT_DEL", "shortDesc": "Motor delay", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Takeoff", "increment": 0.1, "longDesc": "The calibrated airspeed setpoint during the takeoff climbout.\nIf set <= 0, FW_AIRSPD_MIN will be set by default.", "min": -1.0, "name": "FW_TKO_AIRSPD", "shortDesc": "Takeoff Airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW Auto Takeoff", "increment": 0.5, "max": 80.0, "min": -5.0, "name": "FW_TKO_PITCH_MIN", "shortDesc": "Minimum pitch during takeoff", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 30, "group": "FW General", "longDesc": "The time the system should do open loop loiter and wait for GPS recovery\nbefore it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R.\nDoes only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0.", "min": 0, "name": "FW_GPSF_LT", "shortDesc": "GPS failure loiter time", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW General", "increment": 0.5, "longDesc": "Roll angle in GPS failure loiter mode.", "max": 60.0, "min": 0.0, "name": "FW_GPSF_R", "shortDesc": "GPS failure fixed roll angle", "type": "Float", "units": "deg"}, {"bitmask": [{"description": "Alternative stick configuration (height rate on throttle stick, airspeed on pitch stick)", "index": 0}, {"description": "Enable airspeed setpoint via sticks in altitude and position flight mode", "index": 1}], "category": "Standard", "default": 2, "group": "FW General", "longDesc": "Applies in manual Position and Altitude flight modes.", "max": 3, "min": 0, "name": "FW_POS_STK_CONF", "shortDesc": "Custom stick configuration", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW General", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 80.0, "min": 0.0, "name": "FW_P_LIM_MAX", "shortDesc": "Maximum pitch angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -30.0, "group": "FW General", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 0.0, "min": -60.0, "name": "FW_P_LIM_MIN", "shortDesc": "Minimum pitch angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 50.0, "group": "FW General", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 75.0, "min": 35.0, "name": "FW_R_LIM", "shortDesc": "Maximum roll angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW General", "increment": 0.01, "longDesc": "This is the minimum throttle while on the ground (\"landed\") in auto modes.", "max": 1.0, "min": 0.0, "name": "FW_THR_IDLE", "shortDesc": "Idle throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW General", "increment": 0.01, "longDesc": "Applies in any altitude controlled flight mode.\nShould be set accordingly to achieve FW_T_CLMB_MAX.", "max": 1.0, "min": 0.0, "name": "FW_THR_MAX", "shortDesc": "Throttle limit max", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW General", "increment": 0.01, "longDesc": "Applies in any altitude controlled flight mode.\nUsually set to 0 but can be increased to prevent the motor from stopping when\ndescending, which can increase achievable descent rates.", "max": 1.0, "min": 0.0, "name": "FW_THR_MIN", "shortDesc": "Throttle limit min", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "FW General", "increment": 0.01, "longDesc": "In auto modes: default climb rate output by controller to achieve altitude setpoints.\nIn manual modes: maximum climb rate setpoint.", "min": 0.1, "name": "FW_T_CLMB_R_SP", "shortDesc": "Default target climbrate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "FW General", "increment": 0.01, "longDesc": "In auto modes: default sink rate output by controller to achieve altitude setpoints.\nIn manual modes: maximum sink rate setpoint.", "min": 0.1, "name": "FW_T_SINK_R_SP", "shortDesc": "Default target sinkrate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW General", "increment": 1.0, "longDesc": "Adjusts the amount of weighting that the pitch control\napplies to speed vs height errors.\n0 -> control height only\n2 -> control speed only (gliders)", "max": 2.0, "min": 0.0, "name": "FW_T_SPDWEIGHT", "shortDesc": "Speed <--> Altitude weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "FW General", "increment": 1.0, "longDesc": "This is used to constrain a minimum altitude below which we keep wings level to avoid wing tip strike. It's safer\nto give a slight margin here (> 0m)", "min": 0.0, "name": "FW_WING_HEIGHT", "shortDesc": "Height (AGL) of the wings when the aircraft is on the ground", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "FW General", "increment": 0.1, "longDesc": "This is used for limiting the roll setpoint near the ground. (if multiple wings, take the longest span)", "min": 0.1, "name": "FW_WING_SPAN", "shortDesc": "The aircraft's wing span (length from tip to tip)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "FW Lateral Control", "increment": 1.0, "longDesc": "Maximum change in roll angle setpoint per second.\nApplied in all Auto modes, plus manual Position & Altitude modes.", "min": 0.0, "name": "FW_PN_R_SLEW_MAX", "shortDesc": "Path navigation roll slew rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "longDesc": "The controller will increase the commanded airspeed to maintain\nthis minimum groundspeed to the next waypoint.", "max": 40.0, "min": 0.0, "name": "FW_GND_SPD_MIN", "shortDesc": "Minimum groundspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "Maximum slew rate for the commanded throttle", "max": 1.0, "min": 0.0, "name": "FW_THR_SLEW_MAX", "shortDesc": "Throttle max slew rate", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "min": 2.0, "name": "FW_T_ALT_TC", "shortDesc": "Altitude error time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW Longitudinal Control", "longDesc": "Minimum altitude error needed to descend with max airspeed and minimal throttle.\nA negative value disables fast descend.", "min": -1.0, "name": "FW_T_F_ALT_ERR", "shortDesc": "Fast descend: minimum altitude error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW Longitudinal Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_T_HRATE_FF", "shortDesc": "Height rate feed forward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW Longitudinal Control", "increment": 0.05, "longDesc": "Increase it to trim out speed and height offsets faster,\nwith the downside of possible overshoots and oscillations.", "max": 2.0, "min": 0.0, "name": "FW_T_I_GAIN_PIT", "shortDesc": "Integrator gain pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW Longitudinal Control", "increment": 0.1, "max": 2.0, "min": 0.0, "name": "FW_T_PTCH_DAMP", "shortDesc": "Pitch damping gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Longitudinal Control", "increment": 0.5, "longDesc": "Is used to compensate for the additional drag created by turning.\nIncrease this gain if the aircraft initially loses energy in turns\nand reduce if the aircraft initially gains energy in turns.", "max": 20.0, "min": 0.0, "name": "FW_T_RLL2THR", "shortDesc": "Roll -> Throttle feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Longitudinal Control", "increment": 0.01, "max": 3.0, "min": 0.5, "name": "FW_T_SEB_R_FF", "shortDesc": "Specific total energy balance rate feedforward gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "max": 15.0, "min": 1.0, "name": "FW_T_SINK_MAX", "shortDesc": "Maximum descent rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Longitudinal Control", "increment": 0.1, "longDesc": "For the airspeed filter in TECS.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_DEV_STD", "shortDesc": "Airspeed rate measurement standard deviation", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Longitudinal Control", "increment": 0.1, "longDesc": "This is defining the noise in the airspeed rate for the constant airspeed rate model\nof the TECS airspeed filter.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_PRC_STD", "shortDesc": "Process noise standard deviation for the airspeed rate", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.07, "group": "FW Longitudinal Control", "increment": 0.1, "longDesc": "For the airspeed filter in TECS.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_STD", "shortDesc": "Airspeed measurement standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "This filter is applied to the specific total energy rate used for throttle damping.", "max": 2.0, "min": 0.0, "name": "FW_T_STE_R_TC", "shortDesc": "Specific total energy rate first order filter time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "min": 2.0, "name": "FW_T_TAS_TC", "shortDesc": "True airspeed error time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "This is the damping gain for the throttle demand loop.", "max": 1.0, "min": 0.0, "name": "FW_T_THR_DAMPING", "shortDesc": "Throttle damping factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.02, "group": "FW Longitudinal Control", "increment": 0.005, "longDesc": "Increase it to trim out speed and height offsets faster,\nwith the downside of possible overshoots and oscillations.", "max": 1.0, "min": 0.0, "name": "FW_T_THR_INTEG", "shortDesc": "Integrator gain throttle", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW Longitudinal Control", "increment": 1.0, "longDesc": "Height above ground threshold below which tighter altitude\ntracking gets enabled (see FW_LND_THRTC_SC). Below this height, TECS smoothly\n(1 sec / sec) transitions the altitude tracking time constant from FW_T_ALT_TC\nto FW_LND_THRTC_SC*FW_T_ALT_TC.\n-1 to disable.", "min": -1.0, "name": "FW_T_THR_LOW_HGT", "shortDesc": "Low-height threshold for tighter altitude tracking", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 7.0, "group": "FW Longitudinal Control", "increment": 0.5, "longDesc": "This is the maximum vertical acceleration\neither up or down that the controller will use to correct speed\nor height errors.", "max": 10.0, "min": 1.0, "name": "FW_T_VERT_ACC", "shortDesc": "Maximum vertical acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "Multiplying this factor with the current absolute wind estimate gives the airspeed offset\nadded to the minimum airspeed setpoint limit. This helps to make the\nsystem more robust against disturbances (turbulence) in high wind.", "min": 0.0, "name": "FW_WIND_ARSP_SC", "shortDesc": "Wind-based airspeed scaling factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "FW NPFG Control", "increment": 0.01, "longDesc": "Damping ratio of NPFG control law.", "max": 1.0, "min": 0.1, "name": "NPFG_DAMPING", "shortDesc": "NPFG damping ratio", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Avoids limit cycling from a too aggressively tuned period/damping combination.\nIf false, also disables upper bound NPFG_PERIOD_UB.", "name": "NPFG_LB_PERIOD", "shortDesc": "Enable automatic lower bound on the NPFG period", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW NPFG Control", "increment": 0.1, "longDesc": "Period of NPFG control law.", "max": 100.0, "min": 1.0, "name": "NPFG_PERIOD", "shortDesc": "NPFG period", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "FW NPFG Control", "increment": 0.1, "longDesc": "Multiplied by period for conservative minimum period bounding (when period lower\nbounding is enabled). 1.0 bounds at marginal stability.", "max": 10.0, "min": 1.0, "name": "NPFG_PERIOD_SF", "shortDesc": "Period safety factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW NPFG Control", "increment": 0.05, "longDesc": "Time constant of roll controller command / response, modeled as first order delay.\nUsed to determine lower period bound. Setting zero disables automatic period bounding.", "max": 2.0, "min": 0.0, "name": "NPFG_ROLL_TC", "shortDesc": "Roll time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.32, "group": "FW NPFG Control", "increment": 0.01, "longDesc": "Multiplied by the track error boundary to determine when the aircraft switches\nto the next waypoint and/or path segment. Should be less than 1.", "max": 1.0, "min": 0.1, "name": "NPFG_SW_DST_MLT", "shortDesc": "NPFG switch distance multiplier", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Adapts period to maintain track keeping in variable winds and path curvature.", "name": "NPFG_UB_PERIOD", "shortDesc": "Enable automatic upper bound on the NPFG period", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Factor applied to the minimum and stall airspeed when flaps are fully deployed.", "max": 1.0, "min": 0.5, "name": "FW_AIRSPD_FLP_SC", "shortDesc": "Airspeed scale with full flaps", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The maximal airspeed (calibrated airspeed) the user is able to command.", "min": 0.5, "name": "FW_AIRSPD_MAX", "shortDesc": "Maximum Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The minimal airspeed (calibrated airspeed) the user is able to command.\nFurther, if the airspeed falls below this value, the TECS controller will try to\nincrease airspeed more aggressively.\nHas to be set according to the vehicle's stall speed (which should be set in FW_AIRSPD_STALL),\nwith some margin between the stall speed and minimum airspeed.\nThis value corresponds to the desired minimum speed with the default load factor (level flight, default weight),\nand is automatically adpated to the current load factor (calculated from roll setpoint and WEIGHT_GROSS/WEIGHT_BASE).", "min": 0.5, "name": "FW_AIRSPD_MIN", "shortDesc": "Minimum Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 7.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The stall airspeed (calibrated airspeed) of the vehicle.\nIt is used for airspeed sensor failure detection and for the control\nsurface scaling airspeed limits.", "min": 0.5, "name": "FW_AIRSPD_STALL", "shortDesc": "Stall Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The trim CAS (calibrated airspeed) of the vehicle. If an airspeed controller is active,\nthis is the default airspeed setpoint that the controller will try to achieve.\nThis value corresponds to the trim airspeed with the default load factor (level flight, default weight).", "min": 0.5, "name": "FW_AIRSPD_TRIM", "shortDesc": "Trim (Cruise) Airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW Performance", "increment": 1.0, "longDesc": "Altitude in standard atmosphere at which the vehicle in normal configuration (WEIGHT_BASE) is still able to achieve a maximum climb rate of\n0.5m/s at maximum throttle (FW_THR_MAX). Used to compensate for air density in FW_T_CLMB_MAX.\nSet negative to disable.", "min": -1.0, "name": "FW_SERVICE_CEIL", "shortDesc": "Service ceiling", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at maximum airspeed FW_AIRSPD_MAX\nSet to 0 to disable mapping of airspeed to trim throttle.", "max": 1.0, "min": 0.0, "name": "FW_THR_ASPD_MAX", "shortDesc": "Throttle at max airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at minimum airspeed FW_AIRSPD_MIN\nSet to 0 to disable mapping of airspeed to trim throttle below FW_AIRSPD_TRIM.", "max": 1.0, "min": 0.0, "name": "FW_THR_ASPD_MIN", "shortDesc": "Throttle at min airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at FW_AIRSPD_TRIM", "max": 1.0, "min": 0.0, "name": "FW_THR_TRIM", "shortDesc": "Trim throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the maximum calibrated climb rate that the aircraft can achieve with\nthe throttle set to FW_THR_MAX and the airspeed set to the\ntrim value. For electric aircraft make sure this number can be\nachieved towards the end of flight when the battery voltage has reduced.", "min": 1.0, "name": "FW_T_CLMB_MAX", "shortDesc": "Maximum climb rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the minimum calibrated sink rate of the aircraft with the throttle\nset to THR_MIN and flown at the same airspeed as used\nto measure FW_T_CLMB_MAX.", "min": 1.0, "name": "FW_T_SINK_MIN", "shortDesc": "Minimum descent rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the weight of the vehicle at which it's performance limits were derived. A zero or negative value\ndisables trim throttle and minimum airspeed compensation based on weight.", "name": "WEIGHT_BASE", "shortDesc": "Vehicle base weight", "type": "Float", "units": "kg"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Performance", "increment": 0.1, "longDesc": "This is the actual weight of the vehicle at any time. This value will differ from WEIGHT_BASE in case weight was added\nor removed from the base weight. Examples are the addition of payloads or larger batteries. A zero or negative value\ndisables trim throttle and minimum airspeed compensation based on weight.", "name": "WEIGHT_GROSS", "shortDesc": "Vehicle gross weight", "type": "Float", "units": "kg"}, {"category": "Standard", "default": 90.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_X_MAX", "shortDesc": "Acro body roll max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "If this parameter is set to 1, the yaw rate controller is enabled in Fixed-wing Acro mode.\nOtherwise the pilot commands directly the yaw actuator.\nIt is disabled by default because an active yaw rate controller will fight against the\nnatural turn coordination of the plane.", "name": "FW_ACRO_YAW_EN", "shortDesc": "Enable yaw rate controller in Acro", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 90.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_Y_MAX", "shortDesc": "Acro body pitch max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 45.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_Z_MAX", "shortDesc": "Acro body yaw max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "longDesc": "This enables a logic that automatically adjusts the output of the rate controller to take\ninto account the real torque produced by an aerodynamic control surface given\nthe current deviation from the trim airspeed (FW_AIRSPD_TRIM).\nEnable when using aerodynamic control surfaces (e.g.: plane)\nDisable when using rotor wings (e.g.: autogyro)", "name": "FW_ARSP_SCALE_EN", "shortDesc": "Enable airspeed scaling", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "This compensates for voltage drop of the battery over time by attempting to\nnormalize performance across the operating range of the battery.", "name": "FW_BAT_SCALE_EN", "shortDesc": "Enable throttle scale by battery level", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_P_VMAX", "shortDesc": "Pitch trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_P_VMIN", "shortDesc": "Pitch trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_R_VMAX", "shortDesc": "Roll trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_R_VMIN", "shortDesc": "Roll trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_Y_VMAX", "shortDesc": "Yaw trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_Y_VMIN", "shortDesc": "Yaw trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired pitch actuator command in full manual mode. This parameter allows\nto adjust the throws of the control surfaces.", "min": 0.0, "name": "FW_MAN_P_SC", "shortDesc": "Manual pitch scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired roll actuator command in full manual mode. This parameter allows\nto adjust the throws of the control surfaces.", "max": 1.0, "min": 0.0, "name": "FW_MAN_R_SC", "shortDesc": "Manual roll scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows\nto adjust the throws of the control surfaces.", "min": 0.0, "name": "FW_MAN_Y_SC", "shortDesc": "Manual yaw scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "longDesc": "Pitch rate differential gain.", "max": 10.0, "min": 0.0, "name": "FW_PR_D", "shortDesc": "Pitch rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output", "max": 10.0, "min": 0.0, "name": "FW_PR_FF", "shortDesc": "Pitch rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_PR_I", "shortDesc": "Pitch rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_PR_IMAX", "shortDesc": "Pitch rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.08, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_PR_P", "shortDesc": "Pitch rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This gain can be used to counteract the \"adverse yaw\" effect for fixed wings.\nWhen the plane enters a roll it will tend to yaw the nose out of the turn.\nThis gain enables the use of a yaw actuator to counteract this effect.", "min": 0.0, "name": "FW_RLL_TO_YAW_FF", "shortDesc": "Roll control to yaw control feedforward gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_RR_D", "shortDesc": "Roll rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output.", "max": 10.0, "min": 0.0, "name": "FW_RR_FF", "shortDesc": "Roll rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW Rate Control", "increment": 0.01, "max": 10.0, "min": 0.0, "name": "FW_RR_I", "shortDesc": "Roll rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_RR_IMAX", "shortDesc": "Roll integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_RR_P", "shortDesc": "Roll rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "Chose source for manual setting of spoilers in manual flight modes.", "name": "FW_SPOILERS_MAN", "shortDesc": "Spoiler input in manual flight", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Flaps channel", "value": 1}, {"description": "Aux1", "value": 2}]}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "longDesc": "If set to 1, the airspeed measurement data, if valid, is used in the following controllers:\n- Rate controller: output scaling\n- Attitude controller: coordinated turn controller\n- Position controller: airspeed setpoint tracking, takeoff logic\n- VTOL: transition logic", "name": "FW_USE_AIRSPD", "shortDesc": "Use airspeed for control", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_YR_D", "shortDesc": "Yaw rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output", "max": 10.0, "min": 0.0, "name": "FW_YR_FF", "shortDesc": "Yaw rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.1, "group": "FW Rate Control", "increment": 0.5, "max": 10.0, "min": 0.0, "name": "FW_YR_I", "shortDesc": "Yaw rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_YR_IMAX", "shortDesc": "Yaw rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_YR_P", "shortDesc": "Yaw rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 1, "group": "Failure Detector", "longDesc": "If enabled, failure detector will verify that for motors, a minimum amount of ESC current per throttle\nlevel is being consumed.\nOtherwise this indicates an motor failure.", "name": "FD_ACT_EN", "rebootRequired": true, "shortDesc": "Enable Actuator Failure check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Failure Detector", "increment": 1.0, "longDesc": "Motor failure triggers only below this current value", "max": 50.0, "min": 0.0, "name": "FD_ACT_MOT_C2T", "shortDesc": "Motor Failure Current/Throttle Threshold", "type": "Float", "units": "A/%"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Failure Detector", "increment": 0.01, "longDesc": "Motor failure triggers only above this throttle value.", "max": 1.0, "min": 0.0, "name": "FD_ACT_MOT_THR", "shortDesc": "Motor Failure Throttle Threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 100, "group": "Failure Detector", "increment": 100, "longDesc": "Motor failure triggers only if the throttle threshold and the\ncurrent to throttle threshold are violated for this time.", "max": 10000, "min": 10, "name": "FD_ACT_MOT_TOUT", "shortDesc": "Motor Failure Time Threshold", "type": "Int32", "units": "ms"}, {"category": "Standard", "default": 1, "group": "Failure Detector", "longDesc": "If enabled, failure detector will verify that all the ESCs have successfully armed when the vehicle has transitioned to the armed state.\nTimeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback is received the failure detector will auto disarm the vehicle.", "name": "FD_ESCS_EN", "shortDesc": "Enable checks on ESCs that report their arming state", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Failure Detector", "longDesc": "Enabled on either AUX5 or MAIN5 depending on board.\nExternal ATS is required by ASTM F3322-18.", "name": "FD_EXT_ATS_EN", "rebootRequired": true, "shortDesc": "Enable PWM input on for engaging failsafe from an external automatic trigger system (ATS)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1900, "group": "Failure Detector", "longDesc": "External ATS is required by ASTM F3322-18.", "name": "FD_EXT_ATS_TRIG", "shortDesc": "The PWM threshold from external automatic trigger system for engaging failsafe", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 60, "group": "Failure Detector", "longDesc": "Maximum pitch angle before FailureDetector triggers the attitude_failure flag.\nThe flag triggers flight termination (if @CBRK_FLIGHTTERM = 0),\nwhich sets outputs to their failsafe values.\nOn takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM),\nwhich disarms motors but does not set outputs to failsafe values.\nSetting this parameter to 0 disables the check", "max": 180, "min": 0, "name": "FD_FAIL_P", "shortDesc": "FailureDetector Max Pitch", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Failure Detector", "longDesc": "Seconds (decimal) that pitch has to exceed FD_FAIL_P before being considered as a failure.", "max": 5.0, "min": 0.02, "name": "FD_FAIL_P_TTRI", "shortDesc": "Pitch failure trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 60, "group": "Failure Detector", "longDesc": "Maximum roll angle before FailureDetector triggers the attitude_failure flag.\nThe flag triggers flight termination (if @CBRK_FLIGHTTERM = 0),\nwhich sets outputs to their failsafe values.\nOn takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM),\nwhich disarms motors but does not set outputs to failsafe values.\nSetting this parameter to 0 disables the check", "max": 180, "min": 0, "name": "FD_FAIL_R", "shortDesc": "FailureDetector Max Roll", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Failure Detector", "longDesc": "Seconds (decimal) that roll has to exceed FD_FAIL_R before being considered as a failure.", "max": 5.0, "min": 0.02, "name": "FD_FAIL_R_TTRI", "shortDesc": "Roll failure trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 30, "group": "Failure Detector", "increment": 1, "longDesc": "Value at which the imbalanced propeller metric (based on horizontal and\nvertical acceleration variance) triggers a failure\nSetting this value to 0 disables the feature.", "max": 1000, "min": 0, "name": "FD_IMB_PROP_THR", "shortDesc": "Imbalanced propeller check threshold", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 1000.0, "group": "Flight Task Orbit", "increment": 0.5, "max": 10000.0, "min": 1.0, "name": "MC_ORBIT_RAD_MAX", "shortDesc": "Maximum radius of orbit", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Flight Task Orbit", "name": "MC_ORBIT_YAW_MOD", "shortDesc": "Yaw behaviour during orbit flight", "type": "Int32", "values": [{"description": "Front to Circle Center", "value": 0}, {"description": "Hold Initial Heading", "value": 1}, {"description": "Uncontrolled", "value": 2}, {"description": "Hold Front Tangent to Circle", "value": 3}, {"description": "RC Controlled", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Follow target", "longDesc": "Maintain altitude or track target's altitude. When maintaining the altitude,\nthe drone can crash into terrain when the target moves uphill. When tracking\nthe target's altitude, the follow altitude FLW_TGT_HT should be high enough\nto prevent terrain collisions due to GPS inaccuracies of the target.", "name": "FLW_TGT_ALT_M", "shortDesc": "Altitude control mode", "type": "Int32", "values": [{"description": "2D Tracking: Maintain constant altitude relative to home and track XY position only", "value": 0}, {"description": "2D + Terrain: Maintain constant altitude relative to terrain below and track XY position", "value": 1}, {"description": "3D Tracking: Track target's altitude (be aware that GPS altitude bias usually makes this useless)", "value": 2}]}, {"category": "Standard", "default": 8.0, "group": "Follow target", "longDesc": "The distance in meters to follow the target at", "min": 1.0, "name": "FLW_TGT_DST", "shortDesc": "Distance to follow target from", "type": "Float", "units": "m"}, {"category": "Standard", "default": 180.0, "group": "Follow target", "longDesc": "Angle to follow the target from. 0.0 Equals straight in front of the target's\ncourse (direction of motion) and the angle increases in clockwise direction,\nmeaning Right-side would be 90.0 degrees while Left-side is -90.0 degrees\nNote: When the user force sets the angle out of the min/max range, it will be\nwrapped (e.g. 480 -> 120) in the range to gracefully handle the out of range.", "max": 180.0, "min": -180.0, "name": "FLW_TGT_FA", "shortDesc": "Follow Angle setting in degrees", "type": "Float"}, {"category": "Standard", "default": 8.0, "group": "Follow target", "longDesc": "Following height above the target", "min": 8.0, "name": "FLW_TGT_HT", "shortDesc": "Follow target height", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Follow target", "longDesc": "This is the maximum tangential velocity the drone will circle around the target whenever\nan orbit angle setpoint changes. Higher value means more aggressive follow behavior.", "max": 20.0, "min": 0.0, "name": "FLW_TGT_MAX_VEL", "shortDesc": "Maximum tangential velocity setting for generating the follow orbit trajectory", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Follow target", "longDesc": "lower values increase the responsiveness to changing position, but also ignore less noise", "max": 1.0, "min": 0.0, "name": "FLW_TGT_RS", "shortDesc": "Responsiveness to target movement in Target Estimator", "type": "Float"}, {"bitmask": [{"description": "GPS (with QZSS)", "index": 0}, {"description": "SBAS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "BeiDou", "index": 3}, {"description": "GLONASS", "index": 4}, {"description": "NAVIC", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "longDesc": "This integer bitmask controls the set of GNSS systems used by the receiver. Check your\nreceiver's documentation on how many systems are supported to be used in parallel.\nCurrently this functionality is just implemented for u-blox receivers.\nWhen no bits are set, the receiver's default configuration should be used.\nSet bits true to enable:\n0 : Use GPS (with QZSS)\n1 : Use SBAS (multiple GPS augmentation systems)\n2 : Use Galileo\n3 : Use BeiDou\n4 : Use GLONASS\n5 : Use NAVIC", "max": 63, "min": 0, "name": "GPS_1_GNSS", "rebootRequired": true, "shortDesc": "GNSS Systems for Primary GPS (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Select the GPS protocol over serial.\nAuto-detection will probe all protocols, and thus is a bit slower.", "max": 7, "min": 0, "name": "GPS_1_PROTOCOL", "rebootRequired": true, "shortDesc": "Protocol for Main GPS", "type": "Int32", "values": [{"description": "Auto detect", "value": 0}, {"description": "u-blox", "value": 1}, {"description": "MTK", "value": 2}, {"description": "Ashtech / Trimble", "value": 3}, {"description": "Emlid Reach", "value": 4}, {"description": "Femtomes", "value": 5}, {"description": "NMEA (generic)", "value": 6}]}, {"bitmask": [{"description": "GPS (with QZSS)", "index": 0}, {"description": "SBAS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "BeiDou", "index": 3}, {"description": "GLONASS", "index": 4}, {"description": "NAVIC", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "longDesc": "This integer bitmask controls the set of GNSS systems used by the receiver. Check your\nreceiver's documentation on how many systems are supported to be used in parallel.\nCurrently this functionality is just implemented for u-blox receivers.\nWhen no bits are set, the receiver's default configuration should be used.\nSet bits true to enable:\n0 : Use GPS (with QZSS)\n1 : Use SBAS (multiple GPS augmentation systems)\n2 : Use Galileo\n3 : Use BeiDou\n4 : Use GLONASS\n5 : Use NAVIC", "max": 63, "min": 0, "name": "GPS_2_GNSS", "rebootRequired": true, "shortDesc": "GNSS Systems for Secondary GPS (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Select the GPS protocol over serial.\nAuto-detection will probe all protocols, and thus is a bit slower.", "max": 6, "min": 0, "name": "GPS_2_PROTOCOL", "rebootRequired": true, "shortDesc": "Protocol for Secondary GPS", "type": "Int32", "values": [{"description": "Auto detect", "value": 0}, {"description": "u-blox", "value": 1}, {"description": "MTK", "value": 2}, {"description": "Ashtech / Trimble", "value": 3}, {"description": "Emlid Reach", "value": 4}, {"description": "Femtomes", "value": 5}, {"description": "NMEA (generic)", "value": 6}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "If this is set to 1, all GPS communication data will be published via uORB,\nand written to the log file as gps_dump message.\nIf this is set to 2, the main GPS is configured to output RTCM data,\nwhich is then logged as gps_dump and can be used for PPK.", "max": 2, "min": 0, "name": "GPS_DUMP_COMM", "shortDesc": "Log GPS communication data", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Full communication", "value": 1}, {"description": "RTCM output (PPK)", "value": 2}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Enable publication of satellite info (ORB_ID(satellite_info)) if possible.\nNot available on MTK.", "name": "GPS_SAT_INFO", "rebootRequired": true, "shortDesc": "Enable sat info (if available)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 230400, "group": "GPS", "longDesc": "Select a baudrate for the F9P's UART2 port.\nIn GPS_UBX_MODE 1, 2, and 3, the F9P's UART2 port is configured to send/receive RTCM corrections.\nSet this to 57600 if you want to attach a telemetry radio on UART2.", "min": 0, "name": "GPS_UBX_BAUD2", "rebootRequired": true, "shortDesc": "u-blox F9P UART2 Baudrate", "type": "Int32", "units": "B/s"}, {"bitmask": [{"description": "Enable I2C input protocol UBX", "index": 0}, {"description": "Enable I2C input protocol NMEA", "index": 1}, {"description": "Enable I2C input protocol RTCM3X", "index": 2}, {"description": "Enable I2C output protocol UBX", "index": 3}, {"description": "Enable I2C output protocol NMEA", "index": 4}, {"description": "Enable I2C output protocol RTCM3X", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "max": 32, "min": 0, "name": "GPS_UBX_CFG_INTF", "rebootRequired": true, "shortDesc": "u-blox protocol configuration for interfaces", "type": "Int32"}, {"category": "Standard", "default": 7, "group": "GPS", "longDesc": "u-blox receivers support different dynamic platform models to adjust the navigation engine to\nthe expected application environment.", "max": 9, "min": 0, "name": "GPS_UBX_DYNMODEL", "rebootRequired": true, "shortDesc": "u-blox GPS dynamic platform model", "type": "Int32", "values": [{"description": "stationary", "value": 2}, {"description": "automotive", "value": 4}, {"description": "airborne with <1g acceleration", "value": 6}, {"description": "airborne with <2g acceleration", "value": 7}, {"description": "airborne with <4g acceleration", "value": 8}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Select the u-blox configuration setup. Most setups will use the default, including RTK and\ndual GPS without heading.\nIf rover has RTCM corrections from a static base (or other static correction source) coming in on UART2, then select Mode 5.\nThe Heading mode requires 2 F9P devices to be attached. The main GPS will act as rover and output\nheading information, whereas the secondary will act as moving base.\nModes 1 and 2 require each F9P UART1 to be connected to the Autopilot. In addition, UART2 on the\nF9P units are connected to each other.\nModes 3 and 4 only require UART1 on each F9P connected to the Autopilot or Can Node. UART RX DMA is required.\nRTK is still possible with this setup.", "max": 1, "min": 0, "name": "GPS_UBX_MODE", "rebootRequired": true, "shortDesc": "u-blox GPS Mode", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Heading (Rover With Moving Base UART1 Connected To Autopilot, UART2 Connected To Moving Base)", "value": 1}, {"description": "Moving Base (UART1 Connected To Autopilot, UART2 Connected To Rover)", "value": 2}, {"description": "Heading (Rover With Moving Base UART1 Connected to Autopilot Or Can Node At 921600)", "value": 3}, {"description": "Moving Base (Moving Base UART1 Connected to Autopilot Or Can Node At 921600)", "value": 4}, {"description": "Rover with Static Base on UART2 (similar to Default, except coming in on UART2)", "value": 5}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "GPS", "longDesc": "Heading offset angle for dual antenna GPS setups that support heading estimation.\nSet this to 0 if the antennas are parallel to the forward-facing direction\nof the vehicle and the rover (or Unicore primary) antenna is in front.\nThe offset angle increases clockwise.\nSet this to 90 if the rover (or Unicore primary, or Septentrio Mosaic Aux)\nantenna is placed on the right side of the vehicle and the moving base\nantenna is on the left side.\n(Note: the Unicore primary antenna is the one connected on the right as seen\nfrom the top).", "max": 360.0, "min": 0.0, "name": "GPS_YAW_OFFSET", "rebootRequired": true, "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Geofence", "longDesc": "Note: Setting this value to 4 enables flight termination,\nwhich will kill the vehicle on violation of the fence.", "max": 5, "min": 0, "name": "GF_ACTION", "shortDesc": "Geofence violation action", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold mode", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land mode", "value": 5}]}, {"category": "Standard", "default": 0.0, "group": "Geofence", "increment": 1.0, "longDesc": "Maximum horizontal distance in meters the vehicle can be from Home before triggering a geofence action.\nDisabled if 0.", "max": 10000.0, "min": 0.0, "name": "GF_MAX_HOR_DIST", "shortDesc": "Max horizontal distance from Home", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0.0, "group": "Geofence", "increment": 1.0, "longDesc": "Maximum vertical distance in meters the vehicle can be from Home before triggering a geofence action.\nDisabled if 0.", "max": 10000.0, "min": 0.0, "name": "GF_MAX_VER_DIST", "shortDesc": "Max vertical distance from Home", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geofence", "longDesc": "WARNING: This experimental feature may cause flyaways. Use at your own risk.\nPredict the motion of the vehicle and trigger the breach if it is determined that the current trajectory\nwould result in a breach happening before the vehicle can make evasive maneuvers.\nThe vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing).", "name": "GF_PREDICT", "shortDesc": "[EXPERIMENTAL] Use Pre-emptive geofence triggering", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Geofence", "longDesc": "Select which position source should be used. Selecting GPS instead of global position makes sure that there is\nno dependence on the position estimator\n0 = global position, 1 = GPS", "max": 1, "min": 0, "name": "GF_SOURCE", "shortDesc": "Geofence source", "type": "Int32", "values": [{"description": "GPOS", "value": 0}, {"description": "GPS", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines which mixer implementation to use.\nSome are generic, while others are specifically fit to a certain vehicle with a fixed set of actuators.\n'Custom' should only be used if noting else can be used.", "name": "CA_AIRFRAME", "shortDesc": "Airframe selection", "type": "Int32", "values": [{"description": "Multirotor", "value": 0}, {"description": "Fixed-wing", "value": 1}, {"description": "Standard VTOL", "value": 2}, {"description": "Tiltrotor VTOL", "value": 3}, {"description": "Tailsitter VTOL", "value": 4}, {"description": "Rover (Ackermann)", "value": 5}, {"description": "Rover (Differential)", "value": 6}, {"description": "Motors (6DOF)", "value": 7}, {"description": "Multirotor with Tilt", "value": 8}, {"description": "Custom", "value": 9}, {"description": "Helicopter (tail ESC)", "value": 10}, {"description": "Helicopter (tail Servo)", "value": 11}, {"description": "Helicopter (Coaxial)", "value": 12}, {"description": "Rover (Mecanum)", "value": 13}, {"description": "Spacecraft 2D", "value": 14}, {"description": "Spacecraft 3D", "value": 15}]}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "This is used to specify how to handle motor failures\nreported by failure detector.", "name": "CA_FAILURE_MODE", "shortDesc": "Motor failure handling mode", "type": "Int32", "values": [{"description": "Ignore", "value": 0}, {"description": "Remove first failed motor from effectiveness", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": -0.05, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 0 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C0", "shortDesc": "Collective pitch curve at position 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0725, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 1 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C1", "shortDesc": "Collective pitch curve at position 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 2 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C2", "shortDesc": "Collective pitch curve at position 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.325, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 3 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C3", "shortDesc": "Collective pitch curve at position 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.45, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 4 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C4", "shortDesc": "Collective pitch curve at position 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Same definition as the proportional gain but for integral.", "max": 10.0, "min": 0.0, "name": "CA_HELI_RPM_I", "shortDesc": "Integral gain for rpm control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Ratio between rpm error devided by 1000 to how much normalized output gets added to correct for it.\nmotor_command = throttle_curve + CA_HELI_RPM_P * (rpm_setpoint - rpm_measurement) / 1000", "max": 10.0, "min": 0.0, "name": "CA_HELI_RPM_P", "shortDesc": "Proportional gain for rpm control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": 1500.0, "group": "Geometry", "increment": 1.0, "longDesc": "Requires rpm feedback for the controller.", "max": 10000.0, "min": 100.0, "name": "CA_HELI_RPM_SP", "shortDesc": "Setpoint for main rotor rpm", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 0.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C0", "shortDesc": "Throttle curve at position 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 1.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C1", "shortDesc": "Throttle curve at position 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 2.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C2", "shortDesc": "Throttle curve at position 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 3.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C3", "shortDesc": "Throttle curve at position 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 4.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C4", "shortDesc": "Throttle curve at position 4", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Default configuration is for a clockwise turning main rotor and\npositive thrust of the tail rotor is expected to rotate the vehicle clockwise.\nSet this parameter to true if the tail rotor provides thrust in counter-clockwise direction\nwhich is mostly the case when the main rotor turns counter-clockwise.", "name": "CA_HELI_YAW_CCW", "shortDesc": "Main rotor turns counter-clockwise", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to specify which collective pitch command results in the least amount of rotor drag.\nThis is used to increase the accuracy of the yaw drag torque compensation based on collective pitch\nby aligning the lowest rotor drag with zero compensation.\nFor symmetric profile blades this is the command that results in exactly 0\u00b0 collective blade angle.\nFor lift profile blades this is typically a command resulting in slightly negative collective blade angle.\ntail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O)", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_CP_O", "shortDesc": "Offset for yaw compensation based on collective pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to add a proportional factor of the collective pitch command to the yaw command.\nA negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction.\ntail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O)", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_CP_S", "shortDesc": "Scale for yaw compensation based on collective pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to add a proportional factor of the throttle command to the yaw command.\nA negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction.\ntail_output += CA_HELI_YAW_TH_S * throttle", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_TH_S", "shortDesc": "Scale for yaw compensation based on throttle", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Used to linearize mechanical output of swashplate servos to avoid axis coupling and binding with 4 servo redundancy.\nThis requires a symmetric setup where the servo horn is exactly centered with a 0 command.\nSetting to zero disables feature.", "max": 75.0, "min": 0.0, "name": "CA_MAX_SVO_THROW", "shortDesc": "Throw angle of swashplate servo at maximum commands for linearization", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Geometry", "longDesc": "Selects the algorithm and desaturation method.\nIf set to Automatic, the selection is based on the airframe (CA_AIRFRAME).", "name": "CA_METHOD", "shortDesc": "Control allocation method", "type": "Int32", "values": [{"description": "Pseudo-inverse with output clipping", "value": 0}, {"description": "Pseudo-inverse with sequential desaturation technique", "value": 1}, {"description": "Automatic", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R0_SLEW", "shortDesc": "Motor 0 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R10_SLEW", "shortDesc": "Motor 10 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R11_SLEW", "shortDesc": "Motor 11 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R1_SLEW", "shortDesc": "Motor 1 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R2_SLEW", "shortDesc": "Motor 2 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R3_SLEW", "shortDesc": "Motor 3 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R4_SLEW", "shortDesc": "Motor 4 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R5_SLEW", "shortDesc": "Motor 5 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R6_SLEW", "shortDesc": "Motor 6 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R7_SLEW", "shortDesc": "Motor 7 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R8_SLEW", "shortDesc": "Motor 8 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R9_SLEW", "shortDesc": "Motor 9 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AX", "shortDesc": "Axis of rotor 0 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AY", "shortDesc": "Axis of rotor 0 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AZ", "shortDesc": "Axis of rotor 0 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR0_CT", "shortDesc": "Thrust coefficient of rotor 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR0_KM", "shortDesc": "Moment coefficient of rotor 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PX", "shortDesc": "Position of rotor 0 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PY", "shortDesc": "Position of rotor 0 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PZ", "shortDesc": "Position of rotor 0 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR0_TILT", "shortDesc": "Rotor 0 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AX", "shortDesc": "Axis of rotor 10 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AY", "shortDesc": "Axis of rotor 10 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AZ", "shortDesc": "Axis of rotor 10 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR10_CT", "shortDesc": "Thrust coefficient of rotor 10", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR10_KM", "shortDesc": "Moment coefficient of rotor 10", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PX", "shortDesc": "Position of rotor 10 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PY", "shortDesc": "Position of rotor 10 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PZ", "shortDesc": "Position of rotor 10 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR10_TILT", "shortDesc": "Rotor 10 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AX", "shortDesc": "Axis of rotor 11 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AY", "shortDesc": "Axis of rotor 11 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AZ", "shortDesc": "Axis of rotor 11 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR11_CT", "shortDesc": "Thrust coefficient of rotor 11", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR11_KM", "shortDesc": "Moment coefficient of rotor 11", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PX", "shortDesc": "Position of rotor 11 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PY", "shortDesc": "Position of rotor 11 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PZ", "shortDesc": "Position of rotor 11 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR11_TILT", "shortDesc": "Rotor 11 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AX", "shortDesc": "Axis of rotor 1 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AY", "shortDesc": "Axis of rotor 1 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AZ", "shortDesc": "Axis of rotor 1 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR1_CT", "shortDesc": "Thrust coefficient of rotor 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR1_KM", "shortDesc": "Moment coefficient of rotor 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PX", "shortDesc": "Position of rotor 1 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PY", "shortDesc": "Position of rotor 1 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PZ", "shortDesc": "Position of rotor 1 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR1_TILT", "shortDesc": "Rotor 1 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AX", "shortDesc": "Axis of rotor 2 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AY", "shortDesc": "Axis of rotor 2 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AZ", "shortDesc": "Axis of rotor 2 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR2_CT", "shortDesc": "Thrust coefficient of rotor 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR2_KM", "shortDesc": "Moment coefficient of rotor 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PX", "shortDesc": "Position of rotor 2 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PY", "shortDesc": "Position of rotor 2 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PZ", "shortDesc": "Position of rotor 2 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR2_TILT", "shortDesc": "Rotor 2 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AX", "shortDesc": "Axis of rotor 3 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AY", "shortDesc": "Axis of rotor 3 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AZ", "shortDesc": "Axis of rotor 3 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR3_CT", "shortDesc": "Thrust coefficient of rotor 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR3_KM", "shortDesc": "Moment coefficient of rotor 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PX", "shortDesc": "Position of rotor 3 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PY", "shortDesc": "Position of rotor 3 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PZ", "shortDesc": "Position of rotor 3 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR3_TILT", "shortDesc": "Rotor 3 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AX", "shortDesc": "Axis of rotor 4 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AY", "shortDesc": "Axis of rotor 4 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AZ", "shortDesc": "Axis of rotor 4 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR4_CT", "shortDesc": "Thrust coefficient of rotor 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR4_KM", "shortDesc": "Moment coefficient of rotor 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PX", "shortDesc": "Position of rotor 4 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PY", "shortDesc": "Position of rotor 4 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PZ", "shortDesc": "Position of rotor 4 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR4_TILT", "shortDesc": "Rotor 4 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AX", "shortDesc": "Axis of rotor 5 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AY", "shortDesc": "Axis of rotor 5 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AZ", "shortDesc": "Axis of rotor 5 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR5_CT", "shortDesc": "Thrust coefficient of rotor 5", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR5_KM", "shortDesc": "Moment coefficient of rotor 5", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PX", "shortDesc": "Position of rotor 5 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PY", "shortDesc": "Position of rotor 5 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PZ", "shortDesc": "Position of rotor 5 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR5_TILT", "shortDesc": "Rotor 5 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AX", "shortDesc": "Axis of rotor 6 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AY", "shortDesc": "Axis of rotor 6 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AZ", "shortDesc": "Axis of rotor 6 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR6_CT", "shortDesc": "Thrust coefficient of rotor 6", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR6_KM", "shortDesc": "Moment coefficient of rotor 6", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PX", "shortDesc": "Position of rotor 6 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PY", "shortDesc": "Position of rotor 6 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PZ", "shortDesc": "Position of rotor 6 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR6_TILT", "shortDesc": "Rotor 6 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AX", "shortDesc": "Axis of rotor 7 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AY", "shortDesc": "Axis of rotor 7 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AZ", "shortDesc": "Axis of rotor 7 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR7_CT", "shortDesc": "Thrust coefficient of rotor 7", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR7_KM", "shortDesc": "Moment coefficient of rotor 7", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PX", "shortDesc": "Position of rotor 7 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PY", "shortDesc": "Position of rotor 7 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PZ", "shortDesc": "Position of rotor 7 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR7_TILT", "shortDesc": "Rotor 7 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AX", "shortDesc": "Axis of rotor 8 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AY", "shortDesc": "Axis of rotor 8 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AZ", "shortDesc": "Axis of rotor 8 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR8_CT", "shortDesc": "Thrust coefficient of rotor 8", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR8_KM", "shortDesc": "Moment coefficient of rotor 8", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PX", "shortDesc": "Position of rotor 8 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PY", "shortDesc": "Position of rotor 8 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PZ", "shortDesc": "Position of rotor 8 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR8_TILT", "shortDesc": "Rotor 8 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AX", "shortDesc": "Axis of rotor 9 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AY", "shortDesc": "Axis of rotor 9 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AZ", "shortDesc": "Axis of rotor 9 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR9_CT", "shortDesc": "Thrust coefficient of rotor 9", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR9_KM", "shortDesc": "Moment coefficient of rotor 9", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PX", "shortDesc": "Position of rotor 9 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PY", "shortDesc": "Position of rotor 9 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PZ", "shortDesc": "Position of rotor 9 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR9_TILT", "shortDesc": "Rotor 9 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_ROTOR_COUNT", "shortDesc": "Total number of rotors", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}, {"description": "5", "value": 5}, {"description": "6", "value": 6}, {"description": "7", "value": 7}, {"description": "8", "value": 8}, {"description": "9", "value": 9}, {"description": "10", "value": 10}, {"description": "11", "value": 11}, {"description": "12", "value": 12}]}, {"bitmask": [{"description": "Motor 1", "index": 0}, {"description": "Motor 2", "index": 1}, {"description": "Motor 3", "index": 2}, {"description": "Motor 4", "index": 3}, {"description": "Motor 5", "index": 4}, {"description": "Motor 6", "index": 5}, {"description": "Motor 7", "index": 6}, {"description": "Motor 8", "index": 7}, {"description": "Motor 9", "index": 8}, {"description": "Motor 10", "index": 9}, {"description": "Motor 11", "index": 10}, {"description": "Motor 12", "index": 11}], "category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Configure motors to be bidirectional/reversible. Note that the output driver needs to support this as well.", "max": 4095, "min": 0, "name": "CA_R_REV", "shortDesc": "Bidirectional/Reversible motors", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG0", "shortDesc": "Angle for swash plate servo 0", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 140.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG1", "shortDesc": "Angle for swash plate servo 1", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 220.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG2", "shortDesc": "Angle for swash plate servo 2", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG3", "shortDesc": "Angle for swash plate servo 3", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L0", "shortDesc": "Arm length for swash plate servo 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L1", "shortDesc": "Arm length for swash plate servo 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L2", "shortDesc": "Arm length for swash plate servo 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L3", "shortDesc": "Arm length for swash plate servo 3", "type": "Float"}, {"category": "Standard", "default": 3, "group": "Geometry", "name": "CA_SP0_COUNT", "shortDesc": "Number of swash plates servos", "type": "Int32", "values": [{"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV0_SLEW", "shortDesc": "Servo 0 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV1_SLEW", "shortDesc": "Servo 1 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV2_SLEW", "shortDesc": "Servo 2 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV3_SLEW", "shortDesc": "Servo 3 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV4_SLEW", "shortDesc": "Servo 4 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV5_SLEW", "shortDesc": "Servo 5 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV6_SLEW", "shortDesc": "Servo 6 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV7_SLEW", "shortDesc": "Servo 7 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_FLAP", "shortDesc": "Control Surface 0 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_SPOIL", "shortDesc": "Control Surface 0 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_TRIM", "shortDesc": "Control Surface 0 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_P", "shortDesc": "Control Surface 0 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_R", "shortDesc": "Control Surface 0 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_Y", "shortDesc": "Control Surface 0 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS0_TYPE", "shortDesc": "Control Surface 0 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_FLAP", "shortDesc": "Control Surface 1 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_SPOIL", "shortDesc": "Control Surface 1 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_TRIM", "shortDesc": "Control Surface 1 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_P", "shortDesc": "Control Surface 1 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_R", "shortDesc": "Control Surface 1 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_Y", "shortDesc": "Control Surface 1 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS1_TYPE", "shortDesc": "Control Surface 1 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_FLAP", "shortDesc": "Control Surface 2 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_SPOIL", "shortDesc": "Control Surface 2 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_TRIM", "shortDesc": "Control Surface 2 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_P", "shortDesc": "Control Surface 2 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_R", "shortDesc": "Control Surface 2 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_Y", "shortDesc": "Control Surface 2 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS2_TYPE", "shortDesc": "Control Surface 2 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_FLAP", "shortDesc": "Control Surface 3 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_SPOIL", "shortDesc": "Control Surface 3 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_TRIM", "shortDesc": "Control Surface 3 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_P", "shortDesc": "Control Surface 3 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_R", "shortDesc": "Control Surface 3 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_Y", "shortDesc": "Control Surface 3 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS3_TYPE", "shortDesc": "Control Surface 3 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_FLAP", "shortDesc": "Control Surface 4 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_SPOIL", "shortDesc": "Control Surface 4 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_TRIM", "shortDesc": "Control Surface 4 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_P", "shortDesc": "Control Surface 4 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_R", "shortDesc": "Control Surface 4 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_Y", "shortDesc": "Control Surface 4 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS4_TYPE", "shortDesc": "Control Surface 4 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_FLAP", "shortDesc": "Control Surface 5 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_SPOIL", "shortDesc": "Control Surface 5 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_TRIM", "shortDesc": "Control Surface 5 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_P", "shortDesc": "Control Surface 5 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_R", "shortDesc": "Control Surface 5 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_Y", "shortDesc": "Control Surface 5 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS5_TYPE", "shortDesc": "Control Surface 5 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_FLAP", "shortDesc": "Control Surface 6 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_SPOIL", "shortDesc": "Control Surface 6 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_TRIM", "shortDesc": "Control Surface 6 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_P", "shortDesc": "Control Surface 6 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_R", "shortDesc": "Control Surface 6 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_Y", "shortDesc": "Control Surface 6 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS6_TYPE", "shortDesc": "Control Surface 6 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_FLAP", "shortDesc": "Control Surface 7 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_SPOIL", "shortDesc": "Control Surface 7 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_TRIM", "shortDesc": "Control Surface 7 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_P", "shortDesc": "Control Surface 7 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_R", "shortDesc": "Control Surface 7 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_Y", "shortDesc": "Control Surface 7 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS7_TYPE", "shortDesc": "Control Surface 7 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS_COUNT", "shortDesc": "Total number of Control Surfaces", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}, {"description": "5", "value": 5}, {"description": "6", "value": 6}, {"description": "7", "value": 7}, {"description": "8", "value": 8}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL0_CT", "shortDesc": "Tilt 0 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL0_MAXA", "shortDesc": "Tilt Servo 0 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL0_MINA", "shortDesc": "Tilt Servo 0 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle.\nFor example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front',\nthe motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL0_TD", "shortDesc": "Tilt Servo 0 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL1_CT", "shortDesc": "Tilt 1 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL1_MAXA", "shortDesc": "Tilt Servo 1 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL1_MINA", "shortDesc": "Tilt Servo 1 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle.\nFor example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front',\nthe motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL1_TD", "shortDesc": "Tilt Servo 1 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL2_CT", "shortDesc": "Tilt 2 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL2_MAXA", "shortDesc": "Tilt Servo 2 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL2_MINA", "shortDesc": "Tilt Servo 2 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle.\nFor example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front',\nthe motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL2_TD", "shortDesc": "Tilt Servo 2 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL3_CT", "shortDesc": "Tilt 3 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL3_MAXA", "shortDesc": "Tilt Servo 3 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL3_MINA", "shortDesc": "Tilt Servo 3 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle.\nFor example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front',\nthe motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL3_TD", "shortDesc": "Tilt Servo 3 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_TL_COUNT", "shortDesc": "Total number of Tilt Servos", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Hover Thrust Estimator", "longDesc": "Sets the number of standard deviations used\nby the innovation consistency test.", "max": 10.0, "min": 1.0, "name": "HTE_ACC_GATE", "shortDesc": "Gate size for acceleration fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Hover Thrust Estimator", "longDesc": "Sets the number of standard deviations used\nby the innovation consistency test.", "max": 1.0, "min": 0.0, "name": "HTE_HT_ERR_INIT", "shortDesc": "1-sigma initial hover thrust uncertainty", "type": "Float", "units": "normalized_thrust"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0036, "group": "Hover Thrust Estimator", "longDesc": "Reduce to make the hover thrust estimate\nmore stable, increase if the real hover thrust\nis expected to change quickly over time.", "max": 1.0, "min": 0.0001, "name": "HTE_HT_NOISE", "shortDesc": "Hover thrust process noise", "type": "Float", "units": "normalized_thrust/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Hover Thrust Estimator", "longDesc": "Defines the range of the hover thrust estimate around MPC_THR_HOVER.\nA value of 0.2 with MPC_THR_HOVER at 0.5 results in a range of [0.3, 0.7].\nSet to a large value if the vehicle operates in varying physical conditions that\naffect the required hover thrust strongly (e.g. differently sized payloads).", "max": 0.4, "min": 0.01, "name": "HTE_THR_RANGE", "shortDesc": "Max deviation from MPC_THR_HOVER", "type": "Float", "units": "normalized_thrust"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Hover Thrust Estimator", "longDesc": "Above this speed, the measurement noise is linearly increased\nto reduce the sensitivity of the estimator from biased measurement.\nSet to a low value on vehicles with large lifting surfaces.", "max": 20.0, "min": 1.0, "name": "HTE_VXY_THR", "shortDesc": "Horizontal velocity threshold for sensitivity reduction", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Hover Thrust Estimator", "longDesc": "Above this speed, the measurement noise is linearly increased\nto reduce the sensitivity of the estimator from biased measurement.\nSet to a low value on vehicles affected by air drag when climbing or descending.", "max": 10.0, "min": 1.0, "name": "HTE_VZ_THR", "shortDesc": "Vertical velocity threshold for sensitivity reduction", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.0, "group": "Land Detector", "longDesc": "Maximum airspeed allowed in the landed state", "max": 30.0, "min": 2.0, "name": "LNDFW_AIRSPD_MAX", "shortDesc": "Fixed-wing land detector: Max airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Land Detector", "longDesc": "Maximum allowed norm of the angular velocity in the landed state.\nOnly used if neither airspeed nor groundspeed can be used for landing detection.", "name": "LNDFW_ROT_MAX", "shortDesc": "Fixed-wing land detector: max rotational speed", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Land Detector", "longDesc": "Time the land conditions (speeds and acceleration) have to be satisfied to detect a landing.", "min": 0.1, "name": "LNDFW_TRIG_TIME", "rebootRequired": true, "shortDesc": "Fixed-wing land detection trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Land Detector", "longDesc": "Maximum horizontal velocity allowed in the landed state.\nA factor of 0.7 is applied in case of airspeed-less flying\n(either because no sensor is present or sensor data got invalid in flight).", "max": 20.0, "min": 0.5, "name": "LNDFW_VEL_XY_MAX", "shortDesc": "Fixed-wing land detector: Max horizontal velocity threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Land Detector", "longDesc": "Maximum vertical velocity allowed in the landed state.", "max": 20.0, "min": 0.1, "name": "LNDFW_VEL_Z_MAX", "shortDesc": "Fixed-wing land detector: Max vertiacal velocity threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 8.0, "group": "Land Detector", "longDesc": "Maximum horizontal (x,y body axes) acceleration allowed in the landed state", "max": 30.0, "min": 2.0, "name": "LNDFW_XYACC_MAX", "shortDesc": "Fixed-wing land detector: Max horizontal acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Land Detector", "longDesc": "The height above ground below which ground effect creates barometric altitude errors.\nA negative value indicates no ground effect.", "min": -1.0, "name": "LNDMC_ALT_GND", "shortDesc": "Ground effect altitude for multicopters", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Land Detector", "longDesc": "Maximum allowed norm of the angular velocity (roll, pitch) in the landed state.", "name": "LNDMC_ROT_MAX", "shortDesc": "Multicopter max rotational speed", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Land Detector", "longDesc": "Total time it takes to go through all three land detection stages:\nground contact, maybe landed, landed\nwhen all necessary conditions are constantly met.", "max": 10.0, "min": 0.1, "name": "LNDMC_TRIG_TIME", "shortDesc": "Multicopter land detection trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Land Detector", "longDesc": "Maximum horizontal velocity allowed in the landed state", "name": "LNDMC_XY_VEL_MAX", "shortDesc": "Multicopter max horizontal velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "Land Detector", "longDesc": "Vertical velocity threshold to detect landing.\nHas to be set lower than the expected minimal speed for landing,\nwhich is either MPC_LAND_SPEED or MPC_LAND_CRWL.\nThis is enforced by an automatic check.", "min": 0.0, "name": "LNDMC_Z_VEL_MAX", "shortDesc": "Multicopter vertical velocity threshold", "type": "Float", "units": "m/s"}, {"category": "System", "default": 0, "group": "Land Detector", "longDesc": "Total flight time of this autopilot. Higher 32 bits of the value.\nFlight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO.", "min": 0, "name": "LND_FLIGHT_T_HI", "shortDesc": "Total flight time in microseconds", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Land Detector", "longDesc": "Total flight time of this autopilot. Lower 32 bits of the value.\nFlight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO.", "min": 0, "name": "LND_FLIGHT_T_LO", "shortDesc": "Total flight time in microseconds", "type": "Int32", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Landing Target Estimator", "longDesc": "Variance of acceleration measurement used for landing target position prediction.\nHigher values results in tighter following of the measurements and more lenient outlier rejection", "min": 0.01, "name": "LTEST_ACC_UNC", "shortDesc": "Acceleration uncertainty", "type": "Float", "units": "(m/s^2)^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.005, "group": "Landing Target Estimator", "longDesc": "Variance of the landing target measurement from the driver.\nHigher values result in less aggressive following of the measurement and a smoother output as well as fewer rejected measurements.", "name": "LTEST_MEAS_UNC", "shortDesc": "Landing target measurement uncertainty", "type": "Float", "units": "tan(rad)^2"}, {"category": "Standard", "default": 0, "group": "Landing Target Estimator", "longDesc": "Configure the mode of the landing target. Depending on the mode, the landing target observations are used differently to aid position estimation.\nMode Moving: The landing target may be moving around while in the field of view of the vehicle. Landing target measurements are not used to aid positioning.\nMode Stationary: The landing target is stationary. Measured velocity w.r.t. the landing target is used to aid velocity estimation.", "max": 1, "min": 0, "name": "LTEST_MODE", "shortDesc": "Landing target mode", "type": "Int32", "values": [{"description": "Moving", "value": 0}, {"description": "Stationary", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Landing Target Estimator", "longDesc": "Initial variance of the relative landing target position in x and y direction", "min": 0.001, "name": "LTEST_POS_UNC_IN", "shortDesc": "Initial landing target position uncertainty", "type": "Float", "units": "m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Landing Target Estimator", "longDesc": "Landing target x measurements are scaled by this factor before being used", "min": 0.01, "name": "LTEST_SCALE_X", "shortDesc": "Scale factor for sensor measurements in sensor x axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Landing Target Estimator", "longDesc": "Landing target y measurements are scaled by this factor before being used", "min": 0.01, "name": "LTEST_SCALE_Y", "shortDesc": "Scale factor for sensor measurements in sensor y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_X", "rebootRequired": true, "shortDesc": "X Position of IRLOCK in body frame (forward)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_Y", "rebootRequired": true, "shortDesc": "Y Position of IRLOCK in body frame (right)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_Z", "rebootRequired": true, "shortDesc": "Z Position of IRLOCK in body frame (downward)", "type": "Float", "units": "m"}, {"category": "Standard", "default": 2, "group": "Landing Target Estimator", "longDesc": "Default orientation of Yaw 90\u00b0", "max": 40, "min": -1, "name": "LTEST_SENS_ROT", "rebootRequired": true, "shortDesc": "Rotation of IRLOCK sensor relative to airframe", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Landing Target Estimator", "longDesc": "Initial variance of the relative landing target velocity in x and y directions", "min": 0.001, "name": "LTEST_VEL_UNC_IN", "shortDesc": "Initial landing target velocity uncertainty", "type": "Float", "units": "(m/s)^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.012, "group": "Local Position Estimator", "longDesc": "Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)\nLarger than data sheet to account for tilt error.", "max": 2.0, "min": 1e-05, "name": "LPE_ACC_XY", "shortDesc": "Accelerometer xy noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.02, "group": "Local Position Estimator", "longDesc": "Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)", "max": 2.0, "min": 1e-05, "name": "LPE_ACC_Z", "shortDesc": "Accelerometer z noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Local Position Estimator", "max": 100.0, "min": 0.01, "name": "LPE_BAR_Z", "shortDesc": "Barometric presssure altitude z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Local Position Estimator", "name": "LPE_EN", "shortDesc": "Local position estimator enable (unsupported)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Local Position Estimator", "max": 5.0, "min": 1.0, "name": "LPE_EPH_MAX", "shortDesc": "Max EPH allowed for GPS initialization", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 5.0, "group": "Local Position Estimator", "max": 5.0, "min": 1.0, "name": "LPE_EPV_MAX", "shortDesc": "Max EPV allowed for GPS initialization", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Local Position Estimator", "longDesc": "By initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable", "max": 1, "min": 0, "name": "LPE_FAKE_ORIGIN", "shortDesc": "Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow)", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Local Position Estimator", "max": 2.0, "min": 0.0, "name": "LPE_FGYRO_HP", "shortDesc": "Flow gyro high pass filter cut off frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_FLW_OFF_Z", "shortDesc": "Optical flow z offset from center", "type": "Float", "units": "m"}, {"category": "Standard", "default": 150, "group": "Local Position Estimator", "max": 255, "min": 0, "name": "LPE_FLW_QMIN", "shortDesc": "Optical flow minimum quality threshold", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 7.0, "group": "Local Position Estimator", "max": 10.0, "min": 0.1, "name": "LPE_FLW_R", "shortDesc": "Optical flow rotation (roll/pitch) noise gain", "type": "Float", "units": "m/s/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 7.0, "group": "Local Position Estimator", "max": 10.0, "min": 0.0, "name": "LPE_FLW_RR", "shortDesc": "Optical flow angular velocity noise gain", "type": "Float", "units": "m/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.3, "group": "Local Position Estimator", "max": 10.0, "min": 0.1, "name": "LPE_FLW_SCALE", "shortDesc": "Optical flow scale", "type": "Float", "units": "m"}, {"bitmask": [{"description": "fuse GPS, requires GPS for alt. init", "index": 0}, {"description": "fuse optical flow", "index": 1}, {"description": "fuse vision position", "index": 2}, {"description": "fuse landing target", "index": 3}, {"description": "fuse land detector", "index": 4}, {"description": "pub agl as lpos down", "index": 5}, {"description": "flow gyro compensation", "index": 6}, {"description": "fuse baro", "index": 7}], "category": "Standard", "default": 145, "group": "Local Position Estimator", "longDesc": "Set bits in the following positions to enable:\n0 : Set to true to fuse GPS data if available, also requires GPS for altitude init\n1 : Set to true to fuse optical flow data if available\n2 : Set to true to fuse vision position\n3 : Set to true to enable landing target\n4 : Set to true to fuse land detector\n5 : Set to true to publish AGL as local position down component\n6 : Set to true to enable flow gyro compensation\n7 : Set to true to enable baro fusion\ndefault (145 - GPS, baro, land detector)", "max": 255, "min": 0, "name": "LPE_FUSION", "shortDesc": "Integer bitmask controlling data fusion", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.29, "group": "Local Position Estimator", "max": 0.4, "min": 0.0, "name": "LPE_GPS_DELAY", "shortDesc": "GPS delay compensaton", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Local Position Estimator", "longDesc": "EPV used if greater than this value.", "max": 2.0, "min": 0.01, "name": "LPE_GPS_VXY", "shortDesc": "GPS xy velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Local Position Estimator", "max": 2.0, "min": 0.01, "name": "LPE_GPS_VZ", "shortDesc": "GPS z velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Local Position Estimator", "max": 5.0, "min": 0.01, "name": "LPE_GPS_XY", "shortDesc": "Minimum GPS xy standard deviation, uses reported EPH if greater", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Local Position Estimator", "max": 200.0, "min": 0.01, "name": "LPE_GPS_Z", "shortDesc": "Minimum GPS z standard deviation, uses reported EPV if greater", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Local Position Estimator", "max": 10.0, "min": 0.01, "name": "LPE_LAND_VXY", "shortDesc": "Land detector xy velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Local Position Estimator", "max": 10.0, "min": 0.001, "name": "LPE_LAND_Z", "shortDesc": "Land detector z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 8, "default": 47.397742, "group": "Local Position Estimator", "max": 90.0, "min": -90.0, "name": "LPE_LAT", "shortDesc": "Local origin latitude for nav w/o GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_LDR_OFF_Z", "shortDesc": "Lidar z offset from center of vehicle +down", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_LDR_Z", "shortDesc": "Lidar z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 8, "default": 8.545594, "group": "Local Position Estimator", "max": 180.0, "min": -180.0, "name": "LPE_LON", "shortDesc": "Local origin longitude for nav w/o GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0001, "group": "Local Position Estimator", "max": 10.0, "min": 0.0, "name": "LPE_LT_COV", "shortDesc": "Minimum landing target standard covariance, uses reported covariance if greater", "type": "Float", "units": "m^2"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0, "name": "LPE_PN_B", "shortDesc": "Accel bias propagation noise density", "type": "Float", "units": "m/s^3/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Increase to trust measurements more.\nDecrease to trust model more.", "max": 1.0, "min": 0.0, "name": "LPE_PN_P", "shortDesc": "Position propagation noise density", "type": "Float", "units": "m/s/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0, "name": "LPE_PN_T", "shortDesc": "Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001)", "type": "Float", "units": "m/s/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Increase to trust measurements more.\nDecrease to trust model more.", "max": 1.0, "min": 0.0, "name": "LPE_PN_V", "shortDesc": "Velocity propagation noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_SNR_OFF_Z", "shortDesc": "Sonar z offset from center of vehicle +down", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_SNR_Z", "shortDesc": "Sonar z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Local Position Estimator", "longDesc": "Used to calculate increased terrain random walk nosie due to movement.", "max": 100.0, "min": 0.0, "name": "LPE_T_MAX_GRADE", "shortDesc": "Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg)", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0001, "name": "LPE_VIC_P", "shortDesc": "Vicon position standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Set to zero to enable automatic compensation from measurement timestamps", "max": 0.1, "min": 0.0, "name": "LPE_VIS_DELAY", "shortDesc": "Vision delay compensation", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_VIS_XY", "shortDesc": "Vision xy standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "Local Position Estimator", "max": 100.0, "min": 0.01, "name": "LPE_VIS_Z", "shortDesc": "Vision z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.3, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_VXY_PUB", "shortDesc": "Required velocity xy standard deviation to publish position", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 5.0, "group": "Local Position Estimator", "max": 1000.0, "min": 5.0, "name": "LPE_X_LP", "shortDesc": "Cut frequency for state publication", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Local Position Estimator", "max": 5.0, "min": 0.3, "name": "LPE_Z_PUB", "shortDesc": "Required z standard deviation to publish altitude/ terrain", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone\non the local network.", "name": "MAV_0_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 0", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink\ninstance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_0_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 0", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the\nmessage is either broadcast or the target is not the autopilot.\nThis allows for example a GCS to talk to a camera that is connected to the\nautopilot via MAVLink (on a different link than the GCS).", "name": "MAV_0_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 0", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the\nHIGH_LATENCY2 stream for instance 0, configured in iridium mode.\nThis parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_0_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 0", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the\nvehicle's attitude) and their sending rates.", "name": "MAV_0_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 0", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to\n`txbuf` field reported by radio_status.\nRequires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_0_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 0", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1200, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec.\nIf the configured streams exceed the maximum rate, the sending rate of\neach stream is automatically decreased.\nIf this is set to 0 a value of half of the theoretical maximum bandwidth is used.\nThis corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on\n8N1-configured links).", "min": 0, "name": "MAV_0_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 0", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 14550, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 0,\nselected remote port will be set and used in MAVLink instance 0.", "name": "MAV_0_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 0", "type": "Int32"}, {"category": "Standard", "default": 14556, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 0,\nselected udp port will be set and used in MAVLink instance 0.", "name": "MAV_0_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 0", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone\non the local network.", "name": "MAV_1_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 1", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink\ninstance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_1_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 1", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the\nmessage is either broadcast or the target is not the autopilot.\nThis allows for example a GCS to talk to a camera that is connected to the\nautopilot via MAVLink (on a different link than the GCS).", "name": "MAV_1_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 1", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the\nHIGH_LATENCY2 stream for instance 1, configured in iridium mode.\nThis parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_1_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 1", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the\nvehicle's attitude) and their sending rates.", "name": "MAV_1_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 1", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to\n`txbuf` field reported by radio_status.\nRequires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_1_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 1", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec.\nIf the configured streams exceed the maximum rate, the sending rate of\neach stream is automatically decreased.\nIf this is set to 0 a value of half of the theoretical maximum bandwidth is used.\nThis corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on\n8N1-configured links).", "min": 0, "name": "MAV_1_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 1", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 1,\nselected remote port will be set and used in MAVLink instance 1.", "name": "MAV_1_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 1", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 1,\nselected udp port will be set and used in MAVLink instance 1.", "name": "MAV_1_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 1", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone\non the local network.", "name": "MAV_2_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 2", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink\ninstance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_2_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 2", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the\nmessage is either broadcast or the target is not the autopilot.\nThis allows for example a GCS to talk to a camera that is connected to the\nautopilot via MAVLink (on a different link than the GCS).", "name": "MAV_2_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the\nHIGH_LATENCY2 stream for instance 2, configured in iridium mode.\nThis parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_2_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 2", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the\nvehicle's attitude) and their sending rates.", "name": "MAV_2_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 2", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to\n`txbuf` field reported by radio_status.\nRequires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_2_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec.\nIf the configured streams exceed the maximum rate, the sending rate of\neach stream is automatically decreased.\nIf this is set to 0 a value of half of the theoretical maximum bandwidth is used.\nThis corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on\n8N1-configured links).", "min": 0, "name": "MAV_2_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 2", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 2,\nselected remote port will be set and used in MAVLink instance 2.", "name": "MAV_2_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 2", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 2,\nselected udp port will be set and used in MAVLink instance 2.", "name": "MAV_2_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 2", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "max": 250, "min": 1, "name": "MAV_COMP_ID", "rebootRequired": true, "shortDesc": "MAVLink component ID", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If set to 1 incoming external setpoint messages will be directly forwarded\nto the controllers if in offboard control mode", "name": "MAV_FWDEXTSP", "shortDesc": "Forward external setpoint messages", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "Disabling the parameter hash check functionality will make the mavlink instance\nstream parameters continuously.", "name": "MAV_HASH_CHK_EN", "shortDesc": "Parameter hash check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "The mavlink heartbeat message will not be forwarded if this parameter is set to 'disabled'.\nThe main reason for disabling heartbeats to be forwarded is because they confuse dronekit.", "name": "MAV_HB_FORW_EN", "shortDesc": "Heartbeat message forwarding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "name": "MAV_PROTO_VER", "shortDesc": "MAVLink protocol version", "type": "Int32", "values": [{"description": "Default to 1, switch to 2 if GCS sends version 2", "value": 0}, {"description": "Always use version 1", "value": 1}, {"description": "Always use version 2", "value": 2}]}, {"category": "Standard", "default": 5, "group": "MAVLink", "longDesc": "If the connected radio stops reporting RADIO_STATUS for a certain time,\na warning is triggered and, if MAV_X_RADIO_CTL is enabled, the software-flow\ncontrol is reset.", "max": 250, "min": 1, "name": "MAV_RADIO_TOUT", "shortDesc": "Timeout in seconds for the RADIO_STATUS reports coming in", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "When non-zero the MAVLink app will attempt to configure the\nSiK radio to this ID and re-set the parameter to 0. If the value\nis negative it will reset the complete radio config to\nfactory defaults. Only applies if this mavlink instance is going through a SiK radio", "max": 240, "min": -1, "name": "MAV_SIK_RADIO_ID", "shortDesc": "MAVLink SiK Radio ID", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "max": 250, "min": 1, "name": "MAV_SYS_ID", "rebootRequired": true, "shortDesc": "MAVLink system ID", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "max": 22, "min": 0, "name": "MAV_TYPE", "shortDesc": "MAVLink airframe type", "type": "Int32", "values": [{"description": "Generic micro air vehicle", "value": 0}, {"description": "Fixed wing aircraft", "value": 1}, {"description": "Quadrotor", "value": 2}, {"description": "Coaxial helicopter", "value": 3}, {"description": "Normal helicopter with tail rotor", "value": 4}, {"description": "Airship, controlled", "value": 7}, {"description": "Free balloon, uncontrolled", "value": 8}, {"description": "Ground rover", "value": 10}, {"description": "Surface vessel, boat, ship", "value": 11}, {"description": "Submarine", "value": 12}, {"description": "Hexarotor", "value": 13}, {"description": "Octorotor", "value": 14}, {"description": "Tricopter", "value": 15}, {"description": "VTOL Two-rotor Tailsitter", "value": 19}, {"description": "VTOL Quad-rotor Tailsitter", "value": 20}, {"description": "VTOL Tiltrotor", "value": 21}, {"description": "VTOL Standard (separate fixed rotors for hover and cruise flight)", "value": 22}, {"description": "VTOL Tailsitter", "value": 23}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If set to 1 incoming HIL GPS messages are parsed.", "name": "MAV_USEHILGPS", "shortDesc": "Use/Accept HIL GPS message even if not in HIL mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Magnetometer Bias Estimator", "longDesc": "This enables continuous calibration of the magnetometers\nbefore takeoff using gyro data.", "name": "MBE_ENABLE", "rebootRequired": true, "shortDesc": "Enable online mag bias calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 18.0, "group": "Magnetometer Bias Estimator", "increment": 0.1, "longDesc": "Increase to make the estimator more responsive\nDecrease to make the estimator more robust to noise", "max": 100.0, "min": 0.1, "name": "MBE_LEARN_GAIN", "shortDesc": "Mag bias estimator learning gain", "type": "Float"}, {"category": "Standard", "default": 1, "group": "Manual Control", "longDesc": "This determines if moving the left stick to the lower right\narms and to the lower left disarms the vehicle.", "name": "MAN_ARM_GESTURE", "shortDesc": "Enable arm/disarm stick gesture", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Manual Control", "longDesc": "The timeout for holding the left stick to the lower left\nand the right stick to the lower right at the same time until the gesture\nkills the actuators one-way.\nA negative value disables the feature.", "max": 15.0, "min": -1.0, "name": "MAN_KILL_GEST_T", "shortDesc": "Trigger time for kill stick gesture", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mission", "longDesc": "Ensure:\ngripper: NAV_CMD_DO_GRIPPER\nhas released before continuing mission.\nwinch: CMD_DO_WINCH\nhas delivered before continuing mission.\ngimbal: CMD_DO_GIMBAL_MANAGER_PITCHYAW\nhas reached the commanded orientation before beginning to take pictures.", "min": 0.0, "name": "MIS_COMMAND_TOUT", "shortDesc": "Timeout to allow the payload to execute the mission command", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10000.0, "group": "Mission", "increment": 100.0, "longDesc": "There will be a warning message if the current waypoint is more distant than MIS_DIST_1WP from Home.\nHas no effect on mission validity.\nSet a value of zero or less to disable.", "max": 100000.0, "min": -1.0, "name": "MIS_DIST_1WP", "shortDesc": "Maximal horizontal distance from Home to first waypoint", "type": "Float", "units": "m"}, {"category": "Standard", "default": 30, "group": "Mission", "longDesc": "Minimum altitude above landing point that the vehicle will climb to after an aborted landing.\nThen vehicle will loiter in this altitude until further command is received.\nOnly applies to fixed-wing vehicles.", "min": 0, "name": "MIS_LND_ABRT_ALT", "shortDesc": "Landing abort min altitude", "type": "Int32", "units": "m"}, {"category": "Standard", "default": 0, "group": "Mission", "longDesc": "If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading towards the flight direction.\nIf disabled, the vehicle will yaw towards the ROI.", "max": 1, "min": 0, "name": "MIS_MNT_YAW_CTL", "shortDesc": "Enable yaw control of the mount. (Only affects multicopters and ROI mission items)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Enable", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "Mission", "increment": 0.5, "longDesc": "This is the relative altitude the system will take off to\nif not otherwise specified.", "min": 0.0, "name": "MIS_TAKEOFF_ALT", "shortDesc": "Default take-off altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Mission", "longDesc": "Specifies if a mission has to contain a takeoff and/or mission landing.\nValidity of configured takeoffs/landings is checked independently of the setting here.", "name": "MIS_TKO_LAND_REQ", "shortDesc": "Mission takeoff/landing required", "type": "Int32", "values": [{"description": "No requirements", "value": 0}, {"description": "Require a takeoff", "value": 1}, {"description": "Require a landing", "value": 2}, {"description": "Require a takeoff and a landing", "value": 3}, {"description": "Require both a takeoff and a landing, or neither", "value": 4}, {"description": "Same as previous when landed, in-air require landing only if no valid VTOL approach is present", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": 12.0, "group": "Mission", "increment": 1.0, "max": 90.0, "min": 0.0, "name": "MIS_YAW_ERR", "shortDesc": "Max yaw error in degrees needed for waypoint heading acceptance", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 1.0, "longDesc": "If set > 0 it will ignore the target heading for normal waypoint acceptance. If the\nwaypoint forces the heading the timeout will matter. For example on VTOL forwards transition.\nMainly useful for VTOLs that have less yaw authority and might not reach target\nyaw in wind. Disabled by default.", "max": 20.0, "min": -1.0, "name": "MIS_YAW_TMT", "shortDesc": "Time in seconds we wait on reaching target heading at a waypoint if it is forced", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Mission", "max": 4, "min": 0, "name": "MPC_YAW_MODE", "shortDesc": "Heading behavior in autonomous modes", "type": "Int32", "values": [{"description": "towards waypoint", "value": 0}, {"description": "towards home", "value": 1}, {"description": "away from home", "value": 2}, {"description": "along trajectory", "value": 3}, {"description": "towards waypoint (yaw first)", "value": 4}, {"description": "yaw fixed", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Mission", "increment": 0.5, "longDesc": "Default acceptance radius, overridden by acceptance radius of waypoint if set.\nFor fixed wing the npfg switch distance is used for horizontal acceptance.", "max": 200.0, "min": 0.05, "name": "NAV_ACC_RAD", "shortDesc": "Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Mission", "name": "NAV_FORCE_VT", "shortDesc": "Force VTOL mode takeoff and land", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Mission", "longDesc": "Altitude acceptance used for the last waypoint before a fixed-wing landing. This is usually smaller\nthan the standard vertical acceptance because close to the ground higher accuracy is required.", "max": 200.0, "min": 0.05, "name": "NAV_FW_ALTL_RAD", "shortDesc": "FW Altitude Acceptance Radius before a landing", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Mission", "increment": 0.5, "longDesc": "Acceptance radius for fixedwing altitude.", "max": 200.0, "min": 0.05, "name": "NAV_FW_ALT_RAD", "shortDesc": "FW Altitude Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 80.0, "group": "Mission", "increment": 0.5, "longDesc": "Default value of loiter radius in FW mode (e.g. for Loiter mode).", "max": 1000.0, "min": 25.0, "name": "NAV_LOITER_RAD", "shortDesc": "Loiter radius (FW only)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.8, "group": "Mission", "increment": 0.5, "longDesc": "Acceptance radius for multicopter altitude.", "max": 200.0, "min": 0.05, "name": "NAV_MC_ALT_RAD", "shortDesc": "MC Altitude Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 1.0, "longDesc": "Minimum height above ground the vehicle is allowed to descend to during Mission and RTL,\nexcluding landing commands.\nRequires a distance sensor to be set up.\nNote: only prevents the vehicle from descending further, but does not force it to climb.\nSet to a negative value to disable.", "min": -1.0, "name": "NAV_MIN_GND_DIST", "shortDesc": "Minimum height above ground during Mission and RTL", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 0.5, "longDesc": "This is the minimum altitude above Home the system will always obey in Loiter (Hold) mode if switched into this\nmode without specifying an altitude (e.g. through Loiter switch on RC).\nDoesn't affect Loiters that are part of Missions or that are entered through a reposition setpoint (\"Go to\").\nSet to a negative value to disable.", "min": -1.0, "name": "NAV_MIN_LTR_ALT", "shortDesc": "Minimum Loiter altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Mission", "longDesc": "Enabling this will allow the system to respond\nto transponder data from e.g. ADSB transponders", "name": "NAV_TRAFF_AVOID", "shortDesc": "Set traffic avoidance mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warn only", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Position Hold mode", "value": 4}]}, {"category": "Standard", "default": 500.0, "group": "Mission", "longDesc": "Defines a crosstrack horizontal distance", "min": 500.0, "name": "NAV_TRAFF_A_HOR", "shortDesc": "Set NAV TRAFFIC AVOID horizontal distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 500.0, "group": "Mission", "max": 500.0, "min": 10.0, "name": "NAV_TRAFF_A_VER", "shortDesc": "Set NAV TRAFFIC AVOID vertical distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 60, "group": "Mission", "longDesc": "Minimum acceptable time until collsion.\nAssumes constant speed over 3d distance.", "max": 900000000, "min": 1, "name": "NAV_TRAFF_COLL_T", "shortDesc": "Estimated time until collision", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Mixer Output", "longDesc": "The air-mode enables the mixer to increase the total thrust of the multirotor\nin order to keep attitude and rate control even at low and high throttle.\nThis function should be disabled during tuning as it will help the controller\nto diverge if the closed-loop is unstable (i.e. the vehicle is not tuned yet).\nEnabling air-mode for yaw requires the use of an arming switch.", "name": "MC_AIRMODE", "shortDesc": "Multicopter air-mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Roll/Pitch", "value": 1}, {"description": "Roll/Pitch/Yaw", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Mount", "longDesc": "Set to true for servo gimbal, false for passthrough.\nThis is required for a gimbal which is not capable of stabilizing itself\nand relies on the IMU's attitude estimation.", "max": 2, "min": 0, "name": "MNT_DO_STAB", "shortDesc": "Stabilize the mount", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Stabilize all axis", "value": 1}, {"description": "Stabilize yaw for absolute/lock mode.", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "max": 90.0, "min": -90.0, "name": "MNT_LND_P_MAX", "shortDesc": "Pitch maximum when landed", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -90.0, "group": "Mount", "max": 90.0, "min": -90.0, "name": "MNT_LND_P_MIN", "shortDesc": "Pitch minimum when landed", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_PITCH", "shortDesc": "Auxiliary channel to control pitch (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_ROLL", "shortDesc": "Auxiliary channel to control roll (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_YAW", "shortDesc": "Auxiliary channel to control yaw (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 154, "group": "Mount", "longDesc": "If MNT_MODE_OUT is MAVLink protocol v2, mount configure/control commands will be sent with this component ID.", "name": "MNT_MAV_COMPID", "shortDesc": "Mavlink Component ID of the mount", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Mount", "longDesc": "If MNT_MODE_OUT is MAVLink gimbal protocol v1, mount configure/control commands will be sent with this target ID.", "name": "MNT_MAV_SYSID", "shortDesc": "Mavlink System ID of the mount", "type": "Int32"}, {"category": "Standard", "default": -1, "group": "Mount", "longDesc": "This is the protocol used between the ground station and the autopilot.\nRecommended is Auto, RC only or MAVLink gimbal protocol v2.\nThe rest will be deprecated.", "max": 4, "min": -1, "name": "MNT_MODE_IN", "rebootRequired": true, "shortDesc": "Mount input mode", "type": "Int32", "values": [{"description": "DISABLED", "value": -1}, {"description": "Auto (RC and MAVLink gimbal protocol v2)", "value": 0}, {"description": "RC", "value": 1}, {"description": "MAVLINK_ROI (protocol v1, to be deprecated)", "value": 2}, {"description": "MAVLINK_DO_MOUNT (protocol v1, to be deprecated)", "value": 3}, {"description": "MAVlink gimbal protocol v2", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Mount", "longDesc": "This is the protocol used between the autopilot and a connected gimbal.\nRecommended is the MAVLink gimbal protocol v2 if the gimbal supports it.", "max": 2, "min": 0, "name": "MNT_MODE_OUT", "rebootRequired": true, "shortDesc": "Mount output mode", "type": "Int32", "values": [{"description": "AUX", "value": 0}, {"description": "MAVLink gimbal protocol v1", "value": 1}, {"description": "MAVLink gimbal protocol v2", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mount", "max": 360.0, "min": -360.0, "name": "MNT_OFF_PITCH", "shortDesc": "Offset for pitch channel output in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mount", "max": 360.0, "min": -360.0, "name": "MNT_OFF_ROLL", "shortDesc": "Offset for roll channel output in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mount", "max": 360.0, "min": -360.0, "name": "MNT_OFF_YAW", "shortDesc": "Offset for yaw channel output in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_PITCH", "shortDesc": "Range of pitch channel output in degrees (only in AUX output mode)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_ROLL", "shortDesc": "Range of roll channel output in degrees (only in AUX output mode)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 360.0, "group": "Mount", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_YAW", "shortDesc": "Range of yaw channel output in degrees (only in AUX output mode)", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 30.0, "group": "Mount", "longDesc": "Full stick input [-1..1] translats to [-pitch rate..pitch rate].", "max": 90.0, "min": 1.0, "name": "MNT_RATE_PITCH", "shortDesc": "Angular pitch rate for manual input in degrees/second", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 30.0, "group": "Mount", "longDesc": "Full stick input [-1..1] translats to [-yaw rate..yaw rate].", "max": 90.0, "min": 1.0, "name": "MNT_RATE_YAW", "shortDesc": "Angular yaw rate for manual input in degrees/second", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 1, "group": "Mount", "max": 1, "min": 0, "name": "MNT_RC_IN_MODE", "shortDesc": "Input mode for RC gimbal input", "type": "Int32", "values": [{"description": "Angle", "value": 0}, {"description": "Angular rate", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "Exponential factor for tuning the input curve shape.\n0 Purely linear input curve\n1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MC_ACRO_EXPO", "shortDesc": "Acro mode roll, pitch expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "Exponential factor for tuning the input curve shape.\n0 Purely linear input curve\n1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MC_ACRO_EXPO_Y", "shortDesc": "Acro mode yaw expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_P_MAX", "shortDesc": "Acro mode maximum pitch rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_R_MAX", "shortDesc": "Acro mode maximum roll rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using MC_ACRO_EXPO.\n0 Pure Expo function\n0.7 reasonable shape enhancement for intuitive stick feel\n0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "MC_ACRO_SUPEXPO", "shortDesc": "Acro mode roll, pitch super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y.\n0 Pure Expo function\n0.7 reasonable shape enhancement for intuitive stick feel\n0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "MC_ACRO_SUPEXPOY", "shortDesc": "Acro mode yaw super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_Y_MAX", "shortDesc": "Acro mode maximum yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 220.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limit for pitch rate in manual and auto modes (except acro).\nHas effect for large rotations in autonomous mode, to avoid large control\noutput and mixer saturation.\nThis is not only limited by the vehicle's properties, but also by the maximum\nmeasurement rate of the gyro.", "max": 1800.0, "min": 0.0, "name": "MC_PITCHRATE_MAX", "shortDesc": "Max pitch rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 12.0, "min": 0.0, "name": "MC_PITCH_P", "shortDesc": "Pitch P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 220.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limit for roll rate in manual and auto modes (except acro).\nHas effect for large rotations in autonomous mode, to avoid large control\noutput and mixer saturation.\nThis is not only limited by the vehicle's properties, but also by the maximum\nmeasurement rate of the gyro.", "max": 1800.0, "min": 0.0, "name": "MC_ROLLRATE_MAX", "shortDesc": "Max roll rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 12.0, "min": 0.0, "name": "MC_ROLL_P", "shortDesc": "Roll P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 200.0, "group": "Multicopter Attitude Control", "increment": 5.0, "max": 1800.0, "min": 0.0, "name": "MC_YAWRATE_MAX", "shortDesc": "Max yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.8, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 5.0, "min": 0.0, "name": "MC_YAW_P", "shortDesc": "Yaw P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "A fraction [0,1] deprioritizing yaw compared to roll and pitch in non-linear attitude control.\nDeprioritizing yaw is necessary because multicopters have much less control authority\nin yaw compared to the other axes and it makes sense because yaw is not critical for\nstable hovering or 3D navigation.\nFor yaw control tuning use MC_YAW_P. This ratio has no impact on the yaw gain.", "max": 1.0, "min": 0.0, "name": "MC_YAW_WEIGHT", "shortDesc": "Yaw weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": 20.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limits the acceleration of the yaw setpoint to avoid large\ncontrol output and mixer saturation.", "max": 360.0, "min": 5.0, "name": "MPC_YAWRAUTO_ACC", "shortDesc": "Maximum yaw acceleration in autonomous modes", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 0, "default": 60.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limits the rate of change of the yaw setpoint to avoid large\ncontrol output and mixer saturation.", "max": 360.0, "min": 5.0, "name": "MPC_YAWRAUTO_MAX", "shortDesc": "Maximum yaw rate in autonomous modes", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0.4, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "max": 1.0, "min": 0.0, "name": "CP_DELAY", "shortDesc": "Average delay of the range sensor message plus the tracking delay of the position controller in seconds", "type": "Float", "units": "s"}, {"category": "Standard", "default": -1.0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode. Collision avoidance is disabled by setting this parameter to a negative value", "max": 15.0, "min": -1.0, "name": "CP_DIST", "shortDesc": "Minimum distance the vehicle should keep to all obstacles", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "name": "CP_GO_NO_DATA", "shortDesc": "Boolean to allow moving into directions where there is no sensor data (outside FOV)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 30.0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "max": 90.0, "min": 0.0, "name": "CP_GUIDE_ANG", "shortDesc": "Angle left/right from the commanded setpoint by which the collision prevention algorithm can choose to change the setpoint direction", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Position Control", "longDesc": "Setting this parameter to 0 disables the filter", "max": 2.0, "min": 0.0, "name": "MC_MAN_TILT_TAU", "shortDesc": "Manual tilt input filter time constant", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Multicopter Position Control", "longDesc": "Set to decouple tilt from vertical acceleration.\nThis provides smoother flight but slightly worse tracking in position and auto modes.\nUnset if accurate position tracking during dynamic maneuvers is more important than a smooth flight.", "name": "MPC_ACC_DECOUPLE", "shortDesc": "Acceleration to tilt coupling", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 15.0, "min": 2.0, "name": "MPC_ACC_DOWN_MAX", "shortDesc": "Maximum downwards acceleration in climb rate controlled modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "When piloting manually, this parameter is only used in MPC_POS_MODE Acceleration based.", "max": 15.0, "min": 2.0, "name": "MPC_ACC_HOR", "shortDesc": "Acceleration for autonomous and for manual modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "MPC_POS_MODE\n1 just deceleration\n4 not used, use MPC_ACC_HOR instead", "max": 15.0, "min": 2.0, "name": "MPC_ACC_HOR_MAX", "shortDesc": "Maximum horizontal acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 15.0, "min": 2.0, "name": "MPC_ACC_UP_MAX", "shortDesc": "Maximum upwards acceleration in climb rate controlled modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 2, "group": "Multicopter Position Control", "longDesc": "Control height\n0: relative earth frame origin which may drift due to sensors\n1: relative to ground (requires distance sensor) which changes with terrain variation.\nIt will revert to relative earth frame if the distance to ground estimate becomes invalid.\n2: relative to ground (requires distance sensor) when stationary\nand relative to earth frame when moving horizontally.\nThe speed threshold is MPC_HOLD_MAX_XY", "max": 2, "min": 0, "name": "MPC_ALT_MODE", "shortDesc": "Altitude reference mode", "type": "Int32", "values": [{"description": "Altitude following", "value": 0}, {"description": "Terrain following", "value": 1}, {"description": "Terrain hold", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Does not apply to manual throttle and direct attitude piloting by stick.", "max": 1.0, "min": 0.0, "name": "MPC_HOLD_DZ", "shortDesc": "Deadzone for sticks in manual piloted modes", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.8, "group": "Multicopter Position Control", "longDesc": "Only used with MPC_POS_MODE Direct velocity or MPC_ALT_MODE 2", "max": 3.0, "min": 0.0, "name": "MPC_HOLD_MAX_XY", "shortDesc": "Maximum horizontal velocity for which position hold is enabled (use 0 to disable check)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "longDesc": "Only used with MPC_ALT_MODE 1", "max": 3.0, "min": 0.0, "name": "MPC_HOLD_MAX_Z", "shortDesc": "Maximum vertical velocity for which position hold is enabled (use 0 to disable check)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Limit the maximum jerk of the vehicle (how fast the acceleration can change).\nA lower value leads to smoother vehicle motions but also limited agility.", "max": 80.0, "min": 1.0, "name": "MPC_JERK_AUTO", "shortDesc": "Jerk limit in autonomous modes", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 0, "default": 8.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Limit the maximum jerk (acceleration change) of the vehicle.\nA lower value leads to smoother motions but limits agility.\nSetting this to the maximum value essentially disables the limit.\nOnly used with MPC_POS_MODE Acceleration based.", "max": 500.0, "min": 0.5, "name": "MPC_JERK_MAX", "shortDesc": "Maximum horizontal and vertical jerk in Position/Altitude mode", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Multicopter Position Control", "longDesc": "Below this altitude descending velocity gets limited to a value\nbetween \"MPC_Z_VEL_MAX_DN\" (or \"MPC_Z_V_AUTO_DN\") and \"MPC_LAND_SPEED\"\nValue needs to be higher than \"MPC_LAND_ALT2\"", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT1", "shortDesc": "Altitude for 1. step of slow landing (descend)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "longDesc": "Below this altitude descending velocity gets\nlimited to \"MPC_LAND_SPEED\"\nValue needs to be lower than \"MPC_LAND_ALT1\"", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT2", "shortDesc": "Altitude for 2. step of slow landing (landing)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Multicopter Position Control", "longDesc": "If a valid distance sensor measurement to the ground is available,\nlimit descending velocity to \"MPC_LAND_CRWL\" below this altitude.", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT3", "shortDesc": "Altitude for 3. step of slow landing", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.3, "group": "Multicopter Position Control", "longDesc": "Used below MPC_LAND_ALT3 if distance sensor data is availabe.", "min": 0.1, "name": "MPC_LAND_CRWL", "shortDesc": "Land crawl descend rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 1000.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "When nudging is enabled (see MPC_LAND_RC_HELP), this controls\nthe maximum allowed horizontal displacement from the original landing point.", "min": 0.0, "name": "MPC_LAND_RADIUS", "shortDesc": "User assisted landing radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Using stick input the vehicle can be moved horizontally and yawed.\nThe descend speed is amended:\nstick full up - 0\nstick centered - MPC_LAND_SPEED\nstick full down - 2 * MPC_LAND_SPEED\nManual override during auto modes has to be disabled to use this feature (see COM_RC_OVERRIDE).", "max": 1, "min": 0, "name": "MPC_LAND_RC_HELP", "shortDesc": "Enable nudging based on user input during autonomous land routine", "type": "Int32", "values": [{"description": "Nudging disabled", "value": 0}, {"description": "Nudging enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.7, "group": "Multicopter Position Control", "min": 0.6, "name": "MPC_LAND_SPEED", "shortDesc": "Landing descend rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The value is mapped to the lowest throttle stick position in Stabilized mode.\nToo low collective thrust leads to loss of roll/pitch/yaw torque control authority.\nAirmode is used to keep torque authority with zero thrust (see MC_AIRMODE).", "max": 1.0, "min": 0.0, "name": "MPC_MANTHR_MIN", "shortDesc": "Minimum collective thrust in Stabilized mode", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 0, "default": 35.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 70.0, "min": 1.0, "name": "MPC_MAN_TILT_MAX", "shortDesc": "Maximal tilt angle in Stabilized or Altitude mode", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 150.0, "group": "Multicopter Position Control", "increment": 10.0, "max": 400.0, "min": 0.0, "name": "MPC_MAN_Y_MAX", "shortDesc": "Max manual yaw rate for Stabilized, Altitude, Position mode", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Not used in Stabilized mode\nSetting this parameter to 0 disables the filter", "max": 5.0, "min": 0.0, "name": "MPC_MAN_Y_TAU", "shortDesc": "Manual yaw rate input filter time constant", "type": "Float", "units": "s"}, {"category": "Standard", "default": 4, "group": "Multicopter Position Control", "longDesc": "The supported sub-modes are:\nDirect velocity:\nSticks directly map to velocity setpoints without smoothing.\nAlso applies to vertical direction and Altitude mode.\nUseful for velocity control tuning.\nAcceleration based:\nSticks map to acceleration and there's a virtual brake drag", "name": "MPC_POS_MODE", "shortDesc": "Position/Altitude mode variant", "type": "Int32", "values": [{"description": "Direct velocity", "value": 0}, {"description": "Acceleration based", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Defines how the throttle stick is mapped to collective thrust in Stabilized mode.\nRescale to hover thrust estimate:\nStick input is linearly rescaled, such that a centered throttle stick corresponds to the hover thrust estimator's output.\nNo rescale:\nDirectly map the stick 1:1 to the output.\nCan be useful with very low hover thrust which leads to much distortion and the upper half getting sensitive.\nRescale to hover thrust parameter:\nSimilar to rescaling to the hover thrust estimate, but it uses the hover thrust parameter value (see MPC_THR_HOVER) instead of estimated value.\nWith MPC_THR_HOVER 0.5 it's equivalent to No rescale.", "name": "MPC_THR_CURVE", "shortDesc": "Thrust curve mapping in Stabilized Mode", "type": "Int32", "values": [{"description": "Rescale to estimate", "value": 0}, {"description": "No rescale", "value": 1}, {"description": "Rescale to parameter", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Mapped to center throttle stick in Stabilized mode (see MPC_THR_CURVE).\nUsed for initialization of the hover thrust estimator (see MPC_USE_HTE).\nThe estimated hover thrust is used as base for zero vertical acceleration in altitude control.\nThe hover thrust is important for land detection to work correctly.", "max": 0.8, "min": 0.1, "name": "MPC_THR_HOVER", "shortDesc": "Vertical thrust required to hover", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Control", "increment": 0.05, "longDesc": "Limit allowed thrust e.g. for indoor test of overpowered vehicle.", "max": 1.0, "min": 0.0, "name": "MPC_THR_MAX", "shortDesc": "Maximum collective thrust in climb rate controlled modes", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.12, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Too low thrust leads to loss of roll/pitch/yaw torque control authority.\nWith airmode enabled this parameters can be set to 0\nwhile still keeping torque authority (see MC_AIRMODE).", "max": 0.5, "min": 0.05, "name": "MPC_THR_MIN", "shortDesc": "Minimum collective thrust in climb rate controlled modes", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Margin that is kept for horizontal control when higher priority vertical thrust is saturated.\nTo avoid completely starving horizontal control with high vertical error.", "max": 0.5, "min": 0.0, "name": "MPC_THR_XY_MARG", "shortDesc": "Horizontal thrust margin", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Absolute maximum for all velocity or acceleration controlled modes.\nAny higher value is truncated.", "max": 89.0, "min": 20.0, "name": "MPC_TILTMAX_AIR", "shortDesc": "Maximum tilt angle in air", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 12.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Tighter tilt limit during takeoff to avoid tip over.", "max": 89.0, "min": 5.0, "name": "MPC_TILTMAX_LND", "shortDesc": "Maximum tilt during inital takeoff ramp", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 3.0, "group": "Multicopter Position Control", "longDesc": "Increasing this value will make climb rate controlled takeoff slower.\nIf it's too slow the drone might scratch the ground and tip over.\nA time constant of 0 disables the ramp", "max": 5.0, "min": 0.0, "name": "MPC_TKO_RAMP_T", "shortDesc": "Smooth takeoff ramp time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.5, "group": "Multicopter Position Control", "max": 5.0, "min": 1.0, "name": "MPC_TKO_SPEED", "shortDesc": "Takeoff climb rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "Multicopter Position Control", "longDesc": "Disable to use the fixed parameter MPC_THR_HOVER instead of the hover thrust estimate in the position controller.\nThis parameter does not influence Stabilized mode throttle curve (see MPC_THR_CURVE).", "name": "MPC_USE_HTE", "shortDesc": "Use hover thrust estimate for altitude control", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VELD_LP", "shortDesc": "Velocity derivative low pass cutoff frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_LP", "shortDesc": "Velocity low pass cutoff frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Must be smaller than MPC_XY_VEL_MAX.\nThe maximum sideways and backward speed can be set differently\nusing MPC_VEL_MAN_SIDE and MPC_VEL_MAN_BACK, respectively.", "max": 20.0, "min": 3.0, "name": "MPC_VEL_MANUAL", "shortDesc": "Maximum horizontal velocity setpoint in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a negative value or larger than\nMPC_VEL_MANUAL then MPC_VEL_MANUAL is used.", "max": 20.0, "min": -1.0, "name": "MPC_VEL_MAN_BACK", "shortDesc": "Maximum backward velocity in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a negative value or larger than\nMPC_VEL_MANUAL then MPC_VEL_MANUAL is used.", "max": 20.0, "min": -1.0, "name": "MPC_VEL_MAN_SIDE", "shortDesc": "Maximum sideways velocity in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_NF_BW", "shortDesc": "Velocity notch filter bandwidth", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "The center frequency for the 2nd order notch filter on the velocity.\nA value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_NF_FRQ", "shortDesc": "Velocity notch filter frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 0, "default": 5.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "e.g. in Missions, RTL, Goto if the waypoint does not specify differently", "max": 20.0, "min": 3.0, "name": "MPC_XY_CRUISE", "shortDesc": "Default horizontal velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "The integration speed of the trajectory setpoint is linearly\nreduced with the horizontal position tracking error. When the\nerror is above this parameter, the integration of the\ntrajectory is stopped to wait for the drone.\nThis value can be adjusted depending on the tracking\ncapabilities of the vehicle.", "max": 10.0, "min": 0.1, "name": "MPC_XY_ERR_MAX", "shortDesc": "Maximum horizontal error allowed by the trajectory generator", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The higher the value the less sensitivity the stick has around zero\nwhile still reaching the maximum value with full stick deflection.\n0 Purely linear input curve\n1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MPC_XY_MAN_EXPO", "shortDesc": "Manual position control stick exponential curve sensitivity", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.95, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective velocity in m/s per m position error", "max": 2.0, "min": 0.0, "name": "MPC_XY_P", "shortDesc": "Proportional gain for horizontal position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Multicopter Position Control", "increment": 0.1, "max": 1.0, "min": 0.1, "name": "MPC_XY_TRAJ_P", "shortDesc": "Proportional gain for horizontal trajectory position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -10.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a value greater than zero, other parameters are automatically set (such as\nMPC_XY_VEL_MAX or MPC_VEL_MANUAL).\nIf set to a negative value, the existing individual parameters are used.", "max": 20.0, "min": -20.0, "name": "MPC_XY_VEL_ALL", "shortDesc": "Overall Horizontal Velocity Limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative", "max": 2.0, "min": 0.1, "name": "MPC_XY_VEL_D_ACC", "shortDesc": "Differential gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as correction acceleration in m/s^2 per m velocity integral\nAllows to eliminate steady state errors in disturbances like wind.", "max": 60.0, "min": 0.0, "name": "MPC_XY_VEL_I_ACC", "shortDesc": "Integral gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 12.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Absolute maximum for all velocity controlled modes.\nAny higher value is truncated.", "max": 20.0, "min": 0.0, "name": "MPC_XY_VEL_MAX", "shortDesc": "Maximum horizontal velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.8, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s velocity error", "max": 5.0, "min": 1.2, "name": "MPC_XY_VEL_P_ACC", "shortDesc": "Proportional gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The higher the value the less sensitivity the stick has around zero\nwhile still reaching the maximum value with full stick deflection.\n0 Purely linear input curve\n1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MPC_YAW_EXPO", "shortDesc": "Manual control stick yaw rotation exponential curve", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The higher the value the less sensitivity the stick has around zero\nwhile still reaching the maximum value with full stick deflection.\n0 Purely linear input curve\n1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MPC_Z_MAN_EXPO", "shortDesc": "Manual control stick vertical exponential curve", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective velocity in m/s per m position error", "max": 1.5, "min": 0.1, "name": "MPC_Z_P", "shortDesc": "Proportional gain for vertical position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -3.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "If set to a value greater than zero, other parameters are automatically set (such as\nMPC_Z_VEL_MAX_UP or MPC_LAND_SPEED).\nIf set to a negative value, the existing individual parameters are used.", "max": 8.0, "min": -3.0, "name": "MPC_Z_VEL_ALL", "shortDesc": "Overall Vertical Velocity Limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative", "max": 2.0, "min": 0.0, "name": "MPC_Z_VEL_D_ACC", "shortDesc": "Differential gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m velocity integral", "max": 3.0, "min": 0.2, "name": "MPC_Z_VEL_I_ACC", "shortDesc": "Integral gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Absolute maximum for all climb rate controlled modes.\nIn manually piloted modes full stick deflection commands this velocity.\nFor default autonomous velocity see MPC_Z_V_AUTO_UP", "max": 4.0, "min": 0.5, "name": "MPC_Z_VEL_MAX_DN", "shortDesc": "Maximum descent velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Absolute maximum for all climb rate controlled modes.\nIn manually piloted modes full stick deflection commands this velocity.\nFor default autonomous velocity see MPC_Z_V_AUTO_UP", "max": 8.0, "min": 0.5, "name": "MPC_Z_VEL_MAX_UP", "shortDesc": "Maximum ascent velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s velocity error", "max": 15.0, "min": 2.0, "name": "MPC_Z_VEL_P_ACC", "shortDesc": "Proportional gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "For manual modes and offboard, see MPC_Z_VEL_MAX_DN", "max": 4.0, "min": 0.5, "name": "MPC_Z_V_AUTO_DN", "shortDesc": "Descent velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "For manually controlled modes and offboard see MPC_Z_VEL_MAX_UP", "max": 8.0, "min": 0.5, "name": "MPC_Z_V_AUTO_UP", "shortDesc": "Ascent velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": -0.4, "group": "Multicopter Position Control", "increment": 0.05, "longDesc": "Changes the overall responsiveness of the vehicle.\nThe higher the value, the faster the vehicle will react.\nIf set to a value greater than zero, other parameters are automatically set (such as\nthe acceleration or jerk limits).\nIf set to a negative value, the existing individual parameters are used.", "max": 1.0, "min": -1.0, "name": "SYS_VEHICLE_RESP", "shortDesc": "Responsiveness", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "name": "WV_EN", "shortDesc": "Enable weathervane", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1.0, "group": "Multicopter Position Control", "max": 5.0, "min": 0.0, "name": "WV_ROLL_MIN", "shortDesc": "Minimum roll angle setpoint for weathervane controller to demand a yaw-rate", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 90.0, "group": "Multicopter Position Control", "max": 120.0, "min": 0.0, "name": "WV_YRATE_MAX", "shortDesc": "Maximum yawrate the weathervane controller is allowed to demand", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if\nno aux channel is mapped and\nno limit is commanded through MAVLink.", "min": 0.1, "name": "MC_SLOW_DEF_HVEL", "shortDesc": "Default horizontal velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if\nno aux channel is mapped and\nno limit is commanded through MAVLink.", "min": 0.1, "name": "MC_SLOW_DEF_VVEL", "shortDesc": "Default vertical velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if\nno aux channel is mapped and\nno limit is commanded through MAVLink.", "min": 1.0, "name": "MC_SLOW_DEF_YAWR", "shortDesc": "Default yaw rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_HVEL", "shortDesc": "Manual input mapped to scale horizontal velocity in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_PTCH", "shortDesc": "RC_MAP_AUX{N} to allow for gimbal pitch rate control in position slow mode", "type": "Int32", "values": [{"description": "No pitch rate input", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_VVEL", "shortDesc": "Manual input mapped to scale vertical velocity in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_YAWR", "shortDesc": "Manual input mapped to scale yaw rate in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this velocity.", "min": 0.1, "name": "MC_SLOW_MIN_HVEL", "shortDesc": "Horizontal velocity lower limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this velocity.", "min": 0.1, "name": "MC_SLOW_MIN_VVEL", "shortDesc": "Vertical velocity lower limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 3.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this rate.", "min": 1.0, "name": "MC_SLOW_MIN_YAWR", "shortDesc": "Yaw rate lower limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0, "group": "Multicopter Rate Control", "longDesc": "This compensates for voltage drop of the battery over time by attempting to\nnormalize performance across the operating range of the battery. The copter\nshould constantly behave as if it was fully charged with reduced max acceleration\nat lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery,\nit will still be 0.5 at 60% battery.", "name": "MC_BAT_SCALE_EN", "shortDesc": "Battery power level scaler", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 4, "default": 0.003, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "min": 0.0, "name": "MC_PITCHRATE_D", "shortDesc": "Pitch rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_PITCHRATE_FF", "shortDesc": "Pitch rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_PITCHRATE_I", "shortDesc": "Pitch rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller.\nThis gain scales the P, I and D terms of the controller:\noutput = MC_PITCHRATE_K * (MC_PITCHRATE_P * error\n+ MC_PITCHRATE_I * error_integral\n+ MC_PITCHRATE_D * error_derivative)\nSet MC_PITCHRATE_P=1 to implement a PID in the ideal form.\nSet MC_PITCHRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_PITCHRATE_K", "shortDesc": "Pitch rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.6, "min": 0.01, "name": "MC_PITCHRATE_P", "shortDesc": "Pitch rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes.", "min": 0.0, "name": "MC_PR_INT_LIM", "shortDesc": "Pitch rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.003, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "max": 0.01, "min": 0.0, "name": "MC_ROLLRATE_D", "shortDesc": "Roll rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_ROLLRATE_FF", "shortDesc": "Roll rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_ROLLRATE_I", "shortDesc": "Roll rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller.\nThis gain scales the P, I and D terms of the controller:\noutput = MC_ROLLRATE_K * (MC_ROLLRATE_P * error\n+ MC_ROLLRATE_I * error_integral\n+ MC_ROLLRATE_D * error_derivative)\nSet MC_ROLLRATE_P=1 to implement a PID in the ideal form.\nSet MC_ROLLRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_ROLLRATE_K", "shortDesc": "Roll rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.5, "min": 0.01, "name": "MC_ROLLRATE_P", "shortDesc": "Roll rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes.", "min": 0.0, "name": "MC_RR_INT_LIM", "shortDesc": "Roll rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "min": 0.0, "name": "MC_YAWRATE_D", "shortDesc": "Yaw rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_YAWRATE_FF", "shortDesc": "Yaw rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_YAWRATE_I", "shortDesc": "Yaw rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller.\nThis gain scales the P, I and D terms of the controller:\noutput = MC_YAWRATE_K * (MC_YAWRATE_P * error\n+ MC_YAWRATE_I * error_integral\n+ MC_YAWRATE_D * error_derivative)\nSet MC_YAWRATE_P=1 to implement a PID in the ideal form.\nSet MC_YAWRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.0, "name": "MC_YAWRATE_K", "shortDesc": "Yaw rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.6, "min": 0.0, "name": "MC_YAWRATE_P", "shortDesc": "Yaw rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 2.0, "group": "Multicopter Rate Control", "longDesc": "Reduces vibrations by lowering high frequency torque caused by rotor acceleration.\n0 disables the filter", "max": 10.0, "min": 0.0, "name": "MC_YAW_TQ_CUTOFF", "shortDesc": "Low pass filter cutoff frequency for yaw torque setpoint", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes.", "min": 0.0, "name": "MC_YR_INT_LIM", "shortDesc": "Yaw rate integrator limit", "type": "Float"}, {"category": "Standard", "default": 0, "group": "OSD", "longDesc": "Controls the vertical position of the crosshair display.\nResolution is limited by OSD to 15 discrete values. Negative\nvalues will display the crosshairs below the horizon", "max": 8, "min": -8, "name": "OSD_CH_HEIGHT", "shortDesc": "OSD Crosshairs Height", "type": "Int32"}, {"category": "Standard", "default": 500, "group": "OSD", "longDesc": "Amount of time in milliseconds to dwell at the beginning of the display, when scrolling.", "max": 10000, "min": 100, "name": "OSD_DWELL_TIME", "shortDesc": "OSD Dwell Time (ms)", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "OSD", "longDesc": "Minimum security of log level to display on the OSD.", "name": "OSD_LOG_LEVEL", "shortDesc": "OSD Warning Level", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "OSD", "longDesc": "Forward RC stick input to VTX when disarmed", "max": 1, "min": 0, "name": "OSD_RC_STICK", "shortDesc": "OSD RC Stick commands", "type": "Int32"}, {"category": "Standard", "default": 125, "group": "OSD", "longDesc": "Scroll rate in milliseconds for OSD messages longer than available character width.\nThis is lower-bounded by the nominal loop rate of this module.", "max": 1000, "min": 100, "name": "OSD_SCROLL_RATE", "shortDesc": "OSD Scroll Rate (ms)", "type": "Int32"}, {"bitmask": [{"description": "CRAFT_NAME", "index": 0}, {"description": "DISARMED", "index": 1}, {"description": "GPS_LAT", "index": 2}, {"description": "GPS_LON", "index": 3}, {"description": "GPS_SATS", "index": 4}, {"description": "GPS_SPEED", "index": 5}, {"description": "HOME_DIST", "index": 6}, {"description": "HOME_DIR", "index": 7}, {"description": "MAIN_BATT_VOLTAGE", "index": 8}, {"description": "CURRENT_DRAW", "index": 9}, {"description": "MAH_DRAWN", "index": 10}, {"description": "RSSI_VALUE", "index": 11}, {"description": "ALTITUDE", "index": 12}, {"description": "NUMERICAL_VARIO", "index": 13}, {"description": "(unused) FLYMODE", "index": 14}, {"description": "(unused) ESC_TMP", "index": 15}, {"description": "(unused) PITCH_ANGLE", "index": 16}, {"description": "(unused) ROLL_ANGLE", "index": 17}, {"description": "CROSSHAIRS", "index": 18}, {"description": "AVG_CELL_VOLTAGE", "index": 19}, {"description": "(unused) HORIZON_SIDEBARS", "index": 20}, {"description": "POWER", "index": 21}], "category": "Standard", "default": 16383, "group": "OSD", "longDesc": "Configure / toggle support display options.", "max": 4194303, "min": 0, "name": "OSD_SYMBOLS", "shortDesc": "OSD Symbol Selection", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "PWM Outputs", "increment": 0.1, "longDesc": "Parameter used to model the nonlinear relationship between\nmotor control signal (e.g. PWM) and static thrust.\nThe model is: rel_thrust = factor * rel_signal^2 + (1-factor) * rel_signal,\nwhere rel_thrust is the normalized thrust between 0 and 1, and\nrel_signal is the relative motor control signal between 0 and 1.", "max": 1.0, "min": 0.0, "name": "THR_MDL_FAC", "shortDesc": "Thrust to motor control signal model parameter", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Payload Deliverer", "name": "PD_GRIPPER_EN", "rebootRequired": true, "shortDesc": "Enable Gripper actuation in Payload Deliverer", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 3.0, "group": "Payload Deliverer", "longDesc": "Maximum time Gripper will wait while the successful griper actuation isn't recognised.\nIf the gripper has no feedback sensor, it will simply wait for\nthis time before considering gripper actuation successful and publish a\n'VehicleCommandAck' signaling successful gripper action", "min": 0.0, "name": "PD_GRIPPER_TO", "shortDesc": "Timeout for successful gripper actuation acknowledgement", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Payload Deliverer", "max": 0, "min": -1, "name": "PD_GRIPPER_TYPE", "shortDesc": "Type of Gripper (Servo, etc.)", "type": "Int32", "values": [{"description": "Undefined", "value": -1}, {"description": "Servo", "value": 0}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Precision Land", "increment": 0.5, "longDesc": "Time after which the landing target is considered lost without any new measurements.", "max": 50.0, "min": 0.0, "name": "PLD_BTOUT", "shortDesc": "Landing Target Timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Precision Land", "increment": 0.1, "longDesc": "Allow final approach (without horizontal positioning) if losing landing target closer than this to the ground.", "max": 10.0, "min": 0.0, "name": "PLD_FAPPR_ALT", "shortDesc": "Final approach altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Precision Land", "increment": 0.1, "longDesc": "Start descending if closer above landing target than this.", "max": 10.0, "min": 0.0, "name": "PLD_HACC_RAD", "shortDesc": "Horizontal acceptance radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "Precision Land", "longDesc": "Maximum number of times to search for the landing target if it is lost during the precision landing.", "max": 100, "min": 0, "name": "PLD_MAX_SRCH", "shortDesc": "Maximum number of search attempts", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Precision Land", "increment": 0.1, "longDesc": "Altitude above home to which to climb when searching for the landing target.", "max": 100.0, "min": 0.0, "name": "PLD_SRCH_ALT", "shortDesc": "Search altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Precision Land", "increment": 0.1, "longDesc": "Time allowed to search for the landing target before falling back to normal landing.", "max": 100.0, "min": 0.0, "name": "PLD_SRCH_TOUT", "shortDesc": "Search timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Pure Pursuit", "increment": 0.01, "longDesc": "Lower value -> More aggressive controller (beware overshoot/oscillations)", "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_GAIN", "shortDesc": "Tuning parameter for the pure pursuit controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Pure Pursuit", "increment": 0.01, "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_MAX", "shortDesc": "Maximum lookahead distance for the pure pursuit controller", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Pure Pursuit", "increment": 0.01, "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_MIN", "shortDesc": "Minimum lookahead distance for the pure pursuit controller", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC10_DZ", "shortDesc": "RC channel 10 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC10_MAX", "shortDesc": "RC channel 10 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC10_MIN", "shortDesc": "RC channel 10 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC10_REV", "shortDesc": "RC channel 10 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC10_TRIM", "shortDesc": "RC channel 10 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC11_DZ", "shortDesc": "RC channel 11 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC11_MAX", "shortDesc": "RC channel 11 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC11_MIN", "shortDesc": "RC channel 11 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC11_REV", "shortDesc": "RC channel 11 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC11_TRIM", "shortDesc": "RC channel 11 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC12_DZ", "shortDesc": "RC channel 12 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC12_MAX", "shortDesc": "RC channel 12 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC12_MIN", "shortDesc": "RC channel 12 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC12_REV", "shortDesc": "RC channel 12 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC12_TRIM", "shortDesc": "RC channel 12 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC13_DZ", "shortDesc": "RC channel 13 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC13_MAX", "shortDesc": "RC channel 13 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC13_MIN", "shortDesc": "RC channel 13 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC13_REV", "shortDesc": "RC channel 13 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC13_TRIM", "shortDesc": "RC channel 13 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC14_DZ", "shortDesc": "RC channel 14 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC14_MAX", "shortDesc": "RC channel 14 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC14_MIN", "shortDesc": "RC channel 14 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC14_REV", "shortDesc": "RC channel 14 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC14_TRIM", "shortDesc": "RC channel 14 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC15_DZ", "shortDesc": "RC channel 15 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC15_MAX", "shortDesc": "RC channel 15 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC15_MIN", "shortDesc": "RC channel 15 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC15_REV", "shortDesc": "RC channel 15 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC15_TRIM", "shortDesc": "RC channel 15 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC16_DZ", "shortDesc": "RC channel 16 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC16_MAX", "shortDesc": "RC channel 16 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC16_MIN", "shortDesc": "RC channel 16 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC16_REV", "shortDesc": "RC channel 16 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC16_TRIM", "shortDesc": "RC channel 16 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC17_DZ", "shortDesc": "RC channel 17 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC17_MAX", "shortDesc": "RC channel 17 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC17_MIN", "shortDesc": "RC channel 17 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC17_REV", "shortDesc": "RC channel 17 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC17_TRIM", "shortDesc": "RC channel 17 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC18_DZ", "shortDesc": "RC channel 18 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC18_MAX", "shortDesc": "RC channel 18 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC18_MIN", "shortDesc": "RC channel 18 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC18_REV", "shortDesc": "RC channel 18 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC18_TRIM", "shortDesc": "RC channel 18 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC1_DZ", "shortDesc": "RC channel 1 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for RC channel 1", "max": 2200.0, "min": 1500.0, "name": "RC1_MAX", "shortDesc": "RC channel 1 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for RC channel 1", "max": 1500.0, "min": 800.0, "name": "RC1_MIN", "shortDesc": "RC channel 1 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC1_REV", "shortDesc": "RC channel 1 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC1_TRIM", "shortDesc": "RC channel 1 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC2_DZ", "shortDesc": "RC channel 2 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC2_MAX", "shortDesc": "RC channel 2 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC2_MIN", "shortDesc": "RC channel 2 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC2_REV", "shortDesc": "RC channel 2 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC2_TRIM", "shortDesc": "RC channel 2 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC3_DZ", "shortDesc": "RC channel 3 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC3_MAX", "shortDesc": "RC channel 3 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC3_MIN", "shortDesc": "RC channel 3 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC3_REV", "shortDesc": "RC channel 3 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC3_TRIM", "shortDesc": "RC channel 3 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC4_DZ", "shortDesc": "RC channel 4 dead zone", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC4_MAX", "shortDesc": "RC channel 4 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC4_MIN", "shortDesc": "RC channel 4 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC4_REV", "shortDesc": "RC channel 4 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC4_TRIM", "shortDesc": "RC channel 4 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC5_DZ", "shortDesc": "RC channel 5 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC5_MAX", "shortDesc": "RC channel 5 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC5_MIN", "shortDesc": "RC channel 5 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC5_REV", "shortDesc": "RC channel 5 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC5_TRIM", "shortDesc": "RC channel 5 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC6_DZ", "shortDesc": "RC channel 6 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC6_MAX", "shortDesc": "RC channel 6 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC6_MIN", "shortDesc": "RC channel 6 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC6_REV", "shortDesc": "RC channel 6 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC6_TRIM", "shortDesc": "RC channel 6 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC7_DZ", "shortDesc": "RC channel 7 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC7_MAX", "shortDesc": "RC channel 7 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC7_MIN", "shortDesc": "RC channel 7 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC7_REV", "shortDesc": "RC channel 7 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC7_TRIM", "shortDesc": "RC channel 7 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 10.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC8_DZ", "shortDesc": "RC channel 8 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC8_MAX", "shortDesc": "RC channel 8 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC8_MIN", "shortDesc": "RC channel 8 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC8_REV", "shortDesc": "RC channel 8 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC8_TRIM", "shortDesc": "RC channel 8 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0.0, "group": "Radio Calibration", "longDesc": "The +- range of this value around the trim value will be considered as zero.", "max": 100.0, "min": 0.0, "name": "RC9_DZ", "shortDesc": "RC channel 9 dead zone", "type": "Float"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC9_MAX", "shortDesc": "RC channel 9 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC9_MIN", "shortDesc": "RC channel 9 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC9_REV", "shortDesc": "RC channel 9 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC9_TRIM", "shortDesc": "RC channel 9 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "This parameter is used by Ground Station software to save the number\nof channels which were used during RC calibration. It is only meant\nfor ground station use.", "max": 18, "min": 0, "name": "RC_CHAN_CNT", "shortDesc": "RC channel count", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Use RC_MAP_FAILSAFE to specify which channel is used to indicate RC loss via this threshold.\nBy default this is the throttle channel.\nSet to a PWM value slightly above the PWM value for the channel (e.g. throttle) in a failsafe event,\nbut below the minimum PWM value for the channel during normal operation.\nNote: The default value of 0 disables the feature (it is below the expected range).", "max": 2200, "min": 0, "name": "RC_FAILS_THR", "shortDesc": "Failsafe channel PWM threshold", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX1", "shortDesc": "AUX1 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX2", "shortDesc": "AUX2 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX3", "shortDesc": "AUX3 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX4", "shortDesc": "AUX4 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX5", "shortDesc": "AUX5 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX6", "shortDesc": "AUX6 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_ENG_MOT", "shortDesc": "RC channel to engage the main motor (for helicopters)", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Configures which RC channel is used by the receiver to indicate the signal was lost\n(on receivers that use output a fixed signal value to report lost signal).\nIf set to 0, the channel mapped to throttle is used.\nUse RC_FAILS_THR to set the threshold indicating lost signal. By default it's below\nthe expected range and hence disabled.", "max": 18, "min": 0, "name": "RC_MAP_FAILSAFE", "shortDesc": "Failsafe channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel.\nSet to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM1", "shortDesc": "PARAM1 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel.\nSet to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM2", "shortDesc": "PARAM2 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel.\nSet to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM3", "shortDesc": "PARAM3 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates\nwhich channel should be used for reading pitch inputs from.\nA value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_PITCH", "shortDesc": "Pitch control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates\nwhich channel should be used for reading roll inputs from.\nA value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_ROLL", "shortDesc": "Roll control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates\nwhich channel should be used for reading throttle inputs from.\nA value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_THROTTLE", "shortDesc": "Throttle control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates\nwhich channel should be used for reading yaw inputs from.\nA value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_YAW", "shortDesc": "Yaw control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "0: do not read RSSI from input channel\n1-18: read RSSI from specified input channel\nSpecify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters.", "max": 18, "min": 0, "name": "RC_RSSI_PWM_CHAN", "shortDesc": "PWM input channel that provides RSSI", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 2000, "group": "Radio Calibration", "longDesc": "Only used if RC_RSSI_PWM_CHAN > 0", "max": 2000, "min": 0, "name": "RC_RSSI_PWM_MAX", "shortDesc": "Max input value for RSSI reading", "type": "Int32"}, {"category": "Standard", "default": 1000, "group": "Radio Calibration", "longDesc": "Only used if RC_RSSI_PWM_CHAN > 0", "max": 2000, "min": 0, "name": "RC_RSSI_PWM_MIN", "shortDesc": "Min input value for RSSI reading", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs\nfor straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_PITCH", "shortDesc": "Pitch trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs\nfor straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_ROLL", "shortDesc": "Roll trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs\nfor straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_YAW", "shortDesc": "Yaw trim", "type": "Float"}, {"category": "Standard", "default": 0.75, "group": "Radio Switches", "longDesc": "0-1 indicate where in the full channel range the threshold sits\n0 : min\n1 : max\nsign indicates polarity of comparison\npositive : true when channel>th\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channel The rover starts to cut the corner earlier.", "max": 100.0, "min": 1.0, "name": "RA_ACC_RAD_GAIN", "shortDesc": "Tuning parameter for corner cutting", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Ackermann", "increment": 0.01, "longDesc": "The controller scales the acceptance radius based on the angle between\nthe previous, current and next waypoint.\nHigher value -> smoother trajectory at the cost of how close the rover gets\nto the waypoint (Set to -1 to disable corner cutting).", "max": 100.0, "min": -1.0, "name": "RA_ACC_RAD_MAX", "shortDesc": "Maximum acceptance radius for the waypoints", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Ackermann", "increment": 0.01, "max": 1.5708, "min": 0.0, "name": "RA_MAX_STR_ANG", "shortDesc": "Maximum steering angle", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Ackermann", "increment": 0.01, "longDesc": "Set to -1 to disable.", "max": 1000.0, "min": -1.0, "name": "RA_STR_RATE_LIM", "shortDesc": "Steering rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Ackermann", "increment": 0.001, "longDesc": "Distance from the front to the rear axle.", "max": 100.0, "min": 0.0, "name": "RA_WHEEL_BASE", "shortDesc": "Wheel base", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Attitude Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_P", "shortDesc": "Proportional gain for closed loop yaw controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.174533, "group": "Rover Differential", "increment": 0.01, "longDesc": "This threshold is used for the state machine to switch from driving to turning based on the\nerror between the desired and actual yaw. It is also used as the threshold whether the rover should come\nto a smooth stop at the next waypoint. This slow down effect is active if the angle between the\nline segments from prevWP-currWP and currWP-nextWP is smaller then 180 - RD_TRANS_DRV_TRN.", "max": 3.14159, "min": 0.001, "name": "RD_TRANS_DRV_TRN", "shortDesc": "Yaw error threshhold to switch from driving to spot turning", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0872665, "group": "Rover Differential", "increment": 0.01, "longDesc": "This threshold is used for the state machine to switch from turning to driving based on the\nerror between the desired and actual yaw.", "max": 3.14159, "min": 0.001, "name": "RD_TRANS_TRN_DRV", "shortDesc": "Yaw error threshhold to switch from spot turning to driving", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Differential", "increment": 0.001, "longDesc": "Distance from the center of the right wheel to the center of the left wheel.", "max": 100.0, "min": 0.0, "name": "RD_WHEEL_TRACK", "shortDesc": "Wheel track", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.17, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "Threshold for the angle between the active cruise direction and the cruise direction given\nby the stick inputs.\nThis can be understood as a deadzone for the combined stick inputs for forward/backwards\nand lateral speed which defines a course direction.", "max": 3.14, "min": 0.0, "name": "RM_COURSE_CTL_TH", "shortDesc": "Threshold to update course control in manual position mode", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Mecanum", "increment": 0.001, "longDesc": "Distance from the center of the right wheel to the center of the left wheel.", "max": 100.0, "min": 0.0, "name": "RM_WHEEL_TRACK", "shortDesc": "Wheel track", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.75, "group": "Rover Position Control (Deprecated)", "increment": 0.05, "longDesc": "Damping factor for L1 control.", "max": 0.9, "min": 0.6, "name": "GND_L1_DAMPING", "shortDesc": "L1 damping", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Rover Position Control (Deprecated)", "increment": 0.1, "longDesc": "This is the distance at which the next waypoint is activated. This should be set\nto about 2-4x of GND_WHEEL_BASE and not smaller than one meter (due to GPS accuracy).", "max": 50.0, "min": 1.0, "name": "GND_L1_DIST", "shortDesc": "L1 distance", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Rover Position Control (Deprecated)", "increment": 0.5, "longDesc": "This is the L1 distance and defines the tracking\npoint ahead of the rover it's following.\nUse values around 2-5m for a 0.3m wheel base. Tuning instructions: Shorten\nslowly during tuning until response is sharp without oscillation.", "max": 50.0, "min": 0.5, "name": "GND_L1_PERIOD", "shortDesc": "L1 period", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 150.0, "group": "Rover Position Control (Deprecated)", "max": 400.0, "min": 0.0, "name": "GND_MAN_Y_MAX", "shortDesc": "Max manual yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.7854, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "At a control output of 0, the steering wheels are at 0 radians.\nAt a control output of 1, the steering wheels are at GND_MAX_ANG radians.", "max": 3.14159, "min": 0.0, "name": "GND_MAX_ANG", "shortDesc": "Maximum turn angle for Ackerman steering", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the derivative gain for the speed closed loop controller", "max": 50.0, "min": 0.0, "name": "GND_SPEED_D", "shortDesc": "Speed proportional gain", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the integral gain for the speed closed loop controller", "max": 50.0, "min": 0.0, "name": "GND_SPEED_I", "shortDesc": "Speed Integral gain", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the maxim value the integral can reach to prevent wind-up.", "max": 50.0, "min": 0.005, "name": "GND_SPEED_IMAX", "shortDesc": "Speed integral maximum value", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Rover Position Control (Deprecated)", "increment": 0.5, "max": 40.0, "min": 0.0, "name": "GND_SPEED_MAX", "shortDesc": "Maximum ground speed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 2.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is the proportional gain for the speed closed loop controller", "max": 50.0, "min": 0.005, "name": "GND_SPEED_P", "shortDesc": "Speed proportional gain", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Rover Position Control (Deprecated)", "increment": 0.005, "longDesc": "This is a gain to map the speed control output to the throttle linearly.", "max": 50.0, "min": 0.005, "name": "GND_SPEED_THR_SC", "shortDesc": "Speed to throttle scaler", "type": "Float", "units": "%m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Rover Position Control (Deprecated)", "increment": 0.5, "max": 40.0, "min": 0.0, "name": "GND_SPEED_TRIM", "shortDesc": "Trim ground speed", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "Rover Position Control (Deprecated)", "longDesc": "This allows the user to choose between closed loop gps speed or open loop cruise throttle speed", "max": 1, "min": 0, "name": "GND_SP_CTRL_MODE", "shortDesc": "Control mode for speed", "type": "Int32", "values": [{"description": "open loop control", "value": 0}, {"description": "close the loop with gps speed", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "This is the throttle setting required to achieve the desired cruise speed.\n10% is ok for a traxxas stampede vxl with ESC set to training mode", "max": 1.0, "min": 0.0, "name": "GND_THR_CRUISE", "shortDesc": "Cruise throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "This is the maximum throttle % that can be used by the controller.\nFor a Traxxas stampede vxl with the ESC set to training, 30 % is enough", "max": 1.0, "min": 0.0, "name": "GND_THR_MAX", "shortDesc": "Throttle limit max", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "This is the minimum throttle % that can be used by the controller.\nSet to 0 for rover", "max": 1.0, "min": 0.0, "name": "GND_THR_MIN", "shortDesc": "Throttle limit min", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.31, "group": "Rover Position Control (Deprecated)", "increment": 0.01, "longDesc": "A value of 0.31 is typical for 1/10 RC cars.", "min": 0.0, "name": "GND_WHEEL_BASE", "shortDesc": "Distance from front axle to rear axle", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap how quickly the magnitude of yaw rate setpoints can increase.\nSet to -1 to disable.", "max": 10000.0, "min": -1.0, "name": "RO_YAW_ACCEL_LIM", "shortDesc": "Yaw acceleration limit", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap how quickly the magnitude of yaw rate setpoints can decrease.\nSet to -1 to disable.", "max": 10000.0, "min": -1.0, "name": "RO_YAW_DECEL_LIM", "shortDesc": "Yaw deceleration limit", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Multiplicative correction factor for the feedforward mapping of the yaw rate controller.\nIncrease this value (x > 1) if the measured yaw rate is lower than the setpoint, decrease (0 < x < 1) otherwise.\nNote: Tuning this is particularly useful for skid-steered rovers, or rovers with misaligned wheels/steering axes\nthat cause a lot of friction when turning.", "max": 10000.0, "min": 0.01, "name": "RO_YAW_RATE_CORR", "shortDesc": "Yaw rate correction factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_I", "shortDesc": "Integral gain for closed loop yaw rate controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap yaw rate setpoints and map controller inputs to yaw rate setpoints\nin Acro, Stabilized and Position mode.", "max": 10000.0, "min": 0.0, "name": "RO_YAW_RATE_LIM", "shortDesc": "Yaw rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_P", "shortDesc": "Proportional gain for closed loop yaw rate controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "The minimum threshold for the yaw rate measurement not to be interpreted as zero.", "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_TH", "shortDesc": "Yaw rate measurement threshold", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Percentage of stick input range that will be interpreted as zero around the stick centered value.", "max": 1.0, "min": 0.0, "name": "RO_YAW_STICK_DZ", "shortDesc": "Yaw stick deadzone", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable.\nFor mecanum rovers this limit is used for longitudinal and lateral acceleration.", "max": 100.0, "min": -1.0, "name": "RO_ACCEL_LIM", "shortDesc": "Acceleration limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable.\nNote that if it is disabled the rover will not slow down when approaching waypoints in auto modes.\nFor mecanum rovers this limit is used for longitudinal and lateral deceleration.", "max": 100.0, "min": -1.0, "name": "RO_DECEL_LIM", "shortDesc": "Deceleration limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable.\nNote that if it is disabled the rover will not slow down when approaching waypoints in auto modes.\nFor mecanum rovers this limit is used for longitudinal and lateral jerk.", "max": 100.0, "min": -1.0, "name": "RO_JERK_LIM", "shortDesc": "Jerk limit", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Used to linearly map speeds [m/s] to throttle values [-1. 1].", "max": 100.0, "min": 0.0, "name": "RO_MAX_THR_SPEED", "shortDesc": "Speed the rover drives at maximum throttle", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.001, "max": 100.0, "min": 0.0, "name": "RO_SPEED_I", "shortDesc": "Integral gain for ground speed controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Used to cap speed setpoints and map controller inputs to speed setpoints in Position mode.", "max": 100.0, "min": -1.0, "name": "RO_SPEED_LIM", "shortDesc": "Speed limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_SPEED_P", "shortDesc": "Proportional gain for ground speed controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Reduced_speed = RO_MAX_THR_SPEED * (1 - normalized_course_error * RO_SPEED_RED)\nThe normalized course error is the angle between the current course and the bearing setpoint\ninterpolated from [0, 180] -> [0, 1].\nHigher value -> More speed reduction.\nNote: This is also used to calculate the speed at which the vehicle arrives at a waypoint in auto modes.\nSet to -1 to disable bearing error based speed reduction.", "max": 100.0, "min": -1.0, "name": "RO_SPEED_RED", "shortDesc": "Tuning parameter for the speed reduction based on the course error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable.\nThe minimum threshold for the speed measurement not to be interpreted as zero.", "max": 100.0, "min": 0.0, "name": "RO_SPEED_TH", "shortDesc": "Speed measurement threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Runway Takeoff", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "RWTO_MAX_THR", "shortDesc": "Throttle during runway takeoff", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 1, "group": "Runway Takeoff", "longDesc": "This is useful when map, GNSS, or yaw errors on ground are misaligned with what the operator intends for takeoff course.\nParticularly useful for skinny runways or if the wheel servo is a bit off trim.", "name": "RWTO_NUDGE", "shortDesc": "Enable use of yaw stick for nudging the wheel during runway ground roll", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Runway Takeoff", "increment": 0.5, "longDesc": "A taildragger with steerable wheel might need to pitch up\na little to keep its wheel on the ground before airspeed\nto takeoff is reached.", "max": 20.0, "min": -10.0, "name": "RWTO_PSP", "shortDesc": "Pitch setpoint during taxi / before takeoff rotation airspeed is reached", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Runway Takeoff", "increment": 0.1, "max": 15.0, "min": 1.0, "name": "RWTO_RAMP_TIME", "shortDesc": "Throttle ramp up time for runway takeoff", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Runway Takeoff", "increment": 0.1, "longDesc": "The calibrated airspeed threshold during the takeoff ground roll when the plane should start rotating (pitching up).\nMust be less than the takeoff airspeed, will otherwise be capped at the takeoff airpeed (see FW_TKO_AIRSPD).\nIf set <= 0.0, defaults to 0.9 * takeoff airspeed (see FW_TKO_AIRSPD)", "min": -1.0, "name": "RWTO_ROT_AIRSPD", "shortDesc": "Takeoff rotation airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Runway Takeoff", "increment": 0.1, "longDesc": "This is the time desired to linearly ramp in takeoff pitch constraints during the takeoff rotation", "min": 0.1, "name": "RWTO_ROT_TIME", "shortDesc": "Takeoff rotation time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Runway Takeoff", "name": "RWTO_TKOFF", "shortDesc": "Runway takeoff with landing gear", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "SD Logging", "longDesc": "Selects the algorithm used for logfile encryption", "name": "SDLOG_ALGORITHM", "shortDesc": "Logfile Encryption algorithm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "XChaCha20", "value": 2}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "When enabled, logging will not start from boot if battery power is not detected\n(e.g. powered via USB on a test bench). This prevents extraneous flight logs from\nbeing created during bench testing.\nNote that this only applies to log-from-boot modes. This has no effect on arm-based\nmodes.", "name": "SDLOG_BOOT_BAT", "shortDesc": "Battery-only Logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "If there are more log directories than this value,\nthe system will delete the oldest directories during startup.\nIn addition, the system will delete old logs if there is not enough free space left.\nThe minimum amount is 300 MB.\nIf this is set to 0, old directories will only be removed if the free space falls below\nthe minimum.\nNote: this does not apply to mission log files.", "max": 1000, "min": 0, "name": "SDLOG_DIRS_MAX", "rebootRequired": true, "shortDesc": "Maximum number of log directories to keep", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "If the logfile is encrypted using a symmetric key algorithm,\nthe used encryption key is generated at logging start and stored\non the sdcard RSA2048 encrypted using this key.", "max": 255, "min": 0, "name": "SDLOG_EXCH_KEY", "shortDesc": "Logfile Encryption key exchange key", "type": "Int32"}, {"category": "Standard", "default": 2, "group": "SD Logging", "longDesc": "Selects the key in keystore, used for encrypting the log. When using\na symmetric encryption algorithm, the key is generated at logging start\nand kept stored in this index. For symmetric algorithms, the key is\nvolatile and valid only for the duration of logging. The key is stored\nin encrypted format on the sdcard alongside the logfile, using an RSA2048\nkey defined by the SDLOG_EXCHANGE_KEY", "max": 255, "min": 0, "name": "SDLOG_KEY", "shortDesc": "Logfile Encryption key index", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "If enabled, a small additional \"mission\" log file will be written to the SD card.\nThe log contains just those messages that are useful for tasks like\ngenerating flight statistics and geotagging.\nThe different modes can be used to further reduce the logged data\n(and thus the log file size). For example, choose geotagging mode to\nonly log data required for geotagging.\nNote that the normal/full log is still created, and contains all\nthe data in the mission log (and more).", "name": "SDLOG_MISSION", "rebootRequired": true, "shortDesc": "Mission Log", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "All mission messages", "value": 1}, {"description": "Geotagging messages", "value": 2}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "Determines when to start and stop logging. By default, logging is started\nwhen arming the system, and stopped when disarming.", "name": "SDLOG_MODE", "rebootRequired": true, "shortDesc": "Logging Mode", "type": "Int32", "values": [{"description": "disabled", "value": -1}, {"description": "when armed until disarm (default)", "value": 0}, {"description": "from boot until disarm", "value": 1}, {"description": "from boot until shutdown", "value": 2}, {"description": "while manual input AUX1 >30%", "value": 3}, {"description": "from 1st armed until shutdown", "value": 4}]}, {"bitmask": [{"description": "Default set (general log analysis)", "index": 0}, {"description": "Estimator replay (EKF2)", "index": 1}, {"description": "Thermal calibration", "index": 2}, {"description": "System identification", "index": 3}, {"description": "High rate", "index": 4}, {"description": "Debug", "index": 5}, {"description": "Sensor comparison", "index": 6}, {"description": "Computer Vision and Avoidance", "index": 7}, {"description": "Raw FIFO high-rate IMU (Gyro)", "index": 8}, {"description": "Raw FIFO high-rate IMU (Accel)", "index": 9}, {"description": "Mavlink tunnel message logging", "index": 10}, {"description": "High rate sensors", "index": 11}], "category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "This integer bitmask controls the set and rates of logged topics.\nThe default allows for general log analysis while keeping the\nlog file size reasonably small.\nEnabling multiple sets leads to higher bandwidth requirements and larger log\nfiles.\nSet bits true to enable:\n0 : Default set (used for general log analysis)\n1 : Full rate estimator (EKF2) replay topics\n2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data)\n3 : Topics for system identification (high rate actuator control and IMU data)\n4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators)\n5 : Debugging topics (debug_*.msg topics, for custom code)\n6 : Topics for sensor comparison (low rate raw IMU, Baro and magnetometer data)\n7 : Topics for computer vision and collision prevention\n8 : Raw FIFO high-rate IMU (Gyro)\n9 : Raw FIFO high-rate IMU (Accel)\n10: Logging of mavlink tunnel message (useful for payload communication debugging)", "max": 4095, "min": 0, "name": "SDLOG_PROFILE", "rebootRequired": true, "shortDesc": "Logging topic profile (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "the difference in hours and minutes from Coordinated\nUniversal Time (UTC) for a your place and date.\nfor example, In case of South Korea(UTC+09:00),\nUTC offset is 540 min (9*60)\nrefer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets", "max": 1000, "min": -1000, "name": "SDLOG_UTC_OFFSET", "shortDesc": "UTC offset (unit: min)", "type": "Int32", "units": "min"}, {"category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "If set to 1, add an ID to the log, which uniquely identifies the vehicle", "name": "SDLOG_UUID", "shortDesc": "Log UUID", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 60.0, "group": "SITL", "increment": 1.0, "max": 86400.0, "min": 1.0, "name": "SIM_BAT_DRAIN", "shortDesc": "Simulator Battery drain interval", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "SITL", "longDesc": "Enable or disable the internal battery simulation. This is useful\nwhen the battery is simulated externally and interfaced with PX4\nthrough MAVLink for example.", "name": "SIM_BAT_ENABLE", "shortDesc": "Simulator Battery enabled", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 50.0, "group": "SITL", "increment": 0.1, "longDesc": "Can be used to alter the battery level during SITL- or HITL-simulation on the fly.\nParticularly useful for testing different low-battery behaviour.", "max": 100.0, "min": 0.0, "name": "SIM_BAT_MIN_PCT", "shortDesc": "Simulator Battery minimal percentage", "type": "Float", "units": "%"}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC0_ID", "shortDesc": "Accelerometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC0_PRIO", "shortDesc": "Accelerometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC0_ROT", "shortDesc": "Accelerometer 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_XOFF", "shortDesc": "Accelerometer 0 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_XSCALE", "shortDesc": "Accelerometer 0 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_YOFF", "shortDesc": "Accelerometer 0 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_YSCALE", "shortDesc": "Accelerometer 0 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_ZOFF", "shortDesc": "Accelerometer 0 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_ZSCALE", "shortDesc": "Accelerometer 0 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC1_ID", "shortDesc": "Accelerometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC1_PRIO", "shortDesc": "Accelerometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC1_ROT", "shortDesc": "Accelerometer 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_XOFF", "shortDesc": "Accelerometer 1 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_XSCALE", "shortDesc": "Accelerometer 1 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_YOFF", "shortDesc": "Accelerometer 1 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_YSCALE", "shortDesc": "Accelerometer 1 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_ZOFF", "shortDesc": "Accelerometer 1 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_ZSCALE", "shortDesc": "Accelerometer 1 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC2_ID", "shortDesc": "Accelerometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC2_PRIO", "shortDesc": "Accelerometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC2_ROT", "shortDesc": "Accelerometer 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_XOFF", "shortDesc": "Accelerometer 2 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_XSCALE", "shortDesc": "Accelerometer 2 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_YOFF", "shortDesc": "Accelerometer 2 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_YSCALE", "shortDesc": "Accelerometer 2 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_ZOFF", "shortDesc": "Accelerometer 2 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_ZSCALE", "shortDesc": "Accelerometer 2 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC3_ID", "shortDesc": "Accelerometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC3_PRIO", "shortDesc": "Accelerometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC3_ROT", "shortDesc": "Accelerometer 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_XOFF", "shortDesc": "Accelerometer 3 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_XSCALE", "shortDesc": "Accelerometer 3 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_YOFF", "shortDesc": "Accelerometer 3 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_YSCALE", "shortDesc": "Accelerometer 3 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_ZOFF", "shortDesc": "Accelerometer 3 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_ZSCALE", "shortDesc": "Accelerometer 3 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO0_ID", "shortDesc": "Barometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO0_OFF", "shortDesc": "Barometer 0 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO0_PRIO", "shortDesc": "Barometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO1_ID", "shortDesc": "Barometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO1_OFF", "shortDesc": "Barometer 1 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO1_PRIO", "shortDesc": "Barometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO2_ID", "shortDesc": "Barometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO2_OFF", "shortDesc": "Barometer 2 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO2_PRIO", "shortDesc": "Barometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO3_ID", "shortDesc": "Barometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO3_OFF", "shortDesc": "Barometer 3 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO3_PRIO", "shortDesc": "Barometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO0_ID", "shortDesc": "Gyroscope 0 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO0_PRIO", "shortDesc": "Gyroscope 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO0_ROT", "shortDesc": "Gyroscope 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_XOFF", "shortDesc": "Gyroscope 0 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_YOFF", "shortDesc": "Gyroscope 0 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_ZOFF", "shortDesc": "Gyroscope 0 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO1_ID", "shortDesc": "Gyroscope 1 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO1_PRIO", "shortDesc": "Gyroscope 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO1_ROT", "shortDesc": "Gyroscope 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_XOFF", "shortDesc": "Gyroscope 1 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_YOFF", "shortDesc": "Gyroscope 1 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_ZOFF", "shortDesc": "Gyroscope 1 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO2_ID", "shortDesc": "Gyroscope 2 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO2_PRIO", "shortDesc": "Gyroscope 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO2_ROT", "shortDesc": "Gyroscope 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_XOFF", "shortDesc": "Gyroscope 2 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_YOFF", "shortDesc": "Gyroscope 2 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_ZOFF", "shortDesc": "Gyroscope 2 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO3_ID", "shortDesc": "Gyroscope 3 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO3_PRIO", "shortDesc": "Gyroscope 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO3_ROT", "shortDesc": "Gyroscope 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_XOFF", "shortDesc": "Gyroscope 3 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_YOFF", "shortDesc": "Gyroscope 3 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_ZOFF", "shortDesc": "Gyroscope 3 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG0_ID", "shortDesc": "Magnetometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_PITCH", "shortDesc": "Magnetometer 0 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG0_PRIO", "shortDesc": "Magnetometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_ROLL", "shortDesc": "Magnetometer 0 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.\nSet to \"Custom Euler Angle\" to define the rotation using CAL_MAG0_ROLL, CAL_MAG0_PITCH and CAL_MAG0_YAW.", "max": 100, "min": -1, "name": "CAL_MAG0_ROT", "shortDesc": "Magnetometer 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nX component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG0_XCOMP", "shortDesc": "Magnetometer 0 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_XODIAG", "shortDesc": "Magnetometer 0 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_XOFF", "shortDesc": "Magnetometer 0 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_XSCALE", "shortDesc": "Magnetometer 0 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_YAW", "shortDesc": "Magnetometer 0 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nY component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG0_YCOMP", "shortDesc": "Magnetometer 0 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_YODIAG", "shortDesc": "Magnetometer 0 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_YOFF", "shortDesc": "Magnetometer 0 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_YSCALE", "shortDesc": "Magnetometer 0 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nZ component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG0_ZCOMP", "shortDesc": "Magnetometer 0 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_ZODIAG", "shortDesc": "Magnetometer 0 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_ZOFF", "shortDesc": "Magnetometer 0 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_ZSCALE", "shortDesc": "Magnetometer 0 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG1_ID", "shortDesc": "Magnetometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_PITCH", "shortDesc": "Magnetometer 1 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG1_PRIO", "shortDesc": "Magnetometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_ROLL", "shortDesc": "Magnetometer 1 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.\nSet to \"Custom Euler Angle\" to define the rotation using CAL_MAG1_ROLL, CAL_MAG1_PITCH and CAL_MAG1_YAW.", "max": 100, "min": -1, "name": "CAL_MAG1_ROT", "shortDesc": "Magnetometer 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nX component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG1_XCOMP", "shortDesc": "Magnetometer 1 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_XODIAG", "shortDesc": "Magnetometer 1 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_XOFF", "shortDesc": "Magnetometer 1 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_XSCALE", "shortDesc": "Magnetometer 1 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_YAW", "shortDesc": "Magnetometer 1 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nY component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG1_YCOMP", "shortDesc": "Magnetometer 1 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_YODIAG", "shortDesc": "Magnetometer 1 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_YOFF", "shortDesc": "Magnetometer 1 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_YSCALE", "shortDesc": "Magnetometer 1 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nZ component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG1_ZCOMP", "shortDesc": "Magnetometer 1 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_ZODIAG", "shortDesc": "Magnetometer 1 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_ZOFF", "shortDesc": "Magnetometer 1 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_ZSCALE", "shortDesc": "Magnetometer 1 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG2_ID", "shortDesc": "Magnetometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_PITCH", "shortDesc": "Magnetometer 2 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG2_PRIO", "shortDesc": "Magnetometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_ROLL", "shortDesc": "Magnetometer 2 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.\nSet to \"Custom Euler Angle\" to define the rotation using CAL_MAG2_ROLL, CAL_MAG2_PITCH and CAL_MAG2_YAW.", "max": 100, "min": -1, "name": "CAL_MAG2_ROT", "shortDesc": "Magnetometer 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nX component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG2_XCOMP", "shortDesc": "Magnetometer 2 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_XODIAG", "shortDesc": "Magnetometer 2 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_XOFF", "shortDesc": "Magnetometer 2 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_XSCALE", "shortDesc": "Magnetometer 2 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_YAW", "shortDesc": "Magnetometer 2 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nY component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG2_YCOMP", "shortDesc": "Magnetometer 2 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_YODIAG", "shortDesc": "Magnetometer 2 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_YOFF", "shortDesc": "Magnetometer 2 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_YSCALE", "shortDesc": "Magnetometer 2 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nZ component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG2_ZCOMP", "shortDesc": "Magnetometer 2 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_ZODIAG", "shortDesc": "Magnetometer 2 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_ZOFF", "shortDesc": "Magnetometer 2 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_ZSCALE", "shortDesc": "Magnetometer 2 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG3_ID", "shortDesc": "Magnetometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_PITCH", "shortDesc": "Magnetometer 3 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG3_PRIO", "shortDesc": "Magnetometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_ROLL", "shortDesc": "Magnetometer 3 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.\nSet to \"Custom Euler Angle\" to define the rotation using CAL_MAG3_ROLL, CAL_MAG3_PITCH and CAL_MAG3_YAW.", "max": 100, "min": -1, "name": "CAL_MAG3_ROT", "shortDesc": "Magnetometer 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nX component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG3_XCOMP", "shortDesc": "Magnetometer 3 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_XODIAG", "shortDesc": "Magnetometer 3 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_XOFF", "shortDesc": "Magnetometer 3 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_XSCALE", "shortDesc": "Magnetometer 3 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_YAW", "shortDesc": "Magnetometer 3 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nY component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG3_YCOMP", "shortDesc": "Magnetometer 3 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_YODIAG", "shortDesc": "Magnetometer 3 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_YOFF", "shortDesc": "Magnetometer 3 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_YSCALE", "shortDesc": "Magnetometer 3 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nZ component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG3_ZCOMP", "shortDesc": "Magnetometer 3 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_ZODIAG", "shortDesc": "Magnetometer 3 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_ZOFF", "shortDesc": "Magnetometer 3 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_ZSCALE", "shortDesc": "Magnetometer 3 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "name": "CAL_MAG_COMP_TYP", "shortDesc": "Type of magnetometer compensation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Throttle-based compensation", "value": 1}, {"description": "Current-based compensation (battery_status instance 0)", "value": 2}, {"description": "Current-based compensation (battery_status instance 1)", "value": 3}]}, {"category": "Standard", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Pick the appropriate scaling from the datasheet.\nthis number defines the (linear) conversion from voltage\nto Pascal (pa). For the MPXV7002DP this is 1000.\nNOTE: If the sensor always registers zero, try switching\nthe static and dynamic tubes.", "name": "SENS_DPRES_ANSC", "shortDesc": "Differential pressure sensor analog scaling", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "The offset (zero-reading) in Pascal", "name": "SENS_DPRES_OFF", "shortDesc": "Differential pressure sensor offset", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Reverse the raw measurements of all differential pressure sensors.\nThis can be enabled if the sensors have static and dynamic ports swapped.", "name": "SENS_DPRES_REV", "shortDesc": "Reverse differential pressure sensor readings", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 100.0, "group": "Sensor Calibration", "increment": 0.1, "longDesc": "This parameter defines the maximum distance from ground at which the optical flow sensor operates reliably.\nThe height setpoint will be limited to be no greater than this value when the navigation system\nis completely reliant on optical flow data and the height above ground estimate is valid.\nThe sensor may be usable above this height, but accuracy will progressively degrade.", "max": 100.0, "min": 1.0, "name": "SENS_FLOW_MAXHGT", "shortDesc": "Maximum height above ground when reliant on optical flow", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 8.0, "group": "Sensor Calibration", "longDesc": "Optical flow data will not fused by the estimators if the magnitude of the flow rate exceeds this value and\ncontrol loops will be instructed to limit ground speed such that the flow rate produced by movement over ground\nis less than 50% of this value.", "min": 1.0, "name": "SENS_FLOW_MAXR", "shortDesc": "Magnitude of maximum angular flow rate reliably measurable by the optical flow sensor", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Sensor Calibration", "increment": 0.1, "longDesc": "This parameter defines the minimum distance from ground at which the optical flow sensor operates reliably.\nThe sensor may be usable below this height, but accuracy will progressively reduce to loss of focus.", "max": 1.0, "min": 0.0, "name": "SENS_FLOW_MINHGT", "shortDesc": "Minimum height above ground when reliant on optical flow", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "Model with Pitot\nCAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed.\nCAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor.\nModel without Pitot (1.5 mm tubes)\nCAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed.\nCAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor.\nTube Pressure Drop\nCAL_AIR_TUBED_MM: Diameter in mm of the pitot and tubes, must have the same diameter.\nCAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor and the static + dynamic port length of the pitot.", "name": "CAL_AIR_CMODEL", "shortDesc": "Airspeed sensor compensation model for the SDP3x", "type": "Int32", "values": [{"description": "Model with Pitot", "value": 0}, {"description": "Model without Pitot (1.5 mm tubes)", "value": 1}, {"description": "Tube Pressure Drop", "value": 2}]}, {"category": "Standard", "default": 1.5, "group": "Sensors", "max": 100.0, "min": 1.5, "name": "CAL_AIR_TUBED_MM", "shortDesc": "Airspeed sensor tube diameter. Only used for the Tube Pressure Drop Compensation", "type": "Float", "units": "mm"}, {"category": "Standard", "default": 0.2, "group": "Sensors", "longDesc": "See the CAL_AIR_CMODEL explanation on how this parameter should be set.", "max": 2.0, "min": 0.01, "name": "CAL_AIR_TUBELEN", "shortDesc": "Airspeed sensor tube length", "type": "Float", "units": "m"}, {"category": "Developer", "default": 63, "group": "Sensors", "longDesc": "Use SENS_MAG_SIDES instead", "name": "CAL_MAG_SIDES", "shortDesc": "For legacy QGC support only", "type": "Int32"}, {"category": "Standard", "default": 30.0, "group": "Sensors", "longDesc": "The cutoff frequency for the 2nd order butterworth filter on the primary accelerometer.\nThis only affects the signal sent to the controllers, not the estimators. 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_ACCEL_CUTOFF", "rebootRequired": true, "shortDesc": "Low pass filter cutoff frequency for accel", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The cutoff frequency for the 2nd order butterworth filter used on\nthe time derivative of the measured angular velocity, also known as\nthe D-term filter in the rate controller. The D-term uses the derivative of\nthe rate and thus is the most susceptible to noise. Therefore, using\na D-term filter allows to increase IMU_GYRO_CUTOFF, which\nleads to reduced control latency and permits to increase the P gains.\nA value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_DGYRO_CUTOFF", "rebootRequired": true, "shortDesc": "Cutoff frequency for angular acceleration (D-Term filter)", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 1, "group": "Sensors", "name": "IMU_GYRO_CAL_EN", "rebootRequired": true, "shortDesc": "IMU gyro auto calibration enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Sensors", "increment": 0.1, "longDesc": "The cutoff frequency for the 2nd order butterworth filter on the primary gyro.\nThis only affects the angular velocity sent to the controllers, not the estimators.\nIt applies also to the angular acceleration (D-Term filter), see IMU_DGYRO_CUTOFF.\nA value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_CUTOFF", "rebootRequired": true, "shortDesc": "Low pass filter cutoff frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "Sensors", "increment": 0.1, "longDesc": "Bandwidth per notch filter when using dynamic notch filtering with ESC RPM.", "max": 30.0, "min": 5.0, "name": "IMU_GYRO_DNF_BW", "shortDesc": "IMU gyro ESC notch filter bandwidth", "type": "Float", "units": "Hz"}, {"bitmask": [{"description": "ESC RPM", "index": 0}, {"description": "FFT", "index": 1}], "category": "Standard", "default": 0, "group": "Sensors", "longDesc": "Enable bank of dynamically updating notch filters.\nRequires ESC RPM feedback or onboard FFT (IMU_GYRO_FFT_EN).", "max": 3, "min": 0, "name": "IMU_GYRO_DNF_EN", "shortDesc": "IMU gyro dynamic notch filtering", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "Sensors", "longDesc": "ESC RPM number of harmonics (multiples of RPM) for ESC RPM dynamic notch filtering.", "max": 7, "min": 1, "name": "IMU_GYRO_DNF_HMC", "shortDesc": "IMU gyro dynamic notch filter harmonics", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "Sensors", "increment": 0.1, "longDesc": "Minimum notch filter frequency in Hz.", "name": "IMU_GYRO_DNF_MIN", "shortDesc": "IMU gyro dynamic notch filter minimum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "name": "IMU_GYRO_FFT_EN", "rebootRequired": true, "shortDesc": "IMU gyro FFT enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 512, "group": "Sensors", "name": "IMU_GYRO_FFT_LEN", "rebootRequired": true, "shortDesc": "IMU gyro FFT length", "type": "Int32", "units": "Hz", "values": [{"description": "256", "value": 256}, {"description": "512", "value": 512}, {"description": "1024", "value": 1024}, {"description": "4096", "value": 4096}]}, {"category": "Standard", "default": 150.0, "group": "Sensors", "max": 1000.0, "min": 1.0, "name": "IMU_GYRO_FFT_MAX", "rebootRequired": true, "shortDesc": "IMU gyro FFT maximum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 30.0, "group": "Sensors", "max": 1000.0, "min": 1.0, "name": "IMU_GYRO_FFT_MIN", "rebootRequired": true, "shortDesc": "IMU gyro FFT minimum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 10.0, "group": "Sensors", "max": 30.0, "min": 1.0, "name": "IMU_GYRO_FFT_SNR", "shortDesc": "IMU gyro FFT SNR", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The frequency width of the stop band for the 2nd order notch filter on the primary gyro.\nSee \"IMU_GYRO_NF0_FRQ\" to activate the filter and to set the notch frequency.\nApplies to both angular velocity and angular acceleration sent to the controllers.", "max": 100.0, "min": 0.0, "name": "IMU_GYRO_NF0_BW", "rebootRequired": true, "shortDesc": "Notch filter bandwidth for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "increment": 0.1, "longDesc": "The center frequency for the 2nd order notch filter on the primary gyro.\nThis filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency.\nThis only affects the signal sent to the controllers, not the estimators.\nApplies to both angular velocity and angular acceleration sent to the controllers.\nSee \"IMU_GYRO_NF0_BW\" to set the bandwidth of the filter.\nA value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_NF0_FRQ", "rebootRequired": true, "shortDesc": "Notch filter frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The frequency width of the stop band for the 2nd order notch filter on the primary gyro.\nSee \"IMU_GYRO_NF1_FRQ\" to activate the filter and to set the notch frequency.\nApplies to both angular velocity and angular acceleration sent to the controllers.", "max": 100.0, "min": 0.0, "name": "IMU_GYRO_NF1_BW", "rebootRequired": true, "shortDesc": "Notch filter 1 bandwidth for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "increment": 0.1, "longDesc": "The center frequency for the 2nd order notch filter on the primary gyro.\nThis filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency.\nThis only affects the signal sent to the controllers, not the estimators.\nApplies to both angular velocity and angular acceleration sent to the controllers.\nSee \"IMU_GYRO_NF1_BW\" to set the bandwidth of the filter.\nA value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_NF1_FRQ", "rebootRequired": true, "shortDesc": "Notch filter 2 frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 400, "group": "Sensors", "longDesc": "The maximum rate the gyro control data (vehicle_angular_velocity) will be\nallowed to publish at. This is the loop rate for the rate controller and outputs.\nNote: sensor data is always read and filtered at the full raw rate (eg commonly 8 kHz) regardless of this setting.", "max": 2000, "min": 100, "name": "IMU_GYRO_RATEMAX", "rebootRequired": true, "shortDesc": "Gyro control data maximum publication rate (inner loop rate)", "type": "Int32", "units": "Hz", "values": [{"description": "100 Hz", "value": 100}, {"description": "250 Hz", "value": 250}, {"description": "400 Hz", "value": 400}, {"description": "800 Hz", "value": 800}, {"description": "1000 Hz", "value": 1000}, {"description": "2000 Hz", "value": 2000}]}, {"category": "Standard", "default": 200, "group": "Sensors", "longDesc": "The rate at which raw IMU data is integrated to produce delta angles and delta velocities.\nRecommended to set this to a multiple of the estimator update period (currently 10 ms for ekf2).", "max": 1000, "min": 100, "name": "IMU_INTEG_RATE", "rebootRequired": true, "shortDesc": "IMU integration rate", "type": "Int32", "units": "Hz", "values": [{"description": "100 Hz", "value": 100}, {"description": "200 Hz", "value": 200}, {"description": "250 Hz", "value": 250}, {"description": "400 Hz", "value": 400}]}, {"category": "Standard", "default": 1013.25, "group": "Sensors", "max": 1500.0, "min": 500.0, "name": "SENS_BARO_QNH", "shortDesc": "QNH for barometer", "type": "Float", "units": "hPa"}, {"category": "Standard", "default": 20.0, "group": "Sensors", "longDesc": "Barometric air data maximum publication rate. This is an upper bound,\nactual barometric data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_BARO_RATE", "shortDesc": "Baro max rate", "type": "Float", "units": "Hz"}, {"category": "System", "default": 0, "group": "Sensors", "longDesc": "Automatically calibrate barometer based on the GNSS height", "name": "SENS_BAR_AUTOCAL", "shortDesc": "Barometer auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "This parameter defines the rotation of the FMU board relative to the platform.", "max": 40, "min": -1, "name": "SENS_BOARD_ROT", "rebootRequired": true, "shortDesc": "Board rotation", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "longDesc": "Rotation from flight controller board to vehicle body frame.\nThis parameter gets set during the \"level horizon\" calibration or can be\nset manually.", "max": 45.0, "min": -45.0, "name": "SENS_BOARD_X_OFF", "shortDesc": "Board rotation X (roll) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "longDesc": "Rotation from flight controller board to vehicle body frame.\nThis parameter gets set during the \"level horizon\" calibration or can be\nset manually.", "max": 45.0, "min": -45.0, "name": "SENS_BOARD_Y_OFF", "shortDesc": "Board rotation Y (pitch) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "longDesc": "Rotation from flight controller board to vehicle body frame.\nHas to be set manually (not set by any calibration).", "max": 45.0, "min": -45.0, "name": "SENS_BOARD_Z_OFF", "shortDesc": "Board rotation Z (yaw) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_AGPSIM", "rebootRequired": true, "shortDesc": "Simulate Aux Global Position (AGP)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_ARSPDSIM", "rebootRequired": true, "shortDesc": "Enable simulated airspeed sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_BAROSIM", "rebootRequired": true, "shortDesc": "Enable simulated barometer sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_GPSSIM", "rebootRequired": true, "shortDesc": "Enable simulated GPS sinstance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_MAGSIM", "rebootRequired": true, "shortDesc": "Enable simulated magnetometer sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": -1, "group": "Sensors", "name": "SENS_EN_THERMAL", "shortDesc": "Thermal control of sensor temperature", "type": "Int32", "values": [{"description": "Thermal control unavailable", "value": -1}, {"description": "Thermal control off", "value": 0}, {"description": "Thermal control enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Probe for optional external I2C devices.", "name": "SENS_EXT_I2C_PRB", "shortDesc": "External I2C probe", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 70.0, "group": "Sensors", "longDesc": "Optical flow data maximum publication rate. This is an upper bound,\nactual optical flow data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_FLOW_RATE", "rebootRequired": true, "shortDesc": "Optical flow max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "This parameter defines the yaw rotation of the optical flow relative to the vehicle body frame.\nZero rotation is defined as X on flow board pointing towards front of vehicle.", "name": "SENS_FLOW_ROT", "shortDesc": "Optical flow rotation", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Sensors", "max": 1.5, "min": 0.5, "name": "SENS_FLOW_SCALE", "shortDesc": "Optical flow scale factor", "type": "Float"}, {"bitmask": [{"description": "use speed accuracy", "index": 0}, {"description": "use hpos accuracy", "index": 1}, {"description": "use vpos accuracy", "index": 2}], "category": "Standard", "default": 7, "group": "Sensors", "longDesc": "Set bits in the following positions to set which GPS accuracy metrics will be used to calculate the blending weight. Set to zero to disable and always used first GPS instance.\n0 : Set to true to use speed accuracy\n1 : Set to true to use horizontal position accuracy\n2 : Set to true to use vertical position accuracy", "max": 7, "min": 0, "name": "SENS_GPS_MASK", "shortDesc": "Multi GPS Blending Control Mask", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "When no blending is active, this defines the preferred GPS receiver instance.\nThe GPS selection logic waits until the primary receiver is available to\nsend data to the EKF even if a secondary instance is already available.\nThe secondary instance is then only used if the primary one times out.\nTo have an equal priority of all the instances, set this parameter to -1 and\nthe best receiver will be used.\nThis parameter has no effect if blending is active.", "max": 1, "min": -1, "name": "SENS_GPS_PRIME", "shortDesc": "Multi GPS primary instance", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Sensors", "longDesc": "Sets the longest time constant that will be applied to the calculation of GPS position and height offsets used to correct data from multiple GPS data for steady state position differences.", "max": 100.0, "min": 1.0, "name": "SENS_GPS_TAU", "shortDesc": "Multi GPS Blending Time Constant", "type": "Float", "units": "s"}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically initialize IMU (accel/gyro) calibration from bias estimates if available.", "name": "SENS_IMU_AUTOCAL", "shortDesc": "IMU auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Notify the user if the IMU is clipping", "name": "SENS_IMU_CLPNOTI", "shortDesc": "IMU notify clipping", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "name": "SENS_IMU_MODE", "rebootRequired": true, "shortDesc": "Sensors hub IMU mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Publish primary IMU selection", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "For systems with an external barometer, this should be set to false to make sure that the external is used.", "name": "SENS_INT_BARO_EN", "rebootRequired": true, "shortDesc": "Enable internal barometers", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically initialize magnetometer calibration from bias estimate if available.", "name": "SENS_MAG_AUTOCAL", "shortDesc": "Magnetometer auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Sensors", "longDesc": "During calibration attempt to automatically determine the rotation of external magnetometers.", "name": "SENS_MAG_AUTOROT", "shortDesc": "Automatically set external rotations", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "name": "SENS_MAG_MODE", "rebootRequired": true, "shortDesc": "Sensors hub mag mode", "type": "Int32", "values": [{"description": "Publish all magnetometers", "value": 0}, {"description": "Publish primary magnetometer", "value": 1}]}, {"category": "Standard", "default": 15.0, "group": "Sensors", "longDesc": "Magnetometer data maximum publication rate. This is an upper bound,\nactual magnetometer data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_MAG_RATE", "rebootRequired": true, "shortDesc": "Magnetometer max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 63, "group": "Sensors", "longDesc": "If set to two side calibration, only the offsets are estimated, the scale\ncalibration is left unchanged. Thus an initial six side calibration is\nrecommended.\nBits:\nORIENTATION_TAIL_DOWN = 1\nORIENTATION_NOSE_DOWN = 2\nORIENTATION_LEFT = 4\nORIENTATION_RIGHT = 8\nORIENTATION_UPSIDE_DOWN = 16\nORIENTATION_RIGHTSIDE_UP = 32", "max": 63, "min": 34, "name": "SENS_MAG_SIDES", "shortDesc": "Bitfield selecting mag sides for calibration", "type": "Int32", "values": [{"description": "Two side calibration", "value": 34}, {"description": "Three side calibration", "value": 38}, {"description": "Six side calibration", "value": 63}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SIM_ARSPD_FAIL", "rebootRequired": true, "shortDesc": "Dynamically simulate failure of airspeed sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 4, "default": 100.0, "group": "Simulation In Hardware", "increment": 0.01, "max": 1000.0, "min": 0.0, "name": "SIH_DISTSNSR_MAX", "shortDesc": "distance sensor maximum range", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.01, "max": 10.0, "min": 0.0, "name": "SIH_DISTSNSR_MIN", "shortDesc": "distance sensor minimum range", "type": "Float", "units": "m"}, {"category": "Standard", "default": -1.0, "group": "Simulation In Hardware", "longDesc": "Absolute value superior to 10000 will disable distance sensor", "name": "SIH_DISTSNSR_OVR", "shortDesc": "if >= 0 the distance sensor measures will be overridden by this value", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nIt represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IXX", "shortDesc": "Vehicle inertia about X axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nThis value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IXY", "shortDesc": "Vehicle cross term inertia xy", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nThis value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IXZ", "shortDesc": "Vehicle cross term inertia xz", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nIt represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IYY", "shortDesc": "Vehicle inertia about Y axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nThis value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IYZ", "shortDesc": "Vehicle cross term inertia yz", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nIt represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IZZ", "shortDesc": "Vehicle inertia about Z axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "Physical coefficient representing the friction with air particules.\nThe greater this value, the slower the quad will move.\nDrag force function of velocity: D=-KDV*V.\nThe maximum freefall velocity can be computed as V=10*MASS/KDV [m/s]", "min": 0.0, "name": "SIH_KDV", "shortDesc": "First order drag coefficient", "type": "Float", "units": "N/(m/s)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "Physical coefficient representing the friction with air particules during rotations.\nThe greater this value, the slower the quad will rotate.\nAerodynamic moment function of body rate: Ma=-KDW*W_B.\nThis value can be set to 0 if unknown.", "min": 0.0, "name": "SIH_KDW", "shortDesc": "First order angular damper coefficient", "type": "Float", "units": "Nm/(rad/s)"}, {"category": "Standard", "decimalPlaces": 2, "default": 489.4, "group": "Simulation In Hardware", "increment": 0.01, "longDesc": "This value represents the Above Mean Sea Level (AMSL) altitude where the simulation begins.\nIf using FlightGear as a visual animation,\nthis value can be tweaked such that the vehicle lies on the ground at takeoff.\nLAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others\nto represent a physical ground location on Earth.", "max": 8848.0, "min": -420.0, "name": "SIH_LOC_H0", "shortDesc": "Initial AMSL ground altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 47.397742, "group": "Simulation In Hardware", "longDesc": "This value represents the North-South location on Earth where the simulation begins.\nLAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others\nto represent a physical ground location on Earth.", "max": 90.0, "min": -90.0, "name": "SIH_LOC_LAT0", "shortDesc": "Initial geodetic latitude", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 8.545594, "group": "Simulation In Hardware", "longDesc": "This value represents the East-West location on Earth where the simulation begins.\nLAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others\nto represent a physical ground location on Earth.", "max": 180.0, "min": -180.0, "name": "SIH_LOC_LON0", "shortDesc": "Initial geodetic longitude", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the arm length generating the pitching moment\nThis value can be measured with a ruler.\nThis corresponds to half the distance between the front and rear motors.", "min": 0.0, "name": "SIH_L_PITCH", "shortDesc": "Pitch arm length", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the arm length generating the rolling moment\nThis value can be measured with a ruler.\nThis corresponds to half the distance between the left and right motors.", "min": 0.0, "name": "SIH_L_ROLL", "shortDesc": "Roll arm length", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Simulation In Hardware", "increment": 0.1, "longDesc": "This value can be measured by weighting the quad on a scale.", "min": 0.0, "name": "SIH_MASS", "shortDesc": "Vehicle mass", "type": "Float", "units": "kg"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the maximum torque delivered by one propeller\nwhen the motor is running at full speed.\nThis value is usually about few percent of the maximum thrust force.", "min": 0.0, "name": "SIH_Q_MAX", "shortDesc": "Max propeller torque", "type": "Float", "units": "Nm"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "Simulation In Hardware", "increment": 0.5, "longDesc": "This is the maximum force delivered by one propeller\nwhen the motor is running at full speed.\nThis value is usually about 5 times the mass of the quadrotor.", "min": 0.0, "name": "SIH_T_MAX", "shortDesc": "Max propeller thrust force", "type": "Float", "units": "N"}, {"category": "Standard", "default": 0.05, "group": "Simulation In Hardware", "longDesc": "the time taken for the thruster to step from 0 to 100% should be about 4 times tau", "name": "SIH_T_TAU", "shortDesc": "thruster time constant tau", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Simulation In Hardware", "name": "SIH_VEHICLE_TYPE", "rebootRequired": true, "shortDesc": "Vehicle type", "type": "Int32", "values": [{"description": "Quadcopter", "value": 0}, {"description": "Fixed-Wing", "value": 1}, {"description": "Tailsitter", "value": 2}, {"description": "Standard VTOL", "value": 3}, {"description": "Hexacopter", "value": 4}]}, {"bitmask": [{"description": "Stuck", "index": 0}, {"description": "Drift", "index": 1}], "category": "Standard", "default": 0, "group": "Simulator", "longDesc": "Stuck: freeze the measurement to the current location\nDrift: add a linearly growing bias to the sensor data", "max": 3, "min": 0, "name": "SIM_AGP_FAIL", "shortDesc": "AGP failure mode", "type": "Int32"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_BARO_OFF_P", "shortDesc": "simulated barometer pressure offset", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_BARO_OFF_T", "shortDesc": "simulated barometer temperature offset", "type": "Float", "units": "celcius"}, {"category": "Standard", "default": 10, "group": "Simulator", "max": 50, "min": 0, "name": "SIM_GPS_USED", "shortDesc": "simulated GPS number of satellites used", "type": "Int32"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_X", "shortDesc": "simulated magnetometer X offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_Y", "shortDesc": "simulated magnetometer Y offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_Z", "shortDesc": "simulated magnetometer Z offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "Set to 1 to reset parameters on next system startup (setting defaults).\nPlatform-specific values are used if available.\nRC* parameters are preserved.", "name": "SYS_AUTOCONFIG", "shortDesc": "Automatically configure default values", "type": "Int32", "values": [{"description": "Keep parameters", "value": 0}, {"description": "Reset parameters to airframe defaults", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "CHANGING THIS VALUE REQUIRES A RESTART. Defines the auto-start script used to bootstrap the system.", "max": 9999999, "min": 0, "name": "SYS_AUTOSTART", "rebootRequired": true, "shortDesc": "Auto-start script index", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled, update the bootloader on the next boot.\nWARNING: do not cut the power during an update process, otherwise you will\nhave to recover using some alternative method (e.g. JTAG).\nInstructions:\n- Insert an SD card\n- Enable this parameter\n- Reboot the board (plug the power or send a reboot command)\n- Wait until the board comes back up (or at least 2 minutes)\n- If it does not come back, check the file bootlog.txt on the SD card", "name": "SYS_BL_UPDATE", "rebootRequired": true, "shortDesc": "Bootloader update", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing\n1 : Set to 1 to start a calibration at next boot\nThis parameter is reset to zero when the temperature calibration starts.\ndefault (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_ACCEL", "shortDesc": "Enable auto start of accelerometer thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing\n1 : Set to 1 to start a calibration at next boot\nThis parameter is reset to zero when the temperature calibration starts.\ndefault (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_BARO", "shortDesc": "Enable auto start of barometer thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing\n1 : Set to 1 to start a calibration at next boot\nThis parameter is reset to zero when the temperature calibration starts.\ndefault (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_GYRO", "shortDesc": "Enable auto start of rate gyro thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 24, "group": "System", "longDesc": "A temperature increase greater than this value is required during calibration.\nCalibration will complete for each sensor when the temperature increase above the starting temperature exceeds the value set by SYS_CAL_TDEL.\nIf the temperature rise is insufficient, the calibration will continue indefinitely and the board will need to be repowered to exit.", "min": 10, "name": "SYS_CAL_TDEL", "shortDesc": "Required temperature rise during thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 10, "group": "System", "longDesc": "Temperature calibration will not start if the temperature of any sensor is higher than the value set by SYS_CAL_TMAX.", "name": "SYS_CAL_TMAX", "shortDesc": "Maximum starting temperature for thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 5, "group": "System", "longDesc": "Temperature calibration for each sensor will ignore data if the temperature is lower than the value set by SYS_CAL_TMIN.", "name": "SYS_CAL_TMIN", "shortDesc": "Minimum starting temperature for thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If the board supports persistent storage (i.e., the KConfig variable DATAMAN_PERSISTENT_STORAGE is set),\nthe 'Default storage' backend uses a file on persistent storage. If not supported, this backend uses\nnon-persistent storage in RAM.", "name": "SYS_DM_BACKEND", "rebootRequired": true, "shortDesc": "Dataman storage backend", "type": "Int32", "values": [{"description": "Dataman disabled", "value": -1}, {"description": "Default storage", "value": 0}, {"description": "RAM storage", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled, future sensor calibrations will be stored to /fs/mtd_caldata.\nNote: this is only supported on boards with a separate calibration storage\n/fs/mtd_caldata.", "name": "SYS_FAC_CAL_MODE", "shortDesc": "Enable factory calibration mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "All sensors", "value": 1}, {"description": "All sensors except mag", "value": 2}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled allows MAVLink INJECT_FAILURE commands.\nWARNING: the failures can easily cause crashes and are to be used with caution!", "name": "SYS_FAILURE_EN", "shortDesc": "Enable failure injection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "Disable this if the board has no barometer, such as some of the Omnibus\nF4 SD variants.\nIf disabled, the preflight checks will not check for the presence of a\nbarometer.", "name": "SYS_HAS_BARO", "rebootRequired": true, "shortDesc": "Control if the vehicle has a barometer", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "Disable this if the system has no GPS.\nIf disabled, the sensors hub will not process sensor_gps,\nand GPS will not be available for the rest of the system.", "name": "SYS_HAS_GPS", "rebootRequired": true, "shortDesc": "Control if the vehicle has a GPS", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "0: System has no magnetometer, preflight checks should pass without one.\n1-N: Require the presence of N magnetometer sensors for check to pass.", "name": "SYS_HAS_MAG", "rebootRequired": true, "shortDesc": "Control if and how many magnetometers are expected", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "Set this to 0 if the board has no airspeed sensor.\nIf set to 0, the preflight checks will not check for the presence of an\nairspeed sensor.", "max": 1, "min": 0, "name": "SYS_HAS_NUM_ASPD", "shortDesc": "Control if the vehicle has an airspeed sensor", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "The preflight check will fail if fewer than this number of distance sensors with valid data is present.\nDisable the check with 0.", "max": 4, "min": 0, "name": "SYS_HAS_NUM_DIST", "shortDesc": "Number of distance sensors to check being available", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "The preflight check will fail if fewer than this number of optical flow sensors with valid data are present.", "max": 1, "min": 0, "name": "SYS_HAS_NUM_OF", "shortDesc": "Number of optical flow sensors required to be available", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "While enabled the system will boot in Hardware-In-The-Loop (HITL)\nor Simulation-In-Hardware (SIH) mode and not enable all sensors and checks.\nWhen disabled the same vehicle can be flown normally.\nSet to 'external HITL', if the system should perform as if it were a real\nvehicle (the only difference to a real system is then only the parameter\nvalue, which can be used for log analysis).", "name": "SYS_HITL", "rebootRequired": true, "shortDesc": "Enable HITL/SIH mode on next boot", "type": "Int32", "values": [{"description": "external HITL", "value": -1}, {"description": "HITL and SIH disabled", "value": 0}, {"description": "HITL enabled", "value": 1}, {"description": "SIH enabled", "value": 2}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "This is used internally only: an airframe configuration might set an expected\nparameter version value via PARAM_DEFAULTS_VER. This is checked on bootup\nagainst SYS_PARAM_VER, and if they do not match, parameters are reset and\nreloaded from the airframe configuration.", "min": 0, "name": "SYS_PARAM_VER", "shortDesc": "Parameter version", "type": "Int32"}, {"category": "Standard", "default": 1.0, "group": "System", "longDesc": "Set to 0 to disable, 1 for maximum brightness", "name": "SYS_RGB_MAXBRT", "shortDesc": "RGB Led brightness limit", "type": "Float", "units": "%"}, {"category": "Standard", "default": 1, "group": "System", "name": "SYS_STCK_EN", "shortDesc": "Enable stack checking", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "Testing", "name": "TEST_1", "shortDesc": "TEST_1", "type": "Int32"}, {"category": "Standard", "default": 4, "group": "Testing", "name": "TEST_2", "shortDesc": "TEST_2", "type": "Int32"}, {"category": "Standard", "default": 5.0, "group": "Testing", "name": "TEST_3", "shortDesc": "TEST_3", "type": "Float"}, {"category": "Standard", "default": 0.01, "group": "Testing", "name": "TEST_D", "shortDesc": "TEST_D", "type": "Float"}, {"category": "Standard", "default": 2.0, "group": "Testing", "name": "TEST_DEV", "shortDesc": "TEST_DEV", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_D_LP", "shortDesc": "TEST_D_LP", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_HP", "shortDesc": "TEST_HP", "type": "Float"}, {"category": "Standard", "default": 0.1, "group": "Testing", "name": "TEST_I", "shortDesc": "TEST_I", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_I_MAX", "shortDesc": "TEST_I_MAX", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_LP", "shortDesc": "TEST_LP", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_MAX", "shortDesc": "TEST_MAX", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_MEAN", "shortDesc": "TEST_MEAN", "type": "Float"}, {"category": "Standard", "default": -1.0, "group": "Testing", "name": "TEST_MIN", "shortDesc": "TEST_MIN", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "Testing", "name": "TEST_P", "shortDesc": "TEST_P", "type": "Float"}, {"category": "Standard", "default": 12345678, "group": "Testing", "name": "TEST_PARAMS", "shortDesc": "TEST_PARAMS", "type": "Int32"}, {"category": "Standard", "default": 16, "group": "Testing", "name": "TEST_RC2_X", "shortDesc": "TEST_RC2_X", "type": "Int32"}, {"category": "Standard", "default": 8, "group": "Testing", "name": "TEST_RC_X", "shortDesc": "TEST_RC_X", "type": "Int32"}, {"category": "Standard", "default": 0.5, "group": "Testing", "name": "TEST_TRIM", "shortDesc": "TEST_TRIM", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A0_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A0_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A0_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A1_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A1_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A1_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A2_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A2_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A2_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A3_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A3_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A3_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_A_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for accelerometer sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B0_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B0_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B0_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B0_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B1_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B1_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B1_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B1_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B2_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B2_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B2_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B2_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B3_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B3_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B3_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B3_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_B_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for barometric pressure sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G0_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G0_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G0_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G1_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G1_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G1_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G2_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G2_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G2_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G3_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G3_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G3_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_G_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for rate gyro sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M0_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M0_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M0_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M1_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M1_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M1_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M2_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M2_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M2_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M3_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M3_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M3_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_M_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for magnetometer sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_PITCH", "shortDesc": "Direct pitch input", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_ROLL", "shortDesc": "Direct roll input", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_THRUST", "shortDesc": "Direct thrust input", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "UUV Attitude Control", "name": "UUV_DIRCT_YAW", "shortDesc": "Direct yaw input", "type": "Float"}, {"category": "Standard", "default": 0, "group": "UUV Attitude Control", "name": "UUV_INPUT_MODE", "shortDesc": "Select Input Mode", "type": "Int32", "values": [{"description": "use Attitude Setpoints", "value": 0}, {"description": "Direct Feedthrough", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_PITCH_D", "shortDesc": "Pitch differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_PITCH_P", "shortDesc": "Pitch proportional gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.5, "group": "UUV Attitude Control", "name": "UUV_ROLL_D", "shortDesc": "Roll differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_ROLL_P", "shortDesc": "Roll proportional gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_YAW_D", "shortDesc": "Yaw differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_YAW_P", "shortDesc": "Yawh proportional gain", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_X_D", "shortDesc": "Gain of D controller X", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_X_P", "shortDesc": "Gain of P controller X", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_Y_D", "shortDesc": "Gain of D controller Y", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_Y_P", "shortDesc": "Gain of P controller Y", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_Z_D", "shortDesc": "Gain of D controller Z", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_Z_P", "shortDesc": "Gain of P controller Z", "type": "Float"}, {"category": "Standard", "default": 1, "group": "UUV Position Control", "name": "UUV_STAB_MODE", "shortDesc": "Stabilization mode(1) or Position Control(0)", "type": "Int32", "values": [{"description": "Position Control", "value": 0}, {"description": "Stabilization Mode", "value": 1}]}, {"category": "Standard", "default": 2130706433, "group": "UXRCE-DDS Client", "longDesc": "If ethernet is enabled and is the selected configuration for uXRCE-DDS,\nthe selected Agent IP address will be set and used.\nDecimal dot notation is not supported. IP address must be provided\nin int32 format. For example, 192.168.1.2 is mapped to -1062731518;\n127.0.0.1 is mapped to 2130706433.", "name": "UXRCE_DDS_AG_IP", "rebootRequired": true, "shortDesc": "uXRCE-DDS Agent IP address", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "uXRCE-DDS domain ID", "name": "UXRCE_DDS_DOM_ID", "rebootRequired": true, "shortDesc": "uXRCE-DDS domain ID", "type": "Int32"}, {"category": "System", "default": 1, "group": "UXRCE-DDS Client", "longDesc": "uXRCE-DDS key, must be different from zero.\nIn a single agent - multi client configuration, each client\nmust have a unique session key.", "name": "UXRCE_DDS_KEY", "rebootRequired": true, "shortDesc": "uXRCE-DDS session key", "type": "Int32"}, {"category": "Standard", "default": 8888, "group": "UXRCE-DDS Client", "longDesc": "If ethernet is enabled and is the selected configuration for uXRCE-DDS,\nthe selected UDP port will be set and used.", "max": 65535, "min": 0, "name": "UXRCE_DDS_PRT", "rebootRequired": true, "shortDesc": "uXRCE-DDS UDP port", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "Set the participant configuration on the Agent's system.\n0: Use the default configuration.\n1: Restrict messages to localhost\n(use in combination with ROS_LOCALHOST_ONLY=1).\n2: Use a custom participant with the profile name \"px4_participant\".", "max": 2, "min": 0, "name": "UXRCE_DDS_PTCFG", "rebootRequired": true, "shortDesc": "uXRCE-DDS participant configuration", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Localhost-only", "value": 1}, {"description": "Custom participant", "value": 2}]}, {"category": "System", "default": -1, "group": "UXRCE-DDS Client", "longDesc": "Specifies after how many seconds without receiving data the DDS connection is reestablished.\nA value less than one disables the RX rate timeout.", "name": "UXRCE_DDS_RX_TO", "rebootRequired": true, "shortDesc": "RX rate timeout configuration", "type": "Int32", "units": "s"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "When enabled along with UXRCE_DDS_SYNCT, uxrce_dds_client will set the system clock using the agents UTC timestamp.", "name": "UXRCE_DDS_SYNCC", "rebootRequired": true, "shortDesc": "Enable uXRCE-DDS system clock synchronization", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "UXRCE-DDS Client", "longDesc": "When enabled, uxrce_dds_client will synchronize the timestamps of the incoming and outgoing messages measuring the offset between the Agent OS time and the PX4 time.", "name": "UXRCE_DDS_SYNCT", "rebootRequired": true, "shortDesc": "Enable uXRCE-DDS timestamp synchronization", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 3, "group": "UXRCE-DDS Client", "longDesc": "Specifies after how many seconds without sending data the DDS connection is reestablished.\nA value less than one disables the TX rate timeout.", "name": "UXRCE_DDS_TX_TO", "rebootRequired": true, "shortDesc": "TX rate timeout configuration", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 8.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Airspeed at which we can start blending both fw and mc controls. Set to 0 to disable.", "max": 30.0, "min": 0.0, "name": "VT_ARSP_BLEND", "shortDesc": "Transition blending airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Airspeed at which we can switch to fw mode", "max": 30.0, "min": 0.0, "name": "VT_ARSP_TRANS", "shortDesc": "Transition airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Time in seconds it takes to tilt form VT_TILT_FW to VT_TILT_MC.", "max": 10.0, "min": 0.1, "name": "VT_BT_TILT_DUR", "shortDesc": "Duration motor tilt up in backtransition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "VTOL Attitude Control", "increment": 0.05, "max": 0.3, "min": 0.0, "name": "VT_B_DEC_I", "shortDesc": "Backtransition deceleration setpoint to pitch I gain", "type": "Float", "units": "rad s/m"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Used to calculate back transition distance in an auto mode.\nFor standard vtol and tiltrotors a controller is used to track this value during the transition.", "max": 10.0, "min": 0.5, "name": "VT_B_DEC_MSS", "shortDesc": "Approximate deceleration during back transition", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Transition is also declared over if the groundspeed drops below MPC_XY_CRUISE.", "max": 20.0, "min": 0.1, "name": "VT_B_TRANS_DUR", "shortDesc": "Maximum duration of a back transition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "This sets the duration during which the MC motors ramp up to the commanded thrust during the back transition stage.", "max": 20.0, "min": 0.0, "name": "VT_B_TRANS_RAMP", "shortDesc": "Back transition MC motor ramp up time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "VTOL Attitude Control", "longDesc": "If set to 1 the control surfaces are locked at the disarmed value in multicopter mode.", "name": "VT_ELEV_MC_LOCK", "shortDesc": "Lock control surfaces in hover", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Prevents downforce from pitching the body down when facing wind.\nUses puller/pusher (standard VTOL), or forward-tilt (tiltrotor VTOL) to accelerate forward instead.\nOnly active if demanded pitch is below VT_PITCH_MIN.\nUse VT_FWD_THRUST_SC to tune it.\nDescend mode is treated as Landing too.\nOnly active (if enabled) in height-rate controlled modes.", "name": "VT_FWD_THRUST_EN", "shortDesc": "Use fixed-wing actuation in hover to accelerate forward", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled (except LANDING)", "value": 1}, {"description": "Enabled if above MPC_LAND_ALT1", "value": 2}, {"description": "Enabled if above MPC_LAND_ALT2", "value": 3}, {"description": "Enabled constantly", "value": 4}, {"description": "Enabled if above MPC_LAND_ALT1 (except LANDING)", "value": 5}, {"description": "Enabled if above MPC_LAND_ALT2 (except LANDING)", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Scale applied to the demanded pitch (below VT_PITCH_MIN) to get the fixed-wing forward actuation in hover mode.\nEnabled via VT_FWD_THRUST_EN.", "max": 5.0, "min": 0.0, "name": "VT_FWD_THRUST_SC", "shortDesc": "Fixed-wing actuation thrust scale in hover", "type": "Float"}, {"bitmask": [{"description": "Yaw", "index": 0}, {"description": "Roll", "index": 1}, {"description": "Pitch", "index": 2}], "category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Enable differential thrust seperately for roll, pitch, yaw in forward (fixed-wing) mode.\nThe effectiveness of differential thrust around the corresponding axis can be\ntuned by setting VT_FW_DIFTHR_S_R / VT_FW_DIFTHR_S_P / VT_FW_DIFTHR_S_Y.", "max": 7, "min": 0, "name": "VT_FW_DIFTHR_EN", "shortDesc": "Differential thrust in forwards flight", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_P", "shortDesc": "Pitch differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_R", "shortDesc": "Roll differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_Y", "shortDesc": "Yaw differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Minimum altitude for fixed-wing flight. When the vehicle is in fixed-wing mode\nand the altitude drops below this altitude (relative altitude above local origin),\nit will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT.", "max": 200.0, "min": 0.0, "name": "VT_FW_MIN_ALT", "shortDesc": "Quad-chute altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "increment": 1, "longDesc": "Maximum height above the ground (if available, otherwise above\nHome if available, otherwise above the local origin) where triggering a quad-chute is possible.\nAt high altitudes there is a big risk to deplete the battery and therefore crash if quad-chuting there.", "min": 0, "name": "VT_FW_QC_HMAX", "shortDesc": "Quad-chute maximum height", "type": "Int32", "units": "m"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Absolute pitch threshold for quad-chute triggering in FW mode.\nAbove this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT.\nSet to 0 do disable this threshold.", "max": 180, "min": 0, "name": "VT_FW_QC_P", "shortDesc": "Quad-chute max pitch threshold", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Absolute roll threshold for quad-chute triggering in FW mode.\nAbove this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT.\nSet to 0 do disable this threshold.", "max": 180, "min": 0, "name": "VT_FW_QC_R", "shortDesc": "Quad-chute max roll threshold", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Time in seconds used for a transition", "max": 20.0, "min": 0.1, "name": "VT_F_TRANS_DUR", "shortDesc": "Duration of a front transition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_F_TRANS_THR", "shortDesc": "Target throttle value for the transition to fixed-wing flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.0, "group": "VTOL Attitude Control", "increment": 0.5, "longDesc": "The duration of the front transition when there is no airspeed feedback available.\nWhen airspeed is used, transition timeout is declared if airspeed does not\nreach VT_ARSP_BLEND after this time.", "max": 30.0, "min": 1.0, "name": "VT_F_TR_OL_TM", "shortDesc": "Airspeed-less front transition time (open loop)", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": -5.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Overrides VT_PITCH_MIN when the vehicle is in LAND mode (hovering).\nDuring landing it can be beneficial to reduce the pitch angle to reduce the generated lift in head wind.", "max": 45.0, "min": -10.0, "name": "VT_LND_PITCH_MIN", "shortDesc": "Minimum pitch angle during hover landing", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -5.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Any pitch setpoint below this value is translated to a forward force by the fixed-wing forward actuation if\nVT_FWD_TRHUST_EN is set.", "max": 45.0, "min": -10.0, "name": "VT_PITCH_MIN", "shortDesc": "Minimum pitch angle during hover", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.33, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Defines the slew rate of the puller/pusher throttle during transitions.\nZero will deactivate the slew rate limiting and thus produce an instant throttle\nrise to the transition throttle VT_F_TRANS_THR.", "min": 0.0, "name": "VT_PSHER_SLEW", "shortDesc": "Pusher throttle ramp up slew rate", "type": "Float", "units": "1/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Altitude error threshold for quad-chute triggering during fixed-wing flight.\nThe check is only active if altitude is controlled and the vehicle is below the current altitude reference.\nThe altitude error is relative to the highest altitude the vehicle has achieved since it has flown below the current\naltitude reference.\nSet to 0 do disable.", "max": 200.0, "min": 0.0, "name": "VT_QC_ALT_LOSS", "shortDesc": "Quad-chute uncommanded descent threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Altitude loss threshold for quad-chute triggering during VTOL transition to fixed-wing flight\nin altitude-controlled flight modes.\nActive until 5s after completing transition to fixed-wing.\nIf the current altitude is more than this value below the altitude at the beginning of the\ntransition, it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT.\nSet to 0 do disable this threshold.", "max": 50.0, "min": 0.0, "name": "VT_QC_T_ALT_LOSS", "shortDesc": "Quad-chute transition altitude loss threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.1, "max": 1.0, "min": -1.0, "name": "VT_SPOILER_MC_LD", "shortDesc": "Spoiler setting while landing (hover)", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_FW", "shortDesc": "Normalized tilt in FW", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_MC", "shortDesc": "Normalized tilt in Hover", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.4, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_TRANS", "shortDesc": "Normalized tilt in transition to FW", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Minimum time in seconds for front transition.", "max": 20.0, "min": 0.0, "name": "VT_TRANS_MIN_TM", "shortDesc": "Front transition minimum time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Time in seconds it takes to tilt form VT_TILT_TRANS to VT_TILT_FW.", "max": 5.0, "min": 0.1, "name": "VT_TRANS_P2_DUR", "shortDesc": "Duration of front transition phase 2", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 15.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Time in seconds after which transition will be cancelled.", "max": 30.0, "min": 0.1, "name": "VT_TRANS_TIMEOUT", "shortDesc": "Front transition timeout", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "max": 2, "min": 0, "name": "VT_TYPE", "rebootRequired": true, "shortDesc": "VTOL Type (Tailsitter=0, Tiltrotor=1, Standard=2)", "type": "Int32", "values": [{"description": "Tailsitter", "value": 0}, {"description": "Tiltrotor", "value": 1}, {"description": "Standard", "value": 2}]}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "The desired gain to convert roll sp into yaw rate sp.", "max": 3.0, "min": 0.0, "name": "WV_GAIN", "shortDesc": "Weather-vane roll angle to yawrate", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 80.0, "group": "VTOL Takeoff", "increment": 1.0, "longDesc": "Altitude relative to home at which vehicle will loiter after front transition.", "max": 300.0, "min": 20.0, "name": "VTO_LOITER_ALT", "shortDesc": "VTOL Takeoff relative loiter altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Miscellaneous", "name": "UUV_SKIP_CTRL", "shortDesc": "Skip the controller", "type": "Int32", "values": [{"description": "use the module's controller", "value": 0}, {"description": "skip the controller and feedthrough the setpoints", "value": 1}]}], "translation": {"items": {"parameters": {"list": {"items": {"bitmask": {"list": {"key": "index", "translate": ["description"]}}, "values": {"list": {"key": "value", "translate": ["description"]}}}, "key": "name", "translate": ["shortDesc", "longDesc"], "translate-global": ["category", "group"]}}}}, "version": 1} \ No newline at end of file +{"parameters": [{"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets first 4 characters of a total of 8. Valid characters are A-Z, 0-9, \" \". Example \"PX4 \" -> 1347957792\nFor CALLSIGN shorter than 8 characters use the null terminator at the end '\\0'.", "name": "ADSB_CALLSIGN_1", "rebootRequired": true, "shortDesc": "First 4 characters of CALLSIGN", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets second 4 characters of a total of 8. Valid characters are A-Z, 0-9, \" \" only. Example \"TEST\" -> 1413829460\nFor CALLSIGN shorter than 8 characters use the null terminator at the end '\\0'.", "name": "ADSB_CALLSIGN_2", "rebootRequired": true, "shortDesc": "Second 4 characters of CALLSIGN", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets the vehicle emergency state", "max": 6, "min": 0, "name": "ADSB_EMERGC", "rebootRequired": true, "shortDesc": "ADSB-Out Emergency State", "type": "Int32", "values": [{"description": "NoEmergency", "value": 0}, {"description": "General", "value": 1}, {"description": "Medical", "value": 2}, {"description": "LowFuel", "value": 3}, {"description": "NoCommunications", "value": 4}, {"description": "Interference", "value": 5}, {"description": "Downed", "value": 6}]}, {"category": "Standard", "default": 14, "group": "ADSB", "longDesc": "Configure the emitter type of the vehicle.", "max": 15, "min": 0, "name": "ADSB_EMIT_TYPE", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Emitter Type", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "Light", "value": 1}, {"description": "Small", "value": 2}, {"description": "Large", "value": 3}, {"description": "HighVortex", "value": 4}, {"description": "Heavy", "value": 5}, {"description": "Performance", "value": 6}, {"description": "Rotorcraft", "value": 7}, {"description": "RESERVED", "value": 8}, {"description": "Glider", "value": 9}, {"description": "LightAir", "value": 10}, {"description": "Parachute", "value": 11}, {"description": "UltraLight", "value": 12}, {"description": "RESERVED", "value": 13}, {"description": "UAV", "value": 14}, {"description": "Space", "value": 15}, {"description": "RESERVED", "value": 16}, {"description": "EmergencySurf", "value": 17}, {"description": "ServiceSurf", "value": 18}, {"description": "PointObstacle", "value": 19}]}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets GPS lataral offset encoding", "max": 7, "min": 0, "name": "ADSB_GPS_OFF_LAT", "rebootRequired": true, "shortDesc": "ADSB-Out GPS Offset lat", "type": "Int32", "values": [{"description": "NoData", "value": 0}, {"description": "LatLeft2M", "value": 1}, {"description": "LatLeft4M", "value": 2}, {"description": "LatLeft6M", "value": 3}, {"description": "LatRight0M", "value": 4}, {"description": "LatRight2M", "value": 5}, {"description": "LatRight4M", "value": 6}, {"description": "LatRight6M", "value": 7}]}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets GPS longitudinal offset encoding", "max": 1, "min": 0, "name": "ADSB_GPS_OFF_LON", "rebootRequired": true, "shortDesc": "ADSB-Out GPS Offset lon", "type": "Int32", "values": [{"description": "NoData", "value": 0}, {"description": "AppliedBySensor", "value": 1}]}, {"category": "Standard", "default": 1194684, "group": "ADSB", "longDesc": "Defines the ICAO ID of the vehicle", "max": 16777215, "min": -1, "name": "ADSB_ICAO_ID", "rebootRequired": true, "shortDesc": "ADSB-Out ICAO configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "This vehicle is always tracked. Use 0 to disable.", "max": 16777215, "min": 0, "name": "ADSB_ICAO_SPECL", "rebootRequired": true, "shortDesc": "ADSB-In Special ICAO configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Enable Identification of Position feature", "name": "ADSB_IDENT", "rebootRequired": true, "shortDesc": "ADSB-Out Ident Configuration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "ADSB", "longDesc": "Report the length and width of the vehicle in meters. In most cases, use '1' for the smallest vehicle size.", "max": 15, "min": 0, "name": "ADSB_LEN_WIDTH", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Size Configuration", "type": "Int32", "values": [{"description": "SizeUnknown", "value": 0}, {"description": "Len15_Wid23", "value": 1}, {"description": "Len25_Wid28", "value": 2}, {"description": "Len25_Wid34", "value": 3}, {"description": "Len35_Wid33", "value": 4}, {"description": "Len35_Wid38", "value": 5}, {"description": "Len45_Wid39", "value": 6}, {"description": "Len45_Wid45", "value": 7}, {"description": "Len55_Wid45", "value": 8}, {"description": "Len55_Wid52", "value": 9}, {"description": "Len65_Wid59", "value": 10}, {"description": "Len65_Wid67", "value": 11}, {"description": "Len75_Wid72", "value": 12}, {"description": "Len75_Wid80", "value": 13}, {"description": "Len85_Wid80", "value": 14}, {"description": "Len85_Wid90", "value": 15}]}, {"category": "Standard", "default": 25, "group": "ADSB", "longDesc": "Change number of targets to track", "max": 50, "min": 0, "name": "ADSB_LIST_MAX", "rebootRequired": true, "shortDesc": "ADSB-In Vehicle List Size", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Informs ADSB vehicles of this vehicle's max speed capability", "max": 6, "min": 0, "name": "ADSB_MAX_SPEED", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Max Speed", "type": "Int32", "values": [{"description": "UnknownMaxSpeed", "value": 0}, {"description": "75Kts", "value": 1}, {"description": "150Kts", "value": 2}, {"description": "300Kts", "value": 3}, {"description": "600Kts", "value": 4}, {"description": "1200Kts", "value": 5}, {"description": "Over1200Kts", "value": 6}]}, {"category": "Standard", "default": 1200, "group": "ADSB", "longDesc": "This parameter defines the squawk code. Value should be between 0000 and 7777.", "max": 7777, "min": 0, "name": "ADSB_SQUAWK", "rebootRequired": true, "shortDesc": "ADSB-Out squawk code configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 1.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC1", "shortDesc": "SIM Channel 1 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 10.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC10", "shortDesc": "SIM Channel 10 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 11.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC11", "shortDesc": "SIM Channel 11 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 12.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC12", "shortDesc": "SIM Channel 12 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 13.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC13", "shortDesc": "SIM Channel 13 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 14.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC14", "shortDesc": "SIM Channel 14 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 15.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC15", "shortDesc": "SIM Channel 15 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 16.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC16", "shortDesc": "SIM Channel 16 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 2.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC2", "shortDesc": "SIM Channel 2 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 3.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC3", "shortDesc": "SIM Channel 3 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 4.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC4", "shortDesc": "SIM Channel 4 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 5.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC5", "shortDesc": "SIM Channel 5 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 6.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC6", "shortDesc": "SIM Channel 6 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 7.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC7", "shortDesc": "SIM Channel 7 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 8.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC8", "shortDesc": "SIM Channel 8 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 9.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC9", "shortDesc": "SIM Channel 9 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"bitmask": [{"description": "SIM Channel 1", "index": 0}, {"description": "SIM Channel 2", "index": 1}, {"description": "SIM Channel 3", "index": 2}, {"description": "SIM Channel 4", "index": 3}, {"description": "SIM Channel 5", "index": 4}, {"description": "SIM Channel 6", "index": 5}, {"description": "SIM Channel 7", "index": 6}, {"description": "SIM Channel 8", "index": 7}, {"description": "SIM Channel 9", "index": 8}, {"description": "SIM Channel 10", "index": 9}, {"description": "SIM Channel 11", "index": 10}, {"description": "SIM Channel 12", "index": 11}, {"description": "SIM Channel 13", "index": 12}, {"description": "SIM Channel 14", "index": 13}, {"description": "SIM Channel 15", "index": 14}, {"description": "SIM Channel 16", "index": 15}], "category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Allows to reverse the output range for each channel.\nNote: this is only useful for servos.", "max": 65535, "min": 0, "name": "PWM_MAIN_REV", "shortDesc": "Reverse Output Range for SIM", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Airspeed Validator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 5, "min": 1, "name": "ASPD_BETA_GATE", "shortDesc": "Gate size for sideslip angle fusion", "type": "Int32", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Airspeed Validator", "longDesc": "Sideslip measurement noise of the internal wind estimator(s) of the airspeed selector.", "max": 1.0, "min": 0.0, "name": "ASPD_BETA_NOISE", "shortDesc": "Wind estimator sideslip measurement noise", "type": "Float", "units": "rad"}, {"bitmask": [{"description": "Only data missing check (triggers if more than 1s no data)", "index": 0}, {"description": "Data stuck (triggers if data is exactly constant for 2s in FW mode)", "index": 1}, {"description": "Innovation check (see ASPD_FS_INNOV)", "index": 2}, {"description": "Load factor check (triggers if measurement is below stall speed)", "index": 3}, {"description": "First principle check (airspeed change vs. throttle and pitch)", "index": 4}], "category": "Standard", "default": 7, "group": "Airspeed Validator", "longDesc": "Controls which checks are run to check airspeed data for validity. Only applied if ASPD_PRIMARY > 0.\nNote: The missing data check (bit 0) is implicitly always enabled when ASPD_DO_CHECKS > 0, even if bit 0 is not explicitly set.", "max": 31, "min": 0, "name": "ASPD_DO_CHECKS", "shortDesc": "Enable checks on airspeed sensors", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Airspeed Validator", "name": "ASPD_FALLBACK", "shortDesc": "Fallback options", "type": "Int32", "values": [{"description": "Fallback only to other airspeed sensors", "value": 0}, {"description": "Fallback to groundspeed-minus-windspeed airspeed estimation", "value": 1}, {"description": "Fallback to thrust based airspeed estimation", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Airspeed Validator", "longDesc": "Window for comparing airspeed change to throttle and pitch change.\nTriggers when the airspeed change within this window is negative while throttle increases\nand the vehicle pitches down.\nIs meant to catch degrading airspeed blockages as can happen when flying through icing conditions.\nRelies on FW_THR_TRIM being set accurately.", "min": 0.0, "name": "ASPD_FP_T_WINDOW", "shortDesc": "First principle airspeed check time window", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Airspeed Validator", "longDesc": "This specifies the minimum airspeed innovation required to trigger a failsafe. Larger values make the check less sensitive,\nsmaller values make it more sensitive. Large innovations indicate an inconsistency between predicted (groundspeed - windspeeed)\nand measured airspeed.\nThe time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the ASPD_FS_INTEG parameter.", "max": 10.0, "min": 0.5, "name": "ASPD_FS_INNOV", "shortDesc": "Airspeed failure innovation threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Airspeed Validator", "longDesc": "This sets the time integral of airspeed innovation exceedance above ASPD_FS_INNOV required to trigger a failsafe.\nLarger values make the check less sensitive, smaller positive values make it more sensitive.", "max": 50.0, "min": 0.0, "name": "ASPD_FS_INTEG", "shortDesc": "Airspeed failure innovation integral threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Airspeed Validator", "longDesc": "Delay before switching back to using airspeed sensor if checks indicate sensor is good.\nSet to a negative value to disable the re-enabling in flight.", "min": -1.0, "name": "ASPD_FS_T_START", "shortDesc": "Airspeed failsafe start delay", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Airspeed Validator", "longDesc": "Delay before stopping use of airspeed sensor if checks indicate sensor is bad.", "min": 0.0, "name": "ASPD_FS_T_STOP", "shortDesc": "Airspeed failsafe stop delay", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Airspeed Validator", "name": "ASPD_PRIMARY", "rebootRequired": true, "shortDesc": "Index or primary airspeed measurement source", "type": "Int32", "values": [{"description": "Groundspeed minus windspeed", "value": 0}, {"description": "First airspeed sensor", "value": 1}, {"description": "Second airspeed sensor", "value": 2}, {"description": "Third airspeed sensor", "value": 3}, {"description": "Thrust based airspeed", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the first airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_1", "shortDesc": "Scale of airspeed sensor 1", "type": "Float", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the second airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_2", "shortDesc": "Scale of airspeed sensor 2", "type": "Float", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the third airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_3", "shortDesc": "Scale of airspeed sensor 3", "type": "Float", "volatile": true}, {"category": "Standard", "default": 2, "group": "Airspeed Validator", "name": "ASPD_SCALE_APPLY", "shortDesc": "Controls when to apply the new estimated airspeed scale(s)", "type": "Int32", "values": [{"description": "Do not automatically apply the estimated scale", "value": 0}, {"description": "Apply the estimated scale after disarm", "value": 1}, {"description": "Apply the estimated scale in air", "value": 2}]}, {"category": "Standard", "decimalPlaces": 5, "default": 0.0001, "group": "Airspeed Validator", "longDesc": "Airspeed scale process noise of the internal wind estimator(s) of the airspeed selector.\nWhen unaided, the scale uncertainty (1-sigma, unitless) increases by this amount every second.", "max": 0.1, "min": 0.0, "name": "ASPD_SCALE_NSD", "shortDesc": "Wind estimator true airspeed scale process noise spectral density", "type": "Float", "units": "1/s/sqrt(Hz)"}, {"category": "Standard", "default": 4, "group": "Airspeed Validator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 5, "min": 1, "name": "ASPD_TAS_GATE", "shortDesc": "Gate size for true airspeed fusion", "type": "Int32", "units": "SD"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.4, "group": "Airspeed Validator", "longDesc": "True airspeed measurement noise of the internal wind estimator(s) of the airspeed selector.", "max": 4.0, "min": 0.0, "name": "ASPD_TAS_NOISE", "shortDesc": "Wind estimator true airspeed measurement noise", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Airspeed Validator", "longDesc": "The airspeed alternative derived from groundspeed and heading will be declared valid\nas soon and as long the horizontal wind uncertainty is below this value.", "max": 5.0, "min": 0.01, "name": "ASPD_WERR_THR", "shortDesc": "Horizontal wind uncertainty threshold for valid ground-minus-wind", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Airspeed Validator", "longDesc": "Wind process noise of the internal wind estimator(s) of the airspeed selector.\nWhen unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second.", "max": 1.0, "min": 0.0, "name": "ASPD_WIND_NSD", "shortDesc": "Wind estimator wind process noise spectral density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "name": "ATT_ACC_COMP", "shortDesc": "Acceleration compensation based on GPS velocity", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Attitude Q estimator", "max": 2.0, "min": 0.0, "name": "ATT_BIAS_MAX", "shortDesc": "Gyro bias limit", "type": "Float", "units": "rad/s"}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "longDesc": "Enable standalone quaternion based attitude estimator.", "name": "ATT_EN", "shortDesc": "standalone attitude estimator enable (unsupported)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "longDesc": "Set to 1 to use heading estimate from vision.\nSet to 2 to use heading from motion capture.", "max": 2, "min": 0, "name": "ATT_EXT_HDG_M", "shortDesc": "External heading usage mode (from Motion capture/Vision)", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Vision", "value": 1}, {"description": "Motion Capture", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Attitude Q estimator", "longDesc": "This parameter is not used in normal operation,\nas the declination is looked up based on the\nGPS coordinates of the vehicle.", "name": "ATT_MAG_DECL", "shortDesc": "Magnetic declination, in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 1, "group": "Attitude Q estimator", "name": "ATT_MAG_DECL_A", "shortDesc": "Automatic GPS based declination compensation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_ACC", "shortDesc": "Complimentary filter accelerometer weight", "type": "Float"}, {"category": "Standard", "default": 0.1, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_EXT_HDG", "shortDesc": "Complimentary filter external heading weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_GYRO_BIAS", "shortDesc": "Complimentary filter gyroscope bias weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Attitude Q estimator", "longDesc": "Set to 0 to avoid using the magnetometer.", "max": 1.0, "min": 0.0, "name": "ATT_W_MAG", "shortDesc": "Complimentary filter magnetometer weight", "type": "Float"}, {"category": "Standard", "default": 2, "group": "Autotune", "longDesc": "After the auto-tuning sequence is completed,\na new set of gains is available and can be applied\nimmediately or after landing.", "name": "FW_AT_APPLY", "shortDesc": "Controls when to apply the new gains", "type": "Int32", "values": [{"description": "Do not apply the new gains (logging only)", "value": 0}, {"description": "Apply the new gains after disarm", "value": 1}, {"description": "Apply the new gains in air", "value": 2}]}, {"bitmask": [{"description": "roll", "index": 0}, {"description": "pitch", "index": 1}, {"description": "yaw", "index": 2}], "category": "Standard", "default": 3, "group": "Autotune", "longDesc": "Defines which axes will be tuned during the auto-tuning sequence\nSet bits in the following positions to enable:\n0 : Roll\n1 : Pitch\n2 : Yaw", "max": 7, "min": 1, "name": "FW_AT_AXES", "shortDesc": "Tuning axes selection", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "Defines which RC_MAP_AUXn parameter maps the manual control channel used to enable/disable auto tuning.", "max": 6, "min": 0, "name": "FW_AT_MAN_AUX", "shortDesc": "Enable/disable auto tuning using a manual control AUX input", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Aux1", "value": 1}, {"description": "Aux2", "value": 2}, {"description": "Aux3", "value": 3}, {"description": "Aux4", "value": 4}, {"description": "Aux5", "value": 5}, {"description": "Aux6", "value": 6}]}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Autotune", "longDesc": "Can be set lower or higher than the end frequency", "max": 30.0, "min": 0.1, "name": "FW_AT_SYSID_F0", "shortDesc": "Start frequency of the injected signal", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Autotune", "longDesc": "Can be set lower or higher than the start frequency", "max": 30.0, "min": 0.1, "name": "FW_AT_SYSID_F1", "shortDesc": "End frequency of the injected signal", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 0, "default": 10.0, "group": "Autotune", "longDesc": "Duration of the input signal sent on each axis during system identification", "max": 120.0, "min": 5.0, "name": "FW_AT_SYSID_TIME", "shortDesc": "Maneuver time for each axis", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Autotune", "longDesc": "Type of signal used during system identification to excite the system.", "name": "FW_AT_SYSID_TYPE", "shortDesc": "Input signal type", "type": "Int32", "values": [{"description": "Step", "value": 0}, {"description": "Linear sine sweep", "value": 1}, {"description": "Logarithmic sine sweep", "value": 2}]}, {"category": "Standard", "default": 1, "group": "Autotune", "longDesc": "After the auto-tuning sequence is completed,\na new set of gains is available and can be applied\nimmediately or after landing.\nWARNING Applying the gains in air is dangerous as there is no\nguarantee that those new gains will be able to stabilize\nthe drone properly.", "name": "MC_AT_APPLY", "shortDesc": "Controls when to apply the new gains", "type": "Int32", "values": [{"description": "Do not apply the new gains (logging only)", "value": 0}, {"description": "Apply the new gains after disarm", "value": 1}, {"description": "WARNING Apply the new gains in air", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Autotune", "name": "MC_AT_EN", "shortDesc": "Multicopter autotune module enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.14, "group": "Autotune", "max": 0.5, "min": 0.01, "name": "MC_AT_RISE_TIME", "shortDesc": "Desired angular rate closed-loop rise time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.7, "group": "Autotune", "max": 6.0, "min": 0.1, "name": "MC_AT_SYSID_AMP", "shortDesc": "Amplitude of the injected signal", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 1 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT1_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 1 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT1_N_CELLS", "shortDesc": "Number of cells for battery 1", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT1_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 1", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module / Analog'\nmeans that measurements are expected to come from either analog (ADC) inputs\nor an I2C power monitor (e.g. INA226). Analog inputs are voltage and current\nmeasurements read from the board's ADC channels, typically from an onboard\nvoltage divider and current shunt, or an external analog power module.\nI2C power monitors are digital sensors on the I2C bus.\nIf the value is set to 'External' then the system expects to receive MAVLink\nor CAN battery status messages, or the battery data is published by an external driver.\nIf the value is set to 'ESCs', the battery information are taken from the esc_status message.\nThis requires the ESC to provide both voltage as well as current (via ESC telemetry).", "name": "BAT1_SOURCE", "rebootRequired": true, "shortDesc": "Battery 1 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module / Analog", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full.\nFor a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT1_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty.\nThe voltage should be chosen above the steep dropoff at 3.5V. A typical\nlithium battery can only be discharged under high load down to 10% before\nit drops off to a voltage level damaging the cells.", "name": "BAT1_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 2 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT2_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 2 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT2_N_CELLS", "shortDesc": "Number of cells for battery 2", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT2_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 2", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": -1, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module / Analog'\nmeans that measurements are expected to come from either analog (ADC) inputs\nor an I2C power monitor (e.g. INA226). Analog inputs are voltage and current\nmeasurements read from the board's ADC channels, typically from an onboard\nvoltage divider and current shunt, or an external analog power module.\nI2C power monitors are digital sensors on the I2C bus.\nIf the value is set to 'External' then the system expects to receive MAVLink\nor CAN battery status messages, or the battery data is published by an external driver.\nIf the value is set to 'ESCs', the battery information are taken from the esc_status message.\nThis requires the ESC to provide both voltage as well as current (via ESC telemetry).", "name": "BAT2_SOURCE", "rebootRequired": true, "shortDesc": "Battery 2 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module / Analog", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full.\nFor a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT2_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty.\nThe voltage should be chosen above the steep dropoff at 3.5V. A typical\nlithium battery can only be discharged under high load down to 10% before\nit drops off to a voltage level damaging the cells.", "name": "BAT2_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 3 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT3_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 3 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT3_N_CELLS", "shortDesc": "Number of cells for battery 3", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT3_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 3", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": -1, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module / Analog'\nmeans that measurements are expected to come from either analog (ADC) inputs\nor an I2C power monitor (e.g. INA226). Analog inputs are voltage and current\nmeasurements read from the board's ADC channels, typically from an onboard\nvoltage divider and current shunt, or an external analog power module.\nI2C power monitors are digital sensors on the I2C bus.\nIf the value is set to 'External' then the system expects to receive MAVLink\nor CAN battery status messages, or the battery data is published by an external driver.\nIf the value is set to 'ESCs', the battery information are taken from the esc_status message.\nThis requires the ESC to provide both voltage as well as current (via ESC telemetry).", "name": "BAT3_SOURCE", "rebootRequired": true, "shortDesc": "Battery 3 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module / Analog", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full.\nFor a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT3_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty.\nThe voltage should be chosen above the steep dropoff at 3.5V. A typical\nlithium battery can only be discharged under high load down to 10% before\nit drops off to a voltage level damaging the cells.", "name": "BAT3_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 15.0, "group": "Battery Calibration", "increment": 0.1, "longDesc": "This value is used to initialize the in-flight average current estimation,\nwhich in turn is used for estimating remaining flight time and RTL triggering.", "max": 500.0, "min": 0.0, "name": "BAT_AVRG_CURRENT", "shortDesc": "Expected battery current in flight", "type": "Float", "units": "A"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.07, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as critically low.\nThis has to be lower than the low threshold. This threshold commonly\nwill trigger RTL.", "max": 0.5, "min": 0.05, "name": "BAT_CRIT_THR", "shortDesc": "Critical threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as dangerously low.\nThis has to be lower than the critical threshold. This threshold commonly\nwill trigger landing.", "max": 0.5, "min": 0.03, "name": "BAT_EMERGEN_THR", "shortDesc": "Emergency threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as low.\nThis has to be higher than the critical threshold.", "max": 0.5, "min": 0.12, "name": "BAT_LOW_THR", "shortDesc": "Low threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Camera trigger", "longDesc": "This parameter sets the time the trigger needs to pulled high or low.", "max": 3000.0, "min": 0.1, "name": "TRIG_ACT_TIME", "rebootRequired": true, "shortDesc": "Camera trigger activation time", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "Camera trigger", "increment": 1.0, "longDesc": "Sets the distance at which to trigger the camera.", "min": 0.0, "name": "TRIG_DISTANCE", "rebootRequired": true, "shortDesc": "Camera trigger distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 4, "group": "Camera trigger", "longDesc": "Selects the trigger interface", "name": "TRIG_INTERFACE", "rebootRequired": true, "shortDesc": "Camera trigger Interface", "type": "Int32", "values": [{"description": "GPIO", "value": 1}, {"description": "Seagull MAP2 (over PWM)", "value": 2}, {"description": "MAVLink (Camera Protocol v1)", "value": 3}, {"description": "Generic PWM (IR trigger, servo)", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Camera trigger", "longDesc": "This parameter sets the time between two consecutive trigger events", "max": 10000.0, "min": 4.0, "name": "TRIG_INTERVAL", "rebootRequired": true, "shortDesc": "Camera trigger interval", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Camera trigger", "longDesc": "This parameter sets the minimum time between two consecutive trigger events\nthe specific camera setup is supporting.", "max": 10000.0, "min": 1.0, "name": "TRIG_MIN_INTERVA", "rebootRequired": true, "shortDesc": "Minimum camera trigger interval", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "Camera trigger", "max": 4, "min": 0, "name": "TRIG_MODE", "rebootRequired": true, "shortDesc": "Camera trigger mode", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Time based, on command", "value": 1}, {"description": "Time based, always on", "value": 2}, {"description": "Distance based, always on", "value": 3}, {"description": "Distance based, on command (Survey mode)", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Camera trigger", "longDesc": "This parameter sets the polarity of the trigger (0 = active low, 1 = active high )", "max": 1, "min": 0, "name": "TRIG_POLARITY", "rebootRequired": true, "shortDesc": "Camera trigger polarity", "type": "Int32", "values": [{"description": "Active low", "value": 0}, {"description": "Active high", "value": 1}]}, {"category": "Standard", "default": 1500, "group": "Camera trigger", "max": 2000, "min": 1000, "name": "TRIG_PWM_NEUTRAL", "rebootRequired": true, "shortDesc": "PWM neutral output on trigger pin", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 1900, "group": "Camera trigger", "max": 2000, "min": 1000, "name": "TRIG_PWM_SHOOT", "rebootRequired": true, "shortDesc": "PWM output to trigger shot", "type": "Int32", "units": "us"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 782097 will disable the buzzer audio notification.\nSetting this parameter to 782090 will disable the startup tune, while keeping\nall others enabled.", "max": 782097, "min": 0, "name": "CBRK_BUZZER", "rebootRequired": true, "shortDesc": "Circuit breaker for disabling buzzer", "type": "Int32"}, {"category": "Developer", "default": 121212, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 121212 will disable the flight termination action if triggered\nby the FailureDetector logic or if FMU is lost.\nThis circuit breaker does not affect the RC loss, data link loss, geofence,\nand takeoff failure detection safety logic.", "max": 121212, "min": 0, "name": "CBRK_FLIGHTTERM", "rebootRequired": true, "shortDesc": "Circuit breaker for flight termination", "type": "Int32"}, {"category": "Developer", "default": 22027, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 22027 will disable IO safety.\nWARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 22027, "min": 0, "name": "CBRK_IO_SAFETY", "shortDesc": "Circuit breaker for IO safety", "type": "Int32"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 894281 will disable the power valid\nchecks in the commander.\nWARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 894281, "min": 0, "name": "CBRK_SUPPLY_CHK", "shortDesc": "Circuit breaker for power supply check", "type": "Int32"}, {"category": "Developer", "default": 197848, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 197848 will disable the USB connected\nchecks in the commander, setting it to 0 keeps them enabled (recommended).\nWe are generally recommending to not fly with the USB link\nconnected and production vehicles should set this parameter to\nzero to prevent users from flying USB powered. However, for R&D purposes\nit has proven over the years to work just fine.", "max": 197848, "min": 0, "name": "CBRK_USB_CHK", "shortDesc": "Circuit breaker for USB link check", "type": "Int32"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 159753 will enable arming in fixed-wing\nmode for VTOLs.\nWARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 159753, "min": 0, "name": "CBRK_VTOLARMING", "shortDesc": "Circuit breaker for arming in fixed-wing mode check", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Note: actuator failure needs to be enabled and configured via FD_ACT_*\nparameters.", "max": 3, "min": 0, "name": "COM_ACT_FAIL_ACT", "shortDesc": "Set the actuator failure failsafe mode", "type": "Int32", "values": [{"description": "Warning only", "value": 0}, {"description": "Hold mode", "value": 1}, {"description": "Land mode", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Terminate", "value": 4}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Set 0 to prevent accidental use of the vehicle e.g. for safety or maintenance reasons.", "name": "COM_ARMABLE", "shortDesc": "Flag to allow arming", "type": "Int32", "values": [{"description": "Disallow arming", "value": 0}, {"description": "Allow arming", "value": 1}]}, {"category": "Standard", "default": 10, "group": "Commander", "longDesc": "Used if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_ID", "shortDesc": "Arm authorizer system id", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Methods:\n- one arm: request authorization and arm when authorization is received\n- two step arm: 1st arm command request an authorization and\n2nd arm command arm the drone if authorized\nUsed if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_MET", "shortDesc": "Arm authorization method", "type": "Int32", "values": [{"description": "one arm", "value": 0}, {"description": "two step arm", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "By default off. The default allows to arm the vehicle without a arm authorization.", "name": "COM_ARM_AUTH_REQ", "shortDesc": "Require arm authorization to arm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "increment": 0.1, "longDesc": "Timeout for authorizer answer.\nUsed if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_TO", "shortDesc": "Arm authorization timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Commander", "increment": 0.01, "longDesc": "Threshold for battery percentage below arming is prohibited.\nA negative value means BAT_CRIT_THR is the threshold.", "max": 0.9, "min": -1.0, "name": "COM_ARM_BAT_MIN", "shortDesc": "Minimum battery level for arming", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "If this parameter is set, the system will check ESC's online status and failures.\nThis param is specific for ESCs reporting status. It shall be used only if ESCs support telemetry.", "name": "COM_ARM_CHK_ESCS", "shortDesc": "Enable checks on ESCs that report telemetry", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This check detects if there are hardfault files present on the\nSD card. If so, and the parameter is enabled, arming is prevented.", "name": "COM_ARM_HFLT_CHK", "shortDesc": "Enable FMU SD card hardfault detection check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "Commander", "increment": 0.05, "max": 1.0, "min": 0.1, "name": "COM_ARM_IMU_ACC", "shortDesc": "Maximum accelerometer inconsistency between IMU units that will allow arming", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Commander", "increment": 0.01, "max": 0.3, "min": 0.02, "name": "COM_ARM_IMU_GYR", "shortDesc": "Maximum rate gyro inconsistency between IMU units that will allow arming", "type": "Float", "units": "rad/s"}, {"category": "Standard", "default": 60, "group": "Commander", "longDesc": "Set -1 to disable the check.", "max": 180, "min": 3, "name": "COM_ARM_MAG_ANG", "shortDesc": "Maximum magnetic field inconsistency between units that will allow arming", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Commander", "longDesc": "Check if the estimator detects a strong magnetic\ndisturbance (check enabled by EKF2_MAG_CHECK)", "name": "COM_ARM_MAG_STR", "shortDesc": "Enable mag strength preflight check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Deny arming", "value": 1}, {"description": "Warning only", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The default allows to arm the vehicle without a valid mission.", "name": "COM_ARM_MIS_REQ", "shortDesc": "Require valid mission to arm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "This check detects if the Open Drone ID system is missing.\nDepending on the value of the parameter, the check can be\ndisabled, warn only or deny arming.", "name": "COM_ARM_ODID", "shortDesc": "Enable Drone ID system detection and health check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Enforce Open Drone ID system presence", "value": 2}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This check detects if the FMU SD card is missing.\nDepending on the value of the parameter, the check can be\ndisabled, warn only or deny arming.", "name": "COM_ARM_SDCARD", "shortDesc": "Enable FMU SD card detection check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Enforce SD card presence", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "0: Arming/disarming triggers on switch transition.\n1: Arming/disarming triggers when holding the momentary button down like the stick gesture.", "name": "COM_ARM_SWISBTN", "shortDesc": "Arm switch is a momentary button", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Configures whether arming is allowed without GNSS, for modes that require a global position\n(specifically, in those modes when a check defined by EKF2_GPS_CHECK fails).\nThe settings deny arming and warn, allow arming and warn, or silently allow arming.", "name": "COM_ARM_WO_GPS", "shortDesc": "Arming without GNSS configuration", "type": "Int32", "values": [{"description": "Deny arming", "value": 0}, {"description": "Allow arming (with warning)", "value": 1}, {"description": "Allow arming (no warning)", "value": 2}]}, {"category": "Standard", "default": 95.0, "group": "Commander", "increment": 1.0, "longDesc": "The check fails if the CPU load is above this threshold for 2s.\nA negative value disables the check.", "max": 100.0, "min": -1.0, "name": "COM_CPU_MAX", "shortDesc": "Maximum allowed CPU load to still arm", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Commander", "increment": 0.1, "longDesc": "A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be\nautomatically disarmed in case a landing situation has been detected during this period.\nA zero or negative value means that automatic disarming triggered by landing detection is disabled.", "name": "COM_DISARM_LAND", "shortDesc": "Time-out for auto disarm after landing", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "0: Disallow disarming when not landed\n1: Allow disarming in multicopter flight in modes where\nthe thrust is directly controlled by thr throttle stick\ne.g. Stabilized, Acro", "name": "COM_DISARM_MAN", "shortDesc": "Allow disarming via switch/stick/button on multicopters in manual thrust modes", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Commander", "increment": 0.1, "longDesc": "A non-zero, positive value specifies the time in seconds, within which the\nvehicle is expected to take off after arming. In case the vehicle didn't takeoff\nwithin the timeout it disarms again.\nA negative value disables autmoatic disarming triggered by a pre-takeoff timeout.", "name": "COM_DISARM_PRFLT", "shortDesc": "Time-out for auto disarm if not taking off", "type": "Float", "units": "s"}, {"bitmask": [{"description": "Mission", "index": 0}, {"description": "Auto modes", "index": 1}, {"description": "Offboard", "index": 2}, {"description": "External Mode", "index": 3}, {"description": "Altitude Cruise", "index": 4}], "category": "Standard", "default": 0, "group": "Commander", "longDesc": "Specify modes in which ground control station connection loss is ignored and no failsafe action is triggered.\nSee also COM_RCL_EXCEPT.", "max": 31, "min": 0, "name": "COM_DLL_EXCEPT", "shortDesc": "Datalink loss exceptions", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10, "group": "Commander", "increment": 1, "longDesc": "After this amount of seconds without datalink, the GCS connection lost mode triggers", "max": 300, "min": 5, "name": "COM_DL_LOSS_T", "shortDesc": "GCS connection loss time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "longDesc": "Before entering failsafe (RTL, Land, Hold), wait COM_FAIL_ACT_T seconds in Hold mode\nfor the user to realize.\nDuring that time the user can switch modes, but cannot take over control via the stick override feature (see COM_RC_OVERRIDE).\nAfterwards the configured failsafe action is triggered and the user may use stick override.\nA zero value disables the delay.", "max": 25.0, "min": 0.0, "name": "COM_FAIL_ACT_T", "shortDesc": "Delay between failsafe condition triggered and failsafe reaction", "type": "Float", "units": "s"}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This number is incremented automatically after every flight on\ndisarming in order to remember the next flight UUID.\nThe first flight is 0.", "min": 0, "name": "COM_FLIGHT_UUID", "shortDesc": "Next flight UUID", "type": "Int32", "volatile": true}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE1", "shortDesc": "Mode slot 1", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "Altitude Cruise", "value": 16}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE2", "shortDesc": "Mode slot 2", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "Altitude Cruise", "value": 16}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE3", "shortDesc": "Mode slot 3", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "Altitude Cruise", "value": 16}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE4", "shortDesc": "Mode slot 4", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "Altitude Cruise", "value": 16}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE5", "shortDesc": "Mode slot 5", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "Altitude Cruise", "value": 16}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE6", "shortDesc": "Mode slot 6", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "Altitude Cruise", "value": 16}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when the remaining flight time is below\nthe estimated time it takes to reach the RTL destination.", "name": "COM_FLTT_LOW_ACT", "shortDesc": "Remaining flight time low failsafe", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Return", "value": 3}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Describes the intended use of the vehicle.\nCan be used by ground control software or log post processing.\nThis param does not influence the behavior within the firmware. This means for example the control logic is independent of the setting of this param (but depends on other params).", "name": "COM_FLT_PROFILE", "shortDesc": "User Flight Profile", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Pro User", "value": 100}, {"description": "Flight Tester", "value": 200}, {"description": "Developer", "value": 300}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "The vehicle aborts the current operation and returns to launch when\nthe time since takeoff is above this value. It is not possible to resume the\nmission or switch to any auto mode other than RTL or Land. Taking over in any manual\nmode is still possible.\nStarting from 90% of the maximum flight time, a warning message will be sent\nevery 1 minute with the remaining time until automatic RTL.\nSet to -1 to disable.", "min": -1, "name": "COM_FLT_TIME_MAX", "shortDesc": "Maximum allowed flight time", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Force safety when the vehicle disarms", "name": "COM_FORCE_SAFETY", "shortDesc": "Enable force safety", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 120, "group": "Commander", "longDesc": "After this amount of seconds without datalink the data link lost mode triggers", "max": 3600, "min": 60, "name": "COM_HLDL_LOSS_T", "shortDesc": "High Latency Datalink loss time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "After a data link loss: after this number of seconds with a healthy datalink the 'datalink loss'\nflag is set back to false", "max": 60, "min": 0, "name": "COM_HLDL_REG_T", "shortDesc": "High Latency Datalink regain time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Set home position automatically if possible.\nDuring missions, the latitude/longitude of the home position is locked and will not reset during intermediate landings.\nIt will only update once the mission is complete or landed outside of a mission.\nHowever, the altitude is still being adjusted to correct for GNSS vertical drift in the first 2 minutes after takeoff.", "name": "COM_HOME_EN", "rebootRequired": true, "shortDesc": "Home position enabled", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "If set to true, the autopilot is allowed to set its home position after takeoff\nThe true home position is back-computed if a local position is estimate if available.\nIf no local position is available, home is set to the current position.", "name": "COM_HOME_IN_AIR", "shortDesc": "Allows setting the home position after takeoff", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when an imbalanced propeller is detected by the failure detector.\nSee also FD_IMB_PROP_THR to set the failure threshold.", "name": "COM_IMB_PROP_ACT", "shortDesc": "Imbalanced propeller failsafe mode", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Warning", "value": 0}, {"description": "Return", "value": 1}, {"description": "Land", "value": 2}]}, {"category": "Standard", "default": 5.0, "group": "Commander", "increment": 0.1, "longDesc": "Use RC_MAP_KILL_SW to map a kill switch.", "max": 30.0, "min": 0.0, "name": "COM_KILL_DISARM", "shortDesc": "Timeout value for disarming when kill switch is engaged", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Commander", "longDesc": "A non-zero, positive value specifies the timeframe in seconds within failure detector is allowed to disarm the vehicle\nif attitude exceeds the limits defined in FD_FAIL_P and FD_FAIL_R.\nThe check is not executed for flight modes that do support acrobatic maneuvers, e.g: Acro (MC/FW) and Manual (FW).\nA zero or negative value means that the check is disabled.", "max": 5.0, "min": -1.0, "name": "COM_LKDOWN_TKO", "shortDesc": "Timeout for detecting a failure after takeoff", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Action the system takes at critical battery. See also BAT_CRIT_THR and BAT_EMERGEN_THR\nfor definition of battery states.", "name": "COM_LOW_BAT_ACT", "shortDesc": "Battery failsafe mode", "type": "Int32", "values": [{"description": "Warning", "value": 0}, {"description": "Land mode", "value": 2}, {"description": "Return at critical level, land at emergency level", "value": 3}]}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE0_HASH", "shortDesc": "External mode identifier 0", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE1_HASH", "shortDesc": "External mode identifier 1", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE2_HASH", "shortDesc": "External mode identifier 2", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE3_HASH", "shortDesc": "External mode identifier 3", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE4_HASH", "shortDesc": "External mode identifier 4", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE5_HASH", "shortDesc": "External mode identifier 5", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE6_HASH", "shortDesc": "External mode identifier 6", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE7_HASH", "shortDesc": "External mode identifier 7", "type": "Int32", "volatile": true}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "By default disabled for safety reasons", "name": "COM_MODE_ARM_CHK", "shortDesc": "Allow external mode registration while armed", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "If set, enables the actuator test interface via MAVLink (ACTUATOR_TEST), that\nallows spinning the motors and moving the servos for testing purposes.", "name": "COM_MOT_TEST_EN", "shortDesc": "Enable Actuator Testing", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 5.0, "group": "Commander", "increment": 0.01, "max": 60.0, "min": 0.0, "name": "COM_OBC_LOSS_T", "shortDesc": "Time-out to wait when onboard computer connection is lost before warning about loss connection", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The offboard loss failsafe will only be entered after a timeout,\nset by COM_OF_LOSS_T in seconds.", "name": "COM_OBL_RC_ACT", "shortDesc": "Set offboard loss failsafe mode", "type": "Int32", "values": [{"description": "Position mode", "value": 0}, {"description": "Altitude mode", "value": 1}, {"description": "Stabilized", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Land mode", "value": 4}, {"description": "Hold mode", "value": 5}, {"description": "Terminate", "value": 6}, {"description": "Disarm", "value": 7}]}, {"category": "Standard", "default": 1.0, "group": "Commander", "increment": 0.01, "longDesc": "See COM_OBL_RC_ACT to configure action.", "max": 60.0, "min": 0.0, "name": "COM_OF_LOSS_T", "shortDesc": "Time-out to wait when offboard connection is lost before triggering offboard lost action", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "name": "COM_PARACHUTE", "shortDesc": "Expect and require a healthy MAVLink parachute system", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "longDesc": "This is the horizontal position error (EPH) threshold that will trigger a failsafe.\nIf the previous position error was below this threshold, there is an additional\nfactor of 2.5 applied (threshold for invalidation 2.5 times the one for validation).\nOnly used for multicopters and VTOLs in hover mode.\nIndependent from estimator positioning data timeout threshold (see EKF2_NOAID_TOUT).\nSet to -1 to disable.", "max": 400.0, "min": -1.0, "name": "COM_POS_FS_EPH", "shortDesc": "Horizontal position error threshold for hovering systems", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when the estimated position has an accuracy below the specified threshold.\nSee COM_POS_LOW_EPH to set the failsafe threshold.\nThe failsafe action is only executed if the vehicle is in auto mission or auto loiter mode,\notherwise it is only a warning.", "name": "COM_POS_LOW_ACT", "shortDesc": "Low position accuracy action", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold", "value": 2}, {"description": "Return", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land", "value": 5}]}, {"category": "Standard", "default": -1.0, "group": "Commander", "longDesc": "This triggers the action specified in COM_POS_LOW_ACT if the estimated position accuracy is below this threshold.\nLocal position has to be still declared valid, which requires some kind of velocity aiding or large dead-reckoning time (EKF2_NOAID_TOUT),\nand a high failsafe threshold (COM_POS_FS_EPH).\nSet to -1 to disable.", "max": 1000.0, "min": -1.0, "name": "COM_POS_LOW_EPH", "shortDesc": "Low position accuracy failsafe threshold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This configures a check to verify the expected number of 5V rail power supplies are present. By default only one is expected.\nNote: CBRK_SUPPLY_CHK disables all power checks including this one.", "max": 4, "min": 0, "name": "COM_POWER_COUNT", "shortDesc": "Required number of redundant power modules", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Condition to enter the prearmed state, an intermediate state between disarmed and armed\nin which non-throttling actuators are active.", "name": "COM_PREARM_MODE", "shortDesc": "Condition to enter prearmed mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Safety button", "value": 1}, {"description": "Always", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "name": "COM_QC_ACT", "shortDesc": "Set action after a quadchute", "type": "Int32", "values": [{"description": "Warning only", "value": -1}, {"description": "Return mode", "value": 0}, {"description": "Land mode", "value": 1}, {"description": "Hold mode", "value": 2}]}, {"category": "Standard", "default": 95.0, "group": "Commander", "increment": 1.0, "longDesc": "The check fails if the RAM usage is above this threshold.\nA negative value disables the check.", "max": 100.0, "min": -1.0, "name": "COM_RAM_MAX", "shortDesc": "Maximum allowed RAM usage to pass checks", "type": "Float", "units": "%"}, {"bitmask": [{"description": "Mission", "index": 0}, {"description": "Auto modes", "index": 1}, {"description": "Offboard", "index": 2}, {"description": "External Mode", "index": 3}, {"description": "Altitude Cruise", "index": 4}], "category": "Standard", "default": 0, "group": "Commander", "longDesc": "Specify modes in which stick input is ignored and no failsafe action is triggered.\nExternal modes requiring stick input will still failsafe.\nAuto modes are: Hold, Takeoff, Land, RTL, Descend, Follow Target, Precland, Orbit.", "max": 31, "min": 0, "name": "COM_RCL_EXCEPT", "shortDesc": "Manual control loss exceptions", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "Commander", "longDesc": "Selects stick input selection behavior:\neither a traditional remote control receiver (RC) or a MAVLink joystick (MANUAL_CONTROL message)\nPriority sources are immediately switched to whenever they get valid.\n0 RC only. Requires valid RC calibration.\n1 MAVLink only. RC and related checks are disabled.\n2 Switches only if current source becomes invalid.\n3 Locks to the first valid source until reboot.\n4 Ignores all sources.\n5 RC priority, then MAVLink (lower instance before higher)\n6 MAVLink priority (lower instance before higher), then RC\n7 RC priority, then MAVLink (higher instance before lower)\n8 MAVLink priority (higher instance before lower), then RC", "max": 8, "min": 0, "name": "COM_RC_IN_MODE", "shortDesc": "Manual control input source configuration", "type": "Int32", "values": [{"description": "RC only", "value": 0}, {"description": "MAVLink only", "value": 1}, {"description": "RC or MAVLink with fallback", "value": 2}, {"description": "RC or MAVLink keep first", "value": 3}, {"description": "Disable manual control", "value": 4}, {"description": "Prio: RC > MAVL 1 > MAVL 2", "value": 5}, {"description": "Prio: MAVL 1 > MAVL 2 > RC", "value": 6}, {"description": "Prio: RC > MAVL 2 > MAVL 1", "value": 7}, {"description": "Prio: MAVL 2 > MAVL 1 > RC", "value": 8}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Commander", "increment": 0.1, "longDesc": "The time in seconds without a new setpoint from RC or Joystick, after which the connection is considered lost.\nThis must be kept short as the vehicle will use the last supplied setpoint until the timeout triggers.\nEnsure the value is not set lower than the update interval of the RC or Joystick.", "max": 35.0, "min": 0.0, "name": "COM_RC_LOSS_T", "shortDesc": "Manual control loss timeout", "type": "Float", "units": "s"}, {"bitmask": [{"description": "Enable override during auto modes (except for in critical battery reaction)", "index": 0}, {"description": "Enable override during offboard mode", "index": 1}], "category": "Standard", "default": 1, "group": "Commander", "longDesc": "When enabled, moving the sticks more than COM_RC_STICK_OV\nimmediately gives control back to the pilot by switching to Position mode and\nif position is unavailable Altitude mode.\nNote: Only has an effect on multicopters, and VTOLs in multicopter mode.", "max": 3, "min": 0, "name": "COM_RC_OVERRIDE", "shortDesc": "Enable manual control stick override", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 0, "default": 30.0, "group": "Commander", "increment": 0.05, "longDesc": "If COM_RC_OVERRIDE is enabled and the joystick input is moved more than this threshold\nthe autopilot the pilot takes over control.", "max": 80.0, "min": 5.0, "name": "COM_RC_STICK_OV", "shortDesc": "Stick override threshold", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "increment": 0.1, "longDesc": "The minimal time from arming the motors until moving the vehicle is possible is COM_SPOOLUP_TIME seconds.\nGoal:\n- Motors and propellers spool up to idle speed before getting commanded to spin faster\n- Timeout for ESCs and smart batteries to successfulyy do failure checks\ne.g. for stuck rotors before the vehicle is off the ground", "max": 30.0, "min": 0.0, "name": "COM_SPOOLUP_TIME", "shortDesc": "Enforced delay between arming and further navigation", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The mode transition after TAKEOFF has completed successfully.", "name": "COM_TAKEOFF_ACT", "shortDesc": "Action after TAKEOFF has been accepted", "type": "Int32", "values": [{"description": "Hold", "value": 0}, {"description": "Mission (if valid)", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Allows to start the vehicle by throwing it into the air.", "name": "COM_THROW_EN", "shortDesc": "Enable throw-start", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "increment": 0.1, "longDesc": "When the throw launch is enabled, the drone will only allow motors to spin after this speed\nis exceeded before detecting the freefall. This is a safety feature to ensure the drone does\nnot turn on after accidental drop or a rapid movement before the throw.\nSet to 0 to disable.", "min": 0.0, "name": "COM_THROW_SPEED", "shortDesc": "Minimum speed for the throw start", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "longDesc": "This is the horizontal velocity error (EVH) threshold that will trigger a failsafe.\nThe default is appropriate for a multicopter. Can be increased for a fixed-wing.\nIf the previous velocity error was below this threshold, there is an additional\nfactor of 2.5 applied (threshold for invalidation 2.5 times the one for validation).", "min": 0.0, "name": "COM_VEL_FS_EVH", "shortDesc": "Horizontal velocity error threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Commander", "increment": 0.1, "longDesc": "Wind speed threshold above which an automatic failsafe action is triggered.\nFailsafe action can be specified with COM_WIND_MAX_ACT.", "min": -1.0, "name": "COM_WIND_MAX", "shortDesc": "High wind speed failsafe threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when a wind speed above the specified threshold is detected.\nSee COM_WIND_MAX to set the failsafe threshold.\nIf enabled, it is not possible to resume the mission or switch to any auto mode other than\nRTL or Land if this threshold is exceeded. Taking over in any manual\nmode is still possible.", "name": "COM_WIND_MAX_ACT", "shortDesc": "High wind failsafe mode", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold", "value": 2}, {"description": "Return", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Commander", "increment": 0.1, "longDesc": "A warning is triggered if the currently estimated wind speed is above this value.\nWarning is sent periodically (every 1 minute).\nSet to -1 to disable.", "min": -1.0, "name": "COM_WIND_WARN", "shortDesc": "Wind speed warning threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The GCS connection loss failsafe will only be entered after a timeout,\nset by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected\naction will be executed.", "max": 6, "min": 0, "name": "NAV_DLL_ACT", "shortDesc": "Set GCS connection loss failsafe mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Hold mode", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Terminate", "value": 5}, {"description": "Disarm", "value": 6}]}, {"category": "Standard", "default": 2, "group": "Commander", "longDesc": "The manual control loss failsafe will only be entered after a timeout,\nset by COM_RC_LOSS_T in seconds.", "max": 6, "min": 1, "name": "NAV_RCL_ACT", "shortDesc": "Set manual control loss failsafe mode", "type": "Int32", "values": [{"description": "Hold mode", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Terminate", "value": 5}, {"description": "Disarm", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "max": 0.5, "min": 0.0, "name": "EKF2_ABIAS_INIT", "rebootRequired": true, "shortDesc": "1-sigma IMU accelerometer switch-on bias", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "EKF2", "longDesc": "If the magnitude of the IMU accelerometer vector exceeds this value, the EKF accel bias state estimation will be inhibited. This reduces the adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale factor errors on the accel bias estimates.", "max": 200.0, "min": 20.0, "name": "EKF2_ABL_ACCLIM", "shortDesc": "Maximum IMU accel magnitude that allows IMU bias learning", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "If the magnitude of the IMU angular rate vector exceeds this value, the EKF accel bias state estimation will be inhibited. This reduces the adverse effect of rapid rotation rates and associated errors on the accel bias estimates.", "max": 20.0, "min": 2.0, "name": "EKF2_ABL_GYRLIM", "shortDesc": "Maximum IMU gyro angular rate magnitude that allows IMU bias learning", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "EKF2", "longDesc": "The ekf accel bias states will be limited to within a range equivalent to +- of this value.", "max": 0.8, "min": 0.0, "name": "EKF2_ABL_LIM", "shortDesc": "Accelerometer bias learning limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay. This parameter controls the time constant of the decay.", "max": 1.0, "min": 0.1, "name": "EKF2_ABL_TAU", "shortDesc": "Accel bias learning inhibit time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.003, "group": "EKF2", "max": 0.01, "min": 0.0, "name": "EKF2_ACC_B_NOISE", "shortDesc": "Process noise for IMU accelerometer bias prediction", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.35, "group": "EKF2", "max": 1.0, "min": 0.01, "name": "EKF2_ACC_NOISE", "shortDesc": "Accelerometer noise for covariance prediction", "type": "Float", "units": "m/s^2"}, {"bitmask": [{"description": "Horizontal position", "index": 0}, {"description": "Vertical position", "index": 1}], "category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Horizontal position fusion 1 : Vertical position fusion", "max": 3, "min": 0, "name": "EKF2_AGP_CTRL", "shortDesc": "Aux global position (AGP) sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_AGP_DELAY", "rebootRequired": true, "shortDesc": "Aux global position estimator delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_AGP_GATE", "shortDesc": "Gate size for aux global position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Automatic: reset on fusion timeout if no other source of position is available Dead-reckoning: reset on fusion timeout if no source of velocity is available", "name": "EKF2_AGP_MODE", "shortDesc": "Fusion reset mode", "type": "Int32", "values": [{"description": "Automatic", "value": 0}, {"description": "Dead-reckoning", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.9, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_AGP_NOISE", "shortDesc": "Measurement noise for aux global position measurements", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "EKF2", "max": 0.5, "min": 0.0, "name": "EKF2_ANGERR_INIT", "rebootRequired": true, "shortDesc": "1-sigma tilt angle uncertainty after gravity vector alignment", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "longDesc": "Airspeed data is fused for wind estimation if above this threshold. Set to 0 to disable airspeed fusion. For reliable wind estimation both sideslip (see EKF2_FUSE_BETA) and airspeed fusion should be enabled. Only applies to fixed-wing vehicles (or VTOLs in fixed-wing mode).", "min": 0.0, "name": "EKF2_ARSP_THR", "shortDesc": "Airspeed fusion threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "max": 50.0, "min": 5.0, "name": "EKF2_ASPD_MAX", "shortDesc": "Maximum airspeed used for baro static pressure compensation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_ASP_DELAY", "rebootRequired": true, "shortDesc": "Airspeed measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_AVEL_DELAY", "rebootRequired": true, "shortDesc": "Auxiliary Velocity Estimate delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "If this parameter is enabled then the estimator will make use of the barometric height measurements to estimate its height in addition to other height sources (if activated).", "name": "EKF2_BARO_CTRL", "shortDesc": "Barometric sensor height aiding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_BARO_DELAY", "rebootRequired": true, "shortDesc": "Barometer measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_BARO_GATE", "shortDesc": "Gate size for barometric and GPS height fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.5, "group": "EKF2", "max": 15.0, "min": 0.01, "name": "EKF2_BARO_NOISE", "shortDesc": "Measurement noise for barometric altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by bluff body drag along the forward/reverse axis when flying a multi-copter which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis.", "max": 200.0, "min": 0.0, "name": "EKF2_BCOEF_X", "shortDesc": "X-axis ballistic coefficient used for multi-rotor wind estimation", "type": "Float", "units": "kg/m^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by bluff body drag along the right/left axis when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis.", "max": 200.0, "min": 0.0, "name": "EKF2_BCOEF_Y", "shortDesc": "Y-axis ballistic coefficient used for multi-rotor wind estimation", "type": "Float", "units": "kg/m^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_BETA_GATE", "shortDesc": "Gate size for synthetic sideslip fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 1.0, "min": 0.1, "name": "EKF2_BETA_NOISE", "shortDesc": "Noise for synthetic sideslip fusion", "type": "Float", "units": "m/s"}, {"bitmask": [{"description": "use geo_lookup declination", "index": 0}, {"description": "save EKF2_MAG_DECL on disarm", "index": 1}], "category": "Standard", "default": 3, "group": "EKF2", "longDesc": "Set bits in the following positions to enable functions. 0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value. 1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms.", "max": 3, "min": 0, "name": "EKF2_DECL_TYPE", "rebootRequired": true, "shortDesc": "Integer bitmask controlling handling of magnetic declination", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 200.0, "group": "EKF2", "longDesc": "Defines the delay between the current time and the delayed-time horizon. This value should be at least as large as the largest EKF2_XXX_DELAY parameter.", "max": 1000.0, "min": 0.0, "name": "EKF2_DELAY_MAX", "rebootRequired": true, "shortDesc": "Maximum delay of all the aiding sensors", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Activate wind speed estimation using specific-force measurements and a drag model defined by EKF2_BCOEF_[XY] and EKF2_MCOEF. Only use on vehicles that have their thrust aligned with the Z axis and no thrust in the XY plane.", "name": "EKF2_DRAG_CTRL", "shortDesc": "Multirotor wind estimation selection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 2.5, "group": "EKF2", "longDesc": "Used by the multi-rotor specific drag force model. Increasing this makes the multi-rotor wind estimates adjust more slowly.", "max": 10.0, "min": 0.5, "name": "EKF2_DRAG_NOISE", "shortDesc": "Specific drag force observation noise variance", "type": "Float", "units": "(m/s^2)^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.4, "group": "EKF2", "max": 5.0, "min": 0.5, "name": "EKF2_EAS_NOISE", "shortDesc": "Measurement noise for airspeed fusion", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "EKF2", "name": "EKF2_EN", "shortDesc": "EKF2 enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "When enabled, constant position fusion is enabled when the vehicle is landed and armed. This is intended for IC engine warmup (e.g., fuel engines on catapult) to allow mode transitions to auto/takeoff despite vibrations from running engines.", "name": "EKF2_ENGINE_WRM", "shortDesc": "Enable constant position fusion during engine warmup", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.05, "name": "EKF2_EVA_NOISE", "shortDesc": "Measurement noise for vision angle measurements", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_EVP_GATE", "shortDesc": "Gate size for vision position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_EVP_NOISE", "shortDesc": "Measurement noise for vision position measurements", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_EVV_GATE", "shortDesc": "Gate size for vision velocity estimate fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_EVV_NOISE", "shortDesc": "Measurement noise for vision velocity measurements", "type": "Float", "units": "m/s"}, {"bitmask": [{"description": "Horizontal position", "index": 0}, {"description": "Vertical position", "index": 1}, {"description": "3D velocity", "index": 2}, {"description": "Yaw", "index": 3}], "category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Horizontal position fusion 1 : Vertical position fusion 2 : 3D velocity fusion 3 : Yaw", "max": 15, "min": 0, "name": "EKF2_EV_CTRL", "shortDesc": "External vision (EV) sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_EV_DELAY", "rebootRequired": true, "shortDesc": "Vision Position Estimator delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "If set to 0 (default) the measurement noise is taken from the vision message and the EV noise parameters are used as a lower bound. If set to 1 the observation noise is set from the parameters directly,", "name": "EKF2_EV_NOISE_MD", "shortDesc": "External vision (EV) noise mode", "type": "Int32", "values": [{"description": "EV reported variance (parameter lower bound)", "value": 0}, {"description": "EV noise parameters", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_X", "shortDesc": "X position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_Y", "shortDesc": "Y position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_Z", "shortDesc": "Z position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0, "group": "EKF2", "longDesc": "External vision will only be started and fused if the quality metric is above this threshold. The quality metric is a completely optional field provided by some VIO systems.", "max": 100, "min": 0, "name": "EKF2_EV_QMIN", "shortDesc": "External vision (EV) minimum quality (optional)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "For reliable wind estimation both sideslip and airspeed fusion (see EKF2_ARSP_THR) should be enabled. Only applies to vehicles in fixed-wing mode or with airspeed fusion active. Note: side slip fusion is currently not supported for tailsitters.", "name": "EKF2_FUSE_BETA", "shortDesc": "Enable synthetic sideslip fusion", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "max": 0.2, "min": 0.0, "name": "EKF2_GBIAS_INIT", "rebootRequired": true, "shortDesc": "1-sigma IMU gyro switch-on bias", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "EKF2", "longDesc": "Sets the value of deadzone applied to negative baro innovations. Deadzone is enabled when EKF2_GND_EFF_DZ > 0.", "max": 10.0, "min": 0.0, "name": "EKF2_GND_EFF_DZ", "shortDesc": "Baro deadzone range for height fusion", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "EKF2", "longDesc": "Sets the maximum distance to the ground level where negative baro innovations are expected.", "max": 5.0, "min": 0.0, "name": "EKF2_GND_MAX_HGT", "shortDesc": "Height above ground level for ground effect zone", "type": "Float", "units": "m"}, {"bitmask": [{"description": "Sat count (EKF2_REQ_NSATS)", "index": 0}, {"description": "PDOP (EKF2_REQ_PDOP)", "index": 1}, {"description": "EPH (EKF2_REQ_EPH)", "index": 2}, {"description": "EPV (EKF2_REQ_EPV)", "index": 3}, {"description": "Speed accuracy (EKF2_REQ_SACC)", "index": 4}, {"description": "Horizontal position drift (EKF2_REQ_HDRIFT)", "index": 5}, {"description": "Vertical position drift (EKF2_REQ_VDRIFT)", "index": 6}, {"description": "Horizontal speed offset (EKF2_REQ_HDRIFT)", "index": 7}, {"description": "Vertical speed offset (EKF2_REQ_VDRIFT)", "index": 8}, {"description": "Spoofing", "index": 9}, {"description": "GPS fix type (EKF2_REQ_FIX)", "index": 10}, {"description": "Jamming", "index": 11}], "category": "Standard", "default": 2047, "group": "EKF2", "longDesc": "Each threshold value is defined by the parameter indicated next to the check. Drift and offset checks only run when the vehicle is on ground and stationary.", "max": 4095, "min": 0, "name": "EKF2_GPS_CHECK", "shortDesc": "Integer bitmask controlling GPS checks", "type": "Int32"}, {"bitmask": [{"description": "Lon/lat", "index": 0}, {"description": "Altitude", "index": 1}, {"description": "3D velocity", "index": 2}, {"description": "Dual antenna heading", "index": 3}], "category": "Standard", "default": 7, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Longitude and latitude fusion 1 : Altitude fusion 2 : 3D velocity fusion 3 : Dual antenna heading fusion", "max": 15, "min": 0, "name": "EKF2_GPS_CTRL", "shortDesc": "GNSS sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 110.0, "group": "EKF2", "longDesc": "GPS measurement delay relative to IMU measurement if PPS time correction is not available/enabled (PPS_CAP_ENABLE).", "max": 300.0, "min": 0.0, "name": "EKF2_GPS_DELAY", "rebootRequired": true, "shortDesc": "GPS measurement delay relative to IMU measurement", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Automatic: reset on fusion timeout if no other source of position is available. Dead-reckoning: reset on fusion timeout if no source of velocity is available.", "name": "EKF2_GPS_MODE", "shortDesc": "Fusion reset mode", "type": "Int32", "values": [{"description": "Automatic", "value": 0}, {"description": "Dead-reckoning", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward (roll) axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_X", "shortDesc": "X position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Right (pitch) axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_Y", "shortDesc": "Y position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Down (yaw) axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_Z", "shortDesc": "Z position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_GPS_P_GATE", "shortDesc": "Gate size for GNSS position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "max": 10.0, "min": 0.01, "name": "EKF2_GPS_P_NOISE", "shortDesc": "Measurement noise for GNSS position", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_GPS_V_GATE", "shortDesc": "Gate size for GNSS velocity fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 5.0, "min": 0.01, "name": "EKF2_GPS_V_NOISE", "shortDesc": "Measurement noise for GNSS velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 360.0, "min": 0.0, "name": "EKF2_GPS_YAW_OFF", "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "EKF2", "max": 10.0, "min": 0.1, "name": "EKF2_GRAV_NOISE", "shortDesc": "Accelerometer measurement noise for gravity based observations", "type": "Float", "units": "g0"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "EKF2", "longDesc": "If no airspeed measurements are available, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes.", "max": 100.0, "min": 0.0, "name": "EKF2_GSF_TAS", "shortDesc": "Default value of true airspeed used in EKF-GSF AHRS calculation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "EKF2", "longDesc": "The ekf gyro bias states will be limited to within a range equivalent to +- of this value.", "max": 0.4, "min": 0.0, "name": "EKF2_GYR_B_LIM", "shortDesc": "Gyro bias learning limit", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.001, "group": "EKF2", "max": 0.01, "min": 0.0, "name": "EKF2_GYR_B_NOISE", "shortDesc": "Process noise for IMU rate gyro bias prediction", "type": "Float", "units": "rad/s^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.015, "group": "EKF2", "max": 0.1, "min": 0.0001, "name": "EKF2_GYR_NOISE", "shortDesc": "Rate gyro noise for covariance prediction", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.6, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_HDG_GATE", "shortDesc": "Gate size for heading fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 1.0, "min": 0.01, "name": "EKF2_HEAD_NOISE", "shortDesc": "Measurement noise for magnetic heading fusion", "type": "Float", "units": "rad"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "When multiple height sources are enabled at the same time, the height estimate will always converge towards the reference height source selected by this parameter. The range sensor and vision options should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level. If GPS is set as reference but altitude fusion is disabled in EKF2_GPS_CTRL, the GPS altitude is still used to initiaize the bias of the other height sensors.", "name": "EKF2_HGT_REF", "rebootRequired": true, "shortDesc": "Determines the reference source of height data used by the EKF", "type": "Int32", "values": [{"description": "Barometric pressure", "value": 0}, {"description": "GPS", "value": 1}, {"description": "Range sensor", "value": 2}, {"description": "Vision", "value": 3}]}, {"bitmask": [{"description": "Gyro Bias", "index": 0}, {"description": "Accel Bias", "index": 1}, {"description": "Gravity vector fusion", "index": 2}], "category": "Standard", "default": 7, "group": "EKF2", "max": 7, "min": 0, "name": "EKF2_IMU_CTRL", "shortDesc": "IMU control", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_X", "shortDesc": "X position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_Y", "shortDesc": "Y position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_Z", "shortDesc": "Z position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "EKF2", "name": "EKF2_LOG_VERBOSE", "shortDesc": "Verbose logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "The heading is assumed to be observable when the body acceleration is greater than this parameter when a global position/velocity aiding source is active.", "max": 5.0, "min": 0.0, "name": "EKF2_MAG_ACCLIM", "shortDesc": "Horizontal acceleration threshold used for heading observability check", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.0001, "group": "EKF2", "max": 0.1, "min": 0.0, "name": "EKF2_MAG_B_NOISE", "shortDesc": "Process noise for body magnetic field prediction", "type": "Float", "units": "gauss/s"}, {"bitmask": [{"description": "Strength (EKF2_MAG_CHK_STR)", "index": 0}, {"description": "Inclination (EKF2_MAG_CHK_INC)", "index": 1}, {"description": "Wait for WMM", "index": 2}], "category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Bitmask to set which check is used to decide whether the magnetometer data is valid. If GNSS data is received, the magnetic field is compared to a World Magnetic Model (WMM), otherwise an average value is used. This check is useful to reject occasional hard iron disturbance. Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Magnetic field strength. Set tolerance using EKF2_MAG_CHK_STR 1 : Magnetic field inclination. Set tolerance using EKF2_MAG_CHK_INC 2 : Wait for GNSS to find the theoretical strength and inclination using the WMM", "max": 7, "min": 0, "name": "EKF2_MAG_CHECK", "shortDesc": "Magnetic field strength test selection", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "longDesc": "Maximum allowed deviation from the expected magnetic field inclination to pass the check.", "max": 90.0, "min": 0.0, "name": "EKF2_MAG_CHK_INC", "shortDesc": "Magnetic field inclination check tolerance", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "longDesc": "Maximum allowed deviation from the expected magnetic field strength to pass the check.", "max": 1.0, "min": 0.0, "name": "EKF2_MAG_CHK_STR", "shortDesc": "Magnetic field strength check tolerance", "type": "Float", "units": "gauss"}, {"category": "System", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "name": "EKF2_MAG_DECL", "shortDesc": "Magnetic declination", "type": "Float", "units": "deg", "volatile": true}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_MAG_DELAY", "rebootRequired": true, "shortDesc": "Magnetometer measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.001, "group": "EKF2", "max": 0.1, "min": 0.0, "name": "EKF2_MAG_E_NOISE", "shortDesc": "Process noise for earth magnetic field prediction", "type": "Float", "units": "gauss/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_MAG_GATE", "shortDesc": "Gate size for magnetometer XYZ component fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "EKF2", "max": 1.0, "min": 0.001, "name": "EKF2_MAG_NOISE", "shortDesc": "Measurement noise for magnetometer 3-axis fusion", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. The fusion of magnetometer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight. If set to 'Magnetic heading' magnetic heading fusion is used at all times. If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GNSS velocity measurements to align the yaw angle. If set to 'Init' the magnetometer is only used to initalize the heading.", "name": "EKF2_MAG_TYPE", "rebootRequired": true, "shortDesc": "Type of magnetometer fusion", "type": "Int32", "values": [{"description": "Automatic", "value": 0}, {"description": "Magnetic heading", "value": 1}, {"description": "None", "value": 5}, {"description": "Init", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the propeller axis of rotation is lost when passing through the rotor disc. This changes the momentum of the flow which creates a drag reaction force. When comparing un-ducted propellers of the same diameter, the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with propeller selection. Momentum drag is significantly higher for ducted rotors. To account for the drag produced by the body which scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y parameters. Set this parameter to zero to turn off the momentum drag model for both axis.", "max": 1.0, "min": 0.0, "name": "EKF2_MCOEF", "shortDesc": "Propeller momentum drag coefficient for multi-rotor wind estimation", "type": "Float", "units": "1/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.01, "group": "EKF2", "longDesc": "If the vehicle is on ground, is not moving as determined by the motion test and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is available at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground.", "min": 0.01, "name": "EKF2_MIN_RNG", "shortDesc": "Expected range finder reading when on ground", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Maximum number of IMUs to use for Multi-EKF. Set 0 to disable. Requires SENS_IMU_MODE 0.", "max": 4, "min": 0, "name": "EKF2_MULTI_IMU", "rebootRequired": true, "shortDesc": "Multi-EKF IMUs", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Maximum number of magnetometers to use for Multi-EKF. Set 0 to disable. Requires SENS_MAG_MODE 0.", "max": 4, "min": 0, "name": "EKF2_MULTI_MAG", "rebootRequired": true, "shortDesc": "Multi-EKF Magnetometers", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "EKF2", "max": 50.0, "min": 0.5, "name": "EKF2_NOAID_NOISE", "shortDesc": "Measurement noise for non-aiding position hold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 5000000, "group": "EKF2", "longDesc": "Maximum lapsed time from last fusion of measurements that constrain velocity drift before the EKF will report the horizontal nav solution as invalid", "max": 10000000, "min": 500000, "name": "EKF2_NOAID_TOUT", "shortDesc": "Maximum inertial dead-reckoning time", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Enable optical flow fusion.", "name": "EKF2_OF_CTRL", "shortDesc": "Optical flow aiding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "longDesc": "Assumes measurement is timestamped at trailing edge of integration period", "max": 300.0, "min": 0.0, "name": "EKF2_OF_DELAY", "rebootRequired": true, "shortDesc": "Optical flow measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_OF_GATE", "shortDesc": "Gate size for optical flow fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Auto: use gyro from optical flow message if available, internal gyro otherwise. Internal: always use internal gyro", "name": "EKF2_OF_GYR_SRC", "shortDesc": "Optical flow angular rate compensation source", "type": "Int32", "values": [{"description": "Auto", "value": 0}, {"description": "Internal", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "Measurement noise for the optical flow sensor when it's reported quality metric is at the minimum", "min": 0.05, "name": "EKF2_OF_N_MAX", "shortDesc": "Optical flow maximum noise", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "EKF2", "longDesc": "Measurement noise for the optical flow sensor when it's reported quality metric is at the maximum", "min": 0.05, "name": "EKF2_OF_N_MIN", "shortDesc": "Optical flow minimum noise", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_X", "shortDesc": "X position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_Y", "shortDesc": "Y position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_Z", "shortDesc": "Z position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Optical Flow data will only be used in air if the sensor reports a quality metric >= EKF2_OF_QMIN", "max": 255, "min": 0, "name": "EKF2_OF_QMIN", "shortDesc": "In air optical flow minimum quality", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Optical Flow data will only be used on the ground if the sensor reports a quality metric >= EKF2_OF_QMIN_GND", "max": 255, "min": 0, "name": "EKF2_OF_QMIN_GND", "shortDesc": "On ground optical flow minimum quality", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_XN", "shortDesc": "Static pressure position error coefficient for the negative X axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forward flight, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_XP", "shortDesc": "Static pressure position error coefficient for the positive X axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the negative Y (LH) body axis. If the baro height estimate rises during sideways flight to the left, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_YN", "shortDesc": "Pressure position error coefficient for the negative Y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the positive Y (RH) body axis. If the baro height estimate rises during sideways flight to the right, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_YP", "shortDesc": "Pressure position error coefficient for the positive Y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the Z body axis.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_Z", "shortDesc": "Static pressure position error coefficient for the Z axis", "type": "Float"}, {"category": "Standard", "default": 10000, "group": "EKF2", "longDesc": "EKF prediction period in microseconds. This should ideally be an integer multiple of the IMU time delta. Actual filter update will be an integer multiple of IMU update.", "max": 20000, "min": 1000, "name": "EKF2_PREDICT_US", "shortDesc": "EKF prediction period", "type": "Int32", "units": "us"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "max": 100.0, "min": 2.0, "name": "EKF2_REQ_EPH", "shortDesc": "Required EPH to use GPS", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 100.0, "min": 2.0, "name": "EKF2_REQ_EPV", "shortDesc": "Required EPV to use GPS", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "EKF2", "longDesc": "Minimum GPS fix type required for GPS usage.", "name": "EKF2_REQ_FIX", "shortDesc": "Required GPS fix", "type": "Int32", "values": [{"description": "No fix required", "value": 0}, {"description": "2D fix", "value": 2}, {"description": "3D fix", "value": 3}, {"description": "RTCM code differential", "value": 4}, {"description": "RTK float", "value": 5}, {"description": "RTK fixed", "value": 6}, {"description": "Extrapolated", "value": 8}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "EKF2", "longDesc": "Minimum continuous period without GPS failure required to mark a healthy GPS status. It can be reduced to speed up initialization, but it's recommended to keep this unchanged for a vehicle.", "min": 0.1, "name": "EKF2_REQ_GPS_H", "rebootRequired": true, "shortDesc": "Required GPS health time on startup", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "max": 1.0, "min": 0.1, "name": "EKF2_REQ_HDRIFT", "shortDesc": "Maximum horizontal drift speed to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 6, "group": "EKF2", "max": 12, "min": 4, "name": "EKF2_REQ_NSATS", "shortDesc": "Required satellite count to use GPS", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "EKF2", "max": 5.0, "min": 1.5, "name": "EKF2_REQ_PDOP", "shortDesc": "Maximum PDOP to use GPS", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "max": 5.0, "min": 0.5, "name": "EKF2_REQ_SACC", "shortDesc": "Required speed accuracy to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "max": 1.5, "min": 0.1, "name": "EKF2_REQ_VDRIFT", "shortDesc": "Maximum vertical drift speed to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 5.0, "group": "EKF2", "longDesc": "If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1).", "max": 10.0, "min": 1.0, "name": "EKF2_RNG_A_HMAX", "shortDesc": "Maximum height above ground allowed for conditional range aid mode", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1).", "max": 2.0, "min": 0.1, "name": "EKF2_RNG_A_VMAX", "shortDesc": "Maximum horizontal velocity allowed for conditional range aid mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "WARNING: Range finder measurements are less reliable and can experience unexpected errors. For these reasons, if accurate control of height relative to ground is required, it is recommended to use the MPC_ALT_MODE parameter instead, unless baro errors are severe enough to cause problems with landing and takeoff. If this parameter is enabled then the estimator will make use of the range finder measurements to estimate its height in addition to other height sources (if activated). Range sensor aiding can be enabled (i.e.: always use) or set in \"conditional\" mode. Conditional mode: This enables the range finder to be used during low speed (< EKF2_RNG_A_VMAX) and low altitude (< EKF2_RNG_A_HMAX) operation, eg takeoff and landing, where baro interference from rotor wash is excessive and can corrupt EKF state estimates. It is intended to be used where a vertical takeoff and landing is performed, and horizontal flight does not occur until above EKF2_RNG_A_HMAX.", "name": "EKF2_RNG_CTRL", "shortDesc": "Range sensor height aiding", "type": "Int32", "values": [{"description": "Disable range fusion", "value": 0}, {"description": "Enabled (conditional mode)", "value": 1}, {"description": "Enabled", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_RNG_DELAY", "rebootRequired": true, "shortDesc": "Range finder measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Limit for fog detection. If the range finder measures a distance greater than this value, the measurement is considered to not be blocked by fog or rain. If there's a jump from larger than RNG_FOG to smaller than EKF2_RNG_FOG, the measurement may gets rejected. 0 - disabled", "max": 20.0, "min": 0.0, "name": "EKF2_RNG_FOG", "shortDesc": "Maximum distance at which the range finder could detect fog (m)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_RNG_GATE", "shortDesc": "Gate size for range finder fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "To be used, the time derivative of the distance sensor measurements projected on the vertical axis needs to be statistically consistent with the estimated vertical velocity of the drone. Decrease this value to make the filter more robust against range finder faulty data (stuck, reflections, ...). Note: tune the range finder noise parameters (EKF2_RNG_NOISE and EKF2_RNG_SFE) before tuning this gate.", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_K_GATE", "shortDesc": "Gate size used for range finder kinematic consistency check", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "min": 0.01, "name": "EKF2_RNG_NOISE", "shortDesc": "Measurement noise for range finder fusion", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "max": 0.75, "min": -0.75, "name": "EKF2_RNG_PITCH", "shortDesc": "Range sensor pitch offset", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_X", "shortDesc": "X position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_Y", "shortDesc": "Y position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_Z", "shortDesc": "Z position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "Minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (s)", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_QLTY_T", "shortDesc": "Minumum range validity period", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0.05, "group": "EKF2", "longDesc": "Specifies the increase in range finder noise with range.", "max": 0.2, "min": 0.0, "name": "EKF2_RNG_SFE", "shortDesc": "Range finder range dependent noise scaler", "type": "Float", "units": "m/m"}, {"category": "Standard", "default": 0.2, "group": "EKF2", "longDesc": "EKF2 instances have to be better than the selected by at least this amount before their relative score can be reduced.", "name": "EKF2_SEL_ERR_RED", "shortDesc": "Selector error reduce threshold", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "EKF2 selector acceleration error threshold for comparing accelerometers. Acceleration vector differences larger than this will result in accumulated velocity error.", "name": "EKF2_SEL_IMU_ACC", "shortDesc": "Selector acceleration threshold", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 15.0, "group": "EKF2", "longDesc": "EKF2 selector maximum accumulated angular error threshold for comparing gyros. Accumulated angular error larger than this will result in the sensor being declared faulty.", "name": "EKF2_SEL_IMU_ANG", "shortDesc": "Selector angular threshold", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 7.0, "group": "EKF2", "longDesc": "EKF2 selector angular rate error threshold for comparing gyros. Angular rate vector differences larger than this will result in accumulated angular error.", "name": "EKF2_SEL_IMU_RAT", "shortDesc": "Selector angular rate threshold", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 2.0, "group": "EKF2", "longDesc": "EKF2 selector maximum accumulated velocity threshold for comparing accelerometers. Accumulated velocity error larger than this will result in the sensor being declared faulty.", "name": "EKF2_SEL_IMU_VEL", "shortDesc": "Selector angular threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Use for vehicles where the measured body Z magnetic field is subject to strong magnetic interference. For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter will only have an effect if the global position of the drone is known. For 3D mag fusion the magnetometer Z measurement will simply be ignored instead of fusing the synthetic value.", "name": "EKF2_SYNT_MAG_Z", "shortDesc": "Enable synthetic magnetometer Z component measurement", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_TAS_GATE", "shortDesc": "Gate size for TAS fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "EKF2", "longDesc": "Controls how tightly the output track the EKF states", "max": 1.0, "min": 0.1, "name": "EKF2_TAU_POS", "shortDesc": "Output predictor position time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "EKF2", "max": 1.0, "name": "EKF2_TAU_VEL", "shortDesc": "Time constant of the velocity output prediction and smoothing filter", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "min": 0.0, "name": "EKF2_TERR_GRAD", "shortDesc": "Magnitude of terrain gradient", "type": "Float", "units": "m/m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "min": 0.5, "name": "EKF2_TERR_NOISE", "shortDesc": "Terrain altitude process noise", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "max": 299792458.0, "name": "EKF2_VEL_LIM", "shortDesc": "Velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "EKF2", "longDesc": "When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second.", "max": 1.0, "min": 0.0, "name": "EKF2_WIND_NSD", "shortDesc": "Process noise spectral density for wind velocity prediction", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "default": 0, "group": "Events", "longDesc": "Enable/disable event task for RC Loss. When enabled, an alarm tune will be\nplayed via buzzer or ESCs, if supported. The alarm will sound after a disarm,\nif the vehicle was previously armed and only if the vehicle had RC signal at\nsome point. Particularly useful for locating crashed drones without a GPS\nsensor.", "name": "EV_TSK_RC_LOSS", "rebootRequired": true, "shortDesc": "RC Loss Alarm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Events", "longDesc": "Enable/disable event task for displaying the vehicle status using arm-mounted\nLEDs. When enabled and if the vehicle supports it, LEDs will flash\nindicating various vehicle status changes. Currently PX4 has not implemented\nany specific status events.\n-", "name": "EV_TSK_STAT_DIS", "rebootRequired": true, "shortDesc": "Status Display", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "Applies to both directions in all manual modes with attitude stabilization but without altitude control", "max": 90.0, "min": 0.0, "name": "FW_MAN_P_MAX", "shortDesc": "Maximum manual pitch angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 45.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "Applies to both directions in all manual modes with attitude stabilization", "max": 90.0, "min": 0.0, "name": "FW_MAN_R_MAX", "shortDesc": "Maximum manual roll angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "This is the maximally added yaw rate setpoint from the yaw stick in any attitude controlled flight mode.\nIt is added to the yaw rate setpoint generated by the controller for turn coordination.", "min": 0.0, "name": "FW_MAN_YR_MAX", "shortDesc": "Maximum manually added yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "An airframe specific offset of the pitch setpoint in degrees, the value is\nadded to the pitch setpoint and should correspond to the pitch at\ntypical cruise speed of the airframe.", "max": 90.0, "min": -90.0, "name": "FW_PSP_OFF", "shortDesc": "Pitch setpoint offset (pitch at level flight)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 60.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_P_RMAX_NEG", "shortDesc": "Maximum negative / down pitch rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 60.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_P_RMAX_POS", "shortDesc": "Maximum positive / up pitch rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "longDesc": "This defines the latency between a pitch step input and the achieved setpoint\n(inverse to a P gain). Smaller systems may require smaller values.", "max": 1.0, "min": 0.2, "name": "FW_P_TC", "shortDesc": "Attitude pitch time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 70.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_R_RMAX", "shortDesc": "Maximum roll rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "longDesc": "This defines the latency between a roll step input and the achieved setpoint\n(inverse to a P gain). Smaller systems may require smaller values.", "max": 1.0, "min": 0.2, "name": "FW_R_TC", "shortDesc": "Attitude Roll Time Constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Attitude Control", "increment": 0.05, "max": 10.0, "min": 0.0, "name": "FW_WR_FF", "shortDesc": "Wheel steering rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "FW Attitude Control", "increment": 0.005, "longDesc": "This gain defines how much control response will result out of a steady\nstate error. It trims any constant error.", "max": 10.0, "min": 0.0, "name": "FW_WR_I", "shortDesc": "Wheel steering rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_WR_IMAX", "shortDesc": "Wheel steering rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "FW Attitude Control", "increment": 0.005, "longDesc": "This defines how much the wheel steering input will be commanded depending on the\ncurrent body angular rate error.", "max": 10.0, "min": 0.0, "name": "FW_WR_P", "shortDesc": "Wheel steering rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "FW Attitude Control", "longDesc": "Only enabled during automatic runway takeoff and landing.\nIn all manual modes the wheel is directly controlled with yaw stick.", "name": "FW_W_EN", "shortDesc": "Enable wheel steering controller", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "This limits the maximum wheel steering rate the controller will output (in degrees per\nsecond).", "max": 90.0, "min": 0.0, "name": "FW_W_RMAX", "shortDesc": "Maximum wheel steering rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 50.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_Y_RMAX", "shortDesc": "Maximum yaw rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Auto Landing", "increment": 0.01, "longDesc": "Sets a fraction of full flaps during landing.\nAlso applies to flaperons if enabled in the mixer/allocation.", "max": 1.0, "min": 0.0, "name": "FW_FLAPS_LND_SCL", "shortDesc": "Flaps setting during landing", "type": "Float", "units": "norm"}, {"bitmask": [{"description": "Abort if terrain is not found (only applies to mission landings)", "index": 0}, {"description": "Abort if terrain times out (after a first successful measurement)", "index": 1}], "category": "Standard", "default": 3, "group": "FW Auto Landing", "longDesc": "Terrain estimation:\nbit 0: Abort if terrain is not found\nbit 1: Abort if terrain times out (after a first successful measurement)\nThe last estimate is always used as ground, whether the last valid measurement or the land waypoint, depending on the\nselected abort criteria, until an abort condition is entered. If FW_LND_USETER == 0, these bits are ignored.\nTODO: Extend automatic abort conditions\ne.g. glide slope tracking error (horizontal and vertical)", "max": 3, "min": 0, "name": "FW_LND_ABORT", "shortDesc": "Bit mask to set the automatic landing abort conditions", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "The calibrated airspeed setpoint during landing.\nIf set <= 0, landing airspeed = FW_AIRSPD_MIN by default.", "min": -1.0, "name": "FW_LND_AIRSPD", "shortDesc": "Landing airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Typically the desired landing slope angle when landing configuration (flaps, airspeed) is enabled.\nSet this value within the vehicle's performance limits.", "max": 45.0, "min": 1.0, "name": "FW_LND_ANG", "shortDesc": "Maximum landing slope angle", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "FW Auto Landing", "longDesc": "Allows to deploy the landing configuration (flaps, landing airspeed, etc.) already in\nthe loiter-down waypoint before the final approach.\nOtherwise is enabled only in the final approach.", "name": "FW_LND_EARLYCFG", "shortDesc": "Early landing configuration deployment", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * |z-velocity|) is taken as the flare altitude", "min": 0.0, "name": "FW_LND_FLALT", "shortDesc": "Landing flare altitude (relative to landing altitude)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Maximum pitch during landing flare.", "max": 45.0, "min": 0.0, "name": "FW_LND_FL_PMAX", "shortDesc": "Flare, maximum pitch", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Minimum pitch during landing flare.", "max": 15.0, "min": -5.0, "name": "FW_LND_FL_PMIN", "shortDesc": "Flare, minimum pitch", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "TECS will attempt to control the aircraft to this sink rate via pitch angle (throttle killed during flare)", "max": 2.0, "min": 0.0, "name": "FW_LND_FL_SINK", "shortDesc": "Landing flare sink rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "Multiplied by the descent rate to calculate a dynamic altitude at which\nto trigger the flare.\nNOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * descent rate) is taken as the flare altitude", "max": 5.0, "min": 0.1, "name": "FW_LND_FL_TIME", "shortDesc": "Landing flare time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 2, "group": "FW Auto Landing", "longDesc": "Approach angle nudging: shifts the touchdown point laterally while keeping the approach entrance point constant\nApproach path nudging: shifts the touchdown point laterally along with the entire approach path\nThis is useful for manually adjusting the landing point in real time when map or GNSS errors cause an offset from the\ndesired landing vector. Nudging is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is\nrelative to the vehicle heading (stick deflection to the right = land point moves to the right as seen by the vehicle).", "max": 2, "min": 0, "name": "FW_LND_NUDGE", "shortDesc": "Landing touchdown nudging option", "type": "Int32", "values": [{"description": "Disable nudging", "value": 0}, {"description": "Nudge approach angle", "value": 1}, {"description": "Nudge approach path", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "FW Auto Landing", "increment": 1.0, "max": 10.0, "min": 0.0, "name": "FW_LND_TD_OFF", "shortDesc": "Maximum lateral position offset for the touchdown point", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "This is the time after the start of flaring that we expect the vehicle to touch the runway.\nAt this time, a 0.5s clamp down ramp will engage, constraining the pitch setpoint to RWTO_PSP.\nIf enabled, ensure that RWTO_PSP is configured appropriately for full gear contact on ground roll.\nSet to -1.0 to disable touchdown clamping. E.g. it may not be desirable to clamp on belly landings.\nThe touchdown time will be constrained to be greater than or equal to the flare time (FW_LND_FL_TIME).", "max": 5.0, "min": -1.0, "name": "FW_LND_TD_TIME", "shortDesc": "Landing touchdown time (since flare start)", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "The TECS altitude time constant (FW_T_ALT_TC) is multiplied by this value.", "max": 1.0, "min": 0.2, "name": "FW_LND_THRTC_SC", "shortDesc": "Altitude time constant factor for landing and low-height flight", "type": "Float", "units": ""}, {"category": "Standard", "default": 1, "group": "FW Auto Landing", "longDesc": "This is critical for detecting when to flare, and should be enabled if possible.\nIf enabled and no measurement is found within a given timeout, the landing waypoint altitude will be used OR the landing\nwill be aborted, depending on the criteria set in FW_LND_ABORT.\nIf disabled, FW_LND_ABORT terrain based criteria are ignored.", "max": 2, "min": 0, "name": "FW_LND_USETER", "shortDesc": "Use terrain estimation during landing", "type": "Int32", "values": [{"description": "Disable the terrain estimate", "value": 0}, {"description": "Use the terrain estimate to trigger the flare (only)", "value": 1}, {"description": "Calculate landing glide slope relative to the terrain estimate", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Auto Landing", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "FW_SPOILERS_LND", "shortDesc": "Spoiler landing setting", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Auto Takeoff", "increment": 0.01, "longDesc": "Sets a fraction of full flaps during take-off.\nAlso applies to flaperons if enabled in the mixer/allocation.", "max": 1.0, "min": 0.0, "name": "FW_FLAPS_TO_SCL", "shortDesc": "Flaps setting during take-off", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "FW Auto Takeoff", "increment": 0.05, "longDesc": "Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds.", "max": 5.0, "min": 0.0, "name": "FW_LAUN_AC_T", "shortDesc": "Trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Auto Takeoff", "increment": 0.5, "longDesc": "Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds.", "min": 0.0, "name": "FW_LAUN_AC_THLD", "shortDesc": "Trigger acceleration threshold", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 0, "group": "FW Auto Takeoff", "longDesc": "Enables automatic launch detection based on measured acceleration. Use for hand- or catapult-launched vehicles.\nNot compatible with runway takeoff.", "name": "FW_LAUN_DETCN_ON", "shortDesc": "Fixed-wing launch detection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Auto Takeoff", "increment": 0.5, "longDesc": "Start the motor(s) this amount of seconds after launch is detected.", "max": 10.0, "min": 0.0, "name": "FW_LAUN_MOT_DEL", "shortDesc": "Motor delay", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Takeoff", "increment": 0.1, "longDesc": "The calibrated airspeed setpoint during the takeoff climbout.\nIf set <= 0, FW_AIRSPD_MIN will be set by default.", "min": -1.0, "name": "FW_TKO_AIRSPD", "shortDesc": "Takeoff Airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW Auto Takeoff", "increment": 0.5, "max": 80.0, "min": -5.0, "name": "FW_TKO_PITCH_MIN", "shortDesc": "Minimum pitch during takeoff", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 30, "group": "FW General", "longDesc": "The time the system should do open loop loiter and wait for GPS recovery\nbefore it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R.\nDoes only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0.", "min": 0, "name": "FW_GPSF_LT", "shortDesc": "GPS failure loiter time", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW General", "increment": 0.5, "longDesc": "Roll angle in GPS failure loiter mode.", "max": 60.0, "min": 0.0, "name": "FW_GPSF_R", "shortDesc": "GPS failure fixed roll angle", "type": "Float", "units": "deg"}, {"bitmask": [{"description": "Alternative stick configuration (height rate on throttle stick, airspeed on pitch stick)", "index": 0}, {"description": "Enable airspeed setpoint via sticks in altitude and position flight mode", "index": 1}], "category": "Standard", "default": 2, "group": "FW General", "longDesc": "Applies in manual Position and Altitude flight modes.", "max": 3, "min": 0, "name": "FW_POS_STK_CONF", "shortDesc": "Custom stick configuration", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW General", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 80.0, "min": 0.0, "name": "FW_P_LIM_MAX", "shortDesc": "Maximum pitch angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -30.0, "group": "FW General", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 0.0, "min": -60.0, "name": "FW_P_LIM_MIN", "shortDesc": "Minimum pitch angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 50.0, "group": "FW General", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 75.0, "min": 35.0, "name": "FW_R_LIM", "shortDesc": "Maximum roll angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW General", "increment": 0.01, "longDesc": "This is the minimum throttle while on the ground (\"landed\") in auto modes.", "max": 1.0, "min": 0.0, "name": "FW_THR_IDLE", "shortDesc": "Idle throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW General", "increment": 0.01, "longDesc": "Applies in any altitude controlled flight mode.\nShould be set accordingly to achieve FW_T_CLMB_MAX.", "max": 1.0, "min": 0.0, "name": "FW_THR_MAX", "shortDesc": "Throttle limit max", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW General", "increment": 0.01, "longDesc": "Applies in any altitude controlled flight mode.\nUsually set to 0 but can be increased to prevent the motor from stopping when\ndescending, which can increase achievable descent rates.", "max": 1.0, "min": 0.0, "name": "FW_THR_MIN", "shortDesc": "Throttle limit min", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "FW General", "increment": 0.01, "longDesc": "In auto modes: default climb rate output by controller to achieve altitude setpoints.\nIn manual modes: maximum climb rate setpoint.", "min": 0.1, "name": "FW_T_CLMB_R_SP", "shortDesc": "Default target climbrate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "FW General", "increment": 0.01, "longDesc": "In auto modes: default sink rate output by controller to achieve altitude setpoints.\nIn manual modes: maximum sink rate setpoint.", "min": 0.1, "name": "FW_T_SINK_R_SP", "shortDesc": "Default target sinkrate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW General", "increment": 1.0, "longDesc": "Adjusts the amount of weighting that the pitch control\napplies to speed vs height errors.\n0 -> control height only\n2 -> control speed only (gliders)", "max": 2.0, "min": 0.0, "name": "FW_T_SPDWEIGHT", "shortDesc": "Speed <--> Altitude weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "FW General", "increment": 1.0, "longDesc": "This is used to constrain a minimum altitude below which we keep wings level to avoid wing tip strike. It's safer\nto give a slight margin here (> 0m)", "min": 0.0, "name": "FW_WING_HEIGHT", "shortDesc": "Height (AGL) of the wings when the aircraft is on the ground", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "FW General", "increment": 0.1, "longDesc": "This is used for limiting the roll setpoint near the ground. (if multiple wings, take the longest span)", "min": 0.1, "name": "FW_WING_SPAN", "shortDesc": "The aircraft's wing span (length from tip to tip)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "FW Lateral Control", "increment": 1.0, "longDesc": "Maximum change in roll angle setpoint per second.\nApplied in all Auto modes, plus manual Position & Altitude modes.", "min": 0.0, "name": "FW_PN_R_SLEW_MAX", "shortDesc": "Path navigation roll slew rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "longDesc": "The controller will increase the commanded airspeed to maintain\nthis minimum groundspeed to the next waypoint.", "max": 40.0, "min": 0.0, "name": "FW_GND_SPD_MIN", "shortDesc": "Minimum groundspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "Maximum slew rate for the commanded throttle", "max": 1.0, "min": 0.0, "name": "FW_THR_SLEW_MAX", "shortDesc": "Throttle max slew rate", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "min": 2.0, "name": "FW_T_ALT_TC", "shortDesc": "Altitude error time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW Longitudinal Control", "longDesc": "Minimum altitude error needed to descend with max airspeed and minimal throttle.\nA negative value disables fast descend.", "min": -1.0, "name": "FW_T_F_ALT_ERR", "shortDesc": "Fast descend: minimum altitude error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW Longitudinal Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_T_HRATE_FF", "shortDesc": "Height rate feed forward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW Longitudinal Control", "increment": 0.05, "longDesc": "Increase it to trim out speed and height offsets faster,\nwith the downside of possible overshoots and oscillations.", "max": 2.0, "min": 0.0, "name": "FW_T_I_GAIN_PIT", "shortDesc": "Integrator gain pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW Longitudinal Control", "increment": 0.1, "max": 2.0, "min": 0.0, "name": "FW_T_PTCH_DAMP", "shortDesc": "Pitch damping gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Longitudinal Control", "increment": 0.5, "longDesc": "Is used to compensate for the additional drag created by turning.\nIncrease this gain if the aircraft initially loses energy in turns\nand reduce if the aircraft initially gains energy in turns.", "max": 20.0, "min": 0.0, "name": "FW_T_RLL2THR", "shortDesc": "Roll -> Throttle feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Longitudinal Control", "increment": 0.01, "max": 3.0, "min": 0.5, "name": "FW_T_SEB_R_FF", "shortDesc": "Specific total energy balance rate feedforward gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "max": 15.0, "min": 1.0, "name": "FW_T_SINK_MAX", "shortDesc": "Maximum descent rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Longitudinal Control", "increment": 0.1, "longDesc": "For the airspeed filter in TECS.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_DEV_STD", "shortDesc": "Airspeed rate measurement standard deviation", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Longitudinal Control", "increment": 0.1, "longDesc": "This is defining the noise in the airspeed rate for the constant airspeed rate model\nof the TECS airspeed filter.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_PRC_STD", "shortDesc": "Process noise standard deviation for the airspeed rate", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.07, "group": "FW Longitudinal Control", "increment": 0.1, "longDesc": "For the airspeed filter in TECS.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_STD", "shortDesc": "Airspeed measurement standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "This filter is applied to the specific total energy rate used for throttle damping.", "max": 2.0, "min": 0.0, "name": "FW_T_STE_R_TC", "shortDesc": "Specific total energy rate first order filter time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "min": 2.0, "name": "FW_T_TAS_TC", "shortDesc": "True airspeed error time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "This is the damping gain for the throttle demand loop.", "max": 1.0, "min": 0.0, "name": "FW_T_THR_DAMPING", "shortDesc": "Throttle damping factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.02, "group": "FW Longitudinal Control", "increment": 0.005, "longDesc": "Increase it to trim out speed and height offsets faster,\nwith the downside of possible overshoots and oscillations.", "max": 1.0, "min": 0.0, "name": "FW_T_THR_INTEG", "shortDesc": "Integrator gain throttle", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW Longitudinal Control", "increment": 1.0, "longDesc": "Height above ground threshold below which tighter altitude\ntracking gets enabled (see FW_LND_THRTC_SC). Below this height, TECS smoothly\n(1 sec / sec) transitions the altitude tracking time constant from FW_T_ALT_TC\nto FW_LND_THRTC_SC*FW_T_ALT_TC.\n-1 to disable.", "min": -1.0, "name": "FW_T_THR_LOW_HGT", "shortDesc": "Low-height threshold for tighter altitude tracking", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 7.0, "group": "FW Longitudinal Control", "increment": 0.5, "longDesc": "This is the maximum vertical acceleration\neither up or down that the controller will use to correct speed\nor height errors.", "max": 10.0, "min": 1.0, "name": "FW_T_VERT_ACC", "shortDesc": "Maximum vertical acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "Multiplying this factor with the current absolute wind estimate gives the airspeed offset\nadded to the minimum airspeed setpoint limit. This helps to make the\nsystem more robust against disturbances (turbulence) in high wind.", "min": 0.0, "name": "FW_WIND_ARSP_SC", "shortDesc": "Wind-based airspeed scaling factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "FW NPFG Control", "increment": 0.01, "longDesc": "Damping ratio of NPFG control law.", "max": 1.0, "min": 0.1, "name": "NPFG_DAMPING", "shortDesc": "NPFG damping ratio", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Avoids limit cycling from a too aggressively tuned period/damping combination.\nIf false, also disables upper bound NPFG_PERIOD_UB.", "name": "NPFG_LB_PERIOD", "shortDesc": "Enable automatic lower bound on the NPFG period", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW NPFG Control", "increment": 0.1, "longDesc": "Period of NPFG control law.", "max": 100.0, "min": 1.0, "name": "NPFG_PERIOD", "shortDesc": "NPFG period", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "FW NPFG Control", "increment": 0.1, "longDesc": "Multiplied by period for conservative minimum period bounding (when period lower\nbounding is enabled). 1.0 bounds at marginal stability.", "max": 10.0, "min": 1.0, "name": "NPFG_PERIOD_SF", "shortDesc": "Period safety factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW NPFG Control", "increment": 0.05, "longDesc": "Time constant of roll controller command / response, modeled as first order delay.\nUsed to determine lower period bound. Setting zero disables automatic period bounding.", "max": 2.0, "min": 0.0, "name": "NPFG_ROLL_TC", "shortDesc": "Roll time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.32, "group": "FW NPFG Control", "increment": 0.01, "longDesc": "Multiplied by the track error boundary to determine when the aircraft switches\nto the next waypoint and/or path segment. Should be less than 1.", "max": 1.0, "min": 0.1, "name": "NPFG_SW_DST_MLT", "shortDesc": "NPFG switch distance multiplier", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Adapts period to maintain track keeping in variable winds and path curvature.", "name": "NPFG_UB_PERIOD", "shortDesc": "Enable automatic upper bound on the NPFG period", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Factor applied to the minimum and stall airspeed when flaps are fully deployed.", "max": 1.0, "min": 0.5, "name": "FW_AIRSPD_FLP_SC", "shortDesc": "Airspeed scale with full flaps", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The maximal airspeed (calibrated airspeed) the user is able to command.", "min": 0.5, "name": "FW_AIRSPD_MAX", "shortDesc": "Maximum Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The minimal airspeed (calibrated airspeed) the user is able to command.\nFurther, if the airspeed falls below this value, the TECS controller will try to\nincrease airspeed more aggressively.\nHas to be set according to the vehicle's stall speed (which should be set in FW_AIRSPD_STALL),\nwith some margin between the stall speed and minimum airspeed.\nThis value corresponds to the desired minimum speed with the default load factor (level flight, default weight),\nand is automatically adpated to the current load factor (calculated from roll setpoint and WEIGHT_GROSS/WEIGHT_BASE).", "min": 0.5, "name": "FW_AIRSPD_MIN", "shortDesc": "Minimum Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 7.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The stall airspeed (calibrated airspeed) of the vehicle.\nIt is used for airspeed sensor failure detection and for the control\nsurface scaling airspeed limits.", "min": 0.5, "name": "FW_AIRSPD_STALL", "shortDesc": "Stall Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The trim CAS (calibrated airspeed) of the vehicle. If an airspeed controller is active,\nthis is the default airspeed setpoint that the controller will try to achieve.\nThis value corresponds to the trim airspeed with the default load factor (level flight, default weight).", "min": 0.5, "name": "FW_AIRSPD_TRIM", "shortDesc": "Trim (Cruise) Airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW Performance", "increment": 1.0, "longDesc": "Altitude in standard atmosphere at which the vehicle in normal configuration (WEIGHT_BASE) is still able to achieve a maximum climb rate of\n0.5m/s at maximum throttle (FW_THR_MAX). Used to compensate for air density in FW_T_CLMB_MAX.\nSet negative to disable.", "min": -1.0, "name": "FW_SERVICE_CEIL", "shortDesc": "Service ceiling", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at maximum airspeed FW_AIRSPD_MAX\nSet to 0 to disable mapping of airspeed to trim throttle.", "max": 1.0, "min": 0.0, "name": "FW_THR_ASPD_MAX", "shortDesc": "Throttle at max airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at minimum airspeed FW_AIRSPD_MIN\nSet to 0 to disable mapping of airspeed to trim throttle below FW_AIRSPD_TRIM.", "max": 1.0, "min": 0.0, "name": "FW_THR_ASPD_MIN", "shortDesc": "Throttle at min airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at FW_AIRSPD_TRIM", "max": 1.0, "min": 0.0, "name": "FW_THR_TRIM", "shortDesc": "Trim throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the maximum calibrated climb rate that the aircraft can achieve with\nthe throttle set to FW_THR_MAX and the airspeed set to the\ntrim value. For electric aircraft make sure this number can be\nachieved towards the end of flight when the battery voltage has reduced.", "min": 1.0, "name": "FW_T_CLMB_MAX", "shortDesc": "Maximum climb rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the minimum calibrated sink rate of the aircraft with the throttle\nset to THR_MIN and flown at the same airspeed as used\nto measure FW_T_CLMB_MAX.", "min": 1.0, "name": "FW_T_SINK_MIN", "shortDesc": "Minimum descent rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the weight of the vehicle at which it's performance limits were derived. A zero or negative value\ndisables trim throttle and minimum airspeed compensation based on weight.", "name": "WEIGHT_BASE", "shortDesc": "Vehicle base weight", "type": "Float", "units": "kg"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Performance", "increment": 0.1, "longDesc": "This is the actual weight of the vehicle at any time. This value will differ from WEIGHT_BASE in case weight was added\nor removed from the base weight. Examples are the addition of payloads or larger batteries. A zero or negative value\ndisables trim throttle and minimum airspeed compensation based on weight.", "name": "WEIGHT_GROSS", "shortDesc": "Vehicle gross weight", "type": "Float", "units": "kg"}, {"category": "Standard", "default": 90.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_X_MAX", "shortDesc": "Acro body roll max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "If this parameter is set to 1, the yaw rate controller is enabled in Fixed-wing Acro mode.\nOtherwise the pilot commands directly the yaw actuator.\nIt is disabled by default because an active yaw rate controller will fight against the\nnatural turn coordination of the plane.", "name": "FW_ACRO_YAW_EN", "shortDesc": "Enable yaw rate controller in Acro", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 90.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_Y_MAX", "shortDesc": "Acro body pitch max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 45.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_Z_MAX", "shortDesc": "Acro body yaw max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "longDesc": "This enables a logic that automatically adjusts the output of the rate controller to take\ninto account the real torque produced by an aerodynamic control surface given\nthe current deviation from the trim airspeed (FW_AIRSPD_TRIM).\nEnable when using aerodynamic control surfaces (e.g.: plane)\nDisable when using rotor wings (e.g.: autogyro)", "name": "FW_ARSP_SCALE_EN", "shortDesc": "Enable airspeed scaling", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "This compensates for voltage drop of the battery over time by attempting to\nnormalize performance across the operating range of the battery.", "name": "FW_BAT_SCALE_EN", "shortDesc": "Enable throttle scale by battery level", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_P_VMAX", "shortDesc": "Pitch trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_P_VMIN", "shortDesc": "Pitch trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_R_VMAX", "shortDesc": "Roll trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_R_VMIN", "shortDesc": "Roll trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_Y_VMAX", "shortDesc": "Yaw trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_Y_VMIN", "shortDesc": "Yaw trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "name": "FW_GC_EN", "shortDesc": "Enable rate gain compression", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW Rate Control", "increment": 0.01, "longDesc": "The range of the compression gain is between this parameter and 1.0", "max": 1.0, "min": 0.0, "name": "FW_GC_GAIN_MIN", "shortDesc": "Compression gain lower limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired pitch actuator command in full manual mode. This parameter allows\nto adjust the throws of the control surfaces.", "min": 0.0, "name": "FW_MAN_P_SC", "shortDesc": "Manual pitch scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired roll actuator command in full manual mode. This parameter allows\nto adjust the throws of the control surfaces.", "max": 1.0, "min": 0.0, "name": "FW_MAN_R_SC", "shortDesc": "Manual roll scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows\nto adjust the throws of the control surfaces.", "min": 0.0, "name": "FW_MAN_Y_SC", "shortDesc": "Manual yaw scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "longDesc": "Pitch rate differential gain.", "max": 10.0, "min": 0.0, "name": "FW_PR_D", "shortDesc": "Pitch rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output", "max": 10.0, "min": 0.0, "name": "FW_PR_FF", "shortDesc": "Pitch rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_PR_I", "shortDesc": "Pitch rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_PR_IMAX", "shortDesc": "Pitch rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.08, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_PR_P", "shortDesc": "Pitch rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This gain can be used to counteract the \"adverse yaw\" effect for fixed wings.\nWhen the plane enters a roll it will tend to yaw the nose out of the turn.\nThis gain enables the use of a yaw actuator to counteract this effect.", "min": 0.0, "name": "FW_RLL_TO_YAW_FF", "shortDesc": "Roll control to yaw control feedforward gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_RR_D", "shortDesc": "Roll rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output.", "max": 10.0, "min": 0.0, "name": "FW_RR_FF", "shortDesc": "Roll rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW Rate Control", "increment": 0.01, "max": 10.0, "min": 0.0, "name": "FW_RR_I", "shortDesc": "Roll rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_RR_IMAX", "shortDesc": "Roll integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_RR_P", "shortDesc": "Roll rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "Chose source for manual setting of spoilers in manual flight modes.", "name": "FW_SPOILERS_MAN", "shortDesc": "Spoiler input in manual flight", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Flaps channel", "value": 1}, {"description": "Aux1", "value": 2}]}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "longDesc": "If set to 1, the airspeed measurement data, if valid, is used in the following controllers:\n- Rate controller: output scaling\n- Attitude controller: coordinated turn controller\n- Position controller: airspeed setpoint tracking, takeoff logic\n- VTOL: transition logic", "name": "FW_USE_AIRSPD", "shortDesc": "Use airspeed for control", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_YR_D", "shortDesc": "Yaw rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output", "max": 10.0, "min": 0.0, "name": "FW_YR_FF", "shortDesc": "Yaw rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.1, "group": "FW Rate Control", "increment": 0.5, "max": 10.0, "min": 0.0, "name": "FW_YR_I", "shortDesc": "Yaw rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_YR_IMAX", "shortDesc": "Yaw rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_YR_P", "shortDesc": "Yaw rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "Failure Detector", "longDesc": "If enabled, failure detector will verify that for motors, a minimum amount of ESC current per throttle\nlevel is being consumed.\nOtherwise this indicates an motor failure.", "name": "FD_ACT_EN", "rebootRequired": true, "shortDesc": "Enable Actuator Failure check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Failure Detector", "increment": 1.0, "longDesc": "threshold = FD_ACT_MOT_C2T * thrust + FD_ACT_HIGH_OFF", "max": 30.0, "min": 0.0, "name": "FD_ACT_HIGH_OFF", "shortDesc": "Overcurrent motor failure limit offset", "type": "Float", "units": "A"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Failure Detector", "increment": 1.0, "longDesc": "threshold = FD_ACT_MOT_C2T * thrust - FD_ACT_LOW_OFF", "max": 30.0, "min": 0.0, "name": "FD_ACT_LOW_OFF", "shortDesc": "Undercurrent motor failure limit offset", "type": "Float", "units": "A"}, {"category": "Standard", "decimalPlaces": 2, "default": 35.0, "group": "Failure Detector", "increment": 1.0, "longDesc": "Determines the slope between expected steady state current and linearized, normalized thrust command.\nE.g. FD_ACT_MOT_C2T A represents the expected steady state current at 100%.\nFD_ACT_LOW_OFF and FD_ACT_HIGH_OFF offset the threshold from that slope.", "max": 50.0, "min": 0.0, "name": "FD_ACT_MOT_C2T", "shortDesc": "Motor Failure Current/Throttle Scale", "type": "Float", "units": "A/%"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Failure Detector", "increment": 0.01, "longDesc": "Failure detection per motor only triggers above this thrust value.\nSet to 1 to disable the detection.", "max": 1.0, "min": 0.0, "name": "FD_ACT_MOT_THR", "shortDesc": "Motor Failure Thrust Threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 1000, "group": "Failure Detector", "increment": 100, "longDesc": "Motor failure only triggers after current thresholds are exceeded for this time.", "max": 10000, "min": 10, "name": "FD_ACT_MOT_TOUT", "shortDesc": "Motor Failure Hysteresis Time", "type": "Int32", "units": "ms"}, {"category": "Standard", "default": 1, "group": "Failure Detector", "longDesc": "If enabled, failure detector will verify that all the ESCs have successfully armed when the vehicle has transitioned to the armed state.\nTimeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback is received the failure detector will auto disarm the vehicle.", "name": "FD_ESCS_EN", "shortDesc": "Enable checks on ESCs that report their arming state", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Failure Detector", "longDesc": "Enabled on either AUX5 or MAIN5 depending on board.\nExternal ATS is required by ASTM F3322-18.", "name": "FD_EXT_ATS_EN", "rebootRequired": true, "shortDesc": "Enable PWM input on for engaging failsafe from an external automatic trigger system (ATS)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1900, "group": "Failure Detector", "longDesc": "External ATS is required by ASTM F3322-18.", "name": "FD_EXT_ATS_TRIG", "shortDesc": "The PWM threshold from external automatic trigger system for engaging failsafe", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 60, "group": "Failure Detector", "longDesc": "Maximum pitch angle before FailureDetector triggers the attitude_failure flag.\nThe flag triggers flight termination (if @CBRK_FLIGHTTERM = 0),\nwhich sets outputs to their failsafe values.\nOn takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM),\nwhich disarms motors but does not set outputs to failsafe values.\nSetting this parameter to 0 disables the check", "max": 180, "min": 0, "name": "FD_FAIL_P", "shortDesc": "FailureDetector Max Pitch", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Failure Detector", "longDesc": "Seconds (decimal) that pitch has to exceed FD_FAIL_P before being considered as a failure.", "max": 5.0, "min": 0.02, "name": "FD_FAIL_P_TTRI", "shortDesc": "Pitch failure trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 60, "group": "Failure Detector", "longDesc": "Maximum roll angle before FailureDetector triggers the attitude_failure flag.\nThe flag triggers flight termination (if @CBRK_FLIGHTTERM = 0),\nwhich sets outputs to their failsafe values.\nOn takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM),\nwhich disarms motors but does not set outputs to failsafe values.\nSetting this parameter to 0 disables the check", "max": 180, "min": 0, "name": "FD_FAIL_R", "shortDesc": "FailureDetector Max Roll", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Failure Detector", "longDesc": "Seconds (decimal) that roll has to exceed FD_FAIL_R before being considered as a failure.", "max": 5.0, "min": 0.02, "name": "FD_FAIL_R_TTRI", "shortDesc": "Roll failure trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 30, "group": "Failure Detector", "increment": 1, "longDesc": "Value at which the imbalanced propeller metric (based on horizontal and\nvertical acceleration variance) triggers a failure\nSetting this value to 0 disables the feature.", "max": 1000, "min": 0, "name": "FD_IMB_PROP_THR", "shortDesc": "Imbalanced propeller check threshold", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 1000.0, "group": "Flight Task Orbit", "increment": 0.5, "max": 10000.0, "min": 1.0, "name": "MC_ORBIT_RAD_MAX", "shortDesc": "Maximum radius of orbit", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Flight Task Orbit", "name": "MC_ORBIT_YAW_MOD", "shortDesc": "Yaw behaviour during orbit flight", "type": "Int32", "values": [{"description": "Front to Circle Center", "value": 0}, {"description": "Hold Initial Heading", "value": 1}, {"description": "Uncontrolled", "value": 2}, {"description": "Hold Front Tangent to Circle", "value": 3}, {"description": "Manually (yaw stick) Controlled", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Follow target", "longDesc": "Maintain altitude or track target's altitude. When maintaining the altitude,\nthe drone can crash into terrain when the target moves uphill. When tracking\nthe target's altitude, the follow altitude FLW_TGT_HT should be high enough\nto prevent terrain collisions due to GPS inaccuracies of the target.", "name": "FLW_TGT_ALT_M", "shortDesc": "Altitude control mode", "type": "Int32", "values": [{"description": "2D Tracking: Maintain constant altitude relative to home and track XY position only", "value": 0}, {"description": "2D + Terrain: Maintain constant altitude relative to terrain below and track XY position", "value": 1}, {"description": "3D Tracking: Track target's altitude (be aware that GPS altitude bias usually makes this useless)", "value": 2}]}, {"category": "Standard", "default": 8.0, "group": "Follow target", "longDesc": "The distance in meters to follow the target at", "min": 1.0, "name": "FLW_TGT_DST", "shortDesc": "Distance to follow target from", "type": "Float", "units": "m"}, {"category": "Standard", "default": 180.0, "group": "Follow target", "longDesc": "Angle to follow the target from. 0.0 Equals straight in front of the target's\ncourse (direction of motion) and the angle increases in clockwise direction,\nmeaning Right-side would be 90.0 degrees while Left-side is -90.0 degrees\nNote: When the user force sets the angle out of the min/max range, it will be\nwrapped (e.g. 480 -> 120) in the range to gracefully handle the out of range.", "max": 180.0, "min": -180.0, "name": "FLW_TGT_FA", "shortDesc": "Follow Angle setting in degrees", "type": "Float"}, {"category": "Standard", "default": 8.0, "group": "Follow target", "longDesc": "Following height above the target", "min": 8.0, "name": "FLW_TGT_HT", "shortDesc": "Follow target height", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Follow target", "longDesc": "This is the maximum tangential velocity the drone will circle around the target whenever\nan orbit angle setpoint changes. Higher value means more aggressive follow behavior.", "max": 20.0, "min": 0.0, "name": "FLW_TGT_MAX_VEL", "shortDesc": "Maximum tangential velocity setting for generating the follow orbit trajectory", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Follow target", "longDesc": "lower values increase the responsiveness to changing position, but also ignore less noise", "max": 1.0, "min": 0.0, "name": "FLW_TGT_RS", "shortDesc": "Responsiveness to target movement in Target Estimator", "type": "Float"}, {"bitmask": [{"description": "GPS (with QZSS)", "index": 0}, {"description": "SBAS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "BeiDou", "index": 3}, {"description": "GLONASS", "index": 4}, {"description": "NAVIC", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "longDesc": "This integer bitmask controls the set of GNSS systems used by the receiver. Check your\nreceiver's documentation on how many systems are supported to be used in parallel.\nCurrently this functionality is just implemented for u-blox receivers.\nWhen no bits are set, the receiver's default configuration should be used.\nSet bits true to enable:\n0 : Use GPS (with QZSS)\n1 : Use SBAS (multiple GPS augmentation systems)\n2 : Use Galileo\n3 : Use BeiDou\n4 : Use GLONASS\n5 : Use NAVIC", "max": 63, "min": 0, "name": "GPS_1_GNSS", "rebootRequired": true, "shortDesc": "GNSS Systems for Primary GPS (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Select the GPS protocol over serial.\nAuto-detection will probe all protocols, and thus is a bit slower.", "max": 7, "min": 0, "name": "GPS_1_PROTOCOL", "rebootRequired": true, "shortDesc": "Protocol for Main GPS", "type": "Int32", "values": [{"description": "Auto detect", "value": 0}, {"description": "u-blox", "value": 1}, {"description": "MTK", "value": 2}, {"description": "Ashtech / Trimble", "value": 3}, {"description": "Emlid Reach", "value": 4}, {"description": "Femtomes", "value": 5}, {"description": "NMEA (generic)", "value": 6}]}, {"bitmask": [{"description": "GPS (with QZSS)", "index": 0}, {"description": "SBAS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "BeiDou", "index": 3}, {"description": "GLONASS", "index": 4}, {"description": "NAVIC", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "longDesc": "This integer bitmask controls the set of GNSS systems used by the receiver. Check your\nreceiver's documentation on how many systems are supported to be used in parallel.\nCurrently this functionality is just implemented for u-blox receivers.\nWhen no bits are set, the receiver's default configuration should be used.\nSet bits true to enable:\n0 : Use GPS (with QZSS)\n1 : Use SBAS (multiple GPS augmentation systems)\n2 : Use Galileo\n3 : Use BeiDou\n4 : Use GLONASS\n5 : Use NAVIC", "max": 63, "min": 0, "name": "GPS_2_GNSS", "rebootRequired": true, "shortDesc": "GNSS Systems for Secondary GPS (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Select the GPS protocol over serial.\nAuto-detection will probe all protocols, and thus is a bit slower.", "max": 6, "min": 0, "name": "GPS_2_PROTOCOL", "rebootRequired": true, "shortDesc": "Protocol for Secondary GPS", "type": "Int32", "values": [{"description": "Auto detect", "value": 0}, {"description": "u-blox", "value": 1}, {"description": "MTK", "value": 2}, {"description": "Ashtech / Trimble", "value": 3}, {"description": "Emlid Reach", "value": 4}, {"description": "Femtomes", "value": 5}, {"description": "NMEA (generic)", "value": 6}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Some UBX modules have a FLASH that allows to store persistent configuration that will be loaded on start.\nPX4 does override all configuration parameters it needs in RAM, which takes precedence over the values in FLASH.\nHowever, configuration parameters that are not overriden by PX4 can still cause unexpected problems during flight.\nTo avoid these kind of problems a clean config can be reached by wiping the FLASH on boot.\nNote: Currently only supported on UBX.", "name": "GPS_CFG_WIPE", "rebootRequired": true, "shortDesc": "Wipes the flash config of UBX modules", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "If this is set to 1, all GPS communication data will be published via uORB,\nand written to the log file as gps_dump message.\nIf this is set to 2, the main GPS is configured to output RTCM data,\nwhich is then logged as gps_dump and can be used for PPK.", "max": 2, "min": 0, "name": "GPS_DUMP_COMM", "shortDesc": "Log GPS communication data", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Full communication", "value": 1}, {"description": "RTCM output (PPK)", "value": 2}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Enable publication of satellite info (ORB_ID(satellite_info)) if possible.\nNot available on MTK.", "name": "GPS_SAT_INFO", "rebootRequired": true, "shortDesc": "Enable sat info (if available)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 230400, "group": "GPS", "longDesc": "Select a baudrate for the F9P's UART2 port.\nIn GPS_UBX_MODE 1, 2, and 3, the F9P's UART2 port is configured to send/receive RTCM corrections.\nSet this to 57600 if you want to attach a telemetry radio on UART2.", "min": 0, "name": "GPS_UBX_BAUD2", "rebootRequired": true, "shortDesc": "u-blox F9P UART2 Baudrate", "type": "Int32", "units": "B/s"}, {"bitmask": [{"description": "Enable I2C input protocol UBX", "index": 0}, {"description": "Enable I2C input protocol NMEA", "index": 1}, {"description": "Enable I2C input protocol RTCM3X", "index": 2}, {"description": "Enable I2C output protocol UBX", "index": 3}, {"description": "Enable I2C output protocol NMEA", "index": 4}, {"description": "Enable I2C output protocol RTCM3X", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "max": 32, "min": 0, "name": "GPS_UBX_CFG_INTF", "rebootRequired": true, "shortDesc": "u-blox protocol configuration for interfaces", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "When set to 0 (default), default DGNSS timeout set by u-blox will be used.", "max": 255, "min": 0, "name": "GPS_UBX_DGNSS_TO", "rebootRequired": true, "shortDesc": "u-blox GPS DGNSS timeout", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 7, "group": "GPS", "longDesc": "u-blox receivers support different dynamic platform models to adjust the navigation engine to\nthe expected application environment.", "max": 9, "min": 0, "name": "GPS_UBX_DYNMODEL", "rebootRequired": true, "shortDesc": "u-blox GPS dynamic platform model", "type": "Int32", "values": [{"description": "stationary", "value": 2}, {"description": "automotive", "value": 4}, {"description": "airborne with <1g acceleration", "value": 6}, {"description": "airborne with <2g acceleration", "value": 7}, {"description": "airborne with <4g acceleration", "value": 8}]}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Enables or disables the high sensitivity mode for the u-blox jamming detection\n(CFG-SEC-JAMDET_SENSITIVITY_HI). When enabled, the receiver uses a\nmore sensitive algorithm to detect jamming. Disabling this may reduce false\npositives in electrically noisy environments.", "name": "GPS_UBX_JAM_DET", "rebootRequired": true, "shortDesc": "u-blox GPS jamming detection high sensitivity mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "When set to 0 (default), default minimum satellite signal level set by u-blox wll be used.", "max": 255, "min": 0, "name": "GPS_UBX_MIN_CNO", "rebootRequired": true, "shortDesc": "u-blox GPS minimum satellite signal level for navigation", "type": "Int32", "units": "dBHz"}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "When set to 0 (default), default minimum elevation set by u-blox will be used.", "max": 127, "min": 0, "name": "GPS_UBX_MIN_ELEV", "rebootRequired": true, "shortDesc": "u-blox GPS minimum elevation for a GNSS satellite to be used in navigation", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Select the u-blox configuration setup. Most setups will use the default, including RTK and\ndual GPS without heading.\nIf rover has RTCM corrections from a static base (or other static correction source) coming in on UART2, then select Mode 5.\nThe Heading mode requires 2 F9P devices to be attached. The main GPS will act as rover and output\nheading information, whereas the secondary will act as moving base.\nModes 1 and 2 require each F9P UART1 to be connected to the Autopilot. In addition, UART2 on the\nF9P units are connected to each other.\nModes 3 and 4 only require UART1 on each F9P connected to the Autopilot or Can Node. UART RX DMA is required.\nRTK is still possible with this setup.\nMode 6 is intended for use with a ground control station (not necessarily an RTK correction base).", "max": 1, "min": 0, "name": "GPS_UBX_MODE", "rebootRequired": true, "shortDesc": "u-blox GPS Mode", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Heading (Rover With Moving Base UART1 Connected To Autopilot, UART2 Connected To Moving Base)", "value": 1}, {"description": "Moving Base (UART1 Connected To Autopilot, UART2 Connected To Rover)", "value": 2}, {"description": "Heading (Rover With Moving Base UART1 Connected to Autopilot Or Can Node At 921600)", "value": 3}, {"description": "Moving Base (Moving Base UART1 Connected to Autopilot Or Can Node At 921600)", "value": 4}, {"description": "Rover with Static Base on UART2 (similar to Default, except coming in on UART2)", "value": 5}, {"description": "Ground Control Station (UART2 outputs NMEA)", "value": 6}]}, {"category": "Standard", "default": 0, "group": "GPS", "name": "GPS_UBX_PPK", "rebootRequired": true, "shortDesc": "Enable MSM7 message output for PPK workflow", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Configure the output rate of u-blox GPS receivers (protocol v27+).\nWhen set to 0, automatic rate selection is used based on the receiver model.\nDefault rates: M9N=8Hz, F9P L1L2=5Hz, F9P L1L5=5Hz, Others=10Hz.\nNote: Higher rates reduce satellite count (e.g., >8Hz limits to 16 SVs on M9N).\nMax rates vary by model and RTK mode: F9P L1L2=5-7Hz, F9P L1L5=7-8Hz, X20=25Hz.\nHigh rates at 115200 baud may cause dropouts.", "max": 25, "min": 0, "name": "GPS_UBX_RATE", "rebootRequired": true, "shortDesc": "u-blox GPS output rate", "type": "Int32", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "GPS", "longDesc": "Heading offset angle for dual antenna GPS setups that support heading estimation.\nSet this to 0 if the antennas are parallel to the forward-facing direction\nof the vehicle and the rover (or Unicore primary) antenna is in front.\nThe offset angle increases clockwise.\nSet this to 90 if the rover (or Unicore primary, or Septentrio Mosaic Aux)\nantenna is placed on the right side of the vehicle and the moving base\nantenna is on the left side.\n(Note: the Unicore primary antenna is the one connected on the right as seen\nfrom the top).", "max": 360.0, "min": 0.0, "name": "GPS_YAW_OFFSET", "rebootRequired": true, "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Geofence", "longDesc": "Note: Setting this value to 4 enables flight termination,\nwhich will kill the vehicle on violation of the fence.", "max": 5, "min": 0, "name": "GF_ACTION", "shortDesc": "Geofence violation action", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold mode", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land mode", "value": 5}]}, {"category": "Standard", "default": 0.0, "group": "Geofence", "increment": 1.0, "longDesc": "Maximum horizontal distance in meters the vehicle can be from Home before triggering a geofence action.\nDisabled if 0.", "max": 10000.0, "min": 0.0, "name": "GF_MAX_HOR_DIST", "shortDesc": "Max horizontal distance from Home", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0.0, "group": "Geofence", "increment": 1.0, "longDesc": "Maximum vertical distance in meters the vehicle can be from Home before triggering a geofence action.\nDisabled if 0.", "max": 10000.0, "min": 0.0, "name": "GF_MAX_VER_DIST", "shortDesc": "Max vertical distance from Home", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geofence", "longDesc": "WARNING: This experimental feature may cause flyaways. Use at your own risk.\nPredict the motion of the vehicle and trigger the breach if it is determined that the current trajectory\nwould result in a breach happening before the vehicle can make evasive maneuvers.\nThe vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing).", "name": "GF_PREDICT", "shortDesc": "[EXPERIMENTAL] Use Pre-emptive geofence triggering", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Geofence", "longDesc": "Select which position source should be used. Selecting GPS instead of global position makes sure that there is\nno dependence on the position estimator\n0 = global position, 1 = GPS", "max": 1, "min": 0, "name": "GF_SOURCE", "shortDesc": "Geofence source", "type": "Int32", "values": [{"description": "GPOS", "value": 0}, {"description": "GPS", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines which mixer implementation to use.\nSome are generic, while others are specifically fit to a certain vehicle with a fixed set of actuators.\n'Custom' should only be used if noting else can be used.", "name": "CA_AIRFRAME", "shortDesc": "Airframe selection", "type": "Int32", "values": [{"description": "Multirotor", "value": 0}, {"description": "Fixed-wing", "value": 1}, {"description": "Standard VTOL", "value": 2}, {"description": "Tiltrotor VTOL", "value": 3}, {"description": "Tailsitter VTOL", "value": 4}, {"description": "Rover (Ackermann)", "value": 5}, {"description": "Rover (Differential)", "value": 6}, {"description": "Motors (6DOF)", "value": 7}, {"description": "Multirotor with Tilt", "value": 8}, {"description": "Custom", "value": 9}, {"description": "Helicopter (tail ESC)", "value": 10}, {"description": "Helicopter (tail Servo)", "value": 11}, {"description": "Helicopter (Coaxial)", "value": 12}, {"description": "Rover (Mecanum)", "value": 13}, {"description": "Spacecraft 2D", "value": 14}, {"description": "Spacecraft 3D", "value": 15}]}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "This is used to specify how to handle motor failures\nreported by failure detector.", "name": "CA_FAILURE_MODE", "shortDesc": "Motor failure handling mode", "type": "Int32", "values": [{"description": "Ignore", "value": 0}, {"description": "Remove first failed motor from effectiveness", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": -0.05, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 0 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C0", "shortDesc": "Collective pitch curve at position 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0725, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 1 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C1", "shortDesc": "Collective pitch curve at position 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 2 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C2", "shortDesc": "Collective pitch curve at position 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.325, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 3 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C3", "shortDesc": "Collective pitch curve at position 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.45, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 4 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C4", "shortDesc": "Collective pitch curve at position 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Same definition as the proportional gain but for integral.", "max": 10.0, "min": 0.0, "name": "CA_HELI_RPM_I", "shortDesc": "Integral gain for rpm control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Ratio between rpm error devided by 1000 to how much normalized output gets added to correct for it.\nmotor_command = throttle_curve + CA_HELI_RPM_P * (rpm_setpoint - rpm_measurement) / 1000", "max": 10.0, "min": 0.0, "name": "CA_HELI_RPM_P", "shortDesc": "Proportional gain for rpm control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": 1500.0, "group": "Geometry", "increment": 1.0, "longDesc": "Requires rpm feedback for the controller.", "max": 10000.0, "min": 100.0, "name": "CA_HELI_RPM_SP", "shortDesc": "Setpoint for main rotor rpm", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 0.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C0", "shortDesc": "Throttle curve at position 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 1.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C1", "shortDesc": "Throttle curve at position 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 2.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C2", "shortDesc": "Throttle curve at position 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 3.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C3", "shortDesc": "Throttle curve at position 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 4.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C4", "shortDesc": "Throttle curve at position 4", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Default configuration is for a clockwise turning main rotor and\npositive thrust of the tail rotor is expected to rotate the vehicle clockwise.\nSet this parameter to true if the tail rotor provides thrust in counter-clockwise direction\nwhich is mostly the case when the main rotor turns counter-clockwise.", "name": "CA_HELI_YAW_CCW", "shortDesc": "Main rotor turns counter-clockwise", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to specify which collective pitch command results in the least amount of rotor drag.\nThis is used to increase the accuracy of the yaw drag torque compensation based on collective pitch\nby aligning the lowest rotor drag with zero compensation.\nFor symmetric profile blades this is the command that results in exactly 0\u00b0 collective blade angle.\nFor lift profile blades this is typically a command resulting in slightly negative collective blade angle.\ntail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O)", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_CP_O", "shortDesc": "Offset for yaw compensation based on collective pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to add a proportional factor of the collective pitch command to the yaw command.\nA negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction.\ntail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O)", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_CP_S", "shortDesc": "Scale for yaw compensation based on collective pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to add a proportional factor of the throttle command to the yaw command.\nA negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction.\ntail_output += CA_HELI_YAW_TH_S * throttle", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_TH_S", "shortDesc": "Scale for yaw compensation based on throttle", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Ice shedding prevents ice buildup in VTOL aircraft motors by\nperiodically spinning inactive rotors. When enabled (period\n> 0), every cycle lasts for the defined period and includes\na 2\u2011second spin at 0.01 motor output. If period <= 0, the\nfeature is disabled.", "min": 0.0, "name": "CA_ICE_PERIOD", "shortDesc": "Ice shedding cycle period", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Used to linearize mechanical output of swashplate servos to avoid axis coupling and binding with 4 servo redundancy.\nThis requires a symmetric setup where the servo horn is exactly centered with a 0 command.\nSetting to zero disables feature.", "max": 75.0, "min": 0.0, "name": "CA_MAX_SVO_THROW", "shortDesc": "Throw angle of swashplate servo at maximum commands for linearization", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Geometry", "longDesc": "Selects the algorithm and desaturation method.\nIf set to Automatic, the selection is based on the airframe (CA_AIRFRAME).", "name": "CA_METHOD", "shortDesc": "Control allocation method", "type": "Int32", "values": [{"description": "Pseudo-inverse with output clipping", "value": 0}, {"description": "Pseudo-inverse with sequential desaturation technique", "value": 1}, {"description": "Automatic", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R0_SLEW", "shortDesc": "Motor 0 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R10_SLEW", "shortDesc": "Motor 10 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R11_SLEW", "shortDesc": "Motor 11 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R1_SLEW", "shortDesc": "Motor 1 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R2_SLEW", "shortDesc": "Motor 2 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R3_SLEW", "shortDesc": "Motor 3 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R4_SLEW", "shortDesc": "Motor 4 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R5_SLEW", "shortDesc": "Motor 5 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R6_SLEW", "shortDesc": "Motor 6 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R7_SLEW", "shortDesc": "Motor 7 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R8_SLEW", "shortDesc": "Motor 8 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R9_SLEW", "shortDesc": "Motor 9 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AX", "shortDesc": "Axis of rotor 0 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AY", "shortDesc": "Axis of rotor 0 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AZ", "shortDesc": "Axis of rotor 0 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR0_CT", "shortDesc": "Thrust coefficient of rotor 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR0_KM", "shortDesc": "Moment coefficient of rotor 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PX", "shortDesc": "Position of rotor 0 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PY", "shortDesc": "Position of rotor 0 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PZ", "shortDesc": "Position of rotor 0 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR0_TILT", "shortDesc": "Rotor 0 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AX", "shortDesc": "Axis of rotor 10 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AY", "shortDesc": "Axis of rotor 10 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AZ", "shortDesc": "Axis of rotor 10 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR10_CT", "shortDesc": "Thrust coefficient of rotor 10", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR10_KM", "shortDesc": "Moment coefficient of rotor 10", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PX", "shortDesc": "Position of rotor 10 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PY", "shortDesc": "Position of rotor 10 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PZ", "shortDesc": "Position of rotor 10 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR10_TILT", "shortDesc": "Rotor 10 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AX", "shortDesc": "Axis of rotor 11 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AY", "shortDesc": "Axis of rotor 11 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AZ", "shortDesc": "Axis of rotor 11 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR11_CT", "shortDesc": "Thrust coefficient of rotor 11", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR11_KM", "shortDesc": "Moment coefficient of rotor 11", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PX", "shortDesc": "Position of rotor 11 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PY", "shortDesc": "Position of rotor 11 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PZ", "shortDesc": "Position of rotor 11 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR11_TILT", "shortDesc": "Rotor 11 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AX", "shortDesc": "Axis of rotor 1 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AY", "shortDesc": "Axis of rotor 1 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AZ", "shortDesc": "Axis of rotor 1 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR1_CT", "shortDesc": "Thrust coefficient of rotor 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR1_KM", "shortDesc": "Moment coefficient of rotor 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PX", "shortDesc": "Position of rotor 1 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PY", "shortDesc": "Position of rotor 1 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PZ", "shortDesc": "Position of rotor 1 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR1_TILT", "shortDesc": "Rotor 1 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AX", "shortDesc": "Axis of rotor 2 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AY", "shortDesc": "Axis of rotor 2 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AZ", "shortDesc": "Axis of rotor 2 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR2_CT", "shortDesc": "Thrust coefficient of rotor 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR2_KM", "shortDesc": "Moment coefficient of rotor 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PX", "shortDesc": "Position of rotor 2 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PY", "shortDesc": "Position of rotor 2 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PZ", "shortDesc": "Position of rotor 2 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR2_TILT", "shortDesc": "Rotor 2 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AX", "shortDesc": "Axis of rotor 3 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AY", "shortDesc": "Axis of rotor 3 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AZ", "shortDesc": "Axis of rotor 3 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR3_CT", "shortDesc": "Thrust coefficient of rotor 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR3_KM", "shortDesc": "Moment coefficient of rotor 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PX", "shortDesc": "Position of rotor 3 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PY", "shortDesc": "Position of rotor 3 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PZ", "shortDesc": "Position of rotor 3 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR3_TILT", "shortDesc": "Rotor 3 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AX", "shortDesc": "Axis of rotor 4 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AY", "shortDesc": "Axis of rotor 4 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AZ", "shortDesc": "Axis of rotor 4 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR4_CT", "shortDesc": "Thrust coefficient of rotor 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR4_KM", "shortDesc": "Moment coefficient of rotor 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PX", "shortDesc": "Position of rotor 4 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PY", "shortDesc": "Position of rotor 4 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PZ", "shortDesc": "Position of rotor 4 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR4_TILT", "shortDesc": "Rotor 4 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AX", "shortDesc": "Axis of rotor 5 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AY", "shortDesc": "Axis of rotor 5 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AZ", "shortDesc": "Axis of rotor 5 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR5_CT", "shortDesc": "Thrust coefficient of rotor 5", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR5_KM", "shortDesc": "Moment coefficient of rotor 5", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PX", "shortDesc": "Position of rotor 5 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PY", "shortDesc": "Position of rotor 5 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PZ", "shortDesc": "Position of rotor 5 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR5_TILT", "shortDesc": "Rotor 5 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AX", "shortDesc": "Axis of rotor 6 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AY", "shortDesc": "Axis of rotor 6 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AZ", "shortDesc": "Axis of rotor 6 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR6_CT", "shortDesc": "Thrust coefficient of rotor 6", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR6_KM", "shortDesc": "Moment coefficient of rotor 6", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PX", "shortDesc": "Position of rotor 6 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PY", "shortDesc": "Position of rotor 6 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PZ", "shortDesc": "Position of rotor 6 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR6_TILT", "shortDesc": "Rotor 6 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AX", "shortDesc": "Axis of rotor 7 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AY", "shortDesc": "Axis of rotor 7 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AZ", "shortDesc": "Axis of rotor 7 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR7_CT", "shortDesc": "Thrust coefficient of rotor 7", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR7_KM", "shortDesc": "Moment coefficient of rotor 7", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PX", "shortDesc": "Position of rotor 7 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PY", "shortDesc": "Position of rotor 7 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PZ", "shortDesc": "Position of rotor 7 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR7_TILT", "shortDesc": "Rotor 7 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AX", "shortDesc": "Axis of rotor 8 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AY", "shortDesc": "Axis of rotor 8 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AZ", "shortDesc": "Axis of rotor 8 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR8_CT", "shortDesc": "Thrust coefficient of rotor 8", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR8_KM", "shortDesc": "Moment coefficient of rotor 8", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PX", "shortDesc": "Position of rotor 8 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PY", "shortDesc": "Position of rotor 8 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PZ", "shortDesc": "Position of rotor 8 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR8_TILT", "shortDesc": "Rotor 8 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AX", "shortDesc": "Axis of rotor 9 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AY", "shortDesc": "Axis of rotor 9 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AZ", "shortDesc": "Axis of rotor 9 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR9_CT", "shortDesc": "Thrust coefficient of rotor 9", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR9_KM", "shortDesc": "Moment coefficient of rotor 9", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PX", "shortDesc": "Position of rotor 9 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PY", "shortDesc": "Position of rotor 9 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PZ", "shortDesc": "Position of rotor 9 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR9_TILT", "shortDesc": "Rotor 9 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_ROTOR_COUNT", "shortDesc": "Total number of rotors", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}, {"description": "5", "value": 5}, {"description": "6", "value": 6}, {"description": "7", "value": 7}, {"description": "8", "value": 8}, {"description": "9", "value": 9}, {"description": "10", "value": 10}, {"description": "11", "value": 11}, {"description": "12", "value": 12}]}, {"bitmask": [{"description": "Motor 1", "index": 0}, {"description": "Motor 2", "index": 1}, {"description": "Motor 3", "index": 2}, {"description": "Motor 4", "index": 3}, {"description": "Motor 5", "index": 4}, {"description": "Motor 6", "index": 5}, {"description": "Motor 7", "index": 6}, {"description": "Motor 8", "index": 7}, {"description": "Motor 9", "index": 8}, {"description": "Motor 10", "index": 9}, {"description": "Motor 11", "index": 10}, {"description": "Motor 12", "index": 11}], "category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Configure motors to be bidirectional/reversible. Note that the output driver needs to support this as well.", "max": 4095, "min": 0, "name": "CA_R_REV", "shortDesc": "Bidirectional/Reversible motors", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG0", "shortDesc": "Angle for swash plate servo 0", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 140.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG1", "shortDesc": "Angle for swash plate servo 1", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 220.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG2", "shortDesc": "Angle for swash plate servo 2", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG3", "shortDesc": "Angle for swash plate servo 3", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L0", "shortDesc": "Arm length for swash plate servo 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L1", "shortDesc": "Arm length for swash plate servo 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L2", "shortDesc": "Arm length for swash plate servo 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L3", "shortDesc": "Arm length for swash plate servo 3", "type": "Float"}, {"category": "Standard", "default": 3, "group": "Geometry", "name": "CA_SP0_COUNT", "shortDesc": "Number of swash plates servos", "type": "Int32", "values": [{"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV0_SLEW", "shortDesc": "Servo 0 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV1_SLEW", "shortDesc": "Servo 1 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV2_SLEW", "shortDesc": "Servo 2 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV3_SLEW", "shortDesc": "Servo 3 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV4_SLEW", "shortDesc": "Servo 4 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV5_SLEW", "shortDesc": "Servo 5 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV6_SLEW", "shortDesc": "Servo 6 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV7_SLEW", "shortDesc": "Servo 7 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_FLAP", "shortDesc": "Control Surface 0 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_SPOIL", "shortDesc": "Control Surface 0 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_TRIM", "shortDesc": "Control Surface 0 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_P", "shortDesc": "Control Surface 0 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_R", "shortDesc": "Control Surface 0 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_Y", "shortDesc": "Control Surface 0 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS0_TYPE", "shortDesc": "Control Surface 0 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_FLAP", "shortDesc": "Control Surface 1 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_SPOIL", "shortDesc": "Control Surface 1 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_TRIM", "shortDesc": "Control Surface 1 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_P", "shortDesc": "Control Surface 1 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_R", "shortDesc": "Control Surface 1 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_Y", "shortDesc": "Control Surface 1 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS1_TYPE", "shortDesc": "Control Surface 1 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_FLAP", "shortDesc": "Control Surface 2 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_SPOIL", "shortDesc": "Control Surface 2 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_TRIM", "shortDesc": "Control Surface 2 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_P", "shortDesc": "Control Surface 2 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_R", "shortDesc": "Control Surface 2 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_Y", "shortDesc": "Control Surface 2 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS2_TYPE", "shortDesc": "Control Surface 2 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_FLAP", "shortDesc": "Control Surface 3 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_SPOIL", "shortDesc": "Control Surface 3 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_TRIM", "shortDesc": "Control Surface 3 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_P", "shortDesc": "Control Surface 3 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_R", "shortDesc": "Control Surface 3 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_Y", "shortDesc": "Control Surface 3 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS3_TYPE", "shortDesc": "Control Surface 3 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_FLAP", "shortDesc": "Control Surface 4 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_SPOIL", "shortDesc": "Control Surface 4 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_TRIM", "shortDesc": "Control Surface 4 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_P", "shortDesc": "Control Surface 4 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_R", "shortDesc": "Control Surface 4 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_Y", "shortDesc": "Control Surface 4 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS4_TYPE", "shortDesc": "Control Surface 4 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_FLAP", "shortDesc": "Control Surface 5 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_SPOIL", "shortDesc": "Control Surface 5 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_TRIM", "shortDesc": "Control Surface 5 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_P", "shortDesc": "Control Surface 5 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_R", "shortDesc": "Control Surface 5 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_Y", "shortDesc": "Control Surface 5 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS5_TYPE", "shortDesc": "Control Surface 5 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_FLAP", "shortDesc": "Control Surface 6 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_SPOIL", "shortDesc": "Control Surface 6 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_TRIM", "shortDesc": "Control Surface 6 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_P", "shortDesc": "Control Surface 6 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_R", "shortDesc": "Control Surface 6 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_Y", "shortDesc": "Control Surface 6 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS6_TYPE", "shortDesc": "Control Surface 6 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_FLAP", "shortDesc": "Control Surface 7 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_SPOIL", "shortDesc": "Control Surface 7 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_TRIM", "shortDesc": "Control Surface 7 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_P", "shortDesc": "Control Surface 7 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_R", "shortDesc": "Control Surface 7 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_Y", "shortDesc": "Control Surface 7 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS7_TYPE", "shortDesc": "Control Surface 7 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS_COUNT", "shortDesc": "Total number of Control Surfaces", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}, {"description": "5", "value": 5}, {"description": "6", "value": 6}, {"description": "7", "value": 7}, {"description": "8", "value": 8}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Geometry", "max": 5.0, "min": 0.0, "name": "CA_SV_FLAP_SLEW", "shortDesc": "Control Surface slew rate for normalized flaps setpoint", "type": "Float"}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL0_CT", "shortDesc": "Tilt 0 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL0_MAXA", "shortDesc": "Tilt Servo 0 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL0_MINA", "shortDesc": "Tilt Servo 0 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle.\nFor example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front',\nthe motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL0_TD", "shortDesc": "Tilt Servo 0 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL1_CT", "shortDesc": "Tilt 1 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL1_MAXA", "shortDesc": "Tilt Servo 1 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL1_MINA", "shortDesc": "Tilt Servo 1 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle.\nFor example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front',\nthe motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL1_TD", "shortDesc": "Tilt Servo 1 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL2_CT", "shortDesc": "Tilt 2 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL2_MAXA", "shortDesc": "Tilt Servo 2 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL2_MINA", "shortDesc": "Tilt Servo 2 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle.\nFor example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front',\nthe motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL2_TD", "shortDesc": "Tilt Servo 2 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL3_CT", "shortDesc": "Tilt 3 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL3_MAXA", "shortDesc": "Tilt Servo 3 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL3_MINA", "shortDesc": "Tilt Servo 3 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle.\nFor example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front',\nthe motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL3_TD", "shortDesc": "Tilt Servo 3 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_TL_COUNT", "shortDesc": "Total number of Tilt Servos", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Hover Thrust Estimator", "longDesc": "Sets the number of standard deviations used\nby the innovation consistency test.", "max": 10.0, "min": 1.0, "name": "HTE_ACC_GATE", "shortDesc": "Gate size for acceleration fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Hover Thrust Estimator", "longDesc": "Sets the number of standard deviations used\nby the innovation consistency test.", "max": 1.0, "min": 0.0, "name": "HTE_HT_ERR_INIT", "shortDesc": "1-sigma initial hover thrust uncertainty", "type": "Float", "units": "normalized_thrust"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0036, "group": "Hover Thrust Estimator", "longDesc": "Reduce to make the hover thrust estimate\nmore stable, increase if the real hover thrust\nis expected to change quickly over time.", "max": 1.0, "min": 0.0001, "name": "HTE_HT_NOISE", "shortDesc": "Hover thrust process noise", "type": "Float", "units": "normalized_thrust/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Hover Thrust Estimator", "longDesc": "Defines the range of the hover thrust estimate around MPC_THR_HOVER.\nA value of 0.2 with MPC_THR_HOVER at 0.5 results in a range of [0.3, 0.7].\nSet to a large value if the vehicle operates in varying physical conditions that\naffect the required hover thrust strongly (e.g. differently sized payloads).", "max": 0.4, "min": 0.01, "name": "HTE_THR_RANGE", "shortDesc": "Max deviation from MPC_THR_HOVER", "type": "Float", "units": "normalized_thrust"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Hover Thrust Estimator", "longDesc": "Above this speed, the measurement noise is linearly increased\nto reduce the sensitivity of the estimator from biased measurement.\nSet to a low value on vehicles with large lifting surfaces.", "max": 20.0, "min": 1.0, "name": "HTE_VXY_THR", "shortDesc": "Horizontal velocity threshold for sensitivity reduction", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Hover Thrust Estimator", "longDesc": "Above this speed, the measurement noise is linearly increased\nto reduce the sensitivity of the estimator from biased measurement.\nSet to a low value on vehicles affected by air drag when climbing or descending.", "max": 10.0, "min": 1.0, "name": "HTE_VZ_THR", "shortDesc": "Vertical velocity threshold for sensitivity reduction", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.0, "group": "Land Detector", "longDesc": "Maximum airspeed allowed in the landed state", "max": 30.0, "min": 2.0, "name": "LNDFW_AIRSPD_MAX", "shortDesc": "Fixed-wing land detector: Max airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Land Detector", "longDesc": "Maximum allowed norm of the angular velocity in the landed state.\nOnly used if neither airspeed nor groundspeed can be used for landing detection.", "name": "LNDFW_ROT_MAX", "shortDesc": "Fixed-wing land detector: max rotational speed", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Land Detector", "longDesc": "Time the land conditions (speeds and acceleration) have to be satisfied to detect a landing.", "min": 0.1, "name": "LNDFW_TRIG_TIME", "rebootRequired": true, "shortDesc": "Fixed-wing land detection trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Land Detector", "longDesc": "Maximum horizontal velocity allowed in the landed state.\nA factor of 0.7 is applied in case of airspeed-less flying\n(either because no sensor is present or sensor data got invalid in flight).", "max": 20.0, "min": 0.5, "name": "LNDFW_VEL_XY_MAX", "shortDesc": "Fixed-wing land detector: Max horizontal velocity threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Land Detector", "longDesc": "Maximum vertical velocity allowed in the landed state.", "max": 20.0, "min": 0.1, "name": "LNDFW_VEL_Z_MAX", "shortDesc": "Fixed-wing land detector: Max vertiacal velocity threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 8.0, "group": "Land Detector", "longDesc": "Maximum horizontal (x,y body axes) acceleration allowed in the landed state", "max": 30.0, "min": 2.0, "name": "LNDFW_XYACC_MAX", "shortDesc": "Fixed-wing land detector: Max horizontal acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Land Detector", "longDesc": "The height above ground below which ground effect creates barometric altitude errors.\nA negative value indicates no ground effect.", "min": -1.0, "name": "LNDMC_ALT_GND", "shortDesc": "Ground effect altitude for multicopters", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Land Detector", "longDesc": "Maximum allowed norm of the angular velocity (roll, pitch) in the landed state.", "name": "LNDMC_ROT_MAX", "shortDesc": "Multicopter max rotational speed", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Land Detector", "longDesc": "Total time it takes to go through all three land detection stages:\nground contact, maybe landed, landed\nwhen all necessary conditions are constantly met.", "max": 10.0, "min": 0.1, "name": "LNDMC_TRIG_TIME", "shortDesc": "Multicopter land detection trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Land Detector", "longDesc": "Maximum horizontal velocity allowed in the landed state", "name": "LNDMC_XY_VEL_MAX", "shortDesc": "Multicopter max horizontal velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "Land Detector", "longDesc": "Vertical velocity threshold to detect landing.\nHas to be set lower than the expected minimal speed for landing,\nwhich is either MPC_LAND_SPEED or MPC_LAND_CRWL.\nThis is enforced by an automatic check.", "min": 0.0, "name": "LNDMC_Z_VEL_MAX", "shortDesc": "Multicopter vertical velocity threshold", "type": "Float", "units": "m/s"}, {"category": "System", "default": 0, "group": "Land Detector", "longDesc": "Total flight time of this autopilot. Higher 32 bits of the value.\nFlight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO.", "min": 0, "name": "LND_FLIGHT_T_HI", "shortDesc": "Total flight time in microseconds", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Land Detector", "longDesc": "Total flight time of this autopilot. Lower 32 bits of the value.\nFlight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO.", "min": 0, "name": "LND_FLIGHT_T_LO", "shortDesc": "Total flight time in microseconds", "type": "Int32", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Landing Target Estimator", "longDesc": "Variance of acceleration measurement used for landing target position prediction.\nHigher values results in tighter following of the measurements and more lenient outlier rejection", "min": 0.01, "name": "LTEST_ACC_UNC", "shortDesc": "Acceleration uncertainty", "type": "Float", "units": "(m/s^2)^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.005, "group": "Landing Target Estimator", "longDesc": "Variance of the landing target measurement from the driver.\nHigher values result in less aggressive following of the measurement and a smoother output as well as fewer rejected measurements.", "name": "LTEST_MEAS_UNC", "shortDesc": "Landing target measurement uncertainty", "type": "Float", "units": "tan(rad)^2"}, {"category": "Standard", "default": 0, "group": "Landing Target Estimator", "longDesc": "Configure the mode of the landing target. Depending on the mode, the landing target observations are used differently to aid position estimation.\nMode Moving: The landing target may be moving around while in the field of view of the vehicle. Landing target measurements are not used to aid positioning.\nMode Stationary: The landing target is stationary. Measured velocity w.r.t. the landing target is used to aid velocity estimation.", "max": 1, "min": 0, "name": "LTEST_MODE", "shortDesc": "Landing target mode", "type": "Int32", "values": [{"description": "Moving", "value": 0}, {"description": "Stationary", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Landing Target Estimator", "longDesc": "Initial variance of the relative landing target position in x and y direction", "min": 0.001, "name": "LTEST_POS_UNC_IN", "shortDesc": "Initial landing target position uncertainty", "type": "Float", "units": "m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Landing Target Estimator", "longDesc": "Landing target x measurements are scaled by this factor before being used", "min": 0.01, "name": "LTEST_SCALE_X", "shortDesc": "Scale factor for sensor measurements in sensor x axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Landing Target Estimator", "longDesc": "Landing target y measurements are scaled by this factor before being used", "min": 0.01, "name": "LTEST_SCALE_Y", "shortDesc": "Scale factor for sensor measurements in sensor y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_X", "rebootRequired": true, "shortDesc": "X Position of IRLOCK in body frame (forward)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_Y", "rebootRequired": true, "shortDesc": "Y Position of IRLOCK in body frame (right)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_Z", "rebootRequired": true, "shortDesc": "Z Position of IRLOCK in body frame (downward)", "type": "Float", "units": "m"}, {"category": "Standard", "default": 2, "group": "Landing Target Estimator", "longDesc": "Default orientation of Yaw 90\u00b0", "max": 40, "min": -1, "name": "LTEST_SENS_ROT", "rebootRequired": true, "shortDesc": "Rotation of IRLOCK sensor relative to airframe", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Landing Target Estimator", "longDesc": "Initial variance of the relative landing target velocity in x and y directions", "min": 0.001, "name": "LTEST_VEL_UNC_IN", "shortDesc": "Initial landing target velocity uncertainty", "type": "Float", "units": "(m/s)^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.012, "group": "Local Position Estimator", "longDesc": "Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)\nLarger than data sheet to account for tilt error.", "max": 2.0, "min": 1e-05, "name": "LPE_ACC_XY", "shortDesc": "Accelerometer xy noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.02, "group": "Local Position Estimator", "longDesc": "Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)", "max": 2.0, "min": 1e-05, "name": "LPE_ACC_Z", "shortDesc": "Accelerometer z noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Local Position Estimator", "max": 100.0, "min": 0.01, "name": "LPE_BAR_Z", "shortDesc": "Barometric presssure altitude z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Local Position Estimator", "name": "LPE_EN", "shortDesc": "Local position estimator enable (unsupported)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Local Position Estimator", "max": 5.0, "min": 1.0, "name": "LPE_EPH_MAX", "shortDesc": "Max EPH allowed for GPS initialization", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 5.0, "group": "Local Position Estimator", "max": 5.0, "min": 1.0, "name": "LPE_EPV_MAX", "shortDesc": "Max EPV allowed for GPS initialization", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Local Position Estimator", "longDesc": "By initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable", "max": 1, "min": 0, "name": "LPE_FAKE_ORIGIN", "shortDesc": "Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow)", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Local Position Estimator", "max": 2.0, "min": 0.0, "name": "LPE_FGYRO_HP", "shortDesc": "Flow gyro high pass filter cut off frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_FLW_OFF_Z", "shortDesc": "Optical flow z offset from center", "type": "Float", "units": "m"}, {"category": "Standard", "default": 150, "group": "Local Position Estimator", "max": 255, "min": 0, "name": "LPE_FLW_QMIN", "shortDesc": "Optical flow minimum quality threshold", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 7.0, "group": "Local Position Estimator", "max": 10.0, "min": 0.1, "name": "LPE_FLW_R", "shortDesc": "Optical flow rotation (roll/pitch) noise gain", "type": "Float", "units": "m/s/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 7.0, "group": "Local Position Estimator", "max": 10.0, "min": 0.0, "name": "LPE_FLW_RR", "shortDesc": "Optical flow angular velocity noise gain", "type": "Float", "units": "m/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.3, "group": "Local Position Estimator", "max": 10.0, "min": 0.1, "name": "LPE_FLW_SCALE", "shortDesc": "Optical flow scale", "type": "Float", "units": "m"}, {"bitmask": [{"description": "fuse GPS, requires GPS for alt. init", "index": 0}, {"description": "fuse optical flow", "index": 1}, {"description": "fuse vision position", "index": 2}, {"description": "fuse landing target", "index": 3}, {"description": "fuse land detector", "index": 4}, {"description": "pub agl as lpos down", "index": 5}, {"description": "flow gyro compensation", "index": 6}, {"description": "fuse baro", "index": 7}], "category": "Standard", "default": 145, "group": "Local Position Estimator", "longDesc": "Set bits in the following positions to enable:\n0 : Set to true to fuse GPS data if available, also requires GPS for altitude init\n1 : Set to true to fuse optical flow data if available\n2 : Set to true to fuse vision position\n3 : Set to true to enable landing target\n4 : Set to true to fuse land detector\n5 : Set to true to publish AGL as local position down component\n6 : Set to true to enable flow gyro compensation\n7 : Set to true to enable baro fusion\ndefault (145 - GPS, baro, land detector)", "max": 255, "min": 0, "name": "LPE_FUSION", "shortDesc": "Integer bitmask controlling data fusion", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.29, "group": "Local Position Estimator", "max": 0.4, "min": 0.0, "name": "LPE_GPS_DELAY", "shortDesc": "GPS delay compensaton", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Local Position Estimator", "longDesc": "EPV used if greater than this value.", "max": 2.0, "min": 0.01, "name": "LPE_GPS_VXY", "shortDesc": "GPS xy velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Local Position Estimator", "max": 2.0, "min": 0.01, "name": "LPE_GPS_VZ", "shortDesc": "GPS z velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Local Position Estimator", "max": 5.0, "min": 0.01, "name": "LPE_GPS_XY", "shortDesc": "Minimum GPS xy standard deviation, uses reported EPH if greater", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Local Position Estimator", "max": 200.0, "min": 0.01, "name": "LPE_GPS_Z", "shortDesc": "Minimum GPS z standard deviation, uses reported EPV if greater", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Local Position Estimator", "max": 10.0, "min": 0.01, "name": "LPE_LAND_VXY", "shortDesc": "Land detector xy velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Local Position Estimator", "max": 10.0, "min": 0.001, "name": "LPE_LAND_Z", "shortDesc": "Land detector z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 8, "default": 47.397742, "group": "Local Position Estimator", "max": 90.0, "min": -90.0, "name": "LPE_LAT", "shortDesc": "Local origin latitude for nav w/o GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_LDR_OFF_Z", "shortDesc": "Lidar z offset from center of vehicle +down", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_LDR_Z", "shortDesc": "Lidar z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 8, "default": 8.545594, "group": "Local Position Estimator", "max": 180.0, "min": -180.0, "name": "LPE_LON", "shortDesc": "Local origin longitude for nav w/o GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0001, "group": "Local Position Estimator", "max": 10.0, "min": 0.0, "name": "LPE_LT_COV", "shortDesc": "Minimum landing target standard covariance, uses reported covariance if greater", "type": "Float", "units": "m^2"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0, "name": "LPE_PN_B", "shortDesc": "Accel bias propagation noise density", "type": "Float", "units": "m/s^3/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Increase to trust measurements more.\nDecrease to trust model more.", "max": 1.0, "min": 0.0, "name": "LPE_PN_P", "shortDesc": "Position propagation noise density", "type": "Float", "units": "m/s/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0, "name": "LPE_PN_T", "shortDesc": "Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001)", "type": "Float", "units": "m/s/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Increase to trust measurements more.\nDecrease to trust model more.", "max": 1.0, "min": 0.0, "name": "LPE_PN_V", "shortDesc": "Velocity propagation noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_SNR_OFF_Z", "shortDesc": "Sonar z offset from center of vehicle +down", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_SNR_Z", "shortDesc": "Sonar z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Local Position Estimator", "longDesc": "Used to calculate increased terrain random walk nosie due to movement.", "max": 100.0, "min": 0.0, "name": "LPE_T_MAX_GRADE", "shortDesc": "Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg)", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0001, "name": "LPE_VIC_P", "shortDesc": "Vicon position standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Set to zero to enable automatic compensation from measurement timestamps", "max": 0.1, "min": 0.0, "name": "LPE_VIS_DELAY", "shortDesc": "Vision delay compensation", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_VIS_XY", "shortDesc": "Vision xy standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "Local Position Estimator", "max": 100.0, "min": 0.01, "name": "LPE_VIS_Z", "shortDesc": "Vision z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.3, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_VXY_PUB", "shortDesc": "Required velocity xy standard deviation to publish position", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 5.0, "group": "Local Position Estimator", "max": 1000.0, "min": 5.0, "name": "LPE_X_LP", "shortDesc": "Cut frequency for state publication", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Local Position Estimator", "max": 5.0, "min": 0.3, "name": "LPE_Z_PUB", "shortDesc": "Required z standard deviation to publish altitude/ terrain", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone\non the local network.", "name": "MAV_0_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 0", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink\ninstance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_0_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 0", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the\nmessage is either broadcast or the target is not the autopilot.\nThis allows for example a GCS to talk to a camera that is connected to the\nautopilot via MAVLink (on a different link than the GCS).", "name": "MAV_0_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 0", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the\nHIGH_LATENCY2 stream for instance 0, configured in iridium mode.\nThis parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_0_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 0", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the\nvehicle's attitude) and their sending rates.", "name": "MAV_0_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 0", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to\n`txbuf` field reported by radio_status.\nRequires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_0_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 0", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1200, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec.\nIf the configured streams exceed the maximum rate, the sending rate of\neach stream is automatically decreased.\nIf this is set to 0 a value of half of the theoretical maximum bandwidth is used.\nThis corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on\n8N1-configured links).", "min": 0, "name": "MAV_0_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 0", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 14550, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 0,\nselected remote port will be set and used in MAVLink instance 0.", "name": "MAV_0_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 0", "type": "Int32"}, {"category": "Standard", "default": 14556, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 0,\nselected udp port will be set and used in MAVLink instance 0.", "name": "MAV_0_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 0", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone\non the local network.", "name": "MAV_1_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 1", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink\ninstance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_1_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 1", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the\nmessage is either broadcast or the target is not the autopilot.\nThis allows for example a GCS to talk to a camera that is connected to the\nautopilot via MAVLink (on a different link than the GCS).", "name": "MAV_1_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 1", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the\nHIGH_LATENCY2 stream for instance 1, configured in iridium mode.\nThis parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_1_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 1", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the\nvehicle's attitude) and their sending rates.", "name": "MAV_1_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 1", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to\n`txbuf` field reported by radio_status.\nRequires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_1_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 1", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec.\nIf the configured streams exceed the maximum rate, the sending rate of\neach stream is automatically decreased.\nIf this is set to 0 a value of half of the theoretical maximum bandwidth is used.\nThis corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on\n8N1-configured links).", "min": 0, "name": "MAV_1_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 1", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 1,\nselected remote port will be set and used in MAVLink instance 1.", "name": "MAV_1_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 1", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 1,\nselected udp port will be set and used in MAVLink instance 1.", "name": "MAV_1_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 1", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone\non the local network.", "name": "MAV_2_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 2", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink\ninstance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_2_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 2", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the\nmessage is either broadcast or the target is not the autopilot.\nThis allows for example a GCS to talk to a camera that is connected to the\nautopilot via MAVLink (on a different link than the GCS).", "name": "MAV_2_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the\nHIGH_LATENCY2 stream for instance 2, configured in iridium mode.\nThis parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_2_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 2", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the\nvehicle's attitude) and their sending rates.", "name": "MAV_2_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 2", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to\n`txbuf` field reported by radio_status.\nRequires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_2_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec.\nIf the configured streams exceed the maximum rate, the sending rate of\neach stream is automatically decreased.\nIf this is set to 0 a value of half of the theoretical maximum bandwidth is used.\nThis corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on\n8N1-configured links).", "min": 0, "name": "MAV_2_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 2", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 2,\nselected remote port will be set and used in MAVLink instance 2.", "name": "MAV_2_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 2", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 2,\nselected udp port will be set and used in MAVLink instance 2.", "name": "MAV_2_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 2", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "max": 250, "min": 1, "name": "MAV_COMP_ID", "rebootRequired": true, "shortDesc": "MAVLink component ID", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If set to 1 incoming external setpoint messages will be directly forwarded\nto the controllers if in offboard control mode", "name": "MAV_FWDEXTSP", "shortDesc": "Forward external setpoint messages", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "Disabling the parameter hash check functionality will make the mavlink instance\nstream parameters continuously.", "name": "MAV_HASH_CHK_EN", "shortDesc": "Parameter hash check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "The mavlink heartbeat message will not be forwarded if this parameter is set to 'disabled'.\nThe main reason for disabling heartbeats to be forwarded is because they confuse dronekit.", "name": "MAV_HB_FORW_EN", "shortDesc": "Heartbeat message forwarding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "name": "MAV_PROTO_VER", "shortDesc": "MAVLink protocol version", "type": "Int32", "values": [{"description": "Version 1 with auto-upgrade to v2 if detected", "value": 1}, {"description": "Version 2", "value": 2}]}, {"category": "Standard", "default": 5, "group": "MAVLink", "longDesc": "If the connected radio stops reporting RADIO_STATUS for a certain time,\na warning is triggered and, if MAV_X_RADIO_CTL is enabled, the software-flow\ncontrol is reset.", "max": 250, "min": 1, "name": "MAV_RADIO_TOUT", "shortDesc": "Timeout in seconds for the RADIO_STATUS reports coming in", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "When non-zero the MAVLink app will attempt to configure the\nSiK radio to this ID and re-set the parameter to 0. If the value\nis negative it will reset the complete radio config to\nfactory defaults. Only applies if this mavlink instance is going through a SiK radio", "max": 240, "min": -1, "name": "MAV_SIK_RADIO_ID", "shortDesc": "MAVLink SiK Radio ID", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "max": 250, "min": 1, "name": "MAV_SYS_ID", "rebootRequired": true, "shortDesc": "MAVLink system ID", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "TELEM2 on Skynode only.", "name": "MAV_S_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink forwarding on TELEM2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 11, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the\nvehicle's attitude) and their sending rates.", "name": "MAV_S_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for SOM to FMU communication channel", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Onboard", "value": 2}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "max": 22, "min": 0, "name": "MAV_TYPE", "shortDesc": "MAVLink airframe type", "type": "Int32", "values": [{"description": "Generic micro air vehicle", "value": 0}, {"description": "Fixed wing aircraft", "value": 1}, {"description": "Quadrotor", "value": 2}, {"description": "Coaxial helicopter", "value": 3}, {"description": "Normal helicopter with tail rotor", "value": 4}, {"description": "Airship, controlled", "value": 7}, {"description": "Free balloon, uncontrolled", "value": 8}, {"description": "Ground rover", "value": 10}, {"description": "Surface vessel, boat, ship", "value": 11}, {"description": "Submarine", "value": 12}, {"description": "Hexarotor", "value": 13}, {"description": "Octorotor", "value": 14}, {"description": "Tricopter", "value": 15}, {"description": "VTOL Two-rotor Tailsitter", "value": 19}, {"description": "VTOL Quad-rotor Tailsitter", "value": 20}, {"description": "VTOL Tiltrotor", "value": 21}, {"description": "VTOL Standard (separate fixed rotors for hover and cruise flight)", "value": 22}, {"description": "VTOL Tailsitter", "value": 23}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If set to 1 incoming HIL GPS messages are parsed.", "name": "MAV_USEHILGPS", "shortDesc": "Use/Accept HIL GPS message even if not in HIL mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Magnetometer Bias Estimator", "longDesc": "This enables continuous calibration of the magnetometers\nbefore takeoff using gyro data.", "name": "MBE_ENABLE", "rebootRequired": true, "shortDesc": "Enable online mag bias calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 18.0, "group": "Magnetometer Bias Estimator", "increment": 0.1, "longDesc": "Increase to make the estimator more responsive\nDecrease to make the estimator more robust to noise", "max": 100.0, "min": 0.1, "name": "MBE_LEARN_GAIN", "shortDesc": "Mag bias estimator learning gain", "type": "Float"}, {"category": "Standard", "default": 1, "group": "Manual Control", "longDesc": "This determines if moving the left stick to the lower right\narms and to the lower left disarms the vehicle.", "name": "MAN_ARM_GESTURE", "shortDesc": "Enable arm/disarm stick gesture", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Manual Control", "increment": 0.01, "longDesc": "Range around stick center ignored to prevent\nvehicle drift from stick hardware inaccuracy.\nDoes not apply to any precise constant input like\nthrottle and attitude or rate piloting.", "max": 1.0, "min": 0.0, "name": "MAN_DEADZONE", "shortDesc": "Deadzone for sticks (only specific use cases)", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Manual Control", "longDesc": "The timeout for holding the left stick to the lower left\nand the right stick to the lower right at the same time until the gesture\nkills the actuators one-way.\nA negative value disables the feature.", "max": 15.0, "min": -1.0, "name": "MAN_KILL_GEST_T", "shortDesc": "Trigger time for kill stick gesture", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mission", "longDesc": "Ensure:\ngripper: NAV_CMD_DO_GRIPPER\nhas released before continuing mission.\nwinch: CMD_DO_WINCH\nhas delivered before continuing mission.\ngimbal: CMD_DO_GIMBAL_MANAGER_PITCHYAW\nhas reached the commanded orientation before beginning to take pictures.", "min": 0.0, "name": "MIS_COMMAND_TOUT", "shortDesc": "Timeout to allow the payload to execute the mission command", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10000.0, "group": "Mission", "increment": 100.0, "longDesc": "There will be a warning message if the current waypoint is more distant than MIS_DIST_1WP from Home.\nHas no effect on mission validity.\nSet a value of zero or less to disable.", "max": 100000.0, "min": -1.0, "name": "MIS_DIST_1WP", "shortDesc": "Maximal horizontal distance from Home to first waypoint", "type": "Float", "units": "m"}, {"category": "Standard", "default": 30, "group": "Mission", "longDesc": "Minimum altitude above landing point that the vehicle will climb to after an aborted landing.\nThen vehicle will loiter in this altitude until further command is received.\nOnly applies to fixed-wing vehicles.", "min": 0, "name": "MIS_LND_ABRT_ALT", "shortDesc": "Landing abort min altitude", "type": "Int32", "units": "m"}, {"category": "Standard", "default": 0, "group": "Mission", "longDesc": "If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading towards the flight direction.\nIf disabled, the vehicle will yaw towards the ROI.", "max": 1, "min": 0, "name": "MIS_MNT_YAW_CTL", "shortDesc": "Enable yaw control of the mount. (Only affects multicopters and ROI mission items)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Enable", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "Mission", "increment": 0.5, "longDesc": "This is the relative altitude the system will take off to\nif not otherwise specified.", "min": 0.0, "name": "MIS_TAKEOFF_ALT", "shortDesc": "Default take-off altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Mission", "longDesc": "Specifies if a mission has to contain a takeoff and/or mission landing.\nValidity of configured takeoffs/landings is checked independently of the setting here.", "name": "MIS_TKO_LAND_REQ", "shortDesc": "Mission takeoff/landing required", "type": "Int32", "values": [{"description": "No requirements", "value": 0}, {"description": "Require a takeoff", "value": 1}, {"description": "Require a landing", "value": 2}, {"description": "Require a takeoff and a landing", "value": 3}, {"description": "Require both a takeoff and a landing, or neither", "value": 4}, {"description": "Same as previous when landed, in-air require landing only if no valid VTOL approach is present", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": 12.0, "group": "Mission", "increment": 1.0, "max": 90.0, "min": 0.0, "name": "MIS_YAW_ERR", "shortDesc": "Max yaw error in degrees needed for waypoint heading acceptance", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 1.0, "longDesc": "If set > 0 it will ignore the target heading for normal waypoint acceptance. If the\nwaypoint forces the heading the timeout will matter. For example on VTOL forwards transition.\nMainly useful for VTOLs that have less yaw authority and might not reach target\nyaw in wind. Disabled by default.", "max": 20.0, "min": -1.0, "name": "MIS_YAW_TMT", "shortDesc": "Time in seconds we wait on reaching target heading at a waypoint if it is forced", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Mission", "max": 4, "min": 0, "name": "MPC_YAW_MODE", "shortDesc": "Heading behavior in autonomous modes", "type": "Int32", "values": [{"description": "towards waypoint", "value": 0}, {"description": "towards home", "value": 1}, {"description": "away from home", "value": 2}, {"description": "along trajectory", "value": 3}, {"description": "towards waypoint (yaw first)", "value": 4}, {"description": "yaw fixed", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Mission", "increment": 0.5, "longDesc": "Default acceptance radius, overridden by acceptance radius of waypoint if set.\nFor fixed wing the npfg switch distance is used for horizontal acceptance.", "max": 200.0, "min": 0.05, "name": "NAV_ACC_RAD", "shortDesc": "Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Mission", "name": "NAV_FORCE_VT", "shortDesc": "Force VTOL mode takeoff and land", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Mission", "longDesc": "Altitude acceptance used for the last waypoint before a fixed-wing landing. This is usually smaller\nthan the standard vertical acceptance because close to the ground higher accuracy is required.", "max": 200.0, "min": 0.05, "name": "NAV_FW_ALTL_RAD", "shortDesc": "FW Altitude Acceptance Radius before a landing", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Mission", "increment": 0.5, "longDesc": "Acceptance radius for fixedwing altitude.", "max": 200.0, "min": 0.05, "name": "NAV_FW_ALT_RAD", "shortDesc": "FW Altitude Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 80.0, "group": "Mission", "increment": 0.5, "longDesc": "Default value of loiter radius in fixed-wing mode (e.g. for Loiter mode).\nThe direction of the loiter can be set via the sign: A positive value for\nclockwise, negative for counter-clockwise.", "max": 10000.0, "min": -10000.0, "name": "NAV_LOITER_RAD", "shortDesc": "Loiter radius (FW only)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.8, "group": "Mission", "increment": 0.5, "longDesc": "Acceptance radius for multicopter altitude.", "max": 200.0, "min": 0.05, "name": "NAV_MC_ALT_RAD", "shortDesc": "MC Altitude Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 1.0, "longDesc": "Minimum height above ground the vehicle is allowed to descend to during Mission and RTL,\nexcluding landing commands.\nRequires a distance sensor to be set up.\nNote: only prevents the vehicle from descending further, but does not force it to climb.\nSet to a negative value to disable.", "min": -1.0, "name": "NAV_MIN_GND_DIST", "shortDesc": "Minimum height above ground during Mission and RTL", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 0.5, "longDesc": "This is the minimum altitude above Home the system will always obey in Loiter (Hold) mode if switched into this\nmode without specifying an altitude (e.g. through Loiter switch on RC).\nDoesn't affect Loiters that are part of Missions or that are entered through a reposition setpoint (\"Go to\").\nSet to a negative value to disable.", "min": -1.0, "name": "NAV_MIN_LTR_ALT", "shortDesc": "Minimum Loiter altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Mission", "longDesc": "Enabling this will allow the system to respond\nto transponder data from e.g. ADSB transponders", "name": "NAV_TRAFF_AVOID", "shortDesc": "Set traffic avoidance mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warn only", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Position Hold mode", "value": 4}]}, {"category": "Standard", "default": 500.0, "group": "Mission", "longDesc": "Defines a crosstrack horizontal distance", "min": 500.0, "name": "NAV_TRAFF_A_HOR", "shortDesc": "Set NAV TRAFFIC AVOID horizontal distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 500.0, "group": "Mission", "max": 500.0, "min": 10.0, "name": "NAV_TRAFF_A_VER", "shortDesc": "Set NAV TRAFFIC AVOID vertical distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 60, "group": "Mission", "longDesc": "Minimum acceptable time until collsion.\nAssumes constant speed over 3d distance.", "max": 900000000, "min": 1, "name": "NAV_TRAFF_COLL_T", "shortDesc": "Estimated time until collision", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Mixer Output", "longDesc": "The air-mode enables the mixer to increase the total thrust of the multirotor\nin order to keep attitude and rate control even at low and high throttle.\nThis function should be disabled during tuning as it will help the controller\nto diverge if the closed-loop is unstable (i.e. the vehicle is not tuned yet).\nEnabling air-mode for yaw requires the use of an arming switch.", "name": "MC_AIRMODE", "shortDesc": "Multicopter air-mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Roll/Pitch", "value": 1}, {"description": "Roll/Pitch/Yaw", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Mount", "longDesc": "Set to true for servo gimbal, false for passthrough.\nThis is required for a gimbal which is not capable of stabilizing itself\nand relies on the IMU's attitude estimation.", "name": "MNT_DO_STAB", "shortDesc": "Stabilize the mount", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Stabilize all axis", "value": 1}, {"description": "Stabilize yaw for absolute/lock mode.", "value": 2}, {"description": "Stabilize pitch for absolute/lock mode.", "value": 3}]}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "max": 90.0, "min": -90.0, "name": "MNT_LND_P_MAX", "shortDesc": "Pitch maximum when landed", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -90.0, "group": "Mount", "max": 90.0, "min": -90.0, "name": "MNT_LND_P_MIN", "shortDesc": "Pitch minimum when landed", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_PITCH", "shortDesc": "Auxiliary channel to control pitch (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_ROLL", "shortDesc": "Auxiliary channel to control roll (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_YAW", "shortDesc": "Auxiliary channel to control yaw (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 154, "group": "Mount", "longDesc": "If MNT_MODE_OUT is MAVLink protocol v2, mount configure/control commands will be sent with this component ID.", "name": "MNT_MAV_COMPID", "shortDesc": "Mavlink Component ID of the mount", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Mount", "longDesc": "If MNT_MODE_OUT is MAVLink gimbal protocol v1, mount configure/control commands will be sent with this target ID.", "name": "MNT_MAV_SYSID", "shortDesc": "Mavlink System ID of the mount", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 45.0, "group": "Mount", "longDesc": "Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX).", "name": "MNT_MAX_PITCH", "shortDesc": "Max positive angle of pitch setpoint (only in MNT_MODE_OUT=AUX)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -45.0, "group": "Mount", "longDesc": "Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX).", "name": "MNT_MIN_PITCH", "shortDesc": "Min negative angle of pitch setpoint (only in MNT_MODE_OUT=AUX)", "type": "Float", "units": "deg"}, {"category": "Standard", "default": -1, "group": "Mount", "longDesc": "This is the protocol used between the ground station and the autopilot.\nRecommended is Auto, RC only or MAVLink gimbal protocol v2.\nThe rest will be deprecated.", "max": 4, "min": -1, "name": "MNT_MODE_IN", "rebootRequired": true, "shortDesc": "Mount input mode", "type": "Int32", "values": [{"description": "DISABLED", "value": -1}, {"description": "Auto (RC and MAVLink gimbal protocol v2)", "value": 0}, {"description": "RC", "value": 1}, {"description": "MAVLINK_ROI (protocol v1, to be deprecated)", "value": 2}, {"description": "MAVLINK_DO_MOUNT (protocol v1, to be deprecated)", "value": 3}, {"description": "MAVlink gimbal protocol v2", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Mount", "longDesc": "This is the protocol used between the autopilot and a connected gimbal.\nRecommended is the MAVLink gimbal protocol v2 if the gimbal supports it.", "max": 2, "min": 0, "name": "MNT_MODE_OUT", "rebootRequired": true, "shortDesc": "Mount output mode", "type": "Int32", "values": [{"description": "AUX", "value": 0}, {"description": "MAVLink gimbal protocol v1", "value": 1}, {"description": "MAVLink gimbal protocol v2", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "longDesc": "Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX). Note that only symmetric angular ranges are supported.", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_ROLL", "shortDesc": "Range of roll channel output (only in MNT_MODE_OUT=AUX)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 360.0, "group": "Mount", "longDesc": "Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX). Note that only symmetric angular ranges are supported.", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_YAW", "shortDesc": "Range of yaw channel output (only in MNT_MODE_OUT=AUX)", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 30.0, "group": "Mount", "longDesc": "Full stick input [-1..1] translats to [-pitch rate..pitch rate].", "max": 90.0, "min": 1.0, "name": "MNT_RATE_PITCH", "shortDesc": "Angular pitch rate for manual input in degrees/second", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 30.0, "group": "Mount", "longDesc": "Full stick input [-1..1] translats to [-yaw rate..yaw rate].", "max": 90.0, "min": 1.0, "name": "MNT_RATE_YAW", "shortDesc": "Angular yaw rate for manual input in degrees/second", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 1, "group": "Mount", "max": 1, "min": 0, "name": "MNT_RC_IN_MODE", "shortDesc": "Input mode for RC gimbal input", "type": "Int32", "values": [{"description": "Angle", "value": 0}, {"description": "Angular rate", "value": 1}]}, {"category": "Standard", "default": 0.3, "group": "Mount", "longDesc": "Use when no angular position feedback is available.\nWith MNT_MODE_OUT set to AUX, the mount operates in open-loop and directly commands the servo output.\nParameters must be tuned for the specific servo to approximate its speed and response.", "min": 0.0, "name": "MNT_TAU", "shortDesc": "Alpha filter time constant defining the convergence rate (in seconds) for open-loop AUX mount control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "Exponential factor for tuning the input curve shape.\n0 Purely linear input curve\n1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MC_ACRO_EXPO", "shortDesc": "Acro mode roll, pitch expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "Exponential factor for tuning the input curve shape.\n0 Purely linear input curve\n1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MC_ACRO_EXPO_Y", "shortDesc": "Acro mode yaw expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_P_MAX", "shortDesc": "Acro mode maximum pitch rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_R_MAX", "shortDesc": "Acro mode maximum roll rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using MC_ACRO_EXPO.\n0 Pure Expo function\n0.7 reasonable shape enhancement for intuitive stick feel\n0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "MC_ACRO_SUPEXPO", "shortDesc": "Acro mode roll, pitch super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y.\n0 Pure Expo function\n0.7 reasonable shape enhancement for intuitive stick feel\n0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "MC_ACRO_SUPEXPOY", "shortDesc": "Acro mode yaw super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_Y_MAX", "shortDesc": "Acro mode maximum yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 220.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limit for pitch rate in manual and auto modes (except acro).\nHas effect for large rotations in autonomous mode, to avoid large control\noutput and mixer saturation.\nThis is not only limited by the vehicle's properties, but also by the maximum\nmeasurement rate of the gyro.", "max": 1800.0, "min": 0.0, "name": "MC_PITCHRATE_MAX", "shortDesc": "Max pitch rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 12.0, "min": 0.0, "name": "MC_PITCH_P", "shortDesc": "Pitch P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 220.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limit for roll rate in manual and auto modes (except acro).\nHas effect for large rotations in autonomous mode, to avoid large control\noutput and mixer saturation.\nThis is not only limited by the vehicle's properties, but also by the maximum\nmeasurement rate of the gyro.", "max": 1800.0, "min": 0.0, "name": "MC_ROLLRATE_MAX", "shortDesc": "Max roll rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 12.0, "min": 0.0, "name": "MC_ROLL_P", "shortDesc": "Roll P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 200.0, "group": "Multicopter Attitude Control", "increment": 5.0, "max": 1800.0, "min": 0.0, "name": "MC_YAWRATE_MAX", "shortDesc": "Max yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.8, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 5.0, "min": 0.0, "name": "MC_YAW_P", "shortDesc": "Yaw P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "A fraction [0,1] deprioritizing yaw compared to roll and pitch in non-linear attitude control.\nDeprioritizing yaw is necessary because multicopters have much less control authority\nin yaw compared to the other axes and it makes sense because yaw is not critical for\nstable hovering or 3D navigation.\nFor yaw control tuning use MC_YAW_P. This ratio has no impact on the yaw gain.", "max": 1.0, "min": 0.0, "name": "MC_YAW_WEIGHT", "shortDesc": "Yaw weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": 20.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limits the acceleration of the yaw setpoint to avoid large\ncontrol output and mixer saturation.", "max": 360.0, "min": 5.0, "name": "MPC_YAWRAUTO_ACC", "shortDesc": "Maximum yaw acceleration in autonomous modes", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 0, "default": 60.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limits the rate of change of the yaw setpoint to avoid large\ncontrol output and mixer saturation.", "max": 360.0, "min": 5.0, "name": "MPC_YAWRAUTO_MAX", "shortDesc": "Maximum yaw rate in autonomous modes", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0.4, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "max": 1.0, "min": 0.0, "name": "CP_DELAY", "shortDesc": "Average delay of the range sensor message plus the tracking delay of the position controller in seconds", "type": "Float", "units": "s"}, {"category": "Standard", "default": -1.0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode. Collision avoidance is disabled by setting this parameter to a negative value", "max": 15.0, "min": -1.0, "name": "CP_DIST", "shortDesc": "Minimum distance the vehicle should keep to all obstacles", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "name": "CP_GO_NO_DATA", "shortDesc": "Boolean to allow moving into directions where there is no sensor data (outside FOV)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 30.0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "max": 90.0, "min": 0.0, "name": "CP_GUIDE_ANG", "shortDesc": "Angle left/right from the commanded setpoint by which the collision prevention algorithm can choose to change the setpoint direction", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Position Control", "longDesc": "Setting this parameter to 0 disables the filter", "max": 2.0, "min": 0.0, "name": "MC_MAN_TILT_TAU", "shortDesc": "Manual tilt input filter time constant", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Multicopter Position Control", "longDesc": "Set to decouple tilt from vertical acceleration.\nThis provides smoother flight but slightly worse tracking in position and auto modes.\nUnset if accurate position tracking during dynamic maneuvers is more important than a smooth flight.", "name": "MPC_ACC_DECOUPLE", "shortDesc": "Acceleration to tilt coupling", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 15.0, "min": 2.0, "name": "MPC_ACC_DOWN_MAX", "shortDesc": "Maximum downwards acceleration in climb rate controlled modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "When piloting manually, this parameter is only used in MPC_POS_MODE Acceleration based.", "max": 15.0, "min": 2.0, "name": "MPC_ACC_HOR", "shortDesc": "Acceleration for autonomous and for manual modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "MPC_POS_MODE\n1 just deceleration\n4 not used, use MPC_ACC_HOR instead", "max": 15.0, "min": 2.0, "name": "MPC_ACC_HOR_MAX", "shortDesc": "Maximum horizontal acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 15.0, "min": 2.0, "name": "MPC_ACC_UP_MAX", "shortDesc": "Maximum upwards acceleration in climb rate controlled modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 2, "group": "Multicopter Position Control", "longDesc": "Control height\n0: relative earth frame origin which may drift due to sensors\n1: relative to ground (requires distance sensor) which changes with terrain variation.\nIt will revert to relative earth frame if the distance to ground estimate becomes invalid.\n2: relative to ground (requires distance sensor) when stationary\nand relative to earth frame when moving horizontally.\nThe speed threshold is MPC_HOLD_MAX_XY", "max": 2, "min": 0, "name": "MPC_ALT_MODE", "shortDesc": "Altitude reference mode", "type": "Int32", "values": [{"description": "Altitude following", "value": 0}, {"description": "Terrain following", "value": 1}, {"description": "Terrain hold", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.8, "group": "Multicopter Position Control", "longDesc": "Only used with MPC_POS_MODE Direct velocity or MPC_ALT_MODE 2", "max": 3.0, "min": 0.0, "name": "MPC_HOLD_MAX_XY", "shortDesc": "Maximum horizontal velocity for which position hold is enabled (use 0 to disable check)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "longDesc": "Only used with MPC_ALT_MODE 1", "max": 3.0, "min": 0.0, "name": "MPC_HOLD_MAX_Z", "shortDesc": "Maximum vertical velocity for which position hold is enabled (use 0 to disable check)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Limit the maximum jerk of the vehicle (how fast the acceleration can change).\nA lower value leads to smoother vehicle motions but also limited agility.", "max": 80.0, "min": 1.0, "name": "MPC_JERK_AUTO", "shortDesc": "Jerk limit in autonomous modes", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 0, "default": 8.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Limit the maximum jerk (acceleration change) of the vehicle.\nA lower value leads to smoother motions but limits agility.\nSetting this to the maximum value essentially disables the limit.\nOnly used with MPC_POS_MODE Acceleration based.", "max": 500.0, "min": 0.5, "name": "MPC_JERK_MAX", "shortDesc": "Maximum horizontal and vertical jerk in Position/Altitude mode", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Multicopter Position Control", "longDesc": "Below this altitude descending velocity gets limited to a value\nbetween \"MPC_Z_VEL_MAX_DN\" (or \"MPC_Z_V_AUTO_DN\") and \"MPC_LAND_SPEED\"\nValue needs to be higher than \"MPC_LAND_ALT2\"", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT1", "shortDesc": "Altitude for 1. step of slow landing (descend)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "longDesc": "Below this altitude descending velocity gets\nlimited to \"MPC_LAND_SPEED\"\nValue needs to be lower than \"MPC_LAND_ALT1\"", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT2", "shortDesc": "Altitude for 2. step of slow landing (landing)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Multicopter Position Control", "longDesc": "If a valid distance sensor measurement to the ground is available,\nlimit descending velocity to \"MPC_LAND_CRWL\" below this altitude.", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT3", "shortDesc": "Altitude for 3. step of slow landing", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.3, "group": "Multicopter Position Control", "longDesc": "Used below MPC_LAND_ALT3 if distance sensor data is availabe.", "min": 0.1, "name": "MPC_LAND_CRWL", "shortDesc": "Land crawl descend rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "When nudging is enabled (see MPC_LAND_RC_HELP), this defines the maximum\nallowed horizontal displacement from the original landing point.\n- If inside of the radius, only allow nudging inputs that do not move the vehicle outside of it.\n- If outside of the radius, only allow nudging inputs that move the vehicle back towards it.\nSet it to -1 for infinite radius.", "min": -1.0, "name": "MPC_LAND_RADIUS", "shortDesc": "User assisted landing radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Using stick input the vehicle can be moved horizontally and yawed.\nThe descend speed is amended:\nstick full up - 0\nstick centered - MPC_LAND_SPEED\nstick full down - 2 * MPC_LAND_SPEED\nManual override during auto modes has to be disabled to use this feature (see COM_RC_OVERRIDE).", "max": 1, "min": 0, "name": "MPC_LAND_RC_HELP", "shortDesc": "Enable nudging based on user input during autonomous land routine", "type": "Int32", "values": [{"description": "Nudging disabled", "value": 0}, {"description": "Nudging enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.7, "group": "Multicopter Position Control", "min": 0.6, "name": "MPC_LAND_SPEED", "shortDesc": "Landing descend rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The value is mapped to the lowest throttle stick position in Stabilized mode.\nToo low collective thrust leads to loss of roll/pitch/yaw torque control authority.\nAirmode is used to keep torque authority with zero thrust (see MC_AIRMODE).", "max": 1.0, "min": 0.0, "name": "MPC_MANTHR_MIN", "shortDesc": "Minimum collective thrust in Stabilized mode", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 0, "default": 35.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 70.0, "min": 1.0, "name": "MPC_MAN_TILT_MAX", "shortDesc": "Maximal tilt angle in Stabilized, Altitude and Altitude Cruise mode", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 150.0, "group": "Multicopter Position Control", "increment": 10.0, "max": 400.0, "min": 0.0, "name": "MPC_MAN_Y_MAX", "shortDesc": "Max manual yaw rate for Stabilized, Altitude, Position mode", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Not used in Stabilized mode\nSetting this parameter to 0 disables the filter", "max": 5.0, "min": 0.0, "name": "MPC_MAN_Y_TAU", "shortDesc": "Manual yaw rate input filter time constant", "type": "Float", "units": "s"}, {"category": "Standard", "default": 4, "group": "Multicopter Position Control", "longDesc": "The supported sub-modes are:\nDirect velocity:\nSticks directly map to velocity setpoints without smoothing.\nAlso applies to vertical direction and Altitude mode.\nUseful for velocity control tuning.\nAcceleration based:\nSticks map to acceleration and there's a virtual brake drag", "name": "MPC_POS_MODE", "shortDesc": "Position/Altitude mode variant", "type": "Int32", "values": [{"description": "Direct velocity", "value": 0}, {"description": "Acceleration based", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Defines how the throttle stick is mapped to collective thrust in Stabilized mode.\nRescale to hover thrust estimate:\nStick input is linearly rescaled, such that a centered throttle stick corresponds to the hover thrust estimator's output.\nNo rescale:\nDirectly map the stick 1:1 to the output.\nCan be useful with very low hover thrust which leads to much distortion and the upper half getting sensitive.\nRescale to hover thrust parameter:\nSimilar to rescaling to the hover thrust estimate, but it uses the hover thrust parameter value (see MPC_THR_HOVER) instead of estimated value.\nWith MPC_THR_HOVER 0.5 it's equivalent to No rescale.", "name": "MPC_THR_CURVE", "shortDesc": "Thrust curve mapping in Stabilized Mode", "type": "Int32", "values": [{"description": "Rescale to estimate", "value": 0}, {"description": "No rescale", "value": 1}, {"description": "Rescale to parameter", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Mapped to center throttle stick in Stabilized mode (see MPC_THR_CURVE).\nUsed for initialization of the hover thrust estimator (see MPC_USE_HTE).\nThe estimated hover thrust is used as base for zero vertical acceleration in altitude control.\nThe hover thrust is important for land detection to work correctly.", "max": 0.8, "min": 0.1, "name": "MPC_THR_HOVER", "shortDesc": "Vertical thrust required to hover", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Control", "increment": 0.05, "longDesc": "Limit allowed thrust e.g. for indoor test of overpowered vehicle.", "max": 1.0, "min": 0.0, "name": "MPC_THR_MAX", "shortDesc": "Maximum collective thrust in climb rate controlled modes", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.12, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Too low thrust leads to loss of roll/pitch/yaw torque control authority.\nWith airmode enabled this parameters can be set to 0\nwhile still keeping torque authority (see MC_AIRMODE).", "max": 0.5, "min": 0.05, "name": "MPC_THR_MIN", "shortDesc": "Minimum collective thrust in climb rate controlled modes", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Margin that is kept for horizontal control when higher priority vertical thrust is saturated.\nTo avoid completely starving horizontal control with high vertical error.", "max": 0.5, "min": 0.0, "name": "MPC_THR_XY_MARG", "shortDesc": "Horizontal thrust margin", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Absolute maximum for all velocity or acceleration controlled modes.\nAny higher value is truncated.", "max": 89.0, "min": 20.0, "name": "MPC_TILTMAX_AIR", "shortDesc": "Maximum tilt angle in air", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 12.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Tighter tilt limit during takeoff to avoid tip over.", "max": 89.0, "min": 5.0, "name": "MPC_TILTMAX_LND", "shortDesc": "Maximum tilt during inital takeoff ramp", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 3.0, "group": "Multicopter Position Control", "longDesc": "Increasing this value will make climb rate controlled takeoff slower.\nIf it's too slow the drone might scratch the ground and tip over.\nA time constant of 0 disables the ramp", "max": 5.0, "min": 0.0, "name": "MPC_TKO_RAMP_T", "shortDesc": "Smooth takeoff ramp time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.5, "group": "Multicopter Position Control", "max": 5.0, "min": 1.0, "name": "MPC_TKO_SPEED", "shortDesc": "Takeoff climb rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "Multicopter Position Control", "longDesc": "Disable to use the fixed parameter MPC_THR_HOVER instead of the hover thrust estimate in the position controller.\nThis parameter does not influence Stabilized mode throttle curve (see MPC_THR_CURVE).", "name": "MPC_USE_HTE", "shortDesc": "Use hover thrust estimate for altitude control", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VELD_LP", "shortDesc": "Velocity derivative low pass cutoff frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_LP", "shortDesc": "Velocity low pass cutoff frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Must be smaller than MPC_XY_VEL_MAX.\nThe maximum sideways and backward speed can be set differently\nusing MPC_VEL_MAN_SIDE and MPC_VEL_MAN_BACK, respectively.", "max": 20.0, "min": 3.0, "name": "MPC_VEL_MANUAL", "shortDesc": "Maximum horizontal velocity setpoint in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a negative value or larger than\nMPC_VEL_MANUAL then MPC_VEL_MANUAL is used.", "max": 20.0, "min": -1.0, "name": "MPC_VEL_MAN_BACK", "shortDesc": "Maximum backward velocity in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a negative value or larger than\nMPC_VEL_MANUAL then MPC_VEL_MANUAL is used.", "max": 20.0, "min": -1.0, "name": "MPC_VEL_MAN_SIDE", "shortDesc": "Maximum sideways velocity in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_NF_BW", "shortDesc": "Velocity notch filter bandwidth", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "The center frequency for the 2nd order notch filter on the velocity.\nA value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_NF_FRQ", "shortDesc": "Velocity notch filter frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 0, "default": 5.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "e.g. in Missions, RTL, Goto if the waypoint does not specify differently", "max": 20.0, "min": 3.0, "name": "MPC_XY_CRUISE", "shortDesc": "Default horizontal velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "The integration speed of the trajectory setpoint is linearly\nreduced with the horizontal position tracking error. When the\nerror is above this parameter, the integration of the\ntrajectory is stopped to wait for the drone.\nThis value can be adjusted depending on the tracking\ncapabilities of the vehicle.", "max": 10.0, "min": 0.1, "name": "MPC_XY_ERR_MAX", "shortDesc": "Maximum horizontal error allowed by the trajectory generator", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.95, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective velocity in m/s per m position error", "max": 2.0, "min": 0.0, "name": "MPC_XY_P", "shortDesc": "Proportional gain for horizontal position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Multicopter Position Control", "increment": 0.1, "max": 1.0, "min": 0.1, "name": "MPC_XY_TRAJ_P", "shortDesc": "Proportional gain for horizontal trajectory position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -10.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a value greater than zero, other parameters are automatically set (such as\nMPC_XY_VEL_MAX or MPC_VEL_MANUAL).\nIf set to a negative value, the existing individual parameters are used.", "max": 20.0, "min": -20.0, "name": "MPC_XY_VEL_ALL", "shortDesc": "Overall Horizontal Velocity Limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative", "max": 2.0, "min": 0.1, "name": "MPC_XY_VEL_D_ACC", "shortDesc": "Differential gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as correction acceleration in m/s^2 per m velocity integral\nAllows to eliminate steady state errors in disturbances like wind.", "max": 60.0, "min": 0.0, "name": "MPC_XY_VEL_I_ACC", "shortDesc": "Integral gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 12.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Absolute maximum for all velocity controlled modes.\nAny higher value is truncated.", "max": 20.0, "min": 0.0, "name": "MPC_XY_VEL_MAX", "shortDesc": "Maximum horizontal velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.8, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s velocity error", "max": 5.0, "min": 1.2, "name": "MPC_XY_VEL_P_ACC", "shortDesc": "Proportional gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective velocity in m/s per m position error", "max": 1.5, "min": 0.1, "name": "MPC_Z_P", "shortDesc": "Proportional gain for vertical position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -3.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "If set to a value greater than zero, other parameters are automatically set (such as\nMPC_Z_VEL_MAX_UP or MPC_LAND_SPEED).\nIf set to a negative value, the existing individual parameters are used.", "max": 8.0, "min": -3.0, "name": "MPC_Z_VEL_ALL", "shortDesc": "Overall Vertical Velocity Limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative", "max": 2.0, "min": 0.0, "name": "MPC_Z_VEL_D_ACC", "shortDesc": "Differential gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m velocity integral", "max": 3.0, "min": 0.2, "name": "MPC_Z_VEL_I_ACC", "shortDesc": "Integral gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Absolute maximum for all climb rate controlled modes.\nIn manually piloted modes full stick deflection commands this velocity.\nFor default autonomous velocity see MPC_Z_V_AUTO_UP", "max": 4.0, "min": 0.5, "name": "MPC_Z_VEL_MAX_DN", "shortDesc": "Maximum descent velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Absolute maximum for all climb rate controlled modes.\nIn manually piloted modes full stick deflection commands this velocity.\nFor default autonomous velocity see MPC_Z_V_AUTO_UP", "max": 8.0, "min": 0.5, "name": "MPC_Z_VEL_MAX_UP", "shortDesc": "Maximum ascent velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s velocity error", "max": 15.0, "min": 2.0, "name": "MPC_Z_VEL_P_ACC", "shortDesc": "Proportional gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "For manual modes and offboard, see MPC_Z_VEL_MAX_DN", "max": 4.0, "min": 0.5, "name": "MPC_Z_V_AUTO_DN", "shortDesc": "Descent velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "For manually controlled modes and offboard see MPC_Z_VEL_MAX_UP", "max": 8.0, "min": 0.5, "name": "MPC_Z_V_AUTO_UP", "shortDesc": "Ascent velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": -0.4, "group": "Multicopter Position Control", "increment": 0.05, "longDesc": "Changes the overall responsiveness of the vehicle.\nThe higher the value, the faster the vehicle will react.\nIf set to a value greater than zero, other parameters are automatically set (such as\nthe acceleration or jerk limits).\nIf set to a negative value, the existing individual parameters are used.", "max": 1.0, "min": -1.0, "name": "SYS_VEHICLE_RESP", "shortDesc": "Responsiveness", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "name": "WV_EN", "shortDesc": "Enable weathervane", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1.0, "group": "Multicopter Position Control", "max": 5.0, "min": 0.0, "name": "WV_ROLL_MIN", "shortDesc": "Minimum roll angle setpoint for weathervane controller to demand a yaw-rate", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 90.0, "group": "Multicopter Position Control", "max": 120.0, "min": 0.0, "name": "WV_YRATE_MAX", "shortDesc": "Maximum yawrate the weathervane controller is allowed to demand", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if\nno aux channel is mapped and\nno limit is commanded through MAVLink.", "min": 0.1, "name": "MC_SLOW_DEF_HVEL", "shortDesc": "Default horizontal velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if\nno aux channel is mapped and\nno limit is commanded through MAVLink.", "min": 0.1, "name": "MC_SLOW_DEF_VVEL", "shortDesc": "Default vertical velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if\nno aux channel is mapped and\nno limit is commanded through MAVLink.", "min": 1.0, "name": "MC_SLOW_DEF_YAWR", "shortDesc": "Default yaw rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_HVEL", "shortDesc": "Manual input mapped to scale horizontal velocity in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_PTCH", "shortDesc": "RC_MAP_AUX{N} to allow for gimbal pitch rate control in position slow mode", "type": "Int32", "values": [{"description": "No pitch rate input", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_VVEL", "shortDesc": "Manual input mapped to scale vertical velocity in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_YAWR", "shortDesc": "Manual input mapped to scale yaw rate in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this velocity.", "min": 0.1, "name": "MC_SLOW_MIN_HVEL", "shortDesc": "Horizontal velocity lower limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this velocity.", "min": 0.1, "name": "MC_SLOW_MIN_VVEL", "shortDesc": "Vertical velocity lower limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 3.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this rate.", "min": 1.0, "name": "MC_SLOW_MIN_YAWR", "shortDesc": "Yaw rate lower limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0, "group": "Multicopter Rate Control", "longDesc": "This compensates for voltage drop of the battery over time by attempting to\nnormalize performance across the operating range of the battery. The copter\nshould constantly behave as if it was fully charged with reduced max acceleration\nat lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery,\nit will still be 0.5 at 60% battery.", "name": "MC_BAT_SCALE_EN", "shortDesc": "Battery power level scaler", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 4, "default": 0.003, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "min": 0.0, "name": "MC_PITCHRATE_D", "shortDesc": "Pitch rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_PITCHRATE_FF", "shortDesc": "Pitch rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_PITCHRATE_I", "shortDesc": "Pitch rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller.\nThis gain scales the P, I and D terms of the controller:\noutput = MC_PITCHRATE_K * (MC_PITCHRATE_P * error\n+ MC_PITCHRATE_I * error_integral\n+ MC_PITCHRATE_D * error_derivative)\nSet MC_PITCHRATE_P=1 to implement a PID in the ideal form.\nSet MC_PITCHRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_PITCHRATE_K", "shortDesc": "Pitch rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.6, "min": 0.01, "name": "MC_PITCHRATE_P", "shortDesc": "Pitch rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes.", "min": 0.0, "name": "MC_PR_INT_LIM", "shortDesc": "Pitch rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.003, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "max": 0.01, "min": 0.0, "name": "MC_ROLLRATE_D", "shortDesc": "Roll rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_ROLLRATE_FF", "shortDesc": "Roll rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_ROLLRATE_I", "shortDesc": "Roll rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller.\nThis gain scales the P, I and D terms of the controller:\noutput = MC_ROLLRATE_K * (MC_ROLLRATE_P * error\n+ MC_ROLLRATE_I * error_integral\n+ MC_ROLLRATE_D * error_derivative)\nSet MC_ROLLRATE_P=1 to implement a PID in the ideal form.\nSet MC_ROLLRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_ROLLRATE_K", "shortDesc": "Roll rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.5, "min": 0.01, "name": "MC_ROLLRATE_P", "shortDesc": "Roll rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes.", "min": 0.0, "name": "MC_RR_INT_LIM", "shortDesc": "Roll rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "min": 0.0, "name": "MC_YAWRATE_D", "shortDesc": "Yaw rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_YAWRATE_FF", "shortDesc": "Yaw rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_YAWRATE_I", "shortDesc": "Yaw rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller.\nThis gain scales the P, I and D terms of the controller:\noutput = MC_YAWRATE_K * (MC_YAWRATE_P * error\n+ MC_YAWRATE_I * error_integral\n+ MC_YAWRATE_D * error_derivative)\nSet MC_YAWRATE_P=1 to implement a PID in the ideal form.\nSet MC_YAWRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_YAWRATE_K", "shortDesc": "Yaw rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.6, "min": 0.0, "name": "MC_YAWRATE_P", "shortDesc": "Yaw rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 2.0, "group": "Multicopter Rate Control", "longDesc": "Reduces vibrations by lowering high frequency torque caused by rotor acceleration.\n0 disables the filter", "max": 10.0, "min": 0.0, "name": "MC_YAW_TQ_CUTOFF", "shortDesc": "Low pass filter cutoff frequency for yaw torque setpoint", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes.", "min": 0.0, "name": "MC_YR_INT_LIM", "shortDesc": "Yaw rate integrator limit", "type": "Float"}, {"category": "Standard", "default": 0, "group": "OSD", "longDesc": "Controls the vertical position of the crosshair display.\nResolution is limited by OSD to 15 discrete values. Negative\nvalues will display the crosshairs below the horizon", "max": 8, "min": -8, "name": "OSD_CH_HEIGHT", "shortDesc": "OSD Crosshairs Height", "type": "Int32"}, {"category": "Standard", "default": 500, "group": "OSD", "longDesc": "Amount of time in milliseconds to dwell at the beginning of the display, when scrolling.", "max": 10000, "min": 100, "name": "OSD_DWELL_TIME", "shortDesc": "OSD Dwell Time (ms)", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "OSD", "longDesc": "Minimum security of log level to display on the OSD.", "name": "OSD_LOG_LEVEL", "shortDesc": "OSD Warning Level", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "OSD", "longDesc": "Forward RC stick input to VTX when disarmed", "max": 1, "min": 0, "name": "OSD_RC_STICK", "shortDesc": "OSD RC Stick commands", "type": "Int32"}, {"category": "Standard", "default": 125, "group": "OSD", "longDesc": "Scroll rate in milliseconds for OSD messages longer than available character width.\nThis is lower-bounded by the nominal loop rate of this module.", "max": 1000, "min": 100, "name": "OSD_SCROLL_RATE", "shortDesc": "OSD Scroll Rate (ms)", "type": "Int32"}, {"bitmask": [{"description": "CRAFT_NAME", "index": 0}, {"description": "DISARMED", "index": 1}, {"description": "GPS_LAT", "index": 2}, {"description": "GPS_LON", "index": 3}, {"description": "GPS_SATS", "index": 4}, {"description": "GPS_SPEED", "index": 5}, {"description": "HOME_DIST", "index": 6}, {"description": "HOME_DIR", "index": 7}, {"description": "MAIN_BATT_VOLTAGE", "index": 8}, {"description": "CURRENT_DRAW", "index": 9}, {"description": "MAH_DRAWN", "index": 10}, {"description": "RSSI_VALUE", "index": 11}, {"description": "ALTITUDE", "index": 12}, {"description": "NUMERICAL_VARIO", "index": 13}, {"description": "(unused) FLYMODE", "index": 14}, {"description": "(unused) ESC_TMP", "index": 15}, {"description": "(unused) PITCH_ANGLE", "index": 16}, {"description": "(unused) ROLL_ANGLE", "index": 17}, {"description": "CROSSHAIRS", "index": 18}, {"description": "AVG_CELL_VOLTAGE", "index": 19}, {"description": "(unused) HORIZON_SIDEBARS", "index": 20}, {"description": "POWER", "index": 21}], "category": "Standard", "default": 16383, "group": "OSD", "longDesc": "Configure / toggle support display options.", "max": 4194303, "min": 0, "name": "OSD_SYMBOLS", "shortDesc": "OSD Symbol Selection", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "PWM Outputs", "increment": 0.1, "longDesc": "Parameter used to model the nonlinear relationship between\nmotor control signal (e.g. PWM) and static thrust.\nThe model is: rel_thrust = factor * rel_signal^2 + (1-factor) * rel_signal,\nwhere rel_thrust is the normalized thrust between 0 and 1, and\nrel_signal is the relative motor control signal between 0 and 1.", "max": 1.0, "min": 0.0, "name": "THR_MDL_FAC", "shortDesc": "Thrust to motor control signal model parameter", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Payload Deliverer", "longDesc": "Maximum time Gripper will wait while the successful griper actuation isn't recognised.\nIf the gripper has no feedback sensor, it will simply wait for\nthis time before considering gripper actuation successful and publish a\n'VehicleCommandAck' signaling successful gripper action", "min": 0.0, "name": "PD_GRIPPER_TO", "shortDesc": "Timeout for successful gripper actuation acknowledgement", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Payload Deliverer", "max": 0, "min": -1, "name": "PD_GRIPPER_TYPE", "shortDesc": "Type of Gripper (Servo, etc.)", "type": "Int32", "values": [{"description": "Undefined", "value": -1}, {"description": "Servo", "value": 0}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Precision Land", "increment": 0.5, "longDesc": "Time after which the landing target is considered lost without any new measurements.", "max": 50.0, "min": 0.0, "name": "PLD_BTOUT", "shortDesc": "Landing Target Timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Precision Land", "increment": 0.1, "longDesc": "Allow final approach (without horizontal positioning) if losing landing target closer than this to the ground.", "max": 10.0, "min": 0.0, "name": "PLD_FAPPR_ALT", "shortDesc": "Final approach altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Precision Land", "increment": 0.1, "longDesc": "Start descending if closer above landing target than this.", "max": 10.0, "min": 0.0, "name": "PLD_HACC_RAD", "shortDesc": "Horizontal acceptance radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "Precision Land", "longDesc": "Maximum number of times to search for the landing target if it is lost during the precision landing.", "max": 100, "min": 0, "name": "PLD_MAX_SRCH", "shortDesc": "Maximum number of search attempts", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Precision Land", "increment": 0.1, "longDesc": "Altitude above home to which to climb when searching for the landing target.", "max": 100.0, "min": 0.0, "name": "PLD_SRCH_ALT", "shortDesc": "Search altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Precision Land", "increment": 0.1, "longDesc": "Time allowed to search for the landing target before falling back to normal landing.", "max": 100.0, "min": 0.0, "name": "PLD_SRCH_TOUT", "shortDesc": "Search timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Pure Pursuit", "increment": 0.01, "longDesc": "Lower value -> More aggressive controller (beware overshoot/oscillations)", "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_GAIN", "shortDesc": "Tuning parameter for the pure pursuit controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Pure Pursuit", "increment": 0.01, "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_MAX", "shortDesc": "Maximum lookahead distance for the pure pursuit controller", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Pure Pursuit", "increment": 0.01, "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_MIN", "shortDesc": "Minimum lookahead distance for the pure pursuit controller", "type": "Float", "units": "m"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC10_MAX", "shortDesc": "RC channel 10 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC10_MIN", "shortDesc": "RC channel 10 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC10_REV", "shortDesc": "RC channel 10 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC10_TRIM", "shortDesc": "RC channel 10 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC11_MAX", "shortDesc": "RC channel 11 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC11_MIN", "shortDesc": "RC channel 11 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC11_REV", "shortDesc": "RC channel 11 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC11_TRIM", "shortDesc": "RC channel 11 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC12_MAX", "shortDesc": "RC channel 12 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC12_MIN", "shortDesc": "RC channel 12 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC12_REV", "shortDesc": "RC channel 12 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC12_TRIM", "shortDesc": "RC channel 12 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC13_MAX", "shortDesc": "RC channel 13 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC13_MIN", "shortDesc": "RC channel 13 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC13_REV", "shortDesc": "RC channel 13 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC13_TRIM", "shortDesc": "RC channel 13 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC14_MAX", "shortDesc": "RC channel 14 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC14_MIN", "shortDesc": "RC channel 14 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC14_REV", "shortDesc": "RC channel 14 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC14_TRIM", "shortDesc": "RC channel 14 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC15_MAX", "shortDesc": "RC channel 15 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC15_MIN", "shortDesc": "RC channel 15 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC15_REV", "shortDesc": "RC channel 15 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC15_TRIM", "shortDesc": "RC channel 15 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC16_MAX", "shortDesc": "RC channel 16 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC16_MIN", "shortDesc": "RC channel 16 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC16_REV", "shortDesc": "RC channel 16 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC16_TRIM", "shortDesc": "RC channel 16 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC17_MAX", "shortDesc": "RC channel 17 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC17_MIN", "shortDesc": "RC channel 17 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC17_REV", "shortDesc": "RC channel 17 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC17_TRIM", "shortDesc": "RC channel 17 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC18_MAX", "shortDesc": "RC channel 18 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC18_MIN", "shortDesc": "RC channel 18 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC18_REV", "shortDesc": "RC channel 18 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC18_TRIM", "shortDesc": "RC channel 18 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for RC channel 1", "max": 2200.0, "min": 1500.0, "name": "RC1_MAX", "shortDesc": "RC channel 1 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for RC channel 1", "max": 1500.0, "min": 800.0, "name": "RC1_MIN", "shortDesc": "RC channel 1 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC1_REV", "shortDesc": "RC channel 1 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC1_TRIM", "shortDesc": "RC channel 1 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC2_MAX", "shortDesc": "RC channel 2 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC2_MIN", "shortDesc": "RC channel 2 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC2_REV", "shortDesc": "RC channel 2 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC2_TRIM", "shortDesc": "RC channel 2 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC3_MAX", "shortDesc": "RC channel 3 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC3_MIN", "shortDesc": "RC channel 3 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC3_REV", "shortDesc": "RC channel 3 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC3_TRIM", "shortDesc": "RC channel 3 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC4_MAX", "shortDesc": "RC channel 4 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC4_MIN", "shortDesc": "RC channel 4 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC4_REV", "shortDesc": "RC channel 4 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC4_TRIM", "shortDesc": "RC channel 4 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC5_MAX", "shortDesc": "RC channel 5 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC5_MIN", "shortDesc": "RC channel 5 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC5_REV", "shortDesc": "RC channel 5 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC5_TRIM", "shortDesc": "RC channel 5 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC6_MAX", "shortDesc": "RC channel 6 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC6_MIN", "shortDesc": "RC channel 6 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC6_REV", "shortDesc": "RC channel 6 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC6_TRIM", "shortDesc": "RC channel 6 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC7_MAX", "shortDesc": "RC channel 7 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC7_MIN", "shortDesc": "RC channel 7 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC7_REV", "shortDesc": "RC channel 7 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC7_TRIM", "shortDesc": "RC channel 7 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC8_MAX", "shortDesc": "RC channel 8 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC8_MIN", "shortDesc": "RC channel 8 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC8_REV", "shortDesc": "RC channel 8 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC8_TRIM", "shortDesc": "RC channel 8 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC9_MAX", "shortDesc": "RC channel 9 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC9_MIN", "shortDesc": "RC channel 9 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC9_REV", "shortDesc": "RC channel 9 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC9_TRIM", "shortDesc": "RC channel 9 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "This parameter is used by Ground Station software to save the number\nof channels which were used during RC calibration. It is only meant\nfor ground station use.", "max": 18, "min": 0, "name": "RC_CHAN_CNT", "shortDesc": "RC channel count", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Use RC_MAP_FAILSAFE to specify which channel is used to indicate RC loss via this threshold.\nBy default this is the throttle channel.\nSet to a PWM value slightly above the PWM value for the channel (e.g. throttle) in a failsafe event,\nbut below the minimum PWM value for the channel during normal operation.\nNote: The default value of 0 disables the feature (it is below the expected range).", "max": 2200, "min": 0, "name": "RC_FAILS_THR", "shortDesc": "Failsafe channel PWM threshold", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX1", "shortDesc": "AUX1 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX2", "shortDesc": "AUX2 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX3", "shortDesc": "AUX3 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX4", "shortDesc": "AUX4 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX5", "shortDesc": "AUX5 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX6", "shortDesc": "AUX6 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_ENG_MOT", "shortDesc": "RC channel to engage the main motor (for helicopters)", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Configures which RC channel is used by the receiver to indicate the signal was lost\n(on receivers that use output a fixed signal value to report lost signal).\nIf set to 0, the channel mapped to throttle is used.\nUse RC_FAILS_THR to set the threshold indicating lost signal. By default it's below\nthe expected range and hence disabled.", "max": 18, "min": 0, "name": "RC_MAP_FAILSAFE", "shortDesc": "Failsafe channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel.\nSet to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM1", "shortDesc": "PARAM1 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel.\nSet to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM2", "shortDesc": "PARAM2 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel.\nSet to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM3", "shortDesc": "PARAM3 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates\nwhich channel should be used for reading pitch inputs from.\nA value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_PITCH", "shortDesc": "Pitch control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates\nwhich channel should be used for reading roll inputs from.\nA value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_ROLL", "shortDesc": "Roll control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates\nwhich channel should be used for reading throttle inputs from.\nA value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_THROTTLE", "shortDesc": "Throttle control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates\nwhich channel should be used for reading yaw inputs from.\nA value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_YAW", "shortDesc": "Yaw control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "0: do not read RSSI from input channel\n1-18: read RSSI from specified input channel\nSpecify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters.", "max": 18, "min": 0, "name": "RC_RSSI_PWM_CHAN", "shortDesc": "PWM input channel that provides RSSI", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 2000, "group": "Radio Calibration", "longDesc": "Only used if RC_RSSI_PWM_CHAN > 0", "max": 2000, "min": 0, "name": "RC_RSSI_PWM_MAX", "shortDesc": "Max input value for RSSI reading", "type": "Int32"}, {"category": "Standard", "default": 1000, "group": "Radio Calibration", "longDesc": "Only used if RC_RSSI_PWM_CHAN > 0", "max": 2000, "min": 0, "name": "RC_RSSI_PWM_MIN", "shortDesc": "Min input value for RSSI reading", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs\nfor straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_PITCH", "shortDesc": "Pitch trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs\nfor straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_ROLL", "shortDesc": "Roll trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs\nfor straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_YAW", "shortDesc": "Yaw trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.75, "group": "Radio Switches", "longDesc": "0-1 indicate where in the full channel range the threshold sits\n0 : min\n1 : max\nsign indicates polarity of comparison\npositive : true when channel>th\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channel The rover starts to cut the corner earlier.", "max": 100.0, "min": 1.0, "name": "RA_ACC_RAD_GAIN", "shortDesc": "Tuning parameter for corner cutting", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Ackermann", "increment": 0.01, "longDesc": "The controller scales the acceptance radius based on the angle between\nthe previous, current and next waypoint.\nHigher value -> smoother trajectory at the cost of how close the rover gets\nto the waypoint (Set to -1 to disable corner cutting).", "max": 100.0, "min": -1.0, "name": "RA_ACC_RAD_MAX", "shortDesc": "Maximum acceptance radius for the waypoints", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Ackermann", "increment": 0.01, "max": 1.5708, "min": 0.0, "name": "RA_MAX_STR_ANG", "shortDesc": "Maximum steering angle", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Ackermann", "increment": 0.01, "longDesc": "Set to -1 to disable.", "max": 1000.0, "min": -1.0, "name": "RA_STR_RATE_LIM", "shortDesc": "Steering rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Ackermann", "increment": 0.001, "longDesc": "Distance from the front to the rear axle.", "max": 100.0, "min": 0.0, "name": "RA_WHEEL_BASE", "shortDesc": "Wheel base", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Attitude Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_P", "shortDesc": "Proportional gain for closed loop yaw controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.174533, "group": "Rover Differential", "increment": 0.01, "longDesc": "This threshold is used for the state machine to switch from driving to turning based on the\nerror between the desired and actual yaw. It is also used as the threshold whether the rover should come\nto a smooth stop at the next waypoint. This slow down effect is active if the angle between the\nline segments from prevWP-currWP and currWP-nextWP is smaller then 180 - RD_TRANS_DRV_TRN.", "max": 3.14159, "min": 0.001, "name": "RD_TRANS_DRV_TRN", "shortDesc": "Yaw error threshhold to switch from driving to spot turning", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0872665, "group": "Rover Differential", "increment": 0.01, "longDesc": "This threshold is used for the state machine to switch from turning to driving based on the\nerror between the desired and actual yaw.", "max": 3.14159, "min": 0.001, "name": "RD_TRANS_TRN_DRV", "shortDesc": "Yaw error threshhold to switch from spot turning to driving", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Differential", "increment": 0.001, "longDesc": "Distance from the center of the right wheel to the center of the left wheel.", "max": 100.0, "min": 0.0, "name": "RD_WHEEL_TRACK", "shortDesc": "Wheel track", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Rover Differential", "increment": 0.01, "longDesc": "Assign value <1.0 to decrease stick response for yaw control.", "max": 1.0, "min": 0.1, "name": "RD_YAW_STK_GAIN", "shortDesc": "Yaw stick gain for Manual mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.17, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "Threshold for the angle between the active cruise direction and the cruise direction given\nby the stick inputs.\nThis can be understood as a deadzone for the combined stick inputs for forward/backwards\nand lateral speed which defines a course direction.", "max": 3.14, "min": 0.0, "name": "RM_COURSE_CTL_TH", "shortDesc": "Threshold to update course control in manual position mode", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Mecanum", "increment": 0.001, "longDesc": "Distance from the center of the right wheel to the center of the left wheel.", "max": 100.0, "min": 0.0, "name": "RM_WHEEL_TRACK", "shortDesc": "Wheel track", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "Assign value <1.0 to decrease stick response for yaw control.", "max": 1.0, "min": 0.1, "name": "RM_YAW_STK_GAIN", "shortDesc": "Yaw stick gain for Manual mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap how quickly the magnitude of yaw rate setpoints can increase.\nSet to -1 to disable.", "max": 10000.0, "min": -1.0, "name": "RO_YAW_ACCEL_LIM", "shortDesc": "Yaw acceleration limit", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap how quickly the magnitude of yaw rate setpoints can decrease.\nSet to -1 to disable.", "max": 10000.0, "min": -1.0, "name": "RO_YAW_DECEL_LIM", "shortDesc": "Yaw deceleration limit", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Rate Control", "longDesc": "Exponential factor for tuning the input curve shape.\n0 Purely linear input curve\n1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "RO_YAW_EXPO", "shortDesc": "Yaw rate expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Multiplicative correction factor for the feedforward mapping of the yaw rate controller.\nIncrease this value (x > 1) if the measured yaw rate is lower than the setpoint, decrease (0 < x < 1) otherwise.\nNote: Tuning this is particularly useful for skid-steered rovers, or rovers with misaligned wheels/steering axes\nthat cause a lot of friction when turning.", "max": 10000.0, "min": 0.01, "name": "RO_YAW_RATE_CORR", "shortDesc": "Yaw rate correction factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_I", "shortDesc": "Integral gain for closed loop yaw rate controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap yaw rate setpoints and map controller inputs to yaw rate setpoints\nin Acro, Stabilized and Position mode.", "max": 10000.0, "min": 0.0, "name": "RO_YAW_RATE_LIM", "shortDesc": "Yaw rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_P", "shortDesc": "Proportional gain for closed loop yaw rate controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "The minimum threshold for the yaw rate measurement not to be interpreted as zero.", "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_TH", "shortDesc": "Yaw rate measurement threshold", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Percentage of stick input range that will be interpreted as zero around the stick centered value.", "max": 1.0, "min": 0.0, "name": "RO_YAW_STICK_DZ", "shortDesc": "Yaw stick deadzone", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Rate Control", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using RO_YAW_EXPO.\n0 Pure Expo function\n0.7 reasonable shape enhancement for intuitive stick feel\n0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "RO_YAW_SUPEXPO", "shortDesc": "Yaw rate super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable.\nFor mecanum rovers this limit is used for longitudinal and lateral acceleration.", "max": 100.0, "min": -1.0, "name": "RO_ACCEL_LIM", "shortDesc": "Acceleration limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable.\nNote that if it is disabled the rover will not slow down when approaching waypoints in auto modes.\nFor mecanum rovers this limit is used for longitudinal and lateral deceleration.", "max": 100.0, "min": -1.0, "name": "RO_DECEL_LIM", "shortDesc": "Deceleration limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable.\nNote that if it is disabled the rover will not slow down when approaching waypoints in auto modes.\nFor mecanum rovers this limit is used for longitudinal and lateral jerk.", "max": 100.0, "min": -1.0, "name": "RO_JERK_LIM", "shortDesc": "Jerk limit", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Used to linearly map speeds [m/s] to throttle values [-1. 1].", "max": 100.0, "min": 0.0, "name": "RO_MAX_THR_SPEED", "shortDesc": "Speed the rover drives at maximum throttle", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.001, "max": 100.0, "min": 0.0, "name": "RO_SPEED_I", "shortDesc": "Integral gain for ground speed controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Used to cap speed setpoints and map controller inputs to speed setpoints in Position mode.", "max": 100.0, "min": -1.0, "name": "RO_SPEED_LIM", "shortDesc": "Speed limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_SPEED_P", "shortDesc": "Proportional gain for ground speed controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Reduced_speed = RO_MAX_THR_SPEED * (1 - normalized_course_error * RO_SPEED_RED)\nThe normalized course error is the angle between the current course and the bearing setpoint\ninterpolated from [0, 180] -> [0, 1].\nHigher value -> More speed reduction.\nNote: This is also used to calculate the speed at which the vehicle arrives at a waypoint in auto modes.\nSet to -1 to disable bearing error based speed reduction.", "max": 100.0, "min": -1.0, "name": "RO_SPEED_RED", "shortDesc": "Tuning parameter for the speed reduction based on the course error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable.\nThe minimum threshold for the speed measurement not to be interpreted as zero.", "max": 100.0, "min": 0.0, "name": "RO_SPEED_TH", "shortDesc": "Speed measurement threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Runway Takeoff", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "RWTO_MAX_THR", "shortDesc": "Throttle during runway takeoff", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 1, "group": "Runway Takeoff", "longDesc": "This is useful when map, GNSS, or yaw errors on ground are misaligned with what the operator intends for takeoff course.\nParticularly useful for skinny runways or if the wheel servo is a bit off trim.", "name": "RWTO_NUDGE", "shortDesc": "Enable use of yaw stick for nudging the wheel during runway ground roll", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Runway Takeoff", "increment": 0.5, "longDesc": "A taildragger with steerable wheel might need to pitch up\na little to keep its wheel on the ground before airspeed\nto takeoff is reached.", "max": 20.0, "min": -10.0, "name": "RWTO_PSP", "shortDesc": "Pitch setpoint during taxi / before takeoff rotation airspeed is reached", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Runway Takeoff", "increment": 0.1, "max": 15.0, "min": 1.0, "name": "RWTO_RAMP_TIME", "shortDesc": "Throttle ramp up time for runway takeoff", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Runway Takeoff", "increment": 0.1, "longDesc": "The calibrated airspeed threshold during the takeoff ground roll when the plane should start rotating (pitching up).\nMust be less than the takeoff airspeed, will otherwise be capped at the takeoff airpeed (see FW_TKO_AIRSPD).\nIf set <= 0.0, defaults to 0.9 * takeoff airspeed (see FW_TKO_AIRSPD)", "min": -1.0, "name": "RWTO_ROT_AIRSPD", "shortDesc": "Takeoff rotation airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Runway Takeoff", "increment": 0.1, "longDesc": "This is the time desired to linearly ramp in takeoff pitch constraints during the takeoff rotation", "min": 0.1, "name": "RWTO_ROT_TIME", "shortDesc": "Takeoff rotation time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Runway Takeoff", "name": "RWTO_TKOFF", "shortDesc": "Runway takeoff with landing gear", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"bitmask": [{"description": "SD card logging", "index": 0}, {"description": "Mavlink logging", "index": 1}], "category": "Standard", "default": 3, "group": "SD Logging", "longDesc": "If no logging is set the logger will not be started. Set bits true to enable: 0: SD card logging 1: Mavlink logging", "max": 3, "min": 0, "name": "SDLOG_BACKEND", "rebootRequired": true, "shortDesc": "Logging Backend (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "When enabled, logging will not start from boot if battery power is not detected (e.g. powered via USB on a test bench). This prevents extraneous flight logs from being created during bench testing. Note that this only applies to log-from-boot modes. This has no effect on arm-based modes.", "name": "SDLOG_BOOT_BAT", "shortDesc": "Battery-only Logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum. Note: this does not apply to mission log files.", "max": 1000, "min": 0, "name": "SDLOG_DIRS_MAX", "rebootRequired": true, "shortDesc": "Maximum number of log directories to keep", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "If enabled, a small additional \"mission\" log file will be written to the SD card. The log contains just those messages that are useful for tasks like generating flight statistics and geotagging. The different modes can be used to further reduce the logged data (and thus the log file size). For example, choose geotagging mode to only log data required for geotagging. Note that the normal/full log is still created, and contains all the data in the mission log (and more).", "name": "SDLOG_MISSION", "rebootRequired": true, "shortDesc": "Mission Log", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "All mission messages", "value": 1}, {"description": "Geotagging messages", "value": 2}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming. Note: The logging start/end points that can be configured here only apply to SD logging. The mavlink backend is started/stopped independently of these points.", "name": "SDLOG_MODE", "rebootRequired": true, "shortDesc": "Logging Mode", "type": "Int32", "values": [{"description": "when armed until disarm (default)", "value": 0}, {"description": "from boot until disarm", "value": 1}, {"description": "from boot until shutdown", "value": 2}, {"description": "while manual input AUX1 >30%", "value": 3}, {"description": "from 1st armed until shutdown", "value": 4}]}, {"bitmask": [{"description": "Default set (general log analysis)", "index": 0}, {"description": "Estimator replay (EKF2)", "index": 1}, {"description": "Thermal calibration", "index": 2}, {"description": "System identification", "index": 3}, {"description": "High rate", "index": 4}, {"description": "Debug", "index": 5}, {"description": "Sensor comparison", "index": 6}, {"description": "Computer Vision and Avoidance", "index": 7}, {"description": "Raw FIFO high-rate IMU (Gyro)", "index": 8}, {"description": "Raw FIFO high-rate IMU (Accel)", "index": 9}, {"description": "Mavlink tunnel message logging", "index": 10}, {"description": "High rate sensors", "index": 11}], "category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "This integer bitmask controls the set and rates of logged topics. The default allows for general log analysis while keeping the log file size reasonably small. Enabling multiple sets leads to higher bandwidth requirements and larger log files. Set bits true to enable: 0 : Default set (used for general log analysis) 1 : Full rate estimator (EKF2) replay topics 2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data) 3 : Topics for system identification (high rate actuator control and IMU data) 4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) 5 : Debugging topics (debug_*.msg topics, for custom code) 6 : Topics for sensor comparison (low rate raw IMU, Baro and magnetometer data) 7 : Topics for computer vision and collision prevention 8 : Raw FIFO high-rate IMU (Gyro) 9 : Raw FIFO high-rate IMU (Accel) 10: Logging of mavlink tunnel message (useful for payload communication debugging)", "max": 4095, "min": 0, "name": "SDLOG_PROFILE", "rebootRequired": true, "shortDesc": "Logging topic profile (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets", "max": 1000, "min": -1000, "name": "SDLOG_UTC_OFFSET", "shortDesc": "UTC offset (unit: min)", "type": "Int32", "units": "min"}, {"category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "If set to 1, add an ID to the log, which uniquely identifies the vehicle", "name": "SDLOG_UUID", "shortDesc": "Log UUID", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 60.0, "group": "SITL", "increment": 1.0, "max": 86400.0, "min": 1.0, "name": "SIM_BAT_DRAIN", "shortDesc": "Simulator Battery drain interval", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "SITL", "longDesc": "Enable or disable the internal battery simulation. This is useful\nwhen the battery is simulated externally and interfaced with PX4\nthrough MAVLink for example.", "name": "SIM_BAT_ENABLE", "shortDesc": "Simulator Battery enabled", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 50.0, "group": "SITL", "increment": 0.1, "longDesc": "Can be used to alter the battery level during SITL- or HITL-simulation on the fly.\nParticularly useful for testing different low-battery behaviour.", "max": 100.0, "min": 0.0, "name": "SIM_BAT_MIN_PCT", "shortDesc": "Simulator Battery minimal percentage", "type": "Float", "units": "%"}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC0_ID", "shortDesc": "Accelerometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC0_PRIO", "shortDesc": "Accelerometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC0_ROT", "shortDesc": "Accelerometer 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_XOFF", "shortDesc": "Accelerometer 0 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_XSCALE", "shortDesc": "Accelerometer 0 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_YOFF", "shortDesc": "Accelerometer 0 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_YSCALE", "shortDesc": "Accelerometer 0 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_ZOFF", "shortDesc": "Accelerometer 0 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_ZSCALE", "shortDesc": "Accelerometer 0 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC1_ID", "shortDesc": "Accelerometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC1_PRIO", "shortDesc": "Accelerometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC1_ROT", "shortDesc": "Accelerometer 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_XOFF", "shortDesc": "Accelerometer 1 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_XSCALE", "shortDesc": "Accelerometer 1 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_YOFF", "shortDesc": "Accelerometer 1 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_YSCALE", "shortDesc": "Accelerometer 1 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_ZOFF", "shortDesc": "Accelerometer 1 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_ZSCALE", "shortDesc": "Accelerometer 1 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC2_ID", "shortDesc": "Accelerometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC2_PRIO", "shortDesc": "Accelerometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC2_ROT", "shortDesc": "Accelerometer 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_XOFF", "shortDesc": "Accelerometer 2 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_XSCALE", "shortDesc": "Accelerometer 2 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_YOFF", "shortDesc": "Accelerometer 2 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_YSCALE", "shortDesc": "Accelerometer 2 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_ZOFF", "shortDesc": "Accelerometer 2 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_ZSCALE", "shortDesc": "Accelerometer 2 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC3_ID", "shortDesc": "Accelerometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC3_PRIO", "shortDesc": "Accelerometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC3_ROT", "shortDesc": "Accelerometer 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_XOFF", "shortDesc": "Accelerometer 3 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_XSCALE", "shortDesc": "Accelerometer 3 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_YOFF", "shortDesc": "Accelerometer 3 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_YSCALE", "shortDesc": "Accelerometer 3 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_ZOFF", "shortDesc": "Accelerometer 3 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_ZSCALE", "shortDesc": "Accelerometer 3 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO0_ID", "shortDesc": "Barometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO0_OFF", "shortDesc": "Barometer 0 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO0_PRIO", "shortDesc": "Barometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO1_ID", "shortDesc": "Barometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO1_OFF", "shortDesc": "Barometer 1 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO1_PRIO", "shortDesc": "Barometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO2_ID", "shortDesc": "Barometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO2_OFF", "shortDesc": "Barometer 2 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO2_PRIO", "shortDesc": "Barometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO3_ID", "shortDesc": "Barometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO3_OFF", "shortDesc": "Barometer 3 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO3_PRIO", "shortDesc": "Barometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO0_ID", "shortDesc": "Gyroscope 0 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO0_PRIO", "shortDesc": "Gyroscope 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO0_ROT", "shortDesc": "Gyroscope 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_XOFF", "shortDesc": "Gyroscope 0 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_YOFF", "shortDesc": "Gyroscope 0 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_ZOFF", "shortDesc": "Gyroscope 0 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO1_ID", "shortDesc": "Gyroscope 1 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO1_PRIO", "shortDesc": "Gyroscope 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO1_ROT", "shortDesc": "Gyroscope 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_XOFF", "shortDesc": "Gyroscope 1 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_YOFF", "shortDesc": "Gyroscope 1 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_ZOFF", "shortDesc": "Gyroscope 1 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO2_ID", "shortDesc": "Gyroscope 2 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO2_PRIO", "shortDesc": "Gyroscope 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO2_ROT", "shortDesc": "Gyroscope 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_XOFF", "shortDesc": "Gyroscope 2 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_YOFF", "shortDesc": "Gyroscope 2 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_ZOFF", "shortDesc": "Gyroscope 2 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO3_ID", "shortDesc": "Gyroscope 3 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO3_PRIO", "shortDesc": "Gyroscope 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO3_ROT", "shortDesc": "Gyroscope 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_XOFF", "shortDesc": "Gyroscope 3 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_YOFF", "shortDesc": "Gyroscope 3 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_ZOFF", "shortDesc": "Gyroscope 3 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG0_ID", "shortDesc": "Magnetometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_PITCH", "shortDesc": "Magnetometer 0 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG0_PRIO", "shortDesc": "Magnetometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_ROLL", "shortDesc": "Magnetometer 0 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.\nSet to \"Custom Euler Angle\" to define the rotation using CAL_MAG0_ROLL, CAL_MAG0_PITCH and CAL_MAG0_YAW.", "max": 100, "min": -1, "name": "CAL_MAG0_ROT", "shortDesc": "Magnetometer 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nX component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG0_XCOMP", "shortDesc": "Magnetometer 0 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_XODIAG", "shortDesc": "Magnetometer 0 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_XOFF", "shortDesc": "Magnetometer 0 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_XSCALE", "shortDesc": "Magnetometer 0 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_YAW", "shortDesc": "Magnetometer 0 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nY component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG0_YCOMP", "shortDesc": "Magnetometer 0 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_YODIAG", "shortDesc": "Magnetometer 0 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_YOFF", "shortDesc": "Magnetometer 0 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_YSCALE", "shortDesc": "Magnetometer 0 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nZ component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG0_ZCOMP", "shortDesc": "Magnetometer 0 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_ZODIAG", "shortDesc": "Magnetometer 0 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_ZOFF", "shortDesc": "Magnetometer 0 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_ZSCALE", "shortDesc": "Magnetometer 0 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG1_ID", "shortDesc": "Magnetometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_PITCH", "shortDesc": "Magnetometer 1 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG1_PRIO", "shortDesc": "Magnetometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_ROLL", "shortDesc": "Magnetometer 1 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.\nSet to \"Custom Euler Angle\" to define the rotation using CAL_MAG1_ROLL, CAL_MAG1_PITCH and CAL_MAG1_YAW.", "max": 100, "min": -1, "name": "CAL_MAG1_ROT", "shortDesc": "Magnetometer 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nX component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG1_XCOMP", "shortDesc": "Magnetometer 1 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_XODIAG", "shortDesc": "Magnetometer 1 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_XOFF", "shortDesc": "Magnetometer 1 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_XSCALE", "shortDesc": "Magnetometer 1 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_YAW", "shortDesc": "Magnetometer 1 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nY component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG1_YCOMP", "shortDesc": "Magnetometer 1 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_YODIAG", "shortDesc": "Magnetometer 1 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_YOFF", "shortDesc": "Magnetometer 1 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_YSCALE", "shortDesc": "Magnetometer 1 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nZ component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG1_ZCOMP", "shortDesc": "Magnetometer 1 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_ZODIAG", "shortDesc": "Magnetometer 1 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_ZOFF", "shortDesc": "Magnetometer 1 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_ZSCALE", "shortDesc": "Magnetometer 1 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG2_ID", "shortDesc": "Magnetometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_PITCH", "shortDesc": "Magnetometer 2 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG2_PRIO", "shortDesc": "Magnetometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_ROLL", "shortDesc": "Magnetometer 2 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.\nSet to \"Custom Euler Angle\" to define the rotation using CAL_MAG2_ROLL, CAL_MAG2_PITCH and CAL_MAG2_YAW.", "max": 100, "min": -1, "name": "CAL_MAG2_ROT", "shortDesc": "Magnetometer 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nX component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG2_XCOMP", "shortDesc": "Magnetometer 2 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_XODIAG", "shortDesc": "Magnetometer 2 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_XOFF", "shortDesc": "Magnetometer 2 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_XSCALE", "shortDesc": "Magnetometer 2 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_YAW", "shortDesc": "Magnetometer 2 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nY component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG2_YCOMP", "shortDesc": "Magnetometer 2 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_YODIAG", "shortDesc": "Magnetometer 2 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_YOFF", "shortDesc": "Magnetometer 2 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_YSCALE", "shortDesc": "Magnetometer 2 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nZ component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG2_ZCOMP", "shortDesc": "Magnetometer 2 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_ZODIAG", "shortDesc": "Magnetometer 2 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_ZOFF", "shortDesc": "Magnetometer 2 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_ZSCALE", "shortDesc": "Magnetometer 2 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG3_ID", "shortDesc": "Magnetometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_PITCH", "shortDesc": "Magnetometer 3 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG3_PRIO", "shortDesc": "Magnetometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_ROLL", "shortDesc": "Magnetometer 3 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.\nSet to \"Custom Euler Angle\" to define the rotation using CAL_MAG3_ROLL, CAL_MAG3_PITCH and CAL_MAG3_YAW.", "max": 100, "min": -1, "name": "CAL_MAG3_ROT", "shortDesc": "Magnetometer 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nX component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG3_XCOMP", "shortDesc": "Magnetometer 3 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_XODIAG", "shortDesc": "Magnetometer 3 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_XOFF", "shortDesc": "Magnetometer 3 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_XSCALE", "shortDesc": "Magnetometer 3 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_YAW", "shortDesc": "Magnetometer 3 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nY component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG3_YCOMP", "shortDesc": "Magnetometer 3 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_YODIAG", "shortDesc": "Magnetometer 3 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_YOFF", "shortDesc": "Magnetometer 3 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_YSCALE", "shortDesc": "Magnetometer 3 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nZ component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG3_ZCOMP", "shortDesc": "Magnetometer 3 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_ZODIAG", "shortDesc": "Magnetometer 3 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_ZOFF", "shortDesc": "Magnetometer 3 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_ZSCALE", "shortDesc": "Magnetometer 3 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "name": "CAL_MAG_COMP_TYP", "shortDesc": "Type of magnetometer compensation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Throttle-based compensation", "value": 1}, {"description": "Current-based compensation (battery_status instance 0)", "value": 2}, {"description": "Current-based compensation (battery_status instance 1)", "value": 3}]}, {"category": "Standard", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Pick the appropriate scaling from the datasheet.\nthis number defines the (linear) conversion from voltage\nto Pascal (pa). For the MPXV7002DP this is 1000.\nNOTE: If the sensor always registers zero, try switching\nthe static and dynamic tubes.", "name": "SENS_DPRES_ANSC", "shortDesc": "Differential pressure sensor analog scaling", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "The offset (zero-reading) in Pascal", "name": "SENS_DPRES_OFF", "shortDesc": "Differential pressure sensor offset", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Reverse the raw measurements of all differential pressure sensors.\nThis can be enabled if the sensors have static and dynamic ports swapped.", "name": "SENS_DPRES_REV", "shortDesc": "Reverse differential pressure sensor readings", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 100.0, "group": "Sensor Calibration", "increment": 0.1, "longDesc": "This parameter defines the maximum distance from ground at which the optical flow sensor operates reliably.\nThe height setpoint will be limited to be no greater than this value when the navigation system\nis completely reliant on optical flow data and the height above ground estimate is valid.\nThe sensor may be usable above this height, but accuracy will progressively degrade.", "max": 100.0, "min": 1.0, "name": "SENS_FLOW_MAXHGT", "shortDesc": "Maximum height above ground when reliant on optical flow", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 8.0, "group": "Sensor Calibration", "longDesc": "Optical flow data will not fused by the estimators if the magnitude of the flow rate exceeds this value and\ncontrol loops will be instructed to limit ground speed such that the flow rate produced by movement over ground\nis less than 50% of this value.", "min": 1.0, "name": "SENS_FLOW_MAXR", "shortDesc": "Magnitude of maximum angular flow rate reliably measurable by the optical flow sensor", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Sensor Calibration", "increment": 0.1, "longDesc": "This parameter defines the minimum distance from ground at which the optical flow sensor operates reliably.\nThe sensor may be usable below this height, but accuracy will progressively reduce to loss of focus.", "max": 1.0, "min": 0.0, "name": "SENS_FLOW_MINHGT", "shortDesc": "Minimum height above ground when reliant on optical flow", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "Model with Pitot\nCAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed.\nCAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor.\nModel without Pitot (1.5 mm tubes)\nCAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed.\nCAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor.\nTube Pressure Drop\nCAL_AIR_TUBED_MM: Diameter in mm of the pitot and tubes, must have the same diameter.\nCAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor and the static + dynamic port length of the pitot.", "name": "CAL_AIR_CMODEL", "shortDesc": "Airspeed sensor compensation model for the SDP3x", "type": "Int32", "values": [{"description": "Model with Pitot", "value": 0}, {"description": "Model without Pitot (1.5 mm tubes)", "value": 1}, {"description": "Tube Pressure Drop", "value": 2}]}, {"category": "Standard", "default": 1.5, "group": "Sensors", "max": 100.0, "min": 1.5, "name": "CAL_AIR_TUBED_MM", "shortDesc": "Airspeed sensor tube diameter. Only used for the Tube Pressure Drop Compensation", "type": "Float", "units": "mm"}, {"category": "Standard", "default": 0.2, "group": "Sensors", "longDesc": "See the CAL_AIR_CMODEL explanation on how this parameter should be set.", "max": 2.0, "min": 0.01, "name": "CAL_AIR_TUBELEN", "shortDesc": "Airspeed sensor tube length", "type": "Float", "units": "m"}, {"category": "Developer", "default": 63, "group": "Sensors", "longDesc": "Use SENS_MAG_SIDES instead", "name": "CAL_MAG_SIDES", "shortDesc": "For legacy QGC support only", "type": "Int32"}, {"category": "Standard", "default": 30.0, "group": "Sensors", "longDesc": "The cutoff frequency for the 2nd order butterworth filter on the primary accelerometer.\nThis only affects the signal sent to the controllers, not the estimators. 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_ACCEL_CUTOFF", "rebootRequired": true, "shortDesc": "Low pass filter cutoff frequency for accel", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The cutoff frequency for the 2nd order butterworth filter used on\nthe time derivative of the measured angular velocity, also known as\nthe D-term filter in the rate controller. The D-term uses the derivative of\nthe rate and thus is the most susceptible to noise. Therefore, using\na D-term filter allows to increase IMU_GYRO_CUTOFF, which\nleads to reduced control latency and permits to increase the P gains.\nA value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_DGYRO_CUTOFF", "rebootRequired": true, "shortDesc": "Cutoff frequency for angular acceleration (D-Term filter)", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 1, "group": "Sensors", "name": "IMU_GYRO_CAL_EN", "rebootRequired": true, "shortDesc": "IMU gyro auto calibration enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Sensors", "increment": 0.1, "longDesc": "The cutoff frequency for the 2nd order butterworth filter on the primary gyro.\nThis only affects the angular velocity sent to the controllers, not the estimators.\nIt applies also to the angular acceleration (D-Term filter), see IMU_DGYRO_CUTOFF.\nA value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_CUTOFF", "rebootRequired": true, "shortDesc": "Low pass filter cutoff frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "Sensors", "increment": 0.1, "longDesc": "Bandwidth per notch filter when using dynamic notch filtering with ESC RPM.", "max": 30.0, "min": 5.0, "name": "IMU_GYRO_DNF_BW", "shortDesc": "IMU gyro ESC notch filter bandwidth", "type": "Float", "units": "Hz"}, {"bitmask": [{"description": "ESC RPM", "index": 0}, {"description": "FFT", "index": 1}], "category": "Standard", "default": 0, "group": "Sensors", "longDesc": "Enable bank of dynamically updating notch filters.\nRequires ESC RPM feedback or onboard FFT (IMU_GYRO_FFT_EN).", "max": 3, "min": 0, "name": "IMU_GYRO_DNF_EN", "shortDesc": "IMU gyro dynamic notch filtering", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "Sensors", "longDesc": "ESC RPM number of harmonics (multiples of RPM) for ESC RPM dynamic notch filtering.", "max": 7, "min": 1, "name": "IMU_GYRO_DNF_HMC", "shortDesc": "IMU gyro dynamic notch filter harmonics", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "Sensors", "increment": 0.1, "longDesc": "Minimum notch filter frequency in Hz.", "name": "IMU_GYRO_DNF_MIN", "shortDesc": "IMU gyro dynamic notch filter minimum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "name": "IMU_GYRO_FFT_EN", "rebootRequired": true, "shortDesc": "IMU gyro FFT enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 512, "group": "Sensors", "name": "IMU_GYRO_FFT_LEN", "rebootRequired": true, "shortDesc": "IMU gyro FFT length", "type": "Int32", "units": "Hz", "values": [{"description": "256", "value": 256}, {"description": "512", "value": 512}, {"description": "1024", "value": 1024}, {"description": "4096", "value": 4096}]}, {"category": "Standard", "default": 150.0, "group": "Sensors", "max": 1000.0, "min": 1.0, "name": "IMU_GYRO_FFT_MAX", "rebootRequired": true, "shortDesc": "IMU gyro FFT maximum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 30.0, "group": "Sensors", "max": 1000.0, "min": 1.0, "name": "IMU_GYRO_FFT_MIN", "rebootRequired": true, "shortDesc": "IMU gyro FFT minimum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 10.0, "group": "Sensors", "max": 30.0, "min": 1.0, "name": "IMU_GYRO_FFT_SNR", "shortDesc": "IMU gyro FFT SNR", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The frequency width of the stop band for the 2nd order notch filter on the primary gyro.\nSee \"IMU_GYRO_NF0_FRQ\" to activate the filter and to set the notch frequency.\nApplies to both angular velocity and angular acceleration sent to the controllers.", "max": 100.0, "min": 0.0, "name": "IMU_GYRO_NF0_BW", "rebootRequired": true, "shortDesc": "Notch filter bandwidth for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "increment": 0.1, "longDesc": "The center frequency for the 2nd order notch filter on the primary gyro.\nThis filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency.\nThis only affects the signal sent to the controllers, not the estimators.\nApplies to both angular velocity and angular acceleration sent to the controllers.\nSee \"IMU_GYRO_NF0_BW\" to set the bandwidth of the filter.\nA value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_NF0_FRQ", "rebootRequired": true, "shortDesc": "Notch filter frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The frequency width of the stop band for the 2nd order notch filter on the primary gyro.\nSee \"IMU_GYRO_NF1_FRQ\" to activate the filter and to set the notch frequency.\nApplies to both angular velocity and angular acceleration sent to the controllers.", "max": 100.0, "min": 0.0, "name": "IMU_GYRO_NF1_BW", "rebootRequired": true, "shortDesc": "Notch filter 1 bandwidth for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "increment": 0.1, "longDesc": "The center frequency for the 2nd order notch filter on the primary gyro.\nThis filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency.\nThis only affects the signal sent to the controllers, not the estimators.\nApplies to both angular velocity and angular acceleration sent to the controllers.\nSee \"IMU_GYRO_NF1_BW\" to set the bandwidth of the filter.\nA value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_NF1_FRQ", "rebootRequired": true, "shortDesc": "Notch filter 2 frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 400, "group": "Sensors", "longDesc": "The maximum rate the gyro control data (vehicle_angular_velocity) will be\nallowed to publish at. This is the loop rate for the rate controller and outputs.\nNote: sensor data is always read and filtered at the full raw rate (eg commonly 8 kHz) regardless of this setting.", "max": 2000, "min": 100, "name": "IMU_GYRO_RATEMAX", "rebootRequired": true, "shortDesc": "Gyro control data maximum publication rate (inner loop rate)", "type": "Int32", "units": "Hz", "values": [{"description": "100 Hz", "value": 100}, {"description": "250 Hz", "value": 250}, {"description": "400 Hz", "value": 400}, {"description": "800 Hz", "value": 800}, {"description": "1000 Hz", "value": 1000}, {"description": "2000 Hz", "value": 2000}]}, {"category": "Standard", "default": 200, "group": "Sensors", "longDesc": "The rate at which raw IMU data is integrated to produce delta angles and delta velocities.\nRecommended to set this to a multiple of the estimator update period (currently 10 ms for ekf2).", "max": 1000, "min": 100, "name": "IMU_INTEG_RATE", "rebootRequired": true, "shortDesc": "IMU integration rate", "type": "Int32", "units": "Hz", "values": [{"description": "100 Hz", "value": 100}, {"description": "200 Hz", "value": 200}, {"description": "250 Hz", "value": 250}, {"description": "400 Hz", "value": 400}]}, {"category": "Standard", "default": 1013.25, "group": "Sensors", "max": 1500.0, "min": 500.0, "name": "SENS_BARO_QNH", "shortDesc": "QNH for barometer", "type": "Float", "units": "hPa"}, {"category": "Standard", "default": 20.0, "group": "Sensors", "longDesc": "Barometric air data maximum publication rate. This is an upper bound,\nactual barometric data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_BARO_RATE", "shortDesc": "Baro max rate", "type": "Float", "units": "Hz"}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically calibrate barometer based on the GNSS height", "name": "SENS_BAR_AUTOCAL", "shortDesc": "Barometer auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "This parameter defines the rotation of the FMU board relative to the platform.", "max": 40, "min": -1, "name": "SENS_BOARD_ROT", "rebootRequired": true, "shortDesc": "Board rotation", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "longDesc": "Rotation from flight controller board to vehicle body frame.\nThis parameter gets set during the \"level horizon\" calibration or can be\nset manually.", "max": 45.0, "min": -45.0, "name": "SENS_BOARD_X_OFF", "shortDesc": "Board rotation X (roll) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "longDesc": "Rotation from flight controller board to vehicle body frame.\nThis parameter gets set during the \"level horizon\" calibration or can be\nset manually.", "max": 45.0, "min": -45.0, "name": "SENS_BOARD_Y_OFF", "shortDesc": "Board rotation Y (pitch) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "longDesc": "Rotation from flight controller board to vehicle body frame.\nHas to be set manually (not set by any calibration).", "max": 45.0, "min": -45.0, "name": "SENS_BOARD_Z_OFF", "shortDesc": "Board rotation Z (yaw) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_AGPSIM", "rebootRequired": true, "shortDesc": "Simulate Aux Global Position (AGP)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_ARSPDSIM", "rebootRequired": true, "shortDesc": "Enable simulated airspeed sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_BAROSIM", "rebootRequired": true, "shortDesc": "Enable simulated barometer sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_GPSSIM", "rebootRequired": true, "shortDesc": "Enable simulated GPS sinstance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_MAGSIM", "rebootRequired": true, "shortDesc": "Enable simulated magnetometer sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": -1, "group": "Sensors", "name": "SENS_EN_THERMAL", "shortDesc": "Thermal control of sensor temperature", "type": "Int32", "values": [{"description": "Thermal control unavailable", "value": -1}, {"description": "Thermal control off", "value": 0}, {"description": "Thermal control enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Probe for optional external I2C devices.", "name": "SENS_EXT_I2C_PRB", "shortDesc": "External I2C probe", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 70.0, "group": "Sensors", "longDesc": "Optical flow data maximum publication rate. This is an upper bound,\nactual optical flow data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_FLOW_RATE", "rebootRequired": true, "shortDesc": "Optical flow max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "This parameter defines the yaw rotation of the optical flow relative to the vehicle body frame.\nZero rotation is defined as X on flow board pointing towards front of vehicle.", "name": "SENS_FLOW_ROT", "shortDesc": "Optical flow rotation", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Sensors", "max": 1.5, "min": 0.5, "name": "SENS_FLOW_SCALE", "shortDesc": "Optical flow scale factor", "type": "Float"}, {"bitmask": [{"description": "use speed accuracy", "index": 0}, {"description": "use hpos accuracy", "index": 1}, {"description": "use vpos accuracy", "index": 2}], "category": "Standard", "default": 7, "group": "Sensors", "longDesc": "Set bits in the following positions to set which GPS accuracy metrics will be used to calculate the blending weight. Set to zero to disable and always used first GPS instance.\n0 : Set to true to use speed accuracy\n1 : Set to true to use horizontal position accuracy\n2 : Set to true to use vertical position accuracy", "max": 7, "min": 0, "name": "SENS_GPS_MASK", "shortDesc": "Multi GPS Blending Control Mask", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "When no blending is active, this defines the preferred GPS receiver instance.\nThe GPS selection logic waits until the primary receiver is available to\nsend data to the EKF even if a secondary instance is already available.\nThe secondary instance is then only used if the primary one times out.\nAccepted values:\n-1 : Auto (equal priority for all instances)\n0 : Main serial GPS instance\n1 : Secondary serial GPS instance\n2-127 : UAVCAN module node ID\nThis parameter has no effect if blending is active.", "max": 127, "min": -1, "name": "SENS_GPS_PRIME", "shortDesc": "Multi GPS primary instance", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Sensors", "longDesc": "Sets the longest time constant that will be applied to the calculation of GPS position and height offsets used to correct data from multiple GPS data for steady state position differences.", "max": 100.0, "min": 1.0, "name": "SENS_GPS_TAU", "shortDesc": "Multi GPS Blending Time Constant", "type": "Float", "units": "s"}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically initialize IMU (accel/gyro) calibration from bias estimates if available.", "name": "SENS_IMU_AUTOCAL", "shortDesc": "IMU auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Notify the user if the IMU is clipping", "name": "SENS_IMU_CLPNOTI", "shortDesc": "IMU notify clipping", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "name": "SENS_IMU_MODE", "rebootRequired": true, "shortDesc": "Sensors hub IMU mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Publish primary IMU selection", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "For systems with an external barometer, this should be set to false to make sure that the external is used.", "name": "SENS_INT_BARO_EN", "rebootRequired": true, "shortDesc": "Enable internal barometers", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically initialize magnetometer calibration from bias estimate if available.", "name": "SENS_MAG_AUTOCAL", "shortDesc": "Magnetometer auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Sensors", "longDesc": "During calibration attempt to automatically determine the rotation of external magnetometers.", "name": "SENS_MAG_AUTOROT", "shortDesc": "Automatically set external rotations", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "name": "SENS_MAG_MODE", "rebootRequired": true, "shortDesc": "Sensors hub mag mode", "type": "Int32", "values": [{"description": "Publish all magnetometers", "value": 0}, {"description": "Publish primary magnetometer", "value": 1}]}, {"category": "Standard", "default": 15.0, "group": "Sensors", "longDesc": "Magnetometer data maximum publication rate. This is an upper bound,\nactual magnetometer data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_MAG_RATE", "rebootRequired": true, "shortDesc": "Magnetometer max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 63, "group": "Sensors", "longDesc": "If set to two side calibration, only the offsets are estimated, the scale\ncalibration is left unchanged. Thus an initial six side calibration is\nrecommended.\nBits:\nORIENTATION_TAIL_DOWN = 1\nORIENTATION_NOSE_DOWN = 2\nORIENTATION_LEFT = 4\nORIENTATION_RIGHT = 8\nORIENTATION_UPSIDE_DOWN = 16\nORIENTATION_RIGHTSIDE_UP = 32", "max": 63, "min": 34, "name": "SENS_MAG_SIDES", "shortDesc": "Bitfield selecting mag sides for calibration", "type": "Int32", "values": [{"description": "Two side calibration", "value": 34}, {"description": "Three side calibration", "value": 38}, {"description": "Six side calibration", "value": 63}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SIM_ARSPD_FAIL", "rebootRequired": true, "shortDesc": "Dynamically simulate failure of airspeed sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Septentrio", "longDesc": "By default, the receiver is automatically configured. Sometimes it may be used for multiple purposes.\nIf the offered parameters aren't sufficient, this parameter can be disabled to have full control of the receiver configuration.\nA good way to use this is to enable automatic configuration, let the receiver be configured, and then disable it to make manual adjustments.", "name": "SEP_AUTO_CONFIG", "rebootRequired": true, "shortDesc": "Toggle automatic receiver configuration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"bitmask": [{"description": "GPS", "index": 0}, {"description": "GLONASS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "SBAS", "index": 3}, {"description": "BeiDou", "index": 4}], "category": "Standard", "default": 0, "group": "Septentrio", "longDesc": "Choice of which constellations the receiver should use for PVT computation.\nWhen this is 0, the constellation usage isn't changed.", "max": 63, "min": 0, "name": "SEP_CONST_USAGE", "rebootRequired": true, "shortDesc": "Usage of different constellations", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Septentrio", "longDesc": "Log raw communication between the driver and connected receivers.\nFor example, \"To receiver\" will log all commands and corrections sent by the driver to the receiver.", "max": 3, "min": 0, "name": "SEP_DUMP_COMM", "shortDesc": "Log GPS communication data", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "From receiver", "value": 1}, {"description": "To receiver", "value": 2}, {"description": "Both", "value": 3}]}, {"category": "Standard", "default": 0, "group": "Septentrio", "longDesc": "Setup and expected use of the hardware.\n- Default: Use two receivers as completely separate instances.\n- Moving base: Use two receivers in a rover & moving base setup for heading.", "max": 1, "min": 0, "name": "SEP_HARDW_SETUP", "rebootRequired": true, "shortDesc": "Setup and expected use of the hardware", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Moving base", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Septentrio", "longDesc": "When the receiver is already set up to log data, this decides whether extra logged data should be added or overwrite existing data.", "name": "SEP_LOG_FORCE", "rebootRequired": true, "shortDesc": "Whether to overwrite or add to existing logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Septentrio", "longDesc": "Select the frequency at which the connected receiver should log data to its internal storage.", "max": 10, "min": 0, "name": "SEP_LOG_HZ", "rebootRequired": true, "shortDesc": "Logging frequency for the receiver", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "0.1 Hz", "value": 1}, {"description": "0.2 Hz", "value": 2}, {"description": "0.5 Hz", "value": 3}, {"description": "1 Hz", "value": 4}, {"description": "2 Hz", "value": 5}, {"description": "5 Hz", "value": 6}, {"description": "10 Hz", "value": 7}, {"description": "20 Hz", "value": 8}, {"description": "25 Hz", "value": 9}, {"description": "50 Hz", "value": 10}]}, {"category": "Standard", "default": 2, "group": "Septentrio", "longDesc": "Select the level of detail that needs to be logged by the receiver.", "max": 3, "min": 0, "name": "SEP_LOG_LEVEL", "rebootRequired": true, "shortDesc": "Logging level for the receiver", "type": "Int32", "values": [{"description": "Lite", "value": 0}, {"description": "Basic", "value": 1}, {"description": "Default", "value": 2}, {"description": "Full", "value": 3}]}, {"category": "Standard", "default": 1, "group": "Septentrio", "longDesc": "The output frequency of the main SBF blocks needed for PVT information.", "max": 3, "min": 0, "name": "SEP_OUTP_HZ", "rebootRequired": true, "shortDesc": "Output frequency of main SBF blocks", "type": "Int32", "values": [{"description": "5 Hz", "value": 0}, {"description": "10 Hz", "value": 1}, {"description": "20 Hz", "value": 2}, {"description": "25 Hz", "value": 3}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Septentrio", "longDesc": "Vertical offsets can be compensated for by adjusting the Pitch offset.\nNote that this can be interpreted as the \"roll\" angle in case the antennas are aligned along the perpendicular axis.\nThis occurs in situations where the two antenna ARPs may not be exactly at the same height in the vehicle reference frame.\nSince pitch is defined as the right-handed rotation about the vehicle Y axis,\na situation where the main antenna is mounted lower than the aux antenna (assuming the default antenna setup) will result in a positive pitch.", "max": 90.0, "min": -90.0, "name": "SEP_PITCH_OFFS", "rebootRequired": true, "shortDesc": "Pitch offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Septentrio", "longDesc": "Enable publication of satellite info (ORB_ID(satellite_info)) if possible.", "name": "SEP_SAT_INFO", "rebootRequired": true, "shortDesc": "Enable sat info", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "Septentrio", "longDesc": "The stream the autopilot sets up on the receiver to output the logging data.\nSet this to another value if the default stream is already used for another purpose.", "max": 10, "min": 1, "name": "SEP_STREAM_LOG", "rebootRequired": true, "shortDesc": "Logging stream used during automatic configuration", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Septentrio", "longDesc": "The stream the autopilot sets up on the receiver to output the main data.\nSet this to another value if the default stream is already used for another purpose.", "max": 10, "min": 1, "name": "SEP_STREAM_MAIN", "rebootRequired": true, "shortDesc": "Main stream used during automatic configuration", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Septentrio", "longDesc": "Heading offset angle for dual antenna GPS setups that support heading estimation.\nSet this to 0 if the antennas are parallel to the forward-facing direction\nof the vehicle and the rover antenna is in front.\nThe offset angle increases clockwise.\nSet this to 90 if the rover antenna is placed on the\nright side of the vehicle and the moving base antenna is on the left side.", "max": 360.0, "min": -360.0, "name": "SEP_YAW_OFFS", "rebootRequired": true, "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 4, "default": 100.0, "group": "Simulation In Hardware", "increment": 0.01, "max": 1000.0, "min": 0.0, "name": "SIH_DISTSNSR_MAX", "shortDesc": "distance sensor maximum range", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.01, "max": 10.0, "min": 0.0, "name": "SIH_DISTSNSR_MIN", "shortDesc": "distance sensor minimum range", "type": "Float", "units": "m"}, {"category": "Standard", "default": -1.0, "group": "Simulation In Hardware", "longDesc": "Absolute value superior to 10000 will disable distance sensor", "name": "SIH_DISTSNSR_OVR", "shortDesc": "if >= 0 the distance sensor measures will be overridden by this value", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nIt represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IXX", "shortDesc": "Vehicle inertia about X axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nThis value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IXY", "shortDesc": "Vehicle cross term inertia xy", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nThis value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IXZ", "shortDesc": "Vehicle cross term inertia xz", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nIt represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IYY", "shortDesc": "Vehicle inertia about Y axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nThis value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IYZ", "shortDesc": "Vehicle cross term inertia yz", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nIt represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IZZ", "shortDesc": "Vehicle inertia about Z axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "Physical coefficient representing the friction with air particules.\nThe greater this value, the slower the quad will move.\nDrag force function of velocity: D=-KDV*V.\nThe maximum freefall velocity can be computed as V=10*MASS/KDV [m/s]", "min": 0.0, "name": "SIH_KDV", "shortDesc": "First order drag coefficient", "type": "Float", "units": "N/(m/s)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "Physical coefficient representing the friction with air particules during rotations.\nThe greater this value, the slower the quad will rotate.\nAerodynamic moment function of body rate: Ma=-KDW*W_B.\nThis value can be set to 0 if unknown.", "min": 0.0, "name": "SIH_KDW", "shortDesc": "First order angular damper coefficient", "type": "Float", "units": "Nm/(rad/s)"}, {"category": "Standard", "decimalPlaces": 2, "default": 489.4, "group": "Simulation In Hardware", "increment": 0.01, "longDesc": "This value represents the Above Mean Sea Level (AMSL) altitude where the simulation begins.\nIf using FlightGear as a visual animation,\nthis value can be tweaked such that the vehicle lies on the ground at takeoff.\nLAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others\nto represent a physical ground location on Earth.", "max": 8848.0, "min": -420.0, "name": "SIH_LOC_H0", "shortDesc": "Initial AMSL ground altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 47.397742, "group": "Simulation In Hardware", "longDesc": "This value represents the North-South location on Earth where the simulation begins.\nLAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others\nto represent a physical ground location on Earth.", "max": 90.0, "min": -90.0, "name": "SIH_LOC_LAT0", "shortDesc": "Initial geodetic latitude", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 8.545594, "group": "Simulation In Hardware", "longDesc": "This value represents the East-West location on Earth where the simulation begins.\nLAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others\nto represent a physical ground location on Earth.", "max": 180.0, "min": -180.0, "name": "SIH_LOC_LON0", "shortDesc": "Initial geodetic longitude", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the arm length generating the pitching moment\nThis value can be measured with a ruler.\nThis corresponds to half the distance between the front and rear motors.", "min": 0.0, "name": "SIH_L_PITCH", "shortDesc": "Pitch arm length", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the arm length generating the rolling moment\nThis value can be measured with a ruler.\nThis corresponds to half the distance between the left and right motors.", "min": 0.0, "name": "SIH_L_ROLL", "shortDesc": "Roll arm length", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Simulation In Hardware", "increment": 0.1, "longDesc": "This value can be measured by weighting the quad on a scale.", "min": 0.0, "name": "SIH_MASS", "shortDesc": "Vehicle mass", "type": "Float", "units": "kg"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the maximum torque delivered by one propeller\nwhen the motor is running at full speed.\nThis value is usually about few percent of the maximum thrust force.", "min": 0.0, "name": "SIH_Q_MAX", "shortDesc": "Max propeller torque", "type": "Float", "units": "Nm"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "Simulation In Hardware", "increment": 0.5, "longDesc": "This is the maximum force delivered by one propeller\nwhen the motor is running at full speed.\nThis value is usually about 5 times the mass of the quadrotor.", "min": 0.0, "name": "SIH_T_MAX", "shortDesc": "Max propeller thrust force", "type": "Float", "units": "N"}, {"category": "Standard", "default": 0.05, "group": "Simulation In Hardware", "longDesc": "the time taken for the thruster to step from 0 to 100% should be about 4 times tau", "name": "SIH_T_TAU", "shortDesc": "thruster time constant tau", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Simulation In Hardware", "name": "SIH_VEHICLE_TYPE", "rebootRequired": true, "shortDesc": "Vehicle type", "type": "Int32", "values": [{"description": "Quadcopter", "value": 0}, {"description": "Fixed-Wing", "value": 1}, {"description": "Tailsitter", "value": 2}, {"description": "Standard VTOL", "value": 3}, {"description": "Hexacopter", "value": 4}, {"description": "Rover Ackermann", "value": 5}]}, {"bitmask": [{"description": "Stuck", "index": 0}, {"description": "Drift", "index": 1}], "category": "Standard", "default": 0, "group": "Simulator", "longDesc": "Stuck: freeze the measurement to the current location\nDrift: add a linearly growing bias to the sensor data", "max": 3, "min": 0, "name": "SIM_AGP_FAIL", "shortDesc": "AGP failure mode", "type": "Int32"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_BARO_OFF_P", "shortDesc": "simulated barometer pressure offset", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_BARO_OFF_T", "shortDesc": "simulated barometer temperature offset", "type": "Float", "units": "celcius"}, {"category": "Standard", "default": 10, "group": "Simulator", "max": 50, "min": 0, "name": "SIM_GPS_USED", "shortDesc": "simulated GPS number of satellites used", "type": "Int32"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_X", "shortDesc": "simulated magnetometer X offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_Y", "shortDesc": "simulated magnetometer Y offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_Z", "shortDesc": "simulated magnetometer Z offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "Set to 1 to reset parameters on next system startup (setting defaults).\nPlatform-specific values are used if available.\nRC* parameters are preserved.", "name": "SYS_AUTOCONFIG", "shortDesc": "Automatically configure default values", "type": "Int32", "values": [{"description": "Keep parameters", "value": 0}, {"description": "Reset parameters to airframe defaults", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "CHANGING THIS VALUE REQUIRES A RESTART. Defines the auto-start script used to bootstrap the system.", "max": 9999999, "min": 0, "name": "SYS_AUTOSTART", "rebootRequired": true, "shortDesc": "Auto-start script index", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled, update the bootloader on the next boot.\nWARNING: do not cut the power during an update process, otherwise you will\nhave to recover using some alternative method (e.g. JTAG).\nInstructions:\n- Insert an SD card\n- Enable this parameter\n- Reboot the board (plug the power or send a reboot command)\n- Wait until the board comes back up (or at least 2 minutes)\n- If it does not come back, check the file bootlog.txt on the SD card", "name": "SYS_BL_UPDATE", "rebootRequired": true, "shortDesc": "Bootloader update", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing\n1 : Set to 1 to start a calibration at next boot\nThis parameter is reset to zero when the temperature calibration starts.\ndefault (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_ACCEL", "shortDesc": "Enable auto start of accelerometer thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing\n1 : Set to 1 to start a calibration at next boot\nThis parameter is reset to zero when the temperature calibration starts.\ndefault (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_BARO", "shortDesc": "Enable auto start of barometer thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing\n1 : Set to 1 to start a calibration at next boot\nThis parameter is reset to zero when the temperature calibration starts.\ndefault (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_GYRO", "shortDesc": "Enable auto start of rate gyro thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 24, "group": "System", "longDesc": "A temperature increase greater than this value is required during calibration.\nCalibration will complete for each sensor when the temperature increase above the starting temperature exceeds the value set by SYS_CAL_TDEL.\nIf the temperature rise is insufficient, the calibration will continue indefinitely and the board will need to be repowered to exit.", "min": 10, "name": "SYS_CAL_TDEL", "shortDesc": "Required temperature rise during thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 10, "group": "System", "longDesc": "Temperature calibration will not start if the temperature of any sensor is higher than the value set by SYS_CAL_TMAX.", "name": "SYS_CAL_TMAX", "shortDesc": "Maximum starting temperature for thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 5, "group": "System", "longDesc": "Temperature calibration for each sensor will ignore data if the temperature is lower than the value set by SYS_CAL_TMIN.", "name": "SYS_CAL_TMIN", "shortDesc": "Minimum starting temperature for thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If the board supports persistent storage (i.e., the KConfig variable DATAMAN_PERSISTENT_STORAGE is set),\nthe 'Default storage' backend uses a file on persistent storage. If not supported, this backend uses\nnon-persistent storage in RAM.", "name": "SYS_DM_BACKEND", "rebootRequired": true, "shortDesc": "Dataman storage backend", "type": "Int32", "values": [{"description": "Dataman disabled", "value": -1}, {"description": "Default storage", "value": 0}, {"description": "RAM storage", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled, future sensor calibrations will be stored to /fs/mtd_caldata.\nNote: this is only supported on boards with a separate calibration storage\n/fs/mtd_caldata.", "name": "SYS_FAC_CAL_MODE", "shortDesc": "Enable factory calibration mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "All sensors", "value": 1}, {"description": "All sensors except mag", "value": 2}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled allows MAVLink INJECT_FAILURE commands.\nWARNING: the failures can easily cause crashes and are to be used with caution!", "name": "SYS_FAILURE_EN", "shortDesc": "Enable failure injection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "Disable this if the board has no barometer, such as some of the Omnibus\nF4 SD variants.\nIf disabled, the preflight checks will not check for the presence of a\nbarometer.", "name": "SYS_HAS_BARO", "rebootRequired": true, "shortDesc": "Control if the vehicle has a barometer", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "Disable this if the system has no GPS.\nIf disabled, the sensors hub will not process sensor_gps,\nand GPS will not be available for the rest of the system.", "name": "SYS_HAS_GPS", "rebootRequired": true, "shortDesc": "Control if the vehicle has a GPS", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "0: System has no magnetometer, preflight checks should pass without one.\n1-N: Require the presence of N magnetometer sensors for check to pass.", "name": "SYS_HAS_MAG", "rebootRequired": true, "shortDesc": "Control if and how many magnetometers are expected", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "Set this to 0 if the board has no airspeed sensor.\nIf set to 0, the preflight checks will not check for the presence of an\nairspeed sensor.", "max": 1, "min": 0, "name": "SYS_HAS_NUM_ASPD", "shortDesc": "Control if the vehicle has an airspeed sensor", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "The preflight check will fail if fewer than this number of distance sensors with valid data is present.\nDisable the check with 0.", "max": 4, "min": 0, "name": "SYS_HAS_NUM_DIST", "shortDesc": "Number of distance sensors to check being available", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "The preflight check will fail if fewer than this number of optical flow sensors with valid data are present.", "max": 1, "min": 0, "name": "SYS_HAS_NUM_OF", "shortDesc": "Number of optical flow sensors required to be available", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "While enabled the system will boot in Hardware-In-The-Loop (HITL)\nor Simulation-In-Hardware (SIH) mode and not enable all sensors and checks.\nWhen disabled the same vehicle can be flown normally.\nSet to 'external HITL', if the system should perform as if it were a real\nvehicle (the only difference to a real system is then only the parameter\nvalue, which can be used for log analysis).", "name": "SYS_HITL", "rebootRequired": true, "shortDesc": "Enable HITL/SIH mode on next boot", "type": "Int32", "values": [{"description": "external HITL", "value": -1}, {"description": "HITL and SIH disabled", "value": 0}, {"description": "HITL enabled", "value": 1}, {"description": "SIH enabled", "value": 2}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "This is used internally only: an airframe configuration might set an expected\nparameter version value via PARAM_DEFAULTS_VER. This is checked on bootup\nagainst SYS_PARAM_VER, and if they do not match, parameters are reset and\nreloaded from the airframe configuration.", "min": 0, "name": "SYS_PARAM_VER", "shortDesc": "Parameter version", "type": "Int32"}, {"category": "Standard", "default": 1.0, "group": "System", "longDesc": "Set to 0 to disable, 1 for maximum brightness", "name": "SYS_RGB_MAXBRT", "shortDesc": "RGB Led brightness limit", "type": "Float", "units": "%"}, {"category": "Standard", "default": 1, "group": "System", "name": "SYS_STCK_EN", "shortDesc": "Enable stack checking", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "Testing", "name": "TEST_1", "shortDesc": "TEST_1", "type": "Int32"}, {"category": "Standard", "default": 4, "group": "Testing", "name": "TEST_2", "shortDesc": "TEST_2", "type": "Int32"}, {"category": "Standard", "default": 5.0, "group": "Testing", "name": "TEST_3", "shortDesc": "TEST_3", "type": "Float"}, {"category": "Standard", "default": 0.01, "group": "Testing", "name": "TEST_D", "shortDesc": "TEST_D", "type": "Float"}, {"category": "Standard", "default": 2.0, "group": "Testing", "name": "TEST_DEV", "shortDesc": "TEST_DEV", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_D_LP", "shortDesc": "TEST_D_LP", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_HP", "shortDesc": "TEST_HP", "type": "Float"}, {"category": "Standard", "default": 0.1, "group": "Testing", "name": "TEST_I", "shortDesc": "TEST_I", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_I_MAX", "shortDesc": "TEST_I_MAX", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_LP", "shortDesc": "TEST_LP", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_MAX", "shortDesc": "TEST_MAX", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_MEAN", "shortDesc": "TEST_MEAN", "type": "Float"}, {"category": "Standard", "default": -1.0, "group": "Testing", "name": "TEST_MIN", "shortDesc": "TEST_MIN", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "Testing", "name": "TEST_P", "shortDesc": "TEST_P", "type": "Float"}, {"category": "Standard", "default": 12345678, "group": "Testing", "name": "TEST_PARAMS", "shortDesc": "TEST_PARAMS", "type": "Int32"}, {"category": "Standard", "default": 16, "group": "Testing", "name": "TEST_RC2_X", "shortDesc": "TEST_RC2_X", "type": "Int32"}, {"category": "Standard", "default": 8, "group": "Testing", "name": "TEST_RC_X", "shortDesc": "TEST_RC_X", "type": "Int32"}, {"category": "Standard", "default": 0.5, "group": "Testing", "name": "TEST_TRIM", "shortDesc": "TEST_TRIM", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A0_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A0_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A0_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A1_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A1_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A1_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A2_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A2_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A2_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A3_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A3_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A3_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_A_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for accelerometer sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B0_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B0_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B0_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B0_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B1_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B1_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B1_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B1_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B2_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B2_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B2_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B2_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B3_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B3_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B3_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B3_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_B_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for barometric pressure sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G0_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G0_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G0_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G1_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G1_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G1_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G2_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G2_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G2_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G3_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G3_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G3_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_G_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for rate gyro sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M0_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M0_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M0_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M1_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M1_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M1_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M2_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M2_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M2_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M3_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M3_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M3_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_M_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for magnetometer sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_MGM_PITCH", "shortDesc": "Pitch gain for manual inputs in manual control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_MGM_ROLL", "shortDesc": "Roll gain for manual inputs in manual control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_MGM_THRTL", "shortDesc": "Throttle gain for manual inputs in manual control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_MGM_YAW", "shortDesc": "Yaw gain for manual inputs in manual control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_PITCH_D", "shortDesc": "Pitch differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_PITCH_P", "shortDesc": "Pitch proportional gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 100.0, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_RGM_PITCH", "shortDesc": "Pitch gain for manual inputs in rate control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 100.0, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_RGM_ROLL", "shortDesc": "Roll gain for manual inputs in rate control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_RGM_THRTL", "shortDesc": "Throttle gain for manual inputs in rate control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 100.0, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_RGM_YAW", "shortDesc": "Yaw gain for manual inputs in rate control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.5, "group": "UUV Attitude Control", "name": "UUV_ROLL_D", "shortDesc": "Roll differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_ROLL_P", "shortDesc": "Roll proportional gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_SGM_PITCH", "shortDesc": "Pitch gain for manual inputs in attitude control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_SGM_ROLL", "shortDesc": "Roll gain for manual inputs in attitude control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_SGM_THRTL", "shortDesc": "Throttle gain for manual inputs in attitude control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_SGM_YAW", "shortDesc": "Yaw gain for manual inputs in attitude control mode", "type": "Float"}, {"category": "Standard", "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_SP_MAX_AGE", "shortDesc": "Maximum time (in seconds) before resetting setpoint", "type": "Float"}, {"category": "Standard", "default": 0, "group": "UUV Attitude Control", "max": 1, "min": 0, "name": "UUV_STICK_MODE", "shortDesc": "Stick mode selector (0=Heave/sway control, roll/pitch leveled; 1=Pitch/roll control)", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "UUV Attitude Control", "max": 1.0, "min": 0.0, "name": "UUV_THRUST_SAT", "shortDesc": "UUV Thrust setpoint Saturation", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "UUV Attitude Control", "max": 1.0, "min": 0.0, "name": "UUV_TORQUE_SAT", "shortDesc": "UUV Torque setpoint Saturation", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_YAW_D", "shortDesc": "Yaw differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_YAW_P", "shortDesc": "Yawh proportional gain", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_X_D", "shortDesc": "Gain of D controller X", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_X_P", "shortDesc": "Gain of P controller X", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_Y_D", "shortDesc": "Gain of D controller Y", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_Y_P", "shortDesc": "Gain of P controller Y", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_Z_D", "shortDesc": "Gain of D controller Z", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_Z_P", "shortDesc": "Gain of P controller Z", "type": "Float"}, {"category": "Standard", "default": 0.5, "group": "UUV Position Control", "name": "UUV_PGM_VEL", "shortDesc": "Gain for position control velocity setpoint update", "type": "Float"}, {"category": "Standard", "default": 1, "group": "UUV Position Control", "name": "UUV_POS_MODE", "shortDesc": "Stabilization mode(1) or Position Control(0)", "type": "Int32", "values": [{"description": "Moves position setpoint in world frame", "value": 0}, {"description": "Moves position setpoint in body frame", "value": 1}]}, {"category": "Standard", "default": 0.1, "group": "UUV Position Control", "name": "UUV_POS_STICK_DB", "shortDesc": "Deadband for changing position setpoint", "type": "Float"}, {"category": "Standard", "default": 1, "group": "UUV Position Control", "name": "UUV_STAB_MODE", "shortDesc": "Stabilization mode(1) or Position Control(0)", "type": "Int32", "values": [{"description": "Tracks previous attitude setpoint", "value": 0}, {"description": "Tracks horizontal attitude (allows yaw change)", "value": 1}]}, {"category": "Standard", "default": 2130706433, "group": "UXRCE-DDS Client", "longDesc": "If ethernet is enabled and is the selected configuration for uXRCE-DDS,\nthe selected Agent IP address will be set and used.\nDecimal dot notation is not supported. IP address must be provided\nin int32 format. For example, 192.168.1.2 is mapped to -1062731518;\n127.0.0.1 is mapped to 2130706433.", "name": "UXRCE_DDS_AG_IP", "rebootRequired": true, "shortDesc": "uXRCE-DDS Agent IP address", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "uXRCE-DDS domain ID", "name": "UXRCE_DDS_DOM_ID", "rebootRequired": true, "shortDesc": "uXRCE-DDS domain ID", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "This is used to enable flow control for the serial uXRCE instance.\nUsed for reliable high bandwidth communication.", "name": "UXRCE_DDS_FLCTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for UXRCE interface", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "UXRCE-DDS Client", "longDesc": "uXRCE-DDS key, must be different from zero.\nIn a single agent - multi client configuration, each client\nmust have a unique session key.", "name": "UXRCE_DDS_KEY", "rebootRequired": true, "shortDesc": "uXRCE-DDS session key", "type": "Int32"}, {"category": "System", "default": -1, "group": "UXRCE-DDS Client", "longDesc": "Defines an index-based namespace for DDS messages, e.g, uav_0, uav_1, up to uav_9999\nA value less than zero leaves the namespace empty", "max": 9999, "min": -1, "name": "UXRCE_DDS_NS_IDX", "rebootRequired": true, "shortDesc": "Define an index-based message namespace", "type": "Int32"}, {"category": "Standard", "default": 8888, "group": "UXRCE-DDS Client", "longDesc": "If ethernet is enabled and is the selected configuration for uXRCE-DDS,\nthe selected UDP port will be set and used.", "max": 65535, "min": 0, "name": "UXRCE_DDS_PRT", "rebootRequired": true, "shortDesc": "uXRCE-DDS UDP port", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "Set the participant configuration on the Agent's system.\n0: Use the default configuration.\n1: Restrict messages to localhost\n(use in combination with ROS_LOCALHOST_ONLY=1).\n2: Use a custom participant with the profile name \"px4_participant\".", "max": 2, "min": 0, "name": "UXRCE_DDS_PTCFG", "rebootRequired": true, "shortDesc": "uXRCE-DDS participant configuration", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Localhost-only", "value": 1}, {"description": "Custom participant", "value": 2}]}, {"category": "System", "default": -1, "group": "UXRCE-DDS Client", "longDesc": "Specifies after how many seconds without receiving data the DDS connection is reestablished.\nA value less than one disables the RX rate timeout.", "name": "UXRCE_DDS_RX_TO", "rebootRequired": true, "shortDesc": "RX rate timeout configuration", "type": "Int32", "units": "s"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "When enabled along with UXRCE_DDS_SYNCT, uxrce_dds_client will set the system clock using the agents UTC timestamp.", "name": "UXRCE_DDS_SYNCC", "rebootRequired": true, "shortDesc": "Enable uXRCE-DDS system clock synchronization", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "UXRCE-DDS Client", "longDesc": "When enabled, uxrce_dds_client will synchronize the timestamps of the incoming and outgoing messages measuring the offset between the Agent OS time and the PX4 time.", "name": "UXRCE_DDS_SYNCT", "rebootRequired": true, "shortDesc": "Enable uXRCE-DDS timestamp synchronization", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 3, "group": "UXRCE-DDS Client", "longDesc": "Specifies after how many seconds without sending data the DDS connection is reestablished.\nA value less than one disables the TX rate timeout.", "name": "UXRCE_DDS_TX_TO", "rebootRequired": true, "shortDesc": "TX rate timeout configuration", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 8.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Airspeed at which we can start blending both fw and mc controls. Set to 0 to disable.", "max": 30.0, "min": 0.0, "name": "VT_ARSP_BLEND", "shortDesc": "Transition blending airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Airspeed at which we can switch to fw mode", "max": 30.0, "min": 0.0, "name": "VT_ARSP_TRANS", "shortDesc": "Transition airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Time in seconds it takes to tilt form VT_TILT_FW to VT_TILT_MC.", "max": 10.0, "min": 0.1, "name": "VT_BT_TILT_DUR", "shortDesc": "Duration motor tilt up in backtransition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "VTOL Attitude Control", "increment": 0.05, "max": 0.3, "min": 0.0, "name": "VT_B_DEC_I", "shortDesc": "Backtransition deceleration setpoint to tilt I gain", "type": "Float", "units": "rad s/m"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Used to calculate back transition distance in an auto mode.\nFor standard vtol and tiltrotors a controller is used to track this value during the transition.", "max": 10.0, "min": 0.5, "name": "VT_B_DEC_MSS", "shortDesc": "Approximate deceleration during back transition", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Transition is also declared over if the groundspeed drops below MPC_XY_CRUISE.", "max": 20.0, "min": 0.1, "name": "VT_B_TRANS_DUR", "shortDesc": "Maximum duration of a back transition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "This sets the duration during which the MC motors ramp up to the commanded thrust during the back transition stage.", "max": 20.0, "min": 0.0, "name": "VT_B_TRANS_RAMP", "shortDesc": "Back transition MC motor ramp up time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "VTOL Attitude Control", "longDesc": "If set to 1 the control surfaces are locked at the disarmed value in multicopter mode.", "name": "VT_ELEV_MC_LOCK", "shortDesc": "Lock control surfaces in hover", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Prevents downforce from pitching the body down when facing wind.\nUses puller/pusher (standard VTOL), or forward-tilt (tiltrotor VTOL) to accelerate forward instead.\nOnly active if demanded pitch is below VT_PITCH_MIN.\nUse VT_FWD_THRUST_SC to tune it.\nDescend mode is treated as Landing too.\nOnly active (if enabled) in height-rate controlled modes.", "name": "VT_FWD_THRUST_EN", "shortDesc": "Use fixed-wing actuation in hover to accelerate forward", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled (except LANDING)", "value": 1}, {"description": "Enabled if above MPC_LAND_ALT1", "value": 2}, {"description": "Enabled if above MPC_LAND_ALT2", "value": 3}, {"description": "Enabled constantly", "value": 4}, {"description": "Enabled if above MPC_LAND_ALT1 (except LANDING)", "value": 5}, {"description": "Enabled if above MPC_LAND_ALT2 (except LANDING)", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Scale applied to the demanded pitch (below VT_PITCH_MIN) to get the fixed-wing forward actuation in hover mode.\nEnabled via VT_FWD_THRUST_EN.", "max": 5.0, "min": 0.0, "name": "VT_FWD_THRUST_SC", "shortDesc": "Fixed-wing actuation thrust scale in hover", "type": "Float"}, {"bitmask": [{"description": "Yaw", "index": 0}, {"description": "Roll", "index": 1}, {"description": "Pitch", "index": 2}], "category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Enable differential thrust seperately for roll, pitch, yaw in forward (fixed-wing) mode.\nThe effectiveness of differential thrust around the corresponding axis can be\ntuned by setting VT_FW_DIFTHR_S_R / VT_FW_DIFTHR_S_P / VT_FW_DIFTHR_S_Y.", "max": 7, "min": 0, "name": "VT_FW_DIFTHR_EN", "shortDesc": "Differential thrust in forwards flight", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_P", "shortDesc": "Pitch differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_R", "shortDesc": "Roll differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_Y", "shortDesc": "Yaw differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Minimum altitude for fixed-wing flight. When the vehicle is in fixed-wing mode\nand the altitude drops below this altitude (relative altitude above local origin),\nit will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT.", "max": 200.0, "min": 0.0, "name": "VT_FW_MIN_ALT", "shortDesc": "Quad-chute altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "increment": 1, "longDesc": "Maximum height above the ground (if available, otherwise above\nHome if available, otherwise above the local origin) where triggering a quad-chute is possible.\nAt high altitudes there is a big risk to deplete the battery and therefore crash if quad-chuting there.", "min": 0, "name": "VT_FW_QC_HMAX", "shortDesc": "Quad-chute maximum height", "type": "Int32", "units": "m"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Absolute pitch threshold for quad-chute triggering in FW mode.\nAbove this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT.\nSet to 0 do disable this threshold.", "max": 180, "min": 0, "name": "VT_FW_QC_P", "shortDesc": "Quad-chute max pitch threshold", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Absolute roll threshold for quad-chute triggering in FW mode.\nAbove this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT.\nSet to 0 do disable this threshold.", "max": 180, "min": 0, "name": "VT_FW_QC_R", "shortDesc": "Quad-chute max roll threshold", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Time in seconds used for a transition", "max": 20.0, "min": 0.1, "name": "VT_F_TRANS_DUR", "shortDesc": "Duration of a front transition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_F_TRANS_THR", "shortDesc": "Target throttle value for the transition to fixed-wing flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.0, "group": "VTOL Attitude Control", "increment": 0.5, "longDesc": "The duration of the front transition when there is no airspeed feedback available.\nWhen airspeed is used, transition timeout is declared if airspeed does not\nreach VT_ARSP_BLEND after this time.", "max": 30.0, "min": 1.0, "name": "VT_F_TR_OL_TM", "shortDesc": "Airspeed-less front transition time (open loop)", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Overrides VT_PITCH_MIN when the vehicle is in LAND mode (hovering).\nDuring landing it can be beneficial to reduce the pitch angle to reduce the generated lift in head wind.", "max": 45.0, "min": -10.0, "name": "VT_LND_PITCH_MIN", "shortDesc": "Minimum pitch angle during hover landing", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Any pitch setpoint below this value is translated to a forward force by the fixed-wing forward actuation if\nVT_FWD_TRHUST_EN is set.", "max": 45.0, "min": -10.0, "name": "VT_PITCH_MIN", "shortDesc": "Minimum pitch angle during hover", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.33, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Defines the slew rate of the puller/pusher throttle during transitions.\nZero will deactivate the slew rate limiting and thus produce an instant throttle\nrise to the transition throttle VT_F_TRANS_THR.", "min": 0.0, "name": "VT_PSHER_SLEW", "shortDesc": "Pusher throttle ramp up slew rate", "type": "Float", "units": "1/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Altitude error threshold for quad-chute triggering during fixed-wing flight.\nThe check is only active if altitude is controlled and the vehicle is below the current altitude reference.\nThe altitude error is relative to the highest altitude the vehicle has achieved since it has flown below the current\naltitude reference.\nSet to 0 do disable.", "max": 200.0, "min": 0.0, "name": "VT_QC_ALT_LOSS", "shortDesc": "Quad-chute uncommanded descent threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Altitude loss threshold for quad-chute triggering during VTOL transition to fixed-wing flight\nin altitude-controlled flight modes.\nActive until 5s after completing transition to fixed-wing.\nIf the current altitude is more than this value below the altitude at the beginning of the\ntransition, it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT.\nSet to 0 do disable this threshold.", "max": 50.0, "min": 0.0, "name": "VT_QC_T_ALT_LOSS", "shortDesc": "Quad-chute transition altitude loss threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.1, "max": 1.0, "min": -1.0, "name": "VT_SPOILER_MC_LD", "shortDesc": "Spoiler setting while landing (hover)", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_FW", "shortDesc": "Normalized tilt in FW", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_MC", "shortDesc": "Normalized tilt in Hover", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.4, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_TRANS", "shortDesc": "Normalized tilt in transition to FW", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Minimum time in seconds for front transition.", "max": 20.0, "min": 0.0, "name": "VT_TRANS_MIN_TM", "shortDesc": "Front transition minimum time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Time in seconds it takes to tilt form VT_TILT_TRANS to VT_TILT_FW.", "max": 5.0, "min": 0.1, "name": "VT_TRANS_P2_DUR", "shortDesc": "Duration of front transition phase 2", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 15.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Time in seconds after which transition will be cancelled.", "max": 30.0, "min": 0.1, "name": "VT_TRANS_TIMEOUT", "shortDesc": "Front transition timeout", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "max": 2, "min": 0, "name": "VT_TYPE", "rebootRequired": true, "shortDesc": "VTOL Type (Tailsitter=0, Tiltrotor=1, Standard=2)", "type": "Int32", "values": [{"description": "Tailsitter", "value": 0}, {"description": "Tiltrotor", "value": 1}, {"description": "Standard", "value": 2}]}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "The desired gain to convert roll sp into yaw rate sp.", "max": 3.0, "min": 0.0, "name": "WV_GAIN", "shortDesc": "Weather-vane roll angle to yawrate", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 80.0, "group": "VTOL Takeoff", "increment": 1.0, "longDesc": "Altitude relative to home at which vehicle will loiter after front transition.", "max": 300.0, "min": 20.0, "name": "VTO_LOITER_ALT", "shortDesc": "VTOL Takeoff relative loiter altitude", "type": "Float", "units": "m"}], "translation": {"items": {"parameters": {"list": {"items": {"bitmask": {"list": {"key": "index", "translate": ["description"]}}, "values": {"list": {"key": "value", "translate": ["description"]}}}, "key": "name", "translate": ["shortDesc", "longDesc"], "translate-global": ["category", "group"]}}}}, "version": 1} \ No newline at end of file From 8bb1e44c108843e84cf5fa641b8c7bf8d40caf74 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 11 Feb 2026 14:57:40 -0800 Subject: [PATCH 727/812] ci: fix deploy-aws skipped due to upstream always() propagation When build-site uses always() in its if condition, the skipped status from its upstream dependencies propagates to deploy-aws which lacks always(). Add always() with explicit success checks to ensure deploy runs when both metadata-regen and build-site succeed. Signed-off-by: Ramon Roche --- .github/workflows/docs-orchestrator.yml | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/.github/workflows/docs-orchestrator.yml b/.github/workflows/docs-orchestrator.yml index afca6f5e15..ad4ef6c260 100644 --- a/.github/workflows/docs-orchestrator.yml +++ b/.github/workflows/docs-orchestrator.yml @@ -376,8 +376,12 @@ jobs: # ============================================================================= deploy-aws: name: "T4: Deploy" - if: github.event_name == 'push' || github.event_name == 'workflow_dispatch' needs: [metadata-regen, build-site] + if: >- + always() && + needs.metadata-regen.result == 'success' && + needs.build-site.result == 'success' && + (github.event_name == 'push' || github.event_name == 'workflow_dispatch') permissions: id-token: write runs-on: ubuntu-latest From e945c91f8874292e2ceffe5213d3294f0cab5680 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Wed, 11 Feb 2026 23:08:10 +0000 Subject: [PATCH 728/812] docs: auto-sync metadata [skip ci] Co-Authored-By: PX4 BuildBot --- docs/en/config/_autotune.md | 3 +- docs/en/flight_stack/controller_diagrams.md | 2 +- docs/en/middleware/dds_topics.md | 354 ++++++++++---------- 3 files changed, 179 insertions(+), 180 deletions(-) diff --git a/docs/en/config/_autotune.md b/docs/en/config/_autotune.md index 38eb200e95..c782f212a6 100644 --- a/docs/en/config/_autotune.md +++ b/docs/en/config/_autotune.md @@ -84,8 +84,7 @@ The test steps are:

1. In QGroundControl, open the menu **Vehicle setup > PID Tuning**: - ![Tuning Setup > Autotune Enabled](../../assets/qgc/setup/autotune/autotune.png) - + ![Tuning Setup > Autotune Enabled](../../assets/qgc/setup/autotune/autotune.png) 2. Select either the _Rate Controller_ or _Attitude Controller_ tabs. 3. Ensure that the **Autotune enabled** button is enabled (this will display the **Autotune** button and remove the manual tuning selectors). 4. Read the warning popup and click on **OK** to start tuning. diff --git a/docs/en/flight_stack/controller_diagrams.md b/docs/en/flight_stack/controller_diagrams.md index 26453c1361..2a63e7e6d7 100644 --- a/docs/en/flight_stack/controller_diagrams.md +++ b/docs/en/flight_stack/controller_diagrams.md @@ -30,7 +30,7 @@ The diagrams use the standard [PX4 notation](../contribute/notation.md) (and eac ::: info The IMU pipeline is: - gyro data > apply calibration parameters > remove estimated bias > notch filter (`IMU_GYRO_NF0_BW` and `IMU_GYRO_NF0_FRQ`) > low-pass filter (`IMU_GYRO_CUTOFF`) > vehicle_angular_velocity (_filtered angular rate used by the P and I controllers_) > derivative -> low-pass filter (`IMU_DGYRO_CUTOFF`) > vehicle_angular_acceleration (_filtered angular acceleration used by the D controller_) + gyro data > apply calibration parameters > remove estimated bias > notch filter (`IMU_GYRO_NF0_BW` and `IMU_GYRO_NF0_FRQ`) > low-pass filter (`IMU_GYRO_CUTOFF`) > vehicle*angular_velocity (\_filtered angular rate used by the P and I controllers*) > derivative -> low-pass filter (`IMU_DGYRO_CUTOFF`) > vehicle*angular_acceleration (\_filtered angular acceleration used by the D controller*) ![IMU pipeline](../../assets/diagrams/px4_imu_pipeline.png) ::: diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index 8dc46fa490..fa3d583d32 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -94,199 +94,199 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages +- [GpsInjectData](../msg_docs/GpsInjectData.md) +- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) +- [AdcReport](../msg_docs/AdcReport.md) - [EventV0](../msg_docs/EventV0.md) -- [IrlockReport](../msg_docs/IrlockReport.md) -- [QshellReq](../msg_docs/QshellReq.md) -- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) -- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [OrbTestLarge](../msg_docs/OrbTestLarge.md) -- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) -- [FollowTarget](../msg_docs/FollowTarget.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) -- [CameraStatus](../msg_docs/CameraStatus.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [Mission](../msg_docs/Mission.md) -- [LandingTargetPose](../msg_docs/LandingTargetPose.md) -- [Airspeed](../msg_docs/Airspeed.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [Rpm](../msg_docs/Rpm.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [GpioOut](../msg_docs/GpioOut.md) -- [SensorSelection](../msg_docs/SensorSelection.md) -- [ButtonEvent](../msg_docs/ButtonEvent.md) -- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) +- [PositionSetpoint](../msg_docs/PositionSetpoint.md) +- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) +- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [AirspeedWind](../msg_docs/AirspeedWind.md) - [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) -- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) -- [SensorMag](../msg_docs/SensorMag.md) -- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) -- [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) +- [SensorHygrometer](../msg_docs/SensorHygrometer.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [Vtx](../msg_docs/Vtx.md) +- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) +- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) +- [SatelliteInfo](../msg_docs/SatelliteInfo.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [SensorUwb](../msg_docs/SensorUwb.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) +- [EstimatorStates](../msg_docs/EstimatorStates.md) +- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [SensorGyro](../msg_docs/SensorGyro.md) +- [GainCompression](../msg_docs/GainCompression.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) - [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) +- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) +- [RcChannels](../msg_docs/RcChannels.md) +- [GpsDump](../msg_docs/GpsDump.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) - [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) -- [RaptorInput](../msg_docs/RaptorInput.md) -- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [OrbTestMedium](../msg_docs/OrbTestMedium.md) +- [VehicleRoi](../msg_docs/VehicleRoi.md) +- [Gripper](../msg_docs/Gripper.md) +- [LandingTargetPose](../msg_docs/LandingTargetPose.md) +- [LedControl](../msg_docs/LedControl.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) - [HealthReport](../msg_docs/HealthReport.md) - [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) -- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) -- [RtlStatus](../msg_docs/RtlStatus.md) -- [VehicleRoi](../msg_docs/VehicleRoi.md) -- [QshellRetval](../msg_docs/QshellRetval.md) -- [GeneratorStatus](../msg_docs/GeneratorStatus.md) -- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) -- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [ParameterUpdate](../msg_docs/ParameterUpdate.md) -- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) -- [Px4ioStatus](../msg_docs/Px4ioStatus.md) -- [Gripper](../msg_docs/Gripper.md) -- [ActuatorTest](../msg_docs/ActuatorTest.md) -- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) -- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) -- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) -- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) -- [PwmInput](../msg_docs/PwmInput.md) -- [BatteryInfo](../msg_docs/BatteryInfo.md) -- [NeuralControl](../msg_docs/NeuralControl.md) -- [RaptorStatus](../msg_docs/RaptorStatus.md) -- [DeviceInformation](../msg_docs/DeviceInformation.md) -- [Vtx](../msg_docs/Vtx.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [GimbalControls](../msg_docs/GimbalControls.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [Ping](../msg_docs/Ping.md) -- [LedControl](../msg_docs/LedControl.md) -- [ActionRequest](../msg_docs/ActionRequest.md) -- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) -- [GpioConfig](../msg_docs/GpioConfig.md) -- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [LandingGearWheel](../msg_docs/LandingGearWheel.md) -- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) -- [MissionResult](../msg_docs/MissionResult.md) -- [SystemPower](../msg_docs/SystemPower.md) -- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [EstimatorStatus](../msg_docs/EstimatorStatus.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) -- [OrbTestMedium](../msg_docs/OrbTestMedium.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) -- [GpioRequest](../msg_docs/GpioRequest.md) +- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [Cpuload](../msg_docs/Cpuload.md) - [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [EstimatorBias](../msg_docs/EstimatorBias.md) -- [MountOrientation](../msg_docs/MountOrientation.md) -- [RadioStatus](../msg_docs/RadioStatus.md) -- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) -- [SensorAirflow](../msg_docs/SensorAirflow.md) -- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) -- [RoverRateStatus](../msg_docs/RoverRateStatus.md) -- [VehicleAirData](../msg_docs/VehicleAirData.md) -- [PowerButtonState](../msg_docs/PowerButtonState.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) -- [AdcReport](../msg_docs/AdcReport.md) -- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [EstimatorStates](../msg_docs/EstimatorStates.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) -- [MagWorkerData](../msg_docs/MagWorkerData.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) -- [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [DebugValue](../msg_docs/DebugValue.md) -- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) -- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [RcChannels](../msg_docs/RcChannels.md) -- [VehicleImu](../msg_docs/VehicleImu.md) -- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) +- [RtlStatus](../msg_docs/RtlStatus.md) - [InputRc](../msg_docs/InputRc.md) -- [TuneControl](../msg_docs/TuneControl.md) -- [GeofenceStatus](../msg_docs/GeofenceStatus.md) -- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) +- [SensorGyroFft](../msg_docs/SensorGyroFft.md) - [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [GpsInjectData](../msg_docs/GpsInjectData.md) -- [CameraTrigger](../msg_docs/CameraTrigger.md) -- [EscReport](../msg_docs/EscReport.md) -- [SensorAccel](../msg_docs/SensorAccel.md) -- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) -- [LogMessage](../msg_docs/LogMessage.md) -- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [SensorsStatus](../msg_docs/SensorsStatus.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) +- [LandingGearWheel](../msg_docs/LandingGearWheel.md) +- [FuelTankStatus](../msg_docs/FuelTankStatus.md) +- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) +- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) - [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [VehicleImu](../msg_docs/VehicleImu.md) +- [ButtonEvent](../msg_docs/ButtonEvent.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) +- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [BatteryInfo](../msg_docs/BatteryInfo.md) +- [IrlockReport](../msg_docs/IrlockReport.md) +- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) +- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [QshellReq](../msg_docs/QshellReq.md) +- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) +- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) +- [MissionResult](../msg_docs/MissionResult.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) +- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) +- [GeofenceStatus](../msg_docs/GeofenceStatus.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) +- [CameraStatus](../msg_docs/CameraStatus.md) +- [EstimatorStatus](../msg_docs/EstimatorStatus.md) +- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) +- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) +- [FollowTarget](../msg_docs/FollowTarget.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [MagWorkerData](../msg_docs/MagWorkerData.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [SensorMag](../msg_docs/SensorMag.md) - [RcParameterMap](../msg_docs/RcParameterMap.md) -- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) -- [SensorTemp](../msg_docs/SensorTemp.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) +- [SensorBaro](../msg_docs/SensorBaro.md) - [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [VehicleAirData](../msg_docs/VehicleAirData.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) +- [Airspeed](../msg_docs/Airspeed.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) +- [Rpm](../msg_docs/Rpm.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [SensorAccel](../msg_docs/SensorAccel.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) +- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [SensorCorrection](../msg_docs/SensorCorrection.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [Event](../msg_docs/Event.md) +- [GpioConfig](../msg_docs/GpioConfig.md) +- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [CellularStatus](../msg_docs/CellularStatus.md) +- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [CameraCapture](../msg_docs/CameraCapture.md) +- [ActuatorTest](../msg_docs/ActuatorTest.md) +- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) +- [SensorAirflow](../msg_docs/SensorAirflow.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [PpsCapture](../msg_docs/PpsCapture.md) +- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) +- [GpioRequest](../msg_docs/GpioRequest.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [Mission](../msg_docs/Mission.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [QshellRetval](../msg_docs/QshellRetval.md) +- [EscReport](../msg_docs/EscReport.md) +- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [SystemPower](../msg_docs/SystemPower.md) +- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) +- [DifferentialPressure](../msg_docs/DifferentialPressure.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) +- [PwmInput](../msg_docs/PwmInput.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [CameraTrigger](../msg_docs/CameraTrigger.md) +- [RadioStatus](../msg_docs/RadioStatus.md) +- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) - [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) - [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) -- [SensorGyro](../msg_docs/SensorGyro.md) -- [SensorBaro](../msg_docs/SensorBaro.md) -- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) -- [PpsCapture](../msg_docs/PpsCapture.md) -- [SensorsStatus](../msg_docs/SensorsStatus.md) -- [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) -- [SatelliteInfo](../msg_docs/SatelliteInfo.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) -- [UlogStream](../msg_docs/UlogStream.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) -- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) -- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) -- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [EscStatus](../msg_docs/EscStatus.md) -- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) -- [ActuatorArmed](../msg_docs/ActuatorArmed.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) - [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [AirspeedWind](../msg_docs/AirspeedWind.md) -- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) -- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) -- [GpsDump](../msg_docs/GpsDump.md) -- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) -- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [TecsStatus](../msg_docs/TecsStatus.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [DeviceInformation](../msg_docs/DeviceInformation.md) +- [GpioOut](../msg_docs/GpioOut.md) - [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) -- [GainCompression](../msg_docs/GainCompression.md) -- [SensorCorrection](../msg_docs/SensorCorrection.md) -- [SensorUwb](../msg_docs/SensorUwb.md) +- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) +- [RoverRateStatus](../msg_docs/RoverRateStatus.md) +- [SensorSelection](../msg_docs/SensorSelection.md) +- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) - [UlogStreamAck](../msg_docs/UlogStreamAck.md) -- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) -- [Cpuload](../msg_docs/Cpuload.md) +- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [PowerButtonState](../msg_docs/PowerButtonState.md) +- [GeneratorStatus](../msg_docs/GeneratorStatus.md) +- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) +- [OrbTestLarge](../msg_docs/OrbTestLarge.md) +- [LogMessage](../msg_docs/LogMessage.md) +- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [DebugValue](../msg_docs/DebugValue.md) +- [UlogStream](../msg_docs/UlogStream.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) - [GpioIn](../msg_docs/GpioIn.md) -- [CellularStatus](../msg_docs/CellularStatus.md) -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) -- [PositionSetpoint](../msg_docs/PositionSetpoint.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) -- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) -- [DebugArray](../msg_docs/DebugArray.md) -- [Event](../msg_docs/Event.md) +- [OrbTest](../msg_docs/OrbTest.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) +- [NeuralControl](../msg_docs/NeuralControl.md) +- [Ping](../msg_docs/Ping.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [ActionRequest](../msg_docs/ActionRequest.md) +- [ActuatorArmed](../msg_docs/ActuatorArmed.md) +- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [GimbalControls](../msg_docs/GimbalControls.md) ::: From 07d9167d66133e143fb099d7e13bb4edf9c5e982 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 7 Jan 2026 10:41:49 +1100 Subject: [PATCH 729/812] Tunes library MML compatibility[A --- src/lib/tunes/tunes.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/src/lib/tunes/tunes.cpp b/src/lib/tunes/tunes.cpp index 961e10ba64..a659cae126 100644 --- a/src/lib/tunes/tunes.cpp +++ b/src/lib/tunes/tunes.cpp @@ -219,6 +219,13 @@ Tunes::Status Tunes::get_next_note(unsigned &frequency, unsigned &duration, unsi _next_tune++; switch (c) { + + case 'V': // Select volume. + // Consume volume if specified in tune but ignore + // MML compatibility + next_number(); + break; + case 'L': // Select note length. _note_length = next_number(); From 0134d7dd3b8e2fbcafd0918f641966c3d9145299 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 7 Jan 2026 11:31:11 +1100 Subject: [PATCH 730/812] Add R (rest) as alias for Pause (p) --- src/lib/tunes/tunes.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/lib/tunes/tunes.cpp b/src/lib/tunes/tunes.cpp index a659cae126..2f00446f32 100644 --- a/src/lib/tunes/tunes.cpp +++ b/src/lib/tunes/tunes.cpp @@ -295,6 +295,7 @@ Tunes::Status Tunes::get_next_note(unsigned &frequency, unsigned &duration, unsi break; case 'P': // Pause for a note length. + case 'R': frequency = 0; duration = 0; note_length = next_number(); From b3c05bf4da427d0fddd173318666198e0db45c97 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 29 Jan 2026 10:28:16 +1100 Subject: [PATCH 731/812] Update docs for changes to tune format --- src/lib/tunes/tune_definition.desc | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/src/lib/tunes/tune_definition.desc b/src/lib/tunes/tune_definition.desc index c615a16c09..0f07c5f460 100644 --- a/src/lib/tunes/tune_definition.desc +++ b/src/lib/tunes/tune_definition.desc @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2018 PX4 Development Team. All rights reserved. + * Copyright (c) 2018, 2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -32,13 +32,13 @@ ****************************************************************************/ /** - * Driver for the PX4 audio . + * Driver for PX4 audio * - * The tune_control supports a set of predefined "alarm" tunes and - * one user-supplied tune. + * The tune_control supports a set of predefined "alarm" tunes and one user-supplied tune. * - * Tunes follow the syntax of the Microsoft GWBasic/QBasic PLAY - * statement, with some exceptions and extensions. + * Tunes follow the syntax of the Microsoft GWBasic/QBasic PLAY statement, with some exceptions and extensions. + * This is equivalent to Modern MML https://en.wikipedia.org/wiki/Music_Macro_Language#Modern_MML + * With the exception that symbols must be upper-cased, and that the `V` symbol is ignored. * * From Wikibooks: * @@ -70,7 +70,9 @@ * ML Stand for Music Legato. Note duration is full length of that indicated by Ln. * MS Stand for Music Staccato. Note duration is 3/4ths of the length indicated by Ln. * Pn Causes a silence (pause) for the length of note indicated (same as Ln). + * Rn Same as P (pause). * Tn Sets the number of "L4"s per minute (tempo). Valid values are from 32 to 255. The default value is T120. + * Vn Ignored. In specification sets the volume of the instrument (subsequent notes). * . When placed after a note, it causes the duration of the note to be 3/2 of the set duration. * This is how to get "dotted" notes. "L4 C#." would play C sharp as a dotted quarter note. * It can be used for a pause as well. From ad6ee2aadfabaff5a2046eb588850862cdfb7dc0 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 11 Feb 2026 20:34:49 +1300 Subject: [PATCH 732/812] Apply suggestions from code review Co-authored-by: Hamish Willee --- src/lib/tunes/tune_definition.desc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/lib/tunes/tune_definition.desc b/src/lib/tunes/tune_definition.desc index 0f07c5f460..493106f94c 100644 --- a/src/lib/tunes/tune_definition.desc +++ b/src/lib/tunes/tune_definition.desc @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2018, 2025 PX4 Development Team. All rights reserved. + * Copyright (c) 2018 - 2025 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions From 741892c30f525e2a93ebbe7bb5543210f8326f06 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 12 Feb 2026 12:30:56 +1100 Subject: [PATCH 733/812] do make format --- src/lib/tunes/tunes.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/lib/tunes/tunes.cpp b/src/lib/tunes/tunes.cpp index 2f00446f32..02a5b16055 100644 --- a/src/lib/tunes/tunes.cpp +++ b/src/lib/tunes/tunes.cpp @@ -221,7 +221,7 @@ Tunes::Status Tunes::get_next_note(unsigned &frequency, unsigned &duration, unsi switch (c) { case 'V': // Select volume. - // Consume volume if specified in tune but ignore + // Consume volume if specified in tune but ignore // MML compatibility next_number(); break; From c56bc4208db951bac4085017d66906c46a847013 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 14 Jan 2026 09:30:49 -0800 Subject: [PATCH 734/812] docs: document release process Signed-off-by: Ramon Roche --- docs/en/SUMMARY.md | 1 + docs/en/releases/index.md | 2 + docs/en/releases/release_process.md | 276 ++++++++++++++++++++++++++++ 3 files changed, 279 insertions(+) create mode 100644 docs/en/releases/release_process.md diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index f141f91679..173abd0f54 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -908,6 +908,7 @@ - [Terminology/Notation](contribute/notation.md) - [Licenses](contribute/licenses.md) - [Releases](releases/index.md) + - [Release Process](releases/release_process.md) - [main (alpha)](releases/main.md) - [1.17 (alpha)](releases/1.17.md) - [1.16 (stable)](releases/1.16.md) diff --git a/docs/en/releases/index.md b/docs/en/releases/index.md index 69986e1ea4..d5b0cc01b7 100644 --- a/docs/en/releases/index.md +++ b/docs/en/releases/index.md @@ -2,6 +2,8 @@ A list of PX4 release notes, they contain a list of the changes that went into each release, explaining the included features, bug fixes, deprecations and updates in detail. +For maintainers, see [Release Process](release_process.md) for the tagging and publishing workflow. + - [main](../releases/main.md) (changes planned for v1.18 or later) - [v1.17](../releases/1.17.md) (changes planned for v1.17, since v1.16) - [v1.16](../releases/1.16.md) diff --git a/docs/en/releases/release_process.md b/docs/en/releases/release_process.md new file mode 100644 index 0000000000..3d13518cc5 --- /dev/null +++ b/docs/en/releases/release_process.md @@ -0,0 +1,276 @@ +# Release Process + +This page documents the PX4 release process for maintainers. It covers the steps from preparing a release candidate through to the final announcement. + +## Overview + +PX4 uses a branch-based release workflow: + +- **`release/X.Y`** (e.g., `release/1.17`, `release/2.0`) - The active development branch for a specific release where changes are merged and tested +- **`stable`** - Points to the latest stable release tag; reset after each release +- **`beta`** - For flight testers to validate release candidates + +Releases are tracked on the [PX4 Release Project Board](https://github.com/orgs/PX4/projects/45), which is reused and renamed for each release cycle. + +### Release Tag Progression + +Each release goes through the following tag stages: + +| Stage | Example | Branch Status | What Gets Merged | +|-------|---------|---------------|------------------| +| **Alpha** | `v1.18.0-alpha1` | Open for fixes | Bug fixes and regression fixes only | +| **Beta** | `v1.18.0-beta1` | Open for fixes | Bug fixes and regression fixes only | +| **RC** | `v1.18.0-rc1` | Frozen | Nothing (unless veto vote passes) | +| **Stable** | `v1.18.0` | Open for fixes | Bug fixes and regression fixes (for point releases) | + +::: info +New features are never merged to release branches. Once a release branch is created from `main`, only bug fixes and regression fixes are accepted. New features must target `main` and will be included in the next release cycle. +::: + +## Starting a New Release Cycle + +A new release cycle begins immediately after a stable release is published. This involves two votes during the [Weekly Community Q&A Call](../contribute/dev_call.md) when approving a stable release: + +1. **Vote to publish the current release** - Approve the stable release for publication +2. **Vote on the next release name/number** - Decide the version number for the next release (e.g., v1.18 or v2.0) + +### Create the Release Branch + +Once the next release version is decided, create the new release branch from `main`: + +```sh +# Ensure main is up to date +git checkout main +git pull + +# Create the new release branch +git checkout -b release/1.18 +git push origin release/1.18 +``` + +::: warning +Once the release branch is created, it only accepts bug fixes and regression fixes. All new feature development continues on `main`. +::: + +### Create the Alpha Tag + +Immediately after creating the release branch, create the first alpha tag to mark the beginning of the release cycle: + +```sh +# On the new release branch +git checkout release/1.18 + +# Create the signed alpha tag +git tag -s v1.18.0-alpha1 -m "v1.18.0-alpha1" +git push origin v1.18.0-alpha1 +``` + +Subsequent alpha tags can be created as fixes are merged (e.g., `v1.18.0-alpha2`, `v1.18.0-alpha3`). + +### Create Documentation Early + +Create the release notes page as soon as the release branch is created: + +- Create the new release notes file (e.g., `docs/en/releases/1.18.md`) +- Add the initial structure based on existing release notes +- Add the entry to `SUMMARY.md` and `releases/index.md` + +::: tip +Community members are encouraged to help document changes early in the release cycle. As fixes are merged into the release branch, contributors can add them to the release notes. This distributes the documentation workload and ensures changes are documented while they're fresh. +::: + +## Release Steps + +### 1. Review and Merge PRs (Alpha Phase) + +During the alpha phase, review pull requests targeting the release branch: + +- Review PRs according to the project's [contribution guidelines](../contribute/code.md) +- Merge **bug fixes and regression fixes only** +- New features must target `main`, not the release branch +- Create additional alpha tags as fixes are merged (e.g., `v1.18.0-alpha2`) + +### 2. Alpha Testing + +The [Dronecode Test Team](https://www.ascendengineer.com), provided by Dronecode Silver member Ascend Engineering, conducts initial flight testing of alpha builds using: + +- The [test cards](../test_and_ci/test_flights.md) documented in the PX4 guide +- A hardware matrix covering supported flight controllers and airframes + +### 3. Create Beta Tag + +Once alpha testing is successful, create the first beta tag: + +```sh +# On the release branch +git checkout release/1.18 +git pull + +# Create the signed beta tag +git tag -s v1.18.0-beta1 -m "v1.18.0-beta1" +git push origin v1.18.0-beta1 +``` + +### 4. Beta Testing + +The test team conducts more extensive testing of beta builds: + +- Full test card coverage across the hardware matrix +- Focus on stability and regression testing +- Community testing is encouraged during this phase + +During beta, continue to: + +- Review and merge **bug fixes and regression fixes only** +- Create additional beta tags as fixes are merged (e.g., `v1.18.0-beta2`, `v1.18.0-beta3`) + +### 5. Create Release Candidate Tag + +Once beta testing is successful, create the first release candidate: + +```sh +# On the release branch +git checkout release/1.18 +git pull + +# Create the signed RC tag +git tag -s v1.18.0-rc1 -m "v1.18.0-rc1" +git push origin v1.18.0-rc1 +``` + +::: warning +The branch is now frozen. No PRs will be merged unless a veto vote passes (see below). +::: + +::: tip +Tags must be GPG-signed. Ensure your GitHub account is [configured for GPG signing](https://docs.github.com/en/authentication/managing-commit-signature-verification). Only maintainers with registered GPG keys can create release tags. +::: + +### 6. RC Testing and Branch Freeze + +During RC testing, the release branch is frozen: + +- No PRs are merged by default +- Testing focuses on final validation before stable release +- Any issues found are documented and evaluated + +#### Veto Vote for Critical Fixes + +If a critical issue is discovered during RC testing that must be fixed before release: + +1. Raise the issue during the [Weekly Community Q&A Call](../contribute/dev_call.md) +2. Present the case for why the fix is critical +3. Maintainers vote on whether to merge the fix +4. If approved, merge the fix and create a new RC tag (e.g., `v1.18.0-rc2`) + +### 7. Release Vote + +The release vote takes place during the [Weekly Community Q&A Call](../contribute/dev_call.md): + +- Present the release status and test results +- **Vote 1:** Core maintainers vote on whether to publish the release +- **Vote 2:** Decide the name/number of the next release version +- The call happens Wednesdays at 17:00 CET on [Discord](https://discord.gg/BDYmr6FA6Q) + +### 8. Create and Push Release Tag + +After a successful vote, create the final release tag: + +```sh +# On the release branch +git checkout release/1.18 +git pull + +# Create the signed release tag +git tag -s v1.18.0 -m "v1.18.0" +git push origin v1.18.0 +``` + +### 9. Update the Stable Branch + +Reset the `stable` branch to point to the new release tag: + +```sh +git checkout stable +git reset --hard v1.18.0 +git push --force origin stable +``` + +::: warning +This is a force push that rewrites the stable branch history. Ensure you have the correct tag before executing. +::: + +### 10. GitHub Release (Automated) + +When a version tag is pushed, the [build_all_targets.yml](https://github.com/PX4/PX4-Autopilot/blob/main/.github/workflows/build_all_targets.yml) GitHub Actions workflow automatically: + +1. Builds firmware for all supported targets +2. Uploads firmware artifacts to AWS S3 (`Firmware/vX.Y.Z/` and updates `Firmware/stable/`) +3. Creates a **draft release** on GitHub with all `.px4` firmware files attached + +### 11. Publish GitHub Release + +Edit the draft release on GitHub: + +- Add a brief description of major changes +- Link to the full release notes in the documentation (e.g., `releases/1.18.md`) +- Publish the release + +### 12. Finalize Documentation + +Review and finalize the release notes that have been developed throughout the release cycle: + +- Ensure all noteworthy changes, new features, and upgrade guides are documented +- Review for completeness and accuracy +- See existing [release notes](../releases/index.md) for the expected format + +### 13. Announce the Release + +Announce the release through official channels: + +- [PX4 Discuss Forum](https://discuss.px4.io/) +- [PX4 Discord](https://discord.gg/dronecode) +- Social media (Twitter/X, LinkedIn) +- Dronecode newsletter + +### 14. Start Next Release Cycle + +Immediately after publishing, start the next release cycle: + +- Create the new release branch from `main` (see [Create the Release Branch](#create-the-release-branch)) +- Create the alpha tag for the new release +- Create the initial documentation for the next release +- Rename and prepare the project board (see [Project Board Management](#project-board-management)) + +## Point Releases + +After a stable release is published, the release branch reopens for bug fixes and regression fixes to support point releases (e.g., `v1.18.1`). + +For patch releases: + +1. Merge bug fixes and regression fixes to the release branch +2. Create beta tags for testing if needed (e.g., `v1.18.1-beta1`) +3. Create RC tags for final validation (e.g., `v1.18.1-rc1`) +4. After testing and vote, tag the point release +5. Update stable branch and publish + +## Project Board Management + +The [PX4 Release Project Board](https://github.com/orgs/PX4/projects/45) is reused across release cycles to track issues and PRs for the current release. + +### After a Release + +Once a release is published: + +1. **Rename the project board** to reflect the next release version (e.g., "v1.17 Release" → "v1.18 Release") +2. **Review remaining items**: + - Close items that are no longer relevant + - Move incomplete items that should carry over to the next release + - Remove items that were descoped or deferred indefinitely +3. **Update the board description** if needed to reflect the new release target + +## See Also + +- [Source Code Management](../contribute/code.md) - Branching model and contribution guidelines +- [Test Flights](../test_and_ci/test_flights.md) - Flight test procedures and test cards +- [Weekly Community Q&A Call](../contribute/dev_call.md) - Where release votes happen From a6d50d02bc7bd7897256f85d9b70236bd04d1b5c Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Tue, 10 Feb 2026 14:24:19 -0800 Subject: [PATCH 735/812] docs: address review feedback on release process documentation - Move maintainer link to end of index.md in an info block - Fix link path to use relative ../releases/ prefix - Clarify tag stages apply to release branches - Improve Dronecode Test Team formatting with proper link Signed-off-by: Ramon Roche --- docs/en/releases/index.md | 6 ++++-- docs/en/releases/release_process.md | 4 ++-- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/docs/en/releases/index.md b/docs/en/releases/index.md index d5b0cc01b7..2ed2f9c131 100644 --- a/docs/en/releases/index.md +++ b/docs/en/releases/index.md @@ -2,8 +2,6 @@ A list of PX4 release notes, they contain a list of the changes that went into each release, explaining the included features, bug fixes, deprecations and updates in detail. -For maintainers, see [Release Process](release_process.md) for the tagging and publishing workflow. - - [main](../releases/main.md) (changes planned for v1.18 or later) - [v1.17](../releases/1.17.md) (changes planned for v1.17, since v1.16) - [v1.16](../releases/1.16.md) @@ -13,3 +11,7 @@ For maintainers, see [Release Process](release_process.md) for the tagging and p - [v1.12](../releases/1.12.md) The full archive of releases for the PX4 autopilot project can be found on [GitHub](https://github.com/PX4/PX4-Autopilot/releases) + +::: info +For maintainers, see [Release Process](../releases/release_process.md) for the tagging and publishing workflow. +::: diff --git a/docs/en/releases/release_process.md b/docs/en/releases/release_process.md index 3d13518cc5..7d447b6966 100644 --- a/docs/en/releases/release_process.md +++ b/docs/en/releases/release_process.md @@ -14,7 +14,7 @@ Releases are tracked on the [PX4 Release Project Board](https://github.com/orgs/ ### Release Tag Progression -Each release goes through the following tag stages: +Release branches go through the following tag stages: | Stage | Example | Branch Status | What Gets Merged | |-------|---------|---------------|------------------| @@ -92,7 +92,7 @@ During the alpha phase, review pull requests targeting the release branch: ### 2. Alpha Testing -The [Dronecode Test Team](https://www.ascendengineer.com), provided by Dronecode Silver member Ascend Engineering, conducts initial flight testing of alpha builds using: +The _Dronecode Test Team_ (provided by [Ascend Engineering](https://www.ascendengineer.com) — Dronecode Silver member) conducts initial flight testing of alpha builds using: - The [test cards](../test_and_ci/test_flights.md) documented in the PX4 guide - A hardware matrix covering supported flight controllers and airframes From 71fbc63d6709d610341ceda3f67826c00514e4f7 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Tue, 10 Feb 2026 14:37:06 -0800 Subject: [PATCH 736/812] docs: clarify release cycle, documentation workflow, and gate criteria - Add approximate 6-month release cycle target - Move release notes preparation before branching, based on main.md - Add success criteria for alpha and beta phase transitions Signed-off-by: Ramon Roche --- docs/en/releases/release_process.md | 35 +++++++++++++++++------------ 1 file changed, 21 insertions(+), 14 deletions(-) diff --git a/docs/en/releases/release_process.md b/docs/en/releases/release_process.md index 7d447b6966..6db22a79c9 100644 --- a/docs/en/releases/release_process.md +++ b/docs/en/releases/release_process.md @@ -10,6 +10,8 @@ PX4 uses a branch-based release workflow: - **`stable`** - Points to the latest stable release tag; reset after each release - **`beta`** - For flight testers to validate release candidates +The target release cycle is approximately 6 months, best effort. The actual cadence depends on testing results and maintainer availability, with an ongoing goal to shorten the cycle. + Releases are tracked on the [PX4 Release Project Board](https://github.com/orgs/PX4/projects/45), which is reused and renamed for each release cycle. ### Release Tag Progression @@ -34,6 +36,19 @@ A new release cycle begins immediately after a stable release is published. This 1. **Vote to publish the current release** - Approve the stable release for publication 2. **Vote on the next release name/number** - Decide the version number for the next release (e.g., v1.18 or v2.0) +### Prepare Release Notes Before Branching + +Release notes are built incrementally in [`main.md`](../releases/main.md), which accumulates changes as they land on `main`. Before creating the release branch: + +1. Rename `main.md` to the version-specific file (e.g., `docs/en/releases/1.18.md`) +2. Add the new file to `SUMMARY.md` and `releases/index.md` +3. Reset `main.md` to a clean template for the next release cycle +4. Verify that documentation for all included contributions is complete + +::: tip +Community members are encouraged to document changes as they are merged into `main`. This distributes the documentation workload and ensures changes are captured while they're fresh. +::: + ### Create the Release Branch Once the next release version is decided, create the new release branch from `main`: @@ -67,18 +82,6 @@ git push origin v1.18.0-alpha1 Subsequent alpha tags can be created as fixes are merged (e.g., `v1.18.0-alpha2`, `v1.18.0-alpha3`). -### Create Documentation Early - -Create the release notes page as soon as the release branch is created: - -- Create the new release notes file (e.g., `docs/en/releases/1.18.md`) -- Add the initial structure based on existing release notes -- Add the entry to `SUMMARY.md` and `releases/index.md` - -::: tip -Community members are encouraged to help document changes early in the release cycle. As fixes are merged into the release branch, contributors can add them to the release notes. This distributes the documentation workload and ensures changes are documented while they're fresh. -::: - ## Release Steps ### 1. Review and Merge PRs (Alpha Phase) @@ -99,7 +102,9 @@ The _Dronecode Test Team_ (provided by [Ascend Engineering](https://www.ascenden ### 3. Create Beta Tag -Once alpha testing is successful, create the first beta tag: +The alpha phase is complete when the test team's [test cards](../test_and_ci/test_flights.md) pass across the hardware matrix. If test results show failures, the release stays in alpha until the issues are resolved and the test cards pass. + +Once alpha testing passes, create the first beta tag: ```sh # On the release branch @@ -126,7 +131,9 @@ During beta, continue to: ### 5. Create Release Candidate Tag -Once beta testing is successful, create the first release candidate: +The beta phase is complete when full test card coverage passes across the hardware matrix. If test results show failures, the release stays in beta until the issues are resolved and the test cards pass. + +Once beta testing passes, create the first release candidate: ```sh # On the release branch From 27d831fbcdbc9168dd0b51a2b5e87fda147aabbd Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Tue, 10 Feb 2026 14:39:41 -0800 Subject: [PATCH 737/812] docs: add companion repo branching to release process Include px4_msgs and px4-ros2-interface-lib in the release branch creation steps. Signed-off-by: Ramon Roche --- docs/en/releases/release_process.md | 23 ++++++++++++++++------- 1 file changed, 16 insertions(+), 7 deletions(-) diff --git a/docs/en/releases/release_process.md b/docs/en/releases/release_process.md index 6db22a79c9..aa2a3a99b5 100644 --- a/docs/en/releases/release_process.md +++ b/docs/en/releases/release_process.md @@ -51,20 +51,29 @@ Community members are encouraged to document changes as they are merged into `ma ### Create the Release Branch -Once the next release version is decided, create the new release branch from `main`: +Once the next release version is decided, create the new release branch from `main` in PX4-Autopilot and the companion repositories: ```sh -# Ensure main is up to date -git checkout main -git pull - -# Create the new release branch +# PX4-Autopilot +git checkout main && git pull git checkout -b release/1.18 git push origin release/1.18 ``` +Matching release branches must also be created in: + +- [PX4/px4_msgs](https://github.com/PX4/px4_msgs) +- [Auterion/px4-ros2-interface-lib](https://github.com/Auterion/px4-ros2-interface-lib) + +After creating the companion branches, update the [ROS integration test workflow](https://github.com/PX4/PX4-Autopilot/blob/main/.github/workflows/ros_integration_tests.yml) on the release branch to clone `px4-ros2-interface-lib` from the matching release branch: + +```diff +- git clone --recursive https://github.com/Auterion/px4-ros2-interface-lib.git ++ git clone --recursive --branch release/1.18 https://github.com/Auterion/px4-ros2-interface-lib.git +``` + ::: warning -Once the release branch is created, it only accepts bug fixes and regression fixes. All new feature development continues on `main`. +Once the release branches are created, they only accept bug fixes and regression fixes. All new feature development continues on `main`. ::: ### Create the Alpha Tag From 61da2505fe2b31ad44333b298ff73569e4034f75 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 11 Feb 2026 13:26:19 -0800 Subject: [PATCH 738/812] docs: address review feedback on release process - Add step to replace "main (planned for:" badges with release version when preparing release notes (hamishwillee suggestion) - Define explicit exit criteria for alpha phase: test cards pass, regressions fixed/triaged, documentation complete - Differentiate beta testing from alpha: beta is community-driven validation on extended hardware, not a repeat of alpha test cards - Define explicit exit criteria for beta->RC transition - Fix index.md formatting Signed-off-by: Ramon Roche --- docs/en/releases/index.md | 4 ++-- docs/en/releases/release_process.md | 27 ++++++++++++++++++--------- 2 files changed, 20 insertions(+), 11 deletions(-) diff --git a/docs/en/releases/index.md b/docs/en/releases/index.md index 2ed2f9c131..cb00c401d5 100644 --- a/docs/en/releases/index.md +++ b/docs/en/releases/index.md @@ -10,8 +10,8 @@ A list of PX4 release notes, they contain a list of the changes that went into e - [v1.13](../releases/1.13.md) - [v1.12](../releases/1.12.md) -The full archive of releases for the PX4 autopilot project can be found on [GitHub](https://github.com/PX4/PX4-Autopilot/releases) +The full archive of releases for the PX4 autopilot project can be found on [GitHub](https://github.com/PX4/PX4-Autopilot/releases). -::: info +:::info For maintainers, see [Release Process](../releases/release_process.md) for the tagging and publishing workflow. ::: diff --git a/docs/en/releases/release_process.md b/docs/en/releases/release_process.md index aa2a3a99b5..bcf013935a 100644 --- a/docs/en/releases/release_process.md +++ b/docs/en/releases/release_process.md @@ -44,6 +44,8 @@ Release notes are built incrementally in [`main.md`](../releases/main.md), which 2. Add the new file to `SUMMARY.md` and `releases/index.md` 3. Reset `main.md` to a clean template for the next release cycle 4. Verify that documentation for all included contributions is complete +5. Search for instances of `main (planned for:` and replace with the release version now that it is known. + So, for example `` is replaced with `` ::: tip Community members are encouraged to document changes as they are merged into `main`. This distributes the documentation workload and ensures changes are captured while they're fresh. @@ -109,11 +111,15 @@ The _Dronecode Test Team_ (provided by [Ascend Engineering](https://www.ascenden - The [test cards](../test_and_ci/test_flights.md) documented in the PX4 guide - A hardware matrix covering supported flight controllers and airframes +Alpha testing focuses on identifying regressions and blockers early. The alpha phase is complete when: + +- All test cards pass across the core hardware matrix (no critical or high-severity failures) +- All identified regressions have fixes merged or have been triaged as non-blocking +- Release notes and documentation for included changes are complete + ### 3. Create Beta Tag -The alpha phase is complete when the test team's [test cards](../test_and_ci/test_flights.md) pass across the hardware matrix. If test results show failures, the release stays in alpha until the issues are resolved and the test cards pass. - -Once alpha testing passes, create the first beta tag: +Once the alpha exit criteria above are met, create the first beta tag: ```sh # On the release branch @@ -127,11 +133,11 @@ git push origin v1.18.0-beta1 ### 4. Beta Testing -The test team conducts more extensive testing of beta builds: +Beta builds are published for wider community validation. Unlike alpha testing (which is conducted by the Dronecode Test Team on the core hardware matrix), beta testing focuses on: -- Full test card coverage across the hardware matrix -- Focus on stability and regression testing -- Community testing is encouraged during this phase +- **Community testing** — beta builds are made available for community members to test on their own hardware and airframe configurations +- **Extended hardware coverage** — testing on hardware and configurations beyond the core test matrix +- **Real-world flight scenarios** — longer flights, mission testing, and edge cases not covered by standard test cards During beta, continue to: @@ -140,9 +146,12 @@ During beta, continue to: ### 5. Create Release Candidate Tag -The beta phase is complete when full test card coverage passes across the hardware matrix. If test results show failures, the release stays in beta until the issues are resolved and the test cards pass. +The beta phase is complete when: -Once beta testing passes, create the first release candidate: +- No new critical or high-severity issues are reported for at least one beta tag cycle +- All beta-reported regressions have fixes merged or have been triaged as non-blocking + +Once the beta exit criteria are met, create the first release candidate: ```sh # On the release branch From 5f0e3f600f558911ca3250b4534f390b258636bb Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Thu, 12 Feb 2026 02:06:31 +0000 Subject: [PATCH 739/812] docs: auto-sync metadata [skip ci] Co-Authored-By: PX4 BuildBot --- docs/en/config/_autotune.md | 5 +- docs/en/middleware/dds_topics.md | 364 ++++++++++++++-------------- docs/en/releases/release_process.md | 12 +- 3 files changed, 189 insertions(+), 192 deletions(-) diff --git a/docs/en/config/_autotune.md b/docs/en/config/_autotune.md index c782f212a6..fe5373b169 100644 --- a/docs/en/config/_autotune.md +++ b/docs/en/config/_autotune.md @@ -84,10 +84,7 @@ The test steps are: 1. In QGroundControl, open the menu **Vehicle setup > PID Tuning**: - ![Tuning Setup > Autotune Enabled](../../assets/qgc/setup/autotune/autotune.png) - 2. Select either the _Rate Controller_ or _Attitude Controller_ tabs. - 3. Ensure that the **Autotune enabled** button is enabled (this will display the **Autotune** button and remove the manual tuning selectors). - 4. Read the warning popup and click on **OK** to start tuning. + ![Tuning Setup > Autotune Enabled](../../assets/qgc/setup/autotune/autotune.png) 2. Select either the _Rate Controller_ or _Attitude Controller_ tabs. 3. Ensure that the **Autotune enabled** button is enabled (this will display the **Autotune** button and remove the manual tuning selectors). 4. Read the warning popup and click on **OK** to start tuning.
diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index fa3d583d32..d62a81ab36 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -94,199 +94,199 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages -- [GpsInjectData](../msg_docs/GpsInjectData.md) -- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) -- [AdcReport](../msg_docs/AdcReport.md) -- [EventV0](../msg_docs/EventV0.md) -- [PositionSetpoint](../msg_docs/PositionSetpoint.md) - [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) -- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) -- [AirspeedWind](../msg_docs/AirspeedWind.md) -- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) -- [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [Vtx](../msg_docs/Vtx.md) -- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) -- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) -- [SatelliteInfo](../msg_docs/SatelliteInfo.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) -- [SensorUwb](../msg_docs/SensorUwb.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) -- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [EstimatorStates](../msg_docs/EstimatorStates.md) -- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [SensorGyro](../msg_docs/SensorGyro.md) -- [GainCompression](../msg_docs/GainCompression.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) -- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) -- [DebugArray](../msg_docs/DebugArray.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) -- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) -- [RcChannels](../msg_docs/RcChannels.md) -- [GpsDump](../msg_docs/GpsDump.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) -- [SensorTemp](../msg_docs/SensorTemp.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) -- [OrbTestMedium](../msg_docs/OrbTestMedium.md) -- [VehicleRoi](../msg_docs/VehicleRoi.md) -- [Gripper](../msg_docs/Gripper.md) - [LandingTargetPose](../msg_docs/LandingTargetPose.md) -- [LedControl](../msg_docs/LedControl.md) -- [MountOrientation](../msg_docs/MountOrientation.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) -- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) -- [HealthReport](../msg_docs/HealthReport.md) -- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) -- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [Cpuload](../msg_docs/Cpuload.md) -- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [RtlStatus](../msg_docs/RtlStatus.md) -- [InputRc](../msg_docs/InputRc.md) -- [SensorGyroFft](../msg_docs/SensorGyroFft.md) -- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [SensorsStatus](../msg_docs/SensorsStatus.md) -- [RaptorInput](../msg_docs/RaptorInput.md) -- [EscStatus](../msg_docs/EscStatus.md) -- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [LandingGearWheel](../msg_docs/LandingGearWheel.md) -- [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) -- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) -- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [VehicleImu](../msg_docs/VehicleImu.md) -- [ButtonEvent](../msg_docs/ButtonEvent.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) -- [BatteryInfo](../msg_docs/BatteryInfo.md) -- [IrlockReport](../msg_docs/IrlockReport.md) -- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [ParameterUpdate](../msg_docs/ParameterUpdate.md) -- [QshellReq](../msg_docs/QshellReq.md) -- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) -- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) -- [MissionResult](../msg_docs/MissionResult.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) -- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) -- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) -- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [GeofenceStatus](../msg_docs/GeofenceStatus.md) -- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) -- [CameraStatus](../msg_docs/CameraStatus.md) -- [EstimatorStatus](../msg_docs/EstimatorStatus.md) -- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) -- [FollowTarget](../msg_docs/FollowTarget.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) - [MagWorkerData](../msg_docs/MagWorkerData.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) -- [SensorMag](../msg_docs/SensorMag.md) -- [RcParameterMap](../msg_docs/RcParameterMap.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [SensorBaro](../msg_docs/SensorBaro.md) -- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [VehicleAirData](../msg_docs/VehicleAirData.md) -- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) -- [Airspeed](../msg_docs/Airspeed.md) -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) -- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) -- [Rpm](../msg_docs/Rpm.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) -- [SensorAccel](../msg_docs/SensorAccel.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) -- [Px4ioStatus](../msg_docs/Px4ioStatus.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [SensorCorrection](../msg_docs/SensorCorrection.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) -- [Event](../msg_docs/Event.md) -- [GpioConfig](../msg_docs/GpioConfig.md) -- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [Gripper](../msg_docs/Gripper.md) +- [InputRc](../msg_docs/InputRc.md) - [CellularStatus](../msg_docs/CellularStatus.md) -- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [ActuatorTest](../msg_docs/ActuatorTest.md) -- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) -- [SensorAirflow](../msg_docs/SensorAirflow.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) -- [PpsCapture](../msg_docs/PpsCapture.md) -- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [GpioRequest](../msg_docs/GpioRequest.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) -- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) -- [EstimatorBias](../msg_docs/EstimatorBias.md) -- [Mission](../msg_docs/Mission.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) -- [QshellRetval](../msg_docs/QshellRetval.md) -- [EscReport](../msg_docs/EscReport.md) -- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [SystemPower](../msg_docs/SystemPower.md) +- [VehicleAirData](../msg_docs/VehicleAirData.md) - [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) -- [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) -- [RaptorStatus](../msg_docs/RaptorStatus.md) -- [PwmInput](../msg_docs/PwmInput.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [CameraTrigger](../msg_docs/CameraTrigger.md) -- [RadioStatus](../msg_docs/RadioStatus.md) -- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) -- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) -- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) - [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) -- [DeviceInformation](../msg_docs/DeviceInformation.md) -- [GpioOut](../msg_docs/GpioOut.md) -- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) -- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) - [RoverRateStatus](../msg_docs/RoverRateStatus.md) -- [SensorSelection](../msg_docs/SensorSelection.md) -- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) -- [UlogStreamAck](../msg_docs/UlogStreamAck.md) -- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [SensorsStatus](../msg_docs/SensorsStatus.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [BatteryInfo](../msg_docs/BatteryInfo.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) +- [Cpuload](../msg_docs/Cpuload.md) +- [GpioRequest](../msg_docs/GpioRequest.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) +- [AdcReport](../msg_docs/AdcReport.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [RadioStatus](../msg_docs/RadioStatus.md) +- [Vtx](../msg_docs/Vtx.md) +- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [Ping](../msg_docs/Ping.md) +- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) +- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) +- [PositionSetpoint](../msg_docs/PositionSetpoint.md) +- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) +- [AirspeedWind](../msg_docs/AirspeedWind.md) +- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [Mission](../msg_docs/Mission.md) +- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) +- [NeuralControl](../msg_docs/NeuralControl.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [SensorAccel](../msg_docs/SensorAccel.md) +- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) +- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [SensorMag](../msg_docs/SensorMag.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) +- [CameraCapture](../msg_docs/CameraCapture.md) +- [EstimatorStates](../msg_docs/EstimatorStates.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [DeviceInformation](../msg_docs/DeviceInformation.md) +- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) - [PowerButtonState](../msg_docs/PowerButtonState.md) -- [GeneratorStatus](../msg_docs/GeneratorStatus.md) +- [SystemPower](../msg_docs/SystemPower.md) +- [SensorSelection](../msg_docs/SensorSelection.md) +- [Airspeed](../msg_docs/Airspeed.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [SensorBaro](../msg_docs/SensorBaro.md) +- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [GpioIn](../msg_docs/GpioIn.md) +- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) +- [Rpm](../msg_docs/Rpm.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) +- [IrlockReport](../msg_docs/IrlockReport.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) +- [OrbTest](../msg_docs/OrbTest.md) +- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [FuelTankStatus](../msg_docs/FuelTankStatus.md) +- [FollowTarget](../msg_docs/FollowTarget.md) +- [OrbTestMedium](../msg_docs/OrbTestMedium.md) +- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) +- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [DifferentialPressure](../msg_docs/DifferentialPressure.md) +- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) +- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [VehicleImu](../msg_docs/VehicleImu.md) +- [EscReport](../msg_docs/EscReport.md) +- [SensorGyro](../msg_docs/SensorGyro.md) +- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) - [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) - [OrbTestLarge](../msg_docs/OrbTestLarge.md) -- [LogMessage](../msg_docs/LogMessage.md) -- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [TuneControl](../msg_docs/TuneControl.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) +- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) +- [SensorCorrection](../msg_docs/SensorCorrection.md) +- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) +- [ActuatorTest](../msg_docs/ActuatorTest.md) +- [GpsInjectData](../msg_docs/GpsInjectData.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [RcParameterMap](../msg_docs/RcParameterMap.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) - [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) -- [DebugValue](../msg_docs/DebugValue.md) -- [UlogStream](../msg_docs/UlogStream.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) -- [GpioIn](../msg_docs/GpioIn.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [TecsStatus](../msg_docs/TecsStatus.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [ButtonEvent](../msg_docs/ButtonEvent.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) +- [SensorHygrometer](../msg_docs/SensorHygrometer.md) +- [SatelliteInfo](../msg_docs/SatelliteInfo.md) +- [RtlStatus](../msg_docs/RtlStatus.md) +- [CameraStatus](../msg_docs/CameraStatus.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) +- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [QshellReq](../msg_docs/QshellReq.md) +- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [LedControl](../msg_docs/LedControl.md) +- [RcChannels](../msg_docs/RcChannels.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [GpsDump](../msg_docs/GpsDump.md) +- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) +- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) - [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [NeuralControl](../msg_docs/NeuralControl.md) -- [Ping](../msg_docs/Ping.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) -- [ActionRequest](../msg_docs/ActionRequest.md) -- [ActuatorArmed](../msg_docs/ActuatorArmed.md) -- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [SensorAirflow](../msg_docs/SensorAirflow.md) +- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [SensorUwb](../msg_docs/SensorUwb.md) +- [GainCompression](../msg_docs/GainCompression.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [Event](../msg_docs/Event.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [LogMessage](../msg_docs/LogMessage.md) +- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) +- [GpioConfig](../msg_docs/GpioConfig.md) +- [EventV0](../msg_docs/EventV0.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) +- [LandingGearWheel](../msg_docs/LandingGearWheel.md) +- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) +- [UlogStream](../msg_docs/UlogStream.md) +- [MissionResult](../msg_docs/MissionResult.md) +- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [QshellRetval](../msg_docs/QshellRetval.md) +- [CameraTrigger](../msg_docs/CameraTrigger.md) +- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [PpsCapture](../msg_docs/PpsCapture.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) +- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) +- [GpioOut](../msg_docs/GpioOut.md) +- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) - [GimbalControls](../msg_docs/GimbalControls.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [DebugValue](../msg_docs/DebugValue.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) +- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [GeneratorStatus](../msg_docs/GeneratorStatus.md) +- [GeofenceStatus](../msg_docs/GeofenceStatus.md) +- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) +- [ActuatorArmed](../msg_docs/ActuatorArmed.md) +- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) +- [HealthReport](../msg_docs/HealthReport.md) +- [ActionRequest](../msg_docs/ActionRequest.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) +- [EstimatorStatus](../msg_docs/EstimatorStatus.md) +- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) +- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [PwmInput](../msg_docs/PwmInput.md) +- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [VehicleRoi](../msg_docs/VehicleRoi.md) ::: diff --git a/docs/en/releases/release_process.md b/docs/en/releases/release_process.md index bcf013935a..73745a0cd3 100644 --- a/docs/en/releases/release_process.md +++ b/docs/en/releases/release_process.md @@ -18,12 +18,12 @@ Releases are tracked on the [PX4 Release Project Board](https://github.com/orgs/ Release branches go through the following tag stages: -| Stage | Example | Branch Status | What Gets Merged | -|-------|---------|---------------|------------------| -| **Alpha** | `v1.18.0-alpha1` | Open for fixes | Bug fixes and regression fixes only | -| **Beta** | `v1.18.0-beta1` | Open for fixes | Bug fixes and regression fixes only | -| **RC** | `v1.18.0-rc1` | Frozen | Nothing (unless veto vote passes) | -| **Stable** | `v1.18.0` | Open for fixes | Bug fixes and regression fixes (for point releases) | +| Stage | Example | Branch Status | What Gets Merged | +| ---------- | ---------------- | -------------- | --------------------------------------------------- | +| **Alpha** | `v1.18.0-alpha1` | Open for fixes | Bug fixes and regression fixes only | +| **Beta** | `v1.18.0-beta1` | Open for fixes | Bug fixes and regression fixes only | +| **RC** | `v1.18.0-rc1` | Frozen | Nothing (unless veto vote passes) | +| **Stable** | `v1.18.0` | Open for fixes | Bug fixes and regression fixes (for point releases) | ::: info New features are never merged to release branches. Once a release branch is created from `main`, only bug fixes and regression fixes are accepted. New features must target `main` and will be included in the next release cycle. From e239c017d19f38fc677c0b56909855689636ba1a Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 12 Feb 2026 13:03:35 +1300 Subject: [PATCH 740/812] Revert "CI: add ccache to macOS" This reverts commit f751974b41c2e0d4c4e7074bc895e0d2068f5e7f. --- Tools/setup/macos.sh | 6 ------ 1 file changed, 6 deletions(-) diff --git a/Tools/setup/macos.sh b/Tools/setup/macos.sh index d1750bcb3d..a3457129ee 100755 --- a/Tools/setup/macos.sh +++ b/Tools/setup/macos.sh @@ -66,12 +66,6 @@ else fi fi -# Install ccache (used by cmake/ccache.cmake to speed up builds) -if ! command -v ccache &> /dev/null; then - echo "[macos.sh] Installing ccache" - brew install ccache -fi - # Python dependencies echo "[macos.sh] Installing Python3 dependencies" # We need to have future to install pymavlink later. From 41179125061eb065190ed37d0b6a6f3572085c95 Mon Sep 17 00:00:00 2001 From: fakerror <7368920+fakerror@users.noreply.github.com> Date: Thu, 12 Feb 2026 13:25:12 +0800 Subject: [PATCH 741/812] docs: clarify rover MAVLink offboard support (#26411) * docs: clarify rover MAVLink offboard support * Apply suggestion from @hamishwillee --------- Co-authored-by: Hamish Willee --- docs/en/flight_modes/offboard.md | 28 +++++++++++++++++++++++++--- 1 file changed, 25 insertions(+), 3 deletions(-) diff --git a/docs/en/flight_modes/offboard.md b/docs/en/flight_modes/offboard.md index 58143c0605..353c9b75a0 100644 --- a/docs/en/flight_modes/offboard.md +++ b/docs/en/flight_modes/offboard.md @@ -228,7 +228,7 @@ The following MAVLink messages and their particular fields and field values are - Position setpoint **and** velocity setpoint (the velocity setpoint is used as feedforward; it is added to the output of the position controller and the result is used as the input to the velocity controller). - - PX4 supports the following `coordinate_frame` values (only): [MAV_FRAME_GLOBAL](https://mavlink.io/en/messages/common.html#MAV_FRAME_GLOBAL). + - PX4 supports the following `coordinate_frame` values (only): [MAV_FRAME_GLOBAL_INT](https://mavlink.io/en/messages/common.html#MAV_FRAME_GLOBAL_INT), [MAV_FRAME_GLOBAL_RELATIVE_ALT_INT](https://mavlink.io/en/messages/common.html#MAV_FRAME_GLOBAL_RELATIVE_ALT_INT), [MAV_FRAME_GLOBAL_TERRAIN_ALT_INT](https://mavlink.io/en/messages/common.html#MAV_FRAME_GLOBAL_TERRAIN_ALT_INT). - [SET_ATTITUDE_TARGET](https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET) - The following input combinations are supported: @@ -271,7 +271,7 @@ The following MAVLink messages and their particular fields and field values are - 12288: Loiter setpoint (fly a circle centred on setpoint). - 16384: Idle setpoint (zero throttle, zero roll / pitch). - - PX4 supports the following `coordinate_frame` values (only): [MAV_FRAME_GLOBAL](https://mavlink.io/en/messages/common.html#MAV_FRAME_GLOBAL). + - PX4 supports the following `coordinate_frame` values (only): [MAV_FRAME_GLOBAL_INT](https://mavlink.io/en/messages/common.html#MAV_FRAME_GLOBAL_INT), [MAV_FRAME_GLOBAL_RELATIVE_ALT_INT](https://mavlink.io/en/messages/common.html#MAV_FRAME_GLOBAL_RELATIVE_ALT_INT), [MAV_FRAME_GLOBAL_TERRAIN_ALT_INT](https://mavlink.io/en/messages/common.html#MAV_FRAME_GLOBAL_TERRAIN_ALT_INT). - [SET_ATTITUDE_TARGET](https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET) - The following input combinations are supported: @@ -280,7 +280,29 @@ The following MAVLink messages and their particular fields and field values are ### Rover -Rover does not support a MAVLink offboard API (ROS2 is supported). +Rover supports offboard control using the generic MAVLink position/velocity setpoint messages listed below. +These are converted into a [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) internally, and then into rover setpoints by the rover offboard modes. +For rover-specific control setpoints and better behaviour we recommend using the [Rover Setpoints](#rover-setpoints) via ROS 2. + +::: info +Rover MAVLink setpoints are gated by the MAVLink parameter [MAV_FWDEXTSP](../advanced_config/parameter_reference.md#MAV_FWDEXTSP) (Forward external setpoint messages). +::: + +- [SET_POSITION_TARGET_LOCAL_NED](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_LOCAL_NED) + - Position setpoint: `x`, `y` in [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED) (`z` is ignored by rover modules). + - Velocity setpoint: `vx`, `vy` in [MAV_FRAME_LOCAL_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_LOCAL_NED) or [MAV_FRAME_BODY_NED](https://mavlink.io/en/messages/common.html#MAV_FRAME_BODY_NED). + - `yaw`/`yaw_rate`: + - Ackermann/Differential: ignored (in velocity control the yaw setpoint is derived from the velocity direction). + - Mecanum: can be controlled independently (decoupled) using `yaw`/`yaw_rate`. + - Acceleration setpoints (`afx`, `afy`, `afz`) are ignored by rover modules. + +- [SET_POSITION_TARGET_GLOBAL_INT](https://mavlink.io/en/messages/common.html#SET_POSITION_TARGET_GLOBAL_INT) + - Position setpoint: `lat_int`, `lon_int`, `alt` (converted into local NED internally; rover modules only use the horizontal components). + - Velocity setpoint: `vx`, `vy`, `vz` (rover modules use only the horizontal components). + - PX4 supports the following `coordinate_frame` values (only): [MAV_FRAME_GLOBAL_INT](https://mavlink.io/en/messages/common.html#MAV_FRAME_GLOBAL_INT), [MAV_FRAME_GLOBAL_RELATIVE_ALT_INT](https://mavlink.io/en/messages/common.html#MAV_FRAME_GLOBAL_RELATIVE_ALT_INT), [MAV_FRAME_GLOBAL_TERRAIN_ALT_INT](https://mavlink.io/en/messages/common.html#MAV_FRAME_GLOBAL_TERRAIN_ALT_INT). + +- [SET_ATTITUDE_TARGET](https://mavlink.io/en/messages/common.html#SET_ATTITUDE_TARGET) + - Not supported for rover offboard control. ## Offboard Parameters From d6c4dd22da73daec44b02cce8ce93459a3cea7bc Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Thu, 12 Feb 2026 05:32:38 +0000 Subject: [PATCH 742/812] docs: auto-sync metadata [skip ci] Co-Authored-By: PX4 BuildBot --- docs/en/middleware/dds_topics.md | 374 +++++++++++++++---------------- 1 file changed, 187 insertions(+), 187 deletions(-) diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index d62a81ab36..a986a30818 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -94,199 +94,199 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages -- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) -- [LandingTargetPose](../msg_docs/LandingTargetPose.md) -- [MagWorkerData](../msg_docs/MagWorkerData.md) -- [Gripper](../msg_docs/Gripper.md) -- [InputRc](../msg_docs/InputRc.md) -- [CellularStatus](../msg_docs/CellularStatus.md) -- [VehicleAirData](../msg_docs/VehicleAirData.md) -- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) -- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) -- [RoverRateStatus](../msg_docs/RoverRateStatus.md) -- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) -- [SensorsStatus](../msg_docs/SensorsStatus.md) -- [RaptorStatus](../msg_docs/RaptorStatus.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [BatteryInfo](../msg_docs/BatteryInfo.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [Cpuload](../msg_docs/Cpuload.md) -- [GpioRequest](../msg_docs/GpioRequest.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) -- [AdcReport](../msg_docs/AdcReport.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [RadioStatus](../msg_docs/RadioStatus.md) -- [Vtx](../msg_docs/Vtx.md) -- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) -- [Ping](../msg_docs/Ping.md) -- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) -- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) -- [PositionSetpoint](../msg_docs/PositionSetpoint.md) -- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [AirspeedWind](../msg_docs/AirspeedWind.md) -- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) -- [Mission](../msg_docs/Mission.md) -- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) -- [NeuralControl](../msg_docs/NeuralControl.md) -- [MountOrientation](../msg_docs/MountOrientation.md) -- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) -- [SensorAccel](../msg_docs/SensorAccel.md) -- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) -- [SensorMag](../msg_docs/SensorMag.md) -- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [EstimatorStates](../msg_docs/EstimatorStates.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) -- [EstimatorBias](../msg_docs/EstimatorBias.md) -- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) -- [DeviceInformation](../msg_docs/DeviceInformation.md) -- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) -- [PowerButtonState](../msg_docs/PowerButtonState.md) -- [SystemPower](../msg_docs/SystemPower.md) - [SensorSelection](../msg_docs/SensorSelection.md) -- [Airspeed](../msg_docs/Airspeed.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) -- [RaptorInput](../msg_docs/RaptorInput.md) -- [SensorBaro](../msg_docs/SensorBaro.md) -- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) -- [SensorTemp](../msg_docs/SensorTemp.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) -- [GpioIn](../msg_docs/GpioIn.md) +- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) +- [SensorCorrection](../msg_docs/SensorCorrection.md) +- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [EstimatorStatus](../msg_docs/EstimatorStatus.md) +- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [CameraStatus](../msg_docs/CameraStatus.md) +- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [PowerButtonState](../msg_docs/PowerButtonState.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) +- [PositionSetpoint](../msg_docs/PositionSetpoint.md) +- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) +- [ActuatorArmed](../msg_docs/ActuatorArmed.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [RtlStatus](../msg_docs/RtlStatus.md) +- [MissionResult](../msg_docs/MissionResult.md) - [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) -- [Rpm](../msg_docs/Rpm.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [CameraCapture](../msg_docs/CameraCapture.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [Gripper](../msg_docs/Gripper.md) +- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) +- [RcChannels](../msg_docs/RcChannels.md) +- [GeneratorStatus](../msg_docs/GeneratorStatus.md) +- [FuelTankStatus](../msg_docs/FuelTankStatus.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) +- [VehicleImu](../msg_docs/VehicleImu.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [SensorAccel](../msg_docs/SensorAccel.md) - [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) - [IrlockReport](../msg_docs/IrlockReport.md) -- [EscStatus](../msg_docs/EscStatus.md) -- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) -- [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [FollowTarget](../msg_docs/FollowTarget.md) -- [OrbTestMedium](../msg_docs/OrbTestMedium.md) -- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) -- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [Px4ioStatus](../msg_docs/Px4ioStatus.md) -- [VehicleImu](../msg_docs/VehicleImu.md) -- [EscReport](../msg_docs/EscReport.md) -- [SensorGyro](../msg_docs/SensorGyro.md) -- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) -- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) -- [OrbTestLarge](../msg_docs/OrbTestLarge.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) -- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) -- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) -- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [SensorCorrection](../msg_docs/SensorCorrection.md) -- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) -- [ActuatorTest](../msg_docs/ActuatorTest.md) -- [GpsInjectData](../msg_docs/GpsInjectData.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [RcParameterMap](../msg_docs/RcParameterMap.md) -- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) -- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [ButtonEvent](../msg_docs/ButtonEvent.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [SatelliteInfo](../msg_docs/SatelliteInfo.md) -- [RtlStatus](../msg_docs/RtlStatus.md) -- [CameraStatus](../msg_docs/CameraStatus.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) -- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) -- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) -- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) -- [QshellReq](../msg_docs/QshellReq.md) -- [UlogStreamAck](../msg_docs/UlogStreamAck.md) -- [LedControl](../msg_docs/LedControl.md) -- [RcChannels](../msg_docs/RcChannels.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [GpsDump](../msg_docs/GpsDump.md) -- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) -- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) -- [SensorAirflow](../msg_docs/SensorAirflow.md) -- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [Airspeed](../msg_docs/Airspeed.md) - [SensorUwb](../msg_docs/SensorUwb.md) -- [GainCompression](../msg_docs/GainCompression.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) -- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) -- [Event](../msg_docs/Event.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [LogMessage](../msg_docs/LogMessage.md) -- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) -- [GpioConfig](../msg_docs/GpioConfig.md) -- [EventV0](../msg_docs/EventV0.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [LandingGearWheel](../msg_docs/LandingGearWheel.md) -- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [TuneControl](../msg_docs/TuneControl.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) -- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) -- [UlogStream](../msg_docs/UlogStream.md) -- [MissionResult](../msg_docs/MissionResult.md) -- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) -- [QshellRetval](../msg_docs/QshellRetval.md) -- [CameraTrigger](../msg_docs/CameraTrigger.md) -- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) -- [PpsCapture](../msg_docs/PpsCapture.md) -- [TecsStatus](../msg_docs/TecsStatus.md) -- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) -- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) -- [GpioOut](../msg_docs/GpioOut.md) +- [VehicleAirData](../msg_docs/VehicleAirData.md) - [ParameterUpdate](../msg_docs/ParameterUpdate.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) -- [DebugArray](../msg_docs/DebugArray.md) -- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) -- [GimbalControls](../msg_docs/GimbalControls.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) -- [DebugValue](../msg_docs/DebugValue.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [GeneratorStatus](../msg_docs/GeneratorStatus.md) - [GeofenceStatus](../msg_docs/GeofenceStatus.md) -- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [ActuatorArmed](../msg_docs/ActuatorArmed.md) -- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) -- [HealthReport](../msg_docs/HealthReport.md) -- [ActionRequest](../msg_docs/ActionRequest.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [EstimatorStatus](../msg_docs/EstimatorStatus.md) -- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) -- [PwmInput](../msg_docs/PwmInput.md) -- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) +- [RadioStatus](../msg_docs/RadioStatus.md) +- [Mission](../msg_docs/Mission.md) - [VehicleRoi](../msg_docs/VehicleRoi.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) +- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) +- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) +- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) +- [GainCompression](../msg_docs/GainCompression.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) +- [LogMessage](../msg_docs/LogMessage.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [LedControl](../msg_docs/LedControl.md) +- [GimbalControls](../msg_docs/GimbalControls.md) +- [OrbTestMedium](../msg_docs/OrbTestMedium.md) +- [DifferentialPressure](../msg_docs/DifferentialPressure.md) +- [SensorsStatus](../msg_docs/SensorsStatus.md) +- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [CameraTrigger](../msg_docs/CameraTrigger.md) +- [HealthReport](../msg_docs/HealthReport.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) +- [GpioOut](../msg_docs/GpioOut.md) +- [InputRc](../msg_docs/InputRc.md) +- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [MagWorkerData](../msg_docs/MagWorkerData.md) +- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) +- [FollowTarget](../msg_docs/FollowTarget.md) +- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) +- [PwmInput](../msg_docs/PwmInput.md) +- [Vtx](../msg_docs/Vtx.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) +- [QshellRetval](../msg_docs/QshellRetval.md) +- [OrbTestLarge](../msg_docs/OrbTestLarge.md) +- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) +- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) +- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) +- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) +- [CellularStatus](../msg_docs/CellularStatus.md) +- [LandingTargetPose](../msg_docs/LandingTargetPose.md) +- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) +- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [RoverRateStatus](../msg_docs/RoverRateStatus.md) +- [LandingGearWheel](../msg_docs/LandingGearWheel.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [SensorGyro](../msg_docs/SensorGyro.md) +- [UlogStream](../msg_docs/UlogStream.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) +- [DeviceInformation](../msg_docs/DeviceInformation.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [GpsInjectData](../msg_docs/GpsInjectData.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) +- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) +- [GpsDump](../msg_docs/GpsDump.md) +- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) +- [EventV0](../msg_docs/EventV0.md) +- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) +- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [Event](../msg_docs/Event.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [SensorMag](../msg_docs/SensorMag.md) +- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) +- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) +- [PpsCapture](../msg_docs/PpsCapture.md) +- [AirspeedWind](../msg_docs/AirspeedWind.md) +- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) +- [SystemPower](../msg_docs/SystemPower.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) +- [QshellReq](../msg_docs/QshellReq.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) +- [SensorBaro](../msg_docs/SensorBaro.md) +- [Rpm](../msg_docs/Rpm.md) +- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) +- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) +- [RcParameterMap](../msg_docs/RcParameterMap.md) +- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [SatelliteInfo](../msg_docs/SatelliteInfo.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) +- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) +- [GpioRequest](../msg_docs/GpioRequest.md) +- [EstimatorStates](../msg_docs/EstimatorStates.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) +- [Cpuload](../msg_docs/Cpuload.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [GpioConfig](../msg_docs/GpioConfig.md) +- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) +- [SensorAirflow](../msg_docs/SensorAirflow.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) +- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) +- [ActuatorTest](../msg_docs/ActuatorTest.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [ButtonEvent](../msg_docs/ButtonEvent.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [OrbTest](../msg_docs/OrbTest.md) +- [SensorHygrometer](../msg_docs/SensorHygrometer.md) +- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [BatteryInfo](../msg_docs/BatteryInfo.md) +- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [ActionRequest](../msg_docs/ActionRequest.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [NeuralControl](../msg_docs/NeuralControl.md) +- [AdcReport](../msg_docs/AdcReport.md) +- [EscReport](../msg_docs/EscReport.md) +- [Ping](../msg_docs/Ping.md) +- [DebugValue](../msg_docs/DebugValue.md) +- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) +- [GpioIn](../msg_docs/GpioIn.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) ::: From 53a14d10cdbd94a281945ba6c9039a659fadb154 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 12 Feb 2026 16:39:11 +1100 Subject: [PATCH 743/812] docs: Rover flashing update (#26409) --- docs/en/config_rover/index.md | 44 +++++++++++++++++++++-------------- docs/en/frames_rover/index.md | 6 +++++ 2 files changed, 33 insertions(+), 17 deletions(-) diff --git a/docs/en/config_rover/index.md b/docs/en/config_rover/index.md index 6c14cc41fb..366377c8ab 100644 --- a/docs/en/config_rover/index.md +++ b/docs/en/config_rover/index.md @@ -18,27 +18,37 @@ A drive mode will only work properly if all the configuration for the preceding ## Flashing the Rover Build -Rovers use a custom build that must be flashed onto your flight controller instead of the default PX4 build: +Rover is built as a [firmware variant](../dev_setup/building_px4.md#px4-make-build-targets), and must be installed as "Custom Firmware" in QGC (other vehicles are present in the default variant). -1. First build the rover firmware for your flight controller from the `main` branch (there is no release build, so you can't just select this build from QGroundControl). +The release versions of Rover firmware for different boards are attached to the associated GitHub release tag. +For example, you can find `px4_fmu-v5x_rover.px4` on [PX4-Autopilot/releases/tag/v1.16.1](https://github.com/PX4/PX4-Autopilot/releases/tag/v1.16.1). +For the `main` branch version of Rover you will need to [build the firmware](#building-rover). - To build for rover with the `make` command, replace the `_default` suffix with `_rover`. - For example, to build rover for px4_fmu-v6x boards, you would use the command: +Load the firmware onto your flight controller as "Custom Firmware" (see [Loading Firmware > Installing PX4 Main, Beta or Custom Firmware](../config/firmware.md#installing-px4-main-beta-or-custom-firmware)). - ```sh - make px4_fmu-v6x_rover - ``` +## Building Rover - ::: info - You can also enable the modules in default builds by adding these lines to your [board configuration](../hardware/porting_guide_config.md) (e.g. for fmu-v6x you might add them to [`main/boards/px4/fmu-v6x/default.px4board`](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/fmu-v6x/default.px4board)): +Rover is built as the `rover` [firmware variant](../dev_setup/building_px4.md#px4-make-build-targets). +What this means is that when building the firmware with the `make` command, you replace the `_default` suffix in the configuration target with `_rover`. - ```sh - CONFIG_MODULES_ROVER_ACKERMANN=y - CONFIG_MODULES_ROVER_DIFFERENTIAL=y - CONFIG_MODULES_ROVER_MECANUM=y - ``` +For example, to build rover for `px4_fmu-v6x` boards, you would use the following command: - Note that adding the rover modules may lead to flash overflow, in which case you will need to disable modules that you do not plan to use (such as those related to multicopter or fixed wing). - ::: +```sh +make px4_fmu-v6x_rover +``` -2. Load the **custom firmware** that you just built onto your flight controller (see [Loading Firmware > Installing PX4 Main, Beta or Custom Firmware](../config/firmware.md#installing-px4-main-beta-or-custom-firmware)). +Note that configuration targets are constructed with the format "VENDOR_MODEL_VARIANT". + +The built firmware can be installed as custom firmware, as shown above in in [Flashing the Rover Build](#flashing-the-rover-build). + +::: info +You can also enable the modules in default builds by adding these lines to your [board configuration](../hardware/porting_guide_config.md) (e.g. for fmu-v6x you might add them to [`main/boards/px4/fmu-v6x/default.px4board`](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/fmu-v6x/default.px4board)): + +```sh +CONFIG_MODULES_ROVER_ACKERMANN=y +CONFIG_MODULES_ROVER_DIFFERENTIAL=y +CONFIG_MODULES_ROVER_MECANUM=y +``` + +Adding the rover modules may lead to flash overflow, in which case you will need to disable modules that you do not plan to use (such as those related to multicopter or fixed wing). +::: diff --git a/docs/en/frames_rover/index.md b/docs/en/frames_rover/index.md index b3a705ed31..f897cf6275 100644 --- a/docs/en/frames_rover/index.md +++ b/docs/en/frames_rover/index.md @@ -7,6 +7,12 @@ Support for rover is [experimental](../airframes/index.md#experimental-vehicles) Maintainer volunteers, [contribution](../contribute/index.md) of new features, new frame configurations, or other improvements would all be very welcome! ::: +::: tip +Rover is not in the default PX4 firmware downloaded from QGC. +Unlike for other vehicle types you will need to install it as custom firmware. +For more information see [Flashing the Rover Build](../config_rover/index.md#flashing-the-rover-build). +::: + ![Rovers](../../assets/airframes/rover/rovers.png) PX4 provides support for the three most common types of rovers: From ec278758eda642005a479e2f8d278f2be8795eaf Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Thu, 12 Feb 2026 05:57:26 +0000 Subject: [PATCH 744/812] docs: auto-sync metadata [skip ci] Co-Authored-By: PX4 BuildBot --- docs/en/middleware/dds_topics.md | 372 +++++++++++++++---------------- 1 file changed, 186 insertions(+), 186 deletions(-) diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index a986a30818..91e30ef6cd 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -94,199 +94,199 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages -- [SensorSelection](../msg_docs/SensorSelection.md) -- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) -- [SensorCorrection](../msg_docs/SensorCorrection.md) -- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) -- [EstimatorStatus](../msg_docs/EstimatorStatus.md) -- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) -- [CameraStatus](../msg_docs/CameraStatus.md) -- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) -- [PowerButtonState](../msg_docs/PowerButtonState.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) -- [PositionSetpoint](../msg_docs/PositionSetpoint.md) -- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [ActuatorArmed](../msg_docs/ActuatorArmed.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [RtlStatus](../msg_docs/RtlStatus.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [DebugValue](../msg_docs/DebugValue.md) - [MissionResult](../msg_docs/MissionResult.md) -- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [EstimatorBias](../msg_docs/EstimatorBias.md) -- [Gripper](../msg_docs/Gripper.md) -- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) -- [RcChannels](../msg_docs/RcChannels.md) -- [GeneratorStatus](../msg_docs/GeneratorStatus.md) -- [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) -- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) -- [VehicleImu](../msg_docs/VehicleImu.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [SensorAccel](../msg_docs/SensorAccel.md) -- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) -- [IrlockReport](../msg_docs/IrlockReport.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) -- [Airspeed](../msg_docs/Airspeed.md) -- [SensorUwb](../msg_docs/SensorUwb.md) -- [VehicleAirData](../msg_docs/VehicleAirData.md) -- [ParameterUpdate](../msg_docs/ParameterUpdate.md) -- [GeofenceStatus](../msg_docs/GeofenceStatus.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [RadioStatus](../msg_docs/RadioStatus.md) -- [Mission](../msg_docs/Mission.md) -- [VehicleRoi](../msg_docs/VehicleRoi.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) -- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [TecsStatus](../msg_docs/TecsStatus.md) -- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) -- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) -- [GainCompression](../msg_docs/GainCompression.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) -- [LogMessage](../msg_docs/LogMessage.md) -- [MountOrientation](../msg_docs/MountOrientation.md) -- [LedControl](../msg_docs/LedControl.md) -- [GimbalControls](../msg_docs/GimbalControls.md) -- [OrbTestMedium](../msg_docs/OrbTestMedium.md) -- [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [SensorsStatus](../msg_docs/SensorsStatus.md) -- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) -- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) -- [CameraTrigger](../msg_docs/CameraTrigger.md) -- [HealthReport](../msg_docs/HealthReport.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [RaptorInput](../msg_docs/RaptorInput.md) -- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) -- [GpioOut](../msg_docs/GpioOut.md) -- [InputRc](../msg_docs/InputRc.md) -- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [MagWorkerData](../msg_docs/MagWorkerData.md) -- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) -- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) -- [FollowTarget](../msg_docs/FollowTarget.md) -- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) -- [EscStatus](../msg_docs/EscStatus.md) -- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) -- [PwmInput](../msg_docs/PwmInput.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) - [Vtx](../msg_docs/Vtx.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [QshellRetval](../msg_docs/QshellRetval.md) -- [OrbTestLarge](../msg_docs/OrbTestLarge.md) -- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) -- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) -- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) -- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) -- [CellularStatus](../msg_docs/CellularStatus.md) -- [LandingTargetPose](../msg_docs/LandingTargetPose.md) -- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) -- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) -- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) -- [RoverRateStatus](../msg_docs/RoverRateStatus.md) -- [LandingGearWheel](../msg_docs/LandingGearWheel.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [SensorGyro](../msg_docs/SensorGyro.md) -- [UlogStream](../msg_docs/UlogStream.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) -- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [DeviceInformation](../msg_docs/DeviceInformation.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) -- [GpsInjectData](../msg_docs/GpsInjectData.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) -- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) -- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) -- [GpsDump](../msg_docs/GpsDump.md) -- [UlogStreamAck](../msg_docs/UlogStreamAck.md) -- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [EventV0](../msg_docs/EventV0.md) -- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) -- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) -- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [GimbalControls](../msg_docs/GimbalControls.md) - [Event](../msg_docs/Event.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) -- [Px4ioStatus](../msg_docs/Px4ioStatus.md) -- [SensorMag](../msg_docs/SensorMag.md) +- [NeuralControl](../msg_docs/NeuralControl.md) +- [DifferentialPressure](../msg_docs/DifferentialPressure.md) +- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) +- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [FollowTarget](../msg_docs/FollowTarget.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) +- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) +- [ButtonEvent](../msg_docs/ButtonEvent.md) +- [OrbTestLarge](../msg_docs/OrbTestLarge.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) +- [CellularStatus](../msg_docs/CellularStatus.md) +- [PowerButtonState](../msg_docs/PowerButtonState.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) +- [OrbTestMedium](../msg_docs/OrbTestMedium.md) +- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [RcChannels](../msg_docs/RcChannels.md) +- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) +- [InputRc](../msg_docs/InputRc.md) - [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) -- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) -- [PpsCapture](../msg_docs/PpsCapture.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) +- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) +- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) +- [CameraCapture](../msg_docs/CameraCapture.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [LandingTargetPose](../msg_docs/LandingTargetPose.md) +- [SensorsStatus](../msg_docs/SensorsStatus.md) +- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [LogMessage](../msg_docs/LogMessage.md) +- [SensorAirflow](../msg_docs/SensorAirflow.md) +- [ActionRequest](../msg_docs/ActionRequest.md) +- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) +- [RoverRateStatus](../msg_docs/RoverRateStatus.md) +- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [SystemPower](../msg_docs/SystemPower.md) +- [EscReport](../msg_docs/EscReport.md) +- [GpsInjectData](../msg_docs/GpsInjectData.md) +- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) +- [GainCompression](../msg_docs/GainCompression.md) +- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) +- [ActuatorTest](../msg_docs/ActuatorTest.md) +- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) +- [EstimatorStatus](../msg_docs/EstimatorStatus.md) +- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [GeneratorStatus](../msg_docs/GeneratorStatus.md) +- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) +- [FuelTankStatus](../msg_docs/FuelTankStatus.md) +- [GpioConfig](../msg_docs/GpioConfig.md) +- [OrbTest](../msg_docs/OrbTest.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) +- [Cpuload](../msg_docs/Cpuload.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [QshellRetval](../msg_docs/QshellRetval.md) +- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [LandingGearWheel](../msg_docs/LandingGearWheel.md) +- [Mission](../msg_docs/Mission.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) +- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) +- [DeviceInformation](../msg_docs/DeviceInformation.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [LedControl](../msg_docs/LedControl.md) +- [SensorSelection](../msg_docs/SensorSelection.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) +- [QshellReq](../msg_docs/QshellReq.md) +- [EventV0](../msg_docs/EventV0.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [EstimatorStates](../msg_docs/EstimatorStates.md) +- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) +- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) +- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) +- [RtlStatus](../msg_docs/RtlStatus.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [AdcReport](../msg_docs/AdcReport.md) +- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) +- [GpioRequest](../msg_docs/GpioRequest.md) +- [SatelliteInfo](../msg_docs/SatelliteInfo.md) +- [IrlockReport](../msg_docs/IrlockReport.md) +- [Rpm](../msg_docs/Rpm.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [GpioOut](../msg_docs/GpioOut.md) +- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) +- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) +- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) +- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) +- [SensorGyro](../msg_docs/SensorGyro.md) +- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [HealthReport](../msg_docs/HealthReport.md) +- [GpsDump](../msg_docs/GpsDump.md) +- [SensorAccel](../msg_docs/SensorAccel.md) +- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) +- [Airspeed](../msg_docs/Airspeed.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) +- [MagWorkerData](../msg_docs/MagWorkerData.md) +- [PwmInput](../msg_docs/PwmInput.md) +- [CameraTrigger](../msg_docs/CameraTrigger.md) +- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [ActuatorArmed](../msg_docs/ActuatorArmed.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) +- [Gripper](../msg_docs/Gripper.md) +- [VehicleRoi](../msg_docs/VehicleRoi.md) - [AirspeedWind](../msg_docs/AirspeedWind.md) - [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) -- [SystemPower](../msg_docs/SystemPower.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) -- [RaptorStatus](../msg_docs/RaptorStatus.md) -- [QshellReq](../msg_docs/QshellReq.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [SensorTemp](../msg_docs/SensorTemp.md) -- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) -- [SensorBaro](../msg_docs/SensorBaro.md) -- [Rpm](../msg_docs/Rpm.md) -- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) -- [RcParameterMap](../msg_docs/RcParameterMap.md) -- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) -- [SatelliteInfo](../msg_docs/SatelliteInfo.md) -- [DebugArray](../msg_docs/DebugArray.md) -- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) -- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [GpioRequest](../msg_docs/GpioRequest.md) -- [EstimatorStates](../msg_docs/EstimatorStates.md) -- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) -- [Cpuload](../msg_docs/Cpuload.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) -- [SensorGyroFft](../msg_docs/SensorGyroFft.md) -- [GpioConfig](../msg_docs/GpioConfig.md) -- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) -- [SensorAirflow](../msg_docs/SensorAirflow.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) -- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) -- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) -- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) -- [ActuatorTest](../msg_docs/ActuatorTest.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) -- [ButtonEvent](../msg_docs/ButtonEvent.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) - [BatteryInfo](../msg_docs/BatteryInfo.md) -- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) -- [ActionRequest](../msg_docs/ActionRequest.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [TuneControl](../msg_docs/TuneControl.md) -- [NeuralControl](../msg_docs/NeuralControl.md) -- [AdcReport](../msg_docs/AdcReport.md) -- [EscReport](../msg_docs/EscReport.md) +- [RadioStatus](../msg_docs/RadioStatus.md) +- [VehicleAirData](../msg_docs/VehicleAirData.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) +- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) +- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [GeofenceStatus](../msg_docs/GeofenceStatus.md) +- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) +- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) +- [SensorHygrometer](../msg_docs/SensorHygrometer.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) +- [SensorUwb](../msg_docs/SensorUwb.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) - [Ping](../msg_docs/Ping.md) -- [DebugValue](../msg_docs/DebugValue.md) -- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) +- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) +- [PpsCapture](../msg_docs/PpsCapture.md) +- [RcParameterMap](../msg_docs/RcParameterMap.md) +- [UlogStream](../msg_docs/UlogStream.md) +- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) - [GpioIn](../msg_docs/GpioIn.md) -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [SensorBaro](../msg_docs/SensorBaro.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) +- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) +- [SensorCorrection](../msg_docs/SensorCorrection.md) +- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) +- [VehicleImu](../msg_docs/VehicleImu.md) +- [PositionSetpoint](../msg_docs/PositionSetpoint.md) +- [SensorMag](../msg_docs/SensorMag.md) +- [CameraStatus](../msg_docs/CameraStatus.md) ::: From 7edf21414ebec7b619db969da3dcfa39f6f008bc Mon Sep 17 00:00:00 2001 From: alexcekay Date: Thu, 12 Feb 2026 14:24:11 +0100 Subject: [PATCH 745/812] manifest: reserve ID for Skynode-N --- platforms/common/pab_manifest.c | 47 +++++++++++++++++++++++++++++++++ 1 file changed, 47 insertions(+) diff --git a/platforms/common/pab_manifest.c b/platforms/common/pab_manifest.c index 5e0cee9a30..c6560d6803 100644 --- a/platforms/common/pab_manifest.c +++ b/platforms/common/pab_manifest.c @@ -402,6 +402,52 @@ static const px4_hw_mft_item_t base_configuration_18[] = { }, }; +// BASE ID 19 Auterion Skynode N +static const px4_hw_mft_item_t base_configuration_19[] = { + { + .id = PX4_MFT_PX4IO, + .present = 0, + .mandatory = 0, + .connection = px4_hw_con_unknown, + }, + { + .id = PX4_MFT_USB, + .present = 0, + .mandatory = 0, + .connection = px4_hw_con_unknown, + }, + { + .id = PX4_MFT_CAN2, + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, + { + .id = PX4_MFT_CAN3, + .present = 0, + .mandatory = 0, + .connection = px4_hw_con_unknown, + }, + { + .id = PX4_MFT_PM2, + .present = 0, + .mandatory = 0, + .connection = px4_hw_con_unknown, + }, + { + .id = PX4_MFT_ETHERNET, + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, + { + .id = PX4_MFT_T100_ETH, + .present = 1, + .mandatory = 1, + .connection = px4_hw_con_onboard, + }, +}; + // BASE ID 0x100 Holybro Pixhawk Jetson Baseboard Alaised to ID 0 // BASE ID 0x150 ZeroOne Pixhawk Baseboard Alaised to ID 0 // BASE ID 0x200 AmovLab Pixhawk Baseboard Alaised to ID 0 @@ -419,6 +465,7 @@ static px4_hw_mft_list_entry_t mft_lists[] = { {HW_BASE_ID(16), base_configuration_0, arraySize(base_configuration_0)}, // Auterion Skynode ver 16 {HW_BASE_ID(17), base_configuration_17, arraySize(base_configuration_17)}, // Auterion Skynode ver 17 {HW_BASE_ID(18), base_configuration_18, arraySize(base_configuration_18)}, // Auterion Skynode S ver 18 + {HW_BASE_ID(19), base_configuration_19, arraySize(base_configuration_19)}, // Auterion Skynode N {HW_BASE_ID(0x100), base_configuration_0, arraySize(base_configuration_0)}, // Holybro Pixhawk Jetson Baseboard ver 0x100 Alaised to ID 0 {HW_BASE_ID(0x150), base_configuration_0, arraySize(base_configuration_0)}, // ZeroOne Pixhawk Baseboard ver 0x150 {HW_BASE_ID(0x200), base_configuration_0, arraySize(base_configuration_0)}, // AmovLab Pixhawk Baseboard ver 0x150 From 731d754a1525b152e33c6f9724d8f064956f73a6 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 11 Feb 2026 20:50:47 -0800 Subject: [PATCH 746/812] ci: enable VOXL2 CI builds with private Docker container Remove modalai_voxl2 and qurt from CI exclusion lists and add container overrides to use the private ghcr.io/px4/px4-dev-voxl2 image which contains the Qualcomm Hexagon SDK. - Add voxl2 build group with x64 runner for cross-compilation - Add GHCR credentials to workflow for private container pull - Add packages:read permission to workflow - Auto-build libfc_sensor.so stub during cmake configure - Handle missing .px4/.elf gracefully in artifact packaging Signed-off-by: Ramon Roche --- .github/workflows/build_all_targets.yml | 4 ++++ Tools/ci/generate_board_targets_json.py | 30 +++++++++++++++++++++---- Tools/ci/package_build_artifacts.sh | 4 ++-- boards/modalai/voxl2/cmake/init.cmake | 16 +++++++++++++ 4 files changed, 48 insertions(+), 6 deletions(-) diff --git a/.github/workflows/build_all_targets.yml b/.github/workflows/build_all_targets.yml index 56e6a6ee1a..cf02ac2e77 100644 --- a/.github/workflows/build_all_targets.yml +++ b/.github/workflows/build_all_targets.yml @@ -29,6 +29,7 @@ concurrency: permissions: contents: write actions: read + packages: read jobs: group_targets: @@ -94,6 +95,9 @@ jobs: fail-fast: false container: image: ${{ matrix.container }} + credentials: + username: ${{ github.actor }} + password: ${{ secrets.GITHUB_TOKEN }} steps: - uses: runs-on/action@v2 - uses: actions/checkout@v4 diff --git a/Tools/ci/generate_board_targets_json.py b/Tools/ci/generate_board_targets_json.py index b251d74b51..214edd8186 100755 --- a/Tools/ci/generate_board_targets_json.py +++ b/Tools/ci/generate_board_targets_json.py @@ -36,11 +36,20 @@ if args.filter: target_filter.append(target) default_container = 'ghcr.io/px4/px4-dev:v1.16.0-rc1-258-g0369abd556' +voxl2_container = 'ghcr.io/px4/px4-dev-voxl2:v1.5' build_configs = [] grouped_targets = {} -excluded_boards = ['modalai_voxl2', 'px4_ros2', 'espressif_esp32'] # TODO: fix and enable +excluded_boards = ['px4_ros2', 'espressif_esp32'] # TODO: fix and enable excluded_manufacturers = ['atlflight'] -excluded_platforms = ['qurt'] +excluded_platforms = [] + +# Container overrides for platforms/boards that need a non-default container +platform_container_overrides = { + 'qurt': voxl2_container, +} +board_container_overrides = { + 'modalai_voxl2': voxl2_container, +} excluded_labels = [ 'stackcheck', 'nolockstep', 'replay', 'test', @@ -88,7 +97,20 @@ def process_target(px4board_file, target_name): if platform not in excluded_platforms: container = default_container - if platform == 'posix': + + # Extract board name (manufacturer_board) from target name + board_name = '_'.join(target_name.split('_')[:2]) + + # Apply container overrides for specific platforms or boards + if platform in platform_container_overrides: + container = platform_container_overrides[platform] + if board_name in board_container_overrides: + container = board_container_overrides[board_name] + + # Boards with container overrides get their own group + if board_name in board_container_overrides or platform in platform_container_overrides: + group = 'voxl2' + elif platform == 'posix': group = 'base' if toolchain: if toolchain.startswith('aarch64'): @@ -203,7 +225,7 @@ if (args.group): if(verbose): print(f'=:Architectures: [{grouped_targets.keys()}]') for arch in grouped_targets: - runner = 'x64' if arch == 'nuttx' else 'arm64' + runner = 'x64' if arch in ('nuttx', 'voxl2') else 'arm64' if(verbose): print(f'=:Processing: [{arch}]') temp_group = [] diff --git a/Tools/ci/package_build_artifacts.sh b/Tools/ci/package_build_artifacts.sh index f5ebb73fa0..aaf978b19f 100755 --- a/Tools/ci/package_build_artifacts.sh +++ b/Tools/ci/package_build_artifacts.sh @@ -1,8 +1,8 @@ #!/bin/bash mkdir artifacts -cp **/**/*.px4 artifacts/ -cp **/**/*.elf artifacts/ +cp **/**/*.px4 artifacts/ 2>/dev/null || true +cp **/**/*.elf artifacts/ 2>/dev/null || true for build_dir_path in build/*/ ; do build_dir_path=${build_dir_path::${#build_dir_path}-1} build_dir=${build_dir_path#*/} diff --git a/boards/modalai/voxl2/cmake/init.cmake b/boards/modalai/voxl2/cmake/init.cmake index 357d1d45ec..04f4b65a88 100644 --- a/boards/modalai/voxl2/cmake/init.cmake +++ b/boards/modalai/voxl2/cmake/init.cmake @@ -32,3 +32,19 @@ ############################################################################ include_directories(${PX4_BOARD_DIR}/libfc-sensor-api/inc) + +# Build libfc_sensor.so stub library automatically if not already built +set(FC_SENSOR_LIB ${PX4_BOARD_DIR}/libfc-sensor-api/build/libfc_sensor.so) +if(NOT EXISTS ${FC_SENSOR_LIB}) + execute_process( + COMMAND ${CMAKE_COMMAND} -E make_directory ${PX4_BOARD_DIR}/libfc-sensor-api/build + ) + execute_process( + COMMAND ${CMAKE_COMMAND} -DCMAKE_C_COMPILER=${CMAKE_C_COMPILER} .. + WORKING_DIRECTORY ${PX4_BOARD_DIR}/libfc-sensor-api/build + ) + execute_process( + COMMAND ${CMAKE_COMMAND} --build . + WORKING_DIRECTORY ${PX4_BOARD_DIR}/libfc-sensor-api/build + ) +endif() From d641cc3986938843ce781ab89f5de6efd7ecd5e7 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 11 Feb 2026 21:18:43 -0800 Subject: [PATCH 747/812] ci: init libfc-sensor-api submodule before building stub The libfc-sensor-api submodule was not being initialized in CI, causing the stub library build to fail silently. Use the existing check_submodules.sh mechanism to ensure the submodule is fetched before attempting to build, and add RESULT_VARIABLE checks so cmake configuration and build failures are caught early. Signed-off-by: Ramon Roche --- boards/modalai/voxl2/cmake/init.cmake | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/boards/modalai/voxl2/cmake/init.cmake b/boards/modalai/voxl2/cmake/init.cmake index 04f4b65a88..4a60cb5d91 100644 --- a/boards/modalai/voxl2/cmake/init.cmake +++ b/boards/modalai/voxl2/cmake/init.cmake @@ -31,6 +31,12 @@ # ############################################################################ +# Initialize libfc-sensor-api submodule (fetches from GitLab if not present) +execute_process( + COMMAND Tools/check_submodules.sh boards/modalai/voxl2/libfc-sensor-api + WORKING_DIRECTORY ${PX4_SOURCE_DIR} +) + include_directories(${PX4_BOARD_DIR}/libfc-sensor-api/inc) # Build libfc_sensor.so stub library automatically if not already built @@ -42,9 +48,17 @@ if(NOT EXISTS ${FC_SENSOR_LIB}) execute_process( COMMAND ${CMAKE_COMMAND} -DCMAKE_C_COMPILER=${CMAKE_C_COMPILER} .. WORKING_DIRECTORY ${PX4_BOARD_DIR}/libfc-sensor-api/build + RESULT_VARIABLE FC_SENSOR_CMAKE_RESULT ) + if(NOT FC_SENSOR_CMAKE_RESULT EQUAL 0) + message(FATAL_ERROR "Failed to configure libfc_sensor stub library") + endif() execute_process( COMMAND ${CMAKE_COMMAND} --build . WORKING_DIRECTORY ${PX4_BOARD_DIR}/libfc-sensor-api/build + RESULT_VARIABLE FC_SENSOR_BUILD_RESULT ) + if(NOT FC_SENSOR_BUILD_RESULT EQUAL 0) + message(FATAL_ERROR "Failed to build libfc_sensor stub library") + endif() endif() From a38b10c9d03d3c15823aeb3b351b40823c5790a3 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Thu, 12 Feb 2026 13:55:29 -0800 Subject: [PATCH 748/812] docs: modernize README (#26458) * docs: modernize README with hero logo, vehicle icons, and fixed links Add PX4 and Dronecode SVG logos to the repo, replace broken external Dronecode logo URL, fix SITL badge branch from master to main, and restructure the README with centered branding, airframe icon row, quick-start section, and consolidated documentation links. --- README.md | 121 ++++++++++++++------- docs/.vitepress/config.mjs | 66 ++++++++++- docs/assets/site/dronecode_logo.svg | 86 +++++++++++++++ docs/assets/site/px4_logo.svg | 163 ++++++++++++++++++++++++++++ docs/en/index.md | 90 ++++----------- docs/index.md | 33 +++--- docs/public/og-image.png | Bin 0 -> 146077 bytes 7 files changed, 435 insertions(+), 124 deletions(-) create mode 100644 docs/assets/site/dronecode_logo.svg create mode 100644 docs/assets/site/px4_logo.svg create mode 100644 docs/public/og-image.png diff --git a/README.md b/README.md index 8353f3add6..bf4d74bb76 100644 --- a/README.md +++ b/README.md @@ -1,62 +1,109 @@ -# PX4 Drone Autopilot +

+ + PX4 Autopilot + +

-[![Releases](https://img.shields.io/github/release/PX4/PX4-Autopilot.svg)](https://github.com/PX4/PX4-Autopilot/releases) [![DOI](https://zenodo.org/badge/22634/PX4/PX4-Autopilot.svg)](https://zenodo.org/badge/latestdoi/22634/PX4/PX4-Autopilot) +

+ The autopilot stack the industry builds on. +

-[![Build Targets](https://github.com/PX4/PX4-Autopilot/actions/workflows/build_all_targets.yml/badge.svg?branch=main)](https://github.com/PX4/PX4-Autopilot/actions/workflows/build_all_targets.yml) [![SITL Tests](https://github.com/PX4/PX4-Autopilot/workflows/SITL%20Tests/badge.svg?branch=master)](https://github.com/PX4/PX4-Autopilot/actions?query=workflow%3A%22SITL+Tests%22) +

+ Releases + DOI + Build Targets + Discord +

-[![Discord Shield](https://discordapp.com/api/guilds/1022170275984457759/widget.png?style=shield)](https://discord.gg/dronecode) +--- -This repository holds the [PX4](http://px4.io) flight control solution for drones, with the main applications located in the [src/modules](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules) directory. It also contains the PX4 Drone Middleware Platform, which provides drivers and middleware to run drones. +## About -PX4 is highly portable, OS-independent and supports Linux, NuttX and MacOS out of the box. +PX4 is an open-source autopilot stack for drones and unmanned vehicles. It supports multirotors, fixed-wing, VTOL, rovers, and many more experimental platforms from racing quads to industrial survey aircraft. It runs on [NuttX](https://nuttx.apache.org/), Linux, and macOS. Licensed under [BSD 3-Clause](LICENSE). -* Official Website: http://px4.io (License: BSD 3-clause, [LICENSE](https://github.com/PX4/PX4-Autopilot/blob/main/LICENSE)) -* [Supported airframes](https://docs.px4.io/main/en/airframes/airframe_reference.html) ([portfolio](https://px4.io/ecosystem/commercial-systems/)): - * [Multicopters](https://docs.px4.io/main/en/frames_multicopter/) - * [Fixed wing](https://docs.px4.io/main/en/frames_plane/) - * [VTOL](https://docs.px4.io/main/en/frames_vtol/) - * [Autogyro](https://docs.px4.io/main/en/frames_autogyro/) - * [Rover](https://docs.px4.io/main/en/frames_rover/) - * many more experimental types (Blimps, Boats, Submarines, High Altitude Balloons, Spacecraft, etc) -* Releases: [Downloads](https://github.com/PX4/PX4-Autopilot/releases) +## Why PX4 -## Releases +**Modular architecture.** PX4 is built around [uORB](https://docs.px4.io/main/en/middleware/uorb.html), a [DDS](https://docs.px4.io/main/en/middleware/uxrce_dds.html)-compatible publish/subscribe middleware. Modules are fully parallelized and thread safe. You can build custom configurations and trim what you don't need. -Release notes and supporting information for PX4 releases can be found on the [Developer Guide](https://docs.px4.io/main/en/releases/). +**Wide hardware support.** PX4 runs on a wide range of [autopilot boards](https://docs.px4.io/main/en/flight_controller/) and supports an extensive set of sensors, telemetry radios, and actuators through the [Pixhawk](https://pixhawk.org/) ecosystem. -## Building a PX4 based drone, rover, boat or robot +**Developer friendly.** First-class support for [MAVLink](https://mavlink.io/) and [DDS / ROS 2](https://docs.px4.io/main/en/ros2/) integration. Comprehensive [SITL simulation](https://docs.px4.io/main/en/simulation/), hardware-in-the-loop testing, and [log analysis](https://docs.px4.io/main/en/log/flight_log_analysis.html) tools. An active developer community on [Discord](https://discord.gg/dronecode) and the [weekly dev call](https://docs.px4.io/main/en/contribute/). -The [PX4 User Guide](https://docs.px4.io/main/en/) explains how to assemble [supported vehicles](https://docs.px4.io/main/en/airframes/airframe_reference.html) and fly drones with PX4. See the [forum and chat](https://docs.px4.io/main/en/#getting-help) if you need help! +**Vendor neutral governance.** PX4 is hosted under the [Dronecode Foundation](https://www.dronecode.org/), part of the Linux Foundation. Business-friendly BSD-3 license. No single vendor controls the roadmap. +## Supported Vehicles -## Changing Code and Contributing + + + + + + + +
+ + Multicopter
+ Multicopter +
+
+ + Fixed Wing
+ Fixed Wing +
+
+ + VTOL
+ VTOL +
+
+ + Rover
+ Rover +
+
-This [Developer Guide](https://docs.px4.io/main/en/development/development.html) is for software developers who want to modify the flight stack and middleware (e.g. to add new flight modes), hardware integrators who want to support new flight controller boards and peripherals, and anyone who wants to get PX4 working on a new (unsupported) airframe/vehicle. +…and many more: helicopters, autogyros, airships, submarines, boats, and other experimental platforms. These frames have basic support but are not part of the regular flight-test program. See the full airframe reference. -Developers should read the [Guide for Contributions](https://docs.px4.io/main/en/contribute/). -See the [forum and chat](https://docs.px4.io/main/en/#getting-help) if you need help! +## Quick Start +```bash +git clone https://github.com/PX4/PX4-Autopilot.git --recursive +cd PX4-Autopilot +make px4_sitl +``` -## Weekly Dev Call +> [!NOTE] +> See the [Development Guide](https://docs.px4.io/main/en/development/development.html) for toolchain setup and build options. -The PX4 Dev Team syncs up on a [weekly dev call](https://docs.px4.io/main/en/contribute/). +## Documentation & Resources -> **Note** The dev call is open to all interested developers (not just the core dev team). This is a great opportunity to meet the team and contribute to the ongoing development of the platform. It includes a QA session for newcomers. All regular calls are listed in the [Dronecode calendar](https://www.dronecode.org/calendar/). +| Resource | Description | +| --- | --- | +| [User Guide](https://docs.px4.io/main/en/) | Build, configure, and fly with PX4 | +| [Developer Guide](https://docs.px4.io/main/en/development/development.html) | Modify the flight stack, add peripherals, port to new hardware | +| [Airframe Reference](https://docs.px4.io/main/en/airframes/airframe_reference.html) | Full list of supported frames | +| [Autopilot Hardware](https://docs.px4.io/main/en/flight_controller/) | Compatible flight controllers | +| [Release Notes](https://docs.px4.io/main/en/releases/) | What's new in each release | +| [Contribution Guide](https://docs.px4.io/main/en/contribute/) | How to contribute to PX4 | +## Community -## Maintenance Team +- **Weekly Dev Call** — open to all developers ([Dronecode calendar](https://www.dronecode.org/calendar/)) +- **Discord** — [Join the Dronecode server](https://discord.gg/dronecode) +- **Discussion Forum** — [PX4 Discuss](https://discuss.px4.io/) +- **Maintainers** — see [`MAINTAINERS.md`](MAINTAINERS.md) +- **Contributor Stats** — [LFX Insights](https://insights.lfx.linuxfoundation.org/foundation/dronecode) -See the latest list of maintainers on [MAINTAINERS](MAINTAINERS.md) file at the root of the project. +## Contributing -For the latest stats on contributors please see the latest stats for the Dronecode ecosystem in our project dashboard under [LFX Insights](https://insights.lfx.linuxfoundation.org/foundation/dronecode). For information on how to update your profile and affiliations please see the following support link on how to [Complete Your LFX Profile](https://docs.linuxfoundation.org/lfx/my-profile/complete-your-lfx-profile). Dronecode publishes a yearly snapshot of contributions and achievements on its [website under the Reports section](https://dronecode.org). +We welcome contributions of all kinds — bug reports, documentation, new features, and code reviews. Please read the [Contribution Guide](https://docs.px4.io/main/en/contribute/) to get started. -## Supported Hardware +## Governance -For the most up to date information, please visit [PX4 User Guide > Autopilot Hardware](https://docs.px4.io/main/en/flight_controller/). +The PX4 Autopilot project is hosted by the [Dronecode Foundation](https://www.dronecode.org/), a [Linux Foundation](https://www.linuxfoundation.org/) Collaborative Project. Dronecode holds all PX4 trademarks and serves as the project's legal guardian, ensuring vendor-neutral stewardship — no single company owns the name or controls the roadmap. The source code is licensed under the [BSD 3-Clause](LICENSE) license, so you are free to use, modify, and distribute it in your own projects. -## Project Governance - -The PX4 Autopilot project including all of its trademarks is hosted under [Dronecode](https://www.dronecode.org/), part of the Linux Foundation. - -Dronecode Logo -
 
+

+ + Dronecode Logo + +

diff --git a/docs/.vitepress/config.mjs b/docs/.vitepress/config.mjs index e9190be018..c12b4e27ef 100644 --- a/docs/.vitepress/config.mjs +++ b/docs/.vitepress/config.mjs @@ -254,7 +254,63 @@ export default defineConfig({ head.push(["link", { rel: "canonical", href: canonicalUrlToAdd }]); } - // Add any other custom head tags you might want later + // Build version-aware site URL for OG tags + const branch = process.env.BRANCH_NAME || "main"; + const siteUrl = `https://docs.px4.io/${branch}`; + + // OG image — same image for all pages, but URL includes version base + const ogImage = + pageData.frontmatter.ogImage || `${siteUrl}/og-image.png`; + + // Build the actual page URL (version-aware, includes locale prefix) + let ogPath = pageData.relativePath.replace(/\.md$/, ""); + if (ogPath === "index") ogPath = ""; + else if (ogPath.endsWith("/index")) + ogPath = ogPath.slice(0, -"/index".length); + const ogUrl = `${siteUrl}/${ogPath}`; + + // Open Graph + head.push( + [ + "meta", + { + property: "og:title", + content: pageData.title || "PX4 Autopilot", + }, + ], + [ + "meta", + { + property: "og:description", + content: + pageData.description || + "Open-source flight stack for drones and autonomous vehicles.", + }, + ], + ["meta", { property: "og:url", content: ogUrl }], + ["meta", { property: "og:image", content: ogImage }], + ); + + // Twitter Card + head.push( + [ + "meta", + { + name: "twitter:title", + content: pageData.title || "PX4 Autopilot", + }, + ], + [ + "meta", + { + name: "twitter:description", + content: + pageData.description || + "Open-source flight stack for drones and autonomous vehicles.", + }, + ], + ["meta", { name: "twitter:image", content: ogImage }], + ); // Return head that will be merged. return head; @@ -276,6 +332,14 @@ export default defineConfig({ gtag('js', new Date()); gtag('config', 'G-91EWVWRQ93');`, ], + // Open Graph + ["meta", { property: "og:site_name", content: "PX4 Autopilot" }], + ["meta", { property: "og:type", content: "website" }], + ["meta", { property: "og:image:width", content: "1200" }], + ["meta", { property: "og:image:height", content: "630" }], + ["meta", { property: "og:image:type", content: "image/png" }], + // Twitter Card + ["meta", { name: "twitter:card", content: "summary_large_image" }], ], vue: { diff --git a/docs/assets/site/dronecode_logo.svg b/docs/assets/site/dronecode_logo.svg new file mode 100644 index 0000000000..c9315f6b57 --- /dev/null +++ b/docs/assets/site/dronecode_logo.svg @@ -0,0 +1,86 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/docs/assets/site/px4_logo.svg b/docs/assets/site/px4_logo.svg new file mode 100644 index 0000000000..ade96659ab --- /dev/null +++ b/docs/assets/site/px4_logo.svg @@ -0,0 +1,163 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/docs/en/index.md b/docs/en/index.md index 53bcd97f66..f361486948 100644 --- a/docs/en/index.md +++ b/docs/en/index.md @@ -3,19 +3,11 @@ import { useData } from 'vitepress' const { site } = useData(); -
- # PX4 Autopilot User Guide [![Releases](https://img.shields.io/badge/release-main-blue.svg)](https://github.com/PX4/PX4-Autopilot/releases) [![Discuss](https://img.shields.io/badge/discuss-px4-ff69b4.svg)](https://discuss.px4.io//) [![Discord](https://discordapp.com/api/guilds/1022170275984457759/widget.png?style=shield)](https://discord.gg/dronecode) -PX4 is the _Professional Autopilot_. -Developed by world-class developers from industry and academia, and supported by an active world wide community, it powers all kinds of vehicles from racing and cargo drones through to ground vehicles and submersibles. - -:::tip -This guide contains everything you need to assemble, configure, and safely fly a PX4-based vehicle. -Interested in contributing? Check out the [Development](development/development.md) section. -::: +PX4 is an open-source autopilot for drones and autonomous vehicles. It runs on multirotors, fixed-wing, VTOL, helicopters, rovers, and more. This guide covers everything from assembly and configuration to flight operations and development.
@@ -29,83 +21,43 @@ Documented changes since the stable release are captured in the evolving [releas
-## How Do I Get Started? +## For Developers -[Basic Concepts](getting_started/px4_basic_concepts.md) should be read by all users! -It provides an overview of PX4, including features provided by the flight stack (flight modes and safety features) and the supported hardware (flight controller, vehicle types, telemetry systems, RC control systems). +:::tip +Building on PX4 or extending the platform? Start here: [Development Guide](development/development.md). Set up your [dev environment](dev_setup/config_initial.md), [build from source](dev_setup/building_px4.md), run [SITL simulation](simulation/index.md), or integrate via [ROS 2](ros2/index.md) and [MAVSDK](https://mavsdk.mavlink.io/). +::: -Depending on what you want to achieve, the following tips will help you navigate through this guide: +## Getting Started -### I want a vehicle that works with PX4 +Start with [Basic Concepts](getting_started/px4_basic_concepts.md) for an overview of the flight stack, flight modes, safety features, and supported hardware. -In the [Multicopter](frames_multicopter/index.md), [VTOL](frames_vtol/index.md), and [Plane (Fixed-Wing)](frames_plane/index.md) sections you'll find topics like the following (these links are for multicopter): +## Build a Vehicle -- [Complete Vehicles](complete_vehicles_mc/index.md) list "Ready to Fly" (RTF) pre-built vehicles -- [Kits](frames_multicopter/kits.md) lists drones that you have to build yourself from a set of preselected parts -- [DIY Builds](frames_multicopter/diy_builds.md) shows some examples of drones that have been built using parts that were sourced individually +Pick your frame type: [Multicopter](frames_multicopter/index.md), [Fixed-Wing](frames_plane/index.md), [VTOL](frames_vtol/index.md), [Helicopter](frames_helicopter/index.md), or [Rover](frames_rover/index.md). Each section covers complete vehicles, kits, and DIY builds. For assembly instructions see [Assembling a Multicopter](assembly/assembly_mc.md) or the equivalent for your frame. -Both kits and complete vehicles usually include everything you need except for a battery and RC System. -Kits are usually not hard to build, provide a good introduction to how drones fit together, and are relatively inexpensive. -We provide generic instructions for assembly, such as [Assembling a Multicopter](assembly/assembly_mc.md), and most kits come with specific instructions too. +## Configure and Tune -If the kits and complete drones aren't quite right for you then you can build a vehicle from scratch, but this requires more knowledge. -[Airframe Builds](airframes/index.md) lists the supported frame starting points to give you some idea of what is possible. +Once assembled, follow the configuration guide for your vehicle type (e.g. [Multicopter Configuration](config_mc/index.md)). This covers sensor calibration, flight mode setup, and tuning. -Once you have a vehicle that supports PX4 you will need to configure it and calibrate the sensors. -Each vehicle type has its own configuration section that explains the main steps, such as [Multicopter Configuration/Tuning](config_mc/index.md). +## Hardware -### I want to add a payload/camera +The [Hardware Selection & Setup](hardware/drone_parts.md) section covers flight controllers, sensors, telemetry, RC systems, and payloads. See [Payloads](payloads/index.md) for camera and delivery integrations. -The [Payloads](payloads/index.md) section describes how to add a camera and how to configure PX4 to enable you to deliver packages. +## Fly -### I am modifying a supported vehicle +Read [Operations](config/operations.md) to understand safety features and failsafe behavior before your first flight. Then see [Basic Flying (Multicopter)](flying/basic_flying_mc.md) or the equivalent for your frame type. -The [Hardware Selection & Setup](hardware/drone_parts.md) section provides both high level and product-specific information about hardware that you might use with PX4 and its configuration. -This is the first place you should look if you want to modify a drone and add new components. +## Support -### I want to fly - -Before you fly you should read [Operations](config/operations.md) to understand how to set up the safety features of your vehicle and the common behaviours of all frame types. -Once you've done that you're ready to fly. - -Basic instructions for flying each vehicle type are provided in the respective sections, such as [Basic Flying (Multicopter)](flying/basic_flying_mc.md). - -### I want to run PX4 on a new Flight Controller and extend the platform - -The [Development](development/development.md) section explains how to support new airframes and types of vehicles, modify flight algorithms, add new modes, integrate new hardware, communicate with PX4 from outside the flight controller, and contribute to PX4. - -## Getting Help - -The [Support](contribute/support.md) page explains how to get help from the core dev team and the wider community. - -Among other things it covers: - -- [Forums where you can get help](contribute/support.md#forums-and-chat) -- [Diagnosing issues](contribute/support.md#diagnosing-problems) -- [How to report bugs](contribute/support.md#issue-bug-reporting) -- [Weekly dev call](contribute/support.md#weekly-dev-call) - -## Reporting Bugs & Issues - -If you have any problems using PX4 first post them on the [support forums](contribute/support.md#forums-and-chat) (as they may be caused by vehicle configuration). - -If directed by the development team, code issues may be raised on [Github here](https://github.com/PX4/PX4-Autopilot/issues). -Where possible provide [flight logs](getting_started/flight_reporting.md) and other information requested in the issue template. +Get help on the [discussion forums](https://discuss.px4.io/) or [Discord](https://discord.gg/dronecode). See the [Support](contribute/support.md) page for diagnosing problems, reporting bugs, and joining the [weekly dev call](contribute/dev_call.md). ## Contributing -Information on how to contribute to code and documentation can be found in the [Contributing](contribute/index.md) section: - -- [Code](contribute/index.md) -- [Documentation](contribute/docs.md) -- [Translation](contribute/translation.md) +See the [Contributing](contribute/index.md) section for code, [documentation](contribute/docs.md), and [translation](contribute/translation.md) guidelines. ## Translations -There are several [translations](contribute/translation.md) of this guide. -You can access these from the Languages menu (top right): - -![Language Selector](../assets/vuepress/language_selector.png) +There are several [translations](contribute/translation.md) of this guide. Use the language selector in the top navigation. @@ -141,9 +93,9 @@ The following icons used in this library are licensed separately (as shown below ## Governance -The PX4 flight stack is hosted under the governance of the [Dronecode Project](https://dronecode.org/). +The PX4 Autopilot project is hosted by the [Dronecode Foundation](https://www.dronecode.org/), a [Linux Foundation](https://www.linuxfoundation.org/) Collaborative Project. Dronecode holds all PX4 trademarks and serves as the project's legal guardian, ensuring vendor-neutral stewardship. No single company owns the name or controls the roadmap. The source code is licensed under the [BSD 3-Clause](https://opensource.org/license/BSD-3-Clause) license, so you are free to use, modify, and distribute it in your own projects. -Dronecode Logo +Dronecode Logo Linux Foundation Logo
 
diff --git a/docs/index.md b/docs/index.md index 20f2371f3e..6ac4d4ab85 100644 --- a/docs/index.md +++ b/docs/index.md @@ -4,9 +4,9 @@ layout: home hero: name: "PX4" - text: "User Guide" - tagline: PX4 is the Open Source Autopilot for Professional Drone Developers. - image: /logo_pro_small.png + text: "Autopilot" + tagline: Open-source flight stack for drones and autonomous vehicles. BSD-3 licensed. Vendor neutral. + image: /px4-logo.svg actions: - theme: brand text: Read the docs @@ -20,22 +20,21 @@ hero: features: - title: Modular Architecture - details: PX4 is highly modular and extensible both in terms of hardware and software. It utilizes a port-based architecture - which means when developers add components, the extended system does not lose robustness or performance. - - title: Open Source - details: PX4 is co-developed with a global development community. The flightstack is not just fulfilling the needs of one lab or one company, but has been intended as a general toolkit and is widely used and adopted in the industry. - - title: Configurability - details: PX4 offers optimised APIs and SDKs for developers working with integrations. All the modules are self-contained and can be easily exchanged against a different module without modifying the core. Features are easy to deploy and reconfigure. - - title: Autonomy Stack - details: PX4 is designed to be deeply coupled with embedded computer vision for autonomous capabilities . The framework lowers the barrier of entry for developers working on localization and obstacle detection algorithms. - - title: Real-world Validation - details: Thousands of commercial PX4 based systems have been deployed worldwide. In parallel, dedicated flight test team clocking up thousands of flight hours each month running hardware and software tests to ensure the codebase's safety and reliability. + details: Built on uORB, a DDS-compatible publish/subscribe middleware. Every module runs as its own thread, fully parallelized and thread safe. Build custom configurations and strip out what you don't need. + - title: Wide Hardware Support + details: Supports Pixhawk-standard flight controllers and a growing range of boards beyond that standard. DroneCAN peripherals run PX4 firmware in CAN node mode. No vendor lock-in. + - title: Developer Friendly + details: First-class MAVLink and DDS/ROS 2 integration. Comprehensive SITL simulation, hardware-in-the-loop testing, and log analysis tools. MAVSDK provides a high-level SDK/API for programmatic vehicle interaction. + - title: Autonomy Ready + details: Extensible architecture for advanced autonomy. External modes, offboard control, and DDS/ROS 2 interfaces provide the building blocks for computer vision, GPS-denied navigation, and custom flight behaviors. + - title: Proven at Scale + details: Millions of vehicles deployed worldwide across commercial, defense, and research applications. Continuous flight testing validates the codebase across multirotors, fixed-wing, VTOL, helicopters, rovers, and more. - title: Permissive License - details: PX4 is free to use and modify under the terms of the permissive BSD 3-clause license. Which means the software also allows proprietary use and allows the releases under the license to be incorporated into proprietary products. + details: BSD 3-Clause. Use it, modify it, ship it in proprietary products. You only need to include the original copyright notice and license text. - title: Interoperability - details: Beyond being a robust flight stack, PX4 offers an ecosystem of supported devices. The project also leads the standardarization effort for the advancement of communications, peripherals integration, and power management solutions. - - - title: Powerful Safety Features - details: Great safety features including automated failsafe behaviour, support for different return modes, parachutes etc. are by default already included in the codebase. The features are easily configurable and tunable for custom systems. + details: Part of a modular ecosystem. PX4 (autopilot), MAVLink (protocol), QGroundControl (ground station), Pixhawk (hardware standard), MAVSDK (SDK/API), and ROS 2 via DDS or Zenoh. All Dronecode projects, all open source. + - title: Vendor Neutral Governance + details: Hosted by the Dronecode Foundation under the Linux Foundation. No single company owns the name or controls the roadmap. Community-driven with a weekly open dev call. search: false footer: BSD 3-clause license diff --git a/docs/public/og-image.png b/docs/public/og-image.png new file mode 100644 index 0000000000000000000000000000000000000000..5625b82550b2dda50172af7f39f4dc76d335df92 GIT binary patch literal 146077 zcmV(qK<~eaP)x>&-c~qJjZqFR27S4k&A0>KEQt8z1I)PMHY)y4~twc zeCbPHdU9I`pZUyZZol_?zjwO|UU=b!hyPEWJbC7~1f93eZER$NWQ}C*|Nh_q`|!~~ zeQ~BtQhxvE|NNh)eMO!tp|z|tpHb=q96PfA%lf9@{1X9{{n4XGp?1my>P~(q&^SWn z`OR;B^Y9zz{`PPG_8FO{`~J?~`8$WyKhF~~AnRN^7D-o=saiQ3DVJW_{9LIF)_Go^ z*8L<4kPiT|Y}p~Q?^?&THsj@~ZPOC8ek{M!e|qMgywP8%Z&`istdO!2eWucNR@-Rx z=B1^z>BhzgkZjTi<0$D3*k|;cbR>N&-Aczl{`ljE@1!rT#rln1uxGQc;oE| zeDcXB53&bP-XwpIA3wg0!q%-eU^7MPi1fo}Kl|Ab{{hH8AZ<9_Pv&|X0jxygK!KkH zyVKn-xSU307D|8=3>g<1;OML%SCMi^;-$v zFQs(OWIG)NZ7k4qgm&%5#z=tdCS6GXF{To6@ZyUvh9-T8w4&?poxCETuCn|}p56+u zY@8mD+;Q@XKynFr8u{#J^Z&C@dTz~LwqONEWZ}_mF&r&0-1zJ<#-$-*86~9|;u>s& z@qW=VGs|U=j1kRg!{9MH8p}e-;J5mjb>7QEM)zbwn`MysYv)Gc1t(%eE0YE|{@$$Y zNJv@W#*cL30c$Xh&X$(0jigsPZ=LgIzWKdgbdvntG8XZBO7}+7_xiMVZREHt56P=E zls#Ft>a!Lj2?;Chj67?iVJ*F~0!p%&S?*FjSkZD^$E;e98`lQO9XX^{xsEZG;@JvC^xGi%51*78vr|NDRcZ}m6`tRu$It0VHWXu(^4)_WG}oBUn-bMVr^`+K$2J*kyX<_TV%S$iI?XzLdzo?W;rmW zv^|nymTu4pJLHXsi&C9nc^(Z|N0L}r@}QlUh(wdrMAXz6q0w||VYOo^&wB+qXJjn% zIwv`fMj={lzlsr@9esuGQN5fY)7jA4w51>P64>7OmCwB=GF4mw$Um*%``^v`wexPMzOTZuClcX{|LhV@hF!^{}2rEW-)S{Ke-W_sd z1t1!Ml#WKSln7c0PgzMI-QGSZ9RmE~c#8&jQW4Cq!pz<-PY}>}`xe4Z%kwqV+$T%JQFZ0X7}t3j`qk<$5!pWzW|v*l?b~_Um<>eYw-Q%8ok(=X zRS~t-G&?JT9&%--Ug^n8+rJdifTOYf@iJoEMFyMH@sFkcA@#S8aw&UISPJv_xw=ln4)5??(_?yeu9Ni8Vv7bJB_rtdfk7 z_pD&3l=^rJIbC|LsDWL=C^;NO4wueDc6dGWrG%~d^f(;7ki>l}y#AuilAe`-sV#R; z6eXAQdv^FYjsyBN={_va>eah76EXJ&EwV&AhTmCZHOD9&Ez8LPX z`StpUW$^VzK4#*%ko5mwRxx7;K#sA2u~#P+fg@#2>W5a{XN?ci2+Yu}5$D00#OQs_ zm67pW+acOG0w4wGRri@X7ybQSNvxW2*Bi&>@kqXr$*@txRfY^v8rtUVgd>7nEIa1j zfyv?sfrb6d;7?lifb=&!`-X6rO9*>}@Lm=2#yXfSe+Vnb>y&F?kwc~5N5WE?E$NJO z#4S=FGhZvR0(!7C10$XPOnA<+CSUSc=4_rM_-bYwYmV2HCj%wI#=0kRY*koG3F%Xk znc8R1wkNDfjSP9>#wU(>`JN4#B;tsBHa4;V;)=%QY*K*I{`AvNpL=uRmigzQ>C%-Z zcaH#UMv0?d3`7`h%byj}Ch&kr_LjP|h}UJ-?2T}4Mx^I4&80lI0^i8O5z3T|k$ZXr z2pm88(az&{DUDWm22QjrJ<#%p9xQF>Xc;8gfKeWK`yk4l1#etvy(bdMQ#zi3do$eV zd9`qN5cpAp&1w^=LvU>`Mv+$pzJyYHE~yjvu~9lH8>9Nrw)-|#0VX3~eDTHGMK9))oy|<9VNu&1Yobtxx^k=XHsHN01{l`@c-I1C2Xa> zVL@{wj#8d5hP061dx9jcv?Vm!cX@wHm^g>bLrd4vU$v0w%XF@2w1_nN zXtQ_Pl0t95m1I{WN-8oC%l6P_l&pK?F-s3bW;iWqQGNFeM4QSDWl6>&gl(z+X)?Sb zA?Y~}o_wBFeroEhrG72_)tcVMh6Ef-L|e^{G^S1ANpEUnFCC+ZEILouVQJWw{olc| z4I(xc&eiB_?fk5XJZ?X7UxHt=%4B)8{_hPno4I2zEJE+Nx71q*H#RnWtfn+!9AV(u zO1&7#^pTrjbAZHZS;pYW7o`WXfg6C<^1GSUtpvre88p>Zez-+gj_bg?O|kG&Yg7(F({8=`2LZXOH>OG9cQE z#$(GiL_`)glfQQ&t7U0b#qOLQ}L*yGSmy;x!i z;gyA98zLK52g20vZC|VsV6n12zYI?`|?IDsIO8) z6MYb|GFy&#G%_Nwuzb-f3+YiTEhM|(-gM4td5;>CO2Eed600m9JgQz+2KP0hbpt{> zgE)PZkw`COl)%c+A{n&C*n+-sZy=+Ij1MwGHgWqbyk&pUF!88Pkx@}K_qIUOee|1T z!HUEJiG?K&rEqwp%YSoF8j;Q0S0bayBuRA)tQm40t*Xuwjz6(UtMV2>Ou$F}T4M7r{&g*=k_s^FyG>^uo8On_0| z+V&4M`zwva3(Atmjo*Ste%34_%!s)B3=H}enBZALk@2k2*|SY#ZQK)fG*%frIzlsC zEMvyHUY_T(A+u(UWIi>KSRT0-1;{d_i~l{#2WO#W+_RP)%{GMZ1)5HSA=XMVxAx5l z*_$B;tC77k(L+M^q{pw_{dmIyNOg*Cdg-N?mWWa*IrfOidhx{<&GKS-HX^d3Z!J4J zR`9=%1Z+VGOp5o6mm@GTdit!WA<(m4g!9xoS%Ju!g&Lzn6HoYoTnXMX!xCA=|7&R;p?5Ty^u`s;xbo{Q-724nlVsY91gr>`RnSsCNmgm+ zv@xir3>!MEw-S~JW$n0kz86_(_UP}GX7^h#b23#Uqql>!p#c+wSejSbhi^sDcui$5 z5m`iN5Q#-(79zT@1Z({F`h1p7;CYW8kF>mHUh+jLfVC8MwqBI=#mm2S^zSC*qJ0$0 zMSJV+x!h(CoU07dt!0o7n|6LNt(y|wy@gj_7D2i1a3U8*A&{G$y5DXjVL5r*%sYtzLU|4>$ z4e~gw$SjY{T204Da^I5yxhZyZ5G3$Dw7l8GtIgnA2EQafG0ZT zU3r|BZ}|oIWRYgO90iYfoQbTlJ`*)|L&jdok9fu!3k-~^q}7#<)@h(T<@ZQh+Ys4^ zAkyEY3?8M(BKcy2KWkI(4I9z=;xb?vf&AK8K)EouSu#Ka8m`gCBJCL8yxogH$#Te# zMk(6P`;9u><4`*g@h1&#lEK*#ej{gLM?8n-bl&4wVCgc?{@%DRpr4SgIm4c!EfXU0 zT12>#E~Tg|%}xN3Mb}Uy8h^XtnRSU}zaK@~%(4+E4{h=XvVZm{!%^Tib;%~2ZR=Yv zRFc31eUEN?Br`|Ck>kBM>j2%dBx4&R8`)Szk$RA%iAP{;lwmDZ;^*X`)}pU^;5lfe z0gjAQ9}4nw}h4CM$Yb z%KnOD$4c_%P2SFsDP9-ScK3jZzg9f53PZ4*pv*>FAsn#uJltujIk$0Mcyduo=$6uo z${+u39qWabK8GX}_;Kx=r&u@oppiQqB|Tm`*8-%WjTihFe`}yD4-o-mkm4RqhUh;c zwLDow8dqCBs6pxk4sZOD*Wq|HjhR?wtR<&OI#!4<)%MA<>eAD-Ey#+#8db+qK5NI) z8IWb1QMS^UduHc+BL-^YmG`%r4G>vm4WtI1iuB(;$X7pJtyD%F_KN^LFNXk|`iWEkB_zWR|k$j}GiI4{y_lF+B z$+}ObuQ~hjdhI&zKA8vquN~8_(SC2N4>^mc$xejKis(GcxqDI|`tcnGibZ0PQEElA zAT1gswaq^@*}XD>h5FF?IftjyqWK(+RmNi~2RWJ~r(CxAGT74n{C@;i`&l}?1-x&L zKtCOvyV776v(d)=X z2wpj3uNllWWKxZzx^X{{WR`?AtL5FJT~kALNgeBvSa>s`W{4thjliOF-txg3lI|?% z?eAWllqRoQ>T#q2H4`w>xV*^-!Yq`=ge;vOA>T%06blQsnUOWLaiFzPJZ@^S!UmWGkFO&MY4@yNqW^Z_Zqkq`gtX1X$6d~Pw6bzT+>TFZ9E?ZP($qPI(;5o zM{~W6->oD?3mGJxFptE7aYII^yk9OK!`tK<6Dl*>Agl5-9os$}p$-36dYmaZ|2kaZt9ao49o~h3{kwx}_ zwX~3QFzIFJVJuTxssG4vl1Jq6Yvj4n&k(WwGN46Y5xDJN@~w{s*WqW@%^5bYl+7rC zg{>G`@-IeUX@hLWtWb3JeihuCQ`3Wy^`tqh@|<^lDc#7m8{-k#hed0%2(jqN$<-mr zEIAng)R0-dL>3t=mH|M+m(nbj@j~v=rz9CyVQa79Z^1fX(7%X zjnc&6)e+geUBgPc@Jel!ZOcV<9QrArsE#6hhqVNQKXeO;wHmB4UCBsqeU|8qWF+cH zGq@v8<~H1}k7yg0B1IzUYu~L|gR99T?~B%if;{FC7v2DjoqHTF4;--htyJzwW&^C0Z@7P$FA8VlQ z_2Z~#%WQA#WftAcJu=}Z;l72?a%i-H^lCFhSq(YTAnY}UEhX7XE|t!0oCguv8rjw( z34#*wWf_?s@x^~zn~bguJcCC{NgZ!p&#$#0CqVGKL}J0o#&x_bUOu%brFSomezvZ^ z67k1@4c%oFmbM}7h&niH^p(U5&N7;f=T|@Mx>*;PbOFI~RnT)rmI{q71C|!zt%O?N z0Fi}AIQkr2c7jJ@M}4o6$Q-jM9cm-(cqD4)Xy4>W%&?z&CxJPl1eWy%=Mq!`OA=HP z+EN03E}{_56hhk~G@5bYrC}K*JmP_0rx8rrby^-9*MTQf+AJ$4h45l30_w9-KB zAyQ`=wC9qfm-hPz$hMWsSge^si^wWn$J-ubf<|J|Z*0s;GpHC8kv4s_89lyyPG;PVfBev1WLLmu$b6<+|2o^o&Onb1E7OrLJ;CwTK650o zukjxv%Q4D^D8VAJDo zJ?A&pKt$eZNX*i)NFEV@6vp=z9iUcV;F5$zOE~Ej!DS_~v{5_eeXns6`SpAt<==T4 zFBs&OX0-A1cutMP!V&L)RmuITS_RGzt$kyAA8Va zi`@fy>!xPBE)iDJNjk!5+jth}+gK`iPkm{1`J;9rVv6hrkI16)AhJL}&L#*}g-2Sn zq@|G=t3?3Ug7<@~>SN1~DB0Q6m*gIy*0m%X)c>M&_{dAlD`1H@f>9JHw3ViHUF3K4 z+{Rj{C7D`|dwHyAd}s#j3|RSOI!@77&2QLfB~(i!SLr;yONR>iKQU$(wFwUiFDehO z#+GH^=phQU=a65T1trhuzC>bk1c=$z9LrZ1GROn>BGo9k!v@J zbu8fHfbh6i8|DnM2O^8~FzIIP4aNkVBm08CEpo&&-eaE~xq16h^(k%N)!Vh#R_6C{ z``^1RI!4vLjqp)~Nkaq(ormzrLTiMQ)u8kn2HqZc*GEQlk>zA-@^?0ZX%sZYa8!TE zbeISjw0Oj(%&(*vH~J8XHpDrv{Ug6ES;pX|l>q~pB(XqjAhITLi4+nvMlfzH{<>1FBQX*rRR+h*;HOMBkv~;~^IE()E$UrMv&m$yP z)DhNKoZ?Jb|gkbRF&@2(z!Rs?MOfdsc-KMr_XKgmm;zV z2(+LN_S51og^8k-Ah;ql0xLUu@u(g(L+=D&&%r#J^`aOoWIN=gIoUaqtK!NknO|bQjti zdx`LkKC!QmOxxRIF-mG#&ypc`qY1O@bXI_rAaFg{^_q-~S@4riA;L}cNOgjPg1*&}qGbUKk)UOz1L zQK`rHxig@3Y^AYKTRxZ-0nF=n=J+tX9Y;-CXtsQ>uH)@6Vl($grS*o?St&7@F$52t z-+DFX89S&%Ey*O0TSSCML>+B_Z>)h;W)d>VD^2If{;>`6`vW$?<>VEgIH`HfHJ2mJ z@s!Y< zB1&L^Z;I@Nq6U?70F$|whn zLGS#%4(|61Ooq?^M{gLE=Me21g>>>b8HO~aevL#+SvuY#qFSI4xY@)@W_iy5K7lk7 z(07O)1UMOD0w5)2j+K92LCemIK-y40vMB82}=;La#249x^SVUw= z&@+=yOdksHu!t;;XtvIu1+C@9YAuP85x}$R_p18A^Tk@8neK^BL}M9YDIe3Dq?VW%eLvIZM5OGw1b(T2f)-oRIB| zeXit03Hk$;V%5ll73s>yA+5h@(N9rgRYrPQ=WE7=QXkA3U$o~w10rLv_T6gtZ14zm zo)_$+mOL}aE0pc5IC5<09j7wJ^pbPD(FSa9fc=g(bX-0157FR!X`u$PSrCzhNjT4T z;JBAQOLd^}2-a$h?7Xj9&%M!qJ>X+c6g31^bQz&4J(LMC%h64@2)K^!;hVgp0GRFb z91%Ls_t8!BU!~ijpZcDCOCbme=oA8*6IqlgM@1q#z~&c^MFeRU(l_ z>g4U9p930!ZbfHF-L(HWm$V< zU8SGajFF=^ZeMNrXaGQ$E}Dg`i-T9x89{Mo28AlP%zx4elATl7)@V%-3K$_SeCYN=O@g zv&bt9QoYd(Th6Zo7=hNCek3B~6#??%UJtRAk(QU{ zRr+uXQ3tz&Y##Z78|;MzBQ27527z^Er@f^OMq-vD5sBugiRQaUK=wgIY_!3$5iQ^6 zO0tL*MTn~P{8)M^4Tw@qRNPa)8GgZvID$}`k!Ot$7P%JD-;r{cmJvQBuxdAL z=LPUW1g(M|L1JY&<(h+nXft`OcAZr=Ee)?68`pppc_gpNkY6v|EC&hcM)tju_iUUW zR1(S` z%KNSWtXSgFy8j9psRN z+BU$?2i|_rYmf)pBf@IaR`QD9AJLv!pStuDMD6h9^Ze&K>I$u*p zes7Io6G_*5hLsVO1?mHGe^I)ZY#__1&(?=map1iPL&EH_qsBRCb+9y|pZD=iTs;d+ zr0u1GdEnzv&7{gzWfJ}~$rw$}Sua1s+h}n;#)7K?HQM6g{6vt)ZF30$(%d+f5B zmolNxXm|t`x#l(HP+C|A%poH$BF@U0NG$1SXvTxQ*1AqQQXBV+k;Z3Dzs>;l)z{vO9r_#v3R-!^t0 z_?QE5U&b1PuP%r1rRh1bMS`Zs>G;PVfBZ~D)+%-5*-zH>)^*nM!O_uI5>}KdeiM4@ zzocg~^>Axiqx{Mi-HITm=w|NRpXB*H!lv!fO||$;utqv@qhAvmt@5LhSgQ_18YyLA z52PC_z;ecW0mHFX&OH)%BOfE{mm4dk=w9w{w$4hHo<)vBweScpUViN(ugii)Y{_zJ zWSuq!YiWDuYszSquQ$yzj;Gw-;lO@a60-h!u$NEeqqlElI5$?G&Px9*fd2tvVB6cd zuw<#0SiLGx59C+FM=nKVfoL5?WN{r3=?}Gi#!6S4goJ-E6CU?4OFpmM52A7<5hbuN zq0N`xBELtJNOa#TUSMtCD=ZVyW`axUMMx|pAeo3=Q{U&p{qbL>7E$?1Ml(3>Py)hq_ z9E@^gYme0eGb_CglC_!f?lbEHZG_F*Nmujnr9@uIH?-9v;^a#?nju%xNsVkG&(F*6 zJ+S(}=J1w`3oi-{=UWIZ&nd4#ss4`EDVnW=WrQQjHhbyDkyy!*ILfgpO*UKs@H-I2 zvh9TNkovgBKD!5ERX!7lDJ-dj@2pK;@V6F5w&AgS2rnWIV>>@4ui?)U1y5UxxQCB0 z8#8r6?L@>`;n`#nd##pGgnuCY!>~nzOsq}YE$3A;j(K{xAA@Wp66>Mhi@lOGYGm&L zc7rf#;I{f3&dJ|d#%=4S?Glz#ys-vKBordAl+Sq?p zr;5K-aNE`Mz{i2!arKJ!o!0;881{z6#GW=`hX4`!kZfZQH_J}<$gODkvO(#uL|}1@ ze0HndS3qq!qSt#iQ;8EnpNMW>)kI)%1%*&Z4$Oe?gr!m|RfaTDBP14`!@xB|NO)uL zXKPX98hOXl+PDu$!*Zs=%OtPRUq_+WNZQDUCc7Z7V4MLn$g2`s<>x5bi;!C|fMs9K ztV@}uv~^^plg`0j|S`H=h8l$_Qp$Xf*7m>}zb>hSU7$4_5^W<{Qp9Yr6=I*-WG`gjXU z_eRG$evM_%k!^T1vL}VSw9hR2o?LjxYxMC8Y{f=&Gj|!dv{r3`nfrc9HUMb;y2< zV>28UPlrVFt}SOIilQamRe;Hnj6F6t`cOMAYC7?ZG8jSYb3wLwM3$B=_MYY>?yS0u zl318LlemWnU~Bx(Y@?&eEAPBE-bKo*MWI{ZK}!$*=PdxOQ+Y;FWVY3-1pd7giG^}y z?!RLh%9?XlYOvDsgH2xDAEYyN6l}m>+pfU1SHF(YlslPCZL6KLQezek< zv1~93O$T2|FKc~@;E`G*h%GP88gh$|qn^=NOOo;D&S?Kgz41x7QT2W=%Lg^ccAbsZ zd~2N38ab;?`zSzXVRQCPT&)SNXDz>pUmKl7xHp@RPX=R)9E}K~dLdhjle)9&D>9~% zU8j|Ml^2Lec^sMcsELCalQ6BmX^F(LIFe``f#^aSMX9phI9S?bw1s`t9s-56BC!Zr zBvxb=OO{ujlZFESes4;7V;&-k1^=_is}Ui=TG@8LITljSah*)xDe?-4$YJKPK?ym) zZP-8^wUS$-j55oXz;`K!+Bq#9Ej{a6@7YF?TiQ~>-a5Xw=qn8)ot9|6gi(20L@sxr zjwbS=K%F7VWD{3wAmU_3`uv%93<;7u;pZ063RupVg_@Qfmxw&PlUjr^Wrh(+E`*uzL$Wt9rox(}!^ zoHyK4h5Qvgjk%6iQo51Qvl-!c-86l8r;Y|=p zN60doO3qb{yhNVMOV6_pvJGB1ME3^IUb|R9cFtMj3DoV|Kq%;;0RjzIj7EsThD zjqIbscGkGw=PSC~;xkr{2z`-}UmP_`mi5`Bw^em+@ zRNE(e5Yj2|J=HnYepnWr2)<$3Ge z*12_%bs34;;v|<$BMX|mS<&IG#FUr5cb_-=n_+Mw{d*(?wD!!fL61O8LGL>8{s@@TDlkBHPJURGTO?6p~@Y>txi zQo1w9RqI@d2asM&fAi&rLe6s z^8fNXzdvd?XA9uQF&H&amkbI%SY?!9)~j%}aMG5y%Wbqn>TA5hoT73$F;LR0AS<%S zE6XX9d0Mi9XWF`TE@ade#}g5)r5V{-I@C+kvTY>1^A;hcT@x|%dT_6sw`=Vts0N$4Ze{gy^1FXHuLNN&>Pm7e~pH>@Q~`uQt{I*Cm+AE&LIh4= z&p^$L-NslT1f1S9s5$r+Fu-JxSEZRJO;)tAY3s)|VYMm$FR#_eEUEJ{bcQu~Ryy`V zMI?-7SM_4$+3%yE>4RD0%B;Lf`HYARh?EHtyqmZ>A2P<#=sjn#^GZ6t20bJ-d|)ga zw1_N3WMLwj6A9WFRs-ZMvFh@{BRPxN7&%#@LE2;Tc!|V9WMQNn4^dbsI3?`udlfat zM#3_5sRNhZPRL2PXxbXIS*$2Dr)uN67&ZG;N-xui!%WZ2fk^8oXEAK906v(|cQSlh z$g7c&F&=o>awOfYlg|T-*dl0T7XN71wjkOEYR+ftw@qHHhhBT2$HCAhe`k!TB!{$b z;wG-niyHDNa_!MheFidRxhJ}XAH$oWOGFk(1W7P)dnjTXp}n=dP@aurkx8^#=||6d zBo;?>GxvuGEF`QEKp=fGkX?y#F!q=`kXU;F-8efm`PP(#=Csv+OiGGF!TDcC^o4K3E4W zs%~_CwfT%DT}J>m#MZ0lMpS+x#K*?C{s`g-QBjs11|rLwpf0r`&TC|YM^LPWD-fzB zM4oZRgtJ9rp^Su@&D<mU^PEv`7K|ANla_ zr6s3YdRE>W=YU1pdwQ2gl5@SrjeHpP*}8P5{SypiDu{P}26*LRqdJeo!n5@#A3}?8 zdP<>I*>BtzO8t)?%ObB3g>wXUAE`s_45@aE>XsZ0IVMEOEBO|=60`{eZ88AY%KPMT z4(*LN8`npR?&A}6_>QF!1TNP#FEKa*M@~Adg4)T$BT(xwjd1Q~Jv%wbtL}%h;iDvX zUIg?WbIZseuSzzZjL6c!mlkrnztoOen(~EDTNciZ8o2|w{bT`r48I2;`3VtN8rdV6 zSYB95p+yv3D`^zDhlih02edjXj%)jRS&9IxApadHOZ40b<7DGl%x=%@nS&$AD_#yx zZ0vz>44~ieLJUOXMu{u@uOY8+j}~zyXLT(-?a6{gh;7_2N`{ygMUB}&c|HHg<%ma) z$^5qVhHYRMndQJ39h*_}4b(tT2TQY~=JaWsj zRYt%v`s9o!f%i4dNY?r#hrBP^SD&y63Cz}7_se#U5?4}}Xy+|Rol+xbqn(C`t?ixD z^zUepExy8}*hU;)f3{FFep~mi1W)hvq*rslXYZHp(Z(H43|MJkX&~8!TEC^=+P>Ma zB{zPHEP0NMStIjr$upWa$(r12IjS?BS*RKnzN0EryWg6j$7_2jqCf)-Ccb2#r+j;0 z-pEE&9yKSa1u!;N7=SG2a3dGclbpOFM4hBs@(TAzBiD1DHCRqI&tqdF0?VF}q*Wvh zevkHsCoNhllT5%2`b_lNPNT4DxsJwBP7TTBiThKA=kBx{dtX#r54VwQD9Y>EwwrpmkcVyko>Z4jv5tlU!PYEpUxLV=I z+V7*ljlLJ0*?V%%G^Uu~Ehi*I4OgxZO65J1^4=)p=yuE^uLuY;UKP8~w84sA!0ehN zucD|WuPoiyGC)V}!3^TY`A{!l=o{n{&Rt8*;tr>8f&xFelPd}PZ zrr}*PfwCg@c(E49-loslHh8{QXp@MMdjL5`dw%5^Fp_wxxwhrFH@4IgS%}EeuH`Rl z(Cp4Llh-}tYmeVAZIBUt$4b}B&+;n>EoGEJMb>IS)rC!lL3@lpbvkQL ztkQDAENJCBb7$T-2AYz{BCq6&8;-=;2fLL4eNXNE>8GDQW7L$uWiEQ37Jkm#H>;g9 z2GNZ*(A##k1Wbw8(&V*8_9d*P+S1X$2D^wT_sXh0i!?T^GJl{*(@`2^JGz;2zSQ;B! zYyc~7uYbw1SVS}^i{wVfTgO6hEgM~aE2rOJEE9^|l%PT9$sn$KQ zTJ!Z_3FpQJ!5e7!_sE+XN0<+sn%PVrc2YAEnXFvPd+s1K->bxvied%m| zW-BtDF_MNwUPb%_u3x0ik=I!|o+d=K^lDIwx~cI2N;=-k1J_t()3}maSuW+J<;(B$ z?vZ8E%56c)Pz2l#>IEmUO6~l}GI}fl^%^yT8pRo{WbL>V4zR-|5{rj7ThFQqUZit* zMs7`~+_*NZK|_Ae8u(Y85#9Zv9hUAQ{YK|%_sNkm7aef%zvQ5L>G1zD{gS@jdi8!_ z>CKX%D9J9*@V3TpD_?KS_tN9{QJ*EppwwqaO+rNbP~^Ij(OtS`C0IIbWPY{RM(l0P z>DA6<0UNsSD6HcUB|v*7NTr@D>E2b*Q^wkRd#>lU8NRn}4FTQe5n0+j8yi`O$kb<| zgNSC-S+jZ;qSt132BZZN%K~+Fi{Of)#aY@;)&{|w@sQuM`UuvvuL$jR@OzM~2MB!H zpMZ26f3Zc>IN{eujau%&XGd396D-~}8~2G?B2$xB97lQ?<M^b z-clK&=pm(Q(mz{&mF2c{U3Pvo*VfqP_|HEhKxOjed1K=WXd#@n@=E4` zrRytgFS4-#R84_cvomt=^X{JkZ^ko1V)6a5A`t?mXO2WG)L=Vi^P$aBX17Dh3C||4 zFfgr-vpP7d0OS>xZ`43Dj9Otuo>KaR*N`4Sq7)Yk|V4;c;?&o^SnMEYn=dMiLHZ+6+a?6nYCrE9eI&Dfs60?Bmm zWbsB0G(Bp`1mNjE{2yf}&w{6OYwnGpRNtkvwMoXTdMCTFlwPa8JByCrSQFi$7b`jl z+z8T+mzEP^4JLnMP)oj6IeM`>{rw`VkC6UY%hN z3TtrN@BxRG$Sb^Qum-g=sVzFV2QnW^w;}}IyJlk^FqXE;3GUYnO3TPBMJ9O$Zms_D zqHs!vIi1I{>5o48=;=fnPY;B&Mqp*Yvu|3`B6!bR%ImE9eze0=8|_w07;Dj27*nz$ zvq-*4j`xP{xv<7!Z*qwPe$U7VJgq#dphO(i+?Sb`M_xs2v=P9VM12`P1(gB*Ghgw< z$8HZZ2&|ekM*AQ&dbucUPX=KS&-!%ZG>-(g=LUMh$Jbu z7U{*)#irQT5_%TS}zUF=Bl;B zMx$%g&>U-T2C^ni4>jpZ#Vi}4K*~<`;BE~%*0BtEEA0Wd5^4v% zdk5r$^cj6<*ze!f-Dd!Y38URZOX^`)%-<&EbXzeOu~#q0KH@{0Tj zikzfz33_~(?SuZ?aV~6E;etqdYudEuU zB&s;&F?2#}@aB7Bl_CyWJHb})>p^Ri*_}3XfP#~BChQ2TIQWbhMP6}4>McrMNfO^9 z8eb?x#lG-Dd3jOEagx{KSR|i~wSl&i?OL)6WSet2)r>Kj*JzpHX~V9dJ+GuQ51mc@ z8f7~Rf#vB0z$3@6qU+D_EL2AMvH%>{-Uh7Q-};QSj1ZG98+r0#>A9Btd-UNM#^2Vu z;`f%WDMjE~zqNBup5$)SUIQA7XflPD#R9j>;>K%?olg6^eG8HvQ=Ms7)HwGLS7@EdDl)~viXaAlEKR|(bM z{pWeSz(Tbt@~Rd!%SMJWz7nC#^A>J(5ib&`qPuCo_uQn8K=lA zjl6=hz-3$#SQ^1sgQNS0G~l)K+in^QB9XNEjgVJ_UPsf){~obYfAo&k+`n?$YBqPv zy^(86V~%%@6IVx&SJbW)bw!`(B!rx(DV6!GdcMSK)TA>4J#xKrdo1hC&Nf;oA8!^2 z3^IR{S4-JS4&TP{7%g{^^fSpTLQ5F$3fKg28B|B)9zPUIO-`+U+F zC-RE)Rf_{qLtaS&RMVyMe2pO-b;LBXDjEg0aV%;KSk1WiuI2x|>oxg_ey@Q?8lXSX zhV34CCHn;?(zNuvJZs7sB`l)XOVZFwleZ&|Yj&t?b1&T$`v1}8u=F#H8`hFkZNkgz zgQaUqpvjlBPPC0eq|Xqn@iThAJRWUBO;2il7{~elqmfaLQW~}PzWgrjv)M1DfgYf! zD=mU5LRxBiy9EB+rLkiLlx&V{jFjCo*~`luU3WYb4jWG-LL5;xcV_2O_TFbJlwGH6 zj%4QSz1Nx9GNO#*+z}2L**o(T$;lp_J@5Ve-anszpZ$D4&-Zzf?tuox%0!u~D3-j` z$gQ8wk=L#_rTYYF+|!KHuDq51ar*WR8vJjcy`WoTDNSj}WqRTlOKhpdQ&QjvPV6Cwlsub_B&k>Hr$tA zFk1?~c3$Bd-KYVZ7FnyC95;-w{o|}joUU!#q}^{T){wE#updA)5MDUqJM}SG~8gF(gr3%YJOAb!P}nCSNGRdb>;nT>}^8c zbp@Xp2kf~XX4R}+8xt}eQflffS`{7{F$G0!0eFnzCE77@uQ@d3zJOym%$m9uKlywfB9CBmm$3*UzUURkSEZf z>T+R1?ryHyh*L^h35t~gD0A^?htbi)STmHpj%w}yq+73<(iU3M8y*Bl-`|3SS(h=%UDCxO1&2|I;y|g0`W*s{fxp@ry)yh}6%6Y92~< zu}ACjP}so1g!evoZyJRl>h#Hu++LHff*OxTvh!?zyDbvHz815(pE*8xU84znPx!11 za8@B?QXI2>&T$>@kJ+~WBk9AzYv4cG|23GOWBHy6w~JA08jhIHE*f;!Hj6C%r;~8c ziqj&!xHR9JzQ%4^+xX*s$m*B2is(6{?*o!j16On6#5D_D~lO2ChWRhscme7EZ7RHWF zv(Q0?D3f3sw)r;Q5O__D)0vgdZD*2JA4Z>tJJqaaC`M5cV&9dvWMOB)msIHOzc;cg zjg`Xw&9+=K>-2Kx&5&96t!zxq!#K3HJ+tsiW_O_2lG*qvdbL;A{T>4P6+fwZqlcp} zeh?Fx8=OLx1eDOOz_i2ihd!|6Cbw`3ODnofuYA)s-bxhna*s_FH>!aA$f><`B)Hjd z*r-aq=`OMGYGJMN5}!wt(kN&-u+iT}kyM<#m=N3%K2na{DgAb^JoN9hEc_%bn~m{> z*NfGPTc%TUgQ;cd3W6P4s~wHBS~gL~g986tc8_|2kj>3XX*y%lNfvFE;X~0`h-urm zYuEa*M#VLd+KU3t?^M;a-5smfGps*oGiYo3J=MT;h`{$-osk9ZdY9l{V9rtxyfPdMQ6E$Fb||bG<2+n}}PJ7K~3dbgh?n z>WnarI&KRN0KwA74GQB)d=a_Bnu~@aTZ?)6v6{E1|HNK}T7HCD*q6(amse`<{bcT) zS@*(dz?`Mx9kY`tNemp ztv6*86`UzDk;XjYu}@OX50~&SGP{aYy*;$5q)2lfE znNM*`u12xu!m1*k!1Keq=qDJHQS`wSp=jZMX5uDN%;+u_l=+N|%HjmE{=FCaanB_p)+^B8@C#{pz(v za5)T`f4`9LD*}HwC8|8Xv>-4qK7DWR6urpIlf&@u5*72eo^kj~n?d{hyOTrLL>2Xbrb%ZpfksHKuTdui^gq^07OI3@<;g2J4o*5e7x({yK*qHTx9o4RzU-F-1( zcm0`37X*=(g zd9s)9uQ8k6u&THCU?1&nN=nKwcgqDaz2uZn?v?{!xPWZ;TrDq4DAh(eE7oduk=qiF zBTVTTE?p7QpH1C|VA_8@2dDo%eHk_`42YE+^P4&EA2&z^=so3$nZQ{NkN_*U1R}JG z4_zUvkCKeQY7Kg)Vvt~0$wVOPv>|&JD=@)uE2Jm*t@%e)q}haT)#v-7)}NKX(n9yD zRCSt;PR|;~#Sl^tmrRxI1hRhWVE7_gIYn}xQpEN=M4C&&3!54;V=R!SNI05sH+e#F zML(z~o+l!VjQrJIHp%n5BnUB{aEoBltDl@0-F2d`{+W3ukvLPe7U{sSLK@C7&AERh z?Ej;f<)7NI%HQZ6$NAxwNLZIjq4o6V$1kQ+SDrUVopD?Dw>Y%q{UnkRZ&UifRv-cQ$FSGPkxH6M))>h=oFnA%QJVWG!BLyr8vyOkLrL*UM9B6mKzpH5t?g8 zci9-?O!9n3{v|ms3x6Fxtg)Rx%d*>!AJ4~Tu961Q1#3Oji+%Zw^R!^tzi*Ic=8LYf zfr{dCmj0J`ww2Oy+MhS#AH;p2{w2e0cQM0Y22u%%&!Te~%2k2ctEKOW1I+pD=47;F z6SQuMy>2@avjJ=PRAh%>@=q7<=pQG(>n+_lI&Pjmcf~w16M7GR^1>^K9>G5(B~HAv zqaM`m*lZHsGesif029Kb9bpgn|Dn-W>90T%;Y-rAq83d!j&D&MN ztjOLnq^)AH2Whm)a(jPIgt4=0z7X4lGqO>AD!}!`LerPuZAR(KlGY__jWu*K!+G4? zKXU04zzy6Vs3Co{4ooU8FyNa3z8YM8tx{P-6>O~+F~#_5UI=OK4b!wijIFcYWFNDo zoOmP5WB_ZR%@0_@1ZlP=>$2Nxc~g#jfa|4{r1qxiS7?-^_$xs;ehzl@zCNCurh<#s zBpq~%i|A2$SG@|8P`=#nt_Ye1qR<~l2v$a!j*-$#*732GZbK$pl~69MBC41qUesXX z?h+ zosbzV!W~(v0n0v5_**fw*LLw{KxyY}GM96H5~YO=$_RuP%~LDv`?Bb*lfnMbbVUCnOq;(;BQ6cs5m3x0VTgkTNv}xb0=H z;np}QDOQkm9q7v$x>ljh2N^7t(rv{mS%I?s7gAKl78#Scgewlkb;S^$f`tG%+XIcv z4kelbdW6iQg@!&&@?$Q58O*wJ!wZl%6=13~nq^2FQ++*sdTDu%opt)z%e-uGw_tg` z6KROCvrI&C7>OOQj@^vWwwMz8LubLoz za|#lQs}*s|n+dS5g!CyMiay1oE^&|*-wa%(L7sJp1S0CH7M)F-B|z48U~w!+?DubE zv$~*?_uw;H)Fsp;f6m)DG);>Y=#8;iQOzRpAUWb z+sKJO+ka4GFFTT1*>@^U)kP4$_fQv>+1rwPfnDP8({rN8YM*h%iCn7;#!77jmZ2sh zOqE{@o>;t-Lz%Ocvzam}J+-kQr=aV-ptA_-e}EGkN@Yf1vp-zlI8(oqcMj4luCJC9Y%}F1~x>&D9=JHnjh_+9RB_H)2cC`0HGug{rzi zSWZuNWU%!f??>5+6B+OengpNGYHqONo}cJrbGJ(tq*H!rDB7bh=Uo13CQA-8{LrOg zM3G>E>NfUjo7Sqf5aqfGU&^X~1q1`_=Vk7fpw|J){OVb|nFQvPFZocIQ7~JWuSrGA zeOPND-ODxP^=vO=zpbc94pD&7Wz%x=oVEh#zP<}^!OD@idZ}b#4o};Ui?Os5TlRQK zsY@i%jK@=G)8#n$t5K`G*UK~`+d$=NSjM1V?=^RQ5NMYB7YRN-P16W6yq#(ux!${5 z_}q6d_3r+}Z*lRqelguWGOa@Z2C$^P2+}5xw^xWaD@ zY%hD(!_!bs5qG&5I$RHWg(7?U^0;)l-HGRC$lIKm%?Dmm^xXgX;<=sKmWOXMV0dI!zfikq6`z?M#{Q8n0V&`W&cz~ zd#yH#5U2U(AI5Saez5N(yIKc4)FcBk{b`1UCc}X!m)aH5n;47qIFPEC&d@FA`QJuF z;W%rWwyUp^Fh)Hv_pJIQNw>ez0=qsWZqq`UF0N1>wj2L3IC4_tkyPbjenZkyr+A~- zWM-cx(k!ygxixv6$DcywA>g03`07-Mm7~O|2)AAQmO25n=d5bLs@GEa$<6OYrpaCS zaf8MS3(EM+|E^@xice#bV`w~_@%9g6h0Gd#&7jw)rQ`bDxRJ8Se zmk47ggUz>pRG%3!B973#f50YDH>v-aZa+|S76jvyAl~VF;^!!8{iUF$aTC|rvA>6F zCma#;anC;W4Y5nYq<5Kc))Rhkq}fD&6~H(All*QcKzS0OaL0J|O}eM-zW@!s;#)PZ zL~Mp`di%KFn@N6=_=f+=2n?1SxBDUg$sm^#yTmL7A48v@2f6txv_9I!G=9?gihsbA zNoug!q^gwVNTXYwB?gp?7M---2FVFzqVC0&yKTdsf10NIRYx@_adYnhWj`oS3nAe2npOn8=K<78|GwAIvWbk$?y+j58R%T_@m2m5ST z2DhG+ict2ATqCPi6;XJL7nxg9w&E#T5Wt;S8e#tI ze8MY-Fx}5jW_FW1u!btiV)dKn*fZs;7nyX|9TbbR_DbbWBcLRst>%BP7>&|G(UdQC zQ=RQHv)$ct#wgR6@D*`N+`*^I-60~SomS0KQc}s}8?Hd*4bqy@N%O*xXh&ecYNlEI z=>3v73C8G2wyT?DZY35#-7G}1n6epgs3cWX6+cd96L@QCPD^su>IB|_bs7V0#<(g> zvId6yDE$ZsU_qCvDRQbK-e9|pl)kaP8E8{@PpPo^#-_A#00ife&r?Z%qZWaJ+DtSD zq>N7FF9Q%7qxM=SBa2q6x*q^+HDnit07TS9fCCICO;-zK&wbSQWH-?%IWGSU40W0C z`KcY35yLJ%(H_XcAbXS@a+ck6vJ^r(-m)g0H`dqJKk9cN&(Xg+%I>&a?S2oezy9y| zEj>522F#g>)sf%90Z*FSSCVHW#GAjNt>#BrqLR|gPDAb?GC6(h-@L$#RV&?IFw`8k zCln3D4gWUVWleE-@m9~TG7(+LIft{jG6`$SwirxLWZN<6ROxv#Rhyo?7Vkr#Q^`S? z-|5S%+4#PA^6;)s`0(KKW7b^$((BkJbsbLT9raY+kvA4eIG|rp_v8f5dRk*(@QDhz zJ6&xm&qP3ENG>A%pz}8O&+9(YDR&+QKlk-UCHIe*^F!rxEz-I$(jLOj*MI+gV*c1IAEN;e5YfJnM+N^!uZly`af4ItRw*N?y*knUsJ`1*cUb}wV-1md;uWF)t zv~WjaQ;?V4<|Kf^O)7b~^}Yeywa{(GQSir^v(%?k@uM`E1E6}0wusWH)_{nc&NJVD zp?QO(kUNp=sjdO0Wt<3flcm16v zL;phY^-#uKg)$^PY$d}yyaXw&fYvLtqR#I@XWX)0+mj7cFxZpsSo8wI`#S(faM=Oz zAEP4O0w}!7QFJ+LsW(!SlF2D6@mv7;baJk?!0q#Vbz5U~X>6PEIom|fUivK28!o^q zR_Mm8uHH?$EFv9r*8jS&aC3dhu3>le-x+21kkgou)1PRy1RQaDkv3!7Zp-c4OiwuO zQEteHBF7y4J0|n7h)rML3;_3!h95O;zL}L(pp(`w&I#*SaZsJisd1NSz}v{0m+HMI z8uiDAWLt9bpd}SufHyplZ%ZPAKCzn6VMfk3eA7| zR38rTbJZXmk!Gd{D@rVtp*2!&r4PtNm-}PV#t!Q9J)T@@gyD@2)SM0sTH-JB%0KX+sXSzb+0)^>X4z5>}3o?MQyOlGn%@nuP$mUL$g7N}~B zROgA13&i)U2syg>*LN>0Aa!0lQ?@8P-N{ge{hM!hC4RY`8oQuJ!7cV?(wx8@ zvB*qeX^;x>$ohIHWS%hH+glJ06y5mIKw1{M`0&lgM@po%L-0#i9!0xW{+ljLCT`Nz zD+L$MDYekV%kDnouv3nGf8qz8X8%F+Ba{xK?&gww9}tzj?4xtPL9?s zjKb#YN(3hyvL--rk7UEbNQz@^gYX_|K5NoZ$MtN5JLc!y+}CFeVgE@a7tel62a=+O zAbGVdWOnMM*-c323@jC0FW}!_wO$X31>YQyfUxorH>>Ru9K|`W^c6_@Ma8!)5ZQ;X z^_2LnN%{{SdWdJ|WAo){`kS#C>XdQNb;&@Hu8qVaci9CCKC`^Xg; zZT_b)ETPZw64TkewIn_PO6PwyrXzSgaY)f&3bv|xTYr8u!E@C%P?eNK7n;Qsd^n+H zaxxsB$QH*LCCMUw((#4W8Z>JOFkO7|wl%!gT5Dmx-29mOXQ{ZD zVO~gz!pynAWbLQxcczT+%GrBv_uz=vFQ_o8^k+pmuPD}Kb%&^(Kk3}nPxFh523hJ3 zRq2W9-rU$HnaVoKW=;fJ7TDAAfRjyY%|bO_V+SjIxq*b(7wc{TEk)-Q`nTPS2Y68a ztIlN#n&(X{Cj1L8*qL;Lbl?Zm`wc}`uIXm%?Cj4}%Z`gkXGKdc9|2d2LL2ZMzpTPc zDLZ(}i|h;g2V2P@HI@8*{mODcwiMTav5@P7A*7j6$YcMVJLz?SHr`S?!ba&KRWGO3 ztu}_b+Is~~9W~7V_}>Q5mphw?i` zew8eBhrY4cADtf6zWiO+odjDEtxTO;S8`> znu$~tL^-4!*y-7HR54%Sv&1sDYcdPd18c-Zlh~tjV_U>u&%aBhCBD8#?ZsC)T(0PK zx}{Mgp%C5+^0eeUXR8+LKOW@n6F?F72?I>&--uaK`y_4h4prEMeof=gVpA4OKUiZq zDI=<|T|C^dA#2~+XJg}|rBjaup(Up{2qh&YB_%TcfH)g+HQQubE%v$o=CN^?WMCma z_93F$yDhOL_h>j3fwNDgs?G##luq71tTQf(sVV3Lal~2PEtSyOd*!7ma>k;j=I)q! z_lxGY{G5U#U_HZ`M`ZDF+AD2a3fyQ7(w9}GXQYt2KgzVIW`~j(@8A@0teqOo)JIF) z)HdG<^I}0pZP}67>s>9njh26eoMneJpS0oU=7dUoS>Lc!|C4wwJ-cl^#~uY8^BiMu zNwGAR4Cko>eyO&-B&CysQ2jH4#Lal$LbGh}+axu6OT_nQ6!Syhn%#nK6?qGPPESsd zGKbzWw3?Zezfl`$%x4OTlPvWrQbio5xpVNKj@!-7DtEd~t!zXe0-01`M+_(yM3gie zjFszi<&m&~*1<(}n<0Ui#>HVjwOt;;&dv@PhnZuUz=ef7P*Z<^+IRGdmFkgSkLIEl z`H@tv)8JPa=nD?chwwQJHal_JLv5PPR^ND#b8=_n2CgWdQ|}04tZwl%>Ar=RkKcr1 zeh=HnmkMiBt!q>qyr6&|#~!KV4s=FC*>uM2Mg->MCPp)U;wG)9;lVb)qN~9JCm)Up z13dnUk(cGWYXPS8KSR3gUtjE*y%II!!r1V$%fbJIm(=aLsh^a_RrM>HW@P##{SDy& z_}n6H{#)tOOOvtK-}ISY`)g$W@@*|+&!4OI+ak**Q0i2+kFD{knkw)bJ*4?O`Ekys zlp1WB(Sv{6V4<&6QZD_5F*U(t=Su7u1P_QF5g~pt^A$hGNZF41JQ=*t%YBBmWD^@> zDWETXFA)3xAc*}_nxfP)ee=A|1O@l67ie3@mTy%H#m}s@^tIKYOHnRAh6HeBBT@k! z;854rY?%K>7!G)tRs~*h)uRe4y{v;-3?FJC{LRRY8k~)1C+qnacFQ?s8~rm3!Iil3 z)kulgC#n95cAcB4;&N>&QzN}HenSaZF9kL#H*(^aieHEf(Cy>tT-mx4wr6eVu_XMY z>-|jyV_0xOW|r?xJWoz3zbZRBJG+qvNXlNrrSV5vjdhJq+# zT3^}^MuXyTe<%i~wQs8RXu=9GE54^xZ9>RZt(p9k#!eH0*TXQV6Kfgz_RxCbIIEH8 zhqxXW&YlvtCgWcS-9dJqfY8dks?o0MMC}Ws1w-y{U~B-M!<{X|IaQUMRmQWE!br#V$$qq#-F8pNg=xUBSg_zJ>y=9Dxb@X-KonAC`}}f`WYP=74D`#M*@9 zS%Cb@yw`sT)7w&IEoCO68n9nOEWG^0O%aML2e0JRB9l!J-f=88rnq2%&u^5PG(|Pl zMyq6$0j#IeYAblhtbI0kw@QF$lWykq8v6R5)ZYj&Qdi^8(+;0=|9UhgTd;o$3EchZ(iBfJ7*PwQ0eF+p{@AkEBk*V|sakxE`qkbJ6X5J}K3 z<|tiAa=82tZT_!VXwq5sLG*5;*57HyJvwU@yp!M>UUhM|&8>j*%oS>px$V{d@|`bX zy4$my)U-66X=-i4FIN-w5-S*+5&KGR6t;O@6|{S$P~ic4K0449z;J8G0ZkAuQ$=8nZ3=SnvQ+Xa0P;J8eqzpQfa z_Cm1r^%FPo?;WKi3g#G(B)Xgj6W7Z<3bd=MRPk+)6KHLcrgi3S`h;od5juZ@2Lb#O ze-6{ca6gj<7Yutk|8}#<p+!yG2LS7dzbtEM}A|~oDNqKE7TLO%v>+FM}F3@zIKZXeV>%+ z-n;$V=}L<*J)Ql<)zvjoRWvNKe96>YO$asc?vIYNwTJqN_TjX43E0L_PyPn!EZD3e zj6WjKDz#cEBWIM#^Fsy7KtWgIe9`5)9Gg)$Werqitm!Anxd1Vvl)LX0kJ`}>MM3yZ zPdngTWOnl8-$}>h9^$=fDH+E!vw)4?^}kVl-`&rj5=`hlqDYnn*?CT zGOeG*3H7FRCOsInG~>@{+BS7tNTXc@(trfGP021%6&>!k)lH=Yi~R3Bpm_k z_0(M4HhZ;fHwfjLu_+@TXsOB4MYWUTHl9Ui^Xt+A_VMR)%?Irh_8hr)vu8C9ekaFf zWo2rKYBHJ2--O%RmNFNSF4wARvy)AR+D+K}8>!-w1tHD>9dH#RbI0TtQu4-P1YMzK$Vg{Hiiov{Ip{mEw>WX3>{C_^(Di@Mpl*VP=Vij8upV<24 z#XqV}nXJ$Pp&WQ?8U7=!@c3f!2JyQm5fJASEtFpAl{X)zYWK61!#S4mds}b4#Hdao zqUWC72L^uD)$JmYSw+bG8s4ay3k3Ugs^Mf^L7Wj{_v*jm?!QkQ5?xBx>>Z>kG;M5O zT``59d(*qE2lsqBV@>sOef8W*d4l>+uC1pDg?4pLsGC-g2`We$@4!0Y2;3(s$cI6B zxOsu^Ehv6CB_4*PP%fn>KZZp1FnT|`VJY7yaNkwsLz`l~4B0#1epU2+vB-ZgUJ$?d zW@E-DsS6EK{Yexb3m}QPz~U#tgx%$EraQ4^qVUV|F6M;*ssQd`0gg>oXw53kUvwshhVPXb6Nd7CEy8^0`0J2 zG^accx8+6h~5t?U)H7lqg!loJJ$^jtaswEmc$E*J+@l1 z@_0tbObp!4nXVqtk{|omMOrAjqjxDp;O1kxipCKQz5Ab()MFgy2-64suI_HK(pm|D z(=WMS=^Ev|rD!$D~vSuX`2RayVK-X6Q&UOp(g{t@CY zGZPVVCQ4fEu3)jg{Bz%3nRGVh{{M$iF=G#Zj~zsb1}>}Kl`x#AevzVl+DWgr0a$Nt zJEY3sDwn@`sIYX}D_w|qbe4}3DIF50QM|BLMICGYw3`pbM!s;vv&wP!evc2}g>J(V zgfbdUKPQ*;m_&+9$AT}FJv+dz)DsUyVN=!;f9j&N<3Dlg49WlHTszZ3y<)ao$u1!v zti0?N`a$nze3!?+#@@gF-f?>Wd7-}4^}NLbI80l_z1K~W5&XqTyfi`u_NzN@O$1ty zqeb`n_jt&V_IG2ory2cM_b^E(5b`@41n&YR|TssrUYd=|D>3 z+Olc_sk#}AO{(>_9gNC1H7x~SG_PocPBu)3{;Wq1y2V zzFcu3$79zPCyZ)OB{VpU-9&}tlFNPCkYu3R)!Bn56`3E39r?p;P1aBtjnrQ8M0r*U zEkX+$akH`#{N=ujm55e69+dm)H^6+c?Ub`#5)*)|@KuVB{iVt6FPt|0^hJuFy329o zA6E|k6b`m!4lL@-eR0;VLmvFKn(Rkg1ODAWgV{OjZ#R8|BT;FL5+jxzuGy^mryz6q zw?^SH*{S{u(*XEcMlC<0lpauZ_;D{V1RShLdOB+}z(Xq&Xh&e#ouGZ$vKU~yX7SC( z%^+ZA(`m*`)k4`tH~Vw~Z97b+&$6 zhlR04(&o{ub;mD|Q2cs~^5vV;^P)?FV3P;~!k5BX+sIgP!uMY1C#dyNYB2^Q&i*2c zi*a*UkII=;1!<5}=bTV{c%N?4q5rMkjH?&S#fqv<2 zmu!Vve2Ny2_L>v~1<4S2kRf_Su|pg5+AgTp!I8W9m9`$c|H*J_ibY-E{zsTBw~A%K z%8vG^x}EI_h;wKii#_oZ+9|+1#)e5Ku};OvqN& z#w{44cNw}Dv=`8X3fh5hPPTBd4)Rfk6%rXf`a0aKawLJ1EeoWKxwVES^;8DDE#DnR z?|Kd&7IuS>=wg5%GVn}_p<&1Ai#V`$y%f4W00*JF26849**<=OK0+KLvp&rzi@AM@ zg_J4gDHN_IjCAE3RUpEw{lA1%{NeZ@rJx0OZ|jgtjOC3`#1?8&DnU{qA|Xqq)Aj`H|c>DvDN-C zEBPp^oMO9SCauwQRvc89;HSUtkPI*ECCAfm z3t=#vA3wRdxHfBB5|vYMxjXWyue8$he>NU)T;i{df!|8(KHQqCF-k-qNIJ>!*v#s9 z!X*#a8$pI?MGY&DZ-T!(NaxVk z(9P1wSiTyJ5co!~FkZjbUd!TLQWp23&DV+OEV7VD7Ht2V_7%k>&t~ zW@Izj#d>+<;Y$q|_OB{Z+xl$K?58w6qd%w+J@K3iPaqAi|H8H10>t?A_GpWimHw1l ztj1-G!(+4w<{26BbMq_+=A3E{GW3SfX8c}(twFKJFyCYJru_?qA}iX}dF!iBN@g#T zkMWGb@!+-sdVhEv)_!!z(e9*=rhFz-vjw^-oC#ymjeiI#0RLInuC|m-jc}yr0~mu3 zE^`^F%M~j!D;ypVr|N;}&uDo*_s@|#o9LMXETU%F4}z+yFNNuaD_D?G#DQ~YPRe7n zrfn84gWH->4}8X}arm{>hc?o*KwWSGTUSKZvOSb8>7}kV;la+o=@#T!>t6eX3M@10 zhY_CzoC}n-Wn^IrnsQh^C?W;U@>!M+P2hc1YWNw3Hb3*R@R?jE1ET}b%vDm-q!iCTipaN8Y(p5*fIM9=M%M`Vg8s+A0 zPx-PE6E~nQvLteb*Xwwmo6ZlrV{Uf6Ua;JQ#HX>}Y$K|lSw;v+OQnhmPM^xAS~*=H zqc@q~3@}I^>!M9TF^r`GihemR2Oru<%+Q(C2GV!Y;D5djhiNR8O+?$`$ z{rT>-@SCyg7aT7HfVGxOV%o(*4NeGCP=bHq#rB0Yv;-xgm0Jp}$P$avi5O8t&3kp0)ma_0P$W=K-$nOn&LUo*JWt zS@4A&McY%oq&Fpiga)$t(Z^DbTCXRrHERMuHI%@YPRdoRJZUQh?-!ec*5sF(?L$k- zgAYr&ebNOr1OSL>HVdsYCRsD4H!}@OQ?YbE1E{OTL1>bRu<@5$K@bwePWi^|x*5{XYsy@J@p!`B2Ihr#=ke40UI%e#JG<6eejyeu4@1+G-n%IMK4S8I{nt7c*&vZ zsf{0*nQq{7ho`O{YmN8C!B=+`w=w-C-n(}q?`Np*jM zTJ3K9?xqF@TAmaLWoD8ZDOs;ydOj8bSfs+&TTB+@;xh#vh;4eju(C_EZ74<6Mw|YL z9@h;v!Whq_H54{68uL8>xYX#eb)2;ADW;lX$0i#{%&S=ZwHb&CYf*fK63Q)Oo)lL0 zH!i+aD87)(LRunL?;|X~#W5rDv*VaVE!ie;mP0}z+1qcO zBYi3G*-;f=B}t~K(gXCS&!QO|eyV#7X_tT3f#|p*M!o5}zj|=g z<<~{^Oj5-x`i}0NLimPUVi`?68}-vn`McsnRW%aOf9xFHFSI9hg5M=c^=r`nW&-Z=BU2I@fKtuVW=2*zeiRglN1KyRf6s!v88=G=2-1 zhJ4Mn{?n$B^y+zgB_&%uG`R@s>KuE>tsEg{U@H^q%1oTlmug&jAsmfPeLK#w}WUbiZ}>XaYnZgomq zB6xcH?xv6p4fze(@YB$r;dO7TZ!HP{7{TN$)V*UzH<9+Kt(o#2(8Y|}+aBE)unde^ z2J^MfyMD(WWGd5$EvX7H#QvLc0j>5pLJ9;#Fu`~7(co(0mx2zp(gleTXdm+;? zFk(Cq>A!!x;9ddU8*j*vimAA&U5CWp3!4sqzZ7&5hTDW3xUhc;IUBNW$J*?Lm}vD_ zjq)mU=M+~$^$7Z7r=3TVBx@SnT;=ig#0s~2h4w;*K)OVi0j2Oh&M|cF{r7_`ZhDBP zJaB|7vDQ6>s(`m|!i&W@KWV!>5?M?hz6K|U732eqy7tA10y5R_ELSIskpQcAwZaq5v*-H+oOx$a*FaB+b zlTEDv#O-2;Yd)_P) zYB%D&zji#QVcV-|^2!E&5$TgysQA*X*{X%lyp-S86NZCS5g*;1#FV;}$A2SnTBS$L z@PUmStJ;ihKfR@bu%37xp!+;JgwN&B^Q&YkPs$uRwniUHyOu{ulWG|o`1|QfPJSu) z22#(oEkeOrHLiMKPKc4>yM9DXq|h6Fl;FFrF9Kch-v-#Y>?Pr;L~lyz{L?2x?=qGG z90hpR_<=Nl@_>|T_>JCXL6WKb-WBS6oC%Q*eQ7AShdUUB&|orBnKV#7yYHbBrWm6D z`m^s7>MTjIzMFAf@)y@;q8*n+2sy;|M1Ktzg&Pc)dSXhGcmn3tg+V8gq*beeQfGUW z-S_s`Jm~9wcq!q(74N3{v`vp!Q=>%>y&Pyghk@t$C{J2fb=}MfZc&m|5^>=5v%j}rJHR0)#Hw;qr-gF z5*m)I1fRgh=ZzJ|A`pTgF#D7dz9m(Y zK&d_BF`JR(m%GBh7Ozn6^slqIQM5VV2oH~2)9eYeh#pge;KjXZq_fwk>zbwCS;`~! zZPJKnB3U3rO=n4=MY4qO&VTr8g@n~miLk_FQ@eXcSm*pr;EU>aE~z4Hvc|gXvrbC^ zH;4`bx<>X$ubQ&^n;)14FHey|11jDOtD0qex)?dvAm1t8pi>$e85IE{+-yQxF-UvH zUgF9)ubL`__LvZZ_umVdPF@W9;GaFIgZtOZPH*>oizs(Dz7Ytlipl>-_t&blQGo;N z+#XdZgafb-j%k=u%usRW9Vaq1j{C!**QPE#)g6t z_#=M4-M7=iv$1<<1k&h-qHYM&vy~N%(MBg+Il`ZcHr0svr{dk#!_g%9)s8efh_iBKCD$s))wEUAjWf zI)5EnRd2#c_>D8@Sjch!>>`fe`?3a!V2OQE`V6e8@w!IfcEflp$wX8l&4#~~H}CMz zIp+$(4UfT6yAGCa4FYpq1PaSWK2PiT%4-{*&yA`LfxDwyfnp2gn7E5OLYduPQcUF^ z@Vx5OdG(A7>xHELm8&%LLpD9ArqgQr=qI*`tdh4F2(ZF|>?M-38WSg5?pG{@|HTY6 zrWHKawV5WkU%e$8lqoR?7_6vYhs0A6Ta2fk!Ka?`87MvG2`r@5QL1#RM0PXEAnga* z`OpqpBoA#d;drj@%31RVNoizn3~>E%Y+b03tE~lnLjvs%>IIXkdKqmS_AL}x7KqJmDEEL;bFb;Z)mUElQJG8Ta5B2RuAipg=FmKIfo|bi}a_D%nPvz&+9VeW^ zF-EzXaNe|8xVK;ioYyQhaRAL`I^>zA8w`Dmn*oFr(kq?*mZH(%7}xxbrJ(qw-lNr-gdVNhvdRHrHV=`xE+eznqpLEIAo>C{sG>=wo+|mQZl+E1x5-gHDIKqq|!M+kd_~eZjg|WO}a++d-47a&-Gm2bKmE4 z&i(U5q8q^6>-9E<7=--YoY56KyuR;1^bLzL(O0uG`5<@>OT9$6sW=#-?LPR0*_;ZpSseXYh`c<#8;6bW0Tg-4+GCu zKEFC`&&N41B19`bEMhWITvSEcT+>>kiHblbRa$%Sr8dApxAN=tw*6+e&cOH2Z;I5K z$~{fk0;Y3<2IVGIto)meDg_+Wb-$%Yr5wpum8GuxluEYcUAj1|KKm@!8=~1IfLCJA z8u0Gva|7ZZ`Zn{-r@DThI;VSjMbmOotmt^YEP$|rvKO50_a#upI4`42OoJd@TNCyl zv6LDR?6`r6EO{JG+K&?$Km8YARuCx!db<_-!Ep6QpBMX+R>djAEBMK>Nu5g!Na|b` z7(aKMRgTAYF;z=jKk$SXAv;wSD4%;;HK>)S-Lgs--Bszog(9#t8;hJY#-?Svi> zpGQheh8BGkCEKG9G8RoA)d;PM$S79p0$f_whXMnP7I=$4CtUXF276|PH7*4s915QR zJRlZBTnteOv&Fwi8U1i6#%`^nq^CLSWq@U0gP~&@&h0!4ni!ty_}_LA=2sOqSMv8y z932h(BLWkGx=(*P{bv|dQt<8*#ex}oK}~HnP09P|ll!{LkuQI}s_+nhpvQDnPD-f` zNgj_${f~U;A5n&3Tfykz0=sz&@{el&Qw&Jm4}*!C6Je*|XA^>dak)frmA14MKV9{y z`U5)ctetbFXa9_^_{eg^OqBYDc*yod@JE;5hv4lEcyO>C5xr2OGcwE6CuwVnvziog zGiIPPhY)0b{0BO4ATiw=`GmOT3O~>YDCUTklNBegA1sE!>dIvr#Wds(cQlx}hUO(q=>v~dhQ`dqg= zA;f!LaWmBZ)r^L=lZ=S<99U23>^AzJERKTE8q?09>EMv~)@D{D3A75m{0?9g|U;mbHojlOO}5*>!q}v~s=M*Hr{;GoAwvJ3OLrEtuzIV)Wt^z^!*cxps z#?W6pQ9{Ut{@-F2lp+jo(6*6hv8?QM%7XU3)#d2~73SD~Tc`j6|FASltHa|~v1)mm zD%APc+l4ZBf47qxW6SGJWA_RZRQ397$91IS$e2ObV1S$_ zTj~2n|Fs4H33SC)^{Re5qzHNtr|@mpEnP18bT}@j@`1&;i1Xm8{*xRnwGT1Ej9I2e zbIfS;QVQ|8iwMw}ld@{K<)!bpK2@qY(UX4t)RB#q(pt)|#V0x1R??A!ZO$mMD`aH) z(;Qke2Cf>%mIbL`aRmi?zV_5%g#?t5Tz{!=Jn$LwDf&DB1l#OpcJRM63))`~?uruB zv`~ciQM?tUI5+y-rA)z3-+Ds|k*v>dy)~p-sryU33yxrMt$fK0c{^%GP`7_42~Xw} z5&9@O7aC9;0Dp2m64K^}R9VK@m?jk~>~%wh(Jz2r8}VtvUt204@TA)-GJof?{_>MDE(g04m zo+vl=U&EVh?6t*~nn3c~`VoQA{`?_ILVM;2dljo=!A3Jw3-E~AQx%e|&m4GrxzuhO zHh1`0{%U21PY=QH6r7P4&3KTG&CWbN3rT)-hhmzYYXeRBu zhIjhzp(zoc{(0NU@s1~C4tNlRrm1Gme$Y>Tz(81VLb@MIAtbM}J(a9Fy%blzsmz~c zEIKTdt>DVU@xpk5`#1B4{*T;UFvbm*G}++xV=aI|)oV66B&J@3&G}P1#O*2BI?0H1 z*4_7;72R?T5?}vw>m(6&JZjzX%GdFy{LbjW=SnZtuLq9pt9I6fnEMq}nz-~+j<>m&9|($X*odU}9O);l zem}`hGQRr4GSOo1TwyH8SSSK z6m()9E)y-oYEekfR>*BM#m`=g-KvnLMm?yFgV(^1)NSgGd<%L2l@%}YjXv=zM~Lo( z)W0P%8u@f2dfE;&_?&uyTyV)A|E7Hs@AAFiM2(Z6j1FS)v?f`M+>elhm;Ro6BFC!` z7?(n7j+=HbC(JIEW8qolP)vTcipq+O$d_D{ACv!oBYj)`&8^28Be4~tPA*7?woG(? zn8baT6$_)Jqkj2qkHEMbA`?dZPPpOeA|)gyAvufB^;7@PU~vp152bW?BGe^?SOodo zX(M4A^(_n>)BP8lBB3|X9P@$J@T%@W(CNZcvwcSG%UmFOR)eYB_-Qi7gaw3tcm;Oz zPdkewUo_KHid@l<036QCS$EpL$q{J8Rc#S+eQXA@15-iqS7*KQ!DsSJXt4v3<$1r? z7{r)(YHJEB^Dx0U6e`B@kz4cENRn zf)7-a7;#GUS86K)>vA+5{{HqP=xu07=Cue()ou3JVh_I4h-I^>KG9fct!nh(td?WD z>SJpIS`ug{Cz=(wgNzJ}FCJ$#n`X~=(UE775HINEP4%4B^uHx~K1tk?AFFtf^v@+T z|99h^z&4}6l`tY;ZA;p{Whmi#8k3kZdYXN&lkrlgFxYM{WJ)8yd=p!x^QPteUuL8H zd6Im(k_CW|E&8aL_Xu+j8k?QIeV4j%1LZ=zW7XQZk(@oKoG3G1sN36dL4)T> zmUm5L#daeHjaZ^uBFr-ZoeDhRgUZR`$JOc`m;wn;v`wCdM`o$aO-5(b!1o{JuB|{) ziFM#(rvT9zeRI#0bh$lgyS)&fRGhE=5w#}-7HhGqf-o3s)0@3CPf^e$L!8LSG6&@E z$HDMl9x#Ua5ZT3s*AHNfm^1ywf+^Oe`5uBYyYoFwuqg{a^?%O5D#l;2*6OOLWcDr9 z6Lqxa*562Ploa{v-sts|GPj_SHp%50iQA9X%`Lz|WO;NMFfZZu_Qx8VFOH|Ljr?21 zjKjrk3SV?w`3dJpaSXuH1F-i`RU-u$g9W47kv7zh?*}>p3`lt!Nd-&TfB{zA3U-RD z&cr0VY3J-?b0cEOfHIrz4||9Q^U$oK%{V zNzolfU%PSzD}dZjAsbTzSJ>Q_!Fb2jfk)`=rRb}^g!;TrI7 z>8Vh-cy(Y$-K-bq=v?X>RxYV9*}4&E+R%`oF>*KWrJ^PouD%|JJo`a(Mr^N8)h0FQ z#m4WDDBb$rwx=_S8REPm`j!ls3w4=N(eQUfba=6MJ#>d|%*wfOlECIo!|kzOw0;3S z>zzl4Sy4DBj00FUqc#-5m1O+M*gfQCEhIQIDyKM$j?>U+At7h;OX?%mRy0aY3|Lc1 z8SS=ZuHk^Z=qHjF#sGmNm%*V6Gq@nq%n3+71WSISEk~0 zfQu}MtN@Nk4!HXf!6ojfxP5$G)2S^i7|#OGS)DMWHV5S*` zRoE0#AMd)t`cy!4_CjAUx8x|gg$;Jy8b%7~z^n;<-6yt?^?DiV2ajG=1#w2;X2}FY z2U=C(*6q!VBVZf55HUf5n3ML4qX}L2y3y73_&07d(X2|(5Vs%!5`Zxn4gm0@v3oz4 zu6KX!-Py|gg&eNyi!fb#h4?pBKdQ_qEP{@w=EwF^v+Cz`5*_+8_!4Q2X2&4nIENBu zV0G+-AZJNu>oyP{v?fo&yM2B~_w=os!*a z@!EO-4LA4aUzs}bDO1!WGJ@E{2FlL-rJFLNP$y4ZgEH#6F*wdL|qDf9a<_1z?gVuS!AX^&6Dg`|CR?e zuvJotswiG?1_V)B^fF*orov-u=iDF3J#m`jSN7GozKIU^1);=$J{zWqDxDgzyq>cB zWA}F*oL*Z)z;SvfEfS2u039@ZA1S%0S5U#n1S%+pRGNG6uYmVLpx6{~P!&o?>e+}h zTX02crLP<E) zW(hHa`Oa2GI&j00~g^i9TY{ORH6TLW&SSm|sbLSxOGi19%~ zuJ$s%Nzy1=XbYUmH?z8#=d9fN)A%$od}Q<|lN8E!h`|e3hWq%?c<*zn;PB#Y>D1WL zr6rgOs1y04%d?#x!yQgvn@Tf&^G3Ce&Vwi*=kw;R6Y~$V!YM!!dBqoVodNn8m$B{I zdWfMOWAI_-lJ^c&-O-BheXy2AlI@nBj2J)#OP4bPG>#92{#^vYzAlx?-tcT?9M!I% z3=)t2-l`^-{by8(l#BlN!e*SE+!XQQsfty-?*~@va(x$7fzFf%)eSD5c3hkhp8r^1 zGRvqyg{KpLMI^E$!*^L9u|CRTuNCXy>v`mXtUQ|Ad`Og*jJh)(g*0&Wao1G=QRJnX z0RvW4VJEvk_g*%_M+s6SZTLA>?$DbV;={5qi4yn!W>4FJ1Y5-(s+q|t%Z0i_z5Vu& zVfk_`ebaM+_U`MI+WV&1?6vM0tSZ7B9DF4uW-Y~RG+zOqNXd_Aakih;<^DMj4C8FD z%8jsy*2Gzq@sw8HFm;ax761SOx17jV{dR4!?u$O7lx=Q)vvE9ABN5 zEe}}U;4A1r&tfV%K~*jI!QV5Y#3>j~SHaecFTJi_q4S$(f0AD6*3pCAiF)vgSmA7= z7&zaoElprMh{E8TM(`+UmSRptEmUo3)~5uwcJ2bROuW|0NjrT>M)XZh>5qo;KhWNY zie~dzQAB+(Rb17=6A`kOJa>*PTr%YFFNLgGUuwS>4`fqT33Ad;vRLfvqr5%1?wV;N z-3k7UX@&o&7tEFwEoQ~=9jDUMz#;UHaH-AF3F)A4`NQ;+cGwGovd;+x>)&BkoJWh? z;g*+kGZ_=?e?f%kCq`8Ff6&CeQ3>F3xCM#)6;%Vp6#s2^9>;V%v~lDTf&3hIgz;>4QRkFjfWC=+Mk zTd@J>R>g9A>c7M}EU$4sr^F1Ui}SJo)Ks%->Y(mr2=O~Y_kTCWU}ke#e`xoB#@)Ix zGc9hcZj$DSiHMs1tBPV%5r?qdA()05d|@_?<|M)R@wM*>#e(rnP);}>naKIra7A1q zQV-7$lk~1acI97L9jag&=9)iiD`*mPj(FSM!o|yBc5cit{6E0!`sLb+a{|l=KIOc( z?p&2ULpK6b!e588uliJu3#W4YL)=N8&V}ip?z(plZhdMkj_Kr8$}!dWtABjh+W%ssw1Uyg7?gJBl$SSOL#qF!pAuXs=iZ_dds_R>M(bI zrQ^f}_$0ikeEx4T?w9y!Y9*U(+3{Ro#?X$o--p6il7mRo~@mD}$Vwn%dSQ&y!e#~T@WHJ*r{VgF37GC-!nQh27*}^>N z(|s$k=N+S;g_*I-5F6^OL5rE=J z53_q=A~z%wut7vqN%B}SB3)&2*#m?)bH!TL4>@)}9<$nC-Mt;Yg_2JFcHa39=1k~?iU&p4cW zVD#*S+nJJOO5R&ynF_g6BL0K1eN2@=iJG_Kc)1l^PI!QE_xE(^4*>V~3g&{QV`HBj z^V@1`eqXDf#`MbaQhYLisrJ91D240UIOY)xSne>Bi)Zx}3o-_9j;^jF26iGzWoZ4y zX_qb+Pn**o!Ezv(kH-&FmJn<%Gg+O*h>qG1)h|X65m110$h6G z^)pxhEkAOx5NJ*kuJpld#hAwf<{zq0r!eBb_XLt!N^9QRS^3Cv)&+_?n)*tRxG3lv zt94;Eg)P1&zYHiDlzS?qJ7oXwWpt{pyX@p(%{E zec#F{b`s#wO5Eg>KscmCwBJ5y4WZyutzK@UCjxVhZB0BVH@DQxb=sItaG@_LXT;Oj z7-vX>nb>RBZBj_a;_D&Pn*pW-uBUfqlLR?fbD8f0X8yL+p7Xejz@4!WIqtkDViME1 z6fA4&F5;pSB5|}E;`5JU!7}(9XGZSS!yBx-=f7i9WDS){=J}%GKbZ@Eg}!*oYT8q! z_}WvO)o;ta@R8@p%wjW8Bt>lsU{lQtsv8CAGDiOXwxE+0rS>&uZa0wu9|#70%~(r2 zshyJa&sgA@!KXP6-Q)FzT@E_65t5{Q4vhLmR?Z3fHYNSH*N$V(^!)weK`Y{{{_3}B z9)AvNXm`d_{+a_>NG$jRRKxQ9}N{KzIVMwHo6IFXg79_0SZ zNmXZ-Hu{TW<)$gMi#@J%e9BoLWxa#YY`%KwIq5W@CgBXvBy8^Cq{_#A--`SZEoeU2 zrN4SP=KGOe3(zTWLM`F()jWskvWeTggo^Zy{Bh#1F?{_t1@1v>`9Ebne-)R#SK3x7 z0zCp&6<)=E+>7e+f7$0@fBV#660<7j~+)mT0!aPczmzQW+(V&iEvg44cD84aJojuHptj4MkETFHdvLp8Y5ay zeI2WWAv?0V7WPUnV{n;A39~HXBkQg+d5RNeSEm{$Vkz7Rcd*ihb0JJdkxN@xqn9(- zNco#yc1p|N854a6#!$s-&YH^4srSJ&ZA{|c>}5iD8Ru`^Oj!s;-1lZdfazG#$H0FB z6NjMXaH^L-hPv;%FU&wKYAMcPvk)P0rpLfHXaGA#?YQ>J)76lBm_d0Xlc?-NEn-w@J{~ zfxEwLuQ*=1MJ^u~zusR=n=m#4i!8@vx*1L5LJlQEyfQ!LNbc%$jisl;^!-Ej!`b8n z%L*`sjJX$i#i0IEzEQ9CJ9gh9E6B2#kI!ItaD)-r);~T{gyvj@x;{=r?-a1@1Pi;8 z&q{D9>XbuVcBa9WcY?Thl?%t+SCL^~bm>_Bt>Rvbr)ppwYi#W?7_wc!2kWC8(G91F z+QVOr@y*(LCh99A+bx=T{t`BJXok;!9VbC8sfHavk;B!SE_O@N?1!#6mUv7FX3>Ov zeJ9ZVokMM>tnLul{?j+9T1CQ;3eVpRgwhIwOog_KbM6BU37#7$*kVu}HGfh$NpSf$ zumXJSa}VwID#t*F{W8wwQ5s=YP#h6p1^Z@DNjJIwj?ijei{i>(XWOIr49T5(rpXB` zdaQqR`1ST`!v_KcME%;!s~s~K5)M9yX|yoWBv?Z1wK_sf$T){fq}?7Srf9MX&I219VYpsUPT8jWpo;A7?Ji1 zL`!ibCKVr-43u8tnr2A0(<^tbM`&EP{D;Z&Rpp`{XUB9Bh|mOmqPv6%2OJAVmK%Ic zt3#YwZn+F~T<*1pT*kDY#moziW^OvT7trf*P0VIrBavk*@i*)7(VCFW->N~_uF_c_Gb=1DfbmBv9F%Z$43!8ozx%zy*D#0onL6Sy_geKG2LRv zE?Y$--8telIqB>@{#w&gwr9sO-~|$g81sBJCtUF@@btsBI&tU`G^#um&$F{;X!LYU z3V%Kl60Ai;f1USvD7t&oTEIUXL)jix7BETuP*g9&FjHT};9>Go#nCgP@|h*)j5dDy`|ro-L4)_Jr9`iKlg%g3cxQO9}M*N z%%#zAh%}?&)vqbf5olrG9yvIhzhcz(3?7-PxX3mJFbxue^=x0fnOZv~?O(svSW${DpG@4hpTD?a2bHrCY&u?5C8K3PSG;-hI@$r~2MVb`M-L4T1lwC*iWp z`hgx#?Xl~_G#>q)>i8;-AB^1QCS>~bgE$sktLs#ks=8U0erXASowj$4w;+*7pSws| z<{Hq~jJ!PRiSGNf`~uZ@AGr?-mlmSL9AFTY@U6kqgZTG3qckiEz5=IxPN`G|ZCELT zBdsc}A$+f2_DJ=2l{M==%)^F!RUI!D@!56}>4I~<`fg96)ZyxjKDDJ1I`%PVwNWOE zzv({V@7M!?H7#+=P;*G|K;Uqf!Y~9r?eve`It6-@V@@wZdE(ji($5nM6*_P(_r^9E z;mQH*ztg$|$^?5K68EOxx5?N9)L~%R{gHw%=SfXOvkG1yZp)1D(fdhXudsKaNP0m6 zO%-GKdj0tCn5AhSm~6hlUMhyj>iI z#5{&OoH002^$1XVT`hXDkw*6hc$~kAe)wXWMTiuge1^+ zlk_|Fw&0M+Q(G<$Abiq{M#7r~s`1KfAgKB*_F20dCvm*Pcqqk(l|TpLf+w8Q2FMDY0?lUq^3pP? z2Yvyb=Huvoao!WLNisRduwoGR2|%8IRM<3Jhoc0wGSJkfb3U_YXRGn9&`Zld zUPRM(1dR7NH;VBt!oj);U(LvE^v=m^tzR!Q$~MgKZ&VX-&d*C8G3`;>G4?I zQHS=TUjY_WI~g^Nw)$yi4W?PHqKsPxIbEv9@E&%SRZ}-l#XHN+59}kc(wwyy4`wml zzdCe>fV`^V?R`d>dJZVi`9dY{nlydI{`h!TVC#MR0;(bzRtj$oO;$Sr-3TZ5$zPcz z*d=GB163f<*q*yuZVl?ChIU4uIJy4BfPdG8zoc)9^u~GutO|43Tc0O&06$+*-7HhN z3H>-7nm=E(u4+A*Q-)0U_;Ac$GB2I=xI*`Dm!9IYks<-=nxWn*j(>y1 zgP!txQL%bEZU9-Mrd}zsYqY$3H9Y=w%2BXkUxRO|Mq)nsk2G-1xaFyxx0V1Ed+5X?cHgmRP)Q>5X6j0Z;O|{QuSjUtxr;@KGquK>fFD4 z&ZBPA{3_DD*3-oui#*rBB@H6C^7x!!5oS38=jksrQ^(V-AZcaB(M?5_Bd6O|GNbfo z@|8Gc_RCs3FFSJfs(`HSF$o=`3(>&ZSTv_^99q_F+#Om`(RiKft7fjW?kL|v+Vx>= zgynu)K>Y1Y?(AMFD=vUtj7}j%MRLDU*)~_a#ghw|669O{Tv?%O2P$W+H@tbJ-{Ijl z`|dC&kI|!^a8(ejaG`~uUD3xi5dc4#9mz19vDcO>GWX)RNJn@H?|v3{(Sxa~;N$7& zIa0xBSRaAVpTvR2NQHdelSRmDxAbo+4toCO_JS$=1#V6`2;X3);)>eT<-8q4Zr|fv zK=0SxmZFU+BDB6{5>T(mq7sq1Rvt%YTVq=j8|ea{v5C*= z2x1`B^JN5(GMbR7j+8=BbTSl#1Dv&RnS|c*=8Fy85E=1@Ti2&c?!H%?$2ycZr|q}b zBwf6sN>L|^7jrXhCxbO?w`aXn5JJ?QLrvv&$J|!X)h;AIS=!sWTVVS2u>*q8mWf0~ znwJjO2W+<<8h?^=5O%=^m3%PW=_l@0|Bu-HKZgp_%RoyS8bwUT2Oky8OSYd6twjnZ zeq2vfY(AYbwrqWRA6RwMCx6a6k#;c8L zJC^!}fiM1tcz1PCnL4r3>!$6yOE&WI0pG-E=R~2EDGFF&ib#~U(|L$)Jml^XWHsQg z^_N8{u=CfZ&5UI(b1A&lYjbbE_7yG3OEFW)oGNsMmg=*<9xiY0^l~0kA_D%g!+!5e zF(Ua9KYl*^zU^?oofy(HCTja^k5ef&M?Ig13fLJ(5Z~rxDuUfm-3d4knSXw~O!@MJ z;2)qfP*`YI#VC8gne+aA784PZW_w)2$g>fRhJ>}HIL!CdtK~M|4VYE?$9Io_*By!3 zqh=L}K%WAU%v)QAXWJ2VlS*~f=D5*=F;Z_xwDtIi| z2yB9VdCU4DV&nspO|v%z<1V}d5pL5k_7ZUmidm0b=9NEJKVXWEE#c){W82cgWGd6mYaHxC)q?4-cf=X@VmhZA$r#XWOVWXA zSO@tuzum5;yuZY*S_y%tDw85BA4!*5va8v`FSG$B_Z~|ss#szkVLd9IGjDN*!?9z= zL`e3?evB4PO#buTS%%o@V}ZPddPl@XN#mbJ+5^FSNa|-MAm}ZZpVY*SF^aSt<&KMi zKyP3Q*T*yN1?-0tSb=d1@k^Dl>jKQ! z9f>r8qq|>!%Ix0av3_HWPJT;7wyb@$l7aMC)`w+b{-Vq*;Ph>2sf2G^et|a3=IYb7 z896i;3)jYeyj>d0>B}tq({^t1E~GiN8<@>*`If7lZ7R6dg>$Us2OSqA*)d5oPDDTw zluf}rE#o!JKGOwz8JW%ls@2{4B1+8EAFfuuUKTy_sKUG;LOIGI_Grd5D1&%++zhOj z1Dl*)(kSK!Nh+8D-EC#W*T^P=*}GdC>78)Mzgq6>g09PzPzYdyE@~l>z4mhw9fTSp zVOaGCzNo=V1BM`^Ji220RW@b zcp_-w@Zkv8+KQ`CC!evua0eCO{55Cnr_AGT{~P#Q6qeTDIv6(dZQS=i5%6{%@AYbd zgvaOM3~ovDpLJo~i67hm)N}927CTSb1BI4{-VzC4^lxHdyu>O4{a};{y$JD;;XQ(~ zh}1RniX5?gse-_9Yp0zjiRFooDUVJ`QU6UuzPtroTB`r$eCWBa8P}{r1n8Tnm8TZk zSRFlSPmG9E@q|)ybYW>kOJg!{E=*0T@Wh5w12U0X4bGV2Y};UTNq}Z>Z4SS%sXSyi znSIL?^j=%KxWX())midfZccPUWv?tuLb3AW_e>zyR6}O`XB7brk(hYs97BZ=Bjk13 zQIk_tu~BStg%&fA91L(SBKt$92dtL(*R}dmDo>+>HDJHw+{cKi;68yfeKU7*`%?{p zzln*{>?xkE4u4c$qSrxJYixVL5MzIYrN_sOB2!Mz^m|c0M<5N=e7Kx*?WmHJ*@cze z*OQzFk((9MTcYgQOgH@IdqsUDT^O&vt$_R)^pys#!+_kKnDkWjs3$$YN{m2VDW*C~ zP&Roq-x4k}#|lM>I7KF#aauZ2N8zIt5N=HiFGS@(xKJ_bf9C$O7;IFzb`|8CBXHO0 zfjGtNa33D@EHEaFjKPT0Ri+Oowa)yL>`gH)yu#T#mTch$kLlf?xD;5Umg~a$u%>Ex zCg(l7+)6f7)iVkeuXL5P!(VVTpBhrwef&9I*HQdK_2|el-cL?LI8#N$B>5$R9n)On4^jVpDeR1>68ATZSufO4v4Fu? z#3N8?l;fLFD(NqV#Bs6em*b*+p&#m22C-&h&xvM+-_#m+tv6D=Oj{Bn8w1x!lp!c4 zKlLVx6f$xRD)n6o+A^B!tea<2Fwjq$?tusCKT)x(^ZN&LC$Qj)JDB!O<3-oeq)pJ{ zj!Q#q(>rry&9u{RN88%*{H00x4Y~XX&N}2(#w@@DJs6YvRef!NP-r4Q=#z%#VLnO` zfQCREXCS#y;yz5yBRrg^Ni{)}RW!}G-+pZe>Z2Z!`sUk=X0h$g`)_?ETB@AOu)bOp zJ6^y>0#@fN;qN1_FrO$04!$}o86unik9poKjehvYh=ww&eBFpt?Nv@Y?ZHP4B5Zn4 zCTK&sLa3?rp==|3HI5jAPFLfsCZ&&}+vv78e$6~W=-Mwi;1<=UL=wk`o8_9`PUtht z9U>h#teeZHd)e;jsZebyLbz*=MK01L%ACl&%(dF>ZQx-POlefcR^ooR& z^Ecev(CBE+VU&1Rd_R)(96@VzO89&9?mmK-4YTEJZr)VYCPxvBw-|eU)ovRO8Slq~ z5TtE@ww=gz$+(^PDnkC-+IZ`b4Ni5z?LKj){Z`TvBKo|Ood}Bpmn?E4F-kIt>0M_n z&j`r!aFIlU+H5-XEviNJ>x#>MEU~)VvaI|}j6R{fuH`1bj+XiT#lde^yC@H)bUN{M zU}36c5`*?k3~Rv>x;%l{kKroEODeO430Y2>t_Dd?wFGtMqUeempH8dj9zXkfI3E3s zEvso^_s%Br+JNtIOfz-TbA0EToz9qXxVqW94PI|vtg%Znogqe=n@C{7$fRnmpZgy2 zIR!t}EhFL1)T#qH9Ug606{we^9EXPyNyckRjvr}f8@~o$Y)shH^*-ni;W|5 ztCe^c4}n0{D@ip_ii~5gRFe=D=e9zPTYp|@Aa;!ip3^k(s#i`IRTlvK39aEDI%Op0 z6=%Ot)qb@M*x>g1@R*DK7OD1VsKJdp6m3(GpCC8uUPGq(8zt_jvXeG|oW4H{xmcej@rTd#6rxmbC`E0&m9NT9@lHJnii*k`PaY=Nw#K? z-TSpJjhxpo*ZjDzTlE0@*2h~Gx%KK*lrtA%JoZJ}FPYNsvy57s2!%=3J6&}?Cy3Ge zne}c}CU;mFOSh*59y10wpx8xa55Nf~A{UWXC}J2S2U77O1zh}=m{wC!6JOiB`Yw4J zVLQh1yh8*6?j6<~5C|_~rbc~q5NxTv(jcOT_F_nxWmMe1mHl@IPuU04`qObRE(UB> ze5TlR&ULk8>)RTVTzahz?E3$N5$EWLp49es=TRT0ww_M3qa6^18|V!oiEkVVxWLewMf?r#l3 z(Qzl%+McN4NzZ32Wb+5>;VJep9t)QPCABYL_R5vj$)hmS=MP)QjF$=4l}}Dp*@BMt zEhk=#x*laIlL-U#-T5V@pZZ9>?ApkX=O30Y@g2c*=L%$rKFNagP8Grb9L~FW_ zbPrseCU=d>QsHsnQYCMZ+)lxdW4M4?T#icZqMIs+x@G5n&!6R2u(WwcJV%s zE5wM>hIYOMTKGn}%29MAv%C3OaZprCsmH??|D0F3^Es1lZ=LECoNI&9o!7ok8)DZ>)hoOYIwc{E><)0EZMtzb= zg4EJFRhf0H08&xV-;n9!u%ZGZsRF12zLRf`QN#L7$noS}v`u%$azSU`huG#ficb_6 z0}uo(E6*nxY_D=Mwv2ot(0KK(WXm!rF>KAhSwwqW)0nebW7wNYOi7tW%#>ZE*uLpE zVz2ddp+?`9yXA8C=g89uOupdNx~jZ@MZuIMGSFc}>>=kIg1-E^N-mq#W7KGBhFRKy zqw1^`kL+XlQW$1F?CRw%hs;m?;>11F;tku|8`N?<-{v-y%ii-j?V9)J~}FvYn1V~4U^}6 z^zM9YSRH7d8HHtgXxT;s>{bDx`O*MfB+w_V2R+OqPvdvrLvewZJB?GTA{qjOM!}{i zby%>cBby?P0t^9-Vs)BfyILk0dFuYB`cL@O;#k`KQLo_BpG$XhH#_#m_|4wr`k(b5 z%^q$YsleF{|4d`Cx9Qu5pSh(3^TWRG)c^u^H&6%kmbH!UQ>n6LRHq3aQ6g23QzSBv zVmu$0C7_t9Ll$F25?T4r5BNKqs=`OCUbkS;{@o+J+h*qwmID+6ks@r|4 zr8aE>w%GIAln2%YtPJcNUp&EX$txoXAmN)c~O0p9u|HQp}tVl3+wiQqe+yfmG#n8oT-NlaPZaji8mgd+6`3Za3twzf-AD1c@kc{c68%yglIvq6AXi ztjJ$|rdqn~ls_YBWTkF`5G}M{7~gK5EZxk9Aa>;dVt3KHiM78YpRSuC{qin_sKdfB z#W@b*{qdVv#M0&Bj^*uE$n~36>YJhVb4f>i%j6m1kn@4>=Y6deq>yL&*LpeLJFKND^23weq0^WP>Uut^JH*p8r<%<6vP4Z_NG4SbTRtDZkQ$LY zRYaDfCXwQsgP;nh%@yjZxd7P}p2A_O>TiJ?lqB|cstTNjEr; zo>_@Xa)`yTAoCzGi>Axf@RAiKD#7To^5lXQNO`I{z?>ah|9rsrKhfi7L6gtN<(aJ~ z0(x=h#Y;0Z=5#{JJ55Gb$5g1*g2hsbuk<&xYM=`TP!;t~6vb>kF2nGAiIU*=^>y>G zb65lo#|K#CX8FnV<7m1UV!!ktVsjdwG{^(&Ujz)t6FthB4cDS_>aWYrV?f(lGBYzK zF#nkFlyucCK^_8`)L%u%{z+;&y}x}bLLkINOVV)B;ly}uBs$bq$sMiI*CgpLDRKcy z?0p#209W z`rW+8=dgmODHvd?s8f?c*)Wd)5eZAb@3mb_RlU4!OQW=)MIU`y-q??19cCbunC?-- zM!r(<%`Qvm4~VM&td|&}hZu#jJaDyr)Vq#L%NUswX>$EjAY`Ak(|2nY zMtOx8icX?YTm`qQSk#{t%emv5ECV)*#Fm(EH`3Pb&*noAn(!lmC^FUteDqqrv;Nt@JO z*5`Ux&pbXkuXsQOSI9^t{phApNEeSiByD9Ctf>=Y3Fu<|F+%2TQe9ne+E%(josrKr zl?PPdGTJyUD9~rRSC_vaQpreBN_aE<$d$UwrvT0?I|K+{nW`ZxN9zABoH`C86?EJ; zOOR=X__}62Ngzuw7HybVZWxS2uQdAmhCCMM`l1pz_3xFJyTpNbskR1=<6W2jukFTf z_Cyj6BeY~z`)vsSln?xHNUGKn@DH37f5FaUrTHI6JXI?!})D6F8T&ej5{ zLRa?jn_Cv)?|oD*KL)T>s!61U4X$L!SFtDNi!V?Y)UI*v_1NuKspl#$Uwg{ImR_en zCqB=3SJ}=$?n%8~fCQkH%ycc;e!o6?S&aJj|S##EWt>A;pjj>aoj$!o!zxZlsF-DBP*_JZ>@*EsRR zO;_J~q7(7sBN2lfQR4sE{cBuQ)U&9YG?}Id`}pJ=?=;H%#IrSQ^h?+cNZXMso@1_YKop;tO-jZ{|WS z)WG~8Zc!wuJpZhmRg{WMmMK4QRR~Hqc;EgERBsUcp!n96%3%=hBjo$uji8JOmH_); zy~kxVwEfvoqUoshwv}K{Z6)Uw0jzamQqenCh;M+Hn3z~&UuX$0G&}3%Y>G*^z9ea7 zo33_Fb+N>o`Wf#U@I;l*QtUw$Z%nZ{uI6b0IfiZ*S??|6)7Xx{fmZgZewHuXJxLTngVBSQ$)nD; zhi?`|YK$1TrW+LYKq9{2q;z71@w)$f3C`G`=FqV4;dj$0`qs z;7OAnEr{cK@r||0m^TAkX<50$+8qJKQP#;oYmKkM6O&l^_``M{U4xNB((f4XRrW+X z*r0c!w?YmP1T0!JJN=b|<%OCAu&+E@h2hlHgNFN!qlRcZan1XPu!Zb*xt7mQ=w@ef zTC2F^^71e5%Tyg(RCJn_)CG|*W;pKS%UYo$gL)8oTG`+D;~!;4|?Rxu37*GVI@JK3l@ zN&WQRHUWs#+cAKf%ZUGf069R$zoPd{?Z;E@Z~b1D?Nmy>Y!X;Xu=x^Usb;j3T$>hT-@bGuANfHeN^|NXzFts;NR z{95m)$u{fVblN58atR@UJTV^0SWegY zW@^0qt@`OORNXO>pgv%tCCb-{L(YyL3$Pz-oQ%Fovc9?UTEz-1Me5 zJ<7GQlyG2RAOh)q6`5fk@_PU1)$^)m03jJYhEW|Lr{qle&2N75!Nrt6$HjCh}&U11cfL#FtzQl~0(qvMk%%>1{r(pNX@&{Q((yF9gaWa+!x+JKqNqNTT`|H2{Ym>ynJy=S3 z#T8c^|JM?~xjfg7iCJdeRGyw8SF1Z=F6ggc~ z>gyPvIYw)*ET)x0PDj(WK?y-tO4KZcT3t{sHPaqek$a=p$nu%n>ud{hmn%NFYhXzn zWZK#oi_k|TX(hpUR{CC&?Ifx!FkiT~w#}#7QL3%w+F#PgbxxzV1{R66H{*E=pgSSg z;9AQEwII}3vTa3Y73B53l31nXmLfPTg}bINX%DSE^hXXV`rYL3$h+3GkDQ>7Tsx2l z2XO5+59I+%39q^4n!~`rz<>piSM+}8?DYj zZ^6?^Vofo)2d06suK+LhRZd8)rOJGV8GEFcHd#6u zE0;*&!<7jodQ(f}JoH;mU`_>fMh_{SS2`s`j(gAF0_Nz$(&+=c1^(4v{nc@T6mh9? zAY-soHa_?*oq4?aVeBjol3&ap((~E?J+wR`GlyK=TjXh^ZC##9T(a~%dSYot zaA1D0GtqdqI>we}ph~aNo>%(+oS>ka8XPo|=g91dHB+(F?8=-#n}%$$W-TOIlYO}v z3W+7#-5x=gYY&(iyZ!BNfB4+zK6e-x7#JWhTm7Bi`JI>O2U1raa`|*XLS<|EjKFvR3+fhg77GW8P9i26V64SykFA`gh8UFNe!@;?{%pLwf)PR*s2YOH#^RBVa9A=U|;~`)opKk+jC0?tua9#AJ`vgV4_WIWg=bbF!FmX5=-V|N;;fa zr(MVi_S}1=u9-@(MV=8k-wG*Wo#p2tnm=heu1Q*5d+oKyrGeL7cioxCRnESm=M#4N!-VOLZgiuw<*`$VQ_uTK>a?2Q z!SlW6;(e@u@Hy!IA90T0Jt-L#UW=6T)>sQ9vBvI%^Me5ty`_Ve0Mr80V^Y_E)uB?? z<_4KHJh5t*6KYmm=Q%oSH1~|h-07#D%cZh_SGS%!FA2$`R{1FD&nQ`ksih%U(fJg+bVJM3r|x+9o}%<|wyF>?;dgCTNjg z0GATh*q&NGMB17K-gmio!do__1yv6iB-Z>OQ_M!KJBIeYlE)**)<$ic*7q$AsZYa|v5 zd+vsDszAB2FzVGnA{@4FHeB~=&ISdR8>>C(UZ*hxT9KP+_zRe}B^zR{~ z_YHbpr92pVM9%9-dP9}AVcGUA&x({M*3v-zMPp^9JhD>fm5gUa`)sLp?|ENES0Iq22T^6E0}>CDxma%43Q`8;u3NOG>z@vlwQY0_xqr?NTCQq!-(!qMmxM;Y=>pIOTZ>h9v z&JC0!8nitJ$Uwxvfk(y{zxc)BjWsZ^Ltq^J)^GjRBXMPU;pUd<4D1sa*SAPs0Ul{$ z=`)s|BkwJ3=hid5b4!6PWQd!O{=9tny;VzmS7RmZ-v2DXwxs#mh3 zWERS5`)hk*LDY9`;t)D&iHIxGeB1AcDFiPDE-Jfxz*7Rg!8-pF_d0&;1O^|tBdJO2^n!u7s$*bfNLS7^j zN?p?%iFJIr5ff`NwD(nR=fP;2)-fr#*KSWGURFSA;8?1Ua5*8jU$x-n(>kv6-7E1p z7f_yZ>8uA`hEu%r#_WDOki2STbm%%Dk%e7nFvx%DOJ6!%xNzYxFfhI_= z@zJXi-x4YLe5zyODT3tH8nH&FBG)!OqDH5|iMq%$wlZNYK>~*!mwKmlsSDS>ORB6R z^%S`-Ww)es$WvK9D9cXXyAY%dqZScwg}zyc=ZS_19l-UW2j&iPdta z?v(S3zOET{)&uDvLATIBVod`Dx)kaXH3ZgHP|~I?(rOJtPVSnQ3qn3+DdDLg>Xlbg zmV=C12AmlyMQMM%+0AZty#AZN`J0bp4z^H+Vnoj@9LtfQsq@kJf<1s^MNJ#u(tGB> zr3ktlqVLF=RPWpxW3GIcTi^QDhZ10W@vnXDYlmq1bAZMMKHRE&N?uAPEC#j-dgsjP zWiThA#0O!GeN)@_)?_*jcYqU^+5^R!piUi^=Sw`XrjUUp^|)snj==kaaDi?n>on(? z#&5<^rGr3^?V3U6HEK670=SeAWoLn2SZjEvhTkZs)c5F#MFxE=C#(ZK7(DMQVD3g+ zL;kcRjH2z@I-er7=7bFFPC;8sRsk*h&Xx!;<~3K3E$Y-uZx}~)h{U}r^@584eeR|= zz3CzMOg+m4C4dtI7U=K=3#f#Hc$y(~%^@l8DZ}TGw0h40VNB zOF3pTFe>lyp2=m)XcJyrSW|}9v_bR(-s10MPjGK(~3(2x8Mka{NX(<{Y-91RSIrg zVG+52+?8?{K+9#Oaasi-xYr91(#AxSI=Dq&PYv^>=5%H!6#r~;=A zbuGud`v8(q+`61Wa&umcoI#}b+)^6N?!v<%5zYh9C*<2sGhJ$r}V!H{;5lv|dJkCtVW*s|=2 z9CGB<9z3vECX8p5@*48)mrDb;#u-p|(sey`2X259XV#<|z@>yBx|YI`*TIiyC&*o! zQkvJq@Wd(u%LpBq9m3mraH;b2NUXV(X^p7SXI*OwW$AGz3FfHdynJXz)Nc*o?qsU(&@Zo!%uli2FSGV_f(0D%H~r)1YaNm^+; zX-h!e!VAjM8(NU?xSs*tz0d~GTewnS2^{-jjS!3o(BX--UC{6VkUkGK<$SPdP=iME0bv zjii%0Z^_1#5rc1QhLi0=dS0z1A9VYkIxc$G$!CEs`RUwm(G?F9As`z^k_@ebuUyz4R{$ZQG9H(Tgtmq_t?z$=VPik!KnZVKf1Sa=%5OxpR zgOFZUdm*hPJg;q#t1TyVxg3!j6lrk9PiljdDbRIxxp#8vOj&7KOM#7kkXSxw5O8+f z5)^BcT`%<&ZQEA=&}7_FM6dM3qTwi?&;O;^dmqx?DB7zLlEfrxa=qQyqxN}P~TK3_TqMLelYCNB!Jm;QA#Zr4^<;W~9-(YMK zi_D7Vp(T)}wc&}b8~NLF|Cc+Um3m&xjoLiq?(@#Kdf$??qcVPA`(Uu*E$B4tBXbj3 zT+Y6S7)eWj;}6SCZp>ookP?w=G@|t%u~T}1ECY%8R-5y9ikvMMQ2# zuN~MYNM3Eh$W2X>%z@mb$bbz=n&=%2r7TP7jIDIalw9kf&0C}uy^2amE4g{hso3|H z_Z2`puQj-AHnl4ubQ*ZF&W$DnmhOy};sNwXVsUnJ;08$VD``N<^J~SJN&R07+Vi30 zK6$+rxOpys#FERczQW}jGG>^JyEQj*9$3f+lst>PlFGP7PDWhZx%`OA$cq7adeQOl zx;SL<$pHNjOJcS}UX{rDR^!6OF~M04DNi__;aiSn*2Je?ogvQwUR`L}l^QFTbV!gB zZFp}IAdz@hG7Xj?y{z^~JV(F@Fbg`w#2f(WZ!KSBTLZB+x6b7fSTzH9ZsxH^g-M*LnukfDO7b zui0iVI$j$ZwRxnn<^^@faY^#*x&P9u3giwIr^qgbyheMT&NY^KUg)eFjTo!@0T&(btEDD&DL*|O4D~(tQoGji{on!Qi` zzc`i@7DLWt_Mq&~*w7n0`(5#i?X#x^hRO_<+TrjV#i>RWj?}e1DqdVJ zw>C+$7RYi#*jR=D1DR+s~z%jIiE3dqAmbxsK;I&>R);XXz z5)1h`MHfW~46@|j4Dt{rG3Ws%b)C07Vre2vl31gzF9o-f)(WLXCRk;co8=$IQye|U zJ*cU_(mn>o1T$The71tRN3bVj#M<>KN@hVB`6C#M6Z%IaKBc^$ z<1Hs72Wb_9wR15*kF_Pi9bB)!{(7_C(KbM0&9RiQh`^G}am$Vh^rASNQcNt#=%W!r z08vot>$bYQGD;?`1&_qKYz1#DO=1n4hn^WN-8E7x9$Pasdq9n+%3R1z&P47nC7U8a z-AjzKz4mjxEJH5MNRe3#tjjU6bS9WyR{9u8GSBm>l)UmLK2rHwTGq7I6HB}w2}xX7 z$8*O9_5+dvTkyPE^4^+f4HBykCF2OcX?w}Z7;lN8H>sL>PQ-&tUdwTkq!k?>a<+;l zt>p5+fjFp3Xi&bb(J#4_(8?FU$<@|8!X!x^Q6h3)SP`~%X)r+S-bpN$JA;QyWnUsE z+NZD~#Ns&&28ya$yOZ@Xy*bsvFF zZ-88u!5EKR+K{SGNoJ7@Bbk+xZQd-TMLN~anC6}@jm)*>$(rMvHmW@NJY??vf&RPZ zrXRI!+#+AsmhB9waLUm2IYov<>eQN)kt>EQ2a{ZzD~Yp(=W+89Yy9*kRX7=hzBiTz zP6s{RG?t8grGff{7nZkdluHTWh1HUU27>FL~kV4-VFg7Yw@=tMAI=wLp6GCh~&1lf)W^h7C^KXs@i? zvS7|a16JG)eCN`T&u$6buB=H$z>*_#$(Fh0Rx14zxiv_u(?KufRj$oN$*NxTFd1O{ z)R41dQ^#78k}~e2T>dWW#T$>br#8nf?i@&`1}pzM9p+^$4V)L;(NUw9xUlfDL;fs} za{#fsT6&5#w+JGhSgCt~o|Fq3t9vA|s7SLzSl(Ad2(?3`eS7^!8X^2WcR%4^)=SKx zwLt=l@an3zUMz1cudYvt(4tbbm3Q`tgq9$=Od~><3rU&Lck|%#1}@E@A&_fpC|@gH zR*t}$gS?8MrQuY9l78EwkIS*rB9;e*#K6sF^s0bf^gQGNO9`*L?mBa#pGyg^xZ;W?`Mq2} zoR~7W=ai6~;O@;(*(-^q*Hc@uul7!0dCKmZ@cPFZc_fLo#`3M+5LHn0b)LcG8CW{4 z=(T%<9GusD=g640hB6Q0#fwP+f`yY5L#fQeTAJbQVkn7aNql*;)&$9`rR$@I@omjK z46^F<(8IDC3zh*Yu_aRI6iBR`7gbNPMG{DyOkubIiQ)q0!sNGJe%Be90})z`6xF#*&rDO|%7i!rf= zN8aJwGQyM>R&L2kNxhw-0k#(T(!zsoDUjgvg1So*YakB2G(+!V==EoBc`?bcwP#A# zk|QPWT&nw(=#iy6#|~^0=xgu<=uuy>bb>(w^oyn&T7n4;L1cw6;MVj(|!Fa{`?qUu^LEUv*!G9c=gv>x0^e%?cC59Tk zw3k+T-IQn7Ox~2HF>snd`+xzp6?wM@GN7mNa0)EhqL1ZtvL4HV%jBUakXZ0`jN|o# zwCV>Q8N_<(5s<+oOEqu|Bo>wuPQm3R9kIrk;{7!wmKWb+O-OH)Eko{Nb?ULNthQ$z zZ;eRbu<|4SYomHj&=@{t5({O30Ykd-TJ-m&X8awme4y zM3lW&iY_Nrs3>TK0q5bN)#FUvmLQiHa`sxzW~V^e$(;-}IlF|OlNu|Q8uL7PXrW|s zCzb!+bjX4EfW8IKtDaX%SnXDy-x8#)wsn-s8~xk*-xKJu&G?xZzp&Jca+&e0M%aPA zV0m8wJ?nIgKj2{jsG*JnWeiJO5#h(QHvDaBT6PjQ@US7kF8kewPx3@q8MQl4?C>wBy-Dg##gj071UCI(gNL5#kYBOOnMkAcUQSVD>h(Q?i2Td|+tf5=a3FQCU zYp*?yFBn_K($79Y?<-4YY-y7UAeUdX#Tp%_SqaQ3n0uf7t|773TB0U*P_w+RhI{>a zL4~7in-U41-mChD!9h_0>q3s|KTc356v6VDPVl73AoDwV| z8g&5@3rbw7UaYhrS3zRYGixa_YbhP8W}GWMr_alG8~V<6fjVSB>aF0i!X<250{hh# z^p+BNu@|s@E?l^9MqFWRIW=8#EAYIpdfS~lg49w%+K^tL`V_hwy;Cf>_2~t@FU_DL zEtd`s@2fnt7a*~OSJsq4cF8^>ci1`=v?^B}Pib$neG$+QS<9Hz{Y3X|xg5kBfO`Y- z#2sp^a%Eu9p}4j~ZcIQupq-PktVJt+vA&eaWh!Dh$8?vuIpiW3GYC!I7ag(*2yr#E#3A&tq$|+2i z$4L*Ja4r(7)w|_lUqxqzPZ5z>ia7?rNMDF9p_m&GKBqupu`Q4oD3w1JAu7{O{of-% ztgq<_VJY4{PLh;@I}>^&mN&yUP!7*1wfZ{s7Ss(42z*NVfSj?ULDE|9Sj$7a6_J&j z2-Vl@p}(IJ=+(HT`r0dTC9$PGr1QFG8Gx|`;{^kP<3BuNX!DJUtiAyIoJ6Ap^@gni z6L%i@hBjCl(7kK_>69?(Rq#NOZ0+JdMYym`&}is&Wf53Zo`)c_q1)KfZLah=T1g)y zR$HL|)RHc8+vzCwYFKgm<{lvXv-G->=e_%S1r;7oR-H{o5M}%l$oGd7JRPahX zvq)yO+{w^-{u1L|R3=6|pd)#`OnLNsUX}y>fI)$Kt|yDE(q6oKY-d~X!ty-dBNNqI z1Ky3h-BQkR(qy1dfV{GtOt$KMML^d{$!_o`-mZ&gdWQ`lH=EX*N7j--S974J2pTEA zDWm6=#q1Kp1FK(5ZO2RY1+;wzirgz&EPK;+q6sTKL%0`kHmSGw(n|>U0Pa5P?Mw*t zH0iP@)OgPF9vS?dGp{9N)?C5gE$_soQA2R$yvq39Q&@_D8$fcgch4&imY3h&+ZW%p zH(X{oKI|1Je*|r3J#akH7_zPp&|A(LtGNNp9>Dml7Vz%TrG%T?f~8b(S;GSb@W`U2 zK_ZVc>?!Z7fpRRZjO5y~*9UUf%z-_VSgnX9Z3ud0wWl)VOnOf{fN5_GeSGV{IK+5Z z);p2#7!w$En9Eq>_^pG#M+1+`;P3n}4rUGHc-KSUNR5M$u}~lHVe)g}QqVJTi@Qdi zVjJqs!>lKnwFLN{@VtV&=Y%1=uRM&ge|?}1;5}_^u(l_!x!eW<(On5QxrcCyIrjwB z8j1geKnM{daP;emXcWdvjpggxYxn4l^0gcxh;Z(`Pxedbw7wM z>D)5p&V(L`HFhSfM0A^)73S zl>;`=zG3W)iPmjm?eXLk`!C-4y6dhx%6Co}jvWX42EDJWm0NrAz9K-VrUKGialkY- zNninyj+mRBTS_^B5Fra5MGK*i=RwK!VqXDUoYCqHHNksZJ=a5S26{=we6N9`(Vt}h zsV&b`J?=4}XbsC&=xJPBiiwM zoXm#qGG!^@=GlwffRQ?{y|U&6ms8CNYX&hTtiA2k2g)GZm@M}tpPRbIJGQhZ)*hEA zF)qzq<+!Ioi*D>|zEi4i>RqDt2EJD=sC!8e%{?I{D|1+K62l@{Acs(=FjSxv){t2Y z{vMh6%;l%G=UM7_^jWz{9V=b^8CVW9ytm?cAia5WHpeMp?eX3^w%0z5_W=n4!yiB& zy5fo}hMm_r=zV2z1Tuc<-jIuH$VoO2yJ^)qfs|85B#|{&LxEAya+WifPbjopB491! z8bWO!h>*Ccb4#@YE@9aViKXM8%^^4TQdT6dMhuhnAU6i!GEVE=aK4np*aN0|r288F(*`7&Bkm)Y|~ zln3+`82nf|2;luo3E&YvU>z{_l?J`9c+DQc2{#Xn+i78!dzeRsr8nrvG+H+rD1@y7 z80)-Q@4>iNx&cJJudFf}$U_dEJ(Qj96S`iPs%H|ZJ?=nPi(%CGV7u#O4S%G4pMvts zcvvhCO;V7=nk#T}WQ^Xz*rVmVe6O|JkR0O~kCXB@Ql@ezWl4Bi?P2cmuB5$0^5C^C ztN!Ff1^NlU2j&6FH)qtW2|Ydx-PnhvbGCq|zn&`a{*dq7aggLyD#nnP&cL!@-FdOE zdX5Vf7a`F3e*DQftpVMACI={WN zc^Wh__r3Zn%4LVED)@d&QiJW1$WIjn^ZFN~0F*kv= z_5Q%6gFOzyV;1-8^#fwUk{eJOxbq#aUqXgiza_kJTFSqaywlgpGRqP*$bA`qRo5j* zK5`qx$xI_jPll;8b1h&dDs8C-NJ8Jue~Bo3^87hNWrdREPBzeRxb z2(1grcv%c@5Xn2`H{)ed`J9u?tCg`+biUNJL*};wy#srJuG`vr9t5Y47P9x0fpP+Q z#R&z-@G0cg9@^^G+71KmOOS{>rG9{SMccI|lj!uLJ=JzgU`1x!YLyy!e5$Z*8Q7h9 zA%PY3zLF>rV5LUJz;ej7O>f4zg~C>Xy(}l3v#hq*caY~+vHq6AsTvw2vAmrLaem1@ znrrXgc}wY8B0qeVMT%{y@1nn=4RDEJY4CUM7(_BFM-om&ss2@>^Lh8JHQBRw^c?F& zdR1A+Yvt9c0_8z(q142A{&Ux~0u5wur->~f(x*-dTNr?I%YRNOh6dg>MOxrI$cdVXq0&BKkwKn3 z^1OXKqcim^y>wA7SFy%sd9Ow8Ndv7{==Y;8!h(KsX$t>y}kmr~!#fN0poWxH_ zT9N1L^C|LTivBln!_twdhW8v`|4uCxl>aRmajI=1Lh5<4(JJ@Rx6Xs)6~<)#N6_}E z6NXYwZxxg9u0{+2+L6r6JZmcceMw~(DO<2;9<;epFhwn$>3-_9AZd233= z7S`@B*|vL!RQRYkS>-}vBGn${xE_^psqxf%j&+Yd=E<;Vy{Gb{pAj)~w*l37eY zqI`R^b3{ZS(14fAZmc|{6lLx_NJ7l=zA9DRt?N^DBY4`fy23_XuZIaBdOWnQ#DZd?l35!AcJVoWCIm0*0Coq ztQmAI->iB`89UK)-nAu$XsQ0OhaFWlEXA7r8}Cccab4FIq--bIV+DV2F}{@QU%BUc zdWfZi;Jqx*_kl}+cGPQ}7t1CgJkQKh>|w0Y^4zlxQt~)8j#$voON|?Q1KtyI6y8^S zcNqJv36GxIW~*@_lIC1Cn0_`u9ZR1(W$!D3O9??#S@IWUcU*R^Z@RByLKv(MI}#eJ6}=`xQEL;N@HI|F^7V=B<2=QdqRXfZH+CGSnPl3Uvqho zZK2K5TVv~k@2M%pg!a0D=ZqyUNn+)c=4kmvCyJuymaezRB-Ym9ky((@(t|uoX7PH; zO}V?!k_L-B&%EUfYR_Po)X(m;Lpyurs3b+-o@F;zd5V{P>QQyZ5Fyf@^^wbx#I zCOfh8b`Ecyp2~QRzPPq*CJCd#4Rr=C-IY)RyQgFN5=(B$kB~sh9I4 zl1O;~Fdmkkp|BJtf{G+R7J+3MWzn*0Ro}ViPp!+`tWD35^$jeo#Pb^YY(2{rF;J!g z>C3>BTY>Jcrv^#9_k>*gJynHRLrxyC9;sw$Lk0a)##1D$G0Qs_@x1C4n(**qVC@~O zf9fCf%(A@qG^DOVorf}{W!aU;<;Zij9tP;PP7;gf2EGmko9=Oe0;erda-XIN!c zdapH3MDITZ@I6Uh0o=8-RT+4M{2t|3>3g*<4|o0k(J-TYjBz4c+hKMdp{T%CtB(Y>nMT^9e0XIt(!ql_9 zv9h=F_vGQJv=a$QK#{=mc0<;XWESK;$x(h6O_lS>!>JEX-s)v)eNqwGA$jX<|dK$I$I#W zTc%lZz0AiFN*ayiEd+LFKLk!qfu%y#>w88;6!IiFL5L13K+ zV_eZofIAsRKreL2ekiW^SX+%xMRXiXU8l!IdAw#rpFM*!>Ra)u)_Sw9-+`~A#pKX{ z4emHdJs5HoLEC}3beXC3Id}R~QQF=-@2lv0$T7l-eFb2Q90b;RpuAFJ#uwUPTG_b!DghQ%E3ux7bPG7HLRNswBSS=@DtI~fA4%F5FTtm~p_$^X)e z>{NkwNBwVYbC%Kx{Zp)CJ%;MzC25>;AF%+rapA&+v)IPyKir`WsMS?+W2kmaD6JQL zzfPw%-w`>@>vCyCu9cX=BS-?w^1h;c9Jmym_^|3JOZQo%R`1BULdpj0b+j6IO1h`W z=h$2h2wYBR<(&!vgN8D=pM0KF8d@oQkz=K4)Iz@RRP^4?TfVCts3OZGcucpiCCW?& zcJEoq(IoAjfp>&l+L}?~9kUd-fg8#NqyrT%U4~rpg|;wN@!cXULpP^D&n+9K8VYlP zWDa*sE(!k5i9ETChT}oY_f6H0_Z)qX9$TfC{NBd}4U_?l?q0?TOV5s8TYJr((P~0d z_LngR-_WiQsG1W*kRkBAT6(fDCl5>HS<2p6;(n%)`adT;@2fp*el#bzlu)lqJ4ayk zs`Nxq(x|mZ&YX}l3lSyP6W%f=mK-qP{lI|NH1g$hrgREDp!7~0Sii0RxpQ8<^nx7m zRFhWj8X(nvmm;z7oL-l!(NNjKlE)Tc+^Z!F^0`n#Je(p}9%$EctkLDhpzb9`>J%@f zUf|_LkC#&CuGk)YNjN{STmCQ`JV)!z}FLXYj%bJhlA3FBpPV}O!nhK!d5FG2j4VHc(% zr>~`sTjQjqm+cX#mmcD}MEXX~Sl^0XI5$eYO>5FWb)Y<<=SpK8#yjNV+|LE3I(S6x znL}_k zDO_U)#74^akk_m&d~5Qc2d-%PsoBaoA%j`=)K>A{?3;U5#3+0AYJ{DV{EK+H5GWTI zq}(V(--}})5kN$o(ro%1q+M>@_6V;Cta_O$zgx*Xxx^6Z$z_JQywSL37zOE>rAg{i zr0(^~&eHLi5AIsKSHhgK0-qjG+P;Sld?}V_r>8V-SfG5sj)R)KnoF z$EDw=1fHEUB`@&4(rMwp+?93jw!>7QA8;ulFhbrtSZdZXBCPd!D0FP_Ui=8p`)V#m zeGiDfr!`aIom&FYK_-$;ZjkbhT~tdZmLRe43=Zr)V6VoAgft4b0?T-bw$W2orU}0P zjczT(>2H*cDfAS{}PkG8y&b7nO zfBy4_$2{gShik66=G;BK?-<$=n!rMzLLbTPw1*jX7%E#pEg9ExOrSmk*+ZSjTauxH zXR}R`%p##RC2yW=Ny!|ZXSuMA>}B$UKT?y&XqL@HJL{48Ik9fq%q~X+_kAm zm=?sL=Y2JmoIFLl9%DB*6{@yGq6H@fQM5sB4IXpb@?CVwY%)m2v=)3E@e>F#&G`=Jytv_JaMj~1oLK;A6@V&rL0dzyLf zzW2Rv6B4Tir!3bbP!1q@HF*Wx?sm63JoKRtJ^b=7|ME#HQh=0$sXk=^1Qz57ywX1V z+0U-l)>}gNnbJO#B9#fb%nnC9tkf>G@GINXtVlC#~yh z;5{>UEw7(yOQBA=Vnl-Dj&~pPn@oMY97<1hHy5uI#WRwd@UY8E)N-nu?fh90n7 zZ7Q^^(=yO%!%MZ>tpIJ^^8ozuAOG=_FR$7dSSZsU{J|eQJm)#jIlTY~Omc!X{N zdOVV|`BtCP*LWbQ4o?LrwWYz|x#Sfy*r zNG}OFX<&^XR=U=^r`q;Zn*#T9CrO=m#=es8pzoE}^O)unreLf68u`YUpY*`$g&-;= zv8+zuv6xH3YIKp#T3Qb@=m9E4sg5!*9l2SGt-+fCu&#^Ds?3e4o>)@=5(b9o)1UtI zqeq3@>KNqJJKpgQmoWOFANrxg5C8BFAL9vm=RLqv>O&v;(4iDLQcQ#7RqJwvvHm^Z z^F8kQyWHh2hj+jG-G|=r)TchxT=w{ffB1(-Z<@WqTjB{|))?)gckdCr1M1BJ>I`*P z1N4nnLEPbu2xI!0&wS?5yL0b|5I(7E^h`gO1_C6b=-HHm^k}D7mPLj|+PG!3>0^4F z)W>?*%@bpfH%`3b6|XoqF~j9fOXxh$e)hA?WmCixOg`JYN0LeUKI?xDDVsT$mL5Y|Lr#iF zXs=&lN?p~UXPqsFV|+~hnY$vFM2-ZCbgrq-^Ug0-zEptZjy!z+WyUP%z zk^wAr?-B|*iQ6?uERZqqhI;tJAAb1CSH5y))C2Isdf3Ar<|@&Td)(t(0xRVywS@N- z>P{MlEdkOmcOGTdDpru!hP4urQ<~u!=6TBOk-&ms=mCL{F_VbdW2uz(2DBp(L>6kv zE1>oJqFuf2b+0=-@rh472@)%c((%g+{vNrXWESqB{F4FTqmwfwL>7;6+>qnPTEIld zeeQD~^Bk59Q!b-?xbx@|@RrPDDWFGSVTrDXl4ZZAfK*>wno!y^fra1HXF!CWdxibP;V(VQ7+Q6D+ zu*k$E@=^P|$c(u>rU%<4-mxUOZ)?Cv2B|~?grFCe2h4O^nX!)s?-5g^iJVHQX?R7cf6j+mS z^0)qQi6ICUe9%s1$b}TBFTn`mM{ZCMZR^&U>-}e*=>^s^NbbpP;Cq7Xn~+s+ed}8< zx#kOB_<~D%og%C@y|x{&M>~X*y6|8ose*o#iZL1`e@d>IY6o~EOv+Y>*u;`_@@xrt zjfK`WY>r6M`J127Hz_`S+H_y1l@kc-U(T6v``OW9bBNbK0ZI zoBals^1cFjHAkOEIpsXCfL@moo*Lfuu6G^#0|-U5VGyYBT%Z>Qciw}M-^22!CBXh2 zk!LWVr56a~2x5zQas=nGR0^J01JfZrsdVu7NF7>B3}tu*Akq%xn8^S7x74?Ko=l|C z-7C?i%NhjM)mLAAxZ@q~c5id>P=*GPMw+2RLIp`BMv!h8O8Q-XfA9GR?pn{f_dffaz0cl8*Qr>r z+@=py+J~gj6Pz>FWW58x&ahX|s0zTx1mW~JIy^Ao>G?umndARHEyBf)SM%H(bm8K4 z=IS5GRr=iPabZO@Q%5`APT4{^`3OBv4<@UU!e9|9h)B?nBw=X^<*CIrYDM<`YdK-C zHRNK}#V$3HK4KnhUIjvT z_dx~1W)#Q|Qy$jx+-j}6&0iBjpnu2Z!g9(QuWT?)VaWZ&1$KlEe? zN0#^1V!!D6doZ=W(^e>jW~2ehEs!>5(K+yHH)P@wBezW;*SOJ?MjtK~H22c1qm1NL zz_DMYtThH%#YSw`XRjf}MThE+Md4_p>N!NVB=lCz>9EIr#yz7eU*~>}$Px~JAW#Ff zY)EL+yv8>k!-pFaEglum(JV%Q`^R1!A-@!mfl+!Lj%*RR#gvAWiHz4lg3VzQ;TXBG zCZt@wpvtotG4-bc&O~;=^fq~F5fhd}SAnkiKt;SgxI8HNN zC0{ec$M~I~rpSDihuNZY)n#sCC{RVn<-I=O3?6h;HP$pixZ6NJOY-I|8B_c(ZobMg z${nGPK)dHz(JusJlqmlAl5MrPB9{5iClmf=oQpo7T7@xs+iiQE^89u#rGwsHEAl09T8D2LZ@X9+RFHU5775Fb!@4 zzZ}-h0)dak z9{t8xkG_4O0M1bmhu6Qyq#ciMi|&Xav!gW1Y!`Gxun-+`KJZhmWOYzg$kC?!v?!F7P0F!WLy@kknzuxH;qE{gdBsN zZa$KhrFAM=j^iUWtp7M*U%5vrsM$`mYOGpRzZ-WqSO14MzK_#yqtB36tnZ%vl^r2x z%-NZN7ygTzO1t7tgZCFcoL8n{ayg`vE^GP7fj=w6#yFQGr`2p!<#umg$yi~Cyetl& z)e#c%myKy`?@D_(&b-+i__=yt9P37o`Wa{b7tpyDR{WSE)TdZcb zODDlYaErIdn=ZV)v%<%-cVUR<4wl8s1|xy;MgAWjPZb_Co=Eaz ztWg9o*1cp2SHl~7JWs{I-w!(sE<`MEcJRYtY(u6jUx77l313IO_aBXv8KUBN8z0Wz zJxp%37*xF5s|?$NDYQ=l=P((G$)+q_baBpS_rdefLE^u}~+*A@R=O(dK(!71JstT1Raj%^&WY446?|-n% z1)cSr#EAIqlfpFQG;t`f)?#k8!#6Re;eJ@EwGX?dPG6m-!S@ULS096?>+c1dQm}vcxkVvJK z%>3utX18z&B_m~#DJ=5@%K9@Tlefu7&bG_=P{F72*l*exJSo2c<&*p2OW28G0FY)q ze;K*M?_kpuc-a>Q>!S<3_#lQMY<7e|?a-`JjUPQ<4nvw>_7?=!lDR;cCjQ9lsbj=a zI#pu>YW1)MZN^b20gGu~RcasrrI7@&yNIq{n4A~={UaB4xDY19ic7|`yKnP&v&Xhe zWy7xq#nxn*gv&w^SuayiTb}LAqI>Ae*0z`lLiHDQHV$8U5aagaxI7D&h6Dib(g+{r z_k9=A;)x5TA*acs7duOuOG%XN^zcGWrZqWla`~Ogs<$x@I2pufbHJ4R)cik`#2$9P z@UHvg@80`EF9ms()LQXy6n>Dk9S+Y+8%+j0NSU5H_Mg3$`cRLbOZ0gBi}~AY7D-j1 zv_o_5(6juh;PC%&PowwU(YRMp%i8H?im9tlW9BDVaJpRuOVQjXR z+NWyFZQpw10^yve(F1#~wwIrj=M;;PhZZ(TZ-&aS33zGp(cO-ZSLeJX8C37Vj_O;) zn#$dzQ6wixwJM!VhlJ2`w)yI%TTm-GZ042Gr!Z-`xEi^y?l+A8GM0BE)Byj?S!MxN zAy`q;?ae%mMkk|a6G6eRA0{9Wn*U90^2E~mEK(s|Np_@x>Z}O0z=^gJvCl@3_pE$| zCTnVb`y6xM+SwSLr!DmmN0JAHu77rpEGy$`!y9bgi=J8{#~CL3Rur{YMKv8-C z(eY+&;1>j2gmvWC44&SnWuf{Hw0YtTpbYKpZ=HNO8fkEhsgLToh=vhtvh613p|DHt?6>-h_S8^7ILF#SDwPz#&s&kWo_q zpN@+Qj#l9q;7$d?&~H_1#r=MvH-|OcG95x4H563;fdN4%$S#QgYF+5KdQtJjxIb5( zS#*_J;R|;|iK-3-KhWKC7H)=@!}gsx2q}oKWv_)(OVHjsGW8)5;W1`OvC+bW@+F6< z71dEQe8Zit0~W7_;^@}{r-GLIWOGnb8~X}38jm|4(A;9fGsNhCkEK~s{j`1SZITt2 zYH)GMAszSTK+29}ZwgiWD42S8&ny0W_owr$gW$dp`&|xVKuw9#odzk72xtUS-9wft7ftgI;0c~8b;ZNElXr6NtWV`YIRV6!a* zk-Vb#s?$VNGomB_vf(^VkrX__>Nua(yzw>hq2T?nD={2mT$s7YM#=NTJ9hQ44V)wx z#X$e6w=|XI_5Kn#BaeGsii ziYGF)|Kk3OMWZ9>gylo!l+nztGC zHro0j+(h(^RoYKUMG1&Z!z^UI+bb27n8h@$$YhST;n$~X=EJMo;w7U0sn6B8@5bq$ zrYWliol-ZtuIm6qOg`?UJ?y+5<50NjT85{g#Tdst}L!aPjPU9wM zTAd)%i<;%>1po{4<-rNxkx((5^SJ!ljw+}u>AZV0o=m4OYPMzLQOKSYkA8yTVzeB? zQK#q#LCRqODZq zNJZbL86{hP3bsJG?FuH>q4PKS!IffK|BX@95c7j`H8_rEWH~Sa-&exwr${DPcQvei zh~<(tn8tj!3mWWCRI#I|BK+j~0#%pPA6w>!w%_v1e!S>uBFjm8ceftbvdR>(Oia0n z!#&hVF+o&G1))|Ojw1V%7QRa#5rgX9Q4zM9Mp1N!b2njU1EWL?hvQcuw3yWg9@G!tia2_%>=){b)o1ZDw?6|OX7_qqCFT<(_7JWYuUkek#`2D}s#$WFORqUio2=<5^$ln@nJ~KKd zp&{`;c3g~~^Ka`~`Gx`9Tt(lJ*0-@Ix5u+`MO?9cYa$ZpYtDssv(hPA#5ePos2u%<8#6;)= z`^4FJ{_OnS(2JQ#by*Hq*Ol!}X=O5~AL8W^-Qq4bBbZ2*fS55dqS*IJl`0`ll8~ng zZyj(T@rw6kP1xJ`Ek6&xdIrS?c0l5v=|*D`dXWjkob6d`?@tlMW9rwv+nsi=X(s!k z#I?9N=3Qd5Sm3m?ua_ z_T4qXZDzX{6^32c%KPH@OyO?_B~Gz_rDybVgn6@{g}=?^@;HBy6t+iw2_MX`#SsMr zvbftiE9oi+_6^1Bv8-nkvPA11>%S|BY8Ab{5F0piNwjzCQi265c5%Y+SEX=1 z1w&2CCpf8xtSg2K$mPoHH(XVhrWECD2a6tDZ2FN(QeSSk<+@{}&}znIKIn zinJZwz}am*@A;%vO$Sl~s259+b+i3yzpI@mbr;%{bLtC3Dsbe2))_X`Qog|P$TZRp zB9x+m_KNPn39hPcT~aJv1XbX>iC}_zdPmMP1wx6ArdX~$Y8}xJHLd+XEyM!7mZ8>G zAYSC0)airfl3P8`+mg?ReXRF0+@DtQ9kYQO={)?oe8Ph%94#AE{&?LgEaHW?%iB8j zd|BLxj~wixaAS|}L1sD@5b$RqO|NujO%VZNbEI$a%cWBy`*ZG&4~Bp^ot7Jh4TTLO zKc?cBdR0vmhi`Xar3cvQTKB*R6vq}_0IRAEKCJwZSvofGx$dO@aEJ{pm{^FC3Dzy| zxx#1YvmE@^^;b}I4q)(nk9xMlpOW<%=vIA8R%62)ZR)0%`f*TBY&7v|MthRkXFb#4%$#tITo+}MM>z-gZ!aJ%C#ZU?w3;)}lU%e3&P1@V z==PEK@?F$Kzz+?o(l0n<@{{XoBVT^N@s?Q?k;b7x#DVJWd)?mOE#Jn=@SS3JthSgp zvrGh@>?K?$kLF8`{L25SN?#+NnZNUQM&W*jTT4~nJH#M$(Km6`5wA|^cYpFbeo)@i zv|_JupopaA#kbnNeH;Fcgz|TQDS4x-ttqaG1;CF?XsQ_Y5FIXT=8QxDjFl9PB`EH` z4?q6XofGzslHtk3z1snF@^WhO{Agyu!6{Ah*LU)7f=j$P3L=!1INyQ;oy3W1D6soA z^aYX_8}J6y8m+2^NZqRfAwsLf0%>0}9=RLhMGv(;GZ;;%kQxa*4evH*0({=<2msyh z>MK0k`l;Xj0)ouR8d(QiwSQ&=QU~sa{T*bNpD>%yW#!ToD*cQg3qn#G2aH*kPF5iD zgOHq}5Kz=Jsda$T(^rXMulB_UYk2tdPYz)*Wuv(!58FJe;Q-pNwEboMcNM4?Ji9qh z6{?rh5^{~Z}pE)-me_I+PX;hE}@s|-qlU}%~+`j{kHZaG9bo` zeKAikXAxN8J2+vM7(ISb&yP1xdtj&!1R2@wg0QAeR}-Sbk{vic3Uz5`iiJ1-ZY2>o zuDTiPc2E2;{k%af*7~h^P)l6T?{W9k9URd-TUemdWV+se{C~bR?fU+F)=$@RPY^N3 zq^Sriny5kEx5#+Xo-1Z_v3U|BSNRh70u;_sEhvf%U#08|;8|l!#DC(Nvt{P%DZ>uv zYXH8~C;{H;oc7b(>WkDLSVs^eu7Jexer<+lx9#lL@U9ZU7}`@u{>ymIEozAA)Z+9* zYuWTZwO+?xXO2ceA7{_V3VbC5&NyJ4Eyp|%&vbm>Ru?A;013))IlRQ%5zmB;GfknM zH}Q-GEo88<>SI^=sGeYqzIK#yN0GMy7#cz-WKYZAPA74E0yo3=f%jm0p~$CkS)MKa zfkT7SeULY612MiE*=->@TzfII+=9v@vLe)+G1|5*#~IEWuNCfX=J`-|wcm<%Tmi7K zjbD}FR&o}MO3Sh;shWvId-)WfO%1N3`<-&hG)V^8*dHo`oomC_YWQOqU)i3ly$fRe zAYOuYo0rU|nk|H4QI^Ch+^so-mjsn+&R8ybxK?B6B65UrZgE~;fd?(+iRvjQPIQHe zXNF9*Ea5zti!UymI89FEzB<+D4_g2rA)Z=PkIY|nZIL7vIoxvP+UYDJ!jt1$s zlMZAbYi*k!4{e3a1q;)hGf_B24qBL}86&2Kr3-Cgt8lClTz=AXWha2=f#r)2Wk_s*i( z-^zJIG*8r*Y9;nIqRkw?{_5&)ahj?gv`9rN*Xem9yCiVW8HH0$d7bt@BQFG{&=%xn zmAb-|xTnAuma(rXWuPY+u=cHd_wP3(H+%uC&8Fm8UlBj=JdM_N)H(5Y8B8oFrFY=K*6Q zyk>*aepOt>3=0sH#P#4!gM-|zHC3=$N_gYZWO;F6>9J+xsB*(u*YEoyXZ5#rP$S$1 z=q0K6_*u_@kwSN^bb3-u%*ry#5A5*q4U=ioCZuXJO0)NzX}-?YkPP#Qy-3)|f&9Be z9w*rq@@>9-nB@~l6~tBYBNO<|BoX5ZpXid!6Ob8(944{L zu1VLSt=EOMhO^59a$|6mFUO%l^^JJ%&}H&~uYqObsKEGQQ>brx*Y~C~n%7@@UnHj$ zr5nb0%B1PKT}w1= zO%tdr4#A`6Mx>JAK$AbUm-5q1tc!tZxz^oiW1dx&eve@MCac|WG>vQniRlU2GcF7Y zoD4=g2tRq65;I4-DmKR~3NK?YB`!%EU(S^^H5T$ogo4YaHQ0*+G{%@Vsd8VXhjaKqn|&=OCyYJo0nsC7qd-_pr2V|5^Jl79*&W^t3v+ zk!e-XJQ#Pg(TZ8xQgsnV#^zvc)|oiw#&-k51n;|C1ETu&uxP^#r${H>b7q!l=sMUL zTp?d|2S*Ar@LO5HEy7J$%We0wXY)&5s2*L!3nu-X<}oF;*-&;E;Ygp?93o`W!9+tK6hq$Y9$4)3(1|Cvf zT+X-kTv%D!k{KmGYw-X_Vn@5*ym8doQms6v=#v_GUQhloUVk^f_Ro}%dEUk-^QCX8 z|6{%}@8NKRM+~jfG|m+E8hL_P!dsf|Xvv6@ZkNBo-|j@PCq8RF*-$(T-fQ0UUSZcB zZTcvLgF$osEq&sFIHXZZ%#u|j!>Pv2%1}FpYj*_db2d~kA5`K^aC}d#y#VH0SK7AOg7L(tLLkMJF3adD^eun7+|9a;$F9 z6e=ojGaV1lh~CKc3|hrpcL!d0~`Re{cdjQ>8B8X@ae=%qhnenTW-&QczDAJ=(J@ID- zdzB_akpew0u1aGG4xF3IFi*clDd`qoEhkk{;Czs*h-Bv+eM2#nNhrvYg_XBS4M8%{ z6V?2q44h%(9nT!D6eixN%NPd$ctC@!+V=|gm5=9eTu^)1DZ{%Ta?aEcdfVi__J!CX zxg+m16@kDJxwk&&;oFvY^A3PB#TRwp#bhQ~Hq{f|gK3jMh`i?bN6@rSefUpm}&YB5`&W0P9^pIkLt zPV%x^^1yoe=54KU2b$xvf0C|cF+9BA%s(j%Vgqg5GggZ!LwCHJ`YkR~Zk4R=r$z3k z8%27yB^jkJX>wXx;A zHLRRRTLQy%FgFbLA;o$;Q@vDhv~m)0T*M25-#*5Xrmi>;w{LHW@5eFi(rQ^$;=tC3 z%E27aASO&32H89hbmu1DTk1eTb`R+mtLx^v#>L!fC@rah5lfQopUp{HqT2A<#MyHx zOWT4a`K?EQD!z)fK!1u{9h{wNb%Vq zh6Ug6+Y~NyHqvU6s#6A-maXM;6(}OZi!!_9dk&mLd?!+n-iF~ExW$|^@4ovYGiw;K z)@UZgHlB53u+4+#UYZra-g3lReF|y7j*Kzs!r~un&9~^}w-dV69(z)j%f1m5dv0taNON0LL zM zeO(UQ%dF=c$b}p+!18Ho0BHGcOG+VRqAg^i5wI#0MHyd9+f0$ZXG0mXic6UmvcWxh zA)@P|6&P9tJm=Y|QrZg)d_;6o&TOVe@d!{|Y1;(2jq395JIo(Xhy%V!3K$DUKK0iN z3swx{Fc$2{ClSh+u%r+=_**U(N7e+|jdlN~T?GD1Ys9sOBi$mFQgpPhNFv#_U{mQi_)DWo)FQ(9f$6Z z0(zf0kdA!PK=iw$3AfAwo>KQMJ>B#M784hh)ACVCLa+Ny=0@uA1EJ=QWLWEiXR%7w zky)G%|7a{iN{Lhu(-yXeWXpje?gk-F=vkgj=#k?#HRy!q^ljA4WTU3|Ie-1{V)pJs z4=-8O>3KBYjx01ph&6Z@Y!kFYZpb#y1!~Zl+W*Yq#Eq=`r;wsd3moE3%&{@j7`?EY z9OP7cKK?xXEoO*M{xtCT-L=T$a5tgj+`k{hIwYWLX+@ZYD^E$iYV zxJPd_jl6hp%;|I(N&x+!hXbRj-`Q~sr zVg-yi84GrMtD6;g_Wt)WPk0w$nb5wI7L1anyuu2o*i$}UxoL#tCvm0Vc&bQrVhw_2 z2mdDeC)MrP)-0OC@ps$wa#MidvIc;$MJ&2OC|X7Zz}+e#yLLYtxqJAn=5zJF%Y+-f z3kUey+>nIV2i~9GuY9#4*f|_{uk2|~)jcDI9JC}w(&rxJc78qvLopeHG@48o!F=^R z%{ddZVq}MufDrN5c%uR`>}2nE2q3CR)r6c(VKa{jE1f{dCer;ETlzzUJF0-N*vs~IDpFH?f~&=CG0G}(wA`1c z-6Gur_>r@?X5aFH91#(hbwx+(sLx4AohcqBS}GK^mGScc+v<~ZKM8YzvT$tHNHz50 zlM1b*BLm`Uc9{_8(?&PYR%brYCObTO)M9-0Urw}}GC`SUD&r}F0TJ$0O83h&mJ0=4 z^?1ThcwYK%I6N2eL&>0AQ|?2xhwn-B*-?y!wia@M;!e*8H}LdMTSvcnPgrp<)jdzkv*F~*YC=cn0QVnN_sGU@tM&{+~FH)$6)eZ|;&dAHO#))T0 zOA%Bd06Kzf|wVjH1P@+`Oa!a3T(yTSg zF>S@qut=_?<7^Q;j=b)`N^1$UP) zT`;PE>jwg|GeRKG%c2mLE^GLNfncIaEDvgeTSD_S4vFIH=t;j$UvKxlY=&CGUNxK+2#=}ikVbAY3Po`CKHeSD`v>(DZGFX2{H zIoVcxEscx55RHY&q9&#c&sIQOK--|aDBzhk_OU(8eiK#ick*^W-$XP3Zy<(&9{2t# zlK!-wh!L-<;M7kv0ISi-2z;dYDqQfRb?aqaK=-~&SvE6*gYpf#e24QoD8Blmm<#r` z3N!jMTo^QOOVw&XUl|!qhL+ZFEVkiLC)Zrv$<5;S^w~TZtDDy4JV6F3P~mYLKKxR+ zb>`(~)_UT)^7wG25Y$sPO3*9^qTICnlM)*uw~9?U8iXxIPlHJp&?t*>@4ox<_gUff zR|o5s%f3XNhc)J8b0Bi~geo$QfXtc-!U`tFyGhOB?rTzI(lMuzn|qc&VeSi?cS`8n zB=S32(P(16*zYcEt7Z?sJvrSFnN|&*3Z7WvOor+2k}*a#vhe<4sfZU0(uq15kn(q` zgTg1C)RNoAPrsFdBVP;70lnp<9Ewt6!U{;fy>WAVNg_>?=42t``u&);gC+eC-Cecs z(^&80xCL!&P3}CP2xuRKXOLo(cV-tS#HvK(Gm|;#l$sW`eW6;sjggrB85@YgFPq+> zew9&FaI>6o+pQ#KLBK;Kv}(Os10{Vk@^0c|0sqA`7o7L)sq&OvpnJb)toKiG1T6?Z zSDs9MBqNa#c``NF{kN{8(DiQ1>!AWh!2=*>0TIHSq(z}A!ok0`=Mkq(A-1Z0+&JK1 zMd%pD4%GJ_RTSYadh26{+&A(*mvH5<7ThAdY|}Ok!id&Dr`o1TNP?})nr{gHNN(R9J#|)uMWqNh9#X`(T*1LVy_+h~&CZGPBg9^9Jy zu2oXd#@0(7_B7%q(4ozqajU&&Hk?`2GK!ww~1FAqQ97zvys;B$tQkm6kI+@fi zYWdg_>E6%Xcp{wMcWhWTzgma`a_ToqzD)ctB0K6OLN1#PGu*S@aW?of_X(@7QpuQ) zGW!r8*Lxq;IetdjS}HN#>uZ zFm#Dox}J;1V$l+`sD8!kZd7J?WGxB9hodqkMtsYz`JX@z82E7}1isLoI*d`6f3I@Z z3uT9!EryLq!_7W4@0lZ8lqZ@z456B(Y4N>$Skj}-G_TVAc!;N(GSg}IfiCBL;tj6| zkb%pDUvf&U8ipN3?4LFv(sCDdJmDhLfGzzF=N>s{b&Xq~M9 zO5+9k7}1!|;y349niMQOyWI2+A~8Sa^yd{g+NIwgo;kB93;nm-C!<=34cp8PeaZ&q zTbc%F3hH~EEVA3`&Tk;8yVc);%ZN1c^q%T3H)uz3nsK>!1lLEn+@@8$H0GVZhzf-e z8DYEe50z}pvPNd&I#=gHahIY^vUqrkfyD2b`-g+e?CYFaH@#tA#9W^heQY;;%ela! z^*#w&VBpA7&sA1~|FEqVq&e<5)Hc$OBX2#4(caR2)3AUJ#9La$deBq$uZdqk-PY_l8_tplE9E@!d+;Z1^JxSY${F@s&@7~E_H#$jrc!nc^RSV z$BCOJ-t^{!6HSB((s#QZw;T^iI0>q{tt|TO3zl(DYW+}s>%vS=5Yd8Fwm>vx)DB~_ z;*y%u!`7;STJN<**Alm}I=-Jud|&xB8|zAQQ-?X-f*4F~OmD=KE4AdB)_?=-9-p8ozoi2LPMCoAeocXuA$xO`@T3p+>E3yK_n z2<1GCsx5j6b$3)Ldxsml**p z?O7Sjp?ZmTTVCLb4>FESq9GB>wL)`9f9CV1jFD?(-&Lv7cd?HPZzvH;@1GGZD0_tY zvFH3oKjZ5B!Fq$bo1gHMi%h!L)SHFLAarah-gB2aqJ5llgEe3Z0kL=|fOrp+XVSS` zB9}Pz@6^w?Svv-Qn=V%Q30mt_nyVB+-V1RGRhey|gX_X%2sgSQ7Y3Q=*}DxM=xf`^eOW)ehRPrTRMPYdlP7t)->mFnw=do;*^D7m$)CXK zZjXX8PY-H;;ab7bK1+13b&5t5FR*O1=jHoZcRo}w`^wa^nsfJF__hc;-Y-nLyfl@L zB!zcoANeA$=zHZd1e7gQ`?nQ&6)S9KaL3;YvIzdDkNv7w8vCM2w7hp=`HPk)c{5W` z_%^1cyw&caK3~FObSxt{4k*F>UxV*LbC9X0!3Selaj`r?vSo1AJi4Vg#@vJ{TWQgW z`KA=N0>MEe2o=Zx5FdOKA9n{Pyj)`NrX-kbvP$bY|2MW8A_aehP<}_C|Xv zdu5qU;tH154u9Qr$;=TZ&nkPV#mrNS!aA^gCak?ko8s$!_bW1N3ue4?EIIY(mvPF? zhvZWtVO{xe_~16K=2W0uTl4qL-Iujkzaoncb>7R4=|!mZU8ZK~?e8A(M@mm?NSN>L zvKlsX*gB$lu0Jy7FdyD+4v+`ML^oqw$O`0kDw@%c1 zivw?STXLqSw`Zojj4evJ)BN*&8BmU@Tc0nrS`x4nHJ6ro((XG~Ht+yfJ17HOX*s>^ zEyOFIOE{WJkM4AD{bmu!@r)jMi zM}ZgD*pA-BDY1MHpI?Gi7DX*uto9koyf-HaN+2s0OQZEIr1?{I%XL+O=P4{ALkU)% z9N4Ox>w3guK;KUN%TN1XAy0G_&XB&3z8lfJpEs^M#so<_oQ;lWz>&ZobaT4JEcV+< z-RrjCm3eN5w#a3?BxjM0(JjeEQ@qif&MmYUaU^3AyO&Tms@_j%WZ$bR|%ZaLAL z19rCmSF3)u)MhtQilGwPkY-ikP^7-@yt`3SYdmlJhG&$o?zCt6GCV%;2F8OR%Uk;; zH6MC&XXHUy#Ly7i;yq12R$WVFW+*L6R5MbvW;Kq|r$$gOoB(B6R(v!Xc0oR>ro^an z0dzR4M~-EI+%#kK-v2)gbUHWtUrT+rEmUhzT(T6&Xo7wRC>^__6pXq`rlnRZ46IiJcdaLR3F=OOF11u`FgFaNlu@ zJ;JvU{d=eWY;7Qhg-fAnh4W}~S|$%6AXhR>^L`%euAPvbl;eMfSGkr1}+Bt-zaW@~pe*6D&b) z;bBdtL|l0{GNn}A16*I-r$HFgCvDwaYUf!T78<^cu~qv&Y}yog1j&Q!mFn!i=7QzR z$HP3$cWSpre{tRfXiJ^kJkl?IIPaOpYBcZUTw;#@SpeM4va-4P8ZXDz9Y6(1!RpU3 zj@`zSu_4xKb_5iQn&bV>|L^4|w`>hcWTQkwXak_dj9^UguyK_s>ZaYlzzO7D0)9l3 z8r^%Jm(LJr)$~5>_sU-qt^_b1M?zD9nY7I1PgJ_wbn_H;$4tc^TnF4Hpg+5dn(tt8 zdrBGYe}yjQfK%0+vXc6~Fju-@C@>ZF8`p+#gJp!|oRr2KV5l;CUYOxsLMLIknciZI zp<`kR_6Xn+lWZrk2SXB37|rjq7f_b}E{2!^kQAjTLy}6#XcJX~nrwv(NcVqD<>MT^ zmc(mzw#N*JZQw009ru4aXhb)#fgoe~bv18m8D9>9(o(F|@;^J={r`UY;y_JBb!r~^ z!fTfko{D=0fzO>}zh)N#Di?&k@&d+rLUMx4y`4ou5SS)6N#3j1wsVR-q{*Vq{(z+D zy#LfvhgP^i+T^Mg#SRCsC}qbt4P?woAv4iA7fYQvU$)?4Iyp{4g>0NedR6ROdqpNp zDh>Hg1!Op3SPT)*8nsXU*-^vkbZ*6sN5f^D( zN{GKp`m_ah!_my6m;quW?MG4L$1~nuA*K4X3EwIQ>U!G!fW+15=$XDgE5+NG1?~g~ zK;||RrGQ4y)Je|Nh9VySK!B$Uu28209JcABsAZAT0}`o#Q`WH0=DhBj9n@n3Kaugx zbgF7?I`6u~0w14Z4MaAjUwIQtjt~mRT_TP5QxGK(> zDVJ-jV=&_@>Q3??FK+AS^H^{a(L&j+d%b?{&qmQX4+SzK>mB_!S*UtFHWyM+y%!M! z4$%~QVZWRjb0IWx0=ro(Kp)L3{gKbi(Q~bDDs~)zdM@tcb*Dx>QX1y0z&w>FgwLi^9y(k;& zEwb|JeiJ2>Z8~f)Np6EvgIh;98lEbZ3!D7{KMkI4PvNMnnZ!SeoC&sFV8(Z@QgT_{ z|LD;R?XJkust>Czr>Tt>ApZWrS2|Pe5(3M31oo@opo5)j@3aRdI-e6J>73cZ{7>6b zmp0R_OBE0TT)`KqP9VXFeWH7k@dK%_bt!tL^w)8i_LpJvf;+4pnUnD7mtz3@>D8;Ibf!5?&mr9&Q8`cl&E@^3-tDUUw8=#)Cg^N z?DI*XKRitsHUQB0G`%8k=Bd^8^MG0JUi?_^a5uUf;%H!wQa91wwJ9B}NcKu8&nD;B z6r&OiJVLI*1|f_i{%kc&_|~bN_uJnq>x87^{KQ1Ze;pyfB>8mB(iWKB0*RO++HFN#w1am-c!-oChJP?&GX1a2fMj;3m)!)l%pBV=I@SdqUg6 z96QK-6=KmUukH6@Uq%;^0iW%n7S_@`QlhWDpx|E@zIdG7=;f>Qy)v*#e-h0oAW9!T z6d5NxGvsw-o0N8>Qht;7HA=@}{I7vH8q#@+KBPgh@6A2s3$ho9pb74lSV1hP9ci(( zEd~gu%zA|pM7+e_?I=orpKx*HI%fwr<$-sZyqV`(Y%lOV9{o0I>BJYehmSQJGJz!VT(9Z?m8Iz^6$!!(1Gh#@lOj z+(PJdOdAivIVLQPI^FTRUHu+C-@ZYOkFkX2a7R_*T-X1iQVuphl;qvy=Wr$(JYYw>3%LP4z{Tu*dUbUWubUJ zQhMPYAF~+{&y#EKYKsF}2WC;*sLhIj_e3)Inv*|1n$_U%c?W$lFALqwHiI_RP_a{4 zzM#yQ;BIo;c)jm!ju^`V&23fYG{&OM=Dla__CtbrW@aDErzb5lOsjki^K8HtyY7S$ zFNs`HqYlP1uklU%{7iM9Ho8+=EWUS~aM8^m3t^*AfOkPDT5GehLJ+)lM9fXWDZ0jg z=CbqG8ndovFVdTdrIl7UubPrI7HAxE5Qo$v3EjBI0s$ZXh{2!){yAT`@l4&LXgyLI zYf5(ArW2#D7}F5LS*=q>BBh3@Y0$+L5=$3L_wmk;-ewuGl63|7pvvv+`D?d6r|6(c z=W)FZ6Grwj29W^&;r2hnUp|d3ScSTg)3^!A8b|q;|Cqkj&PWrwhyWf{bJo@PmJj7i zn%9mAq$t_ag-05(C)s|oO(}6SH6_^s;wK@A!xgnW43}gph!A!LWyMP*X|UX=<_y;# z>z`(IyCt;|WQR=U{sr9461#LvS=~x6vTXz&0Uf|i`^4olB-_gaeJ#M6wVex`W7>%? zs`E3nCcIv!`elcqU8XoMm-F9{X1dh!PF-@rG=2xwT28wNk8p5JEBOmDefsPXSF$D)nAC@;m3=gP0xd-#2i7- zhy{@5Li4<}+DE#&tLo@dRSmr{(XeezfdnO6Iz?dt$l`s|xpYuPEkhsx%b@JC=ymWh z1FRkpeY*%(FTVS(l+kztNdg&4n{$o4#1miLQDg;1=cwt7%~t-UjXHvICS+t;I8Y=pyu+ADd(Yt)`*kWs@Wnmc8`uInh5B0*4~0LXc} z$s9eM@wNe{Q4?5LDRbL6`jlR&6aY1ypSJy8VHuktO!+Xciuhpdc$cyR5lHw#J>gbF z-<0BZoVAz$|CrvwYq8TTG*&%&9nWd?bo&aAhN9}Z>~KX@p3b&vd};`_0q>k{#XR z3yaPwngya5d{V*0ZB&%tg=cjCkE8Q&XS0jLu)X(Qjo2#`HL7-Ns}-%iM{R0H%%HVb zL{wWrt*Sk1#8!e@sZyKT)LupLUA{lzT<Q55vGEuNAM_R-Va&&vGAXal-Bii1^nLinK3udYFH1DmH) zv{{uG(*S27Fd+iufJL-G8x4&(LiRx(Pt?fGLL8N#sd0S6y3{x=#{eRX!Z`1zb(;@u zdHt`_bP0`Fd~5WHE%?4t1L&V z1pS>4YVrX7gq_JlE~t6GofpPNKUsWg}cZWUfbd=l=L?xICw_PvG#tt4}Prkg^oI37g*y0pzpUa?Hb+nI;t)*Sp zpQbp~SJML74TV}{cKR2pN1XZOl!OT&Dt~%|<*D`e9R1-YE!QP*ldI-4OS&C!wFjvj ztB@k2b1o&`Fw7)Kk#El7hO`o>$+Bu9$as1js_%-`;oS7O-NeCWN-9$%$+&9cSv=~k zvp&dZ=H|5*7q5|NSOG>_4rf=~G0nVm7t~#)jt7w<$c%+}-QHYRE}tJ;>kLN2U`#+5 zAD82;*);wlOL?HIZl@)khr-t^+V_%z7oXdTqGSl*s&r3m+H@Y|{eB~@2_ZUd7pX=c zYgLFVF?Bh=c}$fiI-}{o`bKljlX2=AiNNiG5}Ui`W~yFU+I#;VTIJF?7%tA_u0$R- z!HXD4J-Jd1SgRhbS*vP5*95jR2c~#TLYC(Qd0J!;h2G zSah_f5HwTHqqoD(N};B={gOSf;&H#Q@f(xW4~s#oC_m?$ru`$}0Dy(I_y8tB){i{X zpE`iS8da)QTG$IT?bMSs%Gw53bw6cIt0hobxxXkKb!*{o=g_BQ3Sn$F*nMM60(uS| zt%VbY{00lsnOC@+4w5sAagZ{xHgxbVg=q{nwlvMt(YBqwetf{&b7!<{fvEf$sS^Zv zUaY*SSf}KEmNS1=<`IxHw(Uh|xartAEz|i^h8X6ovagU4z3)^kNGm0+6^KLaPj5E$ zND9WEwi@Xk^xA`k=sBR+%VbIS+q3?^zvS;%HZ?xvI9yxs0yp#BQ<81-XJf-jtNIKG zxu}m4$@8Vd5IZ~X{B~_T@-81emgjESx?Au*3mXQ}s;{?}Hq@nfa;)iXVzL^~MPaIbzTuEwf;6V&bqhK4U2B{g|wpV{rkgt@e9&4GlNYH$g0N z>e)v8xJ8klnh6wGVyTE>#p$zw<1s%cxGBB7VX7C?aFw6BQ2Rlb5*7zBT>L3utr$Q0 z8+sSS?Y&I2Hs57#GX(_QSvn8pzblpT$a$~I$%5(LaXD_5`r`h>_BVi3S4j<7X!$`N z^61)PH2v}Pqj(f80`82D?~l8evB(+qQSdZqeP~-^v2Tq@JT7dAHEmI`4qZC5Ad2Vr zs1Yp^Y?Y@OS|zHPjQ^42BYkq(o6V>IF5kD*w~kgBL=jaFk?3;3QlQ+Zv`jJor%z{D zt^MSzJ?l4oX78KdL#y64V~c)%tczPT;dNR6@>MYXtEwGojiHAf>1bnje$+%R92q5D zSS^oa`Uvm);MYNyd%QO-4DT=GEDB?6A3T~1V>Zg-a{CX2RIga9Mi7J}S%<1p^ zXEsbP_kqgU3v~2gixNn&2EOJ)>p`D+Sj!4eqx}(@m8dpGt+8?@*DR{`0wjC^LPZfK zCgKzZT7xZi`;zLwQQz$-E2tg|kTMYFjhX)jWYF0#NlX^Pvv{h-hCw{6%?z#9 zTX*v>U+?Nz>b@3dBbZVl6J_Y1jmS1`I*r^;u+s}t<4*?pEY2%RhKs3A3^=o5*~$I1 zMPjh^x}#5q5?CL0;^X_{0XVVa^*wr%EPD4veA@K>5m5e=10g%RX_Xlq)Ab~*z2;JWow7lC+_8+nI5u2JN_!wSLy4 zpv3d75txdq=%0B1cf%sD*Q_h99{6gpQi(-IUn&Mec?KX>V^mW`nXOg4cjM&wQQc8M zsSv&d!DQ_h6oHFEZB9|YCk%+E@Md`j$QCxWX2r_LHO8?uRodl9G`26w*;S|R77-;w z;=}Fnsp}bKtu&#>TbC~XYV`5Y>M!4$v*|qA(bL0kU^zN#l^tu#^E?~iHA6=w3le9@ zXfD|}Fo&(@2~_FJftr?tkfq<^hA}XkCM{-8& zm~f$@A>F6cW*(sIA=cLu!K^ha83Q=h(FS@gB80@BX~}n`BsN(dG5ZEiyt}cUOJDUA zrNCz)X+dLZVeH+nH*7@SeN_C~l!$a2423>0@b=66z~SxxVUEK)WY`i=)qXzPoA+-p zkK^{=*xf(z8p_wl$g2Y08tBL75j}{8J+0P6s5>eX+Jp!$Em<1>rMG?562ubt=-#rR{ZrKaN0U}bdC@c!geNJ@;cB^mz&ht@n?HQXUp{r!zatHKj^SS zS9+Eq`dG4aqPZnF{g!}%o%XRX^k#BXG=UDT`LN#1UA$71o^>)j0o??7E2ROIc|H{_ zMhz9E=!=q(j&7+=`d;zK zc5UbNJ8|e8?YD_L;+D^q+9_13h?-iaaa$_N*M;9*2*E7BJd4KzQ z85Fiush=q97^OX7d)a5Xc#Q0|T)LX-?F#CW(fKox6#PY>J>2U^YpW`aVhlrq0(`Wbfl< zSIV7xVlxpFx*PmF!*NPt_j2mHRJPNpiNF*^RB(i@7n#P9^}b(rZ|;6TY45%Fc6D>u z_V##1*Y*m#a=*S69?nZl0Z~|F6TUaBZD9G2^64|>faZ(#gYdsAoVP2FRuAsQ14k#R z!RS>pq_KE(%QXJpHQ=IIb3)PfdUl$s8v3(5aX;j{BfuYW7{eLHOIOvp^W_Iz`aRUAZw7pe2}$Rk9ip3 z9@kJh`B;W~-3P20!Y%xa=z41TkgMj9;*@WBAmYzJYLWRi=#h9fTrztgtKa$nI^BE! zvHSrFIJbq>4Lj6whSd4j*DH2o-b1@*2MihNGX~CMNonfb9(%>Ya``tp$7J*@2N4%- zX`QNqr>XbHp2GSKTOZwGrmk=H9L z)RE2Qe|N8n1agymYh}BD10abGQpo$|-jlw2B7F6Nq40*`>$4>?8j;VMMOO>=P~Fvc z5mh!%qg7oIyL*=kRp%jj=j(m8b7Bm;wtM3iHGt(;R=7I-?hC4Qi81+ietRur;rla3 zrX9ywF5w)T+eag;;g<>=_^>f&V7u6A^aVNY@eXYoq;E!kpA^`77;=yvSCao)-eTdqhI%K5(G&M-wX8P` zA<_f&VET3GW$>X*a`2_iDM$Zb+~0|@M90Zp2Nb6$He;~!C8# z+_jTi4>|5LxZEG;j@-N*tmviB6-Jxhtdbx@(@DER-R5Yf_~6O61sSrmnXf33;W2I% zr{#%aqaEq~&?Y=clGgFg{l@Yw1G>l;sPrTeR9#3Z*?UI!VTX#;t#Y3xiwHLJmKpL3 z<^^}06(X>BfDw=c>6VRUt@t9&FgH*43~1%HW0@2GrTuN*qHuVPiu zq2jByv`IY;adk@w56bgR5Es;4Rs-=Nfiy z%k5iUZ;tS9a`q^mG*O)H>z#+n%zWH)PoyV3Se3VM8y+kZ0zfK9f5J`vq5R*Fh0tz$ z{j9Hq!U>pizRB53bbDl&P2`VSq=Qr)LWT#y058Bwqnbj6h3T3otqGms=vrO(y;MN6 z@HrkCAE_wKBg4bjoDTmm9y2IlSc}sJ1CAqyL^TP^F6Y&F+^BWT%-lWTrdj;Yo;vi` z5liy95P^w-1bb6r3zFJ?kTKhO-7bVs?;D4tVsV9bA>}X;X+tPT^9L_UY79-B#1P+C zpBfDS#(uT-O$P1Z(O*Q}r<{!It86GjJ-O^`@6(eBq^e*%)i0suLktBvhh0<>=@fR=mFTnDopVH17 z)WqX58@w$bJ4FhW=o61j7QPfLH{3!sbmg_(V3r#dfP9I)sR%7@LLHT(rDvnPtbnd3 z5e|lve8U-Pyeh?GJt2GB!e7lxbD+5x*EQAnxL9(LUExi+=8Qe7)9jBZGO2jn8BWl# z&Qme=zVIhDCZt=qUBwJfI+>)()E2m8U#TB+NB&^{{{Hf9HIebH<+KYZq znE81a88~xcs?m7X|3K1ggOY$T9u!t2%U9J6!INC%iGWzghPlC9b6wlD^y4kvrXGKR z9OUkHURm+xBG6H{RH4Ys8-IkHw#e4Y`>o}2mi`f6U=#M!eLG*eX7jfC4OX>&YWOp+ zGM`pf;W?Y*fX|A3>5r+gT07czb(IyBG)TOo2k}dPQncLnOkUk-f@3GxN9(v&(%PpS7$3F{C!T(^v;$2OEC8%%1>FQO1E z5KB5H!-lowSAB;0FumgAdoE!m?RG0|G%Lo6Dd3`Q>BjXn_f)zGP77MlWvwLWVil{P ztKApQd9$TCR`txr&W^_>YgD&9cbpr*%X$54V3gvJA>CkYT38km!qsV|@p*26eev*Z zy)(0*JP5b(kT~*?*roG+xJDUE`YK~_Sss$z&Adu4N#*(m;hNHq)M5uj*w{F+kswC? z>2}$*?tCe46{xH5Yg_|j>>v?aPc&G$Qkjs2bsXvXU#hzx(Wbmgl8OrKYYnF;g7J+? zNu*7*8C!V_vt@l^tmm{*FXi?RdLwu@8zw1PS^##evnLqWtVuyfd3kz2)c&<40ueW_ z@;YSGey+c#CpSi&JI^dT1JAEHZ+jylCQPn(cjrsDbE^mUWTqn2|9?~Z@OAa=PBq}V z8l*hQie$D72V6#jhG{{KI1+DhcE}n`NaeRra|KN9}Cxu7ajGjnl?1m+WP^24Q>aOTX?Mz0*k8s^gK$J zg9ZSbn;p}(gIJf99Gv)J0i~mafrg4>^$%l>r1QNB!|Me&$5Ge*s(*|+F)`8|D>i5Y zQln32{MrsNf76|Nol!WeFSFPpQTA>(7pdl(Gm#k=d6zkPz5^bofqOYA?<|rNNV#pB zLP-0z9e&{+JlWDnPeG=tS$DI`zowp}383FH)*?SP=^)>a9FSl1P2MXT6e$}htjurU zZh9MZ_kJ3^k=}!Fj`e$~EeiXVyANFuA9^3K=_|%gknwGy0~h)?9aD#%1k1b+^A>f# zVzCdgRSyC@r!{Oj&&Z^urPCdbZ$XmOc{^E&ycK)58e#+3fJ_b2nzgqKh^jmI?wuoW z?ernMSxP0<7blCWq{fn)y66!vXV}UU}?~GNi;8R6=Nz_Eh*ShFY;tp(|Yv_hL1-ef0*gX?e@YES%tNwE8LT zW5B{rZd3+$J0nR^j5X1U1g@mIh*?IMCBSs*rfx)|ok#g^H#KTulhwSegFGLt(%=1S zEaO2lRX_S=hi9SIGkR89vm2TN{y`DERcS}Ng7!iK$o;-DBI%(#_%*DbjhWW9y#fal z&tby~0iswJF>xZgxt^uF>ququ14(ZrG0P$EH&8z4Fclc?*GG#tq8n|1@2qPeNe-!= z?l^DM&Y_5=TLRF&J(}S$#aW{~OS?)*H$%>=$VFj@4@U;2PG4SnqBrTTn9f=e!O|x% z4;91EHF<&McH57~2~{44;Ls9Ua}~SLVhT$`mlYp}#QLg1 z&uT#90B4m5(uPndPe~0@e`GVdtEcTOo}oaEIQ2d*1R9rLe6vP+sC0I9$zL{fRsn_RBaqKal770zU~yucdoQR8Oow@1y)fRal{=GPVR8Kl28f0Fsw2mLtkkdb$QA#c4bZ)rzr67yT4_^L_17QHDWJ z{)z$zMG#!clvXhw_NN&YxZC|HxTlYnefzG6R0$1OXdb$jAA%gN1eYR@9^QW22-3;~ zJb|M>Wit$s9mMB%BZCpd-m+=OQKgL7-WxN(z%jv~$eeHx``U5O|LAy|{{GYW(;__N z2X#cBBf@DgqhEZSH{^{%@3ML_b%O|t#=IGxjoLk;4Bv|;AYCItrFd{<{;CEtqpl`P z0oq_Z=b_+CU;K%Fa}7H1tz~$ebMFFKVK{&YND}9wu*w>TRN>@-aSbX$^wP(>C4rRb zB5?H6_AU<+=jc|hqi7G69W#IxT?IRWdWU#P@Ip>eY~^R~#Yjd!Z}nC}#enjfE!|u>F~a0EU>Re@9@bQkQ@f3V6D3)6b5{K6iVaH(wnU7*2(n zZ5n(1Z8_+jK#AxamQ|mop-om$M#>1I4CU^Mj1}re74OACQh|E`U2%idc38*S`&) zcU`E27~2;9>ph9MyNJAlTZ6Ps=<7x#`#(;~>84wVxehL}Jp|dz&3VU4H?d+U5OS*` zlKpfYN1OnQL)4Gj`oGo=2O2=H;-u~i)dyx0==8Vz`l4!i{t~O!#c3hawrGfNkdH{z zfk9eZam!n#_@$U-pJ${%mqpp%`2-TxSk|)r;}`@5RaX zg3eGTIvrkY*Uev*mFI-^7uav|85Pfz@&h!Gn(oUsErne1Y&o23%sRr^`&^yk?`x9% z_s@x(nZ_Cw@`?s%s$z~Frclxt{WVzS9ID{2d7bLEd=+`(b34*Nbx=*^z+`&G+wlc;JW^~&0wS6zSFOdZcWV&7N{Ffc~KNowXOv1xr zp?r6u9QiNJ4-TNM%hkq9aM)?XXm@$lI@}svYk4>f) zcIFy@c9A7SbtGLZ$L7wvF|Nl(j9ed81_HI+A1&s^B2vcb*ZNqo{U=5PlNrEg;KhKc z(EMDWS5pY4zw;#cc9hTQ_x)eL`X$%;zYphnLYJ-=3%{1wG+D=d%zdQJ{K@nWG8nRP z-TR36oHia9#+$*n>KO6?rIyXM@!IHdpxQML|FGNYVCa^c)Hm;uj2Bb2Nu)j^+iud? ziYdX!MH5S&O5RV-0d#FNb$**#vIE{0jI}1cPi@?X?1f`QhPBCsME1(Y;88#ucUhS| z-z;caB^k3`Pxl@RC#z+pn#zw89em%QHP25{%OvTKVjKUY_R*^HP2iK@<}wSqVMUec zJ`CY4YL<-rwKTj603|Rywj?+7o$QiuTfQxiJga8n`eCmE=`TIyKYlgj`;n|Nwe#(9 zhFjN({H{*cF3-!c_dwibX<)Y6Hs4#J zV!cs*jaLl1L&A87oKrOS;HUONzDvAul5?C@GMnf3#)Yv5#03LTyE(x@4>FSl8tf1J zkf{0b)#m+^Maf(~uJ%{kA;qv&zZ@&ErO)gTx3eAdgy18Li1t5RCQ{QF5@9re_r(?pO`!UIvK%CyZSPf9gK{U>TLllN=x!P zfGHeh9qoRz-%u=l$N&8k)>W5mEH|_EEe9?^c!pId3pG0`FQO_M6jk^@9|jRSWvArG zE;4Z{HTC#S+4_FcXCE>kkCIPo%^tRDS4v)`?P-1yiF7=8vG9SusU7I99I}@yKT(j% zf}b?Ks<<);is{@GSD#M)h5h4FfiJ4ru$hNeR_8X~Je3fk41d0>KHv4Fcsk2-3|LV! zLxFzPvby&E+*zCRgFDXws_Xp@>`|7)Uc%@2*7hcvV>*+~lDgj#mt|-Py#w>BS-B>l zqB^EHnzu^Fg)uHwX};FAf9UVv7|(YZ|!605`$npq0#vP~YHBI5{y8i!uYT z#gy0=5VU`k)Ulz-VjB{a-Q8%y+3n8<`{uHF)xcXh1+RpN1yACEZC<*5z^3bG;ECTF znLt6^$qiCfI@xUydYih`GdZy`{;h4?PpShA>EVD_!sHCBo~4Cqb}cWBH1AQyZhZ?S zVCwB=3X#?r9oqkk?IuPbr1EP^q80S>poz8e^JfOv z95@5NY$;9lrJVBjemxN=oF%OHM~jczQZ+Pvh$$Nv`LxuCT=13IZ49eHC4pZ8 z4+Zey@|Q4|qAapzVM=Novh|Pso;ur;8U~3Fm}<{D5X^-n6Gw|HU>bB|K90Qs!!M^DVFTFY&&d@~PQA#BlhAdDmcQAft$VJ3kLsdR+3ldys?*HWwdg;z zXrOQZr6A@~ zRJ1AWA#^?Pd`hnYuNnH*iB+>C1IG!UNtQBe4K<|)A`-VZif#So+r;?%b-PJFO548? zaKlYEO=kvbu|SDAx9-erD7Zy_!%PY}T|bPsa&A^`u0D3kR+rii8$4NTyn1)`0ZNmd zC5af~SQWiuzGB@W>SIK2Oj!uO^V( zulROUERRd@P;`G)E(zTD@bmHFV{q4viJ{rkYC*4Ke(UnFX>d{elg5O#e{d!{RH#vC z2)NP2f44f*h>Ox@DeC&G0oHi_(#9zy#K!ozjX>JZQ-`gxTLMq#JUC)A7$u)Q$7o2G zCuE>gtVGRl%rL3(x*tB!ha+B7Grh#F(zvFf0~oMw`1vFa2Ou9njjdHM~*ld2Z< z=KeNe9h!GzU$gF37e!bswtl`SvelaQ*BaAFp+oIJUjNB2$FA%m`-Q9AFK3s57<%!?FpJ!_!wjn{*sffB%%TD99m%3U9?sTS#-Yhh=KRvu!1%ujR({+hA z-R;VTe)J{Zp6^@YO)NaJ7?CMuh}`pH)V7t}Y&ovSCbiybP(EIuDhf6qJ^3P_6|67D z2;x%^gsg}5<_ia&O?6&S38o!lu-!(gu8kC73o&!oCM&e-M&^_F4bL+#zgA@?T8Ooi zR5;hu8dljgW!C~qkik1MNI#1mb&Hty!EnDh`AtO+Of-x8DgZ^M0={>c$Og-W-B-fQ z({vy2Bs2u48%shI_!+iXMP!e=sw%CZUlb!0%4Ar8K_KoWuXE! z9eix&SC+?Y>mfFNLbj%n@<${qu(599slm9u=)NU`hm5x-m*TJQXW-6k#(RAW`ix(RYES*1P|C=8z3A6Ow6C zp9Sd5Y)U5wtQkF;ms>-gnGaN4OS4;A*kpvc;}&<%xC$}&U0#T*N1Z(#$ApRh1@3CF zeJor4&CmfdcH_VXhEp-W#;ZrQuu!X2x0&M3qu#@!j8YB3?dA*M*TBW&^RX@gr6W?= z*R>i>nuTnjvgRoz5$A^D{aQq`iOOAJ*fQN$1|W6EZd=DL=<^>0u=5Eg0OTjYU0sSf z-C9F(DEqtR=RKpYLwI@jaXGqD{z@m9vO0Fsi=u#zg)aJ^=Y`uqpN!9K?37o_{J=3f zy|;0F$JgC|9JlmKj}~Qo2olKO6=dM_dR7s#RFTckB!}IQi9O3J2 zr5&4nCH)VH01H9tx9$@%OAK{*THiW;KjKwjAD4f422km5evglxOI&Yyl?NY{ZQTbU z&N+vVToOTxe6Zqn6$|d4q+jz1;9XzT*A^7lXLl$nwLm^Zv-EaAcZGs!Nou(U=pEZ( z%ll?-@m?)606Dw?egIsUFH<>I6g~DA&hOe@xPjs(2bBHVI3CQeQqlwT}h+$WwgWzm_InGa5-6PQ#{K62fD_^;>T$8R&RubS>(yBUgHG!o-$kVGK8 zs|_SQ)bRtN6iEK~QA$L$v#3iw*R@Bsb5nHK*UrC5osUlmwBw6p$XpY!55!7w!d3SP z25T+OX`w0`SGfJ5e`GMuZ+Poi26iGY+Lj6kBwgDWbt&a9Zm+8Eu8fe&7U^aP#Ug8OoI7krBYk#H{TR%DGVIp`eH|xHM%)Zqa8uP&$r^AU(kG zqr^>zas1D%6BxE`XrVNZmaCilLN|_iCNB7EtfB0N+%l<#Ii@}OGHF!M_7&)4INWcH z=V*mCMX1R%VmCBkrj#M9zt^3z@^Eb^B&Dh6s!JutoIwsp8)L30_?Xw>*T5PTA02o_ z^CL+Q4}H62x{d9u<0lsb;S^@{GNDUe{L}3{=+@qgHC4I z^W>tIzaW$3$ZW9Qdga<*s{;}(N8SB=_1B(J4#Yg9lKqby0@+8iURDa|1)x1C6^!Zl zuWl+7Lgc4HRB~dw#&BTmmSJq+w}mgB`~yJuKMc`+z@hfoL|n#Rr%b1tf1{RDA$8$uCu`!U4kb zGw$z%Z=yGKt-GSX+v>=ww0-9C1n+rKnW<&P3Dt!s)KFmeCxQ_FY}nGNf0fZ38$nkK z{zxG64;-vA*6Fupu}H+Uf5NA?0cy>zkQe5hsLVDYe@T~7zG#fdDI17ZE$>9DqviBr zPQ)6kO^8OGeWNM4(1T%~?o_o+drh-ww2tE3PJqyNH^CxQg1)8jsZP~bEzmiDXdHNE4@m@5xmrzF&Bt$*hG^iGG65&a`~KR}-~x+jlYPg-}( zvFqOITkkllZUa}CctA28Wzx!H`69I2RJt|`>cbK%`JhElhR8Lcg_KLMFN|7HzHHO} z;r1WA%^gLEX1G2gmsdQ)OhgW!e(G-`fADkiTLu_ulIOs(I1WS@br30t`tTaxf3j& ziM_dA6Ht~*cz*TAMLG0bUUMz#F%O9Qm9UdCcAYx^W_KObs+ZqsKdlR`lDiG5qtPX;l!V^54!BZ!kqk?ig@$f-$iL}>x3XXaFRdQlW_<)DO-NH$(*}jKJAbvPtrGpDb2rt; z=vgpTl=Yp5Llr7MHw)bVped7| zCYvlVn>R3!wRh`y$a++AXgxXV#q6o1B6$ldrX^pyYd~?|cX0PeOtKpL?uT1(kPTw< zlxgmB97bl3uYO%ls|Tnq1v%1n`YvLXIc%8%=h#d0ANF)hUa?m6X=4ydKdxvs+tMDV zs}t?X@7=ff20jT!9L-4FL`<1^2u(nIyg!VRrZQb3&psb@5i1@3`C2j7c=TCQafbuOx2pD2 zrGwompP9oZR5--9v;-$yWyti;?^4)#_tn6=q8JmNJB)x*-A9u1LNL~VO|!1k(krhE z{8X-_U~ljuDgCnS(-qnzZI8~c4yTPRl;C|tnjBtF zq1Z2~ac^E#kpcmb6xw&Bo=@sj%?&YcuC*zj<=DUh#*fhv$VT0=}TuHAPb zaQZ<4h_zSP^p#|~d_V7SKm5FdKf9e;TN7&07~qh;N4gGE`6EbAV7wGrPeY7$2kGr;QvN!m*Ss{n*%nbPf5!i`3R`4V3L1 zmvKn_Z{?Ac_vopTw2M{bR}0qRVqCh!M+r22oyQ`belH-WH;;*rb=c-QugW{2Vxr{A zCy$iomhB3eWDolvh0wdt{c>2VG@ff}FD_atARtL`fp#MGEEv z!^m@(hDZ|2h=x>^o((K^MTusu+&3v_r*r*HgK$>@9Zl>91e3yGw0x`CTKFtyqIb%B zZU+9O91!1vk0p?Yv}L#uvE_wztYtZ1+{DQe$Q|-y$Z8E0FQ7)CrMbZ#D@GwN7(5%w z=B3IuW%8%|zM25g=zJa6%k-yH@ZfvJ zym27i3&zvKgLqr2Ol!VdWV4wS>i?9}O|ke#=3`J~3*u1Q01Eb-9s~QN2$pR9Hjcj) zL|^PvV(9rlogP0%P!EyvGDWwSYVn*)!;Mj>9z7j}IX!yQ7q9k|*h*aSH^#wzDTX^-GOoHs$uy3e#+Yp9avU6-$zNi;Z%xOoJz1 z00ifoJ^Ao1lV2<v7Qi zc=r)6VYiXnsa<&=R<4W?_0&$eGkYtTz?y`?wYfdc&SO=;;8R!$W@wRb+u^7#8w;lx zPNIvc{P8Yf6Z-268uE+OA;m7N3UjBRGIc|sXxL-N#2gn$9+&8RQgGI`3Rjj*00ELz z93wKcP3Z&aoe?tt3fjHUPnqL_HQ0x}ZXwGfj(Pj&5{m=ZXj6E5jl-h;gfh%-`3DVt z#v89`J|u6MsG9S`MaCPPF4>)2aZlZHS1|k~K``E>tD;Eqek^BHXfH1#f zO$`Bz7WdoB0Wv<@DKO9Ivv4N0F(MI!JH{K=_cfED<;)Q7g6dD+i?`=rl}EnXcsCKN zFlmp`u>5SbhjTcY)hA$Xr_OHR+sln1LPrRrCJ8#~p{^h-3x6P)@pKDVn zGlO}GI_h88$aL6tiH+i_`Ku+ZS zffzp=N0M3jQ)-30zDjA6g1qIBvi!By$gR7`z3Q7r;tT(eS%3Qklv|vJ6`_j_g9P#Q6ICB}`752387OAegOz*EAk?H{+upFq z^Re3*%ADfgD>mPTos2G_{X16E<6)I7c*t^KRXK-%%bQo@PN^_LN2IQ;{73Evh- zanbDAWj|JD>lTWG(==&xqIG+){!l_E7l4G=Z|g1RzyNFW*8KAz>;T9tD0uYTi?BRx z$G;R2vbCREVB$`R}C@Y(!n58ap0 zz#!IG@h9TLlGDyOgsWqBm&%bB7k9TykzW*4%ZeS!agTMNw%S`^>B%rZ=MZ|;vbtB+ zxPk$O<0`*#Fzm17jwYgh6Zh;28cOgcd_$L1eT^5u8A6{5o(xf~uX-)q{5u(2itp{b zGQHc`Q%0Cuj~e)iI%M|Kj5s8|873LEM8-bYQk986vc5S7l84|9i@|3?!)C_I^M5^;Dj_!?;{+0 zCBzRwEJ~*;c%*hA*ZF#3o52w-GMyHv>>)3f%P{5{jpATuq5p57O-bzSODYs*x?c=U zIPd-r2-{m0Jw;UZqbPV*63@Gru4bC6Heazrh<1okcDz*RD_rp@hxznaqJA!Inb1AD@coB3 z#hn4B_^51^4>O584T>)ssZL;X8~gcu zQoVbVX9-xDdR!;0I-2uayNm1D(;X_n1Ye}38`Sw#ZvAbZ1L+Dy3NZ^`8vGZgn?cRdVgo=?8^-J8e|7^KvN|2m$UuOAPJ~Qp&+fC$- z!A+TUumwo<1yvVI@4y#F1U_=41ZAJG)%YmmlzSd;h*hv6-58j;obmf7efz`P`^M{; z*4WyE;%@;RdvhI?U-S^E;jT+SB?~3|gD9DlroDEa(eCD-;Yyl4gZ@?~uG=rHOw1%T zo<`))8{Iy^Q65|6KvJdD)Pve%$59=ZA39rvLe#s+iQPgaDF!BFb+TKhaEhMpn{QpS z=!#ESv{kJ{OcqRkJygn2`Y0(Qp>O}R$KyKh=8wxk$C+j4+0?;WA0hvYR+zSH-KQ7) zPx+0jF@x$>NfL^Z`@N1Lgk_s%Hrq`3!9XvAJNuhsg#`RRNE02i%|m15GvnaM&4Ygr zjG3b5ZyrT%j5!6Sa&YCzS4D2FITE!0w#&s8v=kFr8|?x4h>7&YeIVDC*C%!ra4pr! zeOss9-{fvC;3<&oMMxbGX1O*;a!8UNZyL1rF(7rkZgSV>$;gWvSGw=dSMR5r$@WyT zXo0Z6mgbqkn|A`vPW=j&(|4S&?SiUVcFBJdouo^b z6fMGc6vCo1l*N3~>oW{n{f`&%R`2q2ck;1-Ph%>fhgYeH9O`KCZEx5be`oMBu6HfPQ-O$>9HxS)SN{MrZfF@4eD0!k{xs!hL&wlANWP z(x$Uw>!E?|#<;w%r6k3B&%Av^ms&L0d=>iVbntpp1<6Ndt z2k;)uY>n}<;Z$}u2~!W@g^lkU(`T_6h1&wge){W7tw$YE9vIa}^Tg2(W{57=1*DsT z9~KO7uG-gCcJCSwan8EN^4373=zUmr4`+VZzw(I8yzmfvI@cj2|I)UNu+c5Y#{3bz znNgjp&C>gfELZcvcGVcXAt)6SjIVP&ur9e+h3i9y05~!6?RVMXSGu9w+IAAQP@MRU zEW8k1o2FBqw5~dABO>)pP&!Peki}>;1uJ8*&QqLRf7eR_C!)AU6o2F-Or0nk1?vFQ zpryRfQ`dCOvR|IyaBM+~BdwRv30z0s7_iuw90qC#hCr!MEDUNnu+ePpO*x~WQa zvz#T4ft0s*%wMOCSCdXkol+SVy&$-Waic8$~x4M+b(g4eP-#-8mqxfN%J_D@RG=%gGj#!M_S zb`XAKT>2CS*^$a&(y^p%r5GjUMBqgj_Zu zv32&jA&h0o+%~wTYz5Piom)8Fjl~8jYJl`tQa2)7kFZKTMqv_cJe1x!m|ks%!w9&s`XWd5Qo zc24Qtb0F75NA5a(Pp-3)G|3tFx}H7ZBCn|hJ+36V6D6)9?-IdY^(&vZ45EHuVCI?1 zcu&$eiWbk+X}~)XOZ0x?Cw}6=weY@T0Db_=`6$Pa3MebbhgrO?fYewbW#&&VUBGhK(vNbwUNr5L{+iP%BWd*jVvx$+ zgk1T`Hc+5t-T+PA}JU80A-7|)gyL83&=h!zpZmeVQc%e z?njK5cfRwTw-0t2{LE)Q^EBQRcE)lp#D(jQU{@-zNfs&J*$Si(rvdSojt&vhQIFX zzV1d~0f-gl?ND5UUIE*WfFV&@JxS2`EB3HSi3mppElC}O?(C0jkj#LIb z@2k``TDeILNIAtn1+VQe50bdj1MCsR)sfgz&I@_S+4Q53lBGE!v!s7)Ma#5P@59Xz zKvH3;pji#~KG(*5>Nl@+x77h0-?JOGbH~1djsVx;0)`djT=8m3XjpA8W$y3V@tJEHN1$t0ia~p^nh*M_3|gA=L)0{7P9?>qVGq zha=)vmv<9l#MxbM038{<3_h>XZ+VU;nygPWoz(SKnh>I%(AdIsd*mNxAK*$$!yu|` z(unLWly&*FewOvlqxYqmq2t=@2}yQa$G!hvIpe zOyYseYBk=Wog>XJ`I0ZWr91K}t}R~H-v843d!vO+nQ9k8&idgq%0QEHw<{Uoj{*iT zZW|so67`^;y1wU5gqFhGqP(qlVgPh6A1Ssx;;Dy$PsSFBg6SSHlTgd>V+j;vIbd0o z6^v9Xo-D^@1oZ)977-q?lsccg$4f_gSn1#L`)IVtLrz|L$Kip6egg&U#TQ?^^_&0v zpa1jSkwCpL*y+sRd!SrNVv(4kN7-m{NB5O2>ExbKLLR4f^1>K}GF|bpj)9cVrELcH zy!`UZ_w+f&i-|tB1~u~1I;Zsse#_5@c=x;C{d5^2h${qdZvlEfOZ+Tzi+WaE9H9xw@lrGzCDt>g=2Y^yUM(mq<*!lPp<0t>=n)JB+V zEH%d69>4&`^~O0^1eW}^uCF1mECnk<1oeQ-hbFO7281@gEh8P!F|MNEtiq8?zqS}r zk?SobbW}xib})9)*0vPwqbYef3R%^HAkb;1o|QAYqH?!4s2Gm!aTPVx`92`9xDyf} zmEICEH8p;7@ zHKc(=?@45N?`&l?4JAn>b0n0IR--ly#y6;0LX;EGd~ZECM9a-ekLUL)Pc0ny?3%%e zzqfi^rM$uRf~5?UU<*0W%NV>eXmGZcvAMoFay|AYuH-q-=+d(D=<_t0RO3KQT z!qw=>! zU|j*MClD;7d(D>W*R3ZEw%ji#L88#a!;EA?PtYS89_VnmfJc@L?ZR(vNH9}4gIb3T z>)e)ip0T}6LtxFKFl(}6bd(sawXWy21A$k5J`oE_jdgqQp%e+L5EbrVXUILUmP#R|#gKL2I)63{f#;6fwlQt+@kXSNp?|g*F z;-rg3WZ@VL5tRQK;;Ee-^r{1>*X(H|Zjq}}mL9cf$x%RmgjY%{&y+pLtF2yGwa=p7 zUJIlH5(@-MY5qO?XjHptZ^(8BPeOQNS(76;j&X&X%Z#*QC3im6w^lp2kKw0MXCbd< z$JS19gtyd@kb*?d>PSGiQb8{bK**SHT#k{NVLTE?)bSGH?Sb~hHoAp4iQGGa!QYx3 z%B7h)u8pi7`741WuDIRwnW1HKi4h~^zx>`47U6FlZhbKR;PsvH3Xy{==dK> zICr!vEgQ6VYga*?cdIQOjgma%+_C3Pd4?7L}b@U{%@-LWv3p z6vq-WL6Q%t`?Rs^HSRqJ*j8!jJj?i2dg+8UFzftycc~AX5rNq}l9E^i? zX2Y>{n~4xqsdG;T@VEk~7?M1=3M{3!r2Wq(gKFfal(|67{qjEiPsPWg*D`m4T*lo) zczRUN_Grby+8XaCmETlbwY;oy=dMUzVX4(D{iimcDFUiiR&61Ixx09DN%WF$aj-t* zh7zgkShkG0NN>bmIP&LM<58?8srECeO$8W zN5RXdJRiv)gSvAj63_$`1SV%>=;7kI-ph1IfLUdw^S8HRmQogL)2TVX&>kfQNsC$Y znNdn!rMv=;Ca<_F+?AARPB2(Y2!S)TWpC1?oJRCoV6n_eq)xMhTztT zohv|lyY(RJ^=^c$x0>fgN&eh9Pak1>zhcZQ)YIPNRqJP!w5QhXeG7pFFs|Q1JFtDB zKcj6!4(SOH3GFa}`>;$Mb;I~rd$rk=ovg=JFWqQfuQE;!O<>L9eWhn6t=}VqiewbI zj%XdTj&CWS9%Y+SiY)M*=yByS@0^V(9SCVyFeaU`yIE|G9L|Xh@C@ z651uR-=m|4Ay;zFGO$MQx&q{K!80p99+_h8Kp2rrGxY%}Z-Ewhk9u84CbppK;lpuK zUQcq11nZTT70NQT{#)0!e!fLu@my(IHRnpxzM}3x@@g%?Jr0y*S0NMj0>=${ii3>8 zL`RCG*5f|oXOYMv(YR$?Pua!HgJ-uzSE4N3$B+aTy{|@w*O+n&;)nuGvebJF_D>9N zEPY(UIv-KQJ*CbPBDw1scB=U-c_*F>($`)$|H!AyQMNZi+NeA!yfU`}xG$6;=ZyvA z+C0r3%g!VE8q>o)s4MiH+6lc98#+?w(nhxaFAPXv zNrQZ0KcI6kmQw_|nZVL#%XIZ|OOVOqUPs?Di0U+==|!$@Ik+P&Dw6p2VrI<@Prxizs+R8%=H|n1~4u?m| z91ZTyP#UW#GGJJQQi&oHxt7G67B&_Ul}gh~Ka~ermq*vDBp@k#doKk$noL?`R(qg4 zXIe(sy8c@cSNtBqs6t&{&Fjj7R($mY%3kF&g52swh(tWHyyxoin!BP}L>71b{ypWhH(78cpgu-jHrS#raxz0-TXIdxLu)JKGQx#4Qe%-N z_awQb>yyh0G06cUD_5UVc3~``hc7*{qV1uy-Hgfy%z~i^EHt1QJGy3rQy6&(AyFg1 zONgi3xh=@$Bc(7~^(Ps6?_PbayvKXy9^gC4xLK_UVru{?$zSvt`dV4m3w?k=d}Mjt zYw&MHUX5T(vES3{>S{>I4laYTX5II|NU|$s(AA`sO20G>Nt(zV3waKJtio}$^VxRN z^mGpSU!Ok;atV)IMp!H7woW9<=Z+w6j{xccUMHiB)j558YnppO>bA8&z9E}1_AXsD z4Q+!;ST>k-jXqBT3M7^nAB)H2?(YEOW5F8>AGs9NdcLPeqe(yHakRTW1)#>(%l>E*6TU8i*b26|7$$HELe zy@X~&YNG8(NZDq^!O}YXmi$I!^3};JE}0t1b}G@Cd!^}-9XTD+l6!KpqZCNPnj~2$ zgD1!7nQL7qCqB?e=#ho-AqBbfJAmNu7*{}sVO;UrqCOtgoflD6k6{R`k(Lfdg{4-W zymaI>^4Mq%mob#0>%FzYEAPvdO$kcNDJnR&JV!qR)I$HCFa zD~VE_u*dUTlV~;RfiR&SRco7E5xT4*Hnu(|?}2PW9iToyN@?QDvsr1|zVgZ|HzG^N z$MWoYE!P*?V+aC^%H$}J4X>8**XhXbQ9;G9#%ri0ag|cwQe`L&+*Z%@o-KbviO>QO z${Y=U5?PweV!B5{KA%f7WPhw}v$^-uLcRujD@0es(Yp~wl$b4Px43r{@``}msohEE zYS84zQZ`>j4-zF;wmAaFN{8b;>rwVY9K*Pb@ptuy?a(q$?iR^oQeL-`uby!^lFZ#3 zqmx$}N66JylcPLe3mFG%jW4gk^OD<|jy?xSxx{b^7#m0~Mo4zb8ODp|vciZ>y3hwh z5LhF1?9}XIkX~3vJlp!+GTqYi9#LOAX0!rbNXBZ!gakNIk=;Kz(i@=&J)XQ&DX-3bDCToud+V3;Z zJhS9{1`$2fx<(!=@gDU+8N?Wri_o}_sMl@j{a#uG2w=!75?K)vi-4_%Iwg^1dHJq- z?vF2e)0^J(eRl_9*1+u=XKAc*d*qsTYN=d!&yVIS!th%Ry}VZoK7Ad@S18At_#+`` zJr7{p=S=3PZAcPqx$=yhtIdP;jH@fNd*Lj~atrcG{?~nCZ;)Vy++I5j#=#}uGO#Nr z7nb7L7Z&l6x;A%Ce#@nW5}Z(y8=9exW7#tN$r)LS*ce{}J;SMC$J4tUafY(XytY|#4 zJzx=7?7v&vx@B}&=X0|)i^ysZEf;z|=cu$xysqT;(d~`P1(!iy29%XG>$=KtKeW^t z^u!RyZB4G=KRu%vkaw>-FEy4&hc!XxjTMplEs?>w>(2@XqrNh7x?-!ev@MXkJ_Wgq zaG@<~WvR3&xU3KpTJWx-&6n~B<#VA&-~-#wTh?pI#HDL&$Dst)OaW6%1=p;N6Yp5N z<3=xdRZ7(#MukX`?0CccjM6;N!IfRu5y!nz{7K%{!hGgjz|~q?m?ozq|(nl=i|Z zoq5skD|ZJZnK0_Eh8#plWR(v3(HSv$45-<7U?GmyKOhm7G; zw?$snL(9*#yyG~?aXZzXBiHacrpcI-n#iKj0mBl8OON%?xck0{AVJ(QNY<%kfyj{pfJ1HGpp zy|wU-dt`j9t?g#P#~~7tM)?_Gku9lfM{C&HvuIRhL9_Jow=UO|5*bZjmxJD=k2Cs= zg(a_t;#})(Xw68-rG}c&8U->4JW%rfxpt?|M~$C_de8;FMsDvZ=UNe0*8ii4D|%gd zaejbOV*iR@*=bUCl}`-T*xE8pOP1^QUP5-s-}K1R{Tj3FI7cF@Wm_0ok0Q2^^W2)A zkUKE9lC@j%H#=sGd8N^+Keb55(;p)`=axw$E?-{D2z_{VU2Qrwc7gQZ#bybRZ5SU? zP91t|;tsg51wmr%<>h-dECOo-v^P-7NU+Y0*r00!vli~HVGS6mvi1x(x_WwPde5}3 zlO9p}IS^KQM?%jF%Tm(ivpvO~zuA{0nZ@5DD0|F<+!#Q%liJyph5bPywiLRKd)40- z^2+MRqs;oF{NxU5mKUOw7lb^vl&8F`Ssqw<=yujq9_PkjUZeA7LFy-uzTl0mCw=fA z<2K{U)l53+$&^|8U2Q#5uhRFoiuZF>;)?AC#_!c*URh|_9z1>9BR^{U3i^cHjd0;U ztjYSC!0O&PKBFW(>RviNmIvLAxKthYVhQj}VUuRS?mY>WcP0ipWf0BWP@_V6Z$iNu zTr30GA`4S9d=|WSOU=+Sm^%cP6m;4PYm36@JzFj{q;f8|6(5DrvJC51M)o4O`k^GA zn}wr@tCI7Yv>L(dDiUm3PoP+Y*21gh!X1aCe3mootIT33^@yrLD|xQ#RK~~BWVMWs zRk}ffHo%x>>e!K}&4-pRGHz;4Zd&I&-R!Ca7H|g7t6tbD7p#e4i^S6RY{f{ig-1qB z{YLKDLS&Il=CVRh&hfZxF9<7xd+3d|yzts!cLJ-md-jpA7-JsSnCYE4t2Rm;EKdRS z6w4N6oyvc1rXJ-6Aq7Dv(~Abewq|^+eY zjL~KbEX7clyLC^_b3vw^dw!09rNV{svx1wZ2$qs#9uK9^;$w~JsHUB3g8l^h_`0SNL=t?jcp}mmK#^j3QxxwLC!{H zzP^s0%hs64Wrd7y$$;?QyX)V38)YS^$%}W79uq7tgw*{OMvLpY2T)!z`12Xjx=wRM zgw~>80CP0x~Qz zIkI45R|4zIZgbYm+nxqpOV9(W1ihDE$TF4B(H>dyw?!&?#w*V0T?+L~pGpf#r2x;8&*;}r$jLlJqD+Xz|j6n;Fq%DJ# z^}5VtOhZeC==R=wyqf{m_{!r)VhfQ)JwOwj48Y7~h0$0hBlgYOJmp9Ny_LPz$s%cw zri1Jaw68OhSAb_9)zo`!IhDu=YYeC%uy_y2@I_kKs3iw^@0RspOjsu z?N+pd7hZVbmd5P6j2?yEO035g#YaOECH(EVn|ccGXo~Pw1!9W;@{sdHvIZB6(30mP z>B}^!q(#73SSc^8k{KT_kNO&Kz_qUBZ}d$X%~ak;oBh=NO6~$_krF(o(^%LB5}v7@ z@OnPG_WY>C727Bc;}S?YBLA;;?t|r{XK7_{{K$Ab+L+xN78&8m*DVIAhmtgF$5+CO zj|DJ3R&-h6Xy_>;bXjnmi0E4S_|bBCPq5t3rm(c=Dssh}6o{f!25%)rQo3cy^RfI4 z^<10I8DNbaEyj(l>D0(Z$T$*E^wy2YIOY@guuZ_}VJ$0+W0#UDG5lwPZm7~rB#IG* zSjjr=J@c>07k*pyVEqPi9t|E!+c0Bc>1WGerx8SyIca=t0lh$wZz|~{?wldxmPjJP z>wntVU#N%NGJOx^+JEZ2KBq~mqsc26%j|1gu*jvPfN^0(}88;yRo_Xe(+p@siYBMe8&?a7f`Q^J8Uwkp? z$+d7F-B~3n=}R!rrQ~qeyd&XxtMS{L+3V5yOO_83(hEz19!{;{m522|S4Ql&^b8@H z#lAdBTh?TRB(x-!ao-NIe0#Nn62r+mo+GY$^uZ{o@K{R*Tco|;rdzU@lPZ~YB>q;jSdA(fLYk3%9_FNKKXGF9v^+cB?V^eKNj^9@S$AK%8 zS9{6B+Va(MCMtJ4;9buwFD#TyDr{{FTHbG|_ZlJ#6OwOu!y9gWI%P9j<0sk$;$z`+ zwKh_N?n?-34F9uW<^hQeb_uo$b}J8&Yqk(7QDURE4Rh;M>^>o}*G?oYj0={pj1xme z(<6-bhDXjtJ@yvLu*VEyEqUc#lQOvX0{an^oE9^UDM%S!BhSwWl)awe^u~{xcH+s~ zT>5+TrN}dKd6nm7+e#7Id&t|8XGE`+*Kt{)^!g<@A;rxXj#yr8fpt}zk6Jy!8;d>i ziocJXP}m#nCs!x0fEIlvl7{C=rRA`cW!^;S*81X-u{9>Qhb8y6jPH?2DGiJP+-Wcp zA4@(9|8YHo{pX0VE2ArcC5_&zLJPZD42i9AZh9+lolZ9=NvD{i9r8HXCm7E`exB~EQ^kht3 z(=wl{y+4Ew&>baqQvaDwPD!rDK9%QLevV%5Ulj7+>Js3$hc-5?A2=hv+IfM~s~lMT>lwkXNG) z;F1t3xu-W$0|(D}-Zz9)98!6%UE;(1K>)!EOQY9}qxG&S!(Nw@W$@<)0`8szvJRgS zmkoPH=Nc5sQLDJ+(y1k{taNmIw4*@7mx@dZCHYMC)0EM8Wq7mdt;Tz%=cRA8MbB$V zlU-U)TWNZ2JvED*x<{U~beUBCtY@`Gih%R3_v)$SncT(KDpwFV@VLgfzbCfHx-Iv~ z`?aoQ={WKpUUN0s1lN@nyz&{ z$2n`)UdG4bGLSvwWa)cZD81JsUv*i?@B^A~y&5nUEb{6#L}XVajV=0aO}pRHc5y$* zh!&v)W(Lc#^%z_u3!~%5mONpSA7mDH9!xng$h-i!p3V?6%a4|2+l|1QmAnG90=BiV za|+$40!$KEBOCUqx{4^&lDN`ov}(s(N~mLDjSwt91*<$$(C10qF)gX=kJz3xA$mmx zI|>q$HSITIax&1f#d%16x(ge|beyCntL7HXf7OG6u& z-g(OOBju(?QhL_{B}A5Wt&ESQC;RXpV?H-*=rz_KQQqD&^`xhsRFKE7Hol^4uv6J0 zuO7mhKrTT`IWFx6O(e+wwfU90@XWSy4!UeolO!!sI}TZ6UF)%g-j}ckNo1w;IX#($ zd*I~@kA9F@v&oW{GQZ24b3mURB?GKCiwewYP|!Fn>A-u#5{9y~Th{>5cWU)sEK5CD z(OvXNctk)6fe-Si#KJVSrnpmM176gwrx<~3WHM2>j z<;3@e5U1iHXRwzMJ_kzbX{#aZO%iD1=qS+Zs&)J~k8tqvu=bkV8Y?;j46S_X-_!RLl%jG|n7Ig-arP?!;yGyl_6E$P6m4^H-xyJ&RR!UFUMP9w? zd39!Qn-Hgtxk&fLXnE9h_ARi=I(M!7 z?|EtUh)o5Bj`48h%*&RgSbHO90OaoV1~4l9n$Q|GcGkkHh!C(X3~{UPYNO~Vu`e09)qKn%hvW>YfzmHHRMcG-_iP=JkAftFim8^8;gP9w{8-%cfEPfOL_8* zBCC%8J+BsdmB*H`YLrzVCE$e0naAhcyY-X@Ey*!$+t)aCq)1Z82oO@31wl<@Lq3$_B~2_Yj1EHddc z_8l!qz49#~KzXkuv#db53&$fxV6`Bw^fi_tG=kSvk62eVNEw$`C$TK!`O0O|qu-3C z`|LfTrk|aPkHy(`TvJPaZ}I-9L5{p4bibk=c_mPnfnhqz_%J$JEro4it9aK~P71aC z5dD8v-9LqBJ@y2R&)Ri4l-rjE~h@=Ju|?T-r^0O>Q0M z*>OhWx;DsQF9JwHlUG*xTQj5bULM!z8EloYGUT%@1$QP`9x^Q;y;~rVu>{kLGqP|D z=mu{QOSCwu@}%T(GIC>jEt)jR{+XDFX`g(g)*eZ%~H>$y&%1!_&;}jY5J*i zUVJQ+7mO4vA1R4tqV<~SJ+(5kIeP=`4ef8lEwH7bZh6kOCK+b|XDGFdT10p` zEO}pZ|K2F|+AJNja-QELvMl`q=V5GM2Hlzvkk{$|CA0rE$jNEXOXbRa3-3S6Ql8P! zWAe*FtG>Ne2k5o2!%^_$tUksuxh1sBmUdz9GHy9u@H})(5Lu8Vl&9W(TCc`9f*|iN zzWCxj=ZMxiYwL0?u@{?64RBz-GAu8kGmu!iF_kpds6ktrmY1fk1MS``|Le5n@7{_R zml5h+vFL?$hQ5?jdM!^l>wF6If+1Lb5rSl)Eu^PruI{7fG>MhFzc)ypjy$8D8gFv_ z&bsa_K;2z=x1NQvnO%KfsotZXBh!#U&NZpZB}H;sp`Jh-y$zQbAZG;L8_Nb!e+%W% z1Vn8bJ^P7e+togkdh6Ld^}MpM?6OvMrF9o=^QG+bRw!w|kueEl06qN~AIpQK|1mxm z$S_HSwL*__Otl?(Zu6UvyqaOKYB8urJEeZ+%!4^y!lSd6z4B1<>=a3r!d~7y5GW8P z`dPDiVMWVIlShQ*D zIg!^|FE1VEHf!U1c&xO-5eCo^ou)NPXa6jNsTXAV<~*}<*t0D^5lag6j)XILVbyr# zMcYy8nU69q-Lftz%w-ImqY05S!i$%eD`!i|7^R-*bv4Q)O-Wf;vvE;bct+^5TjbTX zQ8EtIcwu=YmhP7_(7PmAY1m@ik`ppDD9L~1x|FVUHAv4o#_3#Wi_-pA+pi2yeC!33D-<3bT(~xH{^%&3 zacO06(nyfI8p`DxS5&%tK)2hOi7U35nKlfFkoZ;~ipa*9!E%v`-rll)VGN}DK@K$} z7N40rE>|+>Wrg^SS#!#xQr)1nVH_o|N+vyL2i}u$5f_e!*Y~3L>M>E<5!Q8E+Bt22 zna89QDRIPmSwxnErwjFzStVo^ulFWGxFUc%4|+tF)n;LP!W)aRgljiy)9FXAPu)|J z?k3HgYxx)A2A5~FjXcQDAXuZqAceh2Bj#B@clI3#TcET*MEej)cLsvzY{ptnv>hY~ zB6X3HgVz0fyM1#R>P+KX)UfnsDQ6jvN@0-#z|vi=3E9p|QA>P9!Lcc|tPr2ba_yF5 zs3(`@dF%QsjH!6X<#}};SZ$fGJbL7@+V+nAyvL4ldqT^L-VeaK~n_%5v}-(E9t9%CC3 zL@fWK2n;BtmKPTOFH+?`tijN`Cfc`1!b>9;Wqo#Qdt7U&7L$gDUhC#>@Ie#<_46u1Gv*_Q66ly4~mCC(;y zBsndQE&b)1u-bj;#9XPoN|9BmWg^nZ(AVhrSn?UI+IEe>QG4%f;4+@&d37CFWLGP~ zcJ^h2UcQfhpH|P8wqpy~W_c+^()Gp?@-lCD!y9g7RL)aZ+sRy32oe=UR!$dA497lQ+QVC@sM}o1(uF%(dv=M6- z#yaOgE|F%;tQ9va4_&raf3%3JJ!OS_rZxc2gqrd^V>#$?Yw0i7Ll5JlB+c6A(lC+Z zk4#g>$C4YDl%O_m9yxx6@saUkmMj?;C8R*k115K#-?cJ^6Q)P+bi4(*iR0*Q_7T)f zKx~Gd9A=aE-3kNP*S zE$%6gzOc+zH-z!g#RcdP|hFfkzcySQ2`v zyS$#B!t^AK<|{WoZaH^Wxxz`0vyfL;7z291Dz_~J7Jy0X5eTf-ZK9|Bt8Ko$kRx-p zrdvY367qVC1&ED>HU&~jJ4k5ga^yXX?^jcQDN?F5Jz3tozqqHIb*8!%&RRCL0%))D zusp9)URS(kl#K|Wd_qWQA>%E{T4)20-A~OL0Bcu6A98@vqunLBP&%N zHRDuj;z56xdh5>sl2`CdSUTDMs39p@6B{}`>wgW92IF8I-L`7W%bO71O6*zB@#;Y5 z!OBbP_Q2=0Mr~f@ebjZ~RfUf?>24i^JxT%$WEja+&n~j+#L}ZI+rUaMr+*a@SZmk8 z>*6SuI|^?ANeu+_!WaQG?zI;dmDJ^hwI3`)R{xg&*^XF;+PE08zx0MRII(Pw0*ya! zm#?eAQ(~f|%`9YrrLbB3n7<`*?bRE1_GsspV!jtVSy+0ncb}C$5G4=gJ$uTWEd~dX zYOC@X33zK+A&d^{4Hi-F<*|mu_Ku%z++&$9^6D5!gLo9Oz?-P3h3vOyL(4j|((*`^ z$oMicN(eHq4dOVL6-pw@f~C`-UB2+b3%C10WYMX@BN9D=DyOeRCR}9tU-YIoz3Kbz z0+0jdf{#|^Ghzpm@fAvx)x8uMZ&qD*DtTRQ>(MN=kvW!uk^j^7Z;|tax)?{!6;GUoyD|91oEYqW!LC2Z+zn$@80o_cicW8us-*> z&)xmlkNw!)um0+<-p)sid;J@v)gSzWfAE$j($C$ak9kVDH~XpK$*&Sp%1gK8cX zQM^2QM3|Y*Ti^QDY%jx2x%Ko5uVOX@zXY7QPVH(y$eB263+O$ND)Uj>G!5>TUw-*P zC%(##gl9mmo=~SWtk0OK3dCOZKoCA^dna_OY?mzs8|8Vopilp@o-|!80f9MbWp&Nmv@!8LQ_U^mB z>$|Fm5sB!1t*^Txwvfvj2HH7xfD{8CIGHi};db*x4p$P*zwrv&N3&p~sw( z`)aODwSVuMBy!0_zXZsI=bn3RIx0*Nd8(DIAp(o*=ofrME64h;?;qLFf_G4azydfUxCeoi5@PZig07S! zg3DfXIZI=FVLqh#wCpF+7?>TN;^Otq7VphL)gvjEArePU@l1_-sq=dP&xS00>7|$M z855WYD3zmM_GMpo_oF}hqqlDl|K{KPn;V%0QcDA5)pvZycier&SA4|-Z!6-LfBBd1 z-uvG7hKR6*aZoF>QpR{xzw!uW&Xjx0L?|OYZ!9k#mT@n~th0<;#9B5u9(obRscSsa z*80yrx5e&x_St7|w$|u~*sbV0tx0Wb;w%L(Z%2|?`W;&3WlI|eiIs|vMOZ`@Jh9-B z716CMTirUBLpBB$zXaXvfgUXI+#5gW>8&Tr^m9@kD3M^mvjJlW zm&Kd~XR+f(eUFxQoYfykL@tk%O}(DmqAeV4e@orBrH)^cmb{L#FGAjHE(7BUJl^3& zj)}wCd`FQau$H$+IV{B{r9jU%@Nw!a?K;Htl4eKNpIXBktLV01Ns@IeR)Ql)${6X^>ozOo||mb zI!Fz+#L(IsBekn79&cyW7fVPic`a-W1bWZOLTem=-UT8HpHzVOt#B=QdIBuOkZSze z)mvV#?-^YofMBg@7e@&OU7j-;{>uw%fnXcvl5Ub&bTc2hO{WYXiPCqV*VPPVa7Bzz zCwjSi3!MhBsy_6g4<)am*Hy~<3MAMfulhoJx_e}l_g|)ydPZwR^*}v2=gC!h9ha(G z&*Uz=KI2>asbkg~-(*ZbL9<&QNHAm!;%(322b^P}5i zDn0GJi?~+s$cpUbEgdZI8(vt@bFe8{kIg;Y7+9RGStx^SC|a?Q*ATk1%wUKy4pvmb z0*+90tU+a_-84~VURf{i$OTR^Fu4D$N_R>LlGjL(xGEW=-**e;IBMxiYm^#Gyk55HsQzeO z=amz64w>GWJ+CMmKwgcyxlbvsGRBSco-G{`kk%|aj~|goO~!21?R0utUdrEl*y+|Y zti08vTl#FsMoyY@bC6Venh><&W2F$SOOwFjEdN3|yhhLeR)x$q(4cLUu&KS3ooI)g zv0byxSYB6)U|x{m>^e!>k>!e(lTk7p?}tFxIU~ax{Bz|p!tC4CAQe!lpm~!%CF$xo z44(H%4d96dyzOmodvFdr5`w()0=|FbBOkf@PygvZ-CY?GCDrPWGxkx-3oLhS3K2sl zS57&3$QgBB%VTFFuK>IsybNY0ucCVJLLMG*;Qddfv8AtoG?+opKf2W^sMDa%@5MGnKf(+;H}L5pBYUMAefAkVuOfY;r2iaQ zC%w^%QGKf=ws^W(GCD_E>1UVpmlkEC^H`iW_ z>}oj)LZD5q2|z*%$p^Ul$>AbEHd8(DOv@NVPXC1utT-A@3lsYWr`bZWiW1v@fBp!0487L~uR5 z6Lr7MdHSTD^-I6>OE*ue-}SqG*X=*ZDJ(6tystoBf%NKusC<#cP|NlonZ?hGJ#h4E$KKGxV+2WuSJLaxlPj8NyV7s;*v zOL?|cE=6UZb)VKLWLkU3%iK5`xj&Lm{cg~wNc`sBW4PDp%q{P$evq?? z{I5SVpw#o{==YkP=s|f~2E1O2ypV@Qrdt2?J&`nW&(!yNpB|7hM+QGOW z!+wAq#g2tJB1-EA7)ub~{qf_+cmMDI{lDUN^V9>2BkHQ%nBVq#L~^+Ah3vQD`|B)m1f#HIvbb{9<=4z030%arW`8v=2n>s}@86 zQPVfrr?^SaNa!JlN}nAa^P(uRWvx8v`j%ttqXYrgqr9YC-tvqRB8wBw4Dk_d^K9pg zk5w|E{yLe+T8=ahQcBDSkns?5#%Qlj8pRpfHOknU73GZR!ugQ$bdbOGrzU-X1QR{8 zTF1@8^Kvta(mSm5xv6whUN$Y#U)T?k@y6;8TEWcqmz4L5cb^s8>gRv{=WjvVOVZKj zJ&&7GJ;6(-250UMR$Gz(^))#}+FGPeymoPy$Y%s8(mxeeL_Tx07>gdxNM3Cz_ZjLe zhZ_B-1~sHft^LDy88r@;N675`>{j+=%e+5wCYe1_DK+8L61|Bmi~)#`1#c_{d-q_C zW!QA*#TQ?^d1ZMX^b$7@EY5hJL698*uOZely3rZ1Bf-W>A}fbI1{VtqW_=dmU1VGr z;_6;lXEvrY9pda`yP>|KX=COom; z{N^{`{g&VITkihjfBcVkAN}Y@ALM0W9C$J%jo^eMgV(Ocj8)+e(ExE>Xn%+kjsYRRsnKu-y&n5Slw(SWz^ zIFN(xpwa+83qWAK^2#d@1VZU@t6A~nNt@*_qhREI?>o;OZ z>VBUxxYzw0r0X^`Jcf8~7ZEt(q1Fx@zSD|Hv zJhoNIul0aU{g!Q59wRIRQr{y{BJVse#MClyl33Ag*7pMP1mX$=)~L|+S99;yXV;!T z61Dv|a;?`l^)b&IlKsV+c#Z)52|K=xHWBa1mfkiVk<$rlFp^$ZIvG-vcJFj}9z4PS z{lEYBsl!X^J{+C(TN7>@#gR@4=}u`75D?ku20=i95u>{Vsf})t8Z|b=b;vGgbt5UDHDQc!! z5xa;>nSOWEk-JXlS4l?wIAaq;lk8ny{kZMP=yv>oQ$d}lvy%27pz-rmD|ks&?$8iF zY~{=V=WzyYw)LL0E!R}=)8oG7ePuf;^x;hJQF&bbt^yT&^wEFy47mD{ByH90Aul3hnl*Ox7d?yLDh40xzH8 zt+oy16Ju}dff`SJ^WbHwzg9+aY3N|cNY`89B^+!kZfs;~r8*)}B6%-w2ShTzHcus4 z(yH@Qmb_IvHq*S$k0Fl`>ok6@C^rc9#iJu6#n{%WIZ2~5j#!`A%pt?2_sOQ4!nN49 zVskDX@|Kj_kJ_8Q2v926S=I5;v{ztu2}_;ovv(N2wu(r>?~P5enH4e352d5Xpz?&d z6%}N}At<%&x#ze@<-@jr=oR_ndb?f-I?aC-ExhV&7y_%2!~q))m@P*8Ke~7x zjv1ny_6|8Nc&oWU-T8oepazdvv?u<=^z86s1)y|LoXId98dJ=2&MK|Dz=RY%8woBo^NWIHh*ZQD zU6wq|@_VdykEftCyvK#abqpgQ#S2qod;5(~b++Xwu93UnE12F$0H-tMh5M$O|N&wgWnYIcjtDT%h`u|W5wB5TKbY!)!dtA^>=keKP1BP+;lGl@@F{k?uRB(eQWetvb)>I? zTq1tDZUag`?Tl{ceQ~X1ZQX_lo9ukVU939kZ=(8{&zDVM)A=xhx*J(G4xTn%PK?RH zh(3vn0ur?wxi=A5&n)y*bfVHS8D)x=v=&oqXC6Ow1XAa&&(0bgYfyp=L=S+?sT~o8 z5)uaPeOyf2k}~rQ^|qJ)HPZ48*;X7;zR^qjG-7;s_JO>kPA#VZe%utD%S0xzYhn7w z?9hXxxr}Zd_eFT(GVyqgqDCn^$F&uI8NZ!I1ltwIpr6u;L3~C?LlEbA`7QzYq3$qk4js^wfP1kZkMZ-Ik^;{WbHq1WKTb<@iz zRdJTtg^r=pW&>ul)qiKUI!;)EXyYw?$+uJxcs3C&3j;XPToMMb&S+e zM)#FJ*brYt%UnFRag#?ty6LD1nr`bo)g-=ti6mX!_@nL+Iv~CMX&e%>g0p9*! zS#+WMi%XcffOtfumv9pEOCjY#{}2Nem>N=1(q_)2KTYJzRA@v$akp@?V&|J0jBEsB zX_HDtvJzGBxOZbhrxB#Qp`dm=?>_^M#Ppx=hW+VoK5~03j67QXVQ~5Q?rZni5nbph zohOp`Uq$5V=wo&FMT^JkKa}rr*T2e+KlRaBpvQ;R$J@mT<+AXz?`)4=zmKn2x;HPs z%xbRP{e!*)I^Xw@-}M~&?=xNlwvLP0?spGm2(=z9ACRG~xBuX+n2++9kC?pZvwtwr zJTON7ap$q)HpB8dBM|k&t3zVtN%v_&a`0bU@(EK7E*|ngInM*h@t39v!EiuB!dqR$ zo>(Cb{fR%Wt!1&DQ0DdQMVbUf^{v5+q{FJ+ zJgDD&uE9!|$#P{mP!Ty?`poM7fqT2$9&9k2?+>`S>l_pW+io{Htfi{_$E|MHHjdyN z=-6!929qSe5KydnTD7_om@#Ad`7L7QH`C4~>(3K_;N>$y4vJTnw@sFTmiQEkUc=dA$+U1Nt_Ts$O*GzPYsZ-xh-V7DP*!fuYJ7e?gA3*g$H0;Up!#CA1{}> zPv{eBu3$jn-|@t z9s&!MV>{-lH8Yv}OvRwgSt+UZ8Djqix2a>GLE^kK89PsC!6_3rq1o97Y`@w4y-dVgG>?(HN~Qt$on5f9ju;fq6Fhbx zh4%ND<0zjGq8cJpCIPe^4HR{GJ-z`?<*+oQVW$7s0r_AY8`A5L+4hwt!m4P)uzR+C zavN}BQKf4CA{eD3M87lf$OfzGWLFnF5d!8Lkk#MU&I1faxH`V8j zNnN{Xyg4enxq$B=s_0;d^Zp+L+P91~0tB|SKfCZ}s0yf|#JI>?f$gRjvL_;Zp(9c* zC4PP|OdwmHJjr=`lTIVA_k}Gb@r-&ucgo{-z0q;;kYKPbHflA{|COen$%^Vt_gw<6 zXzh$Ink&<1n0)BNXvF$YTOPKrHKUmxk>5gt3UbZZ`qf};dk!MC_BskA-XNCVQh(YM zoQOSPPlz@;1g3=oVwMi2ar(7wK4Zd}Hz7fhDrj_UX+o+FS3trR^~5+5%lDp37-r5G zAO}|w5z2i6(qU)n_wSHp|klwKl9S zLfDYE!#A}^DT5jK#s{DKLH}`WBKshYgJ4K^)U=;)go>?7QKfO7X-PW|nP<$$bm)3P zai$jtok%b2@MT&Qkt=6oRL8Rws8S;cq*Fxvh92gw1X|vdT0%uv-V@PF4`V0UUbAsH zqOOHCh5LVD7vgP@Jf1$$$DJUud)DPe?l*S2K#o4YMuo17JeyF@0k34U9^j*jjc1HQ zFN{}@etDKz_qs4uF9ZmD-IZ`S@+Ub|6lcvdmWWBN^ASQ8Oa_~+xF+fwK}{duEIV4H z4P%rT4ZzdGBDz<9mq)8Rj+`Hv@9!FaPIx8AC(If?Hw`{)FrZzHsolzV1923{5#ui&7tJ(&_$Vz9(UzmAK=KmtZrk zMypu>o!#@>=O5zg88&vo#)kP8Cts)yNx0I$7utpyR3-N&TuJLTEK3zUpOYlB$%nL6 zkz3`Tp$F;T{hv(Em9sXDhu-}s`SL}c1T8ME_;J-CD2eJU*;)Fg8^Qv;R=%91;tQXh zpC*UiT{1zg*d8}S0fh8y&N#yMiJ5AeZAOg3pM-;t`5JtCW4LS8a&Vn1=t?Nu^JfC= z?vqROKOTehmD`YUFoQML1h29Br2do!eYhjaG2P>xAFUgMHqbH7Nq!uIe&y5Qm& zY8hHs2SIaO=oBSx zy>Y4hTb0Sw(*=4_5-mVyb%0KHc?$rxw_)-4uUHiGNuUA|e4QD3eHfBmW3*qA8f_nH zBJycF98i9SizY&GDe~kG0m8SGUYlOyeAl7eTZ;q?`|+%jt$D=hk^UG!?DZL1yjZ9U`;~PZ!?ixIT=TBL3J|Vy+Mg=yK9dG% zQrp$%3w{9K2a#My)qB+b_T&aY7I7*rMZ4)P2jC60 zv0L+bBR=Gr#|!GaGPq$3k|?-sU%mHek^8{fPO!hTL4QQB*T1u#rQU({{m+-Ky)Q?l zwQ=mh0M$DuP*r}mi)Y1oQ;J(@VWJDDi{C&{(j#DRcHaS6w?M$RqYtbt8ao8D&hA`? z;-a14A=X3xF`F{Xp}+GSG^Z2v%ePM0h&o*d;t4@Keliui9<8D~0*(5z6aJ%w<@|bO zHt?xKFB$Vk$9!*1})ABF~E@ueqjs+^}4#>8%O>e*BLqIB7wZ!iqh-3C6xwW8|)f9s744SV;f) zd@+jnXY;L$atXtH`Pc$HDGlVugWt@2QQdN$7*1VntMXa6>F^bvY()RJ2>Gwm_2+~^ zl5nuns^hv=!=pw)ZhaJP{adS%%)$6#t3*gev-`5^MLjF*oC{Z zZl=dk&{4}pH?I1T+V>VR>o;0|qj^xaa}y%X6jrsf1a!1oia#Z^I8|%oi=_GuN7?tn z^OUk8C9wg+SIV#Of4&uIWTrG)G2Ql$=bSME<i%u2`v`w;=cSya+!N)$myS~HMFuf%&ik;BA zfzZ3Xvyi>aki8?>u1#5w*`Sk1wxAo<)!WY1z}v*2klU8f+rw-5>ooc6myhhVTe7{+ z4sh76dW2bmvYyJBzmB`jnn6AMMXejS^>#!l@N&F zX|vO`C-kB>wGDx;Z?fs`T}VkTl!l|InBgd-7xL zFJyFWUFX*5ZDFAS7xH`4*cVj>`|O^&37kKKvYAfj0+Yf~8FJ0|W3k_Vhup=C>;7EE zmZmwe!|wF3%W*1B?Q64{Kd$(oo-|8k!Zpj{kF+x@4vLMX!l|3>;Z$*%fLY}gU97Rp z_8Gh+3l9{0zqbQ~|L!S2mEh+=+1Wp~v~{9GrPn9lH%fT= zY2Og;eosp%CP?;4GV90>{x4dWn%_~od(8a@r%kmja7@BI*=_}=G`OH_b*f5k{6>#| ztPI0l2SWi5V|TyTzYqaB(g zu@*Yq;}W;P@Rt@<*=ode)CU?&fh%;!^XaC9Yv(t@DNR`^b>uTwX!MoM_co2$y-#)7 zjX4BECp~Z8_?LdSF-toZ8dy!|2-zypB+@z%_wAIa%vG7M-8FSCu8z(AC7N=_EtKwWPsBfgE9A`77 zL>RDQOoHjG^AQpvT<^?4%pA7HSP4i=24@|PosA%SH0ic9|{lDf}idU^1Y%UMxk@^&2Z#K0YN$Z^i)23u(;FDP*b=-rS#Z&_dc_pFc_i!!K?-*RJW8ADzM*}K zQG5{N1hOR%!>Twpwx-be>^r%Ov+oi$3B^1>#BOOcxrW5vd~~4whbvm~an9HdjMI9P zVdM;I(oW%Mf%aQP?e5%nJhKI=BgOpPH&$Yy>YmuXDvKDj82YRQO2GOg`5UTpz}tE+ zq0{kc5-vLD?6b>uu;fh=R6WwZ7#WAFSi5tfmblI)w$ijS^g~%;PxJzs9_72=p(0RM zkpY*28L@Q5n1f2TPK|H^MDLbR_e;x*s}Glpv0F4Jh2+7zYTUv9fCtNgD`$D_p4V{C z*1#RvRS4!bWc660lTcrmy?(2vjfy=(fx7gBr2B+KI(7G;`{BTo)snsSrNXOl=Gz$0 ztC%lzbWb>mqNoT3u~uawh@$3YS5A|dtfLQ3-OQ6Q(m`SerQdLF_c>Z;f!e2c&}jr$}0!dQD$kjZ0l1Gn^P z;7fyGB{oZ3BlSVWMVp1{(QnDBOxuKEFP3dVtER8%acr&k&@Pe`d(CYFYZF?9^@Ejo zOnjcBa2j5$?D|nf>4sFt*9@7|TkNBkn9-t=Vk7LN6y-*4*_I3s4 z@ScrSMUola*44-R)ljamtyEQ|8G^+Pz56M><@=S@+rZOcoHdzT6@=`7^b6k%C2D{UEL4&h#c6J`Mj{=2#O27AFi-Nkw95TMx;K zm~mG`dmfn#2ZfJe$Ke@}u(=_^Y!@a?^lD0;o0TN4HAQD{i=~L``nJQ|pZj_enGRP} zbJHbHchP0`T`G~JR?{Sn#vgUxETvq-mXw?=$2v})m6DVM?iX76RB!7p z?>#&sIiL4NkUxEZ{%M#ZL2{X@t9yzc5?h5L-N)9RY?E`c`*wpTT$=PMMT#4*)Vb_o zQ)Rr9Zwl4aM%BQ z;oKbxuL{i-!M$cAU~985gfFvj-&sT0X8zq4uP2g-j#e%9<<#ynxwvLBjfvJ^NSmsI zvu)gIEqCEB^2otSiD)#o3M~Mk;1a&3wDNMO0Qh06-2`Il6c0};(2o#PUvTHBv&&rs zzcOuMtYG{5p0>h&#_s(-bh#gq`{lP1#5B9|>>L3*WD~1=xR!t1Dg3Vg{~O3HeAauO zeM9ew3H;NeIQTu00+^#Y19#&iWUrTmWChd-rxNM-EPTJcUxIg`&VNjps%f&Xy=EF< zbCGn&Z!envD`uZQ1@p8`h=3dhb0G)Y<59^mh0(L&|4iF9K$k-1!x%%$`VxEIJ!2 zA)%=_=3Nux;+Ce=8(j<6uV(H;_zO`qyKT=|QuTF2B@0~0vlzq-zI+}v|KspkJ)@I7 zpPQ0vb#pTR;oLor1^zp{?}u*Gap>c1zKCGd-OtWB5QW_{KS~woKX_aKCcgVB9y8Gg zJh=%wy-Sn7PIGV*T#Da(+-18jW*Wz%(xlRS75kN_RGpUaoBRpELr)|I4d^)c>g&Ea zI(|4>Z0PSs8$S$B?hLa~KWVL^fb__Q=`22L+hVlwCfjvcz% zq?b(~LXP9|e7o?fZ|&j|l6BNf-36hc`;6JmrO(tler)*)?_Z94j!21+c&L})zYo@x z$^zkwKkcH=GHlek+VX>?^xOu97to=t%q9-Dg+;%Nlb#sOx~|I#Do!x*G4)?L&C|l3 zJLGoSN99()ufNS-pYSETmSz5(`JVR<-i^YBzA-rgaLq~cNqi*c`XEV#J=V9Q#4NEN zEK@?tK;)U-if68j&Y9f|IpU=6&C_-$(G}Gc((XznEDoXNL5!~Kcq8*nOUixoYQwdUn+!t&)AA0okb%=hClC13u84vrkqK ztHT5;4nk&O6|LSZZGH{RPbXW8M*YPw@8*s=pQ^$X(kZI&KNrdA#zQ}pVSInYli*m^ zWSf@#qA95DmUow0QZaK(jfld*gv{w#Zlc~*$9?IS?A52l_)qM3cx~*yaJT;AQDU{5 zw_tJPvZEcQxOmIY@Wo3QP+upMY_;^7VO1nkZ9gNKh@W4UJ6zE~yMG+JB$jr- zN!YSxtQ*>4YnL#x+})Iz-W*EQ@9AbCRgB=BCr=(VtYFQEoPj__v_vnC8r)bJ^3Kra zBJw-~hO;F{akD{o$;`CPj9rei@ZD$uw-sIv;9-`%bfwy*V}2H$}jwF*sYYLF;;IQCskAok%X z<2O4wZncXaTE8g{mq)dpW4k=3agZeCEC}Ci5@n9fjBP5R!1R8h;D$HJ9x*oB+>A`? zZ+Q7U-wiRi4PpNe1}9BcFhH7dn&Y6_3nU?&7Z#}pQ?ut2$`pH7Cr~Pox!<7IebwAY zbFIYdnWjAHM&G4dHoT$V)v{{HpoEB-`$`&9*e1V4WqMELg&!m3xF*Z2DM)MXJAJ3_ ztIDrtD3-%?umt#rJ9RF5jR;pDQGK$ES)BD^%8d>za;^7J%)2T$Qsc{ zD3L*#E)e0!izt$qeG#>H&%VmiJr3tEG(26XQCSFR+vKdF1r%7Q*jPHx|CEY;(6osi zP_#M}t8vDzi7ltyCg#n4RsYkI%JlBH|Bitc)On~h!*Mr$rLT({sMTM|HPFnbzaDOD z7!PH!PG}hf+LY9nlvNqL&frx)zn9z@jbRG6=V#U)-;JE;mn<#}1MHASP}OFuTDeEE z&IyYOrQ)ie2Y&6&x&1hRviX3)8t$4Nv3OeLy8K`V7Q%LYXL9H_1zN90!B8^K;_!aS zHz*Pk3DC#3z3~?ONRMm{h%n}AEU|9ZsCrfNPB*}~GiWSTj8;rB_?coA<&?$B&#y!n z^O!vJl*=_KaD6aNqjj@z=@54RmLP`Be#2W3ac?S1nZvZ$aRw*wc*&v}F_TnXbw;Ty zGR0nMnD`=3<9hQeav8Zg12i4obN%RSX?^$2Wsi2fi6T~-@8DyjK!`!Bp6}M+tq}S@ zppd8#tGre=KSSNeS<`z#?^T*!hW*YP2FEx<)*Mrj-9&ua8&2Lv)J(G7mysv4A2d1O zM;bi=VbbuWQdnL3m|%~=FdeN>z{-15`H+nO<3`V}J2X-+x!5xDLlVC4ah&<$>T8*> z+ma<~5Cr)Yl1%y(g-W=8sZN+)F#W20JB0i9f@7mc3zdobY;e>a!;=cYA2%>cZC#Sp zn(mi9pzft13*@vk>O9i8St8?lCOm8GXf!^|DU!0Yu4qhxY6f!u1^JBjD3bVi3-5XIE>2rVrT*fc6u7-yR?GC&ZSuq}Yqq5c2T9W(Nd+iy(azFy z?Eyub$MPms7WgmkTA5P@$wR4EeRY(G*HyvpvCna;FxzkhVHucMXmzcjFQ@!5)KH4D2_`JyAtpWaSAx?lYAzUN8MoI7I8S5!& zu~UwEIwVdyf7W_7weYn`@H?ijZwtbKC|NI9Q41IO5a9k6Srz}e89td*R?ru-Ml_xug-#M=j2^0xXUZT;3kkDy0W=QhYxEW)-qI~(R=PrtOYG_0Jb{+tJtXdj=Awy=7( zoa0cXG_@_y4_tArPrJSet`)m@A2j}D_3qEHwnbgE^XzcWtYT(rBa5)Cx}cT9lvXD` zfd*Ndm}olJ_A+Pq$DAI{OTJq;PO0icP52!CKC{?ZQaaf;ra=N0bwZ7%<#C+R;d&3d zsVzOG97jVxesXPO44CX{CeP&MgU^ETgg>hclIJCyHLE{+SnU$$oB`GD5`P%}P?mW$ zk%rNcJ$)i12y&40)=4!ypGtkQ%73PrzJ^2oE?oln-6yBGuq?=67V6%@{Ra7bMM-Ps zs6$3OlwNZn^^pI4dDE=W)nEZJ?-Z~y;@B1;K7O6jpX6h93HKL9yRf|l z%`cKvs?=R~WefEK zi=`BM-tiwjvg&-YVokQagf$o@aM;0XEJUIj6@lLTg^~=ZIp(OL))c$KJUhOo7Q5HX z@sRGRRUSohZ0#dIJ|Kb~<@ZMpY}!2&Fti%xtGi+rpR;`emZL?VJRdOz%@mffu(qu_ z{Pz)gHUs2Ao#6A_17$lJWHy!oI2koVt>0B7`Z{EA-j2TLco{y;MQcPZ9(2%TjD0gf zxJA=zANAr&7;iCk(Q)DVjnfppB(o@LZs5ejJVamHW*scVV8`xH1m!Cr2RD(`p5C>M z`PTCCeKNXvHSt9MSHV#f={{KdzY)8?JAh!V$NZS6ga~m3%RmQl}OMKR=XU zoUT?tyKtk_262z3{_uy=K9OVEQqk1g1z}cD0t}IkSlev8dM>L(?zG`0tq3)xqX$W< z>?Ni~2Ik^*oo7`t8y(y2Mfn`8w3!{0<`3|LNPhHy*#pjqhQ|}hYxs&0?u9>G)}Hl~ z@=9?h;yY;|xk=uH@PyEKx1{y73xEe=BCaVO&!ztPPKGM4y!d@4f03c(vCQg}l>^J0 zOkSkbm2(fH_kXxhwbtjr%5W&z_%pE4YjhiU?7E_Lm6P&S0Ps4(wLW&LeKM;DgYI8= z>S7aqkK|dgFmPWAKc;6o7UNe(%Yjv7HX0W<^zw81F2Qud=vL)rry19lB z@4;RKN`vo#YG`_*rD(h#5)RxBFQkNDpum5Bvnqf(*U3D;2d+oc9SzyQ_;csxb3#5Z zHH_|@KNPQRx4%qg&S&sU+iYH9F@QR2qD1 zoxJ$FH~#UZ+Hj*i4sw;2u4gkRJ&tPMI0CbhX&J9C$gUOFG!>e>JDg&*A_f_?i2xd9 zp{7n{t5#PecnpY%9W9+Y%4#x1>K&gqm^K`MSpqQzpfR!7Z|@Kaf~vo{Wa-=nSz^?1 zGAZ*?dQyj-v7bX4^>g(VV3O(BzF_<~MB0oLII9z6XI#bC=+i61xoQ zPD+)T54Ed$f9id2S`V@aIt7Yw5fz-!Rig$s@_@}@4K%88HZJ{5Ew8Z4_U+%-Q5pVk zN|399S%X%5JPBJ?ZeQc69Knpjy)nE5oPxe2U?$!~aP;;o^gDLExc7HpOlD3Px#s+W%Rh5kpn#9u79)Gi0dLf&R%T%KVUa z>`GZcQfrgWLh!Mmh2*A9Qn~cZlCk9czfYI(w4XKNHso;>UN)Kg#iKdmez6b{A?%OL z17>)lXGr%m29Bt5t8=~k14X%L_9A+0LTy>cW;JaR-_GRir1>VY3Sv^bWo+BI*~G~_ zTa;P2S4{mh$VIgszd^dIHywwzQl@#Eq1L5JEhdm`ymWG|Z5hr+yZnoe&kjn?Y163A4Y1pA#-c z&%Pjm;F-u;Yne!-Nc{7hR4eZ0CQV)wrw3Mtp_OFSbD)|Wjw6~jzrQPI_R}m3QfAFx z#UbMIjw2mEIx4YDu|QGZa2wRA_l5w+ODiXzT2gPX3rU|Bmc|K#GSk0^zXBv@%(xQq z^Va@O`7E=cMfGyZ>s%!S7xBdaIx&4%2Dj>jthnU_#19^UhJ?w%i^)ov1DthKV>Nkz z=iL_ctXXJMcQ$4U)t z7rvi|+$&;8M7VIZG=x$c@^~NI8j4lG%sgfWcM-maG=u`W6izDVcT=rq@?EY`GZ}@l zANz2MOHPHBVtLo9)HWg5URFK+@5Z2si|z18vh)zaLD|Fw38CJ>LUpEcI`~Qo#ivx0 zraZqHugc@vF89cL&wi^hb2UOI)%QrI9}D~*FKq_X6pa>-uJ7PlEz;}kajlK#<6vCc zFmWXv*1>oEzf!mRZOsk7*RhLz3HkZ^RaLf+6$)eBtrVhQLwQF|r9Ipz(Zl&YDL}gN z$ZXm3O@TI5yg1yB_Lw7^rxVd}N$>ou!fWF7QHn9uNLt>B21m=YJ0W*jM=mF3ekN_e z#b{D4f$3J;yM@}8r)3UW9ld2L?0-I$y<wT zs2G#IK4^{=PoEo<#;C8zfzi^p*#RKsqXKTVSlFcgfJqc9yaYCsm)P$2sp9 zkRRJnFODZJhn~z9x|<;h9X*i-JM{XrP-yDxpX%n)^;6MeP99MJgJJ6BK{5GM;xBRW zE#Dje{W+y2-%+MJAhzpq%u!RKQ>Qu_i6|+D(QO4c+ed>fc5dElkC9Yz(;6M>nDT=< zw+58!@=>f3v9jHo#-X6q9Om*3nM&*KOhrU&$1903k-!$Q{$EOqvl4%uHcb|y9)QSx zQpQI974;&!%Mg4{WKPi9X>mB9cX9vUZyR;O0=6POt)Gu0-ns`lGMttEa!?9TM-nbg ztsbT64XbF9(VH$`h^b29w7N!_^OphaQ8N`|kBtD80J{UHu{20)g9s#fd}TiEfK|q| zX;z&mwt^X4ONO0D7}$Km2;dx&HPQn7E~xtZ6(665%4nuRiAuatL{P`~0bDQ}PD7&I zyu9$FcFW>CtnLFFcddilB2~h5+QI_}6PdRnR_&F(Vb4!kJ*oFwXf$ciLsvKq9od_3 zNvelc{pECSM4Ol{g(lLT!YtUWEKcT}E16G*YA}*?|LGbN*hC^wa+Xs(TTV8mv^Ep@ zRI=jN>X`O7^2t2*Y#NZChSMgP6-hZcp{StuA`puqeuxrPjC?IuWS$a*(rJs{8S#n{ zd!bZ-J^ngA;G1TL+(t|QPYLc@t#7-5)vNsY;+#_fBUCXG6lOAI&9pkoM@HXhy0bHB zSmU_-xkpkCNc{CIHc?|`rH-Z2uHR6Hmmvuy^|^N)IjrK?h58a=8q?P&i}9} zZb*`nBp@53uC|?*LIof1MY&*A_^7#D@jwbw$B4Zh>|*Sr8zlZ@?Q>D{K7~Tz1olYK zkU^=)f_%p+N$nGR`OTzA)>qnkDEVVXB7qEKR!&kJD zfTpc>h=$6ZCS!<`D{PFjB$M{yW#`|wy1FOylbN%S<46RTSgcr#2`+7Z#@QVsrNq|a zK3f~ho@;SKm$cSR;!Z(o`@l{9f5yQ<0@#AvETxv>N+wMziLfnT=?{AP@o%C-X6Y%_ z(WE|E3)LSOx*!EYl5xLyB#~FIo+b=@c>Vz=JRLB-<6x@x3Ww8nzBobp)Tr3{<=ET# zKp9GZe%zGO3=8_1!Dlrf?*MC+v9z`s!bN0&?JBlDo`w3p?2CsKf=*K8uw^yb3yG4I z?%DQp&iam1?blLHqU^h@@Jw3X5zUBHLauC8;J~nD&DT>XgTz$iIlJ8C_gv16B(;jC z+>05$y5;QzS~v0jp(N;6z8&#Wa3o@&1EjOKqVi7IMWCXO3n|!0NqNftAIGuQS(xLl zeRPBSzI}9{fVMXl!sJT72VD=hA3mn$+&2AkNu!9WZ2a{HcJUh&s9oO(r#zx8{>Eb< zUcjqG4JmkTY04n0EnkK?$~#O@BlhQ?N)sc!(k*iJDLKzdA%%?>*jwq=v*9fT6gTH# zLfEzvPwVU~al%P~pX#3*q7TQ5uWEuDkwc#>CJs8a5;rI6YpK(_xe+fb@H9k)FKu;8 z(#BG?=?o#Mm~y~OX(s(bEvvFnd!Wk54?GGuDQsZN|J`%e`!3U@z~-FkS%mr2*z0;Z zkw+ZZkSgulnv?UN+8UXq--XVx7-bWmcD6r59Y}5f(Qi4wb$|+r!vH4rbwwqLx{7Cm zmHI28FUN%Ms}w@HPf2(E)_(PxYH+!{+dBZ7Y!!v{XYWT#9H>*MCX6fBR`L$xq-YbX zb2oKfHWOC5)3@F^@Y*Zb{L4~d5`r0~fcrAGER8;666}~f;CbtW-%Op}sYay~t9#d7+*;eQl~HK9T^_-nse>n{j1V z1dFDjxZFi3N8)%V`EFd17!)XRY$E=t;3$aTQVd06xTsFK{M=?P!-hJ$-4W=@CG8z- z7x6p?ED~IiIrcojCZKLiu2-GPRQwe{+5bhTQ#o|jlw=7@MK086MC$sq@1&#QQ}y_2 zMf0-BRt>--BNh|1dy{3}6SZ<6Z12WTwfV!9kV}DNn~?Jfp&2%$gsB>AG}s$SJUo-_ zSL@;M^`7tI$8cx4^t0Aaf=q7hjzkMb;f>MYFarT!Xy))doHCEnlrjbF>sOaJ-EZ#t zp7sP`V=lBz@PYLDr(|P*^Qc1tb0Ub8g^@|}S%7*s8yc&D{^scob@=0npB+HRHDZFR z{AI_Pnf>l=gCB|5)N8iV*Dm{A@1PBDw%l0f%f6B5AD12djME7!c%~N7YIfuMS%-xN z4Rm1tS^WsUl@atl9QjZCfPUc>++VpnoHXPs^$++9Fg*#^Y=&KCOW8P+PiIqlkPp>p z#1?)@qcXAi=!3@YS61ywi%;tUTQn(LM2I`C*1CoFr1~;uu2HHe6h0%h*-&vN84ybT_3nC9!8-{S z3+#UppOD_x^jvDIpJ2h2;GUTE`^nQj@&9)6Lm$B3@s6*ZkdD9p+78k5_r6<97?et< z1k}>&uB&aW2^wE}fO23M?27Xb2gI^O&ZM`SgkWfg&HMilnp7wNRdh=UH zXsOli0My&1^h2a{4jJg+E+2@DhHr0eTL`R3Ff}lme;$7}V`81C$X?IRbS^o_22ede zidI)fJ>*xrpGT?NCEyRczgbAAB7iD@Daf^Tna3x^v?yGE2%tk!Phj?rO;6r<5AG!4 zBj375^SZ==xeqnkh3XwU9QV5lLMQ!F2VU{>ZaRYYhQH2qc0khdp}7nev1p&qDFc)< z?!%zL{T8knuF7H)0#1xWox*nI_kOYgh6%siGe^3J{+@EAS=0U9Nyp^Mwn>+kR=cZ>} zltKAyl+|eay(6>9Bxr1U&qQe8rTrES(zGqg*crK##`<;eoRq8y;fvq(nTb)SLrnI9@Yecp6Js`}WD6k)%@E|RDr z!Eg-BRjc{vv0HNMXfK=$_PoMPHHo-)q4u7e&=v;S1ShH0-km>>(aJ0DtiDY5GJ;{= z$s{jXI;QhbVw*0+I&#+v&6gB*zB%nxdGdUHjR=`IN0`}TO5CT!ujX*{5ylc5PFel5 zER&|0`I7^mELHH#sndh7^hES*k6)~}+-*`MzY~|nBfjY`yLJI+3XvJFxEem$IcpRQ z9uKF}9>&2@Yvz%F;ioHf2CnN5zS%c_|3_79e~usciW8Eny3Tt!D0vtkzCCB zcqt~Xh5h%<+K^nmF*Hz-Vr9iXI_Ly^{oO!j0L+$RyQk-2h z*6C+W?0_DF%i&uKY*&7Y`}%1zUqsB|cKP|$xRpA3Z-j=7Lu9qX^CK}Bg0E7+ zH{OW*8u8qH0_@z_iRi&?47@`{4k-^BjD>_qO!>Jxb~YJB_@~xHqR%;HsT%3uaItef zCPhf8lyLaL+qSp9(o6-X|E5CFz1N&a$x)g`4$7L^@9s6XI$lhLrsxG!hS}MVu!|nU z?%5lBf>f$MCXy!SvamF{d%RR}3l!G&mg0OUwkSG;ejz`}Q?+^%ladh*0^RO*2FM>7 zIejgcHj1N?sEk-k2{mFc(>jbu6eMuRgoW@BH00ij5eZ#C3ONbenq?+tc2AKm%^;F- zx9=$-@r>o{^)Ea?4UBnQSIo=mv=B*o)?n-Fg6;W_&0=ipJP0p55XEx#2dQ)_>&5~e z(6j8S!)5Z4@nor+e(A1LwPxswNy0k*kFd=i(hI<5Ni6q=j-gJ8!J&z^@itii&J$fK zjoO!q6yZ&zqal13xmpZ_l&Xcsv7Ut`=d^0ctiYwjU+9xM>fjKG2Se_`b{&5eH-?UU z@wL&OtTxA9{K#g}rC6E~iy!-qj-Mk-39e@LT68ASPyhH=Q>Lf>R*!r}S53;{`FFhg z+VWW>G=WRO3glHE#s#N_ZmFS~L+~{=2U5w@GqTTN3DBWY;{9;;7~i-4=cS+xYf!N8 z_V&CD6=%fEroPM4oD%aCjH2^~ZRdW!mB5>ytr5Zy+`ma3v=U$F&2IFY7j^bn-X_Er)vd zq1;Th%va=^)@b3$)e9)Qi1$)Tne)cZM+F{P68brE{EydpUHwk!V9RLQGCb9O4FK3ZWxw1~_z25n~(W)&|_U$3hA36s}Q?yMl z{;y@XuNYX9qql%8fi+O<)zM04^;52m@;e8&8OcXM8}z+Vqa&1f&oKSg^7N7LaDgn3Zv2Dm zVXGiMmRwe-^Nh9&QUM-Wdu~<|Maft?5*}r|mi8iDTVQJ);9b$S(9Yl;4!tCIy~HB0 zCc={^V|iRj!27jlRatw(rn_JV$27+%`= zVu0+?Jb@$StZj|G>!#)NT6h)LjKP*yO-nFM$Zv1AHV=Gf$bZDgV(csn@Favc7J_S! zNMvb9a(P5VJd}W$-MxAbqcC$udPsraO9NePzGvYZA&PLSr9*%^!-*+6w;ZQWs` z-a##&#~C>g6DcC=i1p=iKy7`W)pi$o`msew^eR7kUu~HLWqd4ryww043%IOsl=xU)9%dka zYVEMmP(uF7-yrtk-3OUzEr0cFN{QlDzm$#RK*A?ABYjlIEt!S08g!3*AH~E=ZxJdq z`u*gx!jTavyCoCKv349R2jyRC8KFL>w{^GD91Tax@t!Cx>)FZxZLPIDXPftsS^^Yp zM>K-0;J!3mV1&;cQ|^lBE!)_>*e;|2A2Djqq&Kh}jt=VH3L~xT*g75_(H3Q2=p{Gl z!Jk`p6-^82AT}0=ENgQn0Pn(Og`C(}`hOXu4Xh{iW|W&H6Kv8ZM;pR_?l|aqrlrcH zn7}%tVm%6?jniW^qxbYcY8RRmdbTH)=TQbB%R_o&=?=Qrvclf=A5mHtUd1A>>Vf_u z%g&m$k&rTAR*Xz&mE@~*Lc#LR^}a^{-mAt?J#x}XD$nRw-Y$iBFV4I#j0dYv^=?;^ zyo%yzolK(T^W{5f0)Qm&41LG)*!2GQf-E=rsYUKyEeA{Px4f?8xt@AA@*D}=UYaH* zGq|kKOPfo-MqXAps?JpEw4uqaGuT;ZH+U})rn2u@Ws_=KYYE{XC~eHS^B(ir3#kD> zLgufx>$x5Xj{=^}Wrdda2#KuLZn-T6|HzDh^?Sj_+Hr6jU@+yD5$ZlR<95&%_G&Y& z6=I@P7Nxw4Qs<9EtyisAHmP^C?x~gc(z_8PmbD!_-iupZx5m+9^cj#U!ye^p&6-;z zwMB}IP}e>3K+k)|b0OGwM)zVINv5{S%NC>GlCR!59+RIQ_04yI$5gKn6kJw_K<_Di z6~rt&Y2cML3PC&5IAXOgi#X=Fna4=VeZZj46|ZAXCp3Ul!sI+z$+JCG9VjLyR2h8 zfJYX{iBU*e?JO}`ACUQrAUd{>+SidUv=e;Lo=Co?^d9+boqJs>fmB8oj)&!HD^cpI zxF>S6g^~Mft~t8x^7-hzUXXVT0JX~s^=xNt9wYUm2MBp=;XY6oo&vB?2EB|hM}o6Y z%~tkX3H{^t*^g4>#x7M|z%2iB!fxy>fsON$*n#1 zX7>!JLGFF|u2_PlWf^z&JPNXp&489(gC);MJ=dDVmFIf4b?A}WyKfJ0c{$@_S#gi) zq5Jspr(w%v?!XiaRZ|@!nm1{#Y^<%UH5S!dA28i^p-0>9y>jW5~5l7s{qvxXU zQab32+R^21g&KS9R#?LNTmP4_VS}Dmi@a(F_LEdFcgt%;_91WZAJtn`{~oQswKQOB z6tmI1up$Pk<*_mfG?9dv_tY+h_|%S3-n-9YU>}L2%FgmUs?i^2h2?eTfxB$UduIvi zE@9R2tlq#9t=>WQgI?u=vH%Hiq&~^`Sk|&aDHE_%45Y;jvEPnDsy}I&F)JYFNM1pY zAX@ZmSL^G|A}>5dkL3V+z+%0l_q0Ur`J=XH=1cBYsLyk^!Xw|oa+O|4W9>ND9weh8 zg%M0$!Pdz|u=d2rduUy6kOZ%1RLTxX_MF8iOFHRHL=dNAbX9DufWrf~ug&?u4WrbS?&j|6Sy+E#@h;9Yza+Obe zpbuF6o5!>f0dN`NEOJ4<%h7q*iW1or^`;u3d@L|OIWH_v@2XYodO_xiil{{%qff#p z-+S4}!b6Wai$H1t_RW;+-FkdPc=pf}W2uq`#vOVvN*o!~JqnJOM~^`@ljIS2>1lm8 zq9aGItp&;evUj9@gS?<^gUG_Smp3jU!{^B5v!lY3Bl>qOj%YKGdmt_`W@s3 zRYBYr#zjN{ZY^M=gG=c^7)eiGs|TK0ky}>CAn#i6?S&r7@tGiZ9JD;@7PbTBDEo+( zecH|5@`{;l?6VY_Uhhzve#96kd2T62sY||Z?M56LDfzMYJJX=`mK4&nLc-pEM3tEY2H`H3>KV#&dnZxutX2U7KSguYn=&nAkJ zSJpYp>xy39y>Rr>!4$Zx5JXmLr)`W2ATttkrluE_S?bVx&_kz3wjE%*zs!>);$fFrpD!*+2L6BNTXcX(Gom5U&cUhk1Y}g6uE2c66`B(zAppT)A3=9T|x+q zT;U53p_TgFbt58|H)}vUtK!6W#oz@YU>OSZ#^SQVlCl^@F*p-)sh~9+p#6wtdlWN2)r|w6h>#-H9?ZPZXu7> z<)q0O%i~Mp3Oa%`jwAZ_BV!pD$_Zre=u2;-^0jrnZzUjV^Aowx@|0-}dc5wjQArD# zfiy6&!DWTWx0Np1JG^wbtgvMnT11b`--xjCmEvYRTiEi3-4pP#13?MTtKJ@iuUkO` z&xt1i_t-t2=Ut<(*UFLpFOT#7RC==_HKPh);0XjSk7_;Rw8a>`8t5_S4cH59f%X{j z!qWG62KDT9HcJ1r=_~J6^07PEPY-sDI_9<#~N$4!}Hjx zMPw_!?=@xjM%c1=N|C%(h|eF6uo45ZM(F*uqfwx0s75ef!ka5 zOD-#X?z!jOWrcVi$SW)>M6mZQW97`U#*?clFDydqKSu&}2~raEuJwT)cpaA^EiBZ+ zQ*27^x6;XVTq}(;g96PXNobts27#PGnNvuYaq$qS3lfZryxI@B-3ToOfC1oFJ@toH z_;c9eeKjgdc8}E)7$eJC?R~;+vaN9m1QwTzq!jSfv8&_AGLbtEdMK&KGu5x|vytnq z-QK^rcl)C!pV`wWv!;{5($ml)2uTptP{m+3!7M2xyaee892qFvKJH0rGne3OA zeQS?*MxB9#gj|Czum^6v0t)@efdsFJ$TGl)M^i*uwC*nf1XS&ypb=R<(R0RU543P= zO_3$^OxZFB=(e?D2l+r9pbzAh4z`{VzdEE0OeuK!9NV+TEOl{&5*9U9EM>QZygH-7 z8<|v)(1v0uj%>#;P^=||0LCOPDU=3qPDfcX@>S#}@GNpclPg;Y;@tB~$G5Z9YpGsp z#R-BPCcPE+LR7wM&m(^JAhSx_OKE;Ad&(lI^t<;WTeuW2H9^-4o>Ku}$?J%{%4LPA zpxzi8;K2hTYfC@SH3nJ;>yk#h zr-87Qz?og~u@v-D0n2L{~Y(wiWtkrTD~Nv#4&UE3NA+O&n1FExoTb@Ej11^t9Wvd>_!DG9dKAm?)jq-UEBImlBV%tAIib#zJaV zBeGQ3D&N!$z`|X~^J<|VNJgcWZhFfI&xW3Du-1d4L~i7kNt8VM$R!sRv=>&Yt)2xi zRIFVJNn*+6Qrd|3ym^+Kwc*XyOK&Xiz8q4^2X)%|cf_N9R-|NNl-R<=i#Gb$KSpvU zusmAi|DI^6d#1<$>%8Z2M!ln__Z9TY-a)XVd1-wu-V5y>M3xud3uTOc0M8zHWkt$* zcA28(r|f4b?{-i26Fu!X)D7_Lv(N5c{-%}(MXMxk!@|Dsl)IzqtA$ZxDX@`unz@a( zsxuCzP&B;&;;8{wx`E4M^4!8hpuD)If0fa3VA)GUS@!{J8DXhGJhF164UAr>ArT^d z18LThPS(;Xd3*$*47hZT|E~ZTVIZ4p8t)z* zHlpN21q;(Fy?-|5y%lk#2UnB>2EQDUB?n^9s9OEp2g$3^JUy-oy^K(!bQxid3_3Gv zjFysd$C_dEuA3EC-7p8^5tfTs{gb<|rDCvZVsfDlHG1HhoOuPmB_qIQ8zm`lUr2mE5!CdAaL)+EiR-H-h(7%{zL8p9j1z2wad@Uch=z03k>? zmlf9JZS-*@Wsd>52|C{2TV~KZ4j;&_quOfH`XY&?mlQ5VVjO7FCpFOYZq$1WWLvHo z0eax;QDzik5pS$5q~TRT@~URX!BwVxfVS+-j`O!xjB?8euSkmLkSmi~5#zD%Qc8-{M_EvxH=8e;oV!sA*0j>rebP~x&e&n7{CK+Gk0|CDZyV*MT& z5zjb}=&IGlB0wF0OoYse#Q*Jukoy1>j1?DaE@+aZXNP5Hu?Bg0P3r#KHD^Wb03B5t zbIS@XPn21e%)Nl}Bzcu9w>=2Uh1beCH5245BTS_^J9@OY*2ZeBcSA0{5&K#TFRWQ* z2=dJ(g;rmLQp_bH9N(6_tVc=NS^bo;ueRtY*7!GToyvFV^&Z&#K=uth4?*2)0$I0! zSNA=2#M*RgNSIVQ9_iKF`|7B`?G{obm4=qtlHe?n=g{HcjYY3S>mJA@EGvXJR>@M^ z8EhLVW1?hi1g+W>WD&?iZq#xl!s}nqK-MmW^I=4uWwl7cK47~+8`jH|QZs>cOSjUS)yriM^e7u^iD!%V8BM0>VD2fjkP#!cW5`c$ zsR)!~85c`q$;}v~@wkO-i4xG(v9lA9J=&qQ4Lz6H9%Xx_ypN8YAlZV{JEgAgEq~y7 zbTlcTQS#0a$Azd|;BJNJ58lKi#tV1?!6U0=x$R6umIp}`=GwEiJ!%0N1kw=gbOfUH zi{A96H+^5p4QqC6Txg|59@D>D0ZJ&0#uBAm&*~vx5Kw1SOk2KFNm@(EZx623Pmv-# zW)0-I`xffKGKVZmc@0>DyXT=eBlhU`k+Pzkj{ve?E2udV(Nm05=SKnF%QI4T?EIfqOp5$!5b*Oh+Fm&jJq2+UNyj`RhTq=T_K9V6V2;ibTkf zG-vEPsWumxbv;X&a6%xmq;Sd5a(HF-#8?WaJxnM|Tje8X_>KYfrJ(du6)7xW1%E%f4p;XaU9@Wy)Ol~AX%sfmCTe9XenDV0KA@Q%qeIiK^vv5NG1=S+-6>S zPio|59d%uf1R2w&loZchJDVJVZ1t9jz-Y&k!ql!)OK#fG@_@&3UI`J8RBdqTV^PC) zHas#sv1$prR2krY>E*y{VW1x!)P1D>W|18{?p>cFXk>e~ezykoOAz@ZLK7sp@+&>Z z^AS0Pa)Or{H$1S?g+2!Y>+$2q$&EoQ879fuqao!>?m7+q&idPu)gEvy#$bGdKpbi3 z^-VdEB-Tv0fGdZ&=?6ZOOmKtO&Zx3&FwY2{o ziIjr2CrZhyEecU?;$zf)M?z++vYaFFW&!dHgWXyp#eltDjFTl>+hU9N)!FO98V@Xa z*P)-I_>qY0IU#<7+Zj*l89HM{2KZ<|nK3?3N%@t|#9H?))C1#@UVb5A8OYYyHG7}gqdj@gC?T+V zJYQdvQ;PQn%I9cLiV=apurNxjx`OwKx8u|r-+a_eq(nW4EYG7ejbk~_gr1&eNFU>v z4wg(pcW--3lXgAR?{R%3Ez9Wd8D;?WiY0O0vbfpNLKdX@7M8Oi(7P4hgG4;W4R~WA z*!xktdDg&^rKRPWlE;=emIjC`$QqRMhy-ghUoh#7wQwvnsg#?EX!)$#G+N|k6tsSi z8lfe>7wW(b3R37n3NLH}iAM?Tm1B`u*0nQ28?18Ht@U%Pai)a0AITkkZ=@#uEE2rM zgvbn_(Jq&W@ZGsfpD1rpxtyPoyumt7rM5{mbQ1z4IV3dS6R< zQd{Re^2$rAH9W$8M6@c8mgP!MMSP?OuY3kcU&hDM`rg^f-y^>)d)<@Sm|z3xhxR$z z&X`0~?U5wbOf2V_Q0pSt;<>e0il>jL7ndGvM_EcVGhkScDzq1T$o^8YjF3wRqkV2< zY@M~MeGX9SaTv{8={s1lA4VH%s4p!%1a~^JW_?j+xwu#h4-t`T)Ei4Yuxg$+OTCRC zH!wEQIG5!H&k}sjfTM_!$mD*{whGUoE9#jw<9V(xqAcN!mD(W>V+RN<5Lt3by4L+> zA6KjiFbV6Jya(k3@(L44^Z?zXKa`@&^d|(a7q4JpKSW5Z9!ofmp0zp>qrBUQ!e$nr zO>^7c)HPeq1FLTOfSwxKdoJaL#iasgCe%lq(1z1v#3>mq)^Q-bGiN@bQ)u zqI^JNahJj+OSi$Bolij-&}wERN*@4XbcWJN~}YSN1u<*DP5 z^m@t`kn@ml3uUk-r{p=5DTpl3vkmo$K7-g;qc1B=wY`-5NqHe^Pg!j%qRoTggAD{S zFjd}1qnkFzMzUrYkA9Nu{1GbiJ=?s8%oh6VK;$TdIh+^v1lUFBN2`ue9 z3vpl&wgN&E*5IEC^eOL~4ZYgf7J~t(A(OV0|A-1$D!z)A8CN5(2q@ApO04$6T?!Y8 z6^A!=p?q7Eq4os#h^^V{D@EK9E&D9$2eD{$9zbI4wUJiKXGHZ}>%Pdb+`X2byq6~q z+QnG|x9@=*se*FFj(PZalhJZnA%eY2-EX9^HbqiJ<&J(Yi_GG2kb3lh9$n|?J{`#= zg-f}Z3wzbqRh9A{Sbc08&=ymqN96v6ae)4iQV=b2e|AIosJusvISG`#wR=$XIT6g@ zxkPV4V95_3=*KYLEn|d+$kH>np=Y3KOV*yHy{9}OS^{N8uLud)Sgqn=?M2|!5?7`7 zl}@ggj$^feJew_WyXAG*yPcH4>VxPnAhA+G$R&}5@6pDPl&s7x;r6bz>Jb2Wh4Mgo z%@Ch-mmH!%mU6KTB?F`u#PXPAV6FQ~pJ&aamFCq;cQys5$8t;$slGJIfHD(EUX>6Y z@_4D6y*DGW>a88DWrPwn%Lqp|yi&0WTIbs`N=pf*z1zE`gdYtUps8T)S~gr+MlhhP z)o)>ZASTd~qYok5yw(0&7%P@MI5SeZG*O}xM1VBlji|{Fcp{d>!}9t_%5$TY%shIM zC30O)8G^p%d6XWBl2r%VgQsRJ?@_*bc^v;^+~Bf8UG97r1}(?ZLWV#ZU50u2)5op4 z)8KMsELG;t>#6IlXY7sLdJtzC_i}Yzcojz|?5TzwHL7M(LbnchrT1G#^y*XfKv_ay z=iIq_mhp&&_3VIAtG#?uvrxPzN92#**Y;{dTgsuv`wFO;i7dJ12v9eQD2WTNl2~4# zUKsJ*Wonh(Yw)~FS`#cpuCL89&gCXEj%Z_eCXGx926fNnNgDRnIY5(hd$x^IMDpg@ zB)U)V)5{wXz@*xUf!mLmOzN4oCe<)rpx=PV0s(A|AGjWU=<(ynw`GN+gh1+1H?qBh zyut(!%7${q)0@3xN67SDDPR;78pI;8`lF?BkVEOr#u?CKV6S<;&dcgo-3w;1Zw8X1U#w4nlRU8S-e{W*6#t7bvtc@sMBOv94MJ#grRiKT*_yCC|JuF#1 z+@)~EUyY%qoIBejOv=N-T1u5d>vGXS-SK?3`&3>c`S$e7E!c8@svf-KxqCbkxA#P) z7hHT6Y?(yb8**Zp`D1)6E-UniT<%uL7>hGQd*Di7@(k|?uR!X`RzL8L9f?DH7`dcy z_C~QcN|yC`$0Lohb$-r*T<5JRk5cl_x_)*;`$(YdFdMdqJGVFUy$sVnK)FJh*GrBp zFD!XXE+fp%Ld}R??@=`=yGD~@**N+6WIT9|`d*nPpt_YL~ms3fy7T}V?R-J+J40dv>5qrSWqFmT}b&QnAXB z9PS6{c=E(vI;em500XzrF28d+)yU8jllX=w zFNmyE-GHk=d@OimF+SE2s3mi)^N3oYEKOTDia+JMIEmK_I6o+Y1Y4WJACK!P_l>#4o(y!bgY_Ce3G{tg(eu?EE-0gAUHMAxbyz%V{Z8X(4Qy$k_${%AD zm(t2~y`b)TQm3bJDbYIZlp*hta+OtM5@z zLb5FRa35S!$NUb`UZ=DX>I*2Uqp2)GS`Qmp?+NJlU z2$Yl|E>|-2YOkXPZf^;a;nGeT9dcrsD>4wsTu+8bK%Yc_cP=a3Q&+5AX(fUB0eOXM zEV)sWW)8J7Aot8+_VL8atpM+HAu@Y+rn;1!Y0G<+tXKAquRc--dS3M)uWA)|@0v4^ zCnF){`J>N8mUGRB9^_4_OzLScm*!){WrWs5-jWe9ki^2rnp}gyA&rhJ12V6r(SAmG z8NmpB5OoRf5v`-5txHne>JzPz^MH!nU$WYy<{F)^p6!-0X^%Lodm`mkI5SXB@Rq}} zLVSC>6>?c2JhJv$MOM;>G+0OUMoxKNMbgdLsQS6NbW6(**ALaB7KyblwhHbDfn_~Y zr!hJ_m&u;kLUJwGVCdTpOvp=i1q`=6i}aO9zRWJg;(~Zh-y-k1Q`f7Ty`2j?X{;{Ef^SmAjy=j=Vx1fb1@v z#Ltn+mV<}n2x{9!>bXNw!fQ!kJ6Os?iaFg%NSy_i0kK69)9%WVYxS|z|Ajp0eboz5 zK^<)e3vIwP|G5EM*IR0X5$Se*H9T>aV?@xJyeg>!dF{wc3Oz3@3rmLhKwE?7gB8<+ zOA3z+$a^GO?L3&mnwWWr)Ff7mw6RQ$8yXO>rMMes%9FFjQpQqm+|u+T=Ti2K{=J9y z708dXd0#~_vutI5ATf-OH6a4vJu#jj$h+J?p=Z8I0rCn)PD&W)Wzfv9s5+EqG#(I z=6J|~GDTup!QAoDbtvmNN?Pjs_k>4?*XD!wmCAJOebs6#C`reXoul

OO#_5NgG5 zW+S0DP(Co|X+-Msxx$*bPpS5{0u>;KHKCi>6tzH*`xb%|w#a_OCJ>lnAOq!6E8lOr{0B3~e{ zkaro2EtQrWD{sTo!rY~Bp$?X^(n_JQ2IA-}3GW{jy=RlW zXUcEu{1)$rs{-u|LVNF7uog<;LOWm_sa-}$S(hW1BiOr5^fVwnWz~Z$W2qd0GRMW*KA>1~=!Y4t3|!;4+?h9q0=haLu+^eqp0OJSRK}j(8lq-0O&;rh?pq3~x5~z1g}5YQ5jA8OBk7 zav-5{6+@>dP@dc}-15RiKfg*`tX@RZmNaK6^Ac~XS-wIcFTxAn~X_~>u2)5Om6AgXe|iDWAC+s8JDd3%9W4oknT*DH3ZWq`a_} zjHm<34J4NK#$q|c;5hS=!aZVNX+#Y6v$bby;!z*d6QwP^QIR&h&OxF`F!o#P_T5WY zZb|ld<=+D+dwi^R0GzSCN3S`9J;S~V`vTsMAhSHZl9MAcKGq&UIl}`CAer6!c^vXV;cAjsjz_Ewl%g6k1!`qb+ku;n~W5Z*Pc2vf9|IT+o(5 z)XJDQ0E4=>e9jT~N4&4RYkTPV1nO53)bm>ESXXclpj2Eq1;;@ zx|k@%(u*_3Up-2%7)|Fo0-lFeFa4MXtlq!|#&jzZs~0g^>)q@bzmmA>Ii`agXL;9p zI-dopK7Y2Qg>qRT+JHyUpx-_J{PQ=jEQ~X?{XSKG^d#oai6fzQ9Iz%$r*%)Da(Bfg zg(Vdq9T-c!rDjt?qReiqXSH;DUMK?w5^r7l2=J7u$n^``fia^bn7g$b;Z+sVTBJxr ziP|#VB6CM1uL!hNYbVSImfVPeJ2P1!7+?q>An#ec1@?T8MO597n*(S$wTH~XGeBZV zAP;EQtq9thx_**bHrOh>iJq|T*)B28dCQX{&pu zUb%9|QEzhQOqhOs4HUdy+f~kt-Ue2SwD)wSmftPYj2=&=vL;H-H0DG|97|3`%b<6E%*n&(lK0X28Yk*J*}(6m|7-)6 z6N1RHmK4Ikn0-lMYK&?5jF#8U4Ba=aabF(qStj&0gh8#3qit_>0@%`~N+<53lYQ1i zb(BQf0>}}R^^(We1^Y6*u&}HUly7F_9EN8yrhU!&3PM?H93&U0dR{yfIBs>O6Vpmdri}A?OIWA7fZ=@=8Cu z=KR+5f!C#!yO}@|Ys;F_tDuD-FPY6NF?L!&yYKeSPic9kuD_x(*8(GZUbU#x)h5~k z<3!56+VaGZGu5j;;<3SUWMM08A)iJht_a=scuXVb&3Q$Xj>~ALFaRtMP1M1ROA3!_ z6MEdUh?><-Uqea;S>$!<8ViuumT}9V?lmM<>-tNPJ5ht#x{ec2z1kbfUTzAp+Vuh< zmlfh;O^^U+qv(eqvJfAu#32V`6Yc|niY2U9!RsQ7|4dlB6xz^U9VN=TH83nCxemEm zvV}TeP?&AKx99O;^(}AqdZ7*&Cv@B!{aceRxJTBF<-x=684cWCC?&744`w81u}#=hl^3H_40 zNR12{PDkp(l(SY_)E-(_#v>;zg)TQq`soRkDA=y$Gjs8wFi9AiLaAx2heWf_SvYpj|DwSDt-XB{-y0M?Si*N_qnk#i|y zPa~zM^oAU)S_;FhvpEs(tJPM^z#Ru?8uTK09nlNqY{1x%iWLwcu=EW0lgi}}v!R5% z+Ec08YD8$`a3thnV_5BV$&q@n{9qVpZ%xVqkXWNHDIBf-J&!9-&pZ?4yGHauUdvT0(x&&keaM3u_vr^IWMdpK%SvPM0dTGGWn`HzwZ0J>u5Ca{kgFMmKA#O zu}CaG|NQeeGRxac2!zNe?Rzsmb4n?%yE|xLr=fMk$26BsbR7$QzuJcH_mc&~MkO8R>1Qx8ayrLc` z>*fsa->P0oWWDi?Z*=3Tk;~wu33Y$w8@W8U z$HdFR-Ob2=@v6NyxfMD-N0&eHHnO*^y3|a5tn*fSDMBFkT#{H4SQgvD zqi~CEUUHqK$MvZ>h?lo?9s8k&Fh*xx!af=wqi>ZcB$s#>z%_v|{v}vFNjP z-7CjSkdX`T_?2t-%HWF5v$h95N)9!Q6p&aekKr2f^vKK@K#t&y0$%i5@AnL3kLa1b z@3Ql1&2v1Rz0}Jgn2ij8>}3qqLwb(~qu{#uF4`V?2~NfnPQ{D_mNgzFX=9Pa7CHE4 zScH?_FZV^q35%4sNG~|T%=X~9ToyZuTxq$cr*~z$jk;d|dM#VHy#y-=znjbhs|Nmv zk@v}Lzn`C>oc^j)g4J%{c|#{di9f~I9d@o ze>L{D9Gf!z#!=zh!$%hhJx9S-)civGKxELY-Npi@NuC z7Vo%4-g)1Ph^&#a#Eh4#C_O8&!yLbQ0C(iQvHxL%Vo4ziy|eZjbc^(RcC!b*GTAq8 z$N87SYiJp~EtyokCy7>Nr@wa;P+y?EFj-rXZ4WDCV?`0tjEo#P8UtqYMMkL=6@8n& z$T%G}PS%mvae(X{dnLx*@`ot7RTl?ihIO&-=(9|4aTe4D_jaFCYWme9ue{Hk->v0J zHOrH(%AR#krStV`6kv}^qPjQa*j;4|-+|TJB0Fz+ONiw$*r`}n2r>(wXQ;RM6wC~) zp4lm@fSDY-tswgffwkd zJC+o#L|}OsO+>7WOy-fy0G3-zU+L@dpEl*#Aqm@qfNkwpZ$7Ifyjp>_K;}y}s9Fol z2ik2MXgMZ4JL@gb&u5WW)cGKje}8}fvahhk{vFBvZ*M&`v6~X%azac}yQFT`J|`4h zjdAQ{`L+CZE3PU{Z4k)g@>!ze*7tV@v#mJZyr@G>yD>Xqm2vDDq*~^7R8V(8I=h~% zK~AOfNjbBY9(r@$Z1CnS@7yeAs>R^V-I@NFdA?>b_o%HcxjyqqjLdkjWJ)geK=v>k zevnoYI3ErN>kah=?qQ|OJgXhEbJ31+e3hJ(?dIt%NyI`{2^MvaYVGu#FC%hZzxRlb zUSMz)&wg+Zv}~?C-Xpn`<58ZE7j!&ctk*5=PkBv@ON`mw=EQHysPPQGT_By`Hx@;! zHO?$jq1SJYkg*c!bmf{F7CCiDs~A*9lDM*P)kx)pkBNOmMo23xBUCFdZl&|-MNyAK z+6OG=&cc{L$??Z`bVSx8vu2zJBH8gAh0HZa$mCV$t>w4mmYAg<8Iff@42g(f*$K6M z<&F2uJga|;%L!$DMxKMh*w9VryPh^CuC)?@RkEveAjfj{Rz&Muma*MSW8Twea=wEM zfvmw+)^B5`hb$)D>;5f$6MfG*XC#5u`pntu6Op~K8?^1qeJjCA67uYQ21ThKylh?i kG^|aBF$!H`*#d9Ie-QQ=kgEVJ4FCWD07*qoM6N<$f(SMqEC2ui literal 0 HcmV?d00001 From 6a123298e5a6adcdbef0e63024b236209b6be3fe Mon Sep 17 00:00:00 2001 From: Aaron1356 Date: Thu, 12 Feb 2026 15:57:48 -0600 Subject: [PATCH 749/812] [Documentation] Small Doc Update to params for GRF lidars (#26445) * small Doc Update to params for GRF lidars --- docs/en/SUMMARY.md | 2 +- docs/en/sensor/sfxx_lidar.md | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/en/SUMMARY.md b/docs/en/SUMMARY.md index 173abd0f54..261c8995d4 100644 --- a/docs/en/SUMMARY.md +++ b/docs/en/SUMMARY.md @@ -253,7 +253,7 @@ - [Benewake TFmini Lidar](sensor/tfmini.md) - [LeddarOne Lidar](sensor/leddar_one.md) - [Lidar-Lite](sensor/lidar_lite.md) - - [Lightware Lidars (SF/LW)](sensor/sfxx_lidar.md) + - [Lightware Lidars (SF/LW/GRF)](sensor/sfxx_lidar.md) - [Lightware SF45 Rotary Lidar](sensor/sf45_rotating_lidar.md) - [TeraRanger](sensor/teraranger.md) - [✘ Lanbao PSK-CM8JL65-CC5](sensor/cm8jl65_ir_distance_sensor.md) diff --git a/docs/en/sensor/sfxx_lidar.md b/docs/en/sensor/sfxx_lidar.md index 40d21ada31..e225422805 100644 --- a/docs/en/sensor/sfxx_lidar.md +++ b/docs/en/sensor/sfxx_lidar.md @@ -1,4 +1,4 @@ -# LightWare Lidar (SF1X/SF02/LW20/SF45) +# LightWare Lidar (SF1X/SF02/LW20/SF45/GRF250/GRF500) LightWare develops a range of light-weight, general purpose, laser altimeters ("Lidar") suitable for mounting on UAVs. These are useful for applications including terrain following, precision hovering (e.g. for photography), warning of regulatory height limits, anti-collision sensing etc. From f518f87d0f843d765ccaa6e2f8ece20fa45170fa Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Thu, 12 Feb 2026 22:05:22 +0000 Subject: [PATCH 750/812] docs: auto-sync metadata [skip ci] Co-Authored-By: PX4 BuildBot --- docs/en/middleware/dds_topics.md | 360 +++++++++++++++---------------- 1 file changed, 180 insertions(+), 180 deletions(-) diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index 91e30ef6cd..ae78fbc9fa 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -94,199 +94,199 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) -- [DebugValue](../msg_docs/DebugValue.md) -- [MissionResult](../msg_docs/MissionResult.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [Vtx](../msg_docs/Vtx.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) -- [GimbalControls](../msg_docs/GimbalControls.md) -- [Event](../msg_docs/Event.md) -- [NeuralControl](../msg_docs/NeuralControl.md) -- [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) -- [FollowTarget](../msg_docs/FollowTarget.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [SensorGyroFft](../msg_docs/SensorGyroFft.md) -- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) -- [ButtonEvent](../msg_docs/ButtonEvent.md) -- [OrbTestLarge](../msg_docs/OrbTestLarge.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [CellularStatus](../msg_docs/CellularStatus.md) -- [PowerButtonState](../msg_docs/PowerButtonState.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [OrbTestMedium](../msg_docs/OrbTestMedium.md) -- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [RcChannels](../msg_docs/RcChannels.md) -- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) -- [InputRc](../msg_docs/InputRc.md) -- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) -- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) -- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) -- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [DebugArray](../msg_docs/DebugArray.md) -- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) -- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [GpioIn](../msg_docs/GpioIn.md) +- [SystemPower](../msg_docs/SystemPower.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) - [LandingTargetPose](../msg_docs/LandingTargetPose.md) -- [SensorsStatus](../msg_docs/SensorsStatus.md) -- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) -- [RaptorInput](../msg_docs/RaptorInput.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) - [LogMessage](../msg_docs/LogMessage.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) - [SensorAirflow](../msg_docs/SensorAirflow.md) -- [ActionRequest](../msg_docs/ActionRequest.md) +- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [ActuatorArmed](../msg_docs/ActuatorArmed.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [DifferentialPressure](../msg_docs/DifferentialPressure.md) +- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) +- [PwmInput](../msg_docs/PwmInput.md) +- [OrbTestMedium](../msg_docs/OrbTestMedium.md) +- [QshellReq](../msg_docs/QshellReq.md) +- [GeofenceStatus](../msg_docs/GeofenceStatus.md) +- [RcChannels](../msg_docs/RcChannels.md) +- [Cpuload](../msg_docs/Cpuload.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [Mission](../msg_docs/Mission.md) +- [Airspeed](../msg_docs/Airspeed.md) +- [LedControl](../msg_docs/LedControl.md) +- [HealthReport](../msg_docs/HealthReport.md) +- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) +- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [InputRc](../msg_docs/InputRc.md) +- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) +- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) +- [SensorCorrection](../msg_docs/SensorCorrection.md) +- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) +- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) +- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [SensorSelection](../msg_docs/SensorSelection.md) +- [DeviceInformation](../msg_docs/DeviceInformation.md) +- [CameraTrigger](../msg_docs/CameraTrigger.md) +- [SensorAccel](../msg_docs/SensorAccel.md) +- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) +- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) +- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) +- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [VehicleImu](../msg_docs/VehicleImu.md) +- [MissionResult](../msg_docs/MissionResult.md) +- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [OrbTest](../msg_docs/OrbTest.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [FuelTankStatus](../msg_docs/FuelTankStatus.md) +- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) +- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [RtlStatus](../msg_docs/RtlStatus.md) +- [ButtonEvent](../msg_docs/ButtonEvent.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) +- [DebugValue](../msg_docs/DebugValue.md) +- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) +- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [SensorHygrometer](../msg_docs/SensorHygrometer.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) +- [GpioOut](../msg_docs/GpioOut.md) +- [ActuatorTest](../msg_docs/ActuatorTest.md) +- [SensorBaro](../msg_docs/SensorBaro.md) +- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) - [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) - [RoverRateStatus](../msg_docs/RoverRateStatus.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [PpsCapture](../msg_docs/PpsCapture.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) +- [EventV0](../msg_docs/EventV0.md) +- [GpioRequest](../msg_docs/GpioRequest.md) +- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) +- [MagWorkerData](../msg_docs/MagWorkerData.md) +- [FollowTarget](../msg_docs/FollowTarget.md) +- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) - [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) -- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) -- [UlogStreamAck](../msg_docs/UlogStreamAck.md) -- [SystemPower](../msg_docs/SystemPower.md) -- [EscReport](../msg_docs/EscReport.md) -- [GpsInjectData](../msg_docs/GpsInjectData.md) -- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [GainCompression](../msg_docs/GainCompression.md) -- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) -- [EscStatus](../msg_docs/EscStatus.md) -- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) -- [ActuatorTest](../msg_docs/ActuatorTest.md) -- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) -- [EstimatorStatus](../msg_docs/EstimatorStatus.md) -- [Px4ioStatus](../msg_docs/Px4ioStatus.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) +- [ActionRequest](../msg_docs/ActionRequest.md) - [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [GpsInjectData](../msg_docs/GpsInjectData.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) +- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) +- [UlogStream](../msg_docs/UlogStream.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [RcParameterMap](../msg_docs/RcParameterMap.md) +- [AdcReport](../msg_docs/AdcReport.md) +- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) +- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [GpioConfig](../msg_docs/GpioConfig.md) +- [GainCompression](../msg_docs/GainCompression.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [SensorUwb](../msg_docs/SensorUwb.md) +- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) +- [PowerButtonState](../msg_docs/PowerButtonState.md) +- [Rpm](../msg_docs/Rpm.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [CellularStatus](../msg_docs/CellularStatus.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) +- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) +- [OrbTestLarge](../msg_docs/OrbTestLarge.md) +- [BatteryInfo](../msg_docs/BatteryInfo.md) +- [CameraStatus](../msg_docs/CameraStatus.md) +- [QshellRetval](../msg_docs/QshellRetval.md) +- [SensorMag](../msg_docs/SensorMag.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [AirspeedWind](../msg_docs/AirspeedWind.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) +- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) +- [GpsDump](../msg_docs/GpsDump.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) +- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) +- [SensorsStatus](../msg_docs/SensorsStatus.md) +- [EstimatorStatus](../msg_docs/EstimatorStatus.md) +- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) +- [VehicleAirData](../msg_docs/VehicleAirData.md) +- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) - [GeneratorStatus](../msg_docs/GeneratorStatus.md) - [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [GpioConfig](../msg_docs/GpioConfig.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) -- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [Cpuload](../msg_docs/Cpuload.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) -- [TuneControl](../msg_docs/TuneControl.md) -- [QshellRetval](../msg_docs/QshellRetval.md) -- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) - [LandingGearWheel](../msg_docs/LandingGearWheel.md) -- [Mission](../msg_docs/Mission.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) -- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) -- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) -- [DeviceInformation](../msg_docs/DeviceInformation.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) -- [LedControl](../msg_docs/LedControl.md) -- [SensorSelection](../msg_docs/SensorSelection.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) -- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) -- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) -- [QshellReq](../msg_docs/QshellReq.md) -- [EventV0](../msg_docs/EventV0.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [SensorGyro](../msg_docs/SensorGyro.md) +- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) +- [PositionSetpoint](../msg_docs/PositionSetpoint.md) - [EstimatorStates](../msg_docs/EstimatorStates.md) -- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) -- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) -- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) -- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [RtlStatus](../msg_docs/RtlStatus.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) -- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [AdcReport](../msg_docs/AdcReport.md) -- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) -- [GpioRequest](../msg_docs/GpioRequest.md) +- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) +- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) +- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) - [SatelliteInfo](../msg_docs/SatelliteInfo.md) - [IrlockReport](../msg_docs/IrlockReport.md) -- [Rpm](../msg_docs/Rpm.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [GpioOut](../msg_docs/GpioOut.md) -- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) -- [SensorTemp](../msg_docs/SensorTemp.md) -- [EstimatorBias](../msg_docs/EstimatorBias.md) -- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) -- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) -- [MountOrientation](../msg_docs/MountOrientation.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [ParameterUpdate](../msg_docs/ParameterUpdate.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) -- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) -- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) -- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) -- [SensorGyro](../msg_docs/SensorGyro.md) -- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) -- [HealthReport](../msg_docs/HealthReport.md) -- [GpsDump](../msg_docs/GpsDump.md) -- [SensorAccel](../msg_docs/SensorAccel.md) -- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) -- [Airspeed](../msg_docs/Airspeed.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [MagWorkerData](../msg_docs/MagWorkerData.md) -- [PwmInput](../msg_docs/PwmInput.md) -- [CameraTrigger](../msg_docs/CameraTrigger.md) -- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) -- [TecsStatus](../msg_docs/TecsStatus.md) -- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) -- [ActuatorArmed](../msg_docs/ActuatorArmed.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [Gripper](../msg_docs/Gripper.md) -- [VehicleRoi](../msg_docs/VehicleRoi.md) -- [AirspeedWind](../msg_docs/AirspeedWind.md) -- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) -- [BatteryInfo](../msg_docs/BatteryInfo.md) -- [RadioStatus](../msg_docs/RadioStatus.md) -- [VehicleAirData](../msg_docs/VehicleAirData.md) -- [RaptorStatus](../msg_docs/RaptorStatus.md) -- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) -- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) -- [GeofenceStatus](../msg_docs/GeofenceStatus.md) -- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) -- [SensorUwb](../msg_docs/SensorUwb.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) - [Ping](../msg_docs/Ping.md) -- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [PpsCapture](../msg_docs/PpsCapture.md) -- [RcParameterMap](../msg_docs/RcParameterMap.md) -- [UlogStream](../msg_docs/UlogStream.md) +- [CameraCapture](../msg_docs/CameraCapture.md) +- [Vtx](../msg_docs/Vtx.md) +- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) +- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) +- [EscReport](../msg_docs/EscReport.md) +- [Gripper](../msg_docs/Gripper.md) +- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [VehicleRoi](../msg_docs/VehicleRoi.md) +- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [NeuralControl](../msg_docs/NeuralControl.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [GimbalControls](../msg_docs/GimbalControls.md) +- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) +- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [Event](../msg_docs/Event.md) +- [RadioStatus](../msg_docs/RadioStatus.md) - [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) -- [GpioIn](../msg_docs/GpioIn.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) -- [SensorBaro](../msg_docs/SensorBaro.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) -- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) -- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) -- [SensorCorrection](../msg_docs/SensorCorrection.md) -- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) -- [VehicleImu](../msg_docs/VehicleImu.md) -- [PositionSetpoint](../msg_docs/PositionSetpoint.md) -- [SensorMag](../msg_docs/SensorMag.md) -- [CameraStatus](../msg_docs/CameraStatus.md) +- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) ::: From d9996742bee2d87e0a90d771da10c641cbbe1603 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 11 Feb 2026 10:27:13 -0800 Subject: [PATCH 751/812] setup: drop Ubuntu 18.04/20.04 support from ubuntu.sh Remove Gazebo Classic installation branches for Ubuntu 18.04 and 20.04. The script now only supports Ubuntu 22.04 and 24.04 with Gazebo Harmonic. Supported Ubuntu LTS versions going forward: - Ubuntu 24.04 (primary, used in CI and release builds) - Ubuntu 22.04 (secondary, still supported) When Ubuntu 26.04 LTS releases we will bump to 26.04/24.04. Signed-off-by: Ramon Roche --- Tools/setup/ubuntu.sh | 43 ++++++++++++------------------------------- 1 file changed, 12 insertions(+), 31 deletions(-) diff --git a/Tools/setup/ubuntu.sh b/Tools/setup/ubuntu.sh index a1cbc78864..f84db9a603 100755 --- a/Tools/setup/ubuntu.sh +++ b/Tools/setup/ubuntu.sh @@ -6,9 +6,9 @@ set -e ## Can also be used in docker. ## ## Installs: -## - Common dependencies and tools for nuttx, jMAVSim, Gazebo +## - Common dependencies and tools for nuttx, Gazebo ## - NuttX toolchain (omit with arg: --no-nuttx) -## - jMAVSim and Gazebo9 simulator (omit with arg: --no-sim-tools) +## - Gazebo Harmonic simulator (omit with arg: --no-sim-tools) ## INSTALL_NUTTX="true" @@ -207,37 +207,18 @@ if [[ $INSTALL_SIM == "true" ]]; then bc \ ; - # Gazebo / Gazebo classic installation - if [[ "${UBUNTU_RELEASE}" == "18.04" || "${UBUNTU_RELEASE}" == "20.04" ]]; then - sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list' - wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add - - # Update list, since new gazebo-stable.list has been added - sudo apt-get update -y --quiet + # Gazebo Harmonic installation (Ubuntu 22.04+) + echo "[ubuntu.sh] Gazebo (Harmonic) will be installed" + # Add Gazebo binary repository + sudo wget https://packages.osrfoundation.org/gazebo.gpg -O /usr/share/keyrings/pkgs-osrf-archive-keyring.gpg + echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/pkgs-osrf-archive-keyring.gpg] http://packages.osrfoundation.org/gazebo/ubuntu-stable $(lsb_release -cs) main" | sudo tee /etc/apt/sources.list.d/gazebo-stable.list > /dev/null + sudo apt-get update -y --quiet - # Install Gazebo classic - if [[ "${UBUNTU_RELEASE}" == "18.04" ]]; then - gazebo_classic_version=9 - gazebo_packages="gazebo$gazebo_classic_version libgazebo$gazebo_classic_version-dev" - else - # default and Ubuntu 20.04 - gazebo_classic_version=11 - gazebo_packages="gazebo$gazebo_classic_version libgazebo$gazebo_classic_version-dev" - fi - else - # Expects Ubuntu 22.04 > by default - echo "[ubuntu.sh] Gazebo (Harmonic) will be installed" - echo "[ubuntu.sh] Earlier versions will be removed" - # Add Gazebo binary repository - sudo wget https://packages.osrfoundation.org/gazebo.gpg -O /usr/share/keyrings/pkgs-osrf-archive-keyring.gpg - echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/pkgs-osrf-archive-keyring.gpg] http://packages.osrfoundation.org/gazebo/ubuntu-stable $(lsb_release -cs) main" | sudo tee /etc/apt/sources.list.d/gazebo-stable.list > /dev/null - sudo apt-get update -y --quiet + # Install Gazebo + gazebo_packages="gz-harmonic libunwind-dev" - # Install Gazebo - gazebo_packages="gz-harmonic libunwind-dev" - - if [[ "${UBUNTU_RELEASE}" == "24.04" ]]; then - gazebo_packages="$gazebo_packages cppzmq-dev" - fi + if [[ "${UBUNTU_RELEASE}" == "24.04" ]]; then + gazebo_packages="$gazebo_packages cppzmq-dev" fi sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \ From df242827d2cd2376f5b1eb5d76571bce258230aa Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 11 Feb 2026 10:28:18 -0800 Subject: [PATCH 752/812] docs: remove outdated Ubuntu/GCC references from build instructions MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - Remove Ubuntu 18.04 troubleshooting sections (compile errors, VSCode inotify) — Ubuntu 18.04 is no longer supported - Remove Gazebo Classic SITL dropdown from first build section - Update FMUv2 flash warning to reference gcc-arm-none-eabi from current Ubuntu LTS instead of vague "CI/docker" reference - Update flash overflow guidance to point at Ubuntu LTS toolchain - Simplify "too many open files" error example (remove old GCC 7.2.1 path from 2017) Signed-off-by: Ramon Roche --- docs/en/dev_setup/building_px4.md | 40 +++---------------------------- 1 file changed, 3 insertions(+), 37 deletions(-) diff --git a/docs/en/dev_setup/building_px4.md b/docs/en/dev_setup/building_px4.md index b5ab7ccdc3..4e941d2fb6 100644 --- a/docs/en/dev_setup/building_px4.md +++ b/docs/en/dev_setup/building_px4.md @@ -39,15 +39,6 @@ Navigate into the **PX4-Autopilot** directory and start [Gazebo SITL](../sim_gaz make px4_sitl gz_x500 ``` -::: details If you installed Gazebo Classic -Start [Gazebo Classic SITL](../sim_gazebo_classic/index.md) using the following command: - -```sh -make px4_sitl gazebo-classic -``` - -::: - This will bring up the PX4 console: ![PX4 Console](../../assets/toolchain/console_gazebo.png) @@ -126,7 +117,7 @@ The following list shows the build commands for the [Pixhawk standard](../flight - [Pixhawk 1 (FMUv2)](../flight_controller/pixhawk.md): `make px4_fmu-v2_default` :::warning - You **must** use a supported version of GCC to build this board (e.g. the same as used by [CI/docker](../test_and_ci/docker.md)) or remove modules from the build. Building with an unsupported GCC may fail, as PX4 is close to the board's 1MB flash limit. + You **must** use a supported version of GCC to build this board (e.g. the `gcc-arm-none-eabi` package from the current Ubuntu LTS, which is the same toolchain used by CI) or remove modules from the build. Building with an unsupported GCC may fail, as PX4 is close to the board's 1MB flash limit. ::: - Pixhawk 1 with 2 MB flash: `make px4_fmu-v3_default` @@ -191,7 +182,7 @@ The `region 'flash' overflowed by XXXX bytes` error indicates that the firmware This is common for `make px4_fmu-v2_default` builds, where the flash size is limited to 1MB. If you're building the _vanilla_ master branch, the most likely cause is using an unsupported version of GCC. -In this case, install the version specified in the [Developer Toolchain](../dev_setup/dev_env.md) instructions. +In this case, install the `gcc-arm-none-eabi` package from the current Ubuntu LTS as described in the [Developer Toolchain](../dev_setup/dev_env.md) instructions. If building your own branch, it is possible that you have increased the firmware size over the 1MB limit. In this case you will need to remove any drivers/modules that you don't need from the build. @@ -204,7 +195,7 @@ The PX4 build system opens a large number of files, so you may exceed this numbe The build toolchain will then report `Too many open files` for many files, as shown below: ```sh -/usr/local/Cellar/gcc-arm-none-eabi/20171218/bin/../lib/gcc/arm-none-eabi/7.2.1/../../../../arm-none-eabi/bin/ld: cannot find NuttX/nuttx/fs/libfs.a: Too many open files +arm-none-eabi-ld: cannot find NuttX/nuttx/fs/libfs.a: Too many open files ``` The solution is to increase the maximum allowed number of open files (e.g. to 300). @@ -227,31 +218,6 @@ xcode-select --install sudo ln -s /Library/Developer/CommandLineTools/SDKs/MacOSX.sdk/usr/include/* /usr/local/include/ ``` -### Ubuntu 18.04: Compile errors involving arm_none_eabi_gcc - -Build issues related to `arm_none_eabi_gcc`may be due to a broken g++ toolchain installation. -You can verify that this is the case by checking for missing dependencies using: - -```sh -arm-none-eabi-gcc --version -arm-none-eabi-g++ --version -arm-none-eabi-gdb --version -arm-none-eabi-size --version -``` - -Example of bash output with missing dependencies: - -```sh -arm-none-eabi-gdb --version -arm-none-eabi-gdb: command not found -``` - -This can be resolved by removing and [reinstalling the compiler](https://askubuntu.com/questions/1243252/how-to-install-arm-none-eabi-gdb-on-ubuntu-20-04-lts-focal-fossa). - -### Ubuntu 18.04: Visual Studio Code is unable to watch for file changes in this large workspace - -See [Visual Studio Code IDE (VSCode) > Troubleshooting](../dev_setup/vscode.md#troubleshooting). - ### Failed to import Python packages "Failed to import" errors when running the `make px4_sitl jmavsim` command indicates that some Python packages are not installed (where expected). From 103a61450ee4e2f675423e61fb9f9eb411cf0dfe Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 11 Feb 2026 10:29:10 -0800 Subject: [PATCH 753/812] docs: update Ubuntu dev env to reflect supported LTS versions - Replace "older version" collapsible with info block stating supported versions: Ubuntu 24.04 (primary) and 22.04 - Remove Gazebo Classic references (Ubuntu 22.04 section, install step) - Note that GCC version comes from Ubuntu package manager - Clarify that GCC version depends on Ubuntu release Signed-off-by: Ramon Roche --- docs/en/dev_setup/dev_env_linux_ubuntu.md | 25 ++++++++--------------- 1 file changed, 9 insertions(+), 16 deletions(-) diff --git a/docs/en/dev_setup/dev_env_linux_ubuntu.md b/docs/en/dev_setup/dev_env_linux_ubuntu.md index 2c80b959ce..0c7917c8d3 100644 --- a/docs/en/dev_setup/dev_env_linux_ubuntu.md +++ b/docs/en/dev_setup/dev_env_linux_ubuntu.md @@ -4,20 +4,14 @@ The following instructions use a bash script to set up the PX4 development envir The environment includes: -- [Gazebo Simulator](../sim_gazebo_gz/index.md) ("Harmonic") -- [Build toolchain for Pixhawk (and other NuttX-based hardware)](../dev_setup/building_px4.md#nuttx-pixhawk-based-boards). - -On Ubuntu 22.04: - -- [Gazebo Classic Simulator](../sim_gazebo_classic/index.md) can be used instead of Gazebo. - Gazebo is nearing feature-parity with Gazebo-Classic on PX4, and will soon replace it for all use cases. +- [Gazebo Simulator](../sim_gazebo_gz/index.md) (Gazebo Harmonic) +- [Build toolchain for Pixhawk (and other NuttX-based hardware)](../dev_setup/building_px4.md#nuttx-pixhawk-based-boards) using the `gcc-arm-none-eabi` compiler from the Ubuntu package manager. The build toolchain for other flight controllers, simulators, and working with ROS are discussed in the [Other Targets](#other-targets) section below. -::: details Can I use an older version of Ubuntu? -PX4 supports the current and last Ubuntu LTS release where possible. -Older releases are not supported (so you can't raise defects against them), but may still work. -For example, Gazebo Classic setup is included in our standard build instructions for macOS, Ubuntu 18.04 and 20.04, and Windows on WSL2 for the same hosts. +:::info +PX4 targets the **current Ubuntu LTS** (24.04) for CI and release builds, with the **previous LTS** (22.04) also supported. +Older Ubuntu versions are not supported and may not work. ::: ## Simulation and NuttX (Pixhawk) Targets @@ -50,19 +44,18 @@ To install the toolchain: - Acknowledge any prompts as the script progress. - You can use the `--no-nuttx` and `--no-sim-tools` options to omit the NuttX and/or simulation tools. -3. If you need Gazebo Classic (Ubuntu 22.04 only) then you can manually remove Gazebo and install it by following the instructions in [Gazebo Classic > Installation](../sim_gazebo_classic/index.md#installation). - -4. Restart the computer on completion. +3. Restart the computer on completion. :::details Additional notes These notes are provided "for information only": - This setup is supported by the PX4 Dev Team. The instructions may also work on other Debian Linux based systems. -- You can verify the NuttX installation by confirming the `gcc` version as shown: +- You can verify the NuttX installation by confirming `gcc` is available. + The version depends on your Ubuntu release (e.g. GCC 13.2.1 on Ubuntu 24.04): ```sh - $arm-none-eabi-gcc --version + $ arm-none-eabi-gcc --version arm-none-eabi-gcc (15:13.2.rel1-2) 13.2.1 20231009 Copyright (C) 2023 Free Software Foundation, Inc. From 8017baa6e6ebec2de97cce19998322c29a3ea865 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 11 Feb 2026 10:31:45 -0800 Subject: [PATCH 754/812] docs: remove outdated Ubuntu/Gazebo Classic references docker.md: - Update container hierarchy from focal to jammy - Replace ROS Noetic/Foxy references with ROS 2 Humble - Update docker run example to use humble container - Update SITL example from gazebo-classic to gz_x500 - Update VM tested version from Ubuntu 14.04 to 22.04 vscode.md: - Remove "Ubuntu 18.04" from inotify troubleshooting header (this issue is not Ubuntu-version-specific) dev_env_linux_centos.md: - Update GCC warning to reference current Ubuntu LTS toolchain instead of old Focal Docker file Signed-off-by: Ramon Roche --- docs/en/dev_setup/dev_env_linux_centos.md | 5 +++-- docs/en/dev_setup/vscode.md | 4 ++-- docs/en/test_and_ci/docker.md | 25 ++++++++++------------- 3 files changed, 16 insertions(+), 18 deletions(-) diff --git a/docs/en/dev_setup/dev_env_linux_centos.md b/docs/en/dev_setup/dev_env_linux_centos.md index e9b23dee5f..92398f30d8 100644 --- a/docs/en/dev_setup/dev_env_linux_centos.md +++ b/docs/en/dev_setup/dev_env_linux_centos.md @@ -39,8 +39,9 @@ You may want to also install `python-pip` and `screen`. Execute the script below to install GCC 7-2017-q4: :::warning -This version of GCC is out of date. -At time of writing the current version on Ubuntu is `9-2020-q2-update` (see [focal nuttx docker file](https://github.com/PX4/PX4-containers/blob/master/docker/Dockerfile_nuttx-focal#L28)) +This version of GCC is very outdated. +PX4 now uses the `gcc-arm-none-eabi` package from the current Ubuntu LTS (GCC 13.2.1 on Ubuntu 24.04). +This CentOS guide is community-maintained and may not produce working builds. ::: ```sh diff --git a/docs/en/dev_setup/vscode.md b/docs/en/dev_setup/vscode.md index 302e68b250..9a4b60a480 100644 --- a/docs/en/dev_setup/vscode.md +++ b/docs/en/dev_setup/vscode.md @@ -124,10 +124,10 @@ Once that is done you don't need to do anything else; the toolchain will automat This section includes guidance on setup and build errors. -### Ubuntu 18.04: "Visual Studio Code is unable to watch for file changes in this large workspace" +### "Visual Studio Code is unable to watch for file changes in this large workspace" This error surfaces on startup. -On some systems, there is an upper-limit of 8192 file handles imposed on applications, which means that VSCode might not be able to detect file modifications in `/PX4-Autopilot`. +On some systems, there is an upper-limit on file handles imposed on applications, which means that VSCode might not be able to detect file modifications in `/PX4-Autopilot`. You can increase this limit to avoid the error, at the expense of memory consumption. Follow the [instructions here](https://code.visualstudio.com/docs/setup/linux#_visual-studio-code-is-unable-to-watch-for-file-changes-in-this-large-workspace-error-enospc). diff --git a/docs/en/test_and_ci/docker.md b/docs/en/test_and_ci/docker.md index 43f0ee5eb8..03121ff5ab 100644 --- a/docs/en/test_and_ci/docker.md +++ b/docs/en/test_and_ci/docker.md @@ -1,6 +1,6 @@ # PX4 Docker Containers -Docker containers are provided for the complete [PX4 development toolchain](../dev_setup/dev_env.md#supported-targets) including NuttX and Linux based hardware, [Gazebo Classic](../sim_gazebo_classic/index.md) simulation, and [ROS](../simulation/ros_interface.md). +Docker containers are provided for the complete [PX4 development toolchain](../dev_setup/dev_env.md#supported-targets) including NuttX and Linux based hardware, [Gazebo](../sim_gazebo_gz/index.md) simulation, and [ROS 2](../ros2/user_guide.md). This topic shows how to use the [available docker containers](#px4_containers) to access the build environment in a local Linux computer. @@ -41,22 +41,19 @@ The available containers are on [GitHub here](https://github.com/PX4/PX4-contain These allow testing of various build targets and configurations (the included tools can be inferred from their names). The containers are hierarchical, such that containers have the functionality of their parents. -For example, the partial hierarchy below shows that the docker container with NuttX build tools (`px4-dev-nuttx-focal`) does not include ROS 2, while the simulation containers do: +For example, the partial hierarchy below shows that the docker container with NuttX build tools (`px4-dev-nuttx-jammy`) does not include ROS 2, while the simulation containers do: ```plain -- px4io/px4-dev-base-focal - - px4io/px4-dev-nuttx-focal - - px4io/px4-dev-simulation-focal - - px4io/px4-dev-ros-noetic - - px4io/px4-dev-ros2-foxy - - px4io/px4-dev-ros2-rolling - px4io/px4-dev-base-jammy - px4io/px4-dev-nuttx-jammy + - px4io/px4-dev-simulation-jammy + - px4io/px4-dev-ros2-humble + - px4io/px4-dev-ros2-rolling ``` -The most recent version can be accessed using the `latest` tag: `px4io/px4-dev-nuttx-focal:latest` +The most recent version can be accessed using the `latest` tag: `px4io/px4-dev-nuttx-jammy:latest` (available tags are listed for each container on _hub.docker.com_. -For example, the `px4io/px4-dev-nuttx-focal` tags can be found on [hub.docker.com here](https://hub.docker.com/r/px4io/px4-dev-nuttx-focal/tags?page=1&ordering=last_updated)). +For example, the `px4io/px4-dev-nuttx-jammy` tags can be found on [hub.docker.com here](https://hub.docker.com/r/px4io/px4-dev-nuttx-jammy/tags?page=1&ordering=last_updated)). :::tip Typically you should use a recent container, but not necessarily the `latest` (as this changes too often). @@ -137,7 +134,7 @@ docker run -it --privileged \ -v /tmp/.X11-unix:/tmp/.X11-unix:ro \ -e DISPLAY=:0 \ --network host \ ---name=px4-ros px4io/px4-dev-ros2-foxy:2022-07-31 bash +--name=px4-ros px4io/px4-dev-ros2-humble:latest bash ``` ::: info @@ -155,7 +152,7 @@ Verify if everything works by running, for example, SITL: ```sh cd src/PX4-Autopilot #This is -make px4_sitl_default gazebo-classic +make px4_sitl gz_x500 ``` ### Re-enter the Container @@ -219,7 +216,7 @@ This ensures that all files created within the container will be accessible on t #### Graphics Driver Issues -It's possible that running Gazebo Classic will result in a similar error message like the following: +It's possible that running Gazebo will result in a similar error message like the following: ```sh libGL error: failed to load driver: swrast @@ -239,7 +236,7 @@ Any recent Linux distribution should work. The following configuration is tested: -- OS X with VMWare Fusion and Ubuntu 14.04 (Docker container with GUI support on Parallels make the X-Server crash). +- OS X with VMWare Fusion and Ubuntu 22.04 (Docker container with GUI support on Parallels make the X-Server crash). **Memory** From aecd1461d73b341f2f96dff25ea816a145074741 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 11 Feb 2026 10:40:33 -0800 Subject: [PATCH 755/812] docs: document px4-dev as the recommended container The new px4-dev container replaces the old per-distro container hierarchy from PX4/PX4-containers. It is: - Multi-architecture (linux/amd64 + linux/arm64) - Based on Ubuntu 24.04 - Built from the in-tree Dockerfile via GitHub Actions - Published to both ghcr.io and Docker Hub - Tagged with PX4 versions (e.g. px4-dev:v1.16.0) Mark the legacy per-distro containers (px4-dev-nuttx-jammy, px4-dev-ros2-humble, etc.) as deprecated, note that px4-sim is planned for simulation workflows. Update all examples to use px4-dev instead of legacy containers. Signed-off-by: Ramon Roche --- docs/en/dev_setup/building_px4.md | 10 +++++++ docs/en/test_and_ci/docker.md | 45 +++++++++++++++++-------------- 2 files changed, 35 insertions(+), 20 deletions(-) diff --git a/docs/en/dev_setup/building_px4.md b/docs/en/dev_setup/building_px4.md index 4e941d2fb6..c683627102 100644 --- a/docs/en/dev_setup/building_px4.md +++ b/docs/en/dev_setup/building_px4.md @@ -79,6 +79,16 @@ cd PX4-Autopilot make px4_fmu-v5_default ``` +:::tip +You can also build using the [px4-dev Docker container](../test_and_ci/docker.md) without installing the toolchain locally. +From the PX4-Autopilot directory: + +```sh +./Tools/docker_run.sh 'make px4_fmu-v5_default' +``` + +::: + A successful run will end with similar output to: ```sh diff --git a/docs/en/test_and_ci/docker.md b/docs/en/test_and_ci/docker.md index 03121ff5ab..82308fe62f 100644 --- a/docs/en/test_and_ci/docker.md +++ b/docs/en/test_and_ci/docker.md @@ -5,8 +5,7 @@ Docker containers are provided for the complete [PX4 development toolchain](../d This topic shows how to use the [available docker containers](#px4_containers) to access the build environment in a local Linux computer. ::: info -Dockerfiles and README can be found on [Github here](https://github.com/PX4/PX4-containers/tree/master?tab=readme-ov-file#container-hierarchy). -They are built automatically on [Docker Hub](https://hub.docker.com/u/px4io/). +The recommended `px4-dev` container is built from the [Dockerfile in the PX4-Autopilot source tree](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/setup/Dockerfile) by the [Container build workflow](https://github.com/PX4/PX4-Autopilot/actions/workflows/dev_container.yml). ::: ## Prerequisites @@ -35,30 +34,36 @@ sudo usermod -aG docker $USER # Log in/out again before using docker! ``` -## Container Hierarchy {#px4_containers} +## px4-dev Container (Recommended) {#px4_containers} -The available containers are on [GitHub here](https://github.com/PX4/PX4-containers/tree/master?tab=readme-ov-file#container-hierarchy). +The **`px4-dev`** container is the recommended container for building PX4 firmware. +It is a single, multi-architecture container (linux/amd64 and linux/arm64) based on Ubuntu 24.04 that includes everything needed to build PX4 for NuttX hardware targets. -These allow testing of various build targets and configurations (the included tools can be inferred from their names). -The containers are hierarchical, such that containers have the functionality of their parents. -For example, the partial hierarchy below shows that the docker container with NuttX build tools (`px4-dev-nuttx-jammy`) does not include ROS 2, while the simulation containers do: +It is published to both registries simultaneously: -```plain -- px4io/px4-dev-base-jammy - - px4io/px4-dev-nuttx-jammy - - px4io/px4-dev-simulation-jammy - - px4io/px4-dev-ros2-humble - - px4io/px4-dev-ros2-rolling -``` +- **GitHub Container Registry:** [ghcr.io/px4/px4-dev](https://github.com/PX4/PX4-Autopilot/pkgs/container/px4-dev) +- **Docker Hub:** [px4io/px4-dev](https://hub.docker.com/r/px4io/px4-dev) -The most recent version can be accessed using the `latest` tag: `px4io/px4-dev-nuttx-jammy:latest` -(available tags are listed for each container on _hub.docker.com_. -For example, the `px4io/px4-dev-nuttx-jammy` tags can be found on [hub.docker.com here](https://hub.docker.com/r/px4io/px4-dev-nuttx-jammy/tags?page=1&ordering=last_updated)). +The container includes: + +- Ubuntu 24.04 base +- ARM cross-compiler (`gcc-arm-none-eabi`) and Xtensa compiler (for ESP32 targets) +- Build tools: `cmake`, `ninja`, `ccache`, `make` +- Python 3 with PX4 build dependencies +- NuttX toolchain libraries (`libnewlib-arm-none-eabi`, etc.) + +The container is built from the [Dockerfile](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/setup/Dockerfile) in the PX4 source tree using the [Container build workflow](https://github.com/PX4/PX4-Autopilot/actions/workflows/dev_container.yml). +Images are tagged with the PX4 version (e.g. `px4io/px4-dev:v1.16.0`). :::tip -Typically you should use a recent container, but not necessarily the `latest` (as this changes too often). +A `px4-sim` container with simulation tools (Gazebo Harmonic) is planned to complement `px4-dev` for simulation workflows. ::: +### Legacy Containers + +The older per-distro containers from [PX4/PX4-containers](https://github.com/PX4/PX4-containers) (e.g. `px4-dev-nuttx-jammy`, `px4-dev-ros2-humble`, etc.) are no longer recommended. +They will be replaced by `px4-dev` (for builds) and the upcoming `px4-sim` (for simulation). + ## Use the Docker Container The following instructions show how to build PX4 source code on the host computer using a toolchain running in a docker container. @@ -118,7 +123,7 @@ Where, - ``: The host computer directory to be mapped to `` in the container. This should normally be the **PX4-Autopilot** directory. - ``: The location of the shared (source) directory when inside the container. - ``: A name for the docker container being created. This can later be used if we need to reference the container again. -- `:`: The container with version tag to start - e.g.: `px4io/px4-dev-ros:2017-10-23`. +- `:`: The container with version tag to start - e.g.: `px4io/px4-dev:v1.16.0`. - ``: The command to invoke on the new container. E.g. `bash` is used to open a bash shell in the container. The concrete example below shows how to open a bash shell and share the directory **~/src/PX4-Autopilot** on the host computer. @@ -134,7 +139,7 @@ docker run -it --privileged \ -v /tmp/.X11-unix:/tmp/.X11-unix:ro \ -e DISPLAY=:0 \ --network host \ ---name=px4-ros px4io/px4-dev-ros2-humble:latest bash +--name=px4-dev px4io/px4-dev:v1.16.0 bash ``` ::: info From ad0b6bdc6b6738bf98f0fd4664148272068ba5d6 Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Thu, 12 Feb 2026 15:07:31 +1100 Subject: [PATCH 756/812] Subedit --- docs/en/dev_setup/building_px4.md | 5 +++-- docs/en/dev_setup/config_initial.md | 8 ++++---- docs/en/dev_setup/dev_env.md | 6 +++--- docs/en/dev_setup/dev_env_windows_wsl.md | 16 ++++++++-------- docs/en/ros/mavros_installation.md | 4 ++-- 5 files changed, 20 insertions(+), 19 deletions(-) diff --git a/docs/en/dev_setup/building_px4.md b/docs/en/dev_setup/building_px4.md index c683627102..576266ae4d 100644 --- a/docs/en/dev_setup/building_px4.md +++ b/docs/en/dev_setup/building_px4.md @@ -127,7 +127,8 @@ The following list shows the build commands for the [Pixhawk standard](../flight - [Pixhawk 1 (FMUv2)](../flight_controller/pixhawk.md): `make px4_fmu-v2_default` :::warning - You **must** use a supported version of GCC to build this board (e.g. the `gcc-arm-none-eabi` package from the current Ubuntu LTS, which is the same toolchain used by CI) or remove modules from the build. Building with an unsupported GCC may fail, as PX4 is close to the board's 1MB flash limit. + You **must** use a supported version of GCC to build this board (e.g. the `gcc-arm-none-eabi` package from the current Ubuntu LTS, which is the same toolchain used by CI) or remove modules from the build. + Building with an unsupported GCC may fail, as PX4 is close to the board's 1MB flash limit. ::: - Pixhawk 1 with 2 MB flash: `make px4_fmu-v3_default` @@ -238,7 +239,7 @@ You may need to install it using: pip3 install --user jinja2 ``` -If you have already installed these dependencies this may be because there is more than one Python version on the computer (e.g. Python 2.7.16 Python 3.8.3), and the module is not present in the version used by the build toolchain. +If you have already installed these dependencies this may be because there is more than one Python version on the computer (e.g. Python 2.7.16 and Python 3.8.3), and the module is not present in the version used by the build toolchain. You should be able to fix this by explicitly installing the dependencies as shown: diff --git a/docs/en/dev_setup/config_initial.md b/docs/en/dev_setup/config_initial.md index f636aef195..b98f0bf24e 100644 --- a/docs/en/dev_setup/config_initial.md +++ b/docs/en/dev_setup/config_initial.md @@ -20,7 +20,7 @@ The equipment below is highly recommended: ::: - Lenovo Thinkpad with i5-core running Windows 11 - MacBook Pro (early 2015 and later) with macOS 10.15 or later - - Lenovo Thinkpad i5 with Ubuntu Linux 20.04 or later + - Lenovo Thinkpad i5 with Ubuntu Linux 22.04 or later - **Ground control station** (computer or tablet): - iPad (may require Wifi telemetry adapter) @@ -39,9 +39,9 @@ Install the [QGroundControl Daily Build](../dev_setup/qgc_daily_build.md) for a To configure the vehicle: 1. [Install PX4 firmware](../config/firmware.md#installing-px4-main-beta-or-custom-firmware) (including "custom" firmware with your own changes). -1. [Start with the airframe](../config/airframe.md) that best-matches your vehicle from the [airframe reference](../airframes/airframe_reference.md). -1. [Basic Configuration](../config/index.md) explains how to perform basic configuration. -1. [Parameter Configuration](../advanced_config/parameters.md) explains how you can find and modify individual parameters. +2. [Start with the airframe](../config/airframe.md) that best-matches your vehicle from the [airframe reference](../airframes/airframe_reference.md). +3. [Basic Configuration](../config/index.md) explains how to perform basic configuration. +4. [Parameter Configuration](../advanced_config/parameters.md) explains how you can find and modify individual parameters. ::: info diff --git a/docs/en/dev_setup/dev_env.md b/docs/en/dev_setup/dev_env.md index b57ab037c0..5d4810e00a 100644 --- a/docs/en/dev_setup/dev_env.md +++ b/docs/en/dev_setup/dev_env.md @@ -2,7 +2,7 @@ The _supported platforms_ for PX4 development are: -- [Ubuntu Linux (24.04/22.04)](../dev_setup/dev_env_linux_ubuntu.md) — Recommended +- [Ubuntu Linux (24.04/22.04)](../dev_setup/dev_env_linux_ubuntu.md) - [Windows (10/11)](../dev_setup/dev_env_windows_wsl.md) — via WSL2 - [macOS](../dev_setup/dev_env_mac.md) @@ -15,9 +15,9 @@ The table below shows what PX4 targets you can build on each OS. | **NuttX based hardware:** [Pixhawk Series](../flight_controller/pixhawk_series.md), [Crazyflie](../complete_vehicles_mc/crazyflie2.md) | ✓ | ✓ | ✓ | | **Linux-based hardware:** [Raspberry Pi 2/3](../flight_controller/raspberry_pi_navio2.md) | ✓ | | | | **Simulation:** [Gazebo SITL](../sim_gazebo_gz/index.md) | ✓ | ✓ | ✓ | -| **Simulation:** [Gazebo Classic SITL](../sim_gazebo_classic/index.md) | ✓ | ✓ | ✓ | -| **Simulation:** [ROS with Gazebo Classic](../simulation/ros_interface.md) | ✓ | | ✓ | | **Simulation:** ROS 2 with Gazebo | ✓ | | ✓ | +| **Simulation:** [Gazebo Classic SITL](../sim_gazebo_classic/index.md) | | ✓ | ✓ | +| **Simulation:** [ROS with Gazebo Classic](../simulation/ros_interface.md) | | | ✓ | Experienced Docker users can also build with the containers used by our continuous integration system: [Docker Containers](../test_and_ci/docker.md) diff --git a/docs/en/dev_setup/dev_env_windows_wsl.md b/docs/en/dev_setup/dev_env_windows_wsl.md index 92e0de4cbd..98e640124e 100644 --- a/docs/en/dev_setup/dev_env_windows_wsl.md +++ b/docs/en/dev_setup/dev_env_windows_wsl.md @@ -58,20 +58,20 @@ To install WSL2 with Ubuntu on a new installation of Windows 10 or 11: wsl --install ``` - - Ubuntu 20.04 ([Gazebo-Classic Simulation](../sim_gazebo_classic/index.md)) - - ```sh - wsl --install -d Ubuntu-20.04 - ``` - - Ubuntu 22.04 ([Gazebo Simulation](../sim_gazebo_gz/index.md)) ```sh wsl --install -d Ubuntu-22.04 ``` + - Ubuntu 24.04 ([Gazebo Simulation](../sim_gazebo_gz/index.md)) + + ```sh + wsl --install -d Ubuntu-24.04 + ``` + ::: info - You can also install[Ubuntu 20.04](https://www.microsoft.com/store/productId/9MTTCL66CPXJ) and [Ubuntu 22.04](https://www.microsoft.com/store/productId/9PN20MSR04DW) from the store, which allows you to delete the application using the normal Windows Add/Remove settings: + You can also [Ubuntu 24.04](https://www.microsoft.com/store/productId/9nz3klhxdjp5) or [Ubuntu 22.04](https://www.microsoft.com/store/productId/9PN20MSR04DW) from Microsoft Store, which allows you to delete the application using the normal Windows Add/Remove settings. ::: 1. WSL will prompt you for a user name and password for the Ubuntu installation. @@ -106,7 +106,7 @@ To open a WSL shell using a command prompt: ``` ```sh - wsl -d Ubuntu-20.04 + wsl -d Ubuntu-24.04 ``` If you only have one version of Ubuntu, you can just use `wsl`. diff --git a/docs/en/ros/mavros_installation.md b/docs/en/ros/mavros_installation.md index 0929b843df..b8c395e468 100644 --- a/docs/en/ros/mavros_installation.md +++ b/docs/en/ros/mavros_installation.md @@ -26,7 +26,7 @@ They cover the _ROS Melodic and Noetic_ releases. ::: tab ROS Noetic (Ubuntu 20.04) -If you're working with [ROS Noetic](https://wiki.ros.org/noetic) on Ubuntu 20.04: +If you're working with [ROS "Noetic"](https://wiki.ros.org/noetic) on Ubuntu 20.04: 1. Install PX4 without the simulator toolchain: 1. [Download PX4 Source Code](../dev_setup/building_px4.md): @@ -57,7 +57,7 @@ If you're working with [ROS Noetic](https://wiki.ros.org/noetic) on Ubuntu 20.04 ::: tab ROS Melodic (Ubuntu 18.04) -If you're working with ROS "Melodic on Ubuntu 18.04: +If you're working with ROS "Melodic" on Ubuntu 18.04: 1. Download the [ubuntu_sim_ros_melodic.sh](https://raw.githubusercontent.com/PX4/Devguide/master/build_scripts/ubuntu_sim_ros_melodic.sh) script in a bash shell: From 8a3e227dc03efc9927f9882e826155fd088e5e4b Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Thu, 12 Feb 2026 08:08:36 -0800 Subject: [PATCH 757/812] docs: address review feedback on build docs - Update "Failed to import Python packages" section to reference gz_x500 instead of jmavsim, and point to Tools/setup/requirements.txt instead of listing individual packages - Fix :::info admonition spacing in Ubuntu dev env docs Signed-off-by: Ramon Roche --- docs/en/dev_setup/building_px4.md | 6 +++--- docs/en/dev_setup/dev_env_linux_ubuntu.md | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/docs/en/dev_setup/building_px4.md b/docs/en/dev_setup/building_px4.md index 576266ae4d..4d54522bb4 100644 --- a/docs/en/dev_setup/building_px4.md +++ b/docs/en/dev_setup/building_px4.md @@ -231,7 +231,7 @@ sudo ln -s /Library/Developer/CommandLineTools/SDKs/MacOSX.sdk/usr/include/* /us ### Failed to import Python packages -"Failed to import" errors when running the `make px4_sitl jmavsim` command indicates that some Python packages are not installed (where expected). +"Failed to import" errors when running the `make px4_sitl gz_x500` command indicates that some Python packages are not installed (where expected). ```sh Failed to import jinja2: No module named 'jinja2' @@ -241,10 +241,10 @@ You may need to install it using: If you have already installed these dependencies this may be because there is more than one Python version on the computer (e.g. Python 2.7.16 and Python 3.8.3), and the module is not present in the version used by the build toolchain. -You should be able to fix this by explicitly installing the dependencies as shown: +You should be able to fix this by installing the dependencies from the repository's requirements file: ```sh -pip3 install --user pyserial empty toml numpy pandas jinja2 pyyaml pyros-genmsg packaging +pip3 install --user -r Tools/setup/requirements.txt ``` ## PX4 Make Build Targets diff --git a/docs/en/dev_setup/dev_env_linux_ubuntu.md b/docs/en/dev_setup/dev_env_linux_ubuntu.md index 0c7917c8d3..4edfd5793d 100644 --- a/docs/en/dev_setup/dev_env_linux_ubuntu.md +++ b/docs/en/dev_setup/dev_env_linux_ubuntu.md @@ -9,7 +9,7 @@ The environment includes: The build toolchain for other flight controllers, simulators, and working with ROS are discussed in the [Other Targets](#other-targets) section below. -:::info +::: info PX4 targets the **current Ubuntu LTS** (24.04) for CI and release builds, with the **previous LTS** (22.04) also supported. Older Ubuntu versions are not supported and may not work. ::: From 841fccf6b9b35fb089960358a4de608a4ef75239 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Fri, 13 Feb 2026 02:35:53 +0000 Subject: [PATCH 758/812] docs: auto-sync metadata [skip ci] Co-Authored-By: PX4 BuildBot --- docs/en/middleware/dds_topics.md | 370 +++++++++++++++---------------- 1 file changed, 185 insertions(+), 185 deletions(-) diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index ae78fbc9fa..787e08ff11 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -94,199 +94,199 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages -- [GpioIn](../msg_docs/GpioIn.md) -- [SystemPower](../msg_docs/SystemPower.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) -- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) -- [LandingTargetPose](../msg_docs/LandingTargetPose.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [EstimatorBias](../msg_docs/EstimatorBias.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) -- [LogMessage](../msg_docs/LogMessage.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) -- [SensorAirflow](../msg_docs/SensorAirflow.md) -- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) -- [ActuatorArmed](../msg_docs/ActuatorArmed.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [PwmInput](../msg_docs/PwmInput.md) -- [OrbTestMedium](../msg_docs/OrbTestMedium.md) -- [QshellReq](../msg_docs/QshellReq.md) -- [GeofenceStatus](../msg_docs/GeofenceStatus.md) -- [RcChannels](../msg_docs/RcChannels.md) -- [Cpuload](../msg_docs/Cpuload.md) -- [DebugArray](../msg_docs/DebugArray.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) -- [Mission](../msg_docs/Mission.md) +- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) - [Airspeed](../msg_docs/Airspeed.md) -- [LedControl](../msg_docs/LedControl.md) -- [HealthReport](../msg_docs/HealthReport.md) -- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) -- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) -- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) -- [InputRc](../msg_docs/InputRc.md) -- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) -- [SensorCorrection](../msg_docs/SensorCorrection.md) -- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) -- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) -- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [GpsDump](../msg_docs/GpsDump.md) +- [RoverRateStatus](../msg_docs/RoverRateStatus.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [Rpm](../msg_docs/Rpm.md) - [SensorSelection](../msg_docs/SensorSelection.md) -- [DeviceInformation](../msg_docs/DeviceInformation.md) -- [CameraTrigger](../msg_docs/CameraTrigger.md) -- [SensorAccel](../msg_docs/SensorAccel.md) -- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) -- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) -- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) -- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) -- [VehicleImu](../msg_docs/VehicleImu.md) -- [MissionResult](../msg_docs/MissionResult.md) -- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) +- [ActionRequest](../msg_docs/ActionRequest.md) +- [LandingGearWheel](../msg_docs/LandingGearWheel.md) - [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [Px4ioStatus](../msg_docs/Px4ioStatus.md) -- [RtlStatus](../msg_docs/RtlStatus.md) -- [ButtonEvent](../msg_docs/ButtonEvent.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [DebugValue](../msg_docs/DebugValue.md) -- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [PowerButtonState](../msg_docs/PowerButtonState.md) - [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [IrlockReport](../msg_docs/IrlockReport.md) +- [AirspeedWind](../msg_docs/AirspeedWind.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) +- [AdcReport](../msg_docs/AdcReport.md) +- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [PositionSetpoint](../msg_docs/PositionSetpoint.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) +- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [RcParameterMap](../msg_docs/RcParameterMap.md) +- [HealthReport](../msg_docs/HealthReport.md) +- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) +- [DifferentialPressure](../msg_docs/DifferentialPressure.md) +- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [GpioConfig](../msg_docs/GpioConfig.md) +- [RcChannels](../msg_docs/RcChannels.md) +- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) +- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [OrbTestMedium](../msg_docs/OrbTestMedium.md) +- [UlogStream](../msg_docs/UlogStream.md) +- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) +- [GeofenceStatus](../msg_docs/GeofenceStatus.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) - [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) -- [GpioOut](../msg_docs/GpioOut.md) -- [ActuatorTest](../msg_docs/ActuatorTest.md) +- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) +- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) +- [DeviceInformation](../msg_docs/DeviceInformation.md) +- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) +- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) - [SensorBaro](../msg_docs/SensorBaro.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [GeneratorStatus](../msg_docs/GeneratorStatus.md) +- [SensorsStatus](../msg_docs/SensorsStatus.md) +- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) +- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [SatelliteInfo](../msg_docs/SatelliteInfo.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) +- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [ButtonEvent](../msg_docs/ButtonEvent.md) +- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) +- [LedControl](../msg_docs/LedControl.md) +- [CameraTrigger](../msg_docs/CameraTrigger.md) +- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) +- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) +- [EscReport](../msg_docs/EscReport.md) +- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [RadioStatus](../msg_docs/RadioStatus.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [LogMessage](../msg_docs/LogMessage.md) +- [CameraCapture](../msg_docs/CameraCapture.md) +- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) +- [GpioRequest](../msg_docs/GpioRequest.md) +- [Ping](../msg_docs/Ping.md) +- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [SystemPower](../msg_docs/SystemPower.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) +- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) +- [EstimatorStates](../msg_docs/EstimatorStates.md) +- [OrbTestLarge](../msg_docs/OrbTestLarge.md) +- [GainCompression](../msg_docs/GainCompression.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [Cpuload](../msg_docs/Cpuload.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [NeuralControl](../msg_docs/NeuralControl.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [GpsInjectData](../msg_docs/GpsInjectData.md) +- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [InputRc](../msg_docs/InputRc.md) +- [DebugValue](../msg_docs/DebugValue.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [SensorGyro](../msg_docs/SensorGyro.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [EventV0](../msg_docs/EventV0.md) +- [VehicleImu](../msg_docs/VehicleImu.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) - [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) - [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) -- [RoverRateStatus](../msg_docs/RoverRateStatus.md) -- [TecsStatus](../msg_docs/TecsStatus.md) -- [PpsCapture](../msg_docs/PpsCapture.md) -- [RaptorStatus](../msg_docs/RaptorStatus.md) -- [EventV0](../msg_docs/EventV0.md) -- [GpioRequest](../msg_docs/GpioRequest.md) -- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [MagWorkerData](../msg_docs/MagWorkerData.md) -- [FollowTarget](../msg_docs/FollowTarget.md) -- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) -- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [ActionRequest](../msg_docs/ActionRequest.md) -- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) -- [GpsInjectData](../msg_docs/GpsInjectData.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) -- [UlogStream](../msg_docs/UlogStream.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) -- [MountOrientation](../msg_docs/MountOrientation.md) -- [RcParameterMap](../msg_docs/RcParameterMap.md) -- [AdcReport](../msg_docs/AdcReport.md) -- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) -- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [GpioConfig](../msg_docs/GpioConfig.md) -- [GainCompression](../msg_docs/GainCompression.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [SensorUwb](../msg_docs/SensorUwb.md) -- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) -- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [EscStatus](../msg_docs/EscStatus.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [PowerButtonState](../msg_docs/PowerButtonState.md) -- [Rpm](../msg_docs/Rpm.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [CellularStatus](../msg_docs/CellularStatus.md) -- [TuneControl](../msg_docs/TuneControl.md) -- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) -- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) -- [OrbTestLarge](../msg_docs/OrbTestLarge.md) -- [BatteryInfo](../msg_docs/BatteryInfo.md) -- [CameraStatus](../msg_docs/CameraStatus.md) -- [QshellRetval](../msg_docs/QshellRetval.md) -- [SensorMag](../msg_docs/SensorMag.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) -- [AirspeedWind](../msg_docs/AirspeedWind.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) -- [GpsDump](../msg_docs/GpsDump.md) -- [SensorTemp](../msg_docs/SensorTemp.md) -- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [SensorsStatus](../msg_docs/SensorsStatus.md) -- [EstimatorStatus](../msg_docs/EstimatorStatus.md) -- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) -- [VehicleAirData](../msg_docs/VehicleAirData.md) -- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [GeneratorStatus](../msg_docs/GeneratorStatus.md) -- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) -- [LandingGearWheel](../msg_docs/LandingGearWheel.md) -- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) -- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) -- [RaptorInput](../msg_docs/RaptorInput.md) -- [SensorGyro](../msg_docs/SensorGyro.md) -- [ParameterUpdate](../msg_docs/ParameterUpdate.md) -- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) -- [PositionSetpoint](../msg_docs/PositionSetpoint.md) -- [EstimatorStates](../msg_docs/EstimatorStates.md) -- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) -- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) -- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) -- [SatelliteInfo](../msg_docs/SatelliteInfo.md) -- [IrlockReport](../msg_docs/IrlockReport.md) -- [Ping](../msg_docs/Ping.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [Vtx](../msg_docs/Vtx.md) -- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) -- [EscReport](../msg_docs/EscReport.md) -- [Gripper](../msg_docs/Gripper.md) -- [UlogStreamAck](../msg_docs/UlogStreamAck.md) -- [SensorGyroFft](../msg_docs/SensorGyroFft.md) -- [VehicleRoi](../msg_docs/VehicleRoi.md) -- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) -- [NeuralControl](../msg_docs/NeuralControl.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [GimbalControls](../msg_docs/GimbalControls.md) +- [MissionResult](../msg_docs/MissionResult.md) - [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [SensorAccel](../msg_docs/SensorAccel.md) +- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [CellularStatus](../msg_docs/CellularStatus.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [GimbalControls](../msg_docs/GimbalControls.md) +- [VehicleAirData](../msg_docs/VehicleAirData.md) +- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) +- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) - [Event](../msg_docs/Event.md) -- [RadioStatus](../msg_docs/RadioStatus.md) -- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) -- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) +- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) +- [RtlStatus](../msg_docs/RtlStatus.md) +- [Vtx](../msg_docs/Vtx.md) +- [ActuatorTest](../msg_docs/ActuatorTest.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) +- [GpioIn](../msg_docs/GpioIn.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [EstimatorStatus](../msg_docs/EstimatorStatus.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) +- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) +- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) +- [ActuatorArmed](../msg_docs/ActuatorArmed.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) +- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) +- [PwmInput](../msg_docs/PwmInput.md) +- [SensorUwb](../msg_docs/SensorUwb.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) +- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [SensorCorrection](../msg_docs/SensorCorrection.md) +- [GpioOut](../msg_docs/GpioOut.md) +- [CameraStatus](../msg_docs/CameraStatus.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) +- [OrbTest](../msg_docs/OrbTest.md) +- [BatteryInfo](../msg_docs/BatteryInfo.md) +- [LandingTargetPose](../msg_docs/LandingTargetPose.md) +- [SensorAirflow](../msg_docs/SensorAirflow.md) +- [MagWorkerData](../msg_docs/MagWorkerData.md) +- [SensorMag](../msg_docs/SensorMag.md) +- [VehicleRoi](../msg_docs/VehicleRoi.md) +- [Gripper](../msg_docs/Gripper.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) +- [QshellReq](../msg_docs/QshellReq.md) +- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) +- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) +- [PpsCapture](../msg_docs/PpsCapture.md) +- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) +- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [QshellRetval](../msg_docs/QshellRetval.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) +- [FollowTarget](../msg_docs/FollowTarget.md) +- [Mission](../msg_docs/Mission.md) +- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) ::: From 87163c1578297e2239ac8d808c247288d3811975 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Fri, 13 Feb 2026 04:22:19 +0100 Subject: [PATCH 759/812] uavcan esc: initializers cosmetics (#26470) --- src/drivers/uavcan/actuators/esc.cpp | 2 +- src/drivers/uavcan/actuators/esc.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/uavcan/actuators/esc.cpp b/src/drivers/uavcan/actuators/esc.cpp index 33a955be8e..9e4bb64509 100644 --- a/src/drivers/uavcan/actuators/esc.cpp +++ b/src/drivers/uavcan/actuators/esc.cpp @@ -89,7 +89,7 @@ UavcanEscController::update_outputs(uint16_t outputs[MAX_ACTUATORS], uint8_t out _prev_cmd_pub = timestamp; - uavcan::equipment::esc::RawCommand msg = {}; + uavcan::equipment::esc::RawCommand msg{}; for (unsigned i = 0; i < output_array_size; i++) { msg.cmd.push_back(static_cast(outputs[i])); diff --git a/src/drivers/uavcan/actuators/esc.hpp b/src/drivers/uavcan/actuators/esc.hpp index 1170e67574..1a8e45c608 100644 --- a/src/drivers/uavcan/actuators/esc.hpp +++ b/src/drivers/uavcan/actuators/esc.hpp @@ -97,7 +97,7 @@ private: typedef uavcan::MethodBinder TimerCbBinder; - bool _initialized{}; + bool _initialized = false; esc_status_s _esc_status{}; From a235b5c87faa69f1e1589fa0b00088e4feaa3668 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Fri, 13 Feb 2026 03:30:17 +0000 Subject: [PATCH 760/812] docs: auto-sync metadata [skip ci] Co-Authored-By: PX4 BuildBot --- docs/en/middleware/dds_topics.md | 360 +++++++++++++++---------------- 1 file changed, 180 insertions(+), 180 deletions(-) diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index 787e08ff11..ba072996fd 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -94,199 +94,199 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages -- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) -- [Airspeed](../msg_docs/Airspeed.md) -- [GpsDump](../msg_docs/GpsDump.md) -- [RoverRateStatus](../msg_docs/RoverRateStatus.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) -- [Rpm](../msg_docs/Rpm.md) -- [SensorSelection](../msg_docs/SensorSelection.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [ActionRequest](../msg_docs/ActionRequest.md) -- [LandingGearWheel](../msg_docs/LandingGearWheel.md) -- [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [PowerButtonState](../msg_docs/PowerButtonState.md) -- [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [IrlockReport](../msg_docs/IrlockReport.md) -- [AirspeedWind](../msg_docs/AirspeedWind.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [RaptorStatus](../msg_docs/RaptorStatus.md) -- [AdcReport](../msg_docs/AdcReport.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) +- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) +- [CellularStatus](../msg_docs/CellularStatus.md) +- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) - [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) -- [PositionSetpoint](../msg_docs/PositionSetpoint.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) - [RcParameterMap](../msg_docs/RcParameterMap.md) - [HealthReport](../msg_docs/HealthReport.md) -- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) - [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) -- [GpioConfig](../msg_docs/GpioConfig.md) -- [RcChannels](../msg_docs/RcChannels.md) -- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) -- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) -- [OrbTestMedium](../msg_docs/OrbTestMedium.md) -- [UlogStream](../msg_docs/UlogStream.md) -- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) - [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) -- [GeofenceStatus](../msg_docs/GeofenceStatus.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) -- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) -- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) -- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) -- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) -- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) -- [DeviceInformation](../msg_docs/DeviceInformation.md) -- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [TuneControl](../msg_docs/TuneControl.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) -- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [SensorBaro](../msg_docs/SensorBaro.md) -- [RaptorInput](../msg_docs/RaptorInput.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) -- [GeneratorStatus](../msg_docs/GeneratorStatus.md) -- [SensorsStatus](../msg_docs/SensorsStatus.md) -- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) -- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) -- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [SatelliteInfo](../msg_docs/SatelliteInfo.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [FuelTankStatus](../msg_docs/FuelTankStatus.md) +- [Airspeed](../msg_docs/Airspeed.md) +- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [GpioIn](../msg_docs/GpioIn.md) +- [VehicleImu](../msg_docs/VehicleImu.md) +- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) - [ButtonEvent](../msg_docs/ButtonEvent.md) - [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [LedControl](../msg_docs/LedControl.md) -- [CameraTrigger](../msg_docs/CameraTrigger.md) -- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [AirspeedWind](../msg_docs/AirspeedWind.md) - [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) -- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) -- [EscReport](../msg_docs/EscReport.md) -- [SensorGyroFft](../msg_docs/SensorGyroFft.md) -- [RadioStatus](../msg_docs/RadioStatus.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) -- [LogMessage](../msg_docs/LogMessage.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [GpioRequest](../msg_docs/GpioRequest.md) -- [Ping](../msg_docs/Ping.md) -- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) -- [SystemPower](../msg_docs/SystemPower.md) -- [EstimatorBias](../msg_docs/EstimatorBias.md) -- [UlogStreamAck](../msg_docs/UlogStreamAck.md) -- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) -- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [EstimatorStates](../msg_docs/EstimatorStates.md) -- [OrbTestLarge](../msg_docs/OrbTestLarge.md) -- [GainCompression](../msg_docs/GainCompression.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) -- [ParameterUpdate](../msg_docs/ParameterUpdate.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [Cpuload](../msg_docs/Cpuload.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [NeuralControl](../msg_docs/NeuralControl.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) -- [GpsInjectData](../msg_docs/GpsInjectData.md) -- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) -- [InputRc](../msg_docs/InputRc.md) -- [DebugValue](../msg_docs/DebugValue.md) -- [TecsStatus](../msg_docs/TecsStatus.md) -- [SensorGyro](../msg_docs/SensorGyro.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) -- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) -- [EventV0](../msg_docs/EventV0.md) -- [VehicleImu](../msg_docs/VehicleImu.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) -- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) -- [MissionResult](../msg_docs/MissionResult.md) -- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) -- [MountOrientation](../msg_docs/MountOrientation.md) -- [SensorAccel](../msg_docs/SensorAccel.md) -- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [CellularStatus](../msg_docs/CellularStatus.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) -- [GimbalControls](../msg_docs/GimbalControls.md) -- [VehicleAirData](../msg_docs/VehicleAirData.md) -- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) -- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) -- [Event](../msg_docs/Event.md) - [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) -- [RtlStatus](../msg_docs/RtlStatus.md) -- [Vtx](../msg_docs/Vtx.md) -- [ActuatorTest](../msg_docs/ActuatorTest.md) -- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) -- [GpioIn](../msg_docs/GpioIn.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) - [EstimatorStatus](../msg_docs/EstimatorStatus.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) -- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) -- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) -- [SensorTemp](../msg_docs/SensorTemp.md) -- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [EscStatus](../msg_docs/EscStatus.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) +- [RtlStatus](../msg_docs/RtlStatus.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [SensorHygrometer](../msg_docs/SensorHygrometer.md) +- [Event](../msg_docs/Event.md) +- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) +- [NeuralControl](../msg_docs/NeuralControl.md) +- [RadioStatus](../msg_docs/RadioStatus.md) +- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [PositionSetpoint](../msg_docs/PositionSetpoint.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) - [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) +- [PowerButtonState](../msg_docs/PowerButtonState.md) +- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) +- [PpsCapture](../msg_docs/PpsCapture.md) +- [SensorAirflow](../msg_docs/SensorAirflow.md) +- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) +- [GpsDump](../msg_docs/GpsDump.md) +- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) +- [VehicleAirData](../msg_docs/VehicleAirData.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [GpioConfig](../msg_docs/GpioConfig.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [UlogStream](../msg_docs/UlogStream.md) +- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) +- [CameraStatus](../msg_docs/CameraStatus.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [CameraTrigger](../msg_docs/CameraTrigger.md) +- [IrlockReport](../msg_docs/IrlockReport.md) +- [SensorBaro](../msg_docs/SensorBaro.md) +- [SensorGyro](../msg_docs/SensorGyro.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) +- [Ping](../msg_docs/Ping.md) +- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) +- [SensorsStatus](../msg_docs/SensorsStatus.md) +- [SatelliteInfo](../msg_docs/SatelliteInfo.md) +- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) +- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [GimbalControls](../msg_docs/GimbalControls.md) +- [EscReport](../msg_docs/EscReport.md) +- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) +- [DeviceInformation](../msg_docs/DeviceInformation.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [GpioOut](../msg_docs/GpioOut.md) +- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [EventV0](../msg_docs/EventV0.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) +- [Cpuload](../msg_docs/Cpuload.md) +- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) +- [OrbTest](../msg_docs/OrbTest.md) +- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [Gripper](../msg_docs/Gripper.md) +- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) +- [QshellRetval](../msg_docs/QshellRetval.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) +- [EstimatorStates](../msg_docs/EstimatorStates.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [MissionResult](../msg_docs/MissionResult.md) +- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) +- [FollowTarget](../msg_docs/FollowTarget.md) +- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) +- [OrbTestLarge](../msg_docs/OrbTestLarge.md) +- [DebugValue](../msg_docs/DebugValue.md) +- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [ActionRequest](../msg_docs/ActionRequest.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) +- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [MagWorkerData](../msg_docs/MagWorkerData.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) +- [SystemPower](../msg_docs/SystemPower.md) +- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) +- [BatteryInfo](../msg_docs/BatteryInfo.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [InputRc](../msg_docs/InputRc.md) +- [RcChannels](../msg_docs/RcChannels.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [GainCompression](../msg_docs/GainCompression.md) - [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) - [ActuatorArmed](../msg_docs/ActuatorArmed.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) -- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) -- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) -- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [PwmInput](../msg_docs/PwmInput.md) -- [SensorUwb](../msg_docs/SensorUwb.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) -- [DebugArray](../msg_docs/DebugArray.md) -- [SensorCorrection](../msg_docs/SensorCorrection.md) -- [GpioOut](../msg_docs/GpioOut.md) -- [CameraStatus](../msg_docs/CameraStatus.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [BatteryInfo](../msg_docs/BatteryInfo.md) -- [LandingTargetPose](../msg_docs/LandingTargetPose.md) -- [SensorAirflow](../msg_docs/SensorAirflow.md) -- [MagWorkerData](../msg_docs/MagWorkerData.md) -- [SensorMag](../msg_docs/SensorMag.md) -- [VehicleRoi](../msg_docs/VehicleRoi.md) -- [Gripper](../msg_docs/Gripper.md) -- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) -- [QshellReq](../msg_docs/QshellReq.md) -- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) -- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) -- [PpsCapture](../msg_docs/PpsCapture.md) -- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) -- [Px4ioStatus](../msg_docs/Px4ioStatus.md) -- [QshellRetval](../msg_docs/QshellRetval.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) -- [FollowTarget](../msg_docs/FollowTarget.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [CameraCapture](../msg_docs/CameraCapture.md) - [Mission](../msg_docs/Mission.md) +- [LandingGearWheel](../msg_docs/LandingGearWheel.md) +- [GpsInjectData](../msg_docs/GpsInjectData.md) +- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [GeofenceStatus](../msg_docs/GeofenceStatus.md) +- [SensorMag](../msg_docs/SensorMag.md) +- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [LogMessage](../msg_docs/LogMessage.md) +- [OrbTestMedium](../msg_docs/OrbTestMedium.md) +- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) +- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) +- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) +- [AdcReport](../msg_docs/AdcReport.md) - [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [SensorSelection](../msg_docs/SensorSelection.md) +- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [RoverRateStatus](../msg_docs/RoverRateStatus.md) +- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [Vtx](../msg_docs/Vtx.md) +- [SensorCorrection](../msg_docs/SensorCorrection.md) +- [SensorAccel](../msg_docs/SensorAccel.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) +- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) +- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) +- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) +- [LandingTargetPose](../msg_docs/LandingTargetPose.md) +- [GpioRequest](../msg_docs/GpioRequest.md) +- [Rpm](../msg_docs/Rpm.md) +- [SensorUwb](../msg_docs/SensorUwb.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [PwmInput](../msg_docs/PwmInput.md) +- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) +- [VehicleRoi](../msg_docs/VehicleRoi.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [QshellReq](../msg_docs/QshellReq.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) +- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [GeneratorStatus](../msg_docs/GeneratorStatus.md) +- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) +- [ActuatorTest](../msg_docs/ActuatorTest.md) +- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) +- [LedControl](../msg_docs/LedControl.md) ::: From c511e72d4fc468d3ae3b0a41670fc1ca573198e9 Mon Sep 17 00:00:00 2001 From: cuav-chen2 Date: Fri, 13 Feb 2026 09:57:39 +0800 Subject: [PATCH 761/812] cuav_nora: 5V power overcurrent detection pin default to pull-up --- boards/cuav/nora/src/board_config.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/boards/cuav/nora/src/board_config.h b/boards/cuav/nora/src/board_config.h index 56dbf9cc8c..0f289730d2 100644 --- a/boards/cuav/nora/src/board_config.h +++ b/boards/cuav/nora/src/board_config.h @@ -127,8 +127,8 @@ #define GPIO_VDD_5V_RC_EN /* PG5 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN5) #define GPIO_VDD_3V3_SD_CARD_EN /* PG7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTG|GPIO_PIN7) -#define GPIO_VDD_5V_HIPOWER_OC /* PJ3 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTJ|GPIO_PIN3) -#define GPIO_nVDD_5V_PERIPH_OC /* PJ4 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTJ|GPIO_PIN4) +#define GPIO_VDD_5V_HIPOWER_OC /* PJ3 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTJ|GPIO_PIN3) +#define GPIO_nVDD_5V_PERIPH_OC /* PJ4 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTJ|GPIO_PIN4) /* Power switch controls ******************************************************/ #define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_nVDD_5V_PERIPH_EN, (on_true)) From c29630f6aedb76e933dfe6c8fc3f21d425eb1016 Mon Sep 17 00:00:00 2001 From: Marco Hauswirth Date: Wed, 28 Jan 2026 17:51:33 +0100 Subject: [PATCH 762/812] adjust clang-tidy checks and workflow --- .clang-tidy | 32 ++++++++++++++++++++++++++++++++ .github/workflows/clang-tidy.yml | 14 ++++++++++++-- 2 files changed, 44 insertions(+), 2 deletions(-) diff --git a/.clang-tidy b/.clang-tidy index 81f2d62596..6507139938 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -105,6 +105,38 @@ Checks: '*, -readability-redundant-declaration, -readability-static-accessed-through-instance, -readability-static-definition-in-anonymous-namespace, + -altera-struct-pack-align, + -bugprone-easily-swappable-parameters, + -concurrency-mt-unsafe, + -cppcoreguidelines-avoid-const-or-ref-data-members, + -cppcoreguidelines-macro-usage, + -cppcoreguidelines-non-private-member-variables-in-classes, + -hicpp-uppercase-literal-suffix, + -llvm-qualified-auto, + -misc-non-private-member-variables-in-classes, + -misc-use-anonymous-namespace, + -modernize-concat-nested-namespaces, + -readability-const-return-type, + -readability-identifier-length, + -readability-isolate-declaration, + -readability-qualified-auto, + -readability-redundant-access-specifiers, + -cppcoreguidelines-avoid-do-while, + -misc-include-cleaner, + -misc-const-correctness, + -llvm-else-after-return, + -readability-function-cognitive-complexity, + -cppcoreguidelines-init-variables, + -bugprone-reserved-identifier, + -cert-dcl37-c, + -cert-dcl51-cpp, + -modernize-use-nodiscard, + -misc-confusable-identifiers, + -cert-err33-c, + -readability-redundant-inline-specifier, + -readability-uppercase-literal-suffix, + -bugprone-narrowing-conversions, + -cppcoreguidelines-narrowing-conversions, ' WarningsAsErrors: '*' CheckOptions: diff --git a/.github/workflows/clang-tidy.yml b/.github/workflows/clang-tidy.yml index b373c59765..0828e01f91 100644 --- a/.github/workflows/clang-tidy.yml +++ b/.github/workflows/clang-tidy.yml @@ -11,6 +11,7 @@ on: - '**' paths-ignore: - 'docs/**' + jobs: build: runs-on: ubuntu-latest @@ -18,13 +19,22 @@ jobs: - uses: actions/checkout@v4 with: fetch-depth: 0 + fetch-tags: true + + - name: Determine PX4 version for container image + id: px4_version + run: | + echo "px4_version=$(git describe --tags --match 'v[0-9]*')" >> $GITHUB_OUTPUT - name: Testing (clang-tidy) uses: addnab/docker-run-action@v3 with: - image: px4io/px4-dev-clang:2021-09-08 + image: px4io/px4-dev:${{ steps.px4_version.outputs.px4_version }} options: -v ${{ github.workspace }}:/workspace run: | cd /workspace - git config --global --add safe.directory /workspace + apt install clang-tidy-18 -y + update-alternatives --install /usr/bin/clang-tidy clang-tidy /usr/bin/clang-tidy-18 100 + update-alternatives --install /usr/bin/clang clang /usr/bin/clang-18 100 + update-alternatives --install /usr/bin/clang++ clang++ /usr/bin/clang++-18 100 make clang-tidy From 767eb756629b33b233a8e312d9e71cbe5f6067d3 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 4 Feb 2026 18:44:03 +0100 Subject: [PATCH 763/812] gyro_fft: fix clang build error on Linux arm64 Extend the -Wno-asm-operand-widths workaround to include Linux aarch64 in addition to Apple Silicon. CMSIS DSP contains ARM Cortex-M specific assembly that clang (but not gcc) warns about on 64-bit ARM platforms. The assembly code is unused on POSIX builds - only the C fallback implementations are executed in SITL. This fixes clang-tidy CI failing on arm64 runners. Signed-off-by: Ramon Roche --- src/modules/gyro_fft/CMakeLists.txt | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/modules/gyro_fft/CMakeLists.txt b/src/modules/gyro_fft/CMakeLists.txt index 9bf6832ed4..b342ef250f 100644 --- a/src/modules/gyro_fft/CMakeLists.txt +++ b/src/modules/gyro_fft/CMakeLists.txt @@ -38,8 +38,10 @@ if(${PX4_PLATFORM} MATCHES "NuttX") add_compile_options(-DARM_MATH_DSP) endif() -# Disable 32-bit assembly warnings on apple silicon. Triggered by unused code only. -if(${PX4_PLATFORM} MATCHES "posix" AND APPLE AND ${CMAKE_HOST_SYSTEM_PROCESSOR} MATCHES "arm64") +# Disable 32-bit assembly warnings on arm64 platforms (Apple Silicon, Linux aarch64). +# CMSIS DSP contains ARM Cortex-M assembly that triggers clang warnings on 64-bit ARM. +# This code is unused on POSIX platforms - only the C fallback implementations run. +if(${PX4_PLATFORM} MATCHES "posix" AND ${CMAKE_HOST_SYSTEM_PROCESSOR} MATCHES "arm64|aarch64") add_compile_options(-Wno-asm-operand-widths) endif() From dc4aa749d3b2805e18a9bbc3f6383d8a8c9d23e4 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 4 Feb 2026 21:23:17 +0100 Subject: [PATCH 764/812] Tools/run-clang-tidy: add -exclude argument for file filtering Add regex-based file exclusion to the clang-tidy runner script. This allows excluding paths (submodules, vendored code, tests) from static analysis without modifying .clang-tidy files in each directory. The -exclude argument accepts a regex pattern that is matched against file paths from the compilation database. Matching files are skipped. Example: -exclude="src/lib/foo|src/modules/bar" This prepares for the clang-tidy v6 to v18 migration where we need to exclude external code that we consume but don't maintain. Signed-off-by: Ramon Roche --- Tools/run-clang-tidy.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Tools/run-clang-tidy.py b/Tools/run-clang-tidy.py index 4f29868bee..764edd6581 100755 --- a/Tools/run-clang-tidy.py +++ b/Tools/run-clang-tidy.py @@ -144,6 +144,8 @@ def main(): help='number of tidy instances to be run in parallel.') parser.add_argument('files', nargs='*', default=['.*'], help='files to be processed (regex on path)') + parser.add_argument('-exclude', dest='exclude', default=None, + help='regular expression matching files to exclude') parser.add_argument('-fix', action='store_true', help='apply fix-its') parser.add_argument('-format', action='store_true', help='Reformat code ' 'after applying fixes') @@ -192,6 +194,7 @@ def main(): # Build up a big regexy filter from all command line arguments. file_name_re = re.compile('(' + ')|('.join(args.files) + ')') + exclude_re = re.compile(args.exclude) if args.exclude else None try: # Spin up a bunch of tidy-launching threads. @@ -205,6 +208,8 @@ def main(): # Fill the queue with files. for name in files: if file_name_re.search(name): + if exclude_re and exclude_re.search(name): + continue queue.put(name) # Wait for all threads to be done. From d196d37ef207d2b12443f08410f2404d01f6fea9 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 4 Feb 2026 21:23:54 +0100 Subject: [PATCH 765/812] clang-tidy: auto-exclude submodules and third-party code Automatically generate the clang-tidy exclusion list from .gitmodules so new submodules are excluded without manual intervention. Changes: - Makefile: Generate CLANG_TIDY_SUBMODULES from .gitmodules paths - Makefile: Add CLANG_TIDY_EXCLUDE_EXTRA for manual exclusions: - src/systemcmds/tests (test code, looser style allowed) - src/examples (educational code, not production) - src/modules/gyro_fft/CMSIS_5 (vendored ARM DSP library) - Delete src/systemcmds/tests/.clang-tidy (stale since 2019) - Delete src/modules/gyro_fft/CMSIS_5/.clang-tidy (redundant) Rationale: Submodules and vendored code should be linted in their upstream repositories, not here. This reduces noise and focuses clang-tidy on code that PX4 maintainers actually edit. Contributors adding vendored (non-submodule) third-party code should add their path to CLANG_TIDY_EXCLUDE_EXTRA in the Makefile. Signed-off-by: Ramon Roche --- Makefile | 16 ++- src/modules/gyro_fft/CMSIS_5/.clang-tidy | 120 ----------------------- src/systemcmds/tests/.clang-tidy | 119 ---------------------- 3 files changed, 14 insertions(+), 241 deletions(-) delete mode 100644 src/modules/gyro_fft/CMSIS_5/.clang-tidy delete mode 100644 src/systemcmds/tests/.clang-tidy diff --git a/Makefile b/Makefile index 2d33363206..e3fd7d26f3 100644 --- a/Makefile +++ b/Makefile @@ -492,13 +492,25 @@ px4_sitl_default-clang: @cd "$(SRC_DIR)"/build/px4_sitl_default-clang && cmake "$(SRC_DIR)" $(CMAKE_ARGS) -G"$(PX4_CMAKE_GENERATOR)" -DCONFIG=px4_sitl_default -DCMAKE_C_COMPILER=clang -DCMAKE_CXX_COMPILER=clang++ @$(PX4_MAKE) -C "$(SRC_DIR)"/build/px4_sitl_default-clang +# Paths to exclude from clang-tidy (auto-generated from .gitmodules + manual additions): +# - All submodules (external code we consume, not edit) +# - Test code (allowed looser style) +# - Example code (educational, not production) +# - Vendored third-party code (e.g., CMSIS_5) +# +# To add manual exclusions, append to CLANG_TIDY_EXCLUDE_EXTRA below. +# Submodules are automatically excluded - no action needed when adding new ones. +CLANG_TIDY_SUBMODULES := $(shell git config --file .gitmodules --get-regexp path | awk '{print $$2}' | tr '\n' '|' | sed 's/|$$//') +CLANG_TIDY_EXCLUDE_EXTRA := src/systemcmds/tests|src/examples|src/modules/gyro_fft/CMSIS_5 +CLANG_TIDY_EXCLUDE := $(CLANG_TIDY_SUBMODULES)|$(CLANG_TIDY_EXCLUDE_EXTRA) + clang-tidy: px4_sitl_default-clang - @cd "$(SRC_DIR)"/build/px4_sitl_default-clang && "$(SRC_DIR)"/Tools/run-clang-tidy.py -header-filter=".*\.hpp" -j$(j_clang_tidy) -p . + @cd "$(SRC_DIR)"/build/px4_sitl_default-clang && "$(SRC_DIR)"/Tools/run-clang-tidy.py -header-filter=".*\.hpp" -j$(j_clang_tidy) -exclude="$(CLANG_TIDY_EXCLUDE)" -p . # to automatically fix a single check at a time, eg modernize-redundant-void-arg # % run-clang-tidy-4.0.py -fix -j4 -checks=-\*,modernize-redundant-void-arg -p . clang-tidy-fix: px4_sitl_default-clang - @cd "$(SRC_DIR)"/build/px4_sitl_default-clang && "$(SRC_DIR)"/Tools/run-clang-tidy.py -header-filter=".*\.hpp" -j$(j_clang_tidy) -fix -p . + @cd "$(SRC_DIR)"/build/px4_sitl_default-clang && "$(SRC_DIR)"/Tools/run-clang-tidy.py -header-filter=".*\.hpp" -j$(j_clang_tidy) -exclude="$(CLANG_TIDY_EXCLUDE)" -fix -p . # TODO: Fix cppcheck errors then try --enable=warning,performance,portability,style,unusedFunction or --enable=all cppcheck: px4_sitl_default diff --git a/src/modules/gyro_fft/CMSIS_5/.clang-tidy b/src/modules/gyro_fft/CMSIS_5/.clang-tidy deleted file mode 100644 index 64e1b8f404..0000000000 --- a/src/modules/gyro_fft/CMSIS_5/.clang-tidy +++ /dev/null @@ -1,120 +0,0 @@ ---- -Checks: '*, - -android*, - -bugprone-integer-division, - -cert-dcl50-cpp, - -cert-env33-c, - -cert-err34-c, - -cert-err58-cpp, - -cert-msc30-c, - -cert-msc50-cpp, - -cert-flp30-c, - -clang-analyzer-core.CallAndMessage, - -clang-analyzer-core.NullDereference, - -clang-analyzer-core.UndefinedBinaryOperatorResult, - -clang-analyzer-core.uninitialized.Assign, - -clang-analyzer-core.VLASize, - -clang-analyzer-cplusplus.NewDelete, - -clang-analyzer-cplusplus.NewDeleteLeaks, - -clang-analyzer-deadcode.DeadStores, - -clang-analyzer-optin.cplusplus.VirtualCall, - -clang-analyzer-optin.performance.Padding, - -clang-analyzer-security.FloatLoopCounter, - -clang-analyzer-security.insecureAPI.strcpy, - -clang-analyzer-unix.API, - -clang-analyzer-unix.cstring.BadSizeArg, - -clang-analyzer-unix.Malloc, - -clang-analyzer-unix.MallocSizeof, - -cppcoreguidelines-c-copy-assignment-signature, - -cppcoreguidelines-interfaces-global-init, - -cppcoreguidelines-no-malloc, - -cppcoreguidelines-owning-memory, - -cppcoreguidelines-pro-bounds-array-to-pointer-decay, - -cppcoreguidelines-pro-bounds-constant-array-index, - -cppcoreguidelines-pro-bounds-pointer-arithmetic, - -cppcoreguidelines-pro-type-const-cast, - -cppcoreguidelines-pro-type-cstyle-cast, - -cppcoreguidelines-pro-type-member-init, - -cppcoreguidelines-pro-type-reinterpret-cast, - -cppcoreguidelines-pro-type-union-access, - -cppcoreguidelines-pro-type-vararg, - -cppcoreguidelines-special-member-functions, - -fuchsia-default-arguments, - -fuchsia-overloaded-operator, - -google-build-using-namespace, - -google-explicit-constructor, - -google-global-names-in-headers, - -google-readability-braces-around-statements, - -google-readability-casting, - -google-readability-function-size, - -google-readability-namespace-comments, - -google-readability-todo, - -google-runtime-int, - -google-runtime-references, - -hicpp-braces-around-statements, - -hicpp-deprecated-headers, - -hicpp-explicit-conversions, - -hicpp-function-size, - -hicpp-member-init, - -hicpp-no-array-decay, - -hicpp-no-assembler, - -hicpp-no-malloc, - -hicpp-signed-bitwise, - -hicpp-special-member-functions, - -hicpp-use-auto, - -hicpp-use-equals-default, - -hicpp-use-equals-delete, - -hicpp-use-override, - -hicpp-vararg, - -llvm-header-guard, - -llvm-include-order, - -llvm-namespace-comment, - -misc-incorrect-roundings, - -misc-macro-parentheses, - -misc-misplaced-widening-cast, - -misc-redundant-expression, - -misc-unconventional-assign-operator, - -misc-unused-parameters, - -modernize-deprecated-headers, - -modernize-loop-convert, - -modernize-pass-by-value, - -modernize-return-braced-init-list, - -modernize-use-auto, - -modernize-use-bool-literals, - -modernize-use-default-member-init, - -modernize-use-emplace, - -modernize-use-equals-default, - -modernize-use-equals-delete, - -modernize-use-override, - -modernize-use-using, - -performance-inefficient-string-concatenation, - -performance-unnecessary-value-param, - -readability-avoid-const-params-in-decls, - -readability-braces-around-statements, - -readability-container-size-empty, - -readability-delete-null-pointer, - -readability-else-after-return, - -readability-function-size, - -readability-implicit-bool-cast, - -readability-implicit-bool-conversion, - -readability-inconsistent-declaration-parameter-name, - -readability-named-parameter, - -readability-non-const-parameter, - -readability-redundant-control-flow, - -readability-redundant-declaration, - -readability-redundant-member-init, - -readability-simplify-boolean-expr, - -readability-static-accessed-through-instance, - -readability-static-definition-in-anonymous-namespace, - ' -WarningsAsErrors: '*' -CheckOptions: - - key: google-readability-braces-around-statements.ShortStatementLines - value: '1' - - key: google-readability-function-size.BranchThreshold - value: '600' - - key: google-readability-function-size.LineThreshold - value: '4000' - - key: google-readability-function-size.StatementThreshold - value: '4000' -... diff --git a/src/systemcmds/tests/.clang-tidy b/src/systemcmds/tests/.clang-tidy deleted file mode 100644 index 9d2589717a..0000000000 --- a/src/systemcmds/tests/.clang-tidy +++ /dev/null @@ -1,119 +0,0 @@ ---- -Checks: '*, - -android*, - -bugprone-integer-division, - -cert-dcl50-cpp, - -cert-env33-c, - -cert-err34-c, - -cert-err58-cpp, - -cert-msc30-c, - -cert-msc50-cpp, - -cert-flp30-c, - -clang-analyzer-core.CallAndMessage, - -clang-analyzer-core.NullDereference, - -clang-analyzer-core.UndefinedBinaryOperatorResult, - -clang-analyzer-core.uninitialized.Assign, - -clang-analyzer-core.VLASize, - -clang-analyzer-cplusplus.NewDelete, - -clang-analyzer-cplusplus.NewDeleteLeaks, - -clang-analyzer-deadcode.DeadStores, - -clang-analyzer-optin.cplusplus.VirtualCall, - -clang-analyzer-optin.performance.Padding, - -clang-analyzer-security.FloatLoopCounter, - -clang-analyzer-security.insecureAPI.strcpy, - -clang-analyzer-unix.API, - -clang-analyzer-unix.cstring.BadSizeArg, - -clang-analyzer-unix.Malloc, - -clang-analyzer-unix.MallocSizeof, - -cppcoreguidelines-c-copy-assignment-signature, - -cppcoreguidelines-interfaces-global-init, - -cppcoreguidelines-no-malloc, - -cppcoreguidelines-owning-memory, - -cppcoreguidelines-pro-bounds-array-to-pointer-decay, - -cppcoreguidelines-pro-bounds-constant-array-index, - -cppcoreguidelines-pro-bounds-pointer-arithmetic, - -cppcoreguidelines-pro-type-const-cast, - -cppcoreguidelines-pro-type-cstyle-cast, - -cppcoreguidelines-pro-type-member-init, - -cppcoreguidelines-pro-type-reinterpret-cast, - -cppcoreguidelines-pro-type-union-access, - -cppcoreguidelines-pro-type-vararg, - -cppcoreguidelines-special-member-functions, - -fuchsia-default-arguments, - -fuchsia-overloaded-operator, - -google-build-using-namespace, - -google-explicit-constructor, - -google-global-names-in-headers, - -google-readability-casting, - -google-readability-function-size, - -google-readability-namespace-comments, - -google-readability-todo, - -google-runtime-int, - -google-runtime-references, - -hicpp-braces-around-statements, - -hicpp-deprecated-headers, - -hicpp-explicit-conversions, - -hicpp-function-size, - -hicpp-member-init, - -hicpp-no-array-decay, - -hicpp-no-assembler, - -hicpp-no-malloc, - -hicpp-signed-bitwise, - -hicpp-special-member-functions, - -hicpp-use-auto, - -hicpp-use-equals-default, - -hicpp-use-equals-delete, - -hicpp-use-override, - -hicpp-vararg, - -llvm-header-guard, - -llvm-include-order, - -llvm-namespace-comment, - -misc-incorrect-roundings, - -misc-macro-parentheses, - -misc-misplaced-widening-cast, - -misc-redundant-expression, - -misc-unconventional-assign-operator, - -misc-unused-parameters, - -modernize-deprecated-headers, - -modernize-loop-convert, - -modernize-pass-by-value, - -modernize-return-braced-init-list, - -modernize-use-auto, - -modernize-use-bool-literals, - -modernize-use-default-member-init, - -modernize-use-emplace, - -modernize-use-equals-default, - -modernize-use-equals-delete, - -modernize-use-override, - -modernize-use-using, - -performance-inefficient-string-concatenation, - -performance-unnecessary-value-param, - -readability-avoid-const-params-in-decls, - -readability-braces-around-statements, - -readability-container-size-empty, - -readability-delete-null-pointer, - -readability-else-after-return, - -readability-function-size, - -readability-implicit-bool-cast, - -readability-implicit-bool-conversion, - -readability-inconsistent-declaration-parameter-name, - -readability-named-parameter, - -readability-non-const-parameter, - -readability-redundant-control-flow, - -readability-redundant-declaration, - -readability-redundant-member-init, - -readability-simplify-boolean-expr, - -readability-static-accessed-through-instance, - -readability-static-definition-in-anonymous-namespace, - ' -WarningsAsErrors: '*' -CheckOptions: - - key: google-readability-braces-around-statements.ShortStatementLines - value: '1' - - key: google-readability-function-size.BranchThreshold - value: '600' - - key: google-readability-function-size.LineThreshold - value: '4000' - - key: google-readability-function-size.StatementThreshold - value: '4000' -... From 23c9af20dacd86a3437590da0c64f5d18f14b111 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 4 Feb 2026 21:24:11 +0100 Subject: [PATCH 766/812] clang-tidy: disable new checks for v18 compatibility Update .clang-tidy configuration to maintain compatibility with clang-tidy 18 in the new px4io/px4-dev:v1.17.0-alpha1 container. The previous CI container used clang-tidy 6.0 (2018) with ~213 checks. The new container has clang-tidy 18 (2024) with ~537 checks - adding ~324 new checks that would fail without configuration changes. This commit disables the new checks to preserve the existing code quality baseline. The disabled checks can be evaluated and enabled incrementally in future PRs as the codebase is updated to comply. New checks disabled (partial list): - bugprone-assignment-in-if-condition - bugprone-casting-through-void - bugprone-multi-level-implicit-pointer-conversion - cppcoreguidelines-avoid-do-while - cppcoreguidelines-avoid-goto - cppcoreguidelines-avoid-non-const-global-variables - misc-definitions-in-headers - misc-header-include-cycle - misc-no-recursion - modernize-macro-to-enum - modernize-type-traits - performance-enum-size - readability-avoid-nested-conditional-operator - readability-convert-member-functions-to-static - readability-redundant-string-init - readability-simplify-boolean-expr - (and ~35 more) See full list in .clang-tidy. Each check is prefixed with '-' to disable it while keeping WarningsAsErrors: '*' active for enabled checks. Signed-off-by: Ramon Roche --- .clang-tidy | 51 +++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 51 insertions(+) diff --git a/.clang-tidy b/.clang-tidy index 6507139938..9293603c71 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -137,6 +137,57 @@ Checks: '*, -readability-uppercase-literal-suffix, -bugprone-narrowing-conversions, -cppcoreguidelines-narrowing-conversions, + -bugprone-switch-missing-default-case, + -cppcoreguidelines-avoid-goto, + -hicpp-avoid-goto, + -bugprone-branch-clone, + -bugprone-unhandled-self-assignment, + -cert-oop54-cpp, + -performance-enum-size, + -readability-avoid-nested-conditional-operator, + -cppcoreguidelines-prefer-member-initializer, + -cppcoreguidelines-explicit-virtual-functions, + -cppcoreguidelines-virtual-class-destructor, + -readability-convert-member-functions-to-static, + -readability-make-member-function-const, + -bugprone-assignment-in-if-condition, + -bugprone-implicit-widening-of-multiplication-result, + -bugprone-incorrect-roundings, + -bugprone-macro-parentheses, + -bugprone-multi-level-implicit-pointer-conversion, + -bugprone-signed-char-misuse, + -bugprone-too-small-loop-variable, + -cppcoreguidelines-avoid-non-const-global-variables, + -cppcoreguidelines-use-default-member-init, + -hicpp-multiway-paths-covered, + -hicpp-named-parameter, + -misc-header-include-cycle, + -misc-no-recursion, + -performance-no-int-to-ptr, + -readability-avoid-return-with-void-value, + -readability-avoid-unconditional-preprocessor-if, + -readability-delete-null-pointer, + -readability-duplicate-include, + -readability-redundant-casting, + -readability-redundant-member-init, + -readability-reference-to-constructed-temporary, + -readability-simplify-boolean-expr, + -bugprone-unsafe-functions, + -cert-msc24-c, + -cert-msc32-c, + -cert-msc33-c, + -cert-msc51-cpp, + -cert-str34-c, + -cppcoreguidelines-macro-to-enum, + -modernize-macro-to-enum, + -abseil-string-find-str-contains, + -bugprone-suspicious-include, + -clang-analyzer-security.insecureAPI.DeprecatedOrUnsafeBufferHandling, + -clang-analyzer-optin.core.EnumCastOutOfRange, + -modernize-type-traits, + -misc-definitions-in-headers, + -bugprone-casting-through-void, + -readability-redundant-string-init, ' WarningsAsErrors: '*' CheckOptions: From 385450ca370bce8b3bf252cd0999278928c623b3 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 4 Feb 2026 21:40:31 +0100 Subject: [PATCH 767/812] CI: pin clang-tidy workflow to px4-dev:v1.17.0-beta1 container Pin the container image to v1.17.0-beta1 which includes clang-tidy 18 and all required clang dependencies pre-installed. This removes the need to install clang-tidy via apt on each workflow run. Signed-off-by: Ramon Roche --- .github/workflows/clang-tidy.yml | 11 +---------- 1 file changed, 1 insertion(+), 10 deletions(-) diff --git a/.github/workflows/clang-tidy.yml b/.github/workflows/clang-tidy.yml index 0828e01f91..38763d3097 100644 --- a/.github/workflows/clang-tidy.yml +++ b/.github/workflows/clang-tidy.yml @@ -21,20 +21,11 @@ jobs: fetch-depth: 0 fetch-tags: true - - name: Determine PX4 version for container image - id: px4_version - run: | - echo "px4_version=$(git describe --tags --match 'v[0-9]*')" >> $GITHUB_OUTPUT - - name: Testing (clang-tidy) uses: addnab/docker-run-action@v3 with: - image: px4io/px4-dev:${{ steps.px4_version.outputs.px4_version }} + image: px4io/px4-dev:v1.17.0-beta1 options: -v ${{ github.workspace }}:/workspace run: | cd /workspace - apt install clang-tidy-18 -y - update-alternatives --install /usr/bin/clang-tidy clang-tidy /usr/bin/clang-tidy-18 100 - update-alternatives --install /usr/bin/clang clang /usr/bin/clang-18 100 - update-alternatives --install /usr/bin/clang++ clang++ /usr/bin/clang++-18 100 make clang-tidy From 021eee0c5c927ec2d860faeb3468009bf292f4fd Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 11:27:13 -0800 Subject: [PATCH 768/812] CI: use 16-core runs-on runner for clang-tidy workflow The free GitHub runner (4 vCPUs) takes ~22 minutes. Switch to a 16-core runs-on runner and bump parallelism to -j16 to reduce clang-tidy analysis time. Signed-off-by: Ramon Roche --- .github/workflows/clang-tidy.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/clang-tidy.yml b/.github/workflows/clang-tidy.yml index 38763d3097..09d9f0729b 100644 --- a/.github/workflows/clang-tidy.yml +++ b/.github/workflows/clang-tidy.yml @@ -14,7 +14,7 @@ on: jobs: build: - runs-on: ubuntu-latest + runs-on: [runs-on, runner=16cpu-linux-x64, "run-id=${{ github.run_id }}"] steps: - uses: actions/checkout@v4 with: @@ -28,4 +28,4 @@ jobs: options: -v ${{ github.workspace }}:/workspace run: | cd /workspace - make clang-tidy + make -j16 clang-tidy From e831c66ae11ac2a18355363856adf947a52b73aa Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 11:29:21 -0800 Subject: [PATCH 769/812] CI: add ccache and S3 caching to clang-tidy workflow - Switch from addnab/docker-run-action to native container directive - Use runs-on 16-core runner with S3 cache (extras=s3-cache) - Add ccache setup matching build_all_targets pattern - Run clang-tidy with -j16 to leverage all cores Signed-off-by: Ramon Roche --- .github/workflows/clang-tidy.yml | 43 ++++++++++++++++++++++++++------ 1 file changed, 35 insertions(+), 8 deletions(-) diff --git a/.github/workflows/clang-tidy.yml b/.github/workflows/clang-tidy.yml index 09d9f0729b..0187cbcd47 100644 --- a/.github/workflows/clang-tidy.yml +++ b/.github/workflows/clang-tidy.yml @@ -14,18 +14,45 @@ on: jobs: build: - runs-on: [runs-on, runner=16cpu-linux-x64, "run-id=${{ github.run_id }}"] + runs-on: [runs-on, runner=16cpu-linux-x64, "run-id=${{ github.run_id }}", "extras=s3-cache"] + container: + image: px4io/px4-dev:v1.17.0-beta1 steps: + - uses: runs-on/action@v2 - uses: actions/checkout@v4 with: fetch-depth: 0 fetch-tags: true - - name: Testing (clang-tidy) - uses: addnab/docker-run-action@v3 + - name: Git ownership workaround + run: git config --system --add safe.directory '*' + + - name: ccache cache + id: cc_restore + uses: runs-on/cache@v4 with: - image: px4io/px4-dev:v1.17.0-beta1 - options: -v ${{ github.workspace }}:/workspace - run: | - cd /workspace - make -j16 clang-tidy + path: ~/.ccache + key: ccache-clang-tidy-${{ github.ref_name }} + restore-keys: | + ccache-clang-tidy-${{ github.ref_name }}- + ccache-clang-tidy-main- + ccache-clang-tidy- + + - name: ccache config and stats + run: | + mkdir -p ~/.ccache + echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf + echo "compression = true" >> ~/.ccache/ccache.conf + echo "compression_level = 6" >> ~/.ccache/ccache.conf + echo "max_size = 120M" >> ~/.ccache/ccache.conf + echo "hash_dir = false" >> ~/.ccache/ccache.conf + echo "compiler_check = content" >> ~/.ccache/ccache.conf + ccache -s + ccache -z + + - name: Testing (clang-tidy) + run: make -j16 clang-tidy + + - name: ccache post-build stats + if: always() + run: ccache -s From 8a007d38e7356778288705e7cc93d98d2032af09 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 14:12:44 -0800 Subject: [PATCH 770/812] CI: split ccache into restore/save so cache persists on failure Use separate cache/restore and cache/save steps with if: always() on the save step, matching the build_all_targets pattern. Signed-off-by: Ramon Roche --- .github/workflows/clang-tidy.yml | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/.github/workflows/clang-tidy.yml b/.github/workflows/clang-tidy.yml index 0187cbcd47..8eb8cc7a35 100644 --- a/.github/workflows/clang-tidy.yml +++ b/.github/workflows/clang-tidy.yml @@ -27,9 +27,9 @@ jobs: - name: Git ownership workaround run: git config --system --add safe.directory '*' - - name: ccache cache + - name: ccache cache restore id: cc_restore - uses: runs-on/cache@v4 + uses: runs-on/cache/restore@v4 with: path: ~/.ccache key: ccache-clang-tidy-${{ github.ref_name }} @@ -56,3 +56,10 @@ jobs: - name: ccache post-build stats if: always() run: ccache -s + + - name: ccache cache save + if: always() + uses: runs-on/cache/save@v4 + with: + path: ~/.ccache + key: ${{ steps.cc_restore.outputs.cache-primary-key }} From 618a6aa98f60186c0d925d056eb65a26634c433d Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 14:15:50 -0800 Subject: [PATCH 771/812] CI: add explicit permissions block to clang-tidy workflow Set minimal permissions (contents: read) as flagged by CodeQL. Signed-off-by: Ramon Roche --- .github/workflows/clang-tidy.yml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.github/workflows/clang-tidy.yml b/.github/workflows/clang-tidy.yml index 8eb8cc7a35..f3b917cbd0 100644 --- a/.github/workflows/clang-tidy.yml +++ b/.github/workflows/clang-tidy.yml @@ -12,6 +12,9 @@ on: paths-ignore: - 'docs/**' +permissions: + contents: read + jobs: build: runs-on: [runs-on, runner=16cpu-linux-x64, "run-id=${{ github.run_id }}", "extras=s3-cache"] From 29fefeeada10d30ffa1e297a947a0300f1ffeb36 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 14:28:48 -0800 Subject: [PATCH 772/812] CI: fix ccache key to use branch name instead of merge ref github.ref_name resolves to '26367/merge' for pull_request events, causing cache misses. Use github.head_ref (PR source branch) with fallback to github.ref_name for push events. Signed-off-by: Ramon Roche --- .github/workflows/clang-tidy.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/clang-tidy.yml b/.github/workflows/clang-tidy.yml index f3b917cbd0..46e1247c68 100644 --- a/.github/workflows/clang-tidy.yml +++ b/.github/workflows/clang-tidy.yml @@ -35,9 +35,9 @@ jobs: uses: runs-on/cache/restore@v4 with: path: ~/.ccache - key: ccache-clang-tidy-${{ github.ref_name }} + key: ccache-clang-tidy-${{ github.head_ref || github.ref_name }} restore-keys: | - ccache-clang-tidy-${{ github.ref_name }}- + ccache-clang-tidy-${{ github.head_ref || github.ref_name }}- ccache-clang-tidy-main- ccache-clang-tidy- From d9b3e48ec5907b479b60256a9a027e9d4856e95a Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 14:42:45 -0800 Subject: [PATCH 773/812] CI: improve clang-tidy workflow naming and use standard cache actions Rename workflow to "Static Analysis" with job name "Clang-Tidy" for clearer GitHub Checks UI. Use Title Case action-verb step names. Switch from runs-on/cache to actions/cache since the runs-on Magic Cache sidecar transparently handles S3 backing. Signed-off-by: Ramon Roche --- .github/workflows/clang-tidy.yml | 21 +++++++++++---------- 1 file changed, 11 insertions(+), 10 deletions(-) diff --git a/.github/workflows/clang-tidy.yml b/.github/workflows/clang-tidy.yml index 46e1247c68..fc3c5a46ea 100644 --- a/.github/workflows/clang-tidy.yml +++ b/.github/workflows/clang-tidy.yml @@ -1,4 +1,4 @@ -name: Clang Tidy +name: Static Analysis on: push: @@ -16,7 +16,8 @@ permissions: contents: read jobs: - build: + clang_tidy: + name: Clang-Tidy runs-on: [runs-on, runner=16cpu-linux-x64, "run-id=${{ github.run_id }}", "extras=s3-cache"] container: image: px4io/px4-dev:v1.17.0-beta1 @@ -27,12 +28,12 @@ jobs: fetch-depth: 0 fetch-tags: true - - name: Git ownership workaround + - name: Configure Git Safe Directory run: git config --system --add safe.directory '*' - - name: ccache cache restore + - name: Restore Compiler Cache id: cc_restore - uses: runs-on/cache/restore@v4 + uses: actions/cache/restore@v4 with: path: ~/.ccache key: ccache-clang-tidy-${{ github.head_ref || github.ref_name }} @@ -41,7 +42,7 @@ jobs: ccache-clang-tidy-main- ccache-clang-tidy- - - name: ccache config and stats + - name: Configure Compiler Cache run: | mkdir -p ~/.ccache echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf @@ -53,16 +54,16 @@ jobs: ccache -s ccache -z - - name: Testing (clang-tidy) + - name: Run Clang-Tidy Analysis run: make -j16 clang-tidy - - name: ccache post-build stats + - name: Compiler Cache Stats if: always() run: ccache -s - - name: ccache cache save + - name: Save Compiler Cache if: always() - uses: runs-on/cache/save@v4 + uses: actions/cache/save@v4 with: path: ~/.ccache key: ${{ steps.cc_restore.outputs.cache-primary-key }} From 0646fa6c9d5d8a69f23958ba96dff3d86f8ec69f Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 15:09:29 -0800 Subject: [PATCH 774/812] logger: add unit test for ULog INFO message serialization Add a gtest that validates the exact binary layout of INFO and INFO_MULTIPLE messages against the ULog spec. This exercises the same packing logic as write_info/write_info_multiple and will catch any accidental changes to the wire format (e.g. including a null terminator in msg_size). Signed-off-by: Ramon Roche --- src/modules/logger/CMakeLists.txt | 2 + src/modules/logger/ULogMessageInfoTest.cpp | 106 +++++++++++++++++++++ 2 files changed, 108 insertions(+) create mode 100644 src/modules/logger/ULogMessageInfoTest.cpp diff --git a/src/modules/logger/CMakeLists.txt b/src/modules/logger/CMakeLists.txt index 9ff775f220..5212717925 100644 --- a/src/modules/logger/CMakeLists.txt +++ b/src/modules/logger/CMakeLists.txt @@ -60,3 +60,5 @@ px4_add_module( version component_general_json # for checksums.h ) + +px4_add_unit_gtest(SRC ULogMessageInfoTest.cpp) diff --git a/src/modules/logger/ULogMessageInfoTest.cpp b/src/modules/logger/ULogMessageInfoTest.cpp new file mode 100644 index 0000000000..682a4b6447 --- /dev/null +++ b/src/modules/logger/ULogMessageInfoTest.cpp @@ -0,0 +1,106 @@ +/**************************************************************************** + * + * Copyright (C) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include +#include "messages.h" + +TEST(ULogMessageInfo, InfoMessageLayout) +{ + const char *name = "hello"; + const char *value = "world"; + const size_t vlen = strlen(value); + + ulog_message_info_s msg = {}; + uint8_t *buffer = reinterpret_cast(&msg); + msg.msg_type = static_cast(ULogMessageType::INFO); + + msg.key_len = snprintf(msg.key_value_str, sizeof(msg.key_value_str), + "char[%zu] %s", vlen, name); + size_t msg_size = sizeof(msg) - sizeof(msg.key_value_str) + msg.key_len; + + ASSERT_LT(vlen, sizeof(msg) - msg_size); + memcpy(&buffer[msg_size], value, vlen); + msg_size += vlen; + + msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN; + + // msg_size == key_len + vlen + 1 (the +1 is the key_len field itself) + EXPECT_EQ(msg.msg_size, msg.key_len + vlen + 1); + EXPECT_EQ(msg.msg_type, static_cast('I')); + + const char expected_key[] = "char[5] hello"; + EXPECT_EQ(msg.key_len, strlen(expected_key)); + + const size_t header_size = sizeof(msg) - sizeof(msg.key_value_str); + const uint8_t *value_start = &buffer[header_size + msg.key_len]; + EXPECT_EQ(memcmp(value_start, "world", vlen), 0); + + // msg_size must not account for a null terminator + EXPECT_EQ(msg_size, header_size + msg.key_len + vlen); +} + +TEST(ULogMessageInfo, InfoMultipleMessageLayout) +{ + const char *name = "ver"; + const char *value = "1.0"; + const size_t vlen = strlen(value); + + ulog_message_info_multiple_s msg = {}; + uint8_t *buffer = reinterpret_cast(&msg); + msg.msg_type = static_cast(ULogMessageType::INFO_MULTIPLE); + msg.is_continued = false; + + msg.key_len = snprintf(msg.key_value_str, sizeof(msg.key_value_str), + "char[%zu] %s", vlen, name); + size_t msg_size = sizeof(msg) - sizeof(msg.key_value_str) + msg.key_len; + + ASSERT_LT(vlen, sizeof(msg) - msg_size); + memcpy(&buffer[msg_size], value, vlen); + msg_size += vlen; + + msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN; + + const size_t header_size = sizeof(msg) - sizeof(msg.key_value_str); + EXPECT_EQ(msg.msg_size, msg_size - ULOG_MSG_HEADER_LEN); + EXPECT_EQ(msg.msg_type, static_cast('M')); + + const char expected_key[] = "char[3] ver"; + EXPECT_EQ(msg.key_len, strlen(expected_key)); + + const uint8_t *value_start = &buffer[header_size + msg.key_len]; + EXPECT_EQ(memcmp(value_start, "1.0", vlen), 0); + + EXPECT_EQ(msg_size, header_size + msg.key_len + vlen); +} From 83a4d648e35493d10b690929c567ec747e2fd85a Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 15:09:52 -0800 Subject: [PATCH 775/812] logger: copy null terminator in write_info memcpy MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit clang-tidy flags the memcpy of vlen bytes as bugprone-not-null-terminated-result because the destination buffer region is left unterminated in memory. Copy vlen + 1 bytes (including the source null terminator) so the buffer is null-terminated in memory. The ULog msg_size is not incremented for the extra byte — the null sits in the struct's key_value_str padding and is never written to the log file, preserving the ULog wire format which does not include a null terminator for string values. The bounds check (vlen < sizeof(msg) - msg_size) guarantees at least one byte of headroom beyond vlen, so vlen + 1 is always within the struct. Signed-off-by: Ramon Roche --- src/modules/logger/logger.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/logger/logger.cpp b/src/modules/logger/logger.cpp index 196550615e..7e65cf448c 100644 --- a/src/modules/logger/logger.cpp +++ b/src/modules/logger/logger.cpp @@ -1890,7 +1890,7 @@ void Logger::write_info(LogType type, const char *name, const char *value) /* copy string value directly to buffer */ if (vlen < (sizeof(msg) - msg_size)) { - memcpy(&buffer[msg_size], value, vlen); + memcpy(&buffer[msg_size], value, vlen + 1); msg_size += vlen; msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN; @@ -1916,7 +1916,7 @@ void Logger::write_info_multiple(LogType type, const char *name, const char *val /* copy string value directly to buffer */ if (vlen < (sizeof(msg) - msg_size)) { - memcpy(&buffer[msg_size], value, vlen); + memcpy(&buffer[msg_size], value, vlen + 1); msg_size += vlen; msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN; From 5d151c54a4bafb3e176fdc96e4de321329ea0ff4 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 15:10:11 -0800 Subject: [PATCH 776/812] flight_mode_manager: call direct parent instead of grandparent FlightTaskManualAcceleration and FlightTaskOrbit both inherit from FlightTaskManualAltitudeSmoothVel but were calling FlightTask and FlightTaskManualAltitude respectively, skipping the intermediate parent's overrides (smoothing velocity init, parameter chain). Fix the DEFINE_PARAMETERS_CUSTOM_PARENT macro argument and the activate() call to use FlightTaskManualAltitudeSmoothVel. Fixes bugprone-parent-virtual-call clang-tidy diagnostic. Signed-off-by: Ramon Roche --- .../tasks/ManualAcceleration/FlightTaskManualAcceleration.hpp | 2 +- src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/flight_mode_manager/tasks/ManualAcceleration/FlightTaskManualAcceleration.hpp b/src/modules/flight_mode_manager/tasks/ManualAcceleration/FlightTaskManualAcceleration.hpp index 56fefcc792..2ce9a7c44f 100644 --- a/src/modules/flight_mode_manager/tasks/ManualAcceleration/FlightTaskManualAcceleration.hpp +++ b/src/modules/flight_mode_manager/tasks/ManualAcceleration/FlightTaskManualAcceleration.hpp @@ -52,7 +52,7 @@ protected: StickAccelerationXY _stick_acceleration_xy{this}; WeatherVane _weathervane{this}; /**< weathervane library, used to implement a yaw control law that turns the vehicle nose into the wind */ - DEFINE_PARAMETERS_CUSTOM_PARENT(FlightTask, + DEFINE_PARAMETERS_CUSTOM_PARENT(FlightTaskManualAltitudeSmoothVel, (ParamFloat) _param_mpc_vel_manual, (ParamFloat) _param_mpc_acc_hor ) diff --git a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp index d8b68b0db3..55c6b64273 100644 --- a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp +++ b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp @@ -173,7 +173,7 @@ void FlightTaskOrbit::_sanitizeParams(float &radius, float &velocity) const bool FlightTaskOrbit::activate(const trajectory_setpoint_s &last_setpoint) { - bool ret = FlightTaskManualAltitude::activate(last_setpoint); + bool ret = FlightTaskManualAltitudeSmoothVel::activate(last_setpoint); _currently_orbiting = false; _orbit_radius = _radius_min; _orbit_velocity = 1.f; From b60aa5dd2be36a38fa3652a1d4fb0372f10f4fb8 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 15:10:27 -0800 Subject: [PATCH 777/812] ekf2, fw_mode_manager, fw_rate_control: remove unused using declarations MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Remove using-declarations for math::constrain, math::max, and math::min that are never used — all call sites use the fully-qualified form (e.g. math::constrain()). Fixes misc-unused-using-decls clang-tidy diagnostic. Signed-off-by: Ramon Roche --- src/modules/ekf2/EKF2.cpp | 1 - src/modules/fw_mode_manager/FixedWingModeManager.cpp | 3 --- src/modules/fw_rate_control/FixedwingRateControl.cpp | 1 - 3 files changed, 5 deletions(-) diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 4a3ddfc32f..98e2be7828 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -35,7 +35,6 @@ #include "EKF2.hpp" using namespace time_literals; -using math::constrain; using matrix::Eulerf; using matrix::Quatf; using matrix::Vector3f; diff --git a/src/modules/fw_mode_manager/FixedWingModeManager.cpp b/src/modules/fw_mode_manager/FixedWingModeManager.cpp index 0ac0d36264..1f752608ca 100644 --- a/src/modules/fw_mode_manager/FixedWingModeManager.cpp +++ b/src/modules/fw_mode_manager/FixedWingModeManager.cpp @@ -36,9 +36,6 @@ #include #include -using math::constrain; -using math::max; -using math::min; using math::radians; using matrix::Dcmf; diff --git a/src/modules/fw_rate_control/FixedwingRateControl.cpp b/src/modules/fw_rate_control/FixedwingRateControl.cpp index 3ae3272cfa..993d68bdd0 100644 --- a/src/modules/fw_rate_control/FixedwingRateControl.cpp +++ b/src/modules/fw_rate_control/FixedwingRateControl.cpp @@ -36,7 +36,6 @@ using namespace time_literals; using namespace matrix; -using math::constrain; using math::interpolate; using math::radians; From 497704f3b9abb816a8815539587fe2cd8675bcc5 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 15:10:43 -0800 Subject: [PATCH 778/812] fw_mode_manager: pass FigureEightPatternPoints by const reference The 48-byte struct (6 Vector2f) is only read inside initializePattern, so passing by value creates an unnecessary copy. Fixes performance-unnecessary-value-param clang-tidy diagnostic. Signed-off-by: Ramon Roche --- src/modules/fw_mode_manager/figure_eight/FigureEight.cpp | 2 +- src/modules/fw_mode_manager/figure_eight/FigureEight.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/fw_mode_manager/figure_eight/FigureEight.cpp b/src/modules/fw_mode_manager/figure_eight/FigureEight.cpp index f7585f39b4..a995d28543 100644 --- a/src/modules/fw_mode_manager/figure_eight/FigureEight.cpp +++ b/src/modules/fw_mode_manager/figure_eight/FigureEight.cpp @@ -105,7 +105,7 @@ FigureEight::FigureEightPatternParameters FigureEight::sanitizeParameters(const } void FigureEight::initializePattern(const matrix::Vector2f &curr_pos_local, const matrix::Vector2f &ground_speed, - const FigureEightPatternParameters ¶meters, FigureEightPatternPoints pattern_points) + const FigureEightPatternParameters ¶meters, const FigureEightPatternPoints &pattern_points) { // Initialize the currently active segment, if it hasn't been active yet, or the pattern has been changed. if ((_current_segment == FigureEightSegment::SEGMENT_UNDEFINED) || (_active_parameters != parameters)) { diff --git a/src/modules/fw_mode_manager/figure_eight/FigureEight.hpp b/src/modules/fw_mode_manager/figure_eight/FigureEight.hpp index 297e07942c..fcdb39915c 100644 --- a/src/modules/fw_mode_manager/figure_eight/FigureEight.hpp +++ b/src/modules/fw_mode_manager/figure_eight/FigureEight.hpp @@ -140,7 +140,7 @@ private: * @param[in] pattern_points are the figure of eight pattern points. */ void initializePattern(const matrix::Vector2f &curr_pos_local, const matrix::Vector2f &ground_speed, - const FigureEightPatternParameters ¶meters, FigureEightPatternPoints pattern_points); + const FigureEightPatternParameters ¶meters, const FigureEightPatternPoints &pattern_points); /** * @brief Calculate figure eight pattern points From 9849d908770eb493c7e5c61336944cc2839253ea Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 15:10:56 -0800 Subject: [PATCH 779/812] gps: add null check for path in GPS constructor Guard the strncpy call with a null check to prevent undefined behavior if the constructor is ever called with a null path pointer. Fixes clang-analyzer-core.NonNullParamChecker diagnostic. Signed-off-by: Ramon Roche --- src/drivers/gps/gps.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index b33e27ac22..464eb892e9 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -318,9 +318,13 @@ GPS::GPS(const char *path, gps_driver_mode_t mode, GPSHelper::Interface interfac _instance(instance) { /* store port name */ - strncpy(_port, path, sizeof(_port) - 1); - /* enforce null termination */ - _port[sizeof(_port) - 1] = '\0'; + if (path != nullptr) { + strncpy(_port, path, sizeof(_port) - 1); + _port[sizeof(_port) - 1] = '\0'; + + } else { + _port[0] = '\0'; + } _sensor_gps.heading = NAN; _sensor_gps.heading_offset = NAN; From f29afe134201d64472665450305a003fc6999c92 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 15:27:50 -0800 Subject: [PATCH 780/812] logger: expand ULog unit tests to cover all message types Rename ULogMessageInfoTest to ULogMessagesTest and add struct-level coverage for every message type in the ULog spec: - File header: magic bytes, size, field offsets - Flag Bits ('B'): size, field offsets, flag masks - Format ('F'): size, serialization - Info ('I'): string, int32_t, and float value layouts - Info Multiple ('M'): string layout, continuation flag, field offsets - Parameter ('P'): int32_t and float value layouts - Default Parameter ('Q'): size, type bits, field offsets - Subscription ('A'): size, field offsets, serialization - Unsubscription ('R'): size, serialization - Data ('D'): size, field offset - Logging ('L'): size, field offsets, serialization - Logging Tagged ('C'): size, field offsets - Sync ('S'): size, magic bytes - Dropout ('O'): size, default msg_size, serialization - Message header: size, field offsets, ULOG_MSG_HEADER_LEN - Enum values: all 13 ULogMessageType codes Signed-off-by: Ramon Roche --- src/modules/logger/CMakeLists.txt | 2 +- src/modules/logger/ULogMessageInfoTest.cpp | 106 ---- src/modules/logger/ULogMessagesTest.cpp | 666 +++++++++++++++++++++ 3 files changed, 667 insertions(+), 107 deletions(-) delete mode 100644 src/modules/logger/ULogMessageInfoTest.cpp create mode 100644 src/modules/logger/ULogMessagesTest.cpp diff --git a/src/modules/logger/CMakeLists.txt b/src/modules/logger/CMakeLists.txt index 5212717925..b9ea444670 100644 --- a/src/modules/logger/CMakeLists.txt +++ b/src/modules/logger/CMakeLists.txt @@ -61,4 +61,4 @@ px4_add_module( component_general_json # for checksums.h ) -px4_add_unit_gtest(SRC ULogMessageInfoTest.cpp) +px4_add_unit_gtest(SRC ULogMessagesTest.cpp) diff --git a/src/modules/logger/ULogMessageInfoTest.cpp b/src/modules/logger/ULogMessageInfoTest.cpp deleted file mode 100644 index 682a4b6447..0000000000 --- a/src/modules/logger/ULogMessageInfoTest.cpp +++ /dev/null @@ -1,106 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2025 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -#include -#include -#include -#include "messages.h" - -TEST(ULogMessageInfo, InfoMessageLayout) -{ - const char *name = "hello"; - const char *value = "world"; - const size_t vlen = strlen(value); - - ulog_message_info_s msg = {}; - uint8_t *buffer = reinterpret_cast(&msg); - msg.msg_type = static_cast(ULogMessageType::INFO); - - msg.key_len = snprintf(msg.key_value_str, sizeof(msg.key_value_str), - "char[%zu] %s", vlen, name); - size_t msg_size = sizeof(msg) - sizeof(msg.key_value_str) + msg.key_len; - - ASSERT_LT(vlen, sizeof(msg) - msg_size); - memcpy(&buffer[msg_size], value, vlen); - msg_size += vlen; - - msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN; - - // msg_size == key_len + vlen + 1 (the +1 is the key_len field itself) - EXPECT_EQ(msg.msg_size, msg.key_len + vlen + 1); - EXPECT_EQ(msg.msg_type, static_cast('I')); - - const char expected_key[] = "char[5] hello"; - EXPECT_EQ(msg.key_len, strlen(expected_key)); - - const size_t header_size = sizeof(msg) - sizeof(msg.key_value_str); - const uint8_t *value_start = &buffer[header_size + msg.key_len]; - EXPECT_EQ(memcmp(value_start, "world", vlen), 0); - - // msg_size must not account for a null terminator - EXPECT_EQ(msg_size, header_size + msg.key_len + vlen); -} - -TEST(ULogMessageInfo, InfoMultipleMessageLayout) -{ - const char *name = "ver"; - const char *value = "1.0"; - const size_t vlen = strlen(value); - - ulog_message_info_multiple_s msg = {}; - uint8_t *buffer = reinterpret_cast(&msg); - msg.msg_type = static_cast(ULogMessageType::INFO_MULTIPLE); - msg.is_continued = false; - - msg.key_len = snprintf(msg.key_value_str, sizeof(msg.key_value_str), - "char[%zu] %s", vlen, name); - size_t msg_size = sizeof(msg) - sizeof(msg.key_value_str) + msg.key_len; - - ASSERT_LT(vlen, sizeof(msg) - msg_size); - memcpy(&buffer[msg_size], value, vlen); - msg_size += vlen; - - msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN; - - const size_t header_size = sizeof(msg) - sizeof(msg.key_value_str); - EXPECT_EQ(msg.msg_size, msg_size - ULOG_MSG_HEADER_LEN); - EXPECT_EQ(msg.msg_type, static_cast('M')); - - const char expected_key[] = "char[3] ver"; - EXPECT_EQ(msg.key_len, strlen(expected_key)); - - const uint8_t *value_start = &buffer[header_size + msg.key_len]; - EXPECT_EQ(memcmp(value_start, "1.0", vlen), 0); - - EXPECT_EQ(msg_size, header_size + msg.key_len + vlen); -} diff --git a/src/modules/logger/ULogMessagesTest.cpp b/src/modules/logger/ULogMessagesTest.cpp new file mode 100644 index 0000000000..4e5f9d846c --- /dev/null +++ b/src/modules/logger/ULogMessagesTest.cpp @@ -0,0 +1,666 @@ +/**************************************************************************** + * + * Copyright (C) 2025 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include +#include "messages.h" + +// ---------------------------------------------------------------------------- +// Header & constants +// ---------------------------------------------------------------------------- + +TEST(ULogMessages, HeaderLen) +{ + EXPECT_EQ(ULOG_MSG_HEADER_LEN, 3u); +} + +TEST(ULogMessages, MessageHeaderSize) +{ + EXPECT_EQ(sizeof(ulog_message_header_s), 3u); +} + +TEST(ULogMessages, MessageHeaderFieldOffsets) +{ + ulog_message_header_s msg = {}; + uint8_t *base = reinterpret_cast(&msg); + + EXPECT_EQ(reinterpret_cast(&msg.msg_size) - base, 0); + EXPECT_EQ(reinterpret_cast(&msg.msg_type) - base, 2); +} + +// ---------------------------------------------------------------------------- +// File header (16 bytes: 8 magic + 8 timestamp) +// ---------------------------------------------------------------------------- + +TEST(ULogMessages, FileHeaderSize) +{ + EXPECT_EQ(sizeof(ulog_file_header_s), 16u); +} + +TEST(ULogMessages, FileHeaderMagic) +{ + ulog_file_header_s hdr = {}; + const uint8_t expected_magic[] = {'U', 'L', 'o', 'g', 0x01, 0x12, 0x35, 0x01}; + + memcpy(hdr.magic, expected_magic, sizeof(expected_magic)); + hdr.timestamp = 1000000ULL; + + EXPECT_EQ(memcmp(hdr.magic, expected_magic, 7), 0); + EXPECT_EQ(hdr.magic[7], 0x01); + EXPECT_EQ(hdr.timestamp, 1000000ULL); +} + +TEST(ULogMessages, FileHeaderFieldOffsets) +{ + ulog_file_header_s hdr = {}; + uint8_t *base = reinterpret_cast(&hdr); + + EXPECT_EQ(reinterpret_cast(&hdr.magic) - base, 0); + EXPECT_EQ(reinterpret_cast(&hdr.timestamp) - base, 8); +} + +// ---------------------------------------------------------------------------- +// Flag Bits ('B') — must be first message after header +// ---------------------------------------------------------------------------- + +TEST(ULogMessages, FlagBitsSize) +{ + // payload: 8 compat + 8 incompat + 24 appended_offsets = 40 + EXPECT_EQ(sizeof(ulog_message_flag_bits_s), ULOG_MSG_HEADER_LEN + 40u); +} + +TEST(ULogMessages, FlagBitsTypeCode) +{ + ulog_message_flag_bits_s msg = {}; + EXPECT_EQ(msg.msg_type, static_cast('B')); +} + +TEST(ULogMessages, FlagBitsFieldOffsets) +{ + ulog_message_flag_bits_s msg = {}; + uint8_t *base = reinterpret_cast(&msg); + + EXPECT_EQ(reinterpret_cast(&msg.compat_flags) - base, ULOG_MSG_HEADER_LEN); + EXPECT_EQ(reinterpret_cast(&msg.incompat_flags) - base, ULOG_MSG_HEADER_LEN + 8); + EXPECT_EQ(reinterpret_cast(&msg.appended_offsets) - base, ULOG_MSG_HEADER_LEN + 16); +} + +TEST(ULogMessages, FlagBitsDataAppendedMask) +{ + EXPECT_EQ(ULOG_INCOMPAT_FLAG0_DATA_APPENDED_MASK, 1 << 0); + EXPECT_EQ(ULOG_COMPAT_FLAG0_DEFAULT_PARAMETERS_MASK, 1 << 0); +} + +// ---------------------------------------------------------------------------- +// Format Definition ('F') +// ---------------------------------------------------------------------------- + +TEST(ULogMessages, FormatSize) +{ + EXPECT_EQ(sizeof(ulog_message_format_s), ULOG_MSG_HEADER_LEN + 1600u); +} + +TEST(ULogMessages, FormatTypeCode) +{ + ulog_message_format_s msg = {}; + EXPECT_EQ(msg.msg_type, static_cast('F')); +} + +TEST(ULogMessages, FormatSerialization) +{ + ulog_message_format_s msg = {}; + const char *format_str = "test_topic:uint64_t timestamp;float value;"; + size_t len = strlen(format_str); + + strncpy(msg.format, format_str, sizeof(msg.format)); + msg.msg_size = len; + + EXPECT_EQ(msg.msg_size, len); + EXPECT_EQ(memcmp(msg.format, format_str, len), 0); +} + +// ---------------------------------------------------------------------------- +// Information ('I') +// ---------------------------------------------------------------------------- + +TEST(ULogMessages, InfoSize) +{ + // header(3) + key_len(1) + key_value_str(255) = 259 + EXPECT_EQ(sizeof(ulog_message_info_s), ULOG_MSG_HEADER_LEN + 1u + 255u); +} + +TEST(ULogMessages, InfoTypeCode) +{ + ulog_message_info_s msg = {}; + EXPECT_EQ(msg.msg_type, static_cast('I')); +} + +TEST(ULogMessages, InfoStringLayout) +{ + const char *name = "hello"; + const char *value = "world"; + const size_t vlen = strlen(value); + + ulog_message_info_s msg = {}; + uint8_t *buffer = reinterpret_cast(&msg); + msg.msg_type = static_cast(ULogMessageType::INFO); + + msg.key_len = snprintf(msg.key_value_str, sizeof(msg.key_value_str), + "char[%zu] %s", vlen, name); + size_t msg_size = sizeof(msg) - sizeof(msg.key_value_str) + msg.key_len; + + ASSERT_LT(vlen, sizeof(msg) - msg_size); + memcpy(&buffer[msg_size], value, vlen); + msg_size += vlen; + + msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN; + + // msg_size == key_len_field(1) + key_len + vlen + EXPECT_EQ(msg.msg_size, msg.key_len + vlen + 1); + + const char expected_key[] = "char[5] hello"; + EXPECT_EQ(msg.key_len, strlen(expected_key)); + + const size_t header_size = sizeof(msg) - sizeof(msg.key_value_str); + const uint8_t *value_start = &buffer[header_size + msg.key_len]; + EXPECT_EQ(memcmp(value_start, "world", vlen), 0); + + // no null terminator in msg_size + EXPECT_EQ(msg_size, header_size + msg.key_len + vlen); +} + +TEST(ULogMessages, InfoInt32Layout) +{ + const char *name = "sys_param"; + int32_t value = 42; + + ulog_message_info_s msg = {}; + uint8_t *buffer = reinterpret_cast(&msg); + msg.msg_type = static_cast(ULogMessageType::INFO); + + msg.key_len = snprintf(msg.key_value_str, sizeof(msg.key_value_str), + "int32_t %s", name); + size_t msg_size = sizeof(msg) - sizeof(msg.key_value_str) + msg.key_len; + + ASSERT_LE(sizeof(value), sizeof(msg) - msg_size); + memcpy(&buffer[msg_size], &value, sizeof(value)); + msg_size += sizeof(value); + + msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN; + + EXPECT_EQ(msg.msg_size, msg.key_len + sizeof(int32_t) + 1); + + const char expected_key[] = "int32_t sys_param"; + EXPECT_EQ(msg.key_len, strlen(expected_key)); + + const size_t header_size = sizeof(msg) - sizeof(msg.key_value_str); + int32_t read_back = 0; + memcpy(&read_back, &buffer[header_size + msg.key_len], sizeof(int32_t)); + EXPECT_EQ(read_back, 42); +} + +TEST(ULogMessages, InfoFloatLayout) +{ + const char *name = "cal_offset"; + float value = 3.14f; + + ulog_message_info_s msg = {}; + uint8_t *buffer = reinterpret_cast(&msg); + msg.msg_type = static_cast(ULogMessageType::INFO); + + msg.key_len = snprintf(msg.key_value_str, sizeof(msg.key_value_str), + "float %s", name); + size_t msg_size = sizeof(msg) - sizeof(msg.key_value_str) + msg.key_len; + + ASSERT_LE(sizeof(value), sizeof(msg) - msg_size); + memcpy(&buffer[msg_size], &value, sizeof(value)); + msg_size += sizeof(value); + + msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN; + + EXPECT_EQ(msg.msg_size, msg.key_len + sizeof(float) + 1); + + const size_t header_size = sizeof(msg) - sizeof(msg.key_value_str); + float read_back = 0.f; + memcpy(&read_back, &buffer[header_size + msg.key_len], sizeof(float)); + EXPECT_FLOAT_EQ(read_back, 3.14f); +} + +// ---------------------------------------------------------------------------- +// Information Multiple ('M') +// ---------------------------------------------------------------------------- + +TEST(ULogMessages, InfoMultipleSize) +{ + // header(3) + is_continued(1) + key_len(1) + key_value_str(1200) = 1205 + EXPECT_EQ(sizeof(ulog_message_info_multiple_s), ULOG_MSG_HEADER_LEN + 1u + 1u + 1200u); +} + +TEST(ULogMessages, InfoMultipleTypeCode) +{ + ulog_message_info_multiple_s msg = {}; + EXPECT_EQ(msg.msg_type, static_cast('M')); +} + +TEST(ULogMessages, InfoMultipleStringLayout) +{ + const char *name = "ver"; + const char *value = "1.0"; + const size_t vlen = strlen(value); + + ulog_message_info_multiple_s msg = {}; + uint8_t *buffer = reinterpret_cast(&msg); + msg.msg_type = static_cast(ULogMessageType::INFO_MULTIPLE); + msg.is_continued = false; + + msg.key_len = snprintf(msg.key_value_str, sizeof(msg.key_value_str), + "char[%zu] %s", vlen, name); + size_t msg_size = sizeof(msg) - sizeof(msg.key_value_str) + msg.key_len; + + ASSERT_LT(vlen, sizeof(msg) - msg_size); + memcpy(&buffer[msg_size], value, vlen); + msg_size += vlen; + + msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN; + + const size_t header_size = sizeof(msg) - sizeof(msg.key_value_str); + EXPECT_EQ(msg.msg_size, msg_size - ULOG_MSG_HEADER_LEN); + EXPECT_EQ(msg.is_continued, 0); + + const char expected_key[] = "char[3] ver"; + EXPECT_EQ(msg.key_len, strlen(expected_key)); + + const uint8_t *value_start = &buffer[header_size + msg.key_len]; + EXPECT_EQ(memcmp(value_start, "1.0", vlen), 0); + + EXPECT_EQ(msg_size, header_size + msg.key_len + vlen); +} + +TEST(ULogMessages, InfoMultipleContinuation) +{ + ulog_message_info_multiple_s msg = {}; + msg.is_continued = 1; + + EXPECT_EQ(msg.is_continued, 1); + EXPECT_EQ(msg.msg_type, static_cast('M')); +} + +TEST(ULogMessages, InfoMultipleFieldOffsets) +{ + ulog_message_info_multiple_s msg = {}; + uint8_t *base = reinterpret_cast(&msg); + + EXPECT_EQ(reinterpret_cast(&msg.is_continued) - base, ULOG_MSG_HEADER_LEN); + EXPECT_EQ(reinterpret_cast(&msg.key_len) - base, ULOG_MSG_HEADER_LEN + 1); + EXPECT_EQ(reinterpret_cast(&msg.key_value_str) - base, ULOG_MSG_HEADER_LEN + 2); +} + +// ---------------------------------------------------------------------------- +// Parameter ('P') +// ---------------------------------------------------------------------------- + +TEST(ULogMessages, ParameterSize) +{ + EXPECT_EQ(sizeof(ulog_message_parameter_s), ULOG_MSG_HEADER_LEN + 1u + 255u); +} + +TEST(ULogMessages, ParameterTypeCode) +{ + ulog_message_parameter_s msg = {}; + EXPECT_EQ(msg.msg_type, static_cast('P')); +} + +TEST(ULogMessages, ParameterInt32Layout) +{ + const char *name = "SYS_AUTOSTART"; + int32_t value = 4001; + + ulog_message_parameter_s msg = {}; + uint8_t *buffer = reinterpret_cast(&msg); + + msg.key_len = snprintf(msg.key_value_str, sizeof(msg.key_value_str), + "int32_t %s", name); + size_t msg_size = sizeof(msg) - sizeof(msg.key_value_str) + msg.key_len; + + memcpy(&buffer[msg_size], &value, sizeof(value)); + msg_size += sizeof(value); + + msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN; + + EXPECT_EQ(msg.msg_size, msg.key_len + sizeof(int32_t) + 1); + + const size_t header_size = sizeof(msg) - sizeof(msg.key_value_str); + int32_t read_back = 0; + memcpy(&read_back, &buffer[header_size + msg.key_len], sizeof(int32_t)); + EXPECT_EQ(read_back, 4001); +} + +TEST(ULogMessages, ParameterFloatLayout) +{ + const char *name = "MC_PITCHRATE_P"; + float value = 0.15f; + + ulog_message_parameter_s msg = {}; + uint8_t *buffer = reinterpret_cast(&msg); + + msg.key_len = snprintf(msg.key_value_str, sizeof(msg.key_value_str), + "float %s", name); + size_t msg_size = sizeof(msg) - sizeof(msg.key_value_str) + msg.key_len; + + memcpy(&buffer[msg_size], &value, sizeof(value)); + msg_size += sizeof(value); + + msg.msg_size = msg_size - ULOG_MSG_HEADER_LEN; + + const size_t header_size = sizeof(msg) - sizeof(msg.key_value_str); + float read_back = 0.f; + memcpy(&read_back, &buffer[header_size + msg.key_len], sizeof(float)); + EXPECT_FLOAT_EQ(read_back, 0.15f); +} + +// ---------------------------------------------------------------------------- +// Default Parameter ('Q') +// ---------------------------------------------------------------------------- + +TEST(ULogMessages, ParameterDefaultSize) +{ + // header(3) + default_types(1) + key_len(1) + key_value_str(255) = 260 + EXPECT_EQ(sizeof(ulog_message_parameter_default_s), ULOG_MSG_HEADER_LEN + 1u + 1u + 255u); +} + +TEST(ULogMessages, ParameterDefaultTypeCode) +{ + ulog_message_parameter_default_s msg = {}; + EXPECT_EQ(msg.msg_type, static_cast('Q')); +} + +TEST(ULogMessages, ParameterDefaultTypeBits) +{ + EXPECT_EQ(static_cast(ulog_parameter_default_type_t::system), 1 << 0); + EXPECT_EQ(static_cast(ulog_parameter_default_type_t::current_setup), 1 << 1); + + auto combined = ulog_parameter_default_type_t::system | ulog_parameter_default_type_t::current_setup; + EXPECT_EQ(static_cast(combined), 0x03); +} + +TEST(ULogMessages, ParameterDefaultFieldOffsets) +{ + ulog_message_parameter_default_s msg = {}; + uint8_t *base = reinterpret_cast(&msg); + + EXPECT_EQ(reinterpret_cast(&msg.default_types) - base, ULOG_MSG_HEADER_LEN); + EXPECT_EQ(reinterpret_cast(&msg.key_len) - base, ULOG_MSG_HEADER_LEN + 1); + EXPECT_EQ(reinterpret_cast(&msg.key_value_str) - base, ULOG_MSG_HEADER_LEN + 2); +} + +// ---------------------------------------------------------------------------- +// Subscription ('A') +// ---------------------------------------------------------------------------- + +TEST(ULogMessages, AddLoggedSize) +{ + // header(3) + multi_id(1) + msg_id(2) + message_name(255) = 261 + EXPECT_EQ(sizeof(ulog_message_add_logged_s), ULOG_MSG_HEADER_LEN + 1u + 2u + 255u); +} + +TEST(ULogMessages, AddLoggedTypeCode) +{ + ulog_message_add_logged_s msg = {}; + EXPECT_EQ(msg.msg_type, static_cast('A')); +} + +TEST(ULogMessages, AddLoggedFieldOffsets) +{ + ulog_message_add_logged_s msg = {}; + uint8_t *base = reinterpret_cast(&msg); + + EXPECT_EQ(reinterpret_cast(&msg.multi_id) - base, ULOG_MSG_HEADER_LEN); + EXPECT_EQ(reinterpret_cast(&msg.msg_id) - base, ULOG_MSG_HEADER_LEN + 1); + EXPECT_EQ(reinterpret_cast(&msg.message_name) - base, ULOG_MSG_HEADER_LEN + 3); +} + +TEST(ULogMessages, AddLoggedSerialization) +{ + ulog_message_add_logged_s msg = {}; + msg.multi_id = 0; + msg.msg_id = 7; + const char *topic = "sensor_accel"; + size_t len = strlen(topic); + + strncpy(msg.message_name, topic, sizeof(msg.message_name)); + msg.msg_size = sizeof(msg.multi_id) + sizeof(msg.msg_id) + len; + + EXPECT_EQ(msg.multi_id, 0); + EXPECT_EQ(msg.msg_id, 7); + EXPECT_EQ(memcmp(msg.message_name, "sensor_accel", len), 0); +} + +// ---------------------------------------------------------------------------- +// Unsubscription ('R') +// ---------------------------------------------------------------------------- + +TEST(ULogMessages, RemoveLoggedSize) +{ + // header(3) + msg_id(2) = 5 + EXPECT_EQ(sizeof(ulog_message_remove_logged_s), ULOG_MSG_HEADER_LEN + 2u); +} + +TEST(ULogMessages, RemoveLoggedTypeCode) +{ + ulog_message_remove_logged_s msg = {}; + EXPECT_EQ(msg.msg_type, static_cast('R')); +} + +TEST(ULogMessages, RemoveLoggedSerialization) +{ + ulog_message_remove_logged_s msg = {}; + msg.msg_id = 42; + msg.msg_size = sizeof(msg.msg_id); + + EXPECT_EQ(msg.msg_id, 42); + EXPECT_EQ(msg.msg_size, 2); +} + +// ---------------------------------------------------------------------------- +// Logged Data ('D') +// ---------------------------------------------------------------------------- + +TEST(ULogMessages, DataSize) +{ + // header(3) + msg_id(2) = 5 (variable-length payload follows) + EXPECT_EQ(sizeof(ulog_message_data_s), ULOG_MSG_HEADER_LEN + 2u); +} + +TEST(ULogMessages, DataTypeCode) +{ + ulog_message_data_s msg = {}; + EXPECT_EQ(msg.msg_type, static_cast('D')); +} + +TEST(ULogMessages, DataFieldOffset) +{ + ulog_message_data_s msg = {}; + uint8_t *base = reinterpret_cast(&msg); + + EXPECT_EQ(reinterpret_cast(&msg.msg_id) - base, ULOG_MSG_HEADER_LEN); +} + +// ---------------------------------------------------------------------------- +// Logging ('L') +// ---------------------------------------------------------------------------- + +TEST(ULogMessages, LoggingSize) +{ + // header(3) + log_level(1) + timestamp(8) + message(128) = 140 + EXPECT_EQ(sizeof(ulog_message_logging_s), ULOG_MSG_HEADER_LEN + 1u + 8u + 128u); +} + +TEST(ULogMessages, LoggingTypeCode) +{ + ulog_message_logging_s msg = {}; + EXPECT_EQ(msg.msg_type, static_cast('L')); +} + +TEST(ULogMessages, LoggingFieldOffsets) +{ + ulog_message_logging_s msg = {}; + uint8_t *base = reinterpret_cast(&msg); + + EXPECT_EQ(reinterpret_cast(&msg.log_level) - base, ULOG_MSG_HEADER_LEN); + EXPECT_EQ(reinterpret_cast(&msg.timestamp) - base, ULOG_MSG_HEADER_LEN + 1); + EXPECT_EQ(reinterpret_cast(&msg.message) - base, ULOG_MSG_HEADER_LEN + 9); +} + +TEST(ULogMessages, LoggingSerialization) +{ + ulog_message_logging_s msg = {}; + msg.log_level = 6; + msg.timestamp = 5000000ULL; + const char *text = "test message"; + size_t len = strlen(text); + + strncpy(msg.message, text, sizeof(msg.message)); + msg.msg_size = sizeof(msg.log_level) + sizeof(msg.timestamp) + len; + + EXPECT_EQ(msg.log_level, 6); + EXPECT_EQ(msg.timestamp, 5000000ULL); + EXPECT_EQ(memcmp(msg.message, "test message", len), 0); +} + +// ---------------------------------------------------------------------------- +// Logging Tagged ('C') +// ---------------------------------------------------------------------------- + +TEST(ULogMessages, LoggingTaggedSize) +{ + // header(3) + log_level(1) + tag(2) + timestamp(8) + message(128) = 142 + EXPECT_EQ(sizeof(ulog_message_logging_tagged_s), ULOG_MSG_HEADER_LEN + 1u + 2u + 8u + 128u); +} + +TEST(ULogMessages, LoggingTaggedTypeCode) +{ + ulog_message_logging_tagged_s msg = {}; + EXPECT_EQ(msg.msg_type, static_cast('C')); +} + +TEST(ULogMessages, LoggingTaggedFieldOffsets) +{ + ulog_message_logging_tagged_s msg = {}; + uint8_t *base = reinterpret_cast(&msg); + + EXPECT_EQ(reinterpret_cast(&msg.log_level) - base, ULOG_MSG_HEADER_LEN); + EXPECT_EQ(reinterpret_cast(&msg.tag) - base, ULOG_MSG_HEADER_LEN + 1); + EXPECT_EQ(reinterpret_cast(&msg.timestamp) - base, ULOG_MSG_HEADER_LEN + 3); + EXPECT_EQ(reinterpret_cast(&msg.message) - base, ULOG_MSG_HEADER_LEN + 11); +} + +// ---------------------------------------------------------------------------- +// Sync ('S') +// ---------------------------------------------------------------------------- + +TEST(ULogMessages, SyncSize) +{ + // header(3) + sync_magic(8) = 11 + EXPECT_EQ(sizeof(ulog_message_sync_s), ULOG_MSG_HEADER_LEN + 8u); +} + +TEST(ULogMessages, SyncTypeCode) +{ + ulog_message_sync_s msg = {}; + EXPECT_EQ(msg.msg_type, static_cast('S')); +} + +TEST(ULogMessages, SyncMagicBytes) +{ + ulog_message_sync_s msg = {}; + const uint8_t expected_magic[] = {0x2F, 0x73, 0x13, 0x20, 0x25, 0x0C, 0xBB, 0x12}; + + memcpy(msg.sync_magic, expected_magic, sizeof(expected_magic)); + msg.msg_size = sizeof(msg.sync_magic); + + EXPECT_EQ(memcmp(msg.sync_magic, expected_magic, 8), 0); + EXPECT_EQ(msg.msg_size, 8); +} + +// ---------------------------------------------------------------------------- +// Dropout ('O') +// ---------------------------------------------------------------------------- + +TEST(ULogMessages, DropoutSize) +{ + // header(3) + duration(2) = 5 + EXPECT_EQ(sizeof(ulog_message_dropout_s), ULOG_MSG_HEADER_LEN + 2u); +} + +TEST(ULogMessages, DropoutTypeCode) +{ + ulog_message_dropout_s msg = {}; + EXPECT_EQ(msg.msg_type, static_cast('O')); +} + +TEST(ULogMessages, DropoutDefaultMsgSize) +{ + ulog_message_dropout_s msg = {}; + EXPECT_EQ(msg.msg_size, sizeof(uint16_t)); +} + +TEST(ULogMessages, DropoutSerialization) +{ + ulog_message_dropout_s msg = {}; + msg.duration = 150; + + EXPECT_EQ(msg.duration, 150); + EXPECT_EQ(msg.msg_size, sizeof(uint16_t)); +} + +// ---------------------------------------------------------------------------- +// ULogMessageType enum values +// ---------------------------------------------------------------------------- + +TEST(ULogMessages, TypeEnumValues) +{ + EXPECT_EQ(static_cast(ULogMessageType::FORMAT), 'F'); + EXPECT_EQ(static_cast(ULogMessageType::DATA), 'D'); + EXPECT_EQ(static_cast(ULogMessageType::INFO), 'I'); + EXPECT_EQ(static_cast(ULogMessageType::INFO_MULTIPLE), 'M'); + EXPECT_EQ(static_cast(ULogMessageType::PARAMETER), 'P'); + EXPECT_EQ(static_cast(ULogMessageType::PARAMETER_DEFAULT), 'Q'); + EXPECT_EQ(static_cast(ULogMessageType::ADD_LOGGED_MSG), 'A'); + EXPECT_EQ(static_cast(ULogMessageType::REMOVE_LOGGED_MSG), 'R'); + EXPECT_EQ(static_cast(ULogMessageType::SYNC), 'S'); + EXPECT_EQ(static_cast(ULogMessageType::DROPOUT), 'O'); + EXPECT_EQ(static_cast(ULogMessageType::LOGGING), 'L'); + EXPECT_EQ(static_cast(ULogMessageType::LOGGING_TAGGED), 'C'); + EXPECT_EQ(static_cast(ULogMessageType::FLAG_BITS), 'B'); +} From 6d8441dc893589071b6ef67cc2bc0254c930b190 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 15:48:41 -0800 Subject: [PATCH 781/812] docker_run.sh: modernize image and clean up stale CI references Update the local Docker convenience script to use the unified px4io/px4-dev image instead of the retired per-toolchain images (px4-dev-clang, px4-dev-simulation-bionic). Usage: ./Tools/docker_run.sh make px4_sitl_default ./Tools/docker_run.sh make tests TESTFILTER=ULogMessages PX4_DOCKER_REPO="px4io/px4-dev:custom" ./Tools/docker_run.sh make px4_fmu-v6x_default Changes: - Default to px4io/px4-dev:v1.17.0-beta1, remove conditional image guessing for clang/tests targets - Remove stale env passthrough (Travis CI, AWS, Codecov, Coveralls) - Keep CCACHE_DIR and sanitizer flags (PX4_ASAN/MSAN/TSAN/UBSAN) - Fix $PWD shadowing by renaming to SCRIPT_DIR - Use "$@" instead of "$1 $2 $3" for proper argument forwarding Signed-off-by: Ramon Roche --- Tools/docker_run.sh | 28 ++++------------------------ 1 file changed, 4 insertions(+), 24 deletions(-) diff --git a/Tools/docker_run.sh b/Tools/docker_run.sh index 34d08d16f1..773c8992eb 100755 --- a/Tools/docker_run.sh +++ b/Tools/docker_run.sh @@ -1,47 +1,27 @@ #! /bin/bash if [ -z ${PX4_DOCKER_REPO+x} ]; then - echo "guessing PX4_DOCKER_REPO based on input"; - if [[ $@ =~ .*clang.* ]] || [[ $@ =~ .*scan-build.* ]]; then - # clang tools - PX4_DOCKER_REPO="px4io/px4-dev-clang:2021-02-04" - elif [[ $@ =~ .*tests* ]]; then - # run all tests with simulation - PX4_DOCKER_REPO="px4io/px4-dev-simulation-bionic:2021-12-11" - fi + PX4_DOCKER_REPO="px4io/px4-dev:v1.17.0-beta1" else echo "PX4_DOCKER_REPO is set to '$PX4_DOCKER_REPO'"; fi -# otherwise default to nuttx -if [ -z ${PX4_DOCKER_REPO+x} ]; then - PX4_DOCKER_REPO="px4io/px4-dev:v1.16.0-rc1-258-g0369abd556" -fi - echo "PX4_DOCKER_REPO: $PX4_DOCKER_REPO"; -PWD=$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd ) -SRC_DIR=$PWD/../ +SCRIPT_DIR=$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd ) +SRC_DIR=${SCRIPT_DIR}/../ CCACHE_DIR=${HOME}/.ccache mkdir -p "${CCACHE_DIR}" docker run -it --rm -w "${SRC_DIR}" \ --user="$(id -u):$(id -g)" \ - --env=AWS_ACCESS_KEY_ID \ - --env=AWS_SECRET_ACCESS_KEY \ - --env=BRANCH_NAME \ --env=CCACHE_DIR="${CCACHE_DIR}" \ - --env=CI \ - --env=CODECOV_TOKEN \ - --env=COVERALLS_REPO_TOKEN \ --env=PX4_ASAN \ --env=PX4_MSAN \ --env=PX4_TSAN \ --env=PX4_UBSAN \ - --env=TRAVIS_BRANCH \ - --env=TRAVIS_BUILD_ID \ --publish 14556:14556/udp \ --volume=${CCACHE_DIR}:${CCACHE_DIR}:rw \ --volume=${SRC_DIR}:${SRC_DIR}:rw \ - ${PX4_DOCKER_REPO} /bin/bash -c "$1 $2 $3" + ${PX4_DOCKER_REPO} /bin/bash -c "$@" From 47b3f5f6f9e00c2392572ad754854503ab05f4cf Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 16:13:15 -0800 Subject: [PATCH 782/812] docker-entrypoint.sh: consolidate startup output into single useful line Replace the two separate echo lines ("Starting" and "(arch)") with a single line showing architecture and UTC timestamp: [docker-entrypoint.sh] aarch64 | 2026-02-09T15:23:45Z Signed-off-by: Ramon Roche --- Tools/setup/docker-entrypoint.sh | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/Tools/setup/docker-entrypoint.sh b/Tools/setup/docker-entrypoint.sh index 6d998eda2d..69101c5833 100755 --- a/Tools/setup/docker-entrypoint.sh +++ b/Tools/setup/docker-entrypoint.sh @@ -4,7 +4,7 @@ GREEN='\033[0;32m' NO_COLOR='\033[0m' # No Color SCRIPTID="${GREEN}[docker-entrypoint.sh]${NO_COLOR}" -echo -e "$SCRIPTID Starting" +echo -e "$SCRIPTID $( uname -m ) | $(date -u +%FT%TZ)" # Start virtual X server in the background # - DISPLAY default is :99, set in dockerfile @@ -22,6 +22,4 @@ if [ -n "${ROS_DISTRO}" ]; then source "/opt/ros/$ROS_DISTRO/setup.bash" fi -echo -e "$SCRIPTID ($( uname -m ))" - exec "$@" From d74007dc87ef243bfe4a70dda61e726bf902eff2 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 16:15:00 -0800 Subject: [PATCH 783/812] clang-tidy: exclude NuttX-only drivers and emscripten from SITL analysis These files depend on platform headers (px4_platform/gpio/mcp.hpp, device::I2C, emscripten/emscripten.h) that are unavailable in the SITL/clang build, causing clang-tidy to report compiler errors: - src/lib/drivers/mcp_common (NuttX GPIO) - src/drivers/gpio (MCP23009, MCP23017) - src/lib/drivers/smbus (I2C bus driver) - src/modules/commander/failsafe/emscripten (emscripten SDK) Signed-off-by: Ramon Roche --- Makefile | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Makefile b/Makefile index e3fd7d26f3..3fed0ae854 100644 --- a/Makefile +++ b/Makefile @@ -497,11 +497,14 @@ px4_sitl_default-clang: # - Test code (allowed looser style) # - Example code (educational, not production) # - Vendored third-party code (e.g., CMSIS_5) +# - NuttX-only drivers that depend on platform headers unavailable in SITL builds +# (MCP GPIO, SMBus/I2C) +# - Emscripten failsafe web build (requires emscripten SDK not present in container) # # To add manual exclusions, append to CLANG_TIDY_EXCLUDE_EXTRA below. # Submodules are automatically excluded - no action needed when adding new ones. CLANG_TIDY_SUBMODULES := $(shell git config --file .gitmodules --get-regexp path | awk '{print $$2}' | tr '\n' '|' | sed 's/|$$//') -CLANG_TIDY_EXCLUDE_EXTRA := src/systemcmds/tests|src/examples|src/modules/gyro_fft/CMSIS_5 +CLANG_TIDY_EXCLUDE_EXTRA := src/systemcmds/tests|src/examples|src/modules/gyro_fft/CMSIS_5|src/lib/drivers/mcp_common|src/drivers/gpio|src/lib/drivers/smbus|src/modules/commander/failsafe/emscripten CLANG_TIDY_EXCLUDE := $(CLANG_TIDY_SUBMODULES)|$(CLANG_TIDY_EXCLUDE_EXTRA) clang-tidy: px4_sitl_default-clang From 3d457528d282697417130fb47e4d1161d1934e80 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 19:12:52 -0800 Subject: [PATCH 784/812] clang-tidy: gate NuttX-only driver libs by platform instead of exclude list The clang-tidy CI target builds against the SITL (px4_sitl_default-clang) compilation database. Three libraries in src/lib/drivers/ were unconditionally added via add_subdirectory(), causing them to appear in compile_commands.json despite requiring NuttX-only headers: - mcp_common: includes px4_platform/gpio/mcp.hpp (NuttX platform GPIO) - smbus: extends device::I2C which resolves to the NuttX I2C driver - smbus_sbs: includes smbus/SMBus.hpp, same I2C dependency chain When clang-tidy analyzed these files it failed on clang-diagnostic-error (fatal: header not found) since the platform headers don't exist in SITL. The previous commit worked around this by adding the paths to CLANG_TIDY_EXCLUDE_EXTRA in the Makefile, but the proper fix is to prevent these libraries from entering the compilation database at all. Gate mcp_common, smbus, and smbus_sbs behind if(PX4_PLATFORM STREQUAL "nuttx") in src/lib/drivers/CMakeLists.txt. This follows the established pattern already used by the device/ library in the same directory, which conditionally includes NuttX-specific sources (CDev.cpp, I2C.cpp, SPI.cpp) while compiling posix stubs for SITL. The other libraries in the directory (accelerometer, gyroscope, led, magnetometer, rangefinder) are pure abstractions over uORB topics and internal utilities with no platform-specific hardware dependencies, so they compile fine on all platforms without any gating. Remove the now-unnecessary mcp_common and smbus paths from CLANG_TIDY_EXCLUDE_EXTRA, keeping only the emscripten failsafe exclusion (requires the emscripten SDK, not a platform build issue). Signed-off-by: Ramon Roche --- Makefile | 5 ++--- src/lib/drivers/CMakeLists.txt | 9 ++++++--- 2 files changed, 8 insertions(+), 6 deletions(-) diff --git a/Makefile b/Makefile index 3fed0ae854..5c4bb6308a 100644 --- a/Makefile +++ b/Makefile @@ -497,14 +497,13 @@ px4_sitl_default-clang: # - Test code (allowed looser style) # - Example code (educational, not production) # - Vendored third-party code (e.g., CMSIS_5) -# - NuttX-only drivers that depend on platform headers unavailable in SITL builds -# (MCP GPIO, SMBus/I2C) +# - NuttX-only drivers excluded at CMake level (mcp_common, smbus); GPIO excluded here # - Emscripten failsafe web build (requires emscripten SDK not present in container) # # To add manual exclusions, append to CLANG_TIDY_EXCLUDE_EXTRA below. # Submodules are automatically excluded - no action needed when adding new ones. CLANG_TIDY_SUBMODULES := $(shell git config --file .gitmodules --get-regexp path | awk '{print $$2}' | tr '\n' '|' | sed 's/|$$//') -CLANG_TIDY_EXCLUDE_EXTRA := src/systemcmds/tests|src/examples|src/modules/gyro_fft/CMSIS_5|src/lib/drivers/mcp_common|src/drivers/gpio|src/lib/drivers/smbus|src/modules/commander/failsafe/emscripten +CLANG_TIDY_EXCLUDE_EXTRA := src/systemcmds/tests|src/examples|src/modules/gyro_fft/CMSIS_5|src/drivers/gpio|src/modules/commander/failsafe/emscripten CLANG_TIDY_EXCLUDE := $(CLANG_TIDY_SUBMODULES)|$(CLANG_TIDY_EXCLUDE_EXTRA) clang-tidy: px4_sitl_default-clang diff --git a/src/lib/drivers/CMakeLists.txt b/src/lib/drivers/CMakeLists.txt index 1511d19332..6ece18c65e 100644 --- a/src/lib/drivers/CMakeLists.txt +++ b/src/lib/drivers/CMakeLists.txt @@ -36,7 +36,10 @@ add_subdirectory(device) add_subdirectory(gyroscope) add_subdirectory(led) add_subdirectory(magnetometer) -add_subdirectory(mcp_common) add_subdirectory(rangefinder) -add_subdirectory(smbus) -add_subdirectory(smbus_sbs) + +if (${PX4_PLATFORM} STREQUAL "nuttx") + add_subdirectory(mcp_common) + add_subdirectory(smbus) + add_subdirectory(smbus_sbs) +endif() From 82850cb14914273b31e80c5d5e2f57bbc41ec184 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 19:28:49 -0800 Subject: [PATCH 785/812] clang-tidy: exclude emscripten Unity build path from analysis MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit The failsafe_test target uses CMake Unity Builds (UNITY_BUILD ON), which merges emscripten.cpp, failsafe.cpp, and framework.cpp into a single generated file at: build/.../failsafe_test.dir/Unity/unity_0_cxx.cxx The run-clang-tidy.py exclude regex operates on compile_commands.json paths, which reference this generated unity file — not the original source path. The previous exclude (src/modules/commander/failsafe/ emscripten) only matched the source path and missed the unity file, causing clang-diagnostic-error: 'emscripten/emscripten.h' not found. Add failsafe_test\.dir to the exclude regex to catch the unity build path in addition to the source path. Signed-off-by: Ramon Roche --- Makefile | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/Makefile b/Makefile index 5c4bb6308a..684f4767be 100644 --- a/Makefile +++ b/Makefile @@ -498,12 +498,13 @@ px4_sitl_default-clang: # - Example code (educational, not production) # - Vendored third-party code (e.g., CMSIS_5) # - NuttX-only drivers excluded at CMake level (mcp_common, smbus); GPIO excluded here -# - Emscripten failsafe web build (requires emscripten SDK not present in container) +# - Emscripten failsafe web build: source path + Unity build path (failsafe_test.dir) +# because CMake Unity Builds merge sources into a generated .cxx under build/ # # To add manual exclusions, append to CLANG_TIDY_EXCLUDE_EXTRA below. # Submodules are automatically excluded - no action needed when adding new ones. CLANG_TIDY_SUBMODULES := $(shell git config --file .gitmodules --get-regexp path | awk '{print $$2}' | tr '\n' '|' | sed 's/|$$//') -CLANG_TIDY_EXCLUDE_EXTRA := src/systemcmds/tests|src/examples|src/modules/gyro_fft/CMSIS_5|src/drivers/gpio|src/modules/commander/failsafe/emscripten +CLANG_TIDY_EXCLUDE_EXTRA := src/systemcmds/tests|src/examples|src/modules/gyro_fft/CMSIS_5|src/drivers/gpio|src/modules/commander/failsafe/emscripten|failsafe_test\.dir CLANG_TIDY_EXCLUDE := $(CLANG_TIDY_SUBMODULES)|$(CLANG_TIDY_EXCLUDE_EXTRA) clang-tidy: px4_sitl_default-clang From be3e1fb2ef4df54025ef90e0c67ea260e176e853 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 9 Feb 2026 19:51:17 -0800 Subject: [PATCH 786/812] fix(build): restore smbus/smbus_sbs for Linux board targets MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit The previous commit (6b8fd11) gated smbus and smbus_sbs behind PX4_PLATFORM=="nuttx" to prevent clang-tidy errors on SITL, but these libraries depend on device::I2C which has a POSIX implementation (posix/I2C.cpp). Linux boards like bluerobotics_navigator (armhf) and emlid_navio2 (aarch64) enable CONFIG_DRIVERS_BATT_SMBUS, which depends on drivers__smbus — causing CMake to fail with "non-existent target". Move smbus and smbus_sbs back to unconditional add_subdirectory() so they are available on all platforms. Keep mcp_common gated behind NuttX since it includes px4_platform/gpio/mcp.hpp (NuttX-only GPIO headers). Re-add src/lib/drivers/smbus to the Makefile clang-tidy exclude list since the SITL compilation database lacks the I2C platform headers needed for analysis. Signed-off-by: Ramon Roche --- Makefile | 5 +++-- src/lib/drivers/CMakeLists.txt | 5 +++-- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/Makefile b/Makefile index 684f4767be..fb97276b52 100644 --- a/Makefile +++ b/Makefile @@ -497,14 +497,15 @@ px4_sitl_default-clang: # - Test code (allowed looser style) # - Example code (educational, not production) # - Vendored third-party code (e.g., CMSIS_5) -# - NuttX-only drivers excluded at CMake level (mcp_common, smbus); GPIO excluded here +# - NuttX-only drivers excluded at CMake level (mcp_common); I2C-dependent libs excluded here (smbus) +# - GPIO excluded here (NuttX platform headers) # - Emscripten failsafe web build: source path + Unity build path (failsafe_test.dir) # because CMake Unity Builds merge sources into a generated .cxx under build/ # # To add manual exclusions, append to CLANG_TIDY_EXCLUDE_EXTRA below. # Submodules are automatically excluded - no action needed when adding new ones. CLANG_TIDY_SUBMODULES := $(shell git config --file .gitmodules --get-regexp path | awk '{print $$2}' | tr '\n' '|' | sed 's/|$$//') -CLANG_TIDY_EXCLUDE_EXTRA := src/systemcmds/tests|src/examples|src/modules/gyro_fft/CMSIS_5|src/drivers/gpio|src/modules/commander/failsafe/emscripten|failsafe_test\.dir +CLANG_TIDY_EXCLUDE_EXTRA := src/systemcmds/tests|src/examples|src/modules/gyro_fft/CMSIS_5|src/lib/drivers/smbus|src/drivers/gpio|src/modules/commander/failsafe/emscripten|failsafe_test\.dir CLANG_TIDY_EXCLUDE := $(CLANG_TIDY_SUBMODULES)|$(CLANG_TIDY_EXCLUDE_EXTRA) clang-tidy: px4_sitl_default-clang diff --git a/src/lib/drivers/CMakeLists.txt b/src/lib/drivers/CMakeLists.txt index 6ece18c65e..051b40ab0c 100644 --- a/src/lib/drivers/CMakeLists.txt +++ b/src/lib/drivers/CMakeLists.txt @@ -38,8 +38,9 @@ add_subdirectory(led) add_subdirectory(magnetometer) add_subdirectory(rangefinder) +add_subdirectory(smbus) +add_subdirectory(smbus_sbs) + if (${PX4_PLATFORM} STREQUAL "nuttx") add_subdirectory(mcp_common) - add_subdirectory(smbus) - add_subdirectory(smbus_sbs) endif() From 84933cfbdf8b8e2a066e1028c272b822b04c11e5 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Fri, 13 Feb 2026 05:28:01 +0000 Subject: [PATCH 787/812] docs: auto-sync metadata [skip ci] Co-Authored-By: PX4 BuildBot --- docs/en/middleware/dds_topics.md | 372 +++++++++++++++---------------- 1 file changed, 186 insertions(+), 186 deletions(-) diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index ba072996fd..1432fe5ed9 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -94,199 +94,199 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages -- [EstimatorBias](../msg_docs/EstimatorBias.md) -- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) -- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) -- [CellularStatus](../msg_docs/CellularStatus.md) -- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) -- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [RcParameterMap](../msg_docs/RcParameterMap.md) -- [HealthReport](../msg_docs/HealthReport.md) -- [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) -- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) -- [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [Airspeed](../msg_docs/Airspeed.md) +- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) +- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) +- [NeuralControl](../msg_docs/NeuralControl.md) +- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) +- [Mission](../msg_docs/Mission.md) - [SensorGyroFft](../msg_docs/SensorGyroFft.md) -- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [UlogStream](../msg_docs/UlogStream.md) +- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) +- [MagWorkerData](../msg_docs/MagWorkerData.md) +- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [Event](../msg_docs/Event.md) +- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [CellularStatus](../msg_docs/CellularStatus.md) +- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [LedControl](../msg_docs/LedControl.md) +- [GeofenceStatus](../msg_docs/GeofenceStatus.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [GpioConfig](../msg_docs/GpioConfig.md) +- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) +- [ButtonEvent](../msg_docs/ButtonEvent.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [GpsInjectData](../msg_docs/GpsInjectData.md) +- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) +- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [VehicleAirData](../msg_docs/VehicleAirData.md) +- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) +- [DebugValue](../msg_docs/DebugValue.md) +- [SensorAirflow](../msg_docs/SensorAirflow.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) +- [HealthReport](../msg_docs/HealthReport.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [LandingGearWheel](../msg_docs/LandingGearWheel.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [Rpm](../msg_docs/Rpm.md) +- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) +- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) +- [QshellReq](../msg_docs/QshellReq.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) +- [RcChannels](../msg_docs/RcChannels.md) +- [GimbalControls](../msg_docs/GimbalControls.md) +- [GpioRequest](../msg_docs/GpioRequest.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) +- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [EstimatorStatus](../msg_docs/EstimatorStatus.md) +- [RadioStatus](../msg_docs/RadioStatus.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) +- [Ping](../msg_docs/Ping.md) +- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) +- [MissionResult](../msg_docs/MissionResult.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) +- [DeviceInformation](../msg_docs/DeviceInformation.md) +- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [PpsCapture](../msg_docs/PpsCapture.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) +- [ActuatorTest](../msg_docs/ActuatorTest.md) +- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) +- [QshellRetval](../msg_docs/QshellRetval.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) +- [CameraStatus](../msg_docs/CameraStatus.md) +- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) +- [EventV0](../msg_docs/EventV0.md) +- [Airspeed](../msg_docs/Airspeed.md) +- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) +- [OrbTest](../msg_docs/OrbTest.md) +- [SatelliteInfo](../msg_docs/SatelliteInfo.md) +- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) +- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) +- [BatteryInfo](../msg_docs/BatteryInfo.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) +- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) +- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [RtlStatus](../msg_docs/RtlStatus.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) +- [AirspeedWind](../msg_docs/AirspeedWind.md) +- [DifferentialPressure](../msg_docs/DifferentialPressure.md) +- [CameraTrigger](../msg_docs/CameraTrigger.md) +- [ActionRequest](../msg_docs/ActionRequest.md) +- [SensorSelection](../msg_docs/SensorSelection.md) +- [EstimatorStates](../msg_docs/EstimatorStates.md) - [GpioIn](../msg_docs/GpioIn.md) - [VehicleImu](../msg_docs/VehicleImu.md) -- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) -- [ButtonEvent](../msg_docs/ButtonEvent.md) -- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [AirspeedWind](../msg_docs/AirspeedWind.md) -- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) -- [EstimatorStatus](../msg_docs/EstimatorStatus.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [RtlStatus](../msg_docs/RtlStatus.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) -- [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [Event](../msg_docs/Event.md) -- [Px4ioStatus](../msg_docs/Px4ioStatus.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [NeuralControl](../msg_docs/NeuralControl.md) -- [RadioStatus](../msg_docs/RadioStatus.md) -- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) -- [PositionSetpoint](../msg_docs/PositionSetpoint.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) -- [RaptorStatus](../msg_docs/RaptorStatus.md) -- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) -- [PowerButtonState](../msg_docs/PowerButtonState.md) -- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [PpsCapture](../msg_docs/PpsCapture.md) -- [SensorAirflow](../msg_docs/SensorAirflow.md) -- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) -- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) -- [GpsDump](../msg_docs/GpsDump.md) -- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) -- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) -- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [VehicleAirData](../msg_docs/VehicleAirData.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) -- [TuneControl](../msg_docs/TuneControl.md) -- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) -- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [GpioConfig](../msg_docs/GpioConfig.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) -- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) -- [UlogStream](../msg_docs/UlogStream.md) -- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) -- [CameraStatus](../msg_docs/CameraStatus.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [CameraTrigger](../msg_docs/CameraTrigger.md) -- [IrlockReport](../msg_docs/IrlockReport.md) -- [SensorBaro](../msg_docs/SensorBaro.md) -- [SensorGyro](../msg_docs/SensorGyro.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) -- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [Ping](../msg_docs/Ping.md) -- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [SensorsStatus](../msg_docs/SensorsStatus.md) -- [SatelliteInfo](../msg_docs/SatelliteInfo.md) -- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) -- [ParameterUpdate](../msg_docs/ParameterUpdate.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [GimbalControls](../msg_docs/GimbalControls.md) -- [EscReport](../msg_docs/EscReport.md) -- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [DeviceInformation](../msg_docs/DeviceInformation.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) -- [SensorTemp](../msg_docs/SensorTemp.md) -- [GpioOut](../msg_docs/GpioOut.md) -- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [EventV0](../msg_docs/EventV0.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) -- [Cpuload](../msg_docs/Cpuload.md) -- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) -- [Gripper](../msg_docs/Gripper.md) -- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) -- [QshellRetval](../msg_docs/QshellRetval.md) -- [EscStatus](../msg_docs/EscStatus.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) - [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) -- [EstimatorStates](../msg_docs/EstimatorStates.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) -- [MissionResult](../msg_docs/MissionResult.md) -- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) -- [FollowTarget](../msg_docs/FollowTarget.md) -- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) -- [OrbTestLarge](../msg_docs/OrbTestLarge.md) -- [DebugValue](../msg_docs/DebugValue.md) -- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) -- [ActionRequest](../msg_docs/ActionRequest.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) -- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) -- [UlogStreamAck](../msg_docs/UlogStreamAck.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) -- [DebugArray](../msg_docs/DebugArray.md) -- [MagWorkerData](../msg_docs/MagWorkerData.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) -- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) -- [SystemPower](../msg_docs/SystemPower.md) -- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) -- [BatteryInfo](../msg_docs/BatteryInfo.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) -- [InputRc](../msg_docs/InputRc.md) -- [RcChannels](../msg_docs/RcChannels.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) -- [GainCompression](../msg_docs/GainCompression.md) -- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) -- [ActuatorArmed](../msg_docs/ActuatorArmed.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [Mission](../msg_docs/Mission.md) -- [LandingGearWheel](../msg_docs/LandingGearWheel.md) -- [GpsInjectData](../msg_docs/GpsInjectData.md) -- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) -- [GeofenceStatus](../msg_docs/GeofenceStatus.md) +- [SensorUwb](../msg_docs/SensorUwb.md) +- [GpioOut](../msg_docs/GpioOut.md) - [SensorMag](../msg_docs/SensorMag.md) -- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [MountOrientation](../msg_docs/MountOrientation.md) -- [LogMessage](../msg_docs/LogMessage.md) -- [OrbTestMedium](../msg_docs/OrbTestMedium.md) -- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) -- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) -- [AdcReport](../msg_docs/AdcReport.md) -- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [SensorSelection](../msg_docs/SensorSelection.md) -- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) - [RoverRateStatus](../msg_docs/RoverRateStatus.md) -- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [RcParameterMap](../msg_docs/RcParameterMap.md) +- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) +- [Gripper](../msg_docs/Gripper.md) +- [LandingTargetPose](../msg_docs/LandingTargetPose.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [AdcReport](../msg_docs/AdcReport.md) +- [FollowTarget](../msg_docs/FollowTarget.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [InputRc](../msg_docs/InputRc.md) +- [SensorAccel](../msg_docs/SensorAccel.md) +- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) +- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) +- [EscReport](../msg_docs/EscReport.md) +- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) +- [PowerButtonState](../msg_docs/PowerButtonState.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [PwmInput](../msg_docs/PwmInput.md) +- [SensorsStatus](../msg_docs/SensorsStatus.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [IrlockReport](../msg_docs/IrlockReport.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) +- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [SystemPower](../msg_docs/SystemPower.md) +- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [SensorHygrometer](../msg_docs/SensorHygrometer.md) +- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [SensorGyro](../msg_docs/SensorGyro.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) +- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [OrbTestMedium](../msg_docs/OrbTestMedium.md) +- [SensorBaro](../msg_docs/SensorBaro.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) - [Vtx](../msg_docs/Vtx.md) - [SensorCorrection](../msg_docs/SensorCorrection.md) -- [SensorAccel](../msg_docs/SensorAccel.md) -- [RaptorInput](../msg_docs/RaptorInput.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) -- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) -- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [LandingTargetPose](../msg_docs/LandingTargetPose.md) -- [GpioRequest](../msg_docs/GpioRequest.md) -- [Rpm](../msg_docs/Rpm.md) -- [SensorUwb](../msg_docs/SensorUwb.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [PwmInput](../msg_docs/PwmInput.md) -- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) -- [VehicleRoi](../msg_docs/VehicleRoi.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) -- [QshellReq](../msg_docs/QshellReq.md) -- [TecsStatus](../msg_docs/TecsStatus.md) -- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) -- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) - [GeneratorStatus](../msg_docs/GeneratorStatus.md) -- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) -- [ActuatorTest](../msg_docs/ActuatorTest.md) -- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [LedControl](../msg_docs/LedControl.md) +- [PositionSetpoint](../msg_docs/PositionSetpoint.md) +- [GpsDump](../msg_docs/GpsDump.md) +- [OrbTestLarge](../msg_docs/OrbTestLarge.md) +- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [FuelTankStatus](../msg_docs/FuelTankStatus.md) +- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) +- [CameraCapture](../msg_docs/CameraCapture.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [GainCompression](../msg_docs/GainCompression.md) +- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) +- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) +- [LogMessage](../msg_docs/LogMessage.md) +- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) +- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) +- [Cpuload](../msg_docs/Cpuload.md) +- [VehicleRoi](../msg_docs/VehicleRoi.md) +- [ActuatorArmed](../msg_docs/ActuatorArmed.md) ::: From f38aba3c5be9812b5d232cb75f9c6c27d7131727 Mon Sep 17 00:00:00 2001 From: cuav-chen2 Date: Fri, 13 Feb 2026 09:09:35 +0800 Subject: [PATCH 788/812] cuav_fmu-v6x: Adjust the startup sequence of the sensors --- boards/cuav/fmu-v6x/init/rc.board_sensors | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/boards/cuav/fmu-v6x/init/rc.board_sensors b/boards/cuav/fmu-v6x/init/rc.board_sensors index a50c6d004c..5b6e2dd8f8 100644 --- a/boards/cuav/fmu-v6x/init/rc.board_sensors +++ b/boards/cuav/fmu-v6x/init/rc.board_sensors @@ -66,15 +66,15 @@ then fi fi +iim42652 -R 6 -s -C 32768 start bmi088 -A -R 4 -s start bmi088 -G -R 4 -s start -iim42652 -R 6 -s -C 32768 start icm45686 -R 2 -s start rm3100 -I -b 4 start -icp201xx -I -a 0x64 start bmp581 -b 2 -X -a 0x47 start +icp201xx -I -a 0x64 start # External compass on GPS1/I2C1 (the 3rd external bus): standard Holybro Pixhawk 4 or CUAV V5 GPS/compass puck (with lights, safety button, and buzzer) ist8310 -X -b 1 -R 10 start From 14cbcee49f8562a0982bb77185ea74e59c5183a0 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Fri, 13 Feb 2026 10:30:06 +0100 Subject: [PATCH 789/812] CI: replace all usage of addnab/docker-run-action It's unmaintained and the docker version it uses is not supported anymore. --- .github/workflows/checks.yml | 17 +++--- .../ekf_functional_change_indicator.yml | 28 ++++----- .../workflows/ekf_update_change_indicator.yml | 61 +++++++++++-------- .github/workflows/mavros_mission_tests.yml | 34 ++++++----- .github/workflows/mavros_offboard_tests.yml | 35 ++++++----- .github/workflows/nuttx_env_config.yml | 29 ++++----- 6 files changed, 107 insertions(+), 97 deletions(-) diff --git a/.github/workflows/checks.yml b/.github/workflows/checks.yml index 66821d5e17..e43feee8b3 100644 --- a/.github/workflows/checks.yml +++ b/.github/workflows/checks.yml @@ -19,6 +19,10 @@ concurrency: jobs: build: runs-on: ubuntu-latest + + container: + image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556 + strategy: fail-fast: false matrix: @@ -35,20 +39,17 @@ jobs: "px4_sitl_allyes", "module_documentation", ] + steps: - uses: actions/checkout@v4 with: fetch-depth: 0 - name: Building [${{ matrix.check }}] - uses: addnab/docker-run-action@v3 - with: - image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556 - options: -v ${{ github.workspace }}:/workspace - run: | - cd /workspace - git config --global --add safe.directory /workspace - make ${{ matrix.check }} + run: | + cd "$GITHUB_WORKSPACE" + git config --global --add safe.directory "$GITHUB_WORKSPACE" + make ${{ matrix.check }} - name: Uploading Coverage to Codecov.io if: contains(matrix.check, 'coverage') diff --git a/.github/workflows/ekf_functional_change_indicator.yml b/.github/workflows/ekf_functional_change_indicator.yml index d84572386e..11c1970680 100644 --- a/.github/workflows/ekf_functional_change_indicator.yml +++ b/.github/workflows/ekf_functional_change_indicator.yml @@ -15,21 +15,21 @@ concurrency: jobs: unit_tests: runs-on: ubuntu-latest - steps: - - uses: actions/checkout@v4 - with: - fetch-depth: 0 - - name: main test - uses: addnab/docker-run-action@v3 - with: - image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556 - options: -v ${{ github.workspace }}:/workspace + container: + image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556 + + steps: + - uses: actions/checkout@v4 + with: + fetch-depth: 0 + + - name: main test run: | - cd /workspace - git config --global --add safe.directory /workspace + cd "$GITHUB_WORKSPACE" + git config --global --add safe.directory "$GITHUB_WORKSPACE" make tests TESTFILTER=EKF - - name: Check if there is a functional change - run: git diff --exit-code - working-directory: src/modules/ekf2/test/change_indication + - name: Check if there is a functional change + run: git diff --exit-code + working-directory: src/modules/ekf2/test/change_indication diff --git a/.github/workflows/ekf_update_change_indicator.yml b/.github/workflows/ekf_update_change_indicator.yml index 991dfd397b..6f6e1dde55 100644 --- a/.github/workflows/ekf_update_change_indicator.yml +++ b/.github/workflows/ekf_update_change_indicator.yml @@ -8,40 +8,47 @@ on: jobs: unit_tests: runs-on: ubuntu-latest + + container: + image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556 + env: GIT_COMMITTER_EMAIL: bot@px4.io GIT_COMMITTER_NAME: PX4BuildBot - steps: - - uses: actions/checkout@v4 - with: - fetch-depth: 0 - - name: main test - uses: addnab/docker-run-action@v3 - with: - image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556 - options: -v ${{ github.workspace }}:/workspace + steps: + - uses: actions/checkout@v4 + with: + fetch-depth: 0 + + - name: main test run: | - cd /workspace - git config --global --add safe.directory /workspace + cd "$GITHUB_WORKSPACE" + git config --global --add safe.directory "$GITHUB_WORKSPACE" make tests TESTFILTER=EKF - - name: Check if there exists diff and save result in variable - id: diff-check - run: echo "CHANGE_INDICATED=$(git diff --exit-code --output=/dev/null || echo $?)" >> $GITHUB_OUTPUT - working-directory: src/modules/ekf2/test/change_indication + - name: Check if there exists diff and save result in variable + id: diff-check + working-directory: src/modules/ekf2/test/change_indication + run: | + if git diff --quiet; then + echo "CHANGE_INDICATED=false" >> $GITHUB_OUTPUT + else + echo "CHANGE_INDICATED=true" >> $GITHUB_OUTPUT + fi - - name: auto-commit any changes to change indication - uses: stefanzweifel/git-auto-commit-action@v4 - with: - file_pattern: 'src/modules/ekf2/test/change_indication/*.csv' - commit_user_name: ${GIT_COMMITTER_NAME} - commit_user_email: ${GIT_COMMITTER_EMAIL} - commit_message: | - '[AUTO COMMIT] update change indication' + - name: auto-commit any changes to change indication + if: steps.diff-check.outputs.CHANGE_INDICATED == 'true' + uses: stefanzweifel/git-auto-commit-action@v4 + with: + file_pattern: 'src/modules/ekf2/test/change_indication/*.csv' + commit_user_name: ${{ env.GIT_COMMITTER_NAME }} + commit_user_email: ${{ env.GIT_COMMITTER_EMAIL }} + commit_message: | + [AUTO COMMIT] update change indication - See .github/workflopws/ekf_update_change_indicator.yml for more details + See .github/workflows/ekf_update_change_indicator.yml for more details - - name: if there is a functional change, fail check - if: ${{ steps.diff-check.outputs.CHANGE_INDICATED }} - run: exit 1 + - name: if there is a functional change, fail check + if: steps.diff-check.outputs.CHANGE_INDICATED == 'true' + run: exit 1 diff --git a/.github/workflows/mavros_mission_tests.yml b/.github/workflows/mavros_mission_tests.yml index c5d50109b6..0b1a84f7b3 100644 --- a/.github/workflows/mavros_mission_tests.yml +++ b/.github/workflows/mavros_mission_tests.yml @@ -19,25 +19,27 @@ concurrency: jobs: build: runs-on: ubuntu-latest + strategy: fail-fast: false - matrix: - config: - - {vehicle: "iris", mission: "MC_mission_box"} steps: - - uses: actions/checkout@v4 - with: - fetch-depth: 0 + - uses: actions/checkout@v4 + with: + fetch-depth: 0 - - name: Build SITL and Run Tests - uses: addnab/docker-run-action@v3 - with: - image: px4io/px4-dev-ros-melodic:2021-09-08 - options: -v ${{ github.workspace }}:/workspace + - name: Build SITL and Run Tests (inside old ROS container) run: | - cd /workspace - git config --global --add safe.directory /workspace - make px4_sitl_default - make px4_sitl_default sitl_gazebo-classic - ./test/rostest_px4_run.sh mavros_posix_test_mission.test mission:=${{matrix.config.mission}} vehicle:=${{matrix.config.vehicle}} + docker run --rm \ + -v "${GITHUB_WORKSPACE}:/workspace" \ + -w /workspace \ + px4io/px4-dev-ros-melodic:2021-09-08 \ + bash -c ' + git config --global --add safe.directory /workspace + make px4_sitl_default + make px4_sitl_default sitl_gazebo-classic + ./test/rostest_px4_run.sh \ + mavros_posix_test_mission.test \ + mission:=MC_mission_box \ + vehicle:=iris + ' diff --git a/.github/workflows/mavros_offboard_tests.yml b/.github/workflows/mavros_offboard_tests.yml index 2aaf21e95b..dd6b750812 100644 --- a/.github/workflows/mavros_offboard_tests.yml +++ b/.github/workflows/mavros_offboard_tests.yml @@ -19,27 +19,26 @@ concurrency: jobs: build: runs-on: ubuntu-latest - env: - ACTIONS_ALLOW_USE_UNSECURE_NODE_VERSION: true + strategy: fail-fast: false - matrix: - config: - - {test_file: "mavros_posix_tests_offboard_posctl.test", vehicle: "iris"} steps: - - uses: actions/checkout@v4 - with: - fetch-depth: 0 + - uses: actions/checkout@v4 + with: + fetch-depth: 0 - - name: Build PX4 and Run Tests - uses: addnab/docker-run-action@v3 - with: - image: px4io/px4-dev-ros-melodic:2021-09-08 - options: -v ${{ github.workspace }}:/workspace + - name: Build SITL and Run Tests (inside old ROS container) run: | - cd /workspace - git config --global --add safe.directory /workspace - make px4_sitl_default - make px4_sitl_default sitl_gazebo-classic - ./test/rostest_px4_run.sh ${{matrix.config.test_file}} vehicle:=${{matrix.config.vehicle}} + docker run --rm \ + -v "${GITHUB_WORKSPACE}:/workspace" \ + -w /workspace \ + px4io/px4-dev-ros-melodic:2021-09-08 \ + bash -c ' + git config --global --add safe.directory /workspace + make px4_sitl_default + make px4_sitl_default sitl_gazebo-classic + ./test/rostest_px4_run.sh \ + mavros_posix_tests_offboard_posctl.test \ + vehicle:=iris + ' diff --git a/.github/workflows/nuttx_env_config.yml b/.github/workflows/nuttx_env_config.yml index 791f2fbf4c..f05b456bb6 100644 --- a/.github/workflows/nuttx_env_config.yml +++ b/.github/workflows/nuttx_env_config.yml @@ -19,27 +19,28 @@ concurrency: jobs: build: runs-on: ubuntu-latest + + container: + image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556 + strategy: matrix: - config: [ - px4_fmu-v5_default, - ] + config: + - px4_fmu-v5_default steps: - - uses: actions/checkout@v4 - with: - fetch-depth: 0 + - uses: actions/checkout@v4 + with: + fetch-depth: 0 - - name: Build PX4 and Run Test [${{ matrix.config }}] - uses: addnab/docker-run-action@v3 - with: - image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556 - options: -v ${{ github.workspace }}:/workspace + - name: Build PX4 and Run Test [${{ matrix.config }}] run: | - cd /workspace - git config --global --add safe.directory /workspace - export PX4_EXTRA_NUTTX_CONFIG="CONFIG_NSH_LOGIN_PASSWORD=\"test\";CONFIG_NSH_CONSOLE_LOGIN=y" + cd "$GITHUB_WORKSPACE" + git config --global --add safe.directory "$GITHUB_WORKSPACE" + export PX4_EXTRA_NUTTX_CONFIG='CONFIG_NSH_LOGIN_PASSWORD="test";CONFIG_NSH_CONSOLE_LOGIN=y' echo "PX4_EXTRA_NUTTX_CONFIG: $PX4_EXTRA_NUTTX_CONFIG" + make ${{ matrix.config }} nuttx_context + echo "Check that the config option is set" grep CONFIG_NSH_LOGIN_PASSWORD build/${{ matrix.config }}/NuttX/nuttx/.config From b9f4de0b51cae68165b2aa44dc1cb33fd0994ab1 Mon Sep 17 00:00:00 2001 From: Jaeyoung Lim Date: Fri, 13 Feb 2026 05:41:27 -0700 Subject: [PATCH 790/812] Fix TECS throttle integrator runaway (#26472) --- src/lib/tecs/TECS.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/lib/tecs/TECS.cpp b/src/lib/tecs/TECS.cpp index 5ff73eb83c..69d124239d 100644 --- a/src/lib/tecs/TECS.cpp +++ b/src/lib/tecs/TECS.cpp @@ -590,7 +590,9 @@ void TECSControl::_calcThrottleControlUpdate(float dt, const STERateLimit &limit if (_throttle_setpoint >= param.throttle_max) { throttle_integ_input = math::min(0.f, throttle_integ_input); - } else if (_throttle_setpoint <= param.throttle_min) { + } + + if (_throttle_setpoint <= param.throttle_min) { throttle_integ_input = math::max(0.f, throttle_integ_input); } From 79a7ef2869d6fbac9af280b7b4fc129edceb5f19 Mon Sep 17 00:00:00 2001 From: Balduin Date: Fri, 13 Feb 2026 13:42:17 +0100 Subject: [PATCH 791/812] RtlTimeEstimator: Consider minimum ground speed (#26405) * RtlTimeEstimator: Consider minimum ground speed This fixes an issue seen when the wind is faster than the trim airspeed, but not faster than the max airspeed. In that case the RTL time estimator currently assumes that we always fly at trim airspeed and are thus unable to cover ground in the upwind direction. The result is a very large RTL time estimate, resulting in RTL if configured by COM_FLTT_LOW_ACT. By considering the FW_GND_SPD_MIN parameter, we correct this wrong assumption. The RTL remaining time estimate now becomes realistic in this situation. * RtlTimeEstimator: assume min ground speed of 5 if param unavailable --- src/lib/rtl/rtl_time_estimator.cpp | 14 +++++++++++++- src/lib/rtl/rtl_time_estimator.h | 1 + 2 files changed, 14 insertions(+), 1 deletion(-) diff --git a/src/lib/rtl/rtl_time_estimator.cpp b/src/lib/rtl/rtl_time_estimator.cpp index ddc851c5e3..c7cc22bfbb 100644 --- a/src/lib/rtl/rtl_time_estimator.cpp +++ b/src/lib/rtl/rtl_time_estimator.cpp @@ -54,6 +54,7 @@ RtlTimeEstimator::RtlTimeEstimator() : ModuleParams(nullptr) _param_fw_climb_rate = param_find("FW_T_CLMB_R_SP"); _param_fw_sink_rate = param_find("FW_T_SINK_R_SP"); _param_fw_airspeed_trim = param_find("FW_AIRSPD_TRIM"); + _param_fw_gnd_spd_min = param_find("FW_GND_SPD_MIN"); _param_mpc_xy_cruise = param_find("MPC_XY_CRUISE"); _param_rover_cruise_speed = param_find("RO_SPEED_LIM"); }; @@ -142,7 +143,18 @@ float RtlTimeEstimator::getCruiseGroundSpeed(const matrix::Vector2f &direction_n const float ground_speed = sqrtf(cruise_speed * cruise_speed - wind_across_dir * wind_across_dir) + fminf( 0.f, wind_along_dir); - cruise_speed = ground_speed; + // Assume that minimum ground speed is always satisfied. If + // windspeed < cas2tas(FW_AIRSPD_MAX) - FW_GND_SPD_MIN + // the assumption always holds. Otherwise it breaks down when + // flying upwind, and the RTL time estimate is optimistic. + + float fw_gnd_spd_min = 5.0f; + + if (_param_fw_gnd_spd_min != PARAM_INVALID) { + param_get(_param_fw_gnd_spd_min, &fw_gnd_spd_min); + } + + cruise_speed = fmaxf(ground_speed, fw_gnd_spd_min); } return cruise_speed; diff --git a/src/lib/rtl/rtl_time_estimator.h b/src/lib/rtl/rtl_time_estimator.h index 7ca79fba1f..c919f96e3c 100644 --- a/src/lib/rtl/rtl_time_estimator.h +++ b/src/lib/rtl/rtl_time_estimator.h @@ -129,6 +129,7 @@ private: param_t _param_fw_sink_rate{PARAM_INVALID}; /**< FW descend speed parameter */ param_t _param_fw_airspeed_trim{PARAM_INVALID}; /**< FW cruise airspeed parameter */ + param_t _param_fw_gnd_spd_min{PARAM_INVALID}; /**< FW min groundspeed parameter */ param_t _param_mpc_xy_cruise{PARAM_INVALID}; /**< MC horizontal cruise speed parameter */ param_t _param_rover_cruise_speed{PARAM_INVALID}; /**< Rover cruise speed parameter */ From c90811a27788a08e78ac63fa5a05b494e5cf3013 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Fri, 13 Feb 2026 12:49:48 +0000 Subject: [PATCH 792/812] docs: auto-sync metadata [skip ci] Co-Authored-By: PX4 BuildBot --- docs/en/middleware/dds_topics.md | 376 +++++++++++++++---------------- 1 file changed, 188 insertions(+), 188 deletions(-) diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index 1432fe5ed9..1586c38758 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -94,199 +94,199 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages -- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [RaptorStatus](../msg_docs/RaptorStatus.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [NeuralControl](../msg_docs/NeuralControl.md) -- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) -- [Mission](../msg_docs/Mission.md) -- [SensorGyroFft](../msg_docs/SensorGyroFft.md) -- [UlogStream](../msg_docs/UlogStream.md) -- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) -- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) -- [MagWorkerData](../msg_docs/MagWorkerData.md) -- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) -- [Event](../msg_docs/Event.md) -- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) -- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) -- [CellularStatus](../msg_docs/CellularStatus.md) -- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) -- [LedControl](../msg_docs/LedControl.md) -- [GeofenceStatus](../msg_docs/GeofenceStatus.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [GpioConfig](../msg_docs/GpioConfig.md) -- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) -- [ButtonEvent](../msg_docs/ButtonEvent.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [GpsInjectData](../msg_docs/GpsInjectData.md) -- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) -- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) -- [VehicleAirData](../msg_docs/VehicleAirData.md) -- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) -- [DebugValue](../msg_docs/DebugValue.md) -- [SensorAirflow](../msg_docs/SensorAirflow.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [HealthReport](../msg_docs/HealthReport.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) -- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) -- [LandingGearWheel](../msg_docs/LandingGearWheel.md) -- [MountOrientation](../msg_docs/MountOrientation.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [Rpm](../msg_docs/Rpm.md) -- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) -- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [QshellReq](../msg_docs/QshellReq.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [RcChannels](../msg_docs/RcChannels.md) -- [GimbalControls](../msg_docs/GimbalControls.md) -- [GpioRequest](../msg_docs/GpioRequest.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) -- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [UlogStreamAck](../msg_docs/UlogStreamAck.md) -- [EstimatorStatus](../msg_docs/EstimatorStatus.md) -- [RadioStatus](../msg_docs/RadioStatus.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) -- [Ping](../msg_docs/Ping.md) -- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) -- [MissionResult](../msg_docs/MissionResult.md) -- [TecsStatus](../msg_docs/TecsStatus.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [DeviceInformation](../msg_docs/DeviceInformation.md) -- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) -- [PpsCapture](../msg_docs/PpsCapture.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) -- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) -- [ActuatorTest](../msg_docs/ActuatorTest.md) -- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) -- [QshellRetval](../msg_docs/QshellRetval.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [CameraStatus](../msg_docs/CameraStatus.md) -- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) -- [EventV0](../msg_docs/EventV0.md) -- [Airspeed](../msg_docs/Airspeed.md) -- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [SatelliteInfo](../msg_docs/SatelliteInfo.md) -- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) -- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) -- [BatteryInfo](../msg_docs/BatteryInfo.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) -- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) -- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) -- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) -- [RtlStatus](../msg_docs/RtlStatus.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [AirspeedWind](../msg_docs/AirspeedWind.md) -- [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [CameraTrigger](../msg_docs/CameraTrigger.md) -- [ActionRequest](../msg_docs/ActionRequest.md) -- [SensorSelection](../msg_docs/SensorSelection.md) -- [EstimatorStates](../msg_docs/EstimatorStates.md) -- [GpioIn](../msg_docs/GpioIn.md) -- [VehicleImu](../msg_docs/VehicleImu.md) -- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) -- [SensorUwb](../msg_docs/SensorUwb.md) -- [GpioOut](../msg_docs/GpioOut.md) -- [SensorMag](../msg_docs/SensorMag.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) -- [RoverRateStatus](../msg_docs/RoverRateStatus.md) -- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) -- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) -- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) -- [RcParameterMap](../msg_docs/RcParameterMap.md) -- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [Gripper](../msg_docs/Gripper.md) -- [LandingTargetPose](../msg_docs/LandingTargetPose.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) -- [AdcReport](../msg_docs/AdcReport.md) -- [FollowTarget](../msg_docs/FollowTarget.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) -- [InputRc](../msg_docs/InputRc.md) -- [SensorAccel](../msg_docs/SensorAccel.md) -- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) -- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) -- [DebugArray](../msg_docs/DebugArray.md) -- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) -- [EscReport](../msg_docs/EscReport.md) -- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [PowerButtonState](../msg_docs/PowerButtonState.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [SensorTemp](../msg_docs/SensorTemp.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) -- [PwmInput](../msg_docs/PwmInput.md) -- [SensorsStatus](../msg_docs/SensorsStatus.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) -- [IrlockReport](../msg_docs/IrlockReport.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) -- [SystemPower](../msg_docs/SystemPower.md) -- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) -- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) -- [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) -- [Px4ioStatus](../msg_docs/Px4ioStatus.md) -- [SensorGyro](../msg_docs/SensorGyro.md) -- [RaptorInput](../msg_docs/RaptorInput.md) -- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) - [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [OrbTestMedium](../msg_docs/OrbTestMedium.md) -- [SensorBaro](../msg_docs/SensorBaro.md) -- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) +- [SensorGyro](../msg_docs/SensorGyro.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) - [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [Vtx](../msg_docs/Vtx.md) -- [SensorCorrection](../msg_docs/SensorCorrection.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [PowerButtonState](../msg_docs/PowerButtonState.md) +- [AirspeedWind](../msg_docs/AirspeedWind.md) +- [GimbalControls](../msg_docs/GimbalControls.md) - [GeneratorStatus](../msg_docs/GeneratorStatus.md) -- [PositionSetpoint](../msg_docs/PositionSetpoint.md) -- [GpsDump](../msg_docs/GpsDump.md) -- [OrbTestLarge](../msg_docs/OrbTestLarge.md) -- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [RcParameterMap](../msg_docs/RcParameterMap.md) - [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) -- [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [EscStatus](../msg_docs/EscStatus.md) +- [SensorCorrection](../msg_docs/SensorCorrection.md) - [GainCompression](../msg_docs/GainCompression.md) -- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) -- [TuneControl](../msg_docs/TuneControl.md) -- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) -- [LogMessage](../msg_docs/LogMessage.md) -- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) +- [PpsCapture](../msg_docs/PpsCapture.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) +- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) +- [Gripper](../msg_docs/Gripper.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [ActionRequest](../msg_docs/ActionRequest.md) +- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) - [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) -- [Cpuload](../msg_docs/Cpuload.md) -- [VehicleRoi](../msg_docs/VehicleRoi.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) +- [GpioRequest](../msg_docs/GpioRequest.md) +- [DeviceInformation](../msg_docs/DeviceInformation.md) +- [GeofenceStatus](../msg_docs/GeofenceStatus.md) - [ActuatorArmed](../msg_docs/ActuatorArmed.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [CellularStatus](../msg_docs/CellularStatus.md) +- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) +- [InputRc](../msg_docs/InputRc.md) +- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) +- [VehicleImu](../msg_docs/VehicleImu.md) +- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) +- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) +- [SatelliteInfo](../msg_docs/SatelliteInfo.md) +- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [DifferentialPressure](../msg_docs/DifferentialPressure.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [Mission](../msg_docs/Mission.md) +- [ButtonEvent](../msg_docs/ButtonEvent.md) +- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) +- [GpioOut](../msg_docs/GpioOut.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) +- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [SensorsStatus](../msg_docs/SensorsStatus.md) +- [FuelTankStatus](../msg_docs/FuelTankStatus.md) +- [Cpuload](../msg_docs/Cpuload.md) +- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) +- [DebugValue](../msg_docs/DebugValue.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [MagWorkerData](../msg_docs/MagWorkerData.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [SystemPower](../msg_docs/SystemPower.md) +- [EscReport](../msg_docs/EscReport.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) +- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) +- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) +- [VehicleAirData](../msg_docs/VehicleAirData.md) +- [Airspeed](../msg_docs/Airspeed.md) +- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) +- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [CameraStatus](../msg_docs/CameraStatus.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [LogMessage](../msg_docs/LogMessage.md) +- [SensorMag](../msg_docs/SensorMag.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [SensorAirflow](../msg_docs/SensorAirflow.md) +- [AdcReport](../msg_docs/AdcReport.md) +- [Vtx](../msg_docs/Vtx.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) +- [MissionResult](../msg_docs/MissionResult.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) +- [PwmInput](../msg_docs/PwmInput.md) +- [OrbTestMedium](../msg_docs/OrbTestMedium.md) +- [OrbTestLarge](../msg_docs/OrbTestLarge.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) +- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [QshellReq](../msg_docs/QshellReq.md) +- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) +- [HealthReport](../msg_docs/HealthReport.md) +- [LandingGearWheel](../msg_docs/LandingGearWheel.md) +- [SensorBaro](../msg_docs/SensorBaro.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [Event](../msg_docs/Event.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [RadioStatus](../msg_docs/RadioStatus.md) +- [SensorHygrometer](../msg_docs/SensorHygrometer.md) +- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) +- [LandingTargetPose](../msg_docs/LandingTargetPose.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [PositionSetpoint](../msg_docs/PositionSetpoint.md) +- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) +- [CameraTrigger](../msg_docs/CameraTrigger.md) +- [IrlockReport](../msg_docs/IrlockReport.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [LedControl](../msg_docs/LedControl.md) +- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) +- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) +- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) +- [GpsInjectData](../msg_docs/GpsInjectData.md) +- [RoverRateStatus](../msg_docs/RoverRateStatus.md) +- [FollowTarget](../msg_docs/FollowTarget.md) +- [OrbTest](../msg_docs/OrbTest.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [Rpm](../msg_docs/Rpm.md) +- [GpioIn](../msg_docs/GpioIn.md) +- [RcChannels](../msg_docs/RcChannels.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [BatteryInfo](../msg_docs/BatteryInfo.md) +- [VehicleRoi](../msg_docs/VehicleRoi.md) +- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) +- [UlogStream](../msg_docs/UlogStream.md) +- [Ping](../msg_docs/Ping.md) +- [EstimatorStates](../msg_docs/EstimatorStates.md) +- [NeuralControl](../msg_docs/NeuralControl.md) +- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [GpioConfig](../msg_docs/GpioConfig.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) +- [RtlStatus](../msg_docs/RtlStatus.md) +- [CameraCapture](../msg_docs/CameraCapture.md) +- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) +- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) +- [QshellRetval](../msg_docs/QshellRetval.md) +- [EstimatorStatus](../msg_docs/EstimatorStatus.md) +- [SensorAccel](../msg_docs/SensorAccel.md) +- [GpsDump](../msg_docs/GpsDump.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) +- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) +- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [SensorSelection](../msg_docs/SensorSelection.md) +- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) +- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) +- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [EventV0](../msg_docs/EventV0.md) +- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [SensorUwb](../msg_docs/SensorUwb.md) +- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [ActuatorTest](../msg_docs/ActuatorTest.md) +- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) ::: From 302d0601bfd64b1acffcee3319df8512a0dabef7 Mon Sep 17 00:00:00 2001 From: nlsxp Date: Fri, 13 Feb 2026 14:06:47 +0100 Subject: [PATCH 793/812] Smoothen external flight mode GotoControl to Mission transitions (#26254) --- .../tasks/Auto/FlightTaskAuto.cpp | 4 ++-- .../tasks/FlightTask/FlightTask.cpp | 11 +++++++++++ .../tasks/FlightTask/FlightTask.hpp | 1 + .../mc_pos_control/GotoControl/GotoControl.cpp | 14 +++++++------- .../mc_pos_control/GotoControl/GotoControl.hpp | 13 +++++++++---- .../mc_pos_control/MulticopterPositionControl.cpp | 2 +- 6 files changed, 31 insertions(+), 14 deletions(-) diff --git a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp index e2ebb11bd0..ec999cdc0f 100644 --- a/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp +++ b/src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp @@ -61,8 +61,8 @@ bool FlightTaskAuto::activate(const trajectory_setpoint_s &last_setpoint) // If the velocity setpoint is unknown, set to the current velocity if (!PX4_ISFINITE(vel_prev(i))) { vel_prev(i) = _velocity(i); } - // No acceleration estimate available, set to zero if the setpoint is NAN - if (!PX4_ISFINITE(accel_prev(i))) { accel_prev(i) = 0.f; } + // If accel setpoint unknown, set to the current accel + if (!PX4_ISFINITE(accel_prev(i))) { accel_prev(i) = _acceleration(i); } } _position_smoothing.reset(accel_prev, vel_prev, pos_prev); diff --git a/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.cpp b/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.cpp index fa2943f147..58d0253012 100644 --- a/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.cpp +++ b/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.cpp @@ -153,6 +153,17 @@ void FlightTask::_evaluateVehicleLocalPosition() _velocity(2) = _sub_vehicle_local_position.get().vz; } + // acceleration is calculated as the velocity derivative in EKF2, + // if velocity is available acceleration values are available + if (_sub_vehicle_local_position.get().v_xy_valid) { + _acceleration(0) = _sub_vehicle_local_position.get().ax; + _acceleration(1) = _sub_vehicle_local_position.get().ay; + } + + if (_sub_vehicle_local_position.get().v_z_valid) { + _acceleration(2) = _sub_vehicle_local_position.get().az; + } + // distance to bottom if (_sub_vehicle_local_position.get().dist_bottom_valid && PX4_ISFINITE(_sub_vehicle_local_position.get().dist_bottom)) { diff --git a/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.hpp b/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.hpp index 06327d8ca8..080c594d1a 100644 --- a/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.hpp +++ b/src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.hpp @@ -201,6 +201,7 @@ protected: /* Current vehicle state */ matrix::Vector3f _position; /**< current vehicle position */ matrix::Vector3f _velocity; /**< current vehicle velocity */ + matrix::Vector3f _acceleration; /**< current vehicle acceleration (derivative of velocity) */ float _yaw{}; /**< current vehicle yaw heading */ float _unaided_yaw{}; diff --git a/src/modules/mc_pos_control/GotoControl/GotoControl.cpp b/src/modules/mc_pos_control/GotoControl/GotoControl.cpp index a266a5ec1b..663c3a969c 100644 --- a/src/modules/mc_pos_control/GotoControl/GotoControl.cpp +++ b/src/modules/mc_pos_control/GotoControl/GotoControl.cpp @@ -42,6 +42,7 @@ #include using namespace time_literals; +using namespace matrix; bool GotoControl::checkForSetpoint(const hrt_abstime &now, const bool enabled) { @@ -64,10 +65,11 @@ bool GotoControl::checkForSetpoint(const hrt_abstime &now, const bool enabled) return need_to_run; } -void GotoControl::update(const float dt, const matrix::Vector3f &position, const float heading) +void GotoControl::update(const float dt, const Vector3f &position, const Vector3f &velocity, const Vector3f &acceleration, + const float heading) { if (!_is_initialized) { - resetPositionSmoother(position); + resetPositionSmoother(position, velocity, acceleration); resetHeadingSmoother(heading); _is_initialized = true; } @@ -87,7 +89,7 @@ void GotoControl::update(const float dt, const matrix::Vector3f &position, const } if (_need_smoother_reset) { - resetPositionSmoother(position); + resetPositionSmoother(position, velocity, acceleration); } setPositionSmootherLimits(_goto_setpoint); @@ -138,7 +140,7 @@ void GotoControl::update(const float dt, const matrix::Vector3f &position, const _vehicle_constraints_pub.publish(vehicle_constraints); } -void GotoControl::resetPositionSmoother(const matrix::Vector3f &position) +void GotoControl::resetPositionSmoother(const Vector3f &position, const Vector3f &velocity, const Vector3f &acceleration) { if (!position.isAllFinite()) { // TODO: error messaging @@ -146,9 +148,7 @@ void GotoControl::resetPositionSmoother(const matrix::Vector3f &position) return; } - const Vector3f initial_acceleration{}; - const Vector3f initial_velocity{}; - _position_smoothing.reset(initial_acceleration, initial_velocity, position); + _position_smoothing.reset(acceleration, velocity, position); _need_smoother_reset = false; } diff --git a/src/modules/mc_pos_control/GotoControl/GotoControl.hpp b/src/modules/mc_pos_control/GotoControl/GotoControl.hpp index f9ff08f9ca..4ae7aa9ec8 100644 --- a/src/modules/mc_pos_control/GotoControl/GotoControl.hpp +++ b/src/modules/mc_pos_control/GotoControl/GotoControl.hpp @@ -64,9 +64,11 @@ public: /** * @brief resets the position smoother at the current position with zero velocity and acceleration. * - * @param position [m] (NED) local vehicle position + * @param position [m] vehicle position state NED local frame + * @param velocity [m/s] vehicle velocity state + * @param acceleration [m/s^2] vehicle acceleration state */ - void resetPositionSmoother(const matrix::Vector3f &position); + void resetPositionSmoother(const matrix::Vector3f &position, const matrix::Vector3f &velocity, const matrix::Vector3f &acceleration); /** * @brief resets the heading smoother at the current heading with zero heading rate and acceleration. @@ -80,12 +82,15 @@ public: * loops to track. * * @param[in] dt [s] time since last control update - * @param[in] position [m] (NED) local vehicle position + * @param[in] position [m] vehicle position state NED local frame + * @param[in] velocity [m/s] vehicle velocity state + * @param[in] acceleration [m/s^2] vehicle acceleration state * @param[in] heading [rad] (from North) vehicle heading * @param[in] goto_setpoint struct containing current go-to setpoints * @param[out] trajectory_setpoint struct containing trajectory (tracking) setpoints */ - void update(const float dt, const matrix::Vector3f &position, const float heading); + void update(const float dt, const matrix::Vector3f &position, const matrix::Vector3f &velocity, const matrix::Vector3f &acceleration, + const float heading); // Setting all parameters from the outside saves 300bytes flash void setParamMpcAccHor(const float param_mpc_acc_hor) { _param_mpc_acc_hor = param_mpc_acc_hor; } diff --git a/src/modules/mc_pos_control/MulticopterPositionControl.cpp b/src/modules/mc_pos_control/MulticopterPositionControl.cpp index 0d6b57c68b..fe5f138050 100644 --- a/src/modules/mc_pos_control/MulticopterPositionControl.cpp +++ b/src/modules/mc_pos_control/MulticopterPositionControl.cpp @@ -433,7 +433,7 @@ void MulticopterPositionControl::Run() && !_trajectory_setpoint_sub.updated(); if (_goto_control.checkForSetpoint(vehicle_local_position.timestamp_sample, goto_setpoint_enable)) { - _goto_control.update(dt, states.position, states.yaw); + _goto_control.update(dt, states.position, states.velocity, states.acceleration, states.yaw); } _trajectory_setpoint_sub.update(&_setpoint); From b08fefa903af40b986f5876b12a6d6cef99e6fbe Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Fri, 13 Feb 2026 13:14:35 +0000 Subject: [PATCH 794/812] docs: auto-sync metadata [skip ci] Co-Authored-By: PX4 BuildBot --- docs/en/middleware/dds_topics.md | 372 +++++++++++++++---------------- 1 file changed, 186 insertions(+), 186 deletions(-) diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index 1586c38758..6e61104195 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -94,199 +94,199 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages -- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) -- [SensorGyro](../msg_docs/SensorGyro.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) -- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) -- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) -- [PowerButtonState](../msg_docs/PowerButtonState.md) -- [AirspeedWind](../msg_docs/AirspeedWind.md) -- [GimbalControls](../msg_docs/GimbalControls.md) -- [GeneratorStatus](../msg_docs/GeneratorStatus.md) -- [Px4ioStatus](../msg_docs/Px4ioStatus.md) -- [RcParameterMap](../msg_docs/RcParameterMap.md) -- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) -- [SensorCorrection](../msg_docs/SensorCorrection.md) -- [GainCompression](../msg_docs/GainCompression.md) -- [PpsCapture](../msg_docs/PpsCapture.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) -- [Gripper](../msg_docs/Gripper.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [ActionRequest](../msg_docs/ActionRequest.md) -- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) -- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) -- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [GpioRequest](../msg_docs/GpioRequest.md) -- [DeviceInformation](../msg_docs/DeviceInformation.md) -- [GeofenceStatus](../msg_docs/GeofenceStatus.md) -- [ActuatorArmed](../msg_docs/ActuatorArmed.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [CellularStatus](../msg_docs/CellularStatus.md) -- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [InputRc](../msg_docs/InputRc.md) -- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [VehicleImu](../msg_docs/VehicleImu.md) -- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) -- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [SatelliteInfo](../msg_docs/SatelliteInfo.md) -- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) -- [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [TecsStatus](../msg_docs/TecsStatus.md) -- [Mission](../msg_docs/Mission.md) -- [ButtonEvent](../msg_docs/ButtonEvent.md) -- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) -- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) -- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) -- [GpioOut](../msg_docs/GpioOut.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) -- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) -- [SensorTemp](../msg_docs/SensorTemp.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) -- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) -- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) -- [EscStatus](../msg_docs/EscStatus.md) -- [RaptorStatus](../msg_docs/RaptorStatus.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) -- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) -- [SensorsStatus](../msg_docs/SensorsStatus.md) -- [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [Cpuload](../msg_docs/Cpuload.md) -- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) -- [DebugValue](../msg_docs/DebugValue.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) -- [MagWorkerData](../msg_docs/MagWorkerData.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [SystemPower](../msg_docs/SystemPower.md) -- [EscReport](../msg_docs/EscReport.md) -- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) -- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) -- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) -- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [VehicleAirData](../msg_docs/VehicleAirData.md) -- [Airspeed](../msg_docs/Airspeed.md) -- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) -- [RaptorInput](../msg_docs/RaptorInput.md) -- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [UlogStreamAck](../msg_docs/UlogStreamAck.md) -- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [CameraStatus](../msg_docs/CameraStatus.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) -- [LogMessage](../msg_docs/LogMessage.md) -- [SensorMag](../msg_docs/SensorMag.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) -- [SensorAirflow](../msg_docs/SensorAirflow.md) -- [AdcReport](../msg_docs/AdcReport.md) -- [Vtx](../msg_docs/Vtx.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [MissionResult](../msg_docs/MissionResult.md) -- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) -- [PwmInput](../msg_docs/PwmInput.md) -- [OrbTestMedium](../msg_docs/OrbTestMedium.md) -- [OrbTestLarge](../msg_docs/OrbTestLarge.md) -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) -- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) - [QshellReq](../msg_docs/QshellReq.md) -- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) -- [HealthReport](../msg_docs/HealthReport.md) -- [LandingGearWheel](../msg_docs/LandingGearWheel.md) -- [SensorBaro](../msg_docs/SensorBaro.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [Event](../msg_docs/Event.md) -- [MountOrientation](../msg_docs/MountOrientation.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) -- [RadioStatus](../msg_docs/RadioStatus.md) -- [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [LandingTargetPose](../msg_docs/LandingTargetPose.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) -- [PositionSetpoint](../msg_docs/PositionSetpoint.md) -- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) -- [DebugArray](../msg_docs/DebugArray.md) -- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) -- [CameraTrigger](../msg_docs/CameraTrigger.md) -- [IrlockReport](../msg_docs/IrlockReport.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [LedControl](../msg_docs/LedControl.md) +- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) - [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) -- [SensorGyroFft](../msg_docs/SensorGyroFft.md) -- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) -- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) -- [GpsInjectData](../msg_docs/GpsInjectData.md) -- [RoverRateStatus](../msg_docs/RoverRateStatus.md) -- [FollowTarget](../msg_docs/FollowTarget.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [TuneControl](../msg_docs/TuneControl.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) -- [Rpm](../msg_docs/Rpm.md) -- [GpioIn](../msg_docs/GpioIn.md) -- [RcChannels](../msg_docs/RcChannels.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) -- [BatteryInfo](../msg_docs/BatteryInfo.md) -- [VehicleRoi](../msg_docs/VehicleRoi.md) -- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) -- [UlogStream](../msg_docs/UlogStream.md) -- [Ping](../msg_docs/Ping.md) -- [EstimatorStates](../msg_docs/EstimatorStates.md) -- [NeuralControl](../msg_docs/NeuralControl.md) -- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) -- [GpioConfig](../msg_docs/GpioConfig.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [RtlStatus](../msg_docs/RtlStatus.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) -- [QshellRetval](../msg_docs/QshellRetval.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [GainCompression](../msg_docs/GainCompression.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) +- [LedControl](../msg_docs/LedControl.md) +- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) +- [SensorHygrometer](../msg_docs/SensorHygrometer.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [CellularStatus](../msg_docs/CellularStatus.md) +- [Mission](../msg_docs/Mission.md) +- [GpioOut](../msg_docs/GpioOut.md) - [EstimatorStatus](../msg_docs/EstimatorStatus.md) -- [SensorAccel](../msg_docs/SensorAccel.md) +- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) +- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) - [GpsDump](../msg_docs/GpsDump.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) -- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) -- [EstimatorBias](../msg_docs/EstimatorBias.md) -- [SensorSelection](../msg_docs/SensorSelection.md) -- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) -- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) +- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) +- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) - [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [SatelliteInfo](../msg_docs/SatelliteInfo.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [IrlockReport](../msg_docs/IrlockReport.md) +- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) +- [EscReport](../msg_docs/EscReport.md) - [EventV0](../msg_docs/EventV0.md) -- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) -- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) +- [Vtx](../msg_docs/Vtx.md) +- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) +- [SensorMag](../msg_docs/SensorMag.md) - [SensorUwb](../msg_docs/SensorUwb.md) -- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) - [ActuatorTest](../msg_docs/ActuatorTest.md) +- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) +- [SensorGyro](../msg_docs/SensorGyro.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) +- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) +- [VehicleAirData](../msg_docs/VehicleAirData.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [Airspeed](../msg_docs/Airspeed.md) +- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) +- [OrbTest](../msg_docs/OrbTest.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) +- [Gripper](../msg_docs/Gripper.md) +- [GpioRequest](../msg_docs/GpioRequest.md) +- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) +- [CameraTrigger](../msg_docs/CameraTrigger.md) +- [ButtonEvent](../msg_docs/ButtonEvent.md) +- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [DifferentialPressure](../msg_docs/DifferentialPressure.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [CameraStatus](../msg_docs/CameraStatus.md) +- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [GeneratorStatus](../msg_docs/GeneratorStatus.md) +- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) +- [CameraCapture](../msg_docs/CameraCapture.md) +- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [RcParameterMap](../msg_docs/RcParameterMap.md) +- [LogMessage](../msg_docs/LogMessage.md) +- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) +- [OrbTestMedium](../msg_docs/OrbTestMedium.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [RtlStatus](../msg_docs/RtlStatus.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [Event](../msg_docs/Event.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) +- [GimbalControls](../msg_docs/GimbalControls.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [OrbTestLarge](../msg_docs/OrbTestLarge.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [GpioConfig](../msg_docs/GpioConfig.md) +- [MissionResult](../msg_docs/MissionResult.md) +- [SensorSelection](../msg_docs/SensorSelection.md) +- [GpioIn](../msg_docs/GpioIn.md) +- [VehicleRoi](../msg_docs/VehicleRoi.md) +- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) +- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [QshellRetval](../msg_docs/QshellRetval.md) +- [SensorBaro](../msg_docs/SensorBaro.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [HealthReport](../msg_docs/HealthReport.md) +- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) +- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) +- [RadioStatus](../msg_docs/RadioStatus.md) +- [Cpuload](../msg_docs/Cpuload.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) +- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) +- [FuelTankStatus](../msg_docs/FuelTankStatus.md) +- [Rpm](../msg_docs/Rpm.md) +- [SensorAccel](../msg_docs/SensorAccel.md) +- [ActionRequest](../msg_docs/ActionRequest.md) +- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) +- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) +- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) +- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) +- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) +- [SensorAirflow](../msg_docs/SensorAirflow.md) +- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) +- [DebugValue](../msg_docs/DebugValue.md) +- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [BatteryInfo](../msg_docs/BatteryInfo.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [PositionSetpoint](../msg_docs/PositionSetpoint.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [SensorsStatus](../msg_docs/SensorsStatus.md) +- [DeviceInformation](../msg_docs/DeviceInformation.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) - [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) +- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) +- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) +- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) +- [NeuralControl](../msg_docs/NeuralControl.md) +- [SensorCorrection](../msg_docs/SensorCorrection.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [LandingTargetPose](../msg_docs/LandingTargetPose.md) +- [InputRc](../msg_docs/InputRc.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) +- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [UlogStream](../msg_docs/UlogStream.md) +- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) +- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) +- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) +- [PpsCapture](../msg_docs/PpsCapture.md) +- [RoverRateStatus](../msg_docs/RoverRateStatus.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [AirspeedWind](../msg_docs/AirspeedWind.md) +- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [RcChannels](../msg_docs/RcChannels.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [AdcReport](../msg_docs/AdcReport.md) +- [ActuatorArmed](../msg_docs/ActuatorArmed.md) +- [MagWorkerData](../msg_docs/MagWorkerData.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [Ping](../msg_docs/Ping.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [LandingGearWheel](../msg_docs/LandingGearWheel.md) +- [PowerButtonState](../msg_docs/PowerButtonState.md) +- [GpsInjectData](../msg_docs/GpsInjectData.md) +- [VehicleImu](../msg_docs/VehicleImu.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [PwmInput](../msg_docs/PwmInput.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [SystemPower](../msg_docs/SystemPower.md) +- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) +- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) +- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) +- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [EstimatorStates](../msg_docs/EstimatorStates.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [GeofenceStatus](../msg_docs/GeofenceStatus.md) +- [FollowTarget](../msg_docs/FollowTarget.md) ::: From 32c94bd3b1bd16cc4897f61fb0135fb75bdb3c6e Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 11 Feb 2026 22:11:41 -0800 Subject: [PATCH 795/812] ci: fix S3 upload so tags don't overwrite stable firmware Remove the step that uploaded every version tag to the stable/ S3 directory, which caused QGC users selecting "stable" to receive pre-release firmware (#26340). The stable/ and beta/ directories are now controlled exclusively by their respective branch pushes, while version tags only upload to their versioned archive directory (e.g., v1.16.1/). Pre-release tags are also correctly marked on GitHub Releases. Co-authored-by: Julian Oes Fixes #26340 Signed-off-by: Ramon Roche --- .github/workflows/build_all_targets.yml | 77 ++++++++++++++++--------- 1 file changed, 50 insertions(+), 27 deletions(-) diff --git a/.github/workflows/build_all_targets.yml b/.github/workflows/build_all_targets.yml index cf02ac2e77..4c0bc0fcb9 100644 --- a/.github/workflows/build_all_targets.yml +++ b/.github/workflows/build_all_targets.yml @@ -2,6 +2,37 @@ # - If you want to keep the tests running in GitHub Actions you need to uncomment the "runs-on: ubuntu-latest" lines # and comment the "runs-on: [runs-on,runner=..." lines. # - If you would like to duplicate this setup try setting up "RunsOn" on your own AWS account try https://runs-on.com +# +# =================================================================================== +# RELEASE UPLOAD LOGIC +# =================================================================================== +# This workflow handles building firmware and uploading to S3 + GitHub Releases. +# +# S3 Bucket Structure (s3://px4-travis/Firmware/): +# - master/ <- Latest main branch build (for QGC compatibility) +# - stable/ <- Latest stable release, controlled by 'stable' branch +# - beta/ <- Latest pre-release, controlled by 'beta' branch +# - vX.Y.Z/ <- Archived stable release +# - vX.Y.Z-beta1/ <- Archived pre-release +# +# Trigger Behavior: +# - Tag v1.16.1 -> Upload to: v1.16.1/ only (versioned archive) +# - Tag v1.17.0-beta1 -> Upload to: v1.17.0-beta1/ only (versioned archive) +# - Branch main -> Upload to: master/ (for QGC compatibility) +# - Branch stable -> Upload to: stable/ (QGC stable firmware) +# - Branch beta -> Upload to: beta/ (QGC beta firmware) +# - Branch release/** -> Build only, no S3 upload (CI validation) +# - Pull requests -> Build only, no S3 upload (CI validation) +# +# GitHub Releases: +# - All version tags create a draft GitHub Release +# - Pre-releases (alpha/beta/rc suffixes) are automatically marked as such +# +# IMPORTANT: Version tags do NOT upload to stable/ or beta/. Only the +# corresponding branch pushes control those directories. This prevents +# pre-release tags from accidentally overwriting stable firmware (#26340) +# and avoids race conditions between tag and branch builds. +# =================================================================================== name: Build all targets @@ -163,6 +194,13 @@ jobs: path: ~/.ccache key: ${{ steps.cc_restore.outputs.cache-primary-key }} + # =========================================================================== + # ARTIFACT UPLOAD JOB + # =========================================================================== + # Uploads build artifacts to S3 and creates GitHub Releases. + # Runs for version tags (v*), main, stable, and beta branch pushes. + # See header comments for full upload logic documentation. + # =========================================================================== artifacts: name: Upload Artifacts # runs-on: ubuntu-latest @@ -181,31 +219,31 @@ jobs: - name: Choose Upload Location id: upload-location run: | - # Determine upload location based on branch or tag with the following considerations: - # Destination: AWS S3 bucket px4-travis in folder Firmware/ - # - If branch is main -> upload to master/ - # - Older versions of QGC are hardocded to look for master/ - # - If branch is stable or beta -> upload to stable/ or beta/ - # - If a tag vX.Y.Z -> upload to vX.Y.Z/ - # - Also update stable/ to point to the same version - #. - Older versions of QGC are hardocded to look for stable/ - # - If a pull request -> do not upload set -euo pipefail ref="${GITHUB_REF}" branch=${{ needs.group_targets.outputs.branchname }} location="$branch" + is_prerelease="false" + # Main branch uploads to "master" for QGC backward compatibility if [[ "$branch" == "main" ]]; then location="master" fi + # Version tags: upload to versioned directory (e.g., v1.16.1/) if [[ "$ref" == refs/tags/v[0-9]* ]]; then tag="${ref#refs/tags/}" location="$tag" + + # Pre-release tags contain -alpha, -beta, or -rc suffix + if [[ "$tag" =~ -(alpha|beta|rc) ]]; then + is_prerelease="true" + fi fi echo "uploadlocation=$location" >> $GITHUB_OUTPUT + echo "is_prerelease=$is_prerelease" >> $GITHUB_OUTPUT - name: Uploading Artifacts to S3 [${{ steps.upload-location.outputs.uploadlocation }}] uses: jakejarvis/s3-sync-action@master @@ -219,28 +257,13 @@ jobs: SOURCE_DIR: artifacts/ DEST_DIR: Firmware/${{ steps.upload-location.outputs.uploadlocation }}/ - # if we are uploading artifacts to a versioned folder - # we should also update the stable folder in the s3 bucket - - name: Uploading Artifacts to S3 [stable] - uses: jakejarvis/s3-sync-action@master - if: startsWith(github.ref, 'refs/tags/v') - with: - args: --acl public-read - env: - AWS_S3_BUCKET: 'px4-travis' - AWS_ACCESS_KEY_ID: ${{ secrets.AWS_ACCESS_KEY_ID }} - AWS_SECRET_ACCESS_KEY: ${{ secrets.AWS_SECRET_ACCESS_KEY }} - AWS_REGION: 'us-west-1' - SOURCE_DIR: artifacts/ - DEST_DIR: Firmware/stable/ - - # if build is a release triggered by a versioned tag then create a github release - # and upload the build artifacts. A draft release is created so that the release - # can be reviewed before publishing + # Create a draft GitHub Release for all version tags + # Pre-releases are automatically marked as such - name: Upload Artifacts to GitHub Release uses: softprops/action-gh-release@v2 if: startsWith(github.ref, 'refs/tags/v') with: draft: true + prerelease: ${{ steps.upload-location.outputs.is_prerelease == 'true' }} files: artifacts/*.px4 name: ${{ steps.upload-location.outputs.uploadlocation }} From e52ce5c43b85748c5f229a54c5b0275ed13a114f Mon Sep 17 00:00:00 2001 From: Claudio Chies <61051109+Claudio-Chies@users.noreply.github.com> Date: Mon, 16 Feb 2026 09:39:48 -0800 Subject: [PATCH 796/812] UAVCAN: Configurable LED Light Control with Flexible Addressing (#26253) * feat: implement UAVCAN LED control for individual light control and assignment * uavcan led: nit-picks from review * uavcan led: reduce maximum number of lights to avoid unused parameters * uavcan led: simplify anticolision on check * uavcan led: correctly map 8-bit RGB to rgb565 * Trim param name character arrays to 17 16 characters + \0 termination * uavcan led: final nit-picks --------- Co-authored-by: Matthias Grob --- .../amovlabf410_drone_v1.15.4.params | 3 - docs/en/dronecan/index.md | 13 + docs/en/peripherals/vertiq.md | 13 + src/drivers/uavcan/module.yaml | 42 +++ src/drivers/uavcan/rgbled.cpp | 239 +++++++++--------- src/drivers/uavcan/rgbled.hpp | 30 ++- src/drivers/uavcan/uavcan_params.c | 68 +---- src/modules/commander/ModeManagement.cpp | 4 +- .../ActuatorEffectivenessControlSurfaces.cpp | 2 +- 9 files changed, 215 insertions(+), 199 deletions(-) diff --git a/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params b/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params index 53bb8f5a01..4cea5fc9d4 100644 --- a/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params +++ b/docs/assets/airframes/multicopter/amovlab_f410/amovlabf410_drone_v1.15.4.params @@ -1056,9 +1056,6 @@ 1 1 UAVCAN_EC_REV 0 6 1 1 UAVCAN_ENABLE 2 6 1 1 UAVCAN_LGT_ANTCL 2 6 -1 1 UAVCAN_LGT_LAND 0 6 -1 1 UAVCAN_LGT_NAV 3 6 -1 1 UAVCAN_LGT_STROB 1 6 1 1 UAVCAN_NODE_ID 1 6 1 1 UAVCAN_PUB_ARM 0 6 1 1 UAVCAN_PUB_MBD 0 6 diff --git a/docs/en/dronecan/index.md b/docs/en/dronecan/index.md index 13898c9dc3..00ba948cbc 100644 --- a/docs/en/dronecan/index.md +++ b/docs/en/dronecan/index.md @@ -281,6 +281,19 @@ PX4 DroneCAN parameters: Select the specific CAN interface(s) used for ESC data output using the [UAVCAN_ESC_IFACE](../advanced_config/parameter_reference.md#UAVCAN_ESC_IFACE) parameter (all that all interfaces are selected by default). Note that DroneCAN ESCs should be on their own dedicated CAN interface(s) because ESC messages can saturate the bus and starve other nodes of bandwidth. +### Lights + +PX4 can control LEDs via DroneCAN [LightsCommand](https://dronecan.github.io/Specification/7._List_of_standard_data_types/#lightscommand) messages. + +Configuration: + +1. Set [UAVCAN_LGT_NUM](../advanced_config/parameter_reference.md#UAVCAN_LGT_NUM) to the number of lights (0 disables). You might need to reopen the ground station to have parameters for new instances available. +2. For each light slot (0 to NUM-1), set: + - `UAVCAN_LGT_IDx`: The `light_id` matching your peripheral. + - `UAVCAN_LGT_FNx`: `Status` for system status colours, or `Anti-collision` for white beacon. +3. For anti-collision lights, [UAVCAN_LGT_ANTCL](../advanced_config/parameter_reference.md#UAVCAN_LGT_ANTCL) controls when they illuminate (off, armed, prearmed, always on). +4. Reboot for any changes to take effect. + ## QGC CANNODE Parameter Configuration QGroundControl can inspect and modify parameters belonging to CAN devices attached to the flight controller, provided the device are connected to the flight controller before QGC is started. diff --git a/docs/en/peripherals/vertiq.md b/docs/en/peripherals/vertiq.md index 82c7611f16..9a9f80c575 100644 --- a/docs/en/peripherals/vertiq.md +++ b/docs/en/peripherals/vertiq.md @@ -38,6 +38,19 @@ Instructions for integrating the motor/ESC using with DroneCAN can be found in [ These instructions walk you through setting the correct parameters for enabling the flight controller's DroneCAN drivers, setting the correct configuration parameters for communication with Vertiq modules on the DroneCAN bus, ESC configuration, and testing that your flight controller can properly control your modules over DroneCAN. +#### LED Configuration for Vertiq Modules + +::: info +This configuration is only required if you have the optional [Vertiq LED module add-on](https://www.vertiq.co/add-ons). +Standard Vertiq ESC modules do not include LEDs. +::: + +Vertiq LED Add-on modules have two LEDs per ESC (RGB for status, White for anti-collision). +See [DroneCAN Lights](../dronecan/index.md#lights) for configuration instructions. + +The `light_id` for each LED is calculated as: `esc_index × 3 + BASE_ID`, where `BASE_ID` is 1 for RGB and 2 for White. + + ### DShot/PWM Configuration Instructions for integrating the motor/ESC using PWM and DShot can be found in [PWM and DShot Control with a Flight Controller](https://iqmotion.readthedocs.io/en/latest/tutorials/pwm_control_flight_controller.html). diff --git a/src/drivers/uavcan/module.yaml b/src/drivers/uavcan/module.yaml index 0579870297..9518e06494 100644 --- a/src/drivers/uavcan/module.yaml +++ b/src/drivers/uavcan/module.yaml @@ -1,3 +1,5 @@ +__max_num_uavcan_lights: &max_num_uavcan_lights 3 # Needs to be equal to MAX_NUM_UAVCAN_LIGHTS constant + module_name: UAVCAN parameters: - group: UAVCAN @@ -24,6 +26,46 @@ parameters: min: 1 max: 255 reboot_required: true + UAVCAN_LGT_NUM: + description: + short: Number of UAVCAN lights to configure + long: | + Number of lights to control via UAVCAN LightsCommand messages. + Set to 0 to disable UAVCAN light control. + Each light uses two parameters: LGT_IDx for the light_id and LGT_FNx for the function. + type: int32 + min: 0 + max: *max_num_uavcan_lights + default: 1 + reboot_required: true + UAVCAN_LGT_ID${i}: + description: + short: Light ${i} ID + long: | + specifies the light_id value for light ${i} in UAVCAN LightsCommand messages. + This determines which physical LED responds to commands for this light slot. + type: int32 + num_instances: *max_num_uavcan_lights + instance_start: 0 + min: 0 + max: 255 + default: 0 + UAVCAN_LGT_FN${i}: + description: + short: Light ${i} function + long: | + Function assigned to light ${i}. + 0: Status - displays system status colors + 1: Anti-collision - white beacon controlled by LGT_ANTCL parameter + type: enum + num_instances: *max_num_uavcan_lights + instance_start: 0 + min: 0 + max: 1 + default: 0 + values: + 0: Status Light + 1: Anti-collision Light actuator_output: show_subgroups_if: 'UAVCAN_ENABLE>=3' config_parameters: diff --git a/src/drivers/uavcan/rgbled.cpp b/src/drivers/uavcan/rgbled.cpp index 5c4ee8dc21..3ee0e1225e 100644 --- a/src/drivers/uavcan/rgbled.cpp +++ b/src/drivers/uavcan/rgbled.cpp @@ -32,6 +32,7 @@ ****************************************************************************/ #include "rgbled.hpp" +#include UavcanRGBController::UavcanRGBController(uavcan::INode &node) : ModuleParams(nullptr), @@ -44,6 +45,38 @@ UavcanRGBController::UavcanRGBController(uavcan::INode &node) : int UavcanRGBController::init() { + // Cache number of lights (0 disables the feature) + _num_lights = math::min(static_cast(_param_lgt_num.get()), MAX_NUM_UAVCAN_LIGHTS); + + if (_num_lights == 0) { + return 0; // Disabled, don't start timer + } + + // Cache parameter handles and values for each light + for (uint8_t i = 0; i < _num_lights; i++) { + char param_name[17]; + + // Light ID parameter + snprintf(param_name, sizeof(param_name), "UAVCAN_LGT_ID%u", i); + _light_id_params[i] = param_find(param_name); + + if (_light_id_params[i] != PARAM_INVALID) { + int32_t light_id = 0; + param_get(_light_id_params[i], &light_id); + _light_ids[i] = static_cast(light_id); + } + + // Light function parameter + snprintf(param_name, sizeof(param_name), "UAVCAN_LGT_FN%u", i); + _light_fn_params[i] = param_find(param_name); + + if (_light_fn_params[i] != PARAM_INVALID) { + int32_t light_fn = 0; + param_get(_light_fn_params[i], &light_fn); + _light_functions[i] = static_cast(light_fn); + } + } + // Setup timer and call back function for periodic updates _timer.setCallback(TimerCbBinder(this, &UavcanRGBController::periodic_update)); _timer.startPeriodic(uavcan::MonotonicDuration::fromMSec(1000 / MAX_RATE_HZ)); @@ -52,142 +85,108 @@ int UavcanRGBController::init() void UavcanRGBController::periodic_update(const uavcan::TimerEvent &) { - bool publish_lights = false; - uavcan::equipment::indication::LightsCommand cmds; + // Early return if disabled or no lights configured + if (_num_lights == 0) { + return; + } + // Check for status color updates from led_controller LedControlData led_control_data; - if (_led_controller.update(led_control_data) == 1) { - publish_lights = true; + if (_led_controller.update(led_control_data) != 1) { + return; // No update, nothing to do + } - // RGB color in the standard 5-6-5 16-bit palette. - // Monocolor lights should interpret this as brightness setpoint: from zero (0, 0, 0) to full brightness (31, 63, 31). + // Compute status color from led_control_data + uavcan::equipment::indication::RGB565 status_color{}; + uint8_t brightness = led_control_data.leds[0].brightness; + + switch (led_control_data.leds[0].color) { + case led_control_s::COLOR_RED: + status_color = rgb888_to_rgb565(brightness, 0, 0); + break; + + case led_control_s::COLOR_GREEN: + status_color = rgb888_to_rgb565(0, brightness, 0); + break; + + case led_control_s::COLOR_BLUE: + status_color = rgb888_to_rgb565(0, 0, brightness); + break; + + case led_control_s::COLOR_AMBER: // make it the same as yellow + case led_control_s::COLOR_YELLOW: + status_color = rgb888_to_rgb565(brightness, brightness, 0); + break; + + case led_control_s::COLOR_PURPLE: + status_color = rgb888_to_rgb565(brightness, 0, brightness); + break; + + case led_control_s::COLOR_CYAN: + status_color = rgb888_to_rgb565(0, brightness, brightness); + break; + + case led_control_s::COLOR_WHITE: + status_color = rgb888_to_rgb565(brightness, brightness, brightness); + break; + + default: + case led_control_s::COLOR_OFF: + break; + } + + // Build and send light commands for all configured lights + uavcan::equipment::indication::LightsCommand light_command; + + for (uint8_t i = 0; i < _num_lights; i++) { uavcan::equipment::indication::SingleLightCommand cmd; + cmd.light_id = _light_ids[i]; - uint8_t brightness = led_control_data.leds[0].brightness; - - switch (led_control_data.leds[0].color) { - case led_control_s::COLOR_RED: - cmd.color.red = brightness >> 3; - cmd.color.green = 0; - cmd.color.blue = 0; + switch (_light_functions[i]) { + case LightFunction::Status: + cmd.color = status_color; break; - case led_control_s::COLOR_GREEN: - cmd.color.red = 0; - cmd.color.green = brightness >> 2; - cmd.color.blue = 0; - break; - - case led_control_s::COLOR_BLUE: - cmd.color.red = 0; - cmd.color.green = 0; - cmd.color.blue = brightness >> 3; - break; - - case led_control_s::COLOR_AMBER: // make it the same as yellow - - // FALLTHROUGH - case led_control_s::COLOR_YELLOW: - cmd.color.red = (brightness / 2) >> 3; - cmd.color.green = (brightness / 2) >> 2; - cmd.color.blue = 0; - break; - - case led_control_s::COLOR_PURPLE: - cmd.color.red = (brightness / 2) >> 3; - cmd.color.green = 0; - cmd.color.blue = (brightness / 2) >> 3; - break; - - case led_control_s::COLOR_CYAN: - cmd.color.red = 0; - cmd.color.green = (brightness / 2) >> 2; - cmd.color.blue = (brightness / 2) >> 3; - break; - - case led_control_s::COLOR_WHITE: - cmd.color.red = (brightness / 3) >> 3; - cmd.color.green = (brightness / 3) >> 2; - cmd.color.blue = (brightness / 3) >> 3; - break; - - default: // led_control_s::COLOR_OFF - cmd.color.red = 0; - cmd.color.green = 0; - cmd.color.blue = 0; + case LightFunction::AntiCollision: + uint8_t brigtness = is_anticolision_on() ? 255 : 0; + cmd.color = rgb888_to_rgb565(brigtness, brigtness, brigtness); break; } - cmds.commands.push_back(cmd); - + light_command.commands.push_back(cmd); } - if (_armed_sub.updated()) { - publish_lights = true; - - actuator_armed_s armed; - - if (_armed_sub.copy(&armed)) { - - /* Determine the current control mode - * If a light's control mode config >= current control mode, the light will be enabled - * Logic must match UAVCAN_LGT_* param values. - * @value 0 Always off - * @value 1 When autopilot is armed - * @value 2 When autopilot is prearmed - * @value 3 Always on - */ - uint8_t control_mode = 0; - - if (armed.armed) { - control_mode = 1; - - } else if (armed.prearmed) { - control_mode = 2; - - } else { - control_mode = 3; - } - - uavcan::equipment::indication::SingleLightCommand cmd; - - // Beacons - cmd.light_id = uavcan::equipment::indication::SingleLightCommand::LIGHT_ID_ANTI_COLLISION; - cmd.color = brightness_to_rgb565(_param_mode_anti_col.get() >= control_mode ? 255 : 0); - cmds.commands.push_back(cmd); - - // Strobes - cmd.light_id = uavcan::equipment::indication::SingleLightCommand::LIGHT_ID_STROBE; - cmd.color = brightness_to_rgb565(_param_mode_strobe.get() >= control_mode ? 255 : 0); - cmds.commands.push_back(cmd); - - // Nav lights - cmd.light_id = uavcan::equipment::indication::SingleLightCommand::LIGHT_ID_RIGHT_OF_WAY; - cmd.color = brightness_to_rgb565(_param_mode_nav.get() >= control_mode ? 255 : 0); - cmds.commands.push_back(cmd); - - // Landing lights - cmd.light_id = uavcan::equipment::indication::SingleLightCommand::LIGHT_ID_LANDING; - cmd.color = brightness_to_rgb565(_param_mode_land.get() >= control_mode ? 255 : 0); - cmds.commands.push_back(cmd); - } - } - - if (publish_lights) { - _uavcan_pub_lights_cmd.broadcast(cmds); - } + _uavcan_pub_lights_cmd.broadcast(light_command); } -uavcan::equipment::indication::RGB565 UavcanRGBController::brightness_to_rgb565(uint8_t brightness) +bool UavcanRGBController::is_anticolision_on() { - // RGB color in the standard 5-6-5 16-bit palette. - // Monocolor lights should interpret this as brightness setpoint: from zero (0, 0, 0) to full brightness (31, 63, 31). - uavcan::equipment::indication::RGB565 color; + actuator_armed_s actuator_armed{}; + _actuator_armed_sub.copy(&actuator_armed); - color.red = (31.0f * (float)brightness / 255.0f); - color.green = (62.0f * (float)brightness / 255.0f); - color.blue = (31.0f * (float)brightness / 255.0f); + switch (_param_uavcan_lgt_antcl.get()) { + case 3: // Always on + return true; - return color; + case 2: // When autopilot is prearmed + return actuator_armed.armed || actuator_armed.prearmed; + + case 1: // When autopilot is armed + return actuator_armed.armed; + + case 0: // Always off + default: + return false; + } +} + +uavcan::equipment::indication::RGB565 UavcanRGBController::rgb888_to_rgb565(uint8_t red, uint8_t green, uint8_t blue) +{ + // RGB565: Full brightness is (31, 63, 31), off is (0, 0, 0) + uavcan::equipment::indication::RGB565 rgb565{}; + rgb565.red = (red * 31 + 127) / 255; + rgb565.green = (green * 63 + 127) / 255; + rgb565.blue = (blue * 31 + 127) / 255; + return rgb565; } diff --git a/src/drivers/uavcan/rgbled.hpp b/src/drivers/uavcan/rgbled.hpp index be0bc876d3..ee189019e2 100644 --- a/src/drivers/uavcan/rgbled.hpp +++ b/src/drivers/uavcan/rgbled.hpp @@ -54,9 +54,20 @@ private: // Max update rate to avoid excessive bus traffic static constexpr unsigned MAX_RATE_HZ = 20; + // Maximum number of configurable lights + static constexpr uint8_t MAX_NUM_UAVCAN_LIGHTS = 3; + + // Light function types + enum class LightFunction : uint8_t { + Status = 0, // System status colors from led_control + AntiCollision = 1 // White beacon based on arm state + }; + void periodic_update(const uavcan::TimerEvent &); - uavcan::equipment::indication::RGB565 brightness_to_rgb565(uint8_t brightness); + bool is_anticolision_on(); ///< Evaluates current on state of collision lights accordingt to UAVCAN_LGT_ANTCL + + uavcan::equipment::indication::RGB565 rgb888_to_rgb565(uint8_t red, uint8_t green, uint8_t blue); typedef uavcan::MethodBinder TimerCbBinder; @@ -65,14 +76,21 @@ private: uavcan::Publisher _uavcan_pub_lights_cmd; uavcan::TimerEventForwarder _timer; - uORB::Subscription _armed_sub{ORB_ID(actuator_armed)}; + uORB::Subscription _actuator_armed_sub{ORB_ID(actuator_armed)}; LedController _led_controller; + // Cached configuration (set during init, requires reboot to change) + uint8_t _num_lights{0}; + uint8_t _light_ids[MAX_NUM_UAVCAN_LIGHTS] {}; + LightFunction _light_functions[MAX_NUM_UAVCAN_LIGHTS] {}; + + // Cached parameter handles + param_t _light_id_params[MAX_NUM_UAVCAN_LIGHTS] {}; + param_t _light_fn_params[MAX_NUM_UAVCAN_LIGHTS] {}; + DEFINE_PARAMETERS( - (ParamInt) _param_mode_anti_col, - (ParamInt) _param_mode_strobe, - (ParamInt) _param_mode_nav, - (ParamInt) _param_mode_land + (ParamInt) _param_lgt_num, + (ParamInt) _param_uavcan_lgt_antcl ) }; diff --git a/src/drivers/uavcan/uavcan_params.c b/src/drivers/uavcan/uavcan_params.c index 99a38897e4..9dd90e2e4c 100644 --- a/src/drivers/uavcan/uavcan_params.c +++ b/src/drivers/uavcan/uavcan_params.c @@ -135,7 +135,7 @@ PARAM_DEFINE_INT32(UAVCAN_ECU_FUELT, 1); * UAVCAN ANTI_COLLISION light operating mode * * This parameter defines the minimum condition under which the system will command - * the ANTI_COLLISION lights on + * lights with anti-collision function to turn on (white). * * 0 - Always off * 1 - When autopilot is armed @@ -153,72 +153,6 @@ PARAM_DEFINE_INT32(UAVCAN_ECU_FUELT, 1); */ PARAM_DEFINE_INT32(UAVCAN_LGT_ANTCL, 2); -/** - * UAVCAN STROBE light operating mode - * - * This parameter defines the minimum condition under which the system will command - * the STROBE lights on - * - * 0 - Always off - * 1 - When autopilot is armed - * 2 - When autopilot is prearmed - * 3 - Always on - * - * @min 0 - * @max 3 - * @value 0 Always off - * @value 1 When autopilot is armed - * @value 2 When autopilot is prearmed - * @value 3 Always on - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_LGT_STROB, 1); - -/** - * UAVCAN RIGHT_OF_WAY light operating mode - * - * This parameter defines the minimum condition under which the system will command - * the RIGHT_OF_WAY lights on - * - * 0 - Always off - * 1 - When autopilot is armed - * 2 - When autopilot is prearmed - * 3 - Always on - * - * @min 0 - * @max 3 - * @value 0 Always off - * @value 1 When autopilot is armed - * @value 2 When autopilot is prearmed - * @value 3 Always on - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_LGT_NAV, 3); - -/** - * UAVCAN LIGHT_ID_LANDING light operating mode - * - * This parameter defines the minimum condition under which the system will command - * the LIGHT_ID_LANDING lights on - * - * 0 - Always off - * 1 - When autopilot is armed - * 2 - When autopilot is prearmed - * 3 - Always on - * - * @min 0 - * @max 3 - * @value 0 Always off - * @value 1 When autopilot is armed - * @value 2 When autopilot is prearmed - * @value 3 Always on - * @reboot_required true - * @group UAVCAN - */ -PARAM_DEFINE_INT32(UAVCAN_LGT_LAND, 0); - /** * publish Arming Status stream * diff --git a/src/modules/commander/ModeManagement.cpp b/src/modules/commander/ModeManagement.cpp index ae2dee41ff..b7212f05b8 100644 --- a/src/modules/commander/ModeManagement.cpp +++ b/src/modules/commander/ModeManagement.cpp @@ -107,7 +107,7 @@ uint8_t Modes::addExternalMode(const Modes::Mode &mode) int matching_idx = -1; for (int i = 0; i < MAX_NUM; ++i) { - char hash_param_name[20]; + char hash_param_name[17]; snprintf(hash_param_name, sizeof(hash_param_name), "COM_MODE%d_HASH", i); const param_t handle = param_find(hash_param_name); int32_t current_hash{}; @@ -164,7 +164,7 @@ uint8_t Modes::addExternalMode(const Modes::Mode &mode) if (new_mode_idx != -1 && !_modes[new_mode_idx].valid) { if (need_to_update_param) { - char hash_param_name[20]; + char hash_param_name[17]; snprintf(hash_param_name, sizeof(hash_param_name), "COM_MODE%d_HASH", new_mode_idx); const param_t handle = param_find(hash_param_name); diff --git a/src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessControlSurfaces.cpp b/src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessControlSurfaces.cpp index 093185e240..8a033770ce 100644 --- a/src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessControlSurfaces.cpp +++ b/src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessControlSurfaces.cpp @@ -80,7 +80,7 @@ void ActuatorEffectivenessControlSurfaces::updateParams() // Helper to check if a PWM center parameter is enabled, and clamp it to valid range auto check_pwm_center = [](const char *prefix, int channel) -> bool { - char param_name[20]; + char param_name[17]; snprintf(param_name, sizeof(param_name), "%s_CENT%d", prefix, channel); param_t param = param_find(param_name); From 4bebbbae93209d898d6aa9f5302a875693f33b37 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Mon, 16 Feb 2026 17:47:30 +0000 Subject: [PATCH 797/812] docs: auto-sync metadata [skip ci] Co-Authored-By: PX4 BuildBot --- .../en/advanced_config/parameter_reference.md | 116 +++--- docs/en/middleware/dds_topics.md | 360 +++++++++--------- docs/en/peripherals/vertiq.md | 1 - 3 files changed, 253 insertions(+), 224 deletions(-) diff --git a/docs/en/advanced_config/parameter_reference.md b/docs/en/advanced_config/parameter_reference.md index 501a113ee0..b50fe34113 100644 --- a/docs/en/advanced_config/parameter_reference.md +++ b/docs/en/advanced_config/parameter_reference.md @@ -40288,7 +40288,7 @@ starve other nodes on the bus. UAVCAN ANTI_COLLISION light operating mode. This parameter defines the minimum condition under which the system will command -the ANTI_COLLISION lights on +lights with anti-collision function to turn on (white). 0 - Always off 1 - When autopilot is armed 2 - When autopilot is prearmed @@ -40305,67 +40305,97 @@ the ANTI_COLLISION lights on | ------- | -------- | -------- | --------- | ------- | ---- | | ✓ | 0 | 3 | | 2 | -### UAVCAN_LGT_LAND (`INT32`) {#UAVCAN_LGT_LAND} +### UAVCAN_LGT_FN0 (`INT32`) {#UAVCAN_LGT_FN0} -UAVCAN LIGHT_ID_LANDING light operating mode. +Light 0 function. -This parameter defines the minimum condition under which the system will command -the LIGHT_ID_LANDING lights on -0 - Always off -1 - When autopilot is armed -2 - When autopilot is prearmed -3 - Always on +Function assigned to light 0. +0: Status - displays system status colors +1: Anti-collision - white beacon controlled by LGT_ANTCL parameter **Values:** -- `0`: Always off -- `1`: When autopilot is armed -- `2`: When autopilot is prearmed -- `3`: Always on +- `0`: Status Light +- `1`: Anti-collision Light -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 3 | | 0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1 | | 0 | -### UAVCAN_LGT_NAV (`INT32`) {#UAVCAN_LGT_NAV} +### UAVCAN_LGT_FN1 (`INT32`) {#UAVCAN_LGT_FN1} -UAVCAN RIGHT_OF_WAY light operating mode. +Light 1 function. -This parameter defines the minimum condition under which the system will command -the RIGHT_OF_WAY lights on -0 - Always off -1 - When autopilot is armed -2 - When autopilot is prearmed -3 - Always on +Function assigned to light 1. +0: Status - displays system status colors +1: Anti-collision - white beacon controlled by LGT_ANTCL parameter **Values:** -- `0`: Always off -- `1`: When autopilot is armed -- `2`: When autopilot is prearmed -- `3`: Always on +- `0`: Status Light +- `1`: Anti-collision Light -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 3 | | 3 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1 | | 0 | -### UAVCAN_LGT_STROB (`INT32`) {#UAVCAN_LGT_STROB} +### UAVCAN_LGT_FN2 (`INT32`) {#UAVCAN_LGT_FN2} -UAVCAN STROBE light operating mode. +Light 2 function. -This parameter defines the minimum condition under which the system will command -the STROBE lights on -0 - Always off -1 - When autopilot is armed -2 - When autopilot is prearmed -3 - Always on +Function assigned to light 2. +0: Status - displays system status colors +1: Anti-collision - white beacon controlled by LGT_ANTCL parameter **Values:** -- `0`: Always off -- `1`: When autopilot is armed -- `2`: When autopilot is prearmed -- `3`: Always on +- `0`: Status Light +- `1`: Anti-collision Light + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1 | | 0 | + +### UAVCAN_LGT_ID0 (`INT32`) {#UAVCAN_LGT_ID0} + +Light 0 ID. + +specifies the light_id value for light 0 in UAVCAN LightsCommand messages. +This determines which physical LED responds to commands for this light slot. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 255 | | 0 | + +### UAVCAN_LGT_ID1 (`INT32`) {#UAVCAN_LGT_ID1} + +Light 1 ID. + +specifies the light_id value for light 1 in UAVCAN LightsCommand messages. +This determines which physical LED responds to commands for this light slot. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 255 | | 0 | + +### UAVCAN_LGT_ID2 (`INT32`) {#UAVCAN_LGT_ID2} + +Light 2 ID. + +specifies the light_id value for light 2 in UAVCAN LightsCommand messages. +This determines which physical LED responds to commands for this light slot. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 255 | | 0 | + +### UAVCAN_LGT_NUM (`INT32`) {#UAVCAN_LGT_NUM} + +Number of UAVCAN lights to configure. + +Number of lights to control via UAVCAN LightsCommand messages. +Set to 0 to disable UAVCAN light control. +Each light uses two parameters: LGT_IDx for the light_id and LGT_FNx for the function. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index 6e61104195..012b4ef6f0 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -94,199 +94,199 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages -- [QshellReq](../msg_docs/QshellReq.md) -- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) -- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) -- [MountOrientation](../msg_docs/MountOrientation.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) -- [GainCompression](../msg_docs/GainCompression.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) -- [LedControl](../msg_docs/LedControl.md) -- [Px4ioStatus](../msg_docs/Px4ioStatus.md) -- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [SensorTemp](../msg_docs/SensorTemp.md) -- [EscStatus](../msg_docs/EscStatus.md) -- [CellularStatus](../msg_docs/CellularStatus.md) -- [Mission](../msg_docs/Mission.md) -- [GpioOut](../msg_docs/GpioOut.md) -- [EstimatorStatus](../msg_docs/EstimatorStatus.md) -- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) +- [SensorSelection](../msg_docs/SensorSelection.md) +- [AirspeedWind](../msg_docs/AirspeedWind.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) +- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [PowerButtonState](../msg_docs/PowerButtonState.md) +- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) - [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) -- [GpsDump](../msg_docs/GpsDump.md) -- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) -- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) -- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) -- [SatelliteInfo](../msg_docs/SatelliteInfo.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) -- [IrlockReport](../msg_docs/IrlockReport.md) -- [UlogStreamAck](../msg_docs/UlogStreamAck.md) -- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) -- [EscReport](../msg_docs/EscReport.md) -- [EventV0](../msg_docs/EventV0.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [Vtx](../msg_docs/Vtx.md) -- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [RaptorStatus](../msg_docs/RaptorStatus.md) -- [SensorMag](../msg_docs/SensorMag.md) -- [SensorUwb](../msg_docs/SensorUwb.md) -- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) -- [ActuatorTest](../msg_docs/ActuatorTest.md) -- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) -- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) -- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) -- [SensorGyro](../msg_docs/SensorGyro.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) -- [VehicleAirData](../msg_docs/VehicleAirData.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) -- [Airspeed](../msg_docs/Airspeed.md) +- [BatteryInfo](../msg_docs/BatteryInfo.md) +- [LedControl](../msg_docs/LedControl.md) +- [Ping](../msg_docs/Ping.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [LandingGearWheel](../msg_docs/LandingGearWheel.md) +- [NeuralControl](../msg_docs/NeuralControl.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) - [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) -- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) +- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) +- [GpioConfig](../msg_docs/GpioConfig.md) +- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) +- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) +- [SensorAirflow](../msg_docs/SensorAirflow.md) +- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) +- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) - [Gripper](../msg_docs/Gripper.md) -- [GpioRequest](../msg_docs/GpioRequest.md) +- [SensorAccel](../msg_docs/SensorAccel.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) +- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) +- [ActuatorArmed](../msg_docs/ActuatorArmed.md) +- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [CellularStatus](../msg_docs/CellularStatus.md) +- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) +- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) +- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) +- [LogMessage](../msg_docs/LogMessage.md) +- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) +- [OrbTestLarge](../msg_docs/OrbTestLarge.md) +- [VehicleAirData](../msg_docs/VehicleAirData.md) +- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) +- [MagWorkerData](../msg_docs/MagWorkerData.md) +- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) +- [IrlockReport](../msg_docs/IrlockReport.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) - [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) +- [EventV0](../msg_docs/EventV0.md) +- [DifferentialPressure](../msg_docs/DifferentialPressure.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [GpioRequest](../msg_docs/GpioRequest.md) +- [SensorGyro](../msg_docs/SensorGyro.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [EstimatorStatus](../msg_docs/EstimatorStatus.md) +- [GimbalControls](../msg_docs/GimbalControls.md) +- [SystemPower](../msg_docs/SystemPower.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [EscReport](../msg_docs/EscReport.md) +- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [MissionResult](../msg_docs/MissionResult.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [GpioIn](../msg_docs/GpioIn.md) +- [SatelliteInfo](../msg_docs/SatelliteInfo.md) +- [RcParameterMap](../msg_docs/RcParameterMap.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) +- [GeneratorStatus](../msg_docs/GeneratorStatus.md) +- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [LandingTargetPose](../msg_docs/LandingTargetPose.md) +- [SensorBaro](../msg_docs/SensorBaro.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [SensorUwb](../msg_docs/SensorUwb.md) +- [Vtx](../msg_docs/Vtx.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [EstimatorStates](../msg_docs/EstimatorStates.md) +- [RcChannels](../msg_docs/RcChannels.md) +- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) +- [CameraCapture](../msg_docs/CameraCapture.md) +- [GpsInjectData](../msg_docs/GpsInjectData.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) +- [GainCompression](../msg_docs/GainCompression.md) +- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) +- [VehicleImu](../msg_docs/VehicleImu.md) +- [OrbTestMedium](../msg_docs/OrbTestMedium.md) +- [FuelTankStatus](../msg_docs/FuelTankStatus.md) +- [FollowTarget](../msg_docs/FollowTarget.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [DebugValue](../msg_docs/DebugValue.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [Airspeed](../msg_docs/Airspeed.md) +- [InputRc](../msg_docs/InputRc.md) +- [GpsDump](../msg_docs/GpsDump.md) +- [RadioStatus](../msg_docs/RadioStatus.md) +- [ActionRequest](../msg_docs/ActionRequest.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [SensorCorrection](../msg_docs/SensorCorrection.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) +- [Rpm](../msg_docs/Rpm.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [GeofenceStatus](../msg_docs/GeofenceStatus.md) +- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [SensorMag](../msg_docs/SensorMag.md) +- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) +- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) +- [CameraStatus](../msg_docs/CameraStatus.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [HealthReport](../msg_docs/HealthReport.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) +- [PositionSetpoint](../msg_docs/PositionSetpoint.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) +- [RoverRateStatus](../msg_docs/RoverRateStatus.md) +- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) - [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) - [CameraTrigger](../msg_docs/CameraTrigger.md) -- [ButtonEvent](../msg_docs/ButtonEvent.md) -- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) -- [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) -- [CameraStatus](../msg_docs/CameraStatus.md) -- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) -- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) -- [GeneratorStatus](../msg_docs/GeneratorStatus.md) -- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [ParameterUpdate](../msg_docs/ParameterUpdate.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [RcParameterMap](../msg_docs/RcParameterMap.md) -- [LogMessage](../msg_docs/LogMessage.md) -- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) -- [OrbTestMedium](../msg_docs/OrbTestMedium.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [RtlStatus](../msg_docs/RtlStatus.md) -- [TecsStatus](../msg_docs/TecsStatus.md) -- [Event](../msg_docs/Event.md) -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) -- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) -- [GimbalControls](../msg_docs/GimbalControls.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) -- [OrbTestLarge](../msg_docs/OrbTestLarge.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [GpioConfig](../msg_docs/GpioConfig.md) -- [MissionResult](../msg_docs/MissionResult.md) -- [SensorSelection](../msg_docs/SensorSelection.md) -- [GpioIn](../msg_docs/GpioIn.md) -- [VehicleRoi](../msg_docs/VehicleRoi.md) -- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) -- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) - [QshellRetval](../msg_docs/QshellRetval.md) -- [SensorBaro](../msg_docs/SensorBaro.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [Event](../msg_docs/Event.md) - [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) -- [HealthReport](../msg_docs/HealthReport.md) -- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) -- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) -- [RadioStatus](../msg_docs/RadioStatus.md) - [Cpuload](../msg_docs/Cpuload.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [Rpm](../msg_docs/Rpm.md) -- [SensorAccel](../msg_docs/SensorAccel.md) -- [ActionRequest](../msg_docs/ActionRequest.md) -- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) -- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) -- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) +- [Mission](../msg_docs/Mission.md) +- [OrbTest](../msg_docs/OrbTest.md) +- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [ButtonEvent](../msg_docs/ButtonEvent.md) - [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [SensorAirflow](../msg_docs/SensorAirflow.md) -- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [DebugValue](../msg_docs/DebugValue.md) -- [SensorGyroFft](../msg_docs/SensorGyroFft.md) -- [BatteryInfo](../msg_docs/BatteryInfo.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) -- [PositionSetpoint](../msg_docs/PositionSetpoint.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [UlogStream](../msg_docs/UlogStream.md) +- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) +- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) +- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) - [SensorsStatus](../msg_docs/SensorsStatus.md) - [DeviceInformation](../msg_docs/DeviceInformation.md) -- [TuneControl](../msg_docs/TuneControl.md) -- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) -- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) -- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) +- [SensorHygrometer](../msg_docs/SensorHygrometer.md) - [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) -- [NeuralControl](../msg_docs/NeuralControl.md) -- [SensorCorrection](../msg_docs/SensorCorrection.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) -- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) -- [LandingTargetPose](../msg_docs/LandingTargetPose.md) -- [InputRc](../msg_docs/InputRc.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [UlogStream](../msg_docs/UlogStream.md) -- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) -- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) -- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) - [PpsCapture](../msg_docs/PpsCapture.md) -- [RoverRateStatus](../msg_docs/RoverRateStatus.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) -- [AirspeedWind](../msg_docs/AirspeedWind.md) -- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [EstimatorBias](../msg_docs/EstimatorBias.md) -- [RcChannels](../msg_docs/RcChannels.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) -- [AdcReport](../msg_docs/AdcReport.md) -- [ActuatorArmed](../msg_docs/ActuatorArmed.md) -- [MagWorkerData](../msg_docs/MagWorkerData.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) -- [Ping](../msg_docs/Ping.md) -- [DebugArray](../msg_docs/DebugArray.md) -- [LandingGearWheel](../msg_docs/LandingGearWheel.md) -- [PowerButtonState](../msg_docs/PowerButtonState.md) -- [GpsInjectData](../msg_docs/GpsInjectData.md) -- [VehicleImu](../msg_docs/VehicleImu.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) +- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) +- [RtlStatus](../msg_docs/RtlStatus.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) +- [QshellReq](../msg_docs/QshellReq.md) +- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) +- [GpioOut](../msg_docs/GpioOut.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) +- [VehicleRoi](../msg_docs/VehicleRoi.md) +- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) - [PwmInput](../msg_docs/PwmInput.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [RaptorInput](../msg_docs/RaptorInput.md) -- [SystemPower](../msg_docs/SystemPower.md) -- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) -- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [EstimatorStates](../msg_docs/EstimatorStates.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) -- [GeofenceStatus](../msg_docs/GeofenceStatus.md) -- [FollowTarget](../msg_docs/FollowTarget.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) +- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [AdcReport](../msg_docs/AdcReport.md) +- [ActuatorTest](../msg_docs/ActuatorTest.md) ::: diff --git a/docs/en/peripherals/vertiq.md b/docs/en/peripherals/vertiq.md index 9a9f80c575..224118a8bf 100644 --- a/docs/en/peripherals/vertiq.md +++ b/docs/en/peripherals/vertiq.md @@ -50,7 +50,6 @@ See [DroneCAN Lights](../dronecan/index.md#lights) for configuration instruction The `light_id` for each LED is calculated as: `esc_index × 3 + BASE_ID`, where `BASE_ID` is 1 for RGB and 2 for White. - ### DShot/PWM Configuration Instructions for integrating the motor/ESC using PWM and DShot can be found in [PWM and DShot Control with a Flight Controller](https://iqmotion.readthedocs.io/en/latest/tutorials/pwm_control_flight_controller.html). From 061fe4806e7ce14767c9370e225b2435cd657b51 Mon Sep 17 00:00:00 2001 From: ljarvela <168073883+ljarvela@users.noreply.github.com> Date: Mon, 16 Feb 2026 22:25:30 +0200 Subject: [PATCH 798/812] uavcan: add warning about CAN error counter reading issue (#26492) Add warning message in print_info() to alert users that CAN error counter values may increase during the function call due to internal counter reading implementation. Users should not fully trust these counters until the underlying issue is fixed. Co-authored-by: ljarvela --- src/drivers/uavcan/uavcan_main.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/drivers/uavcan/uavcan_main.cpp b/src/drivers/uavcan/uavcan_main.cpp index e70c4436f2..956f5f4193 100644 --- a/src/drivers/uavcan/uavcan_main.cpp +++ b/src/drivers/uavcan/uavcan_main.cpp @@ -1163,6 +1163,11 @@ UavcanNode::print_info() printf("\n"); + // See https://github.com/PX4/PX4-Autopilot/issues/22871 + printf("WARNING: CAN error counter values below may increase during this function call due to internal counter reading implementation.\n"); + printf("Do not fully trust these counters until this issue is fixed.\n"); + printf("\n"); + // UAVCAN node perfcounters printf("UAVCAN node status:\n"); printf("\tInternal failures: %" PRIu64 "\n", _node.getInternalFailureCount()); From 08dc2a776e442a300cc8006d24db33f5c59bafd4 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Mon, 16 Feb 2026 20:33:01 +0000 Subject: [PATCH 799/812] docs: auto-sync metadata [skip ci] Co-Authored-By: PX4 BuildBot --- docs/en/middleware/dds_topics.md | 380 +++++++++++++++---------------- 1 file changed, 190 insertions(+), 190 deletions(-) diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index 012b4ef6f0..ec937cc543 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -94,199 +94,199 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages -- [SensorSelection](../msg_docs/SensorSelection.md) -- [AirspeedWind](../msg_docs/AirspeedWind.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) -- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) -- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [PowerButtonState](../msg_docs/PowerButtonState.md) -- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) -- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) -- [BatteryInfo](../msg_docs/BatteryInfo.md) -- [LedControl](../msg_docs/LedControl.md) -- [Ping](../msg_docs/Ping.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) -- [LandingGearWheel](../msg_docs/LandingGearWheel.md) -- [NeuralControl](../msg_docs/NeuralControl.md) -- [EstimatorBias](../msg_docs/EstimatorBias.md) -- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) -- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [GpioConfig](../msg_docs/GpioConfig.md) -- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) -- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) -- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [DebugArray](../msg_docs/DebugArray.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [SensorAirflow](../msg_docs/SensorAirflow.md) -- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) -- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) -- [Gripper](../msg_docs/Gripper.md) -- [SensorAccel](../msg_docs/SensorAccel.md) -- [SensorTemp](../msg_docs/SensorTemp.md) -- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) -- [RaptorStatus](../msg_docs/RaptorStatus.md) -- [Px4ioStatus](../msg_docs/Px4ioStatus.md) -- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) -- [ActuatorArmed](../msg_docs/ActuatorArmed.md) -- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) -- [CellularStatus](../msg_docs/CellularStatus.md) -- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) -- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) -- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) -- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) -- [LogMessage](../msg_docs/LogMessage.md) -- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) -- [OrbTestLarge](../msg_docs/OrbTestLarge.md) - [VehicleAirData](../msg_docs/VehicleAirData.md) -- [ParameterUpdate](../msg_docs/ParameterUpdate.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [MagWorkerData](../msg_docs/MagWorkerData.md) -- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) -- [IrlockReport](../msg_docs/IrlockReport.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) -- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) -- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) -- [EventV0](../msg_docs/EventV0.md) -- [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [EscStatus](../msg_docs/EscStatus.md) -- [GpioRequest](../msg_docs/GpioRequest.md) -- [SensorGyro](../msg_docs/SensorGyro.md) -- [TuneControl](../msg_docs/TuneControl.md) -- [EstimatorStatus](../msg_docs/EstimatorStatus.md) -- [GimbalControls](../msg_docs/GimbalControls.md) -- [SystemPower](../msg_docs/SystemPower.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) -- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) -- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) -- [MountOrientation](../msg_docs/MountOrientation.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [EscReport](../msg_docs/EscReport.md) -- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) -- [MissionResult](../msg_docs/MissionResult.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) -- [SensorGyroFft](../msg_docs/SensorGyroFft.md) -- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) -- [GpioIn](../msg_docs/GpioIn.md) -- [SatelliteInfo](../msg_docs/SatelliteInfo.md) -- [RcParameterMap](../msg_docs/RcParameterMap.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [GeneratorStatus](../msg_docs/GeneratorStatus.md) -- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) -- [LandingTargetPose](../msg_docs/LandingTargetPose.md) -- [SensorBaro](../msg_docs/SensorBaro.md) -- [TecsStatus](../msg_docs/TecsStatus.md) -- [SensorUwb](../msg_docs/SensorUwb.md) -- [Vtx](../msg_docs/Vtx.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [EstimatorStates](../msg_docs/EstimatorStates.md) -- [RcChannels](../msg_docs/RcChannels.md) -- [UlogStreamAck](../msg_docs/UlogStreamAck.md) -- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [GpsInjectData](../msg_docs/GpsInjectData.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [GainCompression](../msg_docs/GainCompression.md) -- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) -- [VehicleImu](../msg_docs/VehicleImu.md) -- [OrbTestMedium](../msg_docs/OrbTestMedium.md) -- [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [FollowTarget](../msg_docs/FollowTarget.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [DebugValue](../msg_docs/DebugValue.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [Airspeed](../msg_docs/Airspeed.md) -- [InputRc](../msg_docs/InputRc.md) -- [GpsDump](../msg_docs/GpsDump.md) -- [RadioStatus](../msg_docs/RadioStatus.md) -- [ActionRequest](../msg_docs/ActionRequest.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [SensorCorrection](../msg_docs/SensorCorrection.md) -- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) -- [Rpm](../msg_docs/Rpm.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) -- [GeofenceStatus](../msg_docs/GeofenceStatus.md) -- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) -- [SensorMag](../msg_docs/SensorMag.md) -- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) -- [CameraStatus](../msg_docs/CameraStatus.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) -- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) -- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) -- [HealthReport](../msg_docs/HealthReport.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) -- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [PositionSetpoint](../msg_docs/PositionSetpoint.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) -- [RaptorInput](../msg_docs/RaptorInput.md) -- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [RoverRateStatus](../msg_docs/RoverRateStatus.md) -- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) -- [CameraTrigger](../msg_docs/CameraTrigger.md) -- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) -- [QshellRetval](../msg_docs/QshellRetval.md) -- [Event](../msg_docs/Event.md) -- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) -- [Cpuload](../msg_docs/Cpuload.md) -- [Mission](../msg_docs/Mission.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) -- [ButtonEvent](../msg_docs/ButtonEvent.md) -- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [UlogStream](../msg_docs/UlogStream.md) - [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) -- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) -- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) -- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) -- [SensorsStatus](../msg_docs/SensorsStatus.md) -- [DeviceInformation](../msg_docs/DeviceInformation.md) -- [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) -- [PpsCapture](../msg_docs/PpsCapture.md) +- [EstimatorStatus](../msg_docs/EstimatorStatus.md) +- [SensorAccel](../msg_docs/SensorAccel.md) +- [EscReport](../msg_docs/EscReport.md) +- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) +- [PowerButtonState](../msg_docs/PowerButtonState.md) - [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) -- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [RtlStatus](../msg_docs/RtlStatus.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) -- [QshellReq](../msg_docs/QshellReq.md) -- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) -- [GpioOut](../msg_docs/GpioOut.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [VehicleRoi](../msg_docs/VehicleRoi.md) -- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [PwmInput](../msg_docs/PwmInput.md) -- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) -- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [GpioConfig](../msg_docs/GpioConfig.md) +- [EstimatorStates](../msg_docs/EstimatorStates.md) +- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) +- [GpsDump](../msg_docs/GpsDump.md) +- [LandingTargetPose](../msg_docs/LandingTargetPose.md) - [AdcReport](../msg_docs/AdcReport.md) +- [ActionRequest](../msg_docs/ActionRequest.md) +- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [NeuralControl](../msg_docs/NeuralControl.md) +- [UlogStream](../msg_docs/UlogStream.md) +- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) +- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [RoverRateStatus](../msg_docs/RoverRateStatus.md) +- [MagWorkerData](../msg_docs/MagWorkerData.md) +- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) +- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) +- [SatelliteInfo](../msg_docs/SatelliteInfo.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [SensorsStatus](../msg_docs/SensorsStatus.md) +- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) - [ActuatorTest](../msg_docs/ActuatorTest.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) +- [ActuatorArmed](../msg_docs/ActuatorArmed.md) +- [AirspeedWind](../msg_docs/AirspeedWind.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [FollowTarget](../msg_docs/FollowTarget.md) +- [GpioOut](../msg_docs/GpioOut.md) +- [IrlockReport](../msg_docs/IrlockReport.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) +- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) +- [Event](../msg_docs/Event.md) +- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) +- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) +- [InputRc](../msg_docs/InputRc.md) +- [FuelTankStatus](../msg_docs/FuelTankStatus.md) +- [OrbTestLarge](../msg_docs/OrbTestLarge.md) +- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) +- [CellularStatus](../msg_docs/CellularStatus.md) +- [GeneratorStatus](../msg_docs/GeneratorStatus.md) +- [Airspeed](../msg_docs/Airspeed.md) +- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) +- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) +- [GimbalControls](../msg_docs/GimbalControls.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [SensorHygrometer](../msg_docs/SensorHygrometer.md) +- [CameraCapture](../msg_docs/CameraCapture.md) +- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) +- [Ping](../msg_docs/Ping.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [SensorAirflow](../msg_docs/SensorAirflow.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [GpsInjectData](../msg_docs/GpsInjectData.md) +- [SystemPower](../msg_docs/SystemPower.md) +- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) +- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [MissionResult](../msg_docs/MissionResult.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) +- [PpsCapture](../msg_docs/PpsCapture.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [EventV0](../msg_docs/EventV0.md) +- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) +- [CameraStatus](../msg_docs/CameraStatus.md) +- [VehicleImu](../msg_docs/VehicleImu.md) +- [RcChannels](../msg_docs/RcChannels.md) +- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) +- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) +- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [GeofenceStatus](../msg_docs/GeofenceStatus.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [OrbTestMedium](../msg_docs/OrbTestMedium.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [SensorCorrection](../msg_docs/SensorCorrection.md) +- [DifferentialPressure](../msg_docs/DifferentialPressure.md) +- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) +- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [GpioIn](../msg_docs/GpioIn.md) +- [VehicleRoi](../msg_docs/VehicleRoi.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [Rpm](../msg_docs/Rpm.md) +- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) +- [SensorUwb](../msg_docs/SensorUwb.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) +- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [SensorSelection](../msg_docs/SensorSelection.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [PwmInput](../msg_docs/PwmInput.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [GainCompression](../msg_docs/GainCompression.md) +- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) +- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [Gripper](../msg_docs/Gripper.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [PositionSetpoint](../msg_docs/PositionSetpoint.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) +- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) +- [Vtx](../msg_docs/Vtx.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [ButtonEvent](../msg_docs/ButtonEvent.md) +- [LedControl](../msg_docs/LedControl.md) +- [LogMessage](../msg_docs/LogMessage.md) +- [RadioStatus](../msg_docs/RadioStatus.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) +- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) +- [SensorMag](../msg_docs/SensorMag.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) +- [Cpuload](../msg_docs/Cpuload.md) +- [BatteryInfo](../msg_docs/BatteryInfo.md) +- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [GpioRequest](../msg_docs/GpioRequest.md) +- [CameraTrigger](../msg_docs/CameraTrigger.md) +- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [QshellReq](../msg_docs/QshellReq.md) +- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) +- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [SensorBaro](../msg_docs/SensorBaro.md) +- [HealthReport](../msg_docs/HealthReport.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [DebugValue](../msg_docs/DebugValue.md) +- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) +- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) +- [QshellRetval](../msg_docs/QshellRetval.md) +- [OrbTest](../msg_docs/OrbTest.md) +- [Mission](../msg_docs/Mission.md) +- [DeviceInformation](../msg_docs/DeviceInformation.md) +- [RcParameterMap](../msg_docs/RcParameterMap.md) +- [LandingGearWheel](../msg_docs/LandingGearWheel.md) +- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) +- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [SensorGyro](../msg_docs/SensorGyro.md) +- [RtlStatus](../msg_docs/RtlStatus.md) +- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) ::: From 066e8f7fea27391e3e839efd1a49262bd46ab85a Mon Sep 17 00:00:00 2001 From: Aaron1356 Date: Mon, 16 Feb 2026 15:34:48 -0600 Subject: [PATCH 800/812] Adding Light Ware GRF Serial Driver (#26404) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Creating a base for grf lidar * Serial Drive is working, need to work out distance publish * WIP Getting Range Data in cm * Working Rand Distance Values for GRF 250 and GRF500 * Review Changes * Compiler fixes * Update to date * small update * Fix typo and remover unused libs * removing unused enum * Update to the Documentation * Fiving scaling issue * update to the logic * [Feature] Adding I2C driver for the GRF250 and GRF500 models (#26425) * Adding the GRF I2C driver * I2C Driver Working * Removing a lot of unnecessary code * fixing names * Changing the i2c Driver to be in the lightware laser * remove the old driver * formatting fix * Adding Ligthware GRF to documentation * Update to the Documentation * Ensuring sample_perf ends * Updating Docs * uavcannode: implement hardpoint commands (#26334) * implement cannode hardpoint commands Signed-off-by: dirksavage88 * Update src/drivers/uavcannode/Subscribers/HardpointCommand.hpp Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> * Update src/drivers/uavcannode/Subscribers/HardpointCommand.hpp Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> * add hardpoint sub to ark cannode, simplify handling of hardpoint broadcast Signed-off-by: dirksavage88 --------- Signed-off-by: dirksavage88 Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> * voxl_esc: Limit frequency of UART passthru writes to 20Hz * voxl2_io: Added UART passthru * docs: update link for px4 ros2 interface lib python api docs * estimator_interface: remove unused getter * gnss_checks: always run strict checks on ground With the goal to never take off if the GNSS solution is not fullfilling the configured requirements still not stopping to use it in case it degrades mid air. * ekf2 unit-tests: adapt to strict GNSS checks on ground * escCheck: rework online check to properly report offline ESCs previous to this 09d79b221f274523349a029e63ab4462e41d0c1c set `esc_online_flags` e.g. for UAVCAN ESCs which specific one is online and that then got compared to a mask where the first `esc_count` bits were set. So if only ESC 5 is mapped and online you get the message "ESC 156 offline" because `esc_online_flags = 0b1000` gets compared to `online_bitmask = 0b1` based on `esc_count = 1` and the motor index is `esc[0].actuator_function = 0` wrapped using `0 - actuator_motors_s::ACTUATOR_FUNCTION_MOTOR1 + 1 = 156`. * FailureDetector: consistent timestamp naming * FailureDetector: rework motor status check * FailureDetector: implement upper and lower current limit with offset * Update src/modules/commander/failure_detector/FailureDetector.cpp Prevent Buffer overflow * Update Format * Subedit * Shrink and rename image * Apply suggestion from @hamishwillee Sounds good Co-authored-by: Hamish Willee * Apply suggestion from @hamishwillee More universal approach Co-authored-by: Hamish Willee * Update to the Documentation * FailureDetector: rework motor status check * FailureDetector: implement upper and lower current limit with offset * Subedit * docs: update parameter reference metadata * Remove pregenerated files - that should all be tidied up next time this runs * remover GRF parameters * Documentation updates * Fixing Merge Conflicts * remove @ * Undo Changes to parameter_reference * remove the code that will be autogen-ed * Update the Camake File --------- Signed-off-by: dirksavage88 Co-authored-by: Andrew Brahim <35986980+dirksavage88@users.noreply.github.com> Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Co-authored-by: Eric Katzfey Co-authored-by: Beat Küng Co-authored-by: Matthias Grob Co-authored-by: Marco Hauswirth Co-authored-by: Nick <145654544+ttechnick@users.noreply.github.com> Co-authored-by: Hamish Willee Co-authored-by: Ramon Roche --- boards/px4/fmu-v6xrt/default.px4board | 1 + .../sensors/lidar_lightware/grf_500.png | Bin 0 -> 110575 bytes docs/en/SUMMARY.md | 1 + docs/en/sensor/grf_lidar.md | 68 ++ docs/en/sensor/sfxx_lidar.md | 7 +- .../lightware_grf_serial/CMakeLists.txt | 46 ++ .../lightware_grf_serial/Kconfig | 5 + .../lightware_grf_serial/grf_commands.h | 91 +++ .../lightware_grf_serial.cpp | 633 ++++++++++++++++++ .../lightware_grf_serial.hpp | 134 ++++ .../lightware_grf_serial_main.cpp | 167 +++++ .../lightware_grf_serial/module.yaml | 44 ++ 12 files changed, 1195 insertions(+), 2 deletions(-) create mode 100644 docs/assets/hardware/sensors/lidar_lightware/grf_500.png create mode 100644 docs/en/sensor/grf_lidar.md create mode 100755 src/drivers/distance_sensor/lightware_grf_serial/CMakeLists.txt create mode 100755 src/drivers/distance_sensor/lightware_grf_serial/Kconfig create mode 100755 src/drivers/distance_sensor/lightware_grf_serial/grf_commands.h create mode 100755 src/drivers/distance_sensor/lightware_grf_serial/lightware_grf_serial.cpp create mode 100755 src/drivers/distance_sensor/lightware_grf_serial/lightware_grf_serial.hpp create mode 100755 src/drivers/distance_sensor/lightware_grf_serial/lightware_grf_serial_main.cpp create mode 100755 src/drivers/distance_sensor/lightware_grf_serial/module.yaml diff --git a/boards/px4/fmu-v6xrt/default.px4board b/boards/px4/fmu-v6xrt/default.px4board index 395151b8cc..2f9d8479b3 100644 --- a/boards/px4/fmu-v6xrt/default.px4board +++ b/boards/px4/fmu-v6xrt/default.px4board @@ -19,6 +19,7 @@ CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_AUAV=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_SF45_SERIAL=y +CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_GRF_SERIAL=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GNSS_SEPTENTRIO=y CONFIG_DRIVERS_GPS=y diff --git a/docs/assets/hardware/sensors/lidar_lightware/grf_500.png b/docs/assets/hardware/sensors/lidar_lightware/grf_500.png new file mode 100644 index 0000000000000000000000000000000000000000..baccec33a3ed5b7c4442334cbeb8389e420ecb0b GIT binary patch literal 110575 zcmb5!V^<{%pg`f1?Iyq3u9I!swr$(CjmfrMCwp>Dwq29%x*zTjxF7a<{=|+}QjkP~ z$Abp|07%kOVk!Ut1PcHF_6HUM008hCXjB6L07y$=d0_ycDG}k*7zzLYfVrwjiU8{8 z2+jcj0GyMQwkrUDfcC$E1)3Qq0{{>JB{?;5Nhdi`VWH-x1}+XZApySn`dS_?_K=`J zIT^`@`dVdqX<;FLE>8AnJx(ebQWZrxaS@@+^wip#s=_GCEpX z5@Hepe0*wZYCK#VIB4|sHKSh`zZ`9Zu(7ZxDJa?5*$D{=nVFf{SXuaZc^DWNxVgB{ zk+Cez&AB<)%uP)Z;jzWV#QyxzUznc&!dpv8N*EgG85k!%h?w z80hZi1_Dh0$sEau2{h!RSQ)9)Q3p>~BZT z<7|~`ZkgofYUrXRl$e^HlV8|b8PVFRuRw_z6XX`;Y3pVv|Nj1u`ahJ43Vn~T!kipE zKPxQ(PBl(3r=TGHgm^tuIfkmDgjg4y<^qrC^vbG4qoVYnBwtf&I?O!A_56zFGFw5% zfFKu&jwrgxQpwG1{$(wUqTo^^UjP6=@1~-l3ivCf#mHO+hl?k38}c>l3^Mi6JI^@V zdp!xuoSN)7or!90EV{3sY2P|s%SSs@2LOlx(qh7DUYl3BidI`zc#*Nu(ijovV(W+s%8LPj@!w5)Sv|)*bqtBM(DZxyXXZeE% ze@sRyy#f#=7f&V_Z&F{;uorTV;*g695W$p5g3Kb}8O2Ki3GhQ~1J|zIcit14Zg6;StQ=ua7DqzA+5#6R7OjYmnbh2N~vXz4$%ZLt-OXsGx?~t(c$CudN>3E zfM8?#Z+X9xtE#l<@#0OsPRUEPJ{NbvkJpw#ayB_ghSk-=CDbWf4juS!D^_egClnw= z38TT0C`I%RY)kL`W*8b@qGz4(9?8JlnOA-W6XeS5Hqm`FCtQVw{(q_a5cV48KdFLY>7`2x}a;3XVk! zjlBRkN18>;tv(k#Qz@6mW7j$u@0QUFX59>RA%+rfJnPIXq(bBvF?z2E{8w-?4lO))St)uzq11LquG641PXL6rlcYm zC7K_0(Na_xRSXOa<>ApIt4cw^l@?PYBO@;_9LoyOxZ`fW|LNSCRI$=TWB7wd->7Z% zKDVh`{yhb&S`u{aK8a~iiv-HsBa`$HAw@A=;+n?o?X}(QsckQ150zv@wDF?f_x4c1 z@9Pj@PRUYKGUPRIWlk1TT2z^TzM5P-F6zlM#P7)0`C>=;HQc~D zbjv}!oxzt8`zPJNMiQ$TBN0~4lZ?|74H-Ov$l`|(WZQgAddD|TJ!Lj7ZTA0`k5G_Q ze|Yg+iScM(U&ik5qwSNSVHd>FEelv;RJ@<8{5f^&*UUsuZ0mKG?}}{rKw_0_X@Q2} z`f!xvoNEn_YqDh~RcTBbw9o%uJi7EOfVik6sT8(~$Y~UzJ*dsoz^Fa@^h#NM==3$nkIP3#4Y2R4j!|XrmnUg&3ZyJRav0yIYEW>aBRo;_;_AD9C0e`fnTuI#NG1I%VVz`+r9jvd(S13 z-Q~i3TwGin>&&qwwo(AFJSn;%d7r6YFI?v5Z|Y9%t>o%RLp^IS>Up}}P>tQI0=@TH zcqC*_Hu$Bcjk$@6agWY!qzEhtg`qsE6P=+;qJZC-(P&<)x?~D{EP)m`X?)+NoeZvr zXK7Z0-HrXVot=7TMiP^YUsK~(t3lmKH&p3Qb@TRg4-ZR0F2bd+SLp5G4I`uhG} zfsUv5++?5R_hl0n-zi9&LRW*orkjI#KN7E?>`#kYxcT}0-T%eh-5gJ6 z-U{^kz81^-;L4}l<6L?f9e=^8{L%UNU^f=jWcX$s@ycXy{@m0I=Sa-QbJFZk?`OqG5&e#!25wFv$nGM_OM zZ{F9FSvadRHio(Yr-@*GJVQkW0YG^L5j~%lo?c#|?oOpiv;<^RpCcDikT}_IIr+Wg zUHvbDPa~WN0*;umgQybfr-5hz_Wep4TKFfpE_TIi_ErmbcXRfyomGWZTZ87{hiRte zUXpXTmH5m6?bTcqSiQ+cVNZDdDY0x;@Jr5HUcs;5Jd_37;McI@mN)(#{TuR?B8FNS zGa_#;DY@YKDoTq&;_Edq8*2@=E;TB3N4j1b3N^hE-ExYhoUxCw2newVvD3Df$0dWJ z(OOfQw9hu#{=GflM+Q7?A%)9VnLmkv7)U_X(ZqVfFu|eYd9zE$&OL46#Yx?@hz1pV zfmtRJ>#TC)4&>VgG;<+5IlRib!CbX}J$?B?!K*8zTe10%KnUDG&aFc5yMKXxRt-uQ zTOtw-g};sqL=>TR(!_A_u={tu>G1OYL9}X~o?uRx&d(}7of6F1TY#r}f1$SoNvam| zf54a_&O5i&y`P^u8VmRP3zDbFb4IHiHa zWPS@pvgV^=naOUC*2oY`sI)_Qts*c8izBGa;MXJqVOiv;QttS(zw49t~f_xB{PsiXto11up2XK zT97YKFySMpbICWilF;90t`3TtAlPnoe!G+xbOj2cy7g?Azl&r|jSwBXtoZb4R~hx8 zwb&YgGY*Ddu+`w|8YBdxv(!}RnTg}}=&`4|FfcWwfc9Yc*&t!I20?Yt=1)t2Uv^1= z;FGsfMbCp!hmP1~ukZImY8F+&dvtC0rj~7^g{oZ}t>l&Gk&s=YD2Fkpy~VTZ@nMjg z2e5GLBvs+7i{w9SrU38jO-;icKu;W{9u{PAcqrMHjQ=h+A~H7%DPH@-yR9aY5eq04O z^!y88kuc#rH_Ho#9AxI6-euJawp|;ldy+40H!0mlPs+j$b@Q>S*A-y@@2RWCT>s21 zCZFf&`5fiMrvf%TedYrQX(tV14dWi(@CV#2vC8*NGCk)D;#MJCbt z4JLd^QMj-IN%_Mkhx_sZBi zB(c(SQl_40Q8mdsm8;jW5BY#U$WsgOKmWHz)o0;)vf|&RdI)JYA-gm@a;AsH6mg9O z|JC8BTL<%gHG@OK*nztQX$`b8FPIdSRit)Fa2IzaE>Av8kH|LDu0PqjmXKYyU#;mP zAWk83$+{>KB-JFA3%=o2mcUFU3je^ZllQ`0rLhe3Vi?{9RVEnNrSkd^RAua~wXTWE1G^#y<9 z4G|?7@EIy!hAY#v`5x9&N+ZgAs?coPF$W$NF@;cijN?l-!aS33Ly$=(^1 z9~(*nB$MgGhLl9%UCwM(U>|RwpP!&=?J>7LE@wpC&O;1x=BxdW_Ka<}83CJVt{z9w z7&}XDzms#wul2Z-KQhlI0vk#XV>V6O{9gV}P77m@Rpso1@gYV3sS1W66Jtb29;?(l zD2-G_u|lIDn4)5tmqcdl)*bzRUF46ms064Exp9dplDx7CiT)dA1p_3w{>_iEwZXN7 zM=VKziZt!mV)*eVL)FTKu~;hNw$BkQ^68sw|0^)~;!B9{{x2kv_03?WmP?5208LeG zMuk2Pq{WfDv$46^|M;XpTER9*HUh7*YKrG9x<|~;=r|xh?*{~9!G5hYYpHT@sP2>Z zdiELkn5{~co#}ZzH6#$!p3p#eCt;bKoMGO<-6ZBd`|%ua>1Pv(MjK38KrCjF><$&65&<(R9=K`S6OCuSogIDAqYwx|cm2{|+qBH6qZTd!Nhin>w6eR_JDcN6bc zw7Z$~*wM|ZZQ36sC>ekMp(ViD+S!z! zFt!wzRKeBDmK^0ER=Nn;J5=%u(L~2+vNAY!GFCWl>kto>L2T0SY-dYMq}xr6Z6H`K z|BbCC)p+3Zl~?3sEcWo!chSq0lWCm{3!hbwz;sHEwX5g$Sp|MA%6!|Rd*-+q&Ge?k zkS&i*aEx68nZY69kYLqrCSe0}@S17Y)RWKa8GsrFoesUa^B2rsS(ixzSmuT`Ewumj z^@R?}u_7}RW1EIj4)`02sH}Ra2J~o(j-yy0@9$2NhuWUo*x2BPwZFO9>BHBHdJPwr z#~$lngK6leZnrJ~hb;rJ7HST{ppOkrEiLC;qcuwZfiRtjh;>sMobp1&mQMom}L6Ri~cagGVGDLD7ie;fvQ*u zk|SX`4aPA#xj#I-Ex6*3LuJ2ppTFuZW!odgY`zySy#fR47sPz{r*}h~iV0Fqnuf(0 zLvz5vD+Li6OJ2FoTnrm$GnQ@g1Kfvfy%$WQ2(pSQ_1%_z-jv(S`c+NHoL*R{8WXca z^f3JAk1DbTZIg#9X;y*FqeK@@Y)BSBlQV>3vNRbnY=YpV-S;|-y!s99wUO+t{%onh zq}!nJwo3>Tf|$yV>1rppr^*b!qWvdAw2GZ4P5tPKXTFuwhQjQB8-Hlr6`dz{g zq71#h#NePJ%I$-|D1yc#?n5|gVRPd}WKE6ZP?>w1id{i_+VDtE90a+mT)!>*_g$qn zucEAk>DHIArvGtLtL&KEM-sj?DtALLU|aoI`}#ObEKCgT*5BNy;N zL%eSv*weYN9FMzfZ2QFwPC$oQXmJeYh2ZXwN&Fpy>06LvPD4%kg^+20;^`jGKcSNN z{>!{BBUlhRKKb~|DQn5arTqK;kJEbsOPzJes*wa=hQh6#qdf@`J_0aUXz=oRW7Zpk zuemFiQy<0g_8olxyJ$5y=^t*ueSAdyi2Ui<>~v{qCOd5N#@ny2jb6H(O4j&Arrk~t z^|1=4!B_0`z#?m#MMYyo#kl!XArmPrbWyuOt{~r_NlgQgRKo#u6eU(Q9=-O`ZY`(Z8(;1Q|vMUz&Z_M;b>6Pu9^8n^d); zgN@P!tEI&7N;zV@l=x`ES1EKj6$#a*w(p zaDf9(BR?Ir&Oi35=eWHFCi(Ny)L={|K794=p1unx_5~x{MR;Jy6&k>S>v6walhU)r zqOv&u!30Exo6r-I`KZ8`EVMxTsFF(GBTTpM&chyH>Ji*oaLMAMF;B#TAR`XMPx6ND z8x-4EAD=@juP6?WXOeSLM-8yq51Z!bS9MF^OasKP4cZWB2*v!3aHg(0HkevG-*8o# z+Ud|p8WG3(<>FhJAr_FNnwElW^RI8y+@a;3q0V80O^U>8tbhJccaSKaj#b^~JVpLh z{Ez9WL=|A6<&Sw(1extj6Uk`fY0WRVgu3INVcjD1m8yeWqmaD$^2As*S&=fF(Y(j5Dun3=h&->*3%jF#yN8Co)QYuJM(!L;Vn8+eJ7`%xIP3!|ph8^OPT0?o z274Y8M+pIwl0x#jxB5Y7k3~!_H6~+pdCbWJV722i8Q}r)eB_{T6mOY{lID>1SG*!Hx8hP5h!o#MiNlxC2&|$%olfgc%qv;xP#HoA=<- z#o_2g*f2#WA<2&r+7O7@M25`ii$3;6Woph69EznHxpEI;@&oltjvaEU1o#VGUtIzO z?H^j_+=C{HxVrwjb)bNn`YSIYnz*AdQ@5!AG(OlO=Anhh)Be(tDC)`kBY)Q9DX0Ex zBPTL^>MZHPUAWpSjs;vSYYL<-O4+w)Ilwi9&Zkwp5y?ND972}W)i!-}ADo<`#gl^< zBrI#3XIV?gUSvIije*}UpP!$d26A*eDViqXCy_Id0%!y_yO4GFE-tOJ!&VY&%~Y!7%1@S5rW;v?e$4s)ic#j;r8ni{ zt`{MDbu_i?Z-Wh*@GMXX)r+tX>5x+JdQXGnq+~YMu-HMNHWED&Z4E6bi$$o19&#-b z!PnQ<*49JQzQ)(5Xxy>xwz>C}ZVpaMnjh$HAxj^;eP58lSC?!m)Z}i`Z|{8lzO>PE z(%M*GH<}roNkqkEKB}ajY9=`5Bfw5Sr@xroZv)4IwwSIPrI%%8O9%t^!}o~3SJX6q zXlR-V&z_4Tko&ADbu6^PdmJBN>SI;Pf*~CVJFx?sjnsE+*Sn=QthD3!fSMzMw~wI2 zN#EDJ82sdLPT;*y+vv(J##alYqRu|vd|8*#^|4W?lZX?e#gb)X>F=00H@5ioMZBJ$ zn4NJcl{K1FrXBhhmcdFTTeXyDJ#i!jKi-GB(bH;jZ}NABbRT~~dP@&#{v9h1N`mkp zbY7ED0=4jZP$OOfBK^t1>8Mm3Uce&u=;QhhO6GVVHPmOy`q_#2z)|vDK~5bPamnVz zyJBMrn>;Br$PH2PXly3!Wqo0mlnhkQIR$f?nc38;{{s6xP8td$KtCmh2oN0=G6=0g zqKY+^Rw%dD1fRGtl{FEd`Sg_U^dsw?LuN_qFjC_n9hWoR5G;9oR;4`glr#;>%q%1s z`F#>6Jv-@B|DoL`Vck9+%?!CxjA%XM7oZ;oMRdxf(HLJ1hg+jSIM2ihx?J`d)W+B$ zp;4+ z)A3i_Iw3rgU~Hm#8Jn7tFx>czZ?~FzU~KAY2 z8>`Ka!f@J@#j+xNw&U5NrAkv#ktFw>^QFLg4E`3gU3t-{>vZ)nTe=AvPK>Uh`}RG-aHr2$70ztr^T9?C^>>c0Ua@+EP{OQHJ$CJ z@z00}o31sz+Cu9(6m+zpN|;%at%B&{kF#vd*fFp?T#pqclKbCIGre!M0mbmrV#fSh zW5us*v_nc3Is3P}2uE3&>Nxbjr;m}rSwDjVr?qPMwnMYQ{aZ zL`~wLSnyU&Dv3pFGK0;3Ds&!xMj8@ljxQy9^B7VCRkC;`khra=sHoa9Orfb~9Wr9? z&^d#X4!`_7fOO!L*TZw`l<_bLa`;if9oZ(A@Gnr9A2eFeI}h2q1X@^jM#FHzhB&V; zChkrM!*FE+V!6ha4IrP2gCnFNmgMSzrDEg%djZUanQ6I|aIZ*4^1qk(Z5%;?g8fpS zWItrL@CF!@56msVC&V3K%Lfeom3g8>6gdkHJ8B6f9&I?ix(+HD3YLKeO)I0uMarMa z(BEk!@GoVg&=NLGOC*q2q7jtjZZMGcXH`6-e~Zs!5w)=_TsL=b`Ps{RenR;W*w00+ z>TdmaZ(sXg`4h3LW@RTB(A_}JlJF#G1vI}lq(_lP1ftrDb^pR951l=Gz)vvqn*>K& zWGR{;oCnN6j;G6MpN5Xc;5jR5(WpCCcJ_m-w57W8uWZN_qar!_bfEWb z*XQ4ARoHRt)S`{T4rat>7+q851us-j?>n)?1ZqKun2rs!pFL91Z*{jh*1Zjj zOzgIxh1hTPpk82*Q6>#^;^Mqc@~Lu57;=QSli&>6LKj3R{fC|8-Ay36Y3{AFFqk`@ zkVO>mhR6z=iB@9fmYBT}Y(C3psLUMJoO0AiGtyL1bsc)S*noF-Y+^!XUP|9TsE!}) z66XNWPgczns*O7N-_${m{FH(A9}6)6BesjbP-%Fi))r`7*Hi6PxV51$AK_psJj7sXi=N3HUt9~dSz*Cj;MrG z1Wmk5_QhU_$;IeOR12DsIB1Sz6u~v56=Ff#kWvnZ(L@u=US#G8N`*`#pu@+j2d#&w z9BCJ*KdF$m`+E9r)q|IwS+_`(f8>-?=h#cT0Gpc7we)p#EPoj#r2!8{kn##e*K`Kr+y#~TF|%pAf=>TxLMJxD4r7aJAI6YI zaAZxQ$HkZj=2Ej_S_b;oQf3Q&od&8(zl1B``tRZBFI6lC4Idxx!QxwmUd}p|{F$Nj zzX%umB!CD)bM2 zxKN_s)7M{TtT?#a0Ub4U*}DoDnv}GP@D8^hqi{GGx4NXclc&d;pJg;M?>NM`69Pm` z@|DYcNKha4LHp`NWib`YI_I}@GCri2{zvl*}7f^*I{*CZyAs0$mKjZWzzw# zL~5k|rH<1qoNZ~48LCq`9NPrUFdhkiSmw`_vQP5)d+>X`TZoYW{~UbC3t2c)&5WGaY(H3xTEk%STyP6ssg?L1wX)*G zTN>Y=y<9`jNHi-e%OjyNFxY$x?(q%{0ri~Km|o#@{{v&a(AKS0m!aSoA+kh2jeZ1w zKtx5nU_}O`#^qZ)_t$GVX%<0rgmZJAp`V@T>QG?c?+bi9KdV!hex^ddy!i2rjZ=O& zQ$~Yd$svRMSBbxVrLnJ@Mc{@UTGAEZ_B^w}Mpg+SEp^%aY2L6aQ=w`5(+ha2p!wCm zhwR8z#ww*IoW?>@>wuus-e3$zx?(jt`<9hglkpqZY0Y$&x&o+S(8hi6unWsH9~p{< zl7fUPKiG2QH1qC@g-5}gzg5!aTQl%tr zytB%C8DE%ZX?4DP*AM0pU)xwDZ*8Ycqr=70j%i|J8&lpfa1kUZy&*G$yU)~5H{ro= zKYx7jUOLP+iP)P<)ab!`-K+^(vK&h9X=@xE!X^m@18Vz}p#>V!wI~Jz?kLgVXd~Q#3hU zqNLgkSK&x-3EoZ5yd%zkW9B$_3$W2T5%yttv}UFRUdQi)%+lOY=BbU=we2}}a3X^l z&%5ifizyRJO3h1mCp**+TI@unE6%$As);pOgb=3|StK`dq=^;huPw5*|5}+oE3wT? zPun`vGgc82t!-R!=z#``NM76RW6eKPtZnC!VakOxe;7TdB99OBe)oLCcx~5pg+Mz` z08FwJR|RgdMPs3La+|g%QwwljrmAV#88F5XwPQ(`65q7W9S1&6&esA19@L#|3q-R= z%HBx1jYMj!xmM5|)2r5Y`^5K%b&~Yz(MY)x${XGse)istI|nm=H>+J-Px)uv+4n@$ z*G`w(;=tsYx7rMln#4(54%=DC%2B4%fTtP}i$Hnl+xU z@T=-VZ%b)X4UetFBFLi}pkPElBBCToADJ|1O*Xei@UWPw@LFK&x|hK6P@}yr@xKbO z8q8DuwQe4jQUXfn=Iyo9ba zlShZi*XAJjR2P8q2Eq_aIM?lwt!GYSjvyX+1)f^%DS~p^DXVra z1}vffeEugC_d7fND8Vuw`nIl4Wz>&`!Ujn2BZ3m24e9mJnIpZ4{5U;r)$0t(ifmd! zIpm8iD;KHT)k&4cLieK#$qqE$LM3Mn_e6Zt)K)gr4gn{M@!!LFFt+Wkhih+)U7Fmz zQqv`^)|K{PEhmS7HPbdUNYKOtLqTm7B_7w4W%M$D4f|32yU|#_(c5hBh%81EH8|sWPTi)%$A~qrpwWFmRwJv{0EyBS`K%PPf z`;4h$nY@5{b0N|hyH`E`_%Rz7ecG;fc5{MV0ty=;$)5Kse66^H#RCQ!J^4g#B%rtC zMYbafG(rU9IGK^2T(_a)Q`{%g1R`<-y-R$4t8U7A)IS-~vS+u-om{R(BS^(28oMC| zLrLZW7`{JxQ%}cAjCx{B z{?U1T-QDg;5oz(3RmnCYg;iH%!!pvhlOomFXd6%E{*ao}zB;kk8uT6P791chOTVkI z8Q%5d$z}gaopgeAe79WlTstSMMkGGOl`4UB_#R+lH(;)h+j_rvm*K%_zovy46E>^O z!G9cU#K%y=KqzSmaiwhh;2Qh~Ec678#kDtg&|^(JiTOWnd(IG2Fv?F3?aD3`*VhP;J3;v@A2RMA%CqVa+})goZ4GE+(9147eV?tK85}8+ zSA(V3W>+fzlS~6&nwHi#mnL}dusV*ehKe^DCcqr`612D_bW&O3mQ1}6wdZNz&)Cmp zNR8CZ&hEj74b_!eaQdi8)s{%4`vHX;1vXCL@PDlUS!xhn#?I8_`*F;2mG2vg?veEj^>VM#^Xob1)6r!72 z=PSs0rCi0(Yo^2DL`VPmF5bK&0xyk{qFn?$6KZBI;kMz!FIVn0BvuJH3xiOGqQ{Uh&6*H%a9h~h_Y&tNaW{y zz&1}vOEh<%Lc#n`9Co_-axWK^WpVs_8)*Z``4`)^7GgXb&s}2@r0t0?qruMkmD+ZE zJWv(1)_*Xa0N@8BuOmxV$}eT9KTuCvmih#3D+QG0HCTZ^t!Y*UyFMv<-;$!o3J|`H zY9>;IC#`TA$c#?+ln@-?hziJC&UQURjx9Cy1L|~n?X-KHno*VAAxvH>;`6qD?mQs2 zH=liCCv95n?5}m~K8@Lql#yE1F|RB2#BI7&MP`L~ZVC6yLVshABe#B>K3{Ha-QLt! z0A1u?w!nYk?dN4Uvu{1Skr+r}izq0-?6FnH%TQsxutR56oyQ^2oUp)%Y zw84e%ckBeF5D^h(6emy{P2w;HV!c+i5>qj4G@X!d9y7HiN*l#Bmz>FS)I1rYk9n)p z{BREVy=vTRM~$BS5shzNfjE|kr0kjVM6FF3{-=)N$`1prbAJ?QE8pbReEaZ=M|fwW zLa}gKMAN{)|KHX?f6w*HmWkH5>s-zXLCH?5`Rdr(%`I9s-szDC;)zomGB%&qo?BaH z62Pjz@a@;yw@XOMa@V5;t5h84k@nyir*iZ#>(66(?*!6d(Yd(aRv6A*(&B5!@a(4f zDc9?xN2t1Gr7zS}PWv4m{X_y>@W!889eUndq%%LqzK(T07$#2KN?;kkx{@t@pMw|3 zbUWI(nNup`m%{5yp=Za^x$|S5nVq6@;dC##s_dD|((IV9h7%#MlN0@=FhPQ>@jy(a zYmM@OdfswhLF*LeeZ>}lS5ZqL$+BK)X7ZP+;yDUIP9$_Mq zYih+!FgcOrg8Oy?qRXN9xZM4YDRW}3Mrs$afJ&%l;ZYCX<93olWHUcwWm&#>e_O$| znglu-&>|g|uiCWPSYD-58BSJo<@bFYoK{mKBja>h<#R~p*!^;R)qDBc{2KQSf_|j9 zedhIRRnZBeqJVQ}DFo>R7}Nf?pfTTDI{Mge_13*HCpAjJO|T*oNZ&B) zzB{SJ=831WEQ!li?|}n+qFx7U?jMfv`)&gDCSho?Qc7{B zg2!o-NT%W$sJ-mST-R>mi>hYoY!W@{1wEaQfj}Ulfq-A@eo%A$C4@OYBE-f88>Vpy z>iT#RmVU*&{ZhRmPeK{CmCt{`LZ{o1mxmc%{Q7&`7WwtxFSt;T8plCW= zxf2N@{FJTTVg3QA&Ou3pn~wAo>8Pfxj(o-f*M|8>6kmGDsich{?C%8ct&0;cY-(r3Zz?mq(-xl~RN|2ZN|QHpJa?gVEJuki=Br{*Sfgn=$R&v80d%cYEY@_VD2$Sx^fx z#pKzCrrkVwgcq~L#YC1nToN|A!ez?v@!?eyy51aNYBYQc{X3t8)hD)_{RvUPU$U&- z&u{E2Ae{2{M?W#JT0 z;IyRB$+@z_2tOQu_8WXwI)bQxD2~j?J{gzexmqYlaoGH4|HejSYpR~Pc)2?t(XBjI z#i~M;`oFW2Aq4loq65TceHB#3;gQK-kmw+USUWQkJNpBxRIlUk#}FR>--loX@t`V zwD$Yns>P~%hDa+)ysd=5zcKsCsR(I~Nv*Jvpd)m4M)wiG2=XW^B%!}?o;`@(SX&6U z1_rx>IaK5M43Ej|dk(xctnt&uUSj!xS=`j;e*e!?OQb4GATeSpo}2I=6!iU@v)!98 zQMknklcu|nVtnA(WLv<%cF22B)6eMCn0Vwl&Qo(ghbYJnR31UXVpOB!GV(&H7>-enxvmCV?oeVx_pB17y}NV{f2 zo9F3W3ufhSf%~OdU-u(C+Wy5NeR{+=9e8Y>8$A5%e^;o_c1)XY`2P4e-bdt2K@_&5 zV9JLIyS{BAjf)8kzE77Z)!s1G;6J-pwBW1MX@rvqH-!!aXhiDUqLQ`EOko=aXz>C9 z-X|Gkr*+}QG3oOHXcw)H7-`OxDUKc&w~@)!+@#Pb+^o{~+t+w`c4rJdUbiqJ zzhWQJNh$L);z$?ZM~%AloFhDP&RP2vMHHoibQR?wxyH7Q$uZi=8c}yAL66g>?pOM_ zh;bAt&BU?Y(CbRO>-B&_Kxk6_U#5qQ6)AIK;-c)xG#`j(hb zY)-M6=+~ig=0%%)HlY=xF9Zj|iCs_B!xk{nvus;7Tf5^}`ua+5#Fl@BM*1^!RO~a8 zb!LoAOo4-ow}pj<`uaKcze^N89#LRf$pk?Nt zG{E$_MCK@u5~F#0cs%jA5fPzNf2h0POZ_$bY!)RBiod=9#aD%xD=zh&O+!CS~> z2@}Oj6C6%sdb0;9MJO7(T4jkhY4872J<%0meZ;Gu@kGc?or0?~ecTzXKX5Gw3sqnBkO5IXmoT-j+uEHK-j7Qsz z$2G%w|99zD+S#j5nV?-F;?AX=&+qfy$%9j(9VhxPq8QXr-^bWDM;{-G{uhRhgc>wLu~=EMXz(A)8b9}5F*Y_e-@9&>lX)<|6?N|~Wdr&w2*q5{-3LZvQN|NJ~Vi z9bpe?>xDBPcb|?yURvsfguj2EK||=B0%aPr5cENd*1sn;&6TA8yw*sH9v$s|t0)%y z<^YM{Q%3+yig?xFYrL$D^+;QA|K7*tpbbr!yKfN1#Yu!f{6_*{ZK^|TD>Zs1@v<+T zwLo}{{`0W)ij?MdmP0i?Nj{Czq9Kz^orLR$JUMyuO%i4brI@82M3#riH?x<0LCNp9 zDMZsa&XZu}?I^dle|y_$WD^+@H*CY(c|-)$Nezk3!=*#{6obBC#cI<$Y!f7J-mk5* z??P};n}s!lE~_w^R+WWkfj5r9 z5m;lVF!^RvPTE|&<8?Fi9!_cU*Y2vPr4Yrqx+mT&3BEw}xX^#mS~7C>qsaoqPb&U6 zV)6fifGHq17Rw16SWFNPzB`AX6FivSAY*)UdhLPiuwnY#2_?f|(miVzwRyN&NWZ~< zwy8XzoLRB1!8bC zvyLG(AxS&2_?+$waxiXn{hNY~nqNELK%~GDZe207@hc;mAB$m;823gAt5gCr>DM)z zM~g^yMP^{G?BniTfW~g?e1o3XeyLbImJs0UnTI*xdrN}yv1eeLI{I<3f+LwL3k}A` zj1Nx&3+57_#b&WDX2FS-aHWO^Whde6k;xni72cpN*b9Ta!WDE+n>(H*@<{OqbHe>U zr1R84+94-3;d!RkAwm9d$zvQWrIIZrVkt5LWMo9P)6qkm@A(CRUu$xd*)u}7O{C90 zXstN^0}Vj(zdAs%1#hCHP-xMd-y;w7X0wYmyxr?#1yFM@tD)nCVgcrEBoYb6l4L~r zPeKfieTEum4U$dnf;S3tDgA;M3j^oul?)vwCncMC2psk>-FH}Cj@^lhOj@{U*-M4Y_6faNllIO+E%|Bd6%x_qO1oH+- zoR1MOlD)7mIs!&;ugSRUW#l0lW==JP6WM`@jU{@RJs_nQ?oo>t+!MtDw58oStU)_w znDOGqW}3&3K-R1)5Kb90Swl>z01YJoas*H^<_n-{5*nkDIbRkeg%;vw7g4r@KN=0& zBN$9*GP!hm@nWRlmihz8aXn|U8wVw>_gE-kqs38zI58($ zaI~&AWcY2X*4(Q#c9DZar^ReGZ5Z+fkusr2iRY<%Kz9e>(xn{p3EIsav@&~b*02XY zp7W>I#((nI!ULT%uiKaZ>Q7XPxYE8ky#PMGWmUtl%6?B~Oc0%%@=)0?*sC=BS^U

oX6wm#EyiLWv&w+FKPjS$r@Alhl~25) zDA;ucTMJK5Pfbr7$U^}}HBoDX8E%4p-I_XaSH9sXgthGGOMgq{p@R3s_=PH zX5Y$Xly*L@I}t^7u^>xUUUIBF3=n>swucsNr&C@Qj9qyVQl9R z*vy|`g=HKoCPz!l!VX@5*yzG?+x$&M-L}jjYfW(I2stItzg;NbbXDfW76QoJTG*%aH zEE(WdH5j0+W62rju{G?gi6ledU}#W$K7TB!vZRPUa z7t4niS68>Ebb(pm<8$$ZFOY6_tUS@h_iz67#)X>9Fw}HcO1t9=Mq1b9c!IDOkM#jC zgqar((;#YiHlX098n^q30ssIY07*naRMXM?)C)~j-9vYlQWkpIWudez2riw8j4=a45|bD*B0~~ihy)8tE>R@oC7RQC@*txU zM&ZpxZn%SLM-@+OgLCjf2 zRjz*MU;og*Qex$WWgJ`W^QU5AaAC*}Rofb2gL+f#6qK#J=wII2I~KBHCg!%n3uV>M zhy8xh9Fp1J{~&tM?tT2J%`Qb`%#^^i+syEo-4{WNkH_Ep#av@LV(0ZDp)-bn=!#3*55z{*lCn-GI4g^89*WJ5XvGl|xRyXOLVB8wU_gS*^XyMB=hNb7{Cm#lJWMl^|^4Rrdtc}zhL8Bm$7p)z#WrN$&7f)kU|QI*P}3rgM) z5u`+@2#N?2@)piJI&a0f5H~#CTGh;8`+slF&SR@0j;t!J(^jkBDjnp*5u6*8jjW!< z&P${%V4Af_Wym(Gswsu{D^xa^7|V ws>I{lN?HD^eJ^9~^!NuKy<=`^*l$&2VOH zMwHo9sf^wS!{Ilk*z@NVIoKYnL|Y-%I8@-~lAIc(<}yQNBh@@JlP6~A5vDn@OaJEN%Ly1Z3f}e@zyl6PXFH46hpH@*0S_%24206kCbR zrd&l#ZHfmSus&#cI8lQdW2lV8re=0e49C4X;ES*`g4P`}a&loh^2yDGt}lkhn1H$H zN>_$WJN(gGv01l!`dm}PfJ?u1ohg+r*Jv$#Ah^1iEUCgOLu$y0QQJg}Xe>h|DGW)> zkGMRO1~Pwff1p?97iVXL3=lKA9^j7oFk^%ILS>VQ=2#XfeXFe9pa@~m%%PV z=BHKUL@=RK!omg8b<(AWEHhSOh!-}=2$*i&0ES+tn$JFZJg;b#FqmYgtt(9{T?L}> z>t5*fdbV_l17)fqG@WWDk-@=BdvtDxh`Fp#pbU4;Du4L;b90B;NAxQOdprjJL3iHu z|JA3`4AY$ze_(l`kxqs}p>#6cSZFNp+!KL~w_!c-C0_WNg*1Lkve8HjawrWL6#IvS z)Qrh-0L052v!ln-ED29)e)iHv04#LICV_Y%R!F2RZjGe}+8RRJ_RKB%kNjX10y55R z^z#KW=)K@)a$_F5#+__=$yF}AUvqYr0%Lr{s$%LtepnQ{G;w4{|I~8&SI6OYhs#Fx zR3)B`XEwNfHd*Pr2q4O^yGp)oPs{Yo$!?d0=(P>s<+~*dir8R7Py=+OUkfir`O^#6=?=iKO8vJWeL@Ya2!;40 zaWUauWGy*RhPwi$SYVuk!~8%|CeXw~Q0BmK>#f1tNG>=1$8t&K48#C2^z1skFOuH- zTUcn7mzW&#{7t-d0+#}rTSjKkFsn7|)__>k#0Xknx|Ey@VPgJC-KIo_fqBmwW8fkr zhF=d1vYI4j-!b7o*R(83OnF2jmgM8>R$+I?tR6;l(VVWH+S4B`}t=w1B1|@H6*5G<09b*asigBVQj6gg0m7` zT|oH>0VD(n0)*R!aoJ=9zb!<63MZWwVnc;mm_Zl&unp_X>f6|Lc4YN4J{<$MrkoI6 z0<=&jPHmj8^%}H+9H%jH;{~`iJ5L=Ld;r62e4O{fxW~DUeZm7uB6l4-M~uH5cWvAK z(bXvR8!vB0a^*zX`5>#&x^o~V)0do>pegLpmO#)MRgG2TIGe*m%nywy58~Thcv$m3@C8CKgw>csjyv~H zevagd<)Q=!j5;KShDOrd$eyszq;+N=hGyWglpX{*n<|J98dzwF-Q9BJ&)*x#nwKMc zYbY4-*BvC|6$a2mr#f#5#1R#adHYyzaaL~D8yMs_;hNkYTj78Pt~D!`cgv3^<7kp$ zAz}rHVP;x7IsF)p@~YtI?rOE9nuy^l-~Ienrgg=wBku$<-N7rqR@Z@{q)Kyyl8j`e zW<7$Llargbx4_DO-v68JGU@o^kNOk*v?j;Os%(_i4-WU=OilNCQQOm(FaLg2*0k6X z{^HjHGk*U{yo8w;U1ZcIS!J}Dg&0kPZ*bCeWg#@${kD?xGX1Vm^ofNfOCNRE(^l7qGx(GtOx zMmeI11WLF-JZ)7tHAarpF-masS{in4Y>UBkncFw9Fo38@kBU1FQS;)}_O{EduWiNv z8h9!AuUhE^b0sYn>PZTw;!*~H`%ASOr$3=(fTSKKYTAD?N$ChGt(eY3>SLc(j} zDWg^@nNGc=9EgINyj(iCv9VRzQ;x2fn7-%dr1PrT=P#jtwgexz|<7o)5hT{S3)v($SA9Ev+F}iB(Y@kKc z**N($0vg~O3j>Up^UD{b+Mk76<3ehj9!lTOIc&H?xz`J1aTl0+p6&6l80_e$8xgbP z!~L&ta1&rUlFJq+-7!tYkv4E$ggFCq$~Sy;sa7=lYgOrV!l}JH&ma~f@Mug?C)~Qy zyRA@WZuIQGj)YzUmS3-rP?A9{(Lt%}XWa;`b=i~Q?!~{hl z%9lt;`K6(IE#7U6eTr=hWCUvJ)WC}?(gQo&QMC{kIRO|z4Cxp&tjoL& z;y99^3r0#eo2@|LuYbGxhmUgN%%`8&*aGH>rEtEBJ7|_NZRVI|!v)~5=`otuALigp zJjdLX1Y?D0#u}w5X%ae8BtiKBCK{b-m}=Ne(;uO^oP!U_8Yy2|HmL^5ab52cct2*S z#yK)FJmC$7+<@jZNVX;rLaWs(EPhE-FvnQta3ent0Z1R0PruZ05u-I>fIrlWXk=Q4>5 zgo&uy8_^tMhCYuZa|B@-0H$jo=1|8C$7Reha}RfRw`<#R)-f-h)$5&3T?6Is_2-*v z2-AnyM$vEvqlFyCVnyz(!w|Iqh*^}&D`gsgUMwg3O)|N%5HckE>EIMvbUUjlOf{t= ziM%X}FIjTWACc4 z5=THsglfn=M(74)Q{hP}w98vhJ2O`87PPpmfU$y!M+kVsZZx4G)gWRP)y!f_nmN%Y z2J{zezU^_LjRt*F3T9|<6^AT0o6=2Ot8(qyjiI}@h2$9?8hYXhl4lN79Q=S4DIK~w z8o)ky8V3>8Gz|@ynr2`|3uJjI9y|y!WKGm}MewQC_q0t-yz_Ec);Y3PRCWqTGSWWmPo8bEvHkK~H6Ip$LtRSMdLcELt36!~m+p-~ZdK~vwP-jK=Bn#bc03Q-eg z(9Bd6BYzeVk(#1Z5(!2OuuVcqP>`l59HVi7rblQ!b{eC`>9SgCjC=qbhd;EmhEzks zMn!>>k}SoV92YIdWO#D?i{YVL6W*|H zH4VpnAliaAY>1c~%}kdyaoPej?KW^;PQ)eoI0-cdX0Xf4WwZyl z`uu24J@3r2Mio{X+?P4CZ*kL@#hQLU%@b!M4B!52BiLxrz6ylPbv)O`GIA;A5Bee% zk09H|{H$A%9M@wx9@C8*jI=YjSx#GfljC9yyzbepY9@gD?RogUNi$Vx9ilS4Z)%t> zgX_4X`!WeLyKtGCH4*^{3rKzwBM*Ci!JuxpdUVu%_x3_ae`~FuAhTuIqj#}Ifglr? z)%pdF8PnQ(`+Jc^Ipdq2##h81lOie3ZD8wmkt4HW5p88TGRaU}HlRHw$wU9+@tmRg znQNk%C7+VUivRI1IIH>D^VPz#Y^0ubd%%?sulgaja)e591_*|xUpkOo*lNkl0oSn? z*oAEH)70pA|Ng|JU2h;WP_wWA(b>GNYDC&OEg4dViA7|dBZ|nUG0%`K0RF#l*vLEU zRvLl~JuXQaYXdY+r&%Bqnu#f@Vn0 zWs|u;Gbwqf{f7|aQzDbs-8rHBa|Kn?-e`mx9XIW|c=yc~lG&ZA8i=p*Iu(&E!*p4> zy0p%4fmOb7*E69&UB2 zJe4!PQ_HAp2QOc}Z0{YMob0cc7Nr^2^wUX~)9d^77_?s&)e0Z1OBQRjhgFqLGALuR zX9E#K$-;6ji6jybfB?iS!euZ644%#xR>)Jdnk~tk91y@VOf^?Npop7cZ)0b!+QFSY;CgZwi znUl6~6{KDr?7f8IGCz%fiShnObD z;cGj^X0yv?G#=1*`YJp)<5sy04D$mB2Kjv?9y@?T={aHX4Hh{8aUqjxWq%YoMs-G2{gU;+2zt>G}k4jvCigjI&B{RYy$T_uBFp&(!4i)En!8CB|Piv<9vMg zE_a>{4H46fHi2PUtz1F!dTjJfcsx$;YYtF9pZU?FQiOfa0>642Y@MFV5OO9vtj1rSeM9IqJ0eXQftoCB8~oWK7G8 zjCmX&lTqW(SIYchuh+lLE*Y`$FTN@U0~XaNxn%-sgzMWgOQmKjpod~21Ff%yfC!?L zUyHb7|M(!f=F?B$8eb^MsvD=rIB@PB$&v70DD3x)4sSg8H=M8Ospo8LY)~O^+Ue+_ z87tKYNi$Dongl8Shp90WLO$O)G3KzJ+*-VP1ndR~-E$z(aL|_&zDQ{FNSx$xNogAb{Z~@a|;c#&B zzr3B#OIvFi#~1g~TLv!oZss4DKOmCJEhlKTQfpd|(Znob5{ZN?63Q$h$0&rvAhcl? zS%jN}k_eei8X}m{D~L&`*o9C;(J-PGra47ZW>J`_Qrvp?G*a28mODW9cM5 zzq%BTO-}DQ86+z!r>CbcUmmU>PEAb>F^e+$aCY{Y+0Q?H|HHQo`z4DnUT`?6CJFPE zbGUBUw#H}yUI>{9jTiBN+$=7FgEnB*k#X`HNevu2fy@v!up7LwATnrSE%tASZkjNa zZ!p+_?tn=@45ayRB-$gQ8d0Xv5@wv9uE}S<(`jxw$h@-E3}*RLvDmo#u^|`m^yX{; zbOt=QbN`{uVl%<+PTL5W)oOK`jv5OMdANnSp<=aCO7fJlHsjAsp<)bEne=`=ovh|^ z5pnXc;HDbdLt5}l{?R64V2qhhxuC=x>%`PMnCSq77b&lp&P#2pR@?$$(mIpJZ!a!B z@@giHU-F{`65xoYQ8X%E)y;m1b7uJN?LNOF06z$uG}kyuCg&9u%8!+*rZpSvTUIV# zyr32Txyt*)Cfd`cW;<#H*s4@o3Wf6IZovwa)SSy^w~zMa?ISBIPo6MFUcOvkpCTKA z%MkGb#0)WFz&?NeaO)4>ikaKDOeWuI!7X8F1?nn$J{Zt9_v-4R%ZpKC_`?`O2AHvT zdS-aK1fJu_ltz;pE;fFGCWvV=-WWg$fuPVIdI&DWpj3mS&sv4kNgZh2odELH8E7$S z1J#-=&Mg2kFs;L)r9DH5vwQ8PDB9p&bQabO^bK3gbFeu87FiyBX{nc$OTSH}N(6)E zpxx%R%QtVtKA8|55K$?m)6gWtiP305VhUy)ooDu%5%Z}-V~&q^xx{SMuC1?J2MFOI zt_VzxnlZ6abC-z>{oQHkDiDJ;IH8HeZ1Po3K#T&B3~U@z{mfJMSnSr35!o~2XP;>% zG0wokNvqXT)KEwT^OmYOo1Lf@(rlY6b`gMQ8)b zU;ro!vuVf_W}{OJOsCx#)Zh@O=-V`zZ)%+pEEzV~N-p2y7-SjPzY$~N1$UHpzFOlH z$$+QYhUaJZp7lMlU=_+HTUg9{qF$;qHnmbBVyXx2bIy#`z5GtWAO?~H>BzoPh-~Nd zp1yB&h2U_eiA=vrHlKK#KwaE$m5i)vfXa>1OiT2vnD&IgYj0OrK%w{ z6r#8tPBJffh|F{7<7^Z4ebwY~sAhd0x3eIc!(>Lw1TL3a`L1mNr^dbf{Z1u|+4lsJu}HFBr8 zTooFK(R`DRSSkor8nA_Mb}5{i>}WzmZk}982Vm>w-QH1~&2BUK81Lb7!(&x1FX_OP z(!l{E=F@rmKkum-6Z*=OQkvH{OOd)DhM#qxqocfwtNjo9pXFB=Gwbi(x7+9Bm2sKb zt<|@VKN^O-V6Uq|M>;zB>*9^Nc-=W2v%ke926=%UYOo!hd^WLzCbyXrN1<)!Hmb!E z6OJMzfKR@B$u|5>i``~%`Ft$!A7MWQe>e^r10q9HVN|_WBS6^WofS}LjI&8Gdg ze6(@4lK=o907*naRQ^?-7RA5H=YLx{MQ@8!vOXpF0KaQiLj(ndF@m}R#-s(FN696N zMt_ffK06bB86fl158oo}_pB=8xHbj?b&we6$l72}H!g!+D#Lv;Ztw@k*7^rzlO$=o z{hVFEI4OZPXJ~e2)J)>!b4Lb^FSenjry6P{TcyZ$BFp{@b05i8rZMb8;$liGxdQ&|JUC^{ zA5+OKBU9oBVMnrBX|+zu;f6aP11;>w_#7xXoYF!P3QIs%*bSYoA)OP11a46j6!60^ zZ~>nzsySuRrqCG9%%5(5{jlGaQDPFdCR06IvfUl*F)B<~6tk#@{@T;QUw-KsT>SIh zyTcx%VW`e%g_=~OkXn%e7uundknREw6EgAMHVG&KSvWf!1goabo zhJeP7Itp_`2Ob0Agt9pCQAXvg40$4H^Sg|NoPbD^mal z9pP*+P7?J5;sOtKxYXg*CTdKi2B#z!y{(qFPyd!ya-m{ZcQjm&)~#g{>E&0_>tKubwcAZ%8Yo= zW1vP%KBxFhO<45Ph?N0k*`=lI0v||o@Fui?w$Vw_8)~{Ln+CZtp54KI5*?9s%p%0Nym5g_6~R6wE-7k=KNFpeLF;(nV4&` zyIE7xu;qR`*I|iLtRJ`8^shiLgUPas3r5|)KY`ZlZ|z=uq~QiHbN9yP&394)&j$$7NzaNjTNb z1X)T~z>N*x<)z^GxZmSkfzzy>pu2U*Ob7`DB2!vC!dV!?4?ntG+~Z=>A%FlG;SmeK z0&k(P(AP(!oT1;NZ_Zxnz>v!P@#{Kf-}y43phO2=FmpK}LpIoL#yCbW!{dLr{yI4L z>mmaNnd$A5c>zo?8CpQNeQBnEm_Ks2a?-r!q|U?M#DOY&P>Qes|f3d77?Y%cTOZ?m^2Kw+Ga6^qN* z{jtN*4i|eCV?G2h4g!YPjcXnz29tBYpCREVi;uZFSi>P&2#%vsEr8E%;vpI=mpz>c z&(5UND$$vhR%qj)QCW4iL*sVq`_EWyI`j$Z9f5&Vl*Xeaah5=-Fk4A%Av0U=a1YG$ z?eqCeU&q}U=qRi#mQvYtczUQ(snsfn2Na=2)_H@XAZBiVl_uRk*Ve*haQq`0FmV4` zUuQ*#jJRMyV~+pL24;ZF%Wr|01)5wz#0V9kjrgXyvXqgpRK&$kpf}>1K}k?Zg2+g; zYFh{lY++pl4^km6;x|aOQl(TWx;FzuKyG$l%jGheOkX0QD!^)ykc_B)38f{n$R)!t zDh(UdPBBP3IL0yv7GwxHiqQxBGk-HiW-5t!9E)v#_nkd1dwc2E7n$}CL?-;ux5V`YTCOoKBGEFSk{aoNZ# zX7YSYU?v`k7P6&6wg5oiDpzWiZJ{--h)A6u05u}>U)f(r^B6Yx!xzt<-@6^^zmdy< zbLX}Go8DTvE<|RrdVDO2;iB0qbnRbIj+hom_!VXEEGHCfeT{^SHgrFp=N&HeOU0;I{?w!SApEn_UiQC(%n>a$XEq*f0sxY@qP)G1mM?TE(%5V`I zN?5pBEMFNC8iNvl{Je{J;h0S;E?dGf%4IIDFZ15dk`sQgR~Ff^cyf9l^_*82ybqqM zmdWLCI0nDafLU5z`tnA9r(bbGv$?HHWjGW}`TW{(G%zWVXE@RIj3Toz)tO;a02GC3 zH;u9n93Fe6V5#s=Ls3B(rDQXAd?4j5<+Wk z`fp{k**I;Mo|rBRYIeSF1mWn&t0(KhmC2XQdoOVEqh&4Jp7MxyZNW^Yujs7Q8)6-_ z4&FRIJUrE{Wl>|m!+!zpR#;d~5D`vEP)JZok{TXJNJ;2Mt3Y8Rw2(j!;R*iF_4?u3 zc&Os<6e)@Lg>mZ^R)9Ak;4=H}BbHu?DI_EYE>1Zp2Z>2qVtCEdg-;(0g^CG^WJLyH z2BtQK(wmq>heQV3Ff#Z{GtkF ze<+QDws^eQ$nO5c;b@Nw_hZhBjEKk_pL}5kWJ^d4Fw@Jtz>tgpA6)bY{8nK6Ix-|R za2^eq*(G1F0oqIxmc{^KSrQeI91A~3+aROM6ww?TRl4qu0~!?2AgCk%Xg_U z&8JhHUh$6Zh3mDrQ-f5d)H?V9GXK*PX~#VG3MM2ke1^F@)wb3-+FH~hX`z|`B0@`K zsT+$BC?upK2uZOh2+1%cwp}SBTBk$@#G)%IJ8@A(IL6YVD@aUf3`3wmVNFqWV(z;b z=8Bm~4CnvUpOM7_VkVCYvt>_Z{&Ybi^Fe7GE+~&z5aV`t)3zABb!irtHCXhQJ(n#C z!)sGKZuZLgOUMZgUs4m8xFVqEGkmy4eACoah}Z7!E}3j7V$1~;fd^Wa4vkUXGb<7s z^w^MxM$vOqn^tQ*?`$6f-4U3ML*5%jYk4RGgp0YO`{$Uk6aez9G(-(VXr9sO@I*E} zTZ#mm&ETA%W`BPrLd3jy#<-x)JX;9v6&h=mF0Z%fO?Y=|v|(mrr2giZqq4}!>Ftx? zE5XZG-@JM-ce|~SlqlXJW?G6Ak`%y%DDk3}C6tnE10Wk3Agm$gcE_Ju2GZb?I*wggiF%WV?R8dCgGZNlIYblGDF5ae zYIM?{;DA6DjtI!3HCPP*M|7xLqwj6N$CCuCmFLbbiz&LCAuyFq%6tY&XVKJJ=Kc{Z z6`v(cXqXrM3DcUbTz6M!Ivt1hCU(U4BCGpnq%ABoOwaR`c;TQ?Un^INiNsD(5CiV{ zm5O-JZ?pt6w@+AO78WKSJP^PXtkD)mTo7{+D6)MDQX>AFl#syBEPmF!HElN=@6>dc zfQ%SzHN|Mh3wGi$g~u&lhJwRIY)BYn9ZUsXhRXF#8PVb}!=g3JjQSC@;@s;560>zK zmAM#^`CZB1;lv{ky&m_CK?KIuytGuzv=RVw)6=5?v!sC8#O3KaPYaDQ^XoMMduYb{ zo`ITOxafB|v$;D=a|C#i*M`s(-hU>Kqp1UF<9FeP8v{no@f$WLG~3B%_=@w>6aZ6& zz9xlcf&15wt^+hVDK(6Y5*Z6K9HC{pJ!2{8)*BAlXVYZ3GK#UzoUG^Ev%**j9gkYq60N_@^0;Ei*HsKCoEBu0BO z#HUA88B7Nz=Ayo%O-JaV@^_b6FxIhY$4A=*7^|O}$`Bh+x2xrMwj?TBmM-SoOCMYS zFu(fa-3}o!c;Lg^J?Q8mVi+46FH&Pqf4283|tc?P*~yv@gcA&&F6}%rch>!(^7CO2l>%c?U7a;?dyO zBecnXgeU<_YU15Ryc^~2)1bLO!#f#mD>M6;7bP;k4@2X!7mj>*yRS%8+J$C=Ju((k zC9@vd8FQyi4ztPY;loWp21r3$JUDlwQNvQBM8c4xYX-(Zl+P7PD-gIFcE*jSu7GG&{gFMuttf?g2zv+*#GraLuM^8ofem2 zA;J=RnZ1?&B_^1#G=LM66nd_sq6kWA0uv#exsN_Z>jm^H5x2`=TMA=L&oOf`ZOr$7 z@gcaz^ua8l{{BbIigx0%r)`~C?Nq)3N&g*t4zo#jSpR}2-)Nge{Hx6MCSb3y;h}GZn1`chhRGgTUBzO}rHr#DliKOJ+q_ofIW7@-LgGLSomT;>Ll{F%-NI#6xIfM$E)8cA+ycn^6%I+FAFW zbMAfbKK(e()V;Fh#LSSy_NVXr&N=sdrl)@!?L{zIIWfqDy(mC-sb5;^L+AY|o6V^L zV8ZY+b`8EI3?>$ix%~06AHP>(KQ>8NpBs-yXAQ7eF=HRD0SNQ20wvv@gn=Fysas~jyb1+cf5+KjMok=qp!JY!&H496Vucf!u=*B{^Aj4RuJ z|1IoBdHm@o{8Ij(|K07x5(~;p#0*F>1{e@!yhXzBv3YOvg>2kWpGcNO6t>1|t#gik z9?>*ptTcvPi}Yzx`Wk=E$I6%Rc0v!Xx&S4eg?PdTOTHjBF6;{C^Zu##%`-J+bGlWV z&8E6BVy+!%w;yaK((${;f@V0!T)kvjcI9VH_T!ku#K+jY(=MIa$rN*444FY$*#Hb+ z#zYL~mp*~!TaCw+LsEHN#Fi7!Fn^&fCY7wz$mBoAQj~y^^Xwsk#@m}kLxeAb1Ewv;3fbtC z445gWI}{8t#K1yqUo4(>c*>>nQZrM0{oQx}&*`#vewB47-Z%!O`mRme$3Vu4p6dq7 zz_V(%8I73xywgv35s+bzKD;aWI@)*hSwc)*OX6ZpxaMWtK{FtO9~@?gEmBQ^YG;TY zaYtayEIV`L5XJDgC*JlX(D2-6nnKg~+@`|_4s=Mjo;^$3tC%{49MfuTH{)*90xrYQ zyx?}mQZ*aK%ppDohl9bZCr^$G2e2;i(;GKG|Lk91t*-y=>&|A-EN)FI0nc$txsb>@ z&!jZQg1{sd3zbZ0z?g-A74v%JIT*o@Kqv$gK#4cG5K9CZmq3QE%gv7qgM1lQ{ICiy z7)+$|#e&~CW#WZ#On7D?8L~M83x!%Wlc`pj;x6_ww`+NawZQ!D>^`ec&$i# z!RKe?C4oE=%}h$iEGVQJ6lPM{c}*JHCTb8j=BXvJHY)ZAVc}W0?OtBWvc<^(+ zvIi8?f;Y%z-0-?kKfAd&`-WrYuBA6KOfiEe0x*NqSEqx)@#{jZR?s|fbN8$N{8Oj9 zB>P6kea?aw!o|usQKetR)DMZNQTP~WX}mp2>B7rQa3#9LC7q6-5&%gUxCAf)LDx)Q zK_qDua}<0D=ytFdEKOrFwcKU&8w|K@Qvxv&U(6eGJ6*|KGnHB@!jiB;LBj^ZF;asxC4ExEAh z$ZAS_-j8WvL0^o0LW*|E8cxRJQA9EaKU8<_5!LiipiyLvzznAw=+?lNjWw~dredL* z8js&Fs?KEl<@5k0(;|9-BvXh4)gn$fKr|5vGDZbp_zd_P0Ok_3}v!u`yGj4?mxOe>iY>Z57~PU z)-K^OU{mlWAm`f~3q*j3*((gZyd+}jMTa7AVvvkSVi^yQeBy(fR68qU&>rjySgsh} zWlgNyY&Q95T7?hN@L)mQxmhjN^L)z&%x%he!CxuWEg%=z+XS=x8(RezWMlx-Fvx_4 zXl4j913@!~2phr+K!$K4@PbXgA?>4&(?cUI6a7tkY%;yPnN@Vlbr*fY0UBAMIxy)i zuqAPyk9qfK23y2wq*th9j6nASJ zMO<@6@xNOem5LUb!itS5Nwa$vX*SF<@F0qL#Yv`NU`23@{f7^a`n76l3Ab64Pzy24Xza_&PC(Q~ zxHkZ*fz8IG(8#)saWv+^HMMo@ZT8676ie8wG2&}Qv5c=j16Mai~!^x%}IZ zJ-YrsHYZ1F2g9-Q(5Dg)8CLkObNo^IH#VBLGrPN)Omn%l{=2hW)a?o~b&`k%+))n=a^&*`it~js zYM1Z~f8U?}=rSor@yA$qrDe% z-i^68TJ-N>;dSZmi*#P``!Rfi3)R+LxcJsac!a|th6?DvtJF!1V0Xl%5~jJC!lo_W zCQ5XK2b)`z)6hzEoOh zXBB47UPzdcX=WfPGm~Y^$n&ILYnh6w`z$s+6?)eP@0P(t>7`RncN7I!8XzDW0w5G2bL zMkPztZnqBY+v84$uGwv-@1v1N< zez*<}PWV5CA?C_ux)|>az9NK&JdEjMXvS=IEM_FzZ=sk+oMJ>_nE{5qeZ3Qq?fNTt#QnIDzjmEsTf%!h#pt9hIdG>vbreVFj%w1~(Zd zM4uCq&}atD92q!(J2eb4#d;4?3l)c%9YFa3i;g8)K8trfq5dCJZSv2KJ7SIjd^~Jt z1_Cldlnt%|R-QISHQBjPXiS(|nT!!#l((coGb^9$8){381H+;ev`F)_wi+ zdyj7%IK`L>fCauyL@%LeLhJ6Hz$F|!`mUt6(3b3BKB=U)zQ8c7${Lb;LCeAf{ig2$ zE(u{|^-a6|;05f?1jrz0I-O%r^VW^Wk8kZ|H`W!EVO4c$xm*h8IWVUS9=TL*iJ;H^ zIX}E|X%xe3eCmMwpFgJ8h;&;G`|b7@w}5HLGpKt|x@=);emKY#vL z?!sZ~IFn{&$k9v${ZT|rgc}(F7@HGby};Fkq6?zj71G|M?+5JP}vB{htAu*5WM1MTaa%*MQJ0XbX;O=uOE*FP84zywCHz?|a^p#I_3_F->hSr#a{IexKj( z3iYGS?}%YEV!#H6mv1kyfb(go?hIunO~J|-G;-V4nLD=*`m#1np@PL+T(^P2dq_7_ z)65A?*EY_a8Y2Y8S$i@Nm`@D$eNS(TFZZK5OqbQroRGm0i<-@%w?|Y~T|w`i_VGm}f$|BIl7(sX8W|hj&T~cfKzL*h_UY##n(;+npWQ3vzz`24tu6 z;=kAa-39Kiq{Vz#gm86aq}L{s^~-(w0zdGe0@($aa5w|Y4<0;l_%J&Rm=`)t$bJ9- zAOJ~3K~yiEJ|(+`F$1?;o=HL?5g!$1**IMzfehb(l2J46i#Z569~V0okfCxM)ES)80~$kq|ByuH6NngKkU4WULQMuT(#STPkUS=XD;Sb)B)e+^32$)NgSR8x zzsy9&Xjdpy{cE8RmsWthw;>W%t?eJ3^3fZm0yasI%>~b2Rx0R}FiP@sY0Vo8$H9FK znYi~GEHzxP_^;J@9a1n@MP#Uh?{TpOyT|OW{`m06rPbx#Wj~%?WR@nRLP9zR3*;e` z$n%1UM*EK!=f!B=IIJ6i&`94Qp^=y<!NY-jirW%IHJRwKP zi?H!HHT-wOn=)jWWmaoK*H5bm%|q<_(Gu*%{ABsg6ujCPgTO1hz*KYv*Nt5$Z6805 zM&t447b!7QA+Uz7j0`%iNQD_u*im9=-#R7cp0kgP`!M%~!XPkj-n@Uky1l)H>&>;< zTqeVA>?mZpM7T^L#>I)jMM#fo7SG8LFCUi~d?9Ycna9X8gq}fka*(fN?)~8$<~?(V z89ujTE;oSF-NawvQD51y}X^9R-kX+e4x?m@sUkUKFUfjK;C8G;l zJ3#_PvDko^&Enp~-;NkFr~fLfRyNii@xdEO9A4GwP|m8uyNgWI;~MToMtVl7X~x!c zh75>ItIT)OXzy=8AL`Q51_->z9L>z}F)O@#!y8M46Z_mOYhM&GOk&*e5Ud+l2jOx> zZIl`5cm7dguJ;4uaQubDd;=yK@bc!}vtM?flyJN7wP~1=#O~IZAV$8KjeK zVnAzRF?SvZr1S2ybSh%9tK2IyoEost`i(Qr%&{FHyZM2buiPLa>r|A!R0$W7hJb{; z60mo{S*^7jIGF!vd$qC# z+ln+hy@%QR1hKJ~8lf{bGU&_%0w^+nWjKOFaeJz$`hFVc2fUu{RIAm zX%-9{eOMuepN>fK05E*eGXT?Vb=z$#m0K+xA~AX(8jVC5Cb*j~9sV)@-UQACxTpl? zrOzyPECB0Y+>YNj+sNTq+b$q zp2on384`DYPlcKFf%K**&s%vvnWScyTjI}&9|V`*~UxdbMP$dJrr zc$Wac=JqB7*g>mYZriFPi^HXd0!U4}ZoB>yb}3npZ!$Plav-GSwhRM($vHRlo3qHg6AB%k6{g!G9_*pCcrK4Co`q zXH-fIw%W<@P`7Dzn)Uig$734o1+C+up>D@DJnT48cyAyEf${qRm~t|SW?8%2j>Xc2 zQVJIVJrIYT;{CK?yq~b~6EPQ-@&}3W#e!zovP)zC`)<$~e|7;YG_W4Zj#1ok(z4abdrZZY=rMJiDYb zsj1OeJwoRArn5fS))GZZ8q(e>GlQ!NPRZ0%5TdeN#zY7nyWnNqVc;ZWn5ht^W3B6kWX(PY|Mm++|k2z>$PgfTaj&c#?g&|U}7ulb6fCTAj;s3mBf|;%3 zb%hL8tJ^Ia9y&vX7?U!mRo^D`+C^*8WI6emi;U$>Z}Y_9nv7_#_e|%`!oZ z^K$D+OW0zTCIZdU08@-G4wEe|nx$xshVwS5vL8pvfU=;bGbtbQ!^7CvBtQcU5l+Ah zS;#Px3okNVP&n}ZWLtR&5%v0;9Yx`-#))zF&fSA``FW;RK#83%YZ6?Dk z1V+r>!O`kMy>$X!|4H|_TW8dChmKnzy~7AH;jK;h$^V909{gBjjSYJjXf_&0n-b2E z6N4j2ra)qVm?&g05gC|;kj_+A{j?G>VzBKVNg-sICLLtSD!Z7J|L1?uv{F-~LP*bFWWhD7yRrY%;DfJW%%T{r6~;ojrSx#N1lDHj{}#eK&UidCD88W@&DQ7_fx623b?5;V{SaXI5}hBq~7s_)_o z8M;UVDzx%EmP24%JrYCpd*r@&)TB&x{dE1gWk_6vO*S5Uz5H<22Pp|#UgCG2yc`Ww zH>2%rVXM|D9uFNCjSw@s${m->=wP~vt{}Bemdi~;IxJA-9IVog2Hs@N2aAIYLO>3a zB*qWGATh-x=49H>bGb^v2e*jMh=I#T*XTFauI9Ck^o$<@$+7>4q)77UgZa|p%t#}R zypqKtM-4K;#16(#hp-AP7R6yP0sBy}Q==Hykb}1dts@dBZE%x4B(%YswDgcJrMbko z7x{)5@Lo^^1pH!Tns)rSL0VN zVq^$8@z3UNktUno+#KX%(Dn0ipfQ4Y4(lTNrNhGklK#ZIXfiC0j-{<}zwg8CG<3RYpO#O%1wlT@Dv+ zDK(e78HzNiz*%uRrZRHsA;g;Za#on||614*+|0Lyii@KJ(xd30Z=|;B1<56#1QoTY z!-PB$P&5FT=y?`KlwpDeOoo_+`GuWsnj{$tWuCVgAMW0(s{v7Ftp9#*Z&fdB{pIVG zcAX+Ih4_pU38i3Cs4_!u8F*1M$^D zwY{24;x-xGC0fyh`3I>`xk1i*Wf2<^W) zCjbUwNkohdgF-MFXh16jJ6AZI3Mx(G=N3P4(a&IMhKib%3i~(Y&E&}WhX4Y0psjPk zMd@H9RLvQ1B%MY+74d&nH05L&)OCX~Qj(zLX~AgN#6$*%WP)tuv9+_Z^Gfrx3mulx zUfRf*LBtq$Up`ziRc$NtekP|teNvG>02hl8M8Mb+PCa#C;u3qr*fWRr5I8#l0ZNg* z;vJWFB2bqB6J@q02&P-<()-`{57t)N8$d@4F)BEJ(q+Ui3^8Vxwtx<)fO#ns%Tjpw zDa0bS{)v8Ob_j}*9P>EDG2eKa%rpL!lpVf4IXR}RtU58<07<0T1s}&KvgjWPSQ$51 zyUg@k{#t|Xp+U8 zzH`J3sY&L_WN@SF8!i{IRgFLuH^Mkjy?@KOe+%z+J0{J!Z> zhM@{2d)eoUgczOL4|1Y7XJLbsf!P9P~WjEVMY zwUn(-tv*j<=`qc>T`)!gQbs`FS{TkL4k}$w=)y0YqBvk;3%{*_Ob_C?1A?sFWq5%{ z30UU8dwYAoTS*gQY}fQBWymw;KX2Ul3J^1tl0Oq=F^AfUE>emSh>1hA%&V8vo6`a? zn?b<*)WC|;}6|gwIak*Ds?Xp?8Fqptmq>b88OrE)%Z=$QH^2nTg#T= zMDP-@$>{-3Prj7lx7|Ql#?vtNwVFv2>KriG0g@)nhywrx%EHCeEMEq30o611OSnkp zq9YeSqURjok4IrfC6`M_`g9vpcg5?~YW3!wX4X-2SdvlFK2@8H@b$!Jqa}bCtCFZ_ zDIZ{nVN#a)@!i_1BEy59WUB4vkNs zQ{;%LFhis1-g8}8hn)`{qL^$q!5&@Un(iBhm_Jt)LX0U~j3)kCS0ZLOCI4U4V~GMj zM1JV~_#VOb_4~Z1g9J;psBx7;a;}1&TTPnHhf=k-5`?T?!`65P3C! zZ$d^+Y$@eT#)lVgAv58nCGAV2k#$VHH>c0d&Gp!0k$qTXj~-5&!^^!yOE)PP$nrQ0 zpK4o`LATgDFiKk)4Zha_AY+oqfS{Rzv<|!|I<98@Kae>aG^lPYT`e$qV=z2hU|0es zKRt!}3>R)TOIiU^XyJ?k7oGDN#zRcn*xJf*z@!CSU`E;f`0n6`kSZ(8EZu9>CaSC3 zWwLo9Dbb|+gS_7ML&c96%2qhTRLXTthx|p=DYmr9`BXrXAz(@XnC?FqV&2Rm&{Lz_ z!FY&)ProBoHk1P9mCKn-nKHb=_=ulc$0WpzqbMWaKOF=NQOxo(M-1l}s>l5LHMtl7 z%+ZVa=bzKw@GQPiWd+mkV|<;Mk*Jl31uVa;XV#&&vW3IS&1Svi*u5S>rPsrc3@c-c z<6~pvW4#`oIM;!twHa<`vP>#4j-k8-l$qRO%7wgT+yZ%r`@Dh3orZd4(|khH678{4bfYb&!c%}B$N1ibpBMeg+#4K2b!M#b)4bxfMUR$t(6ngHsF9)ct=8pnZvqj za19LSipt4FG>st1P?J@_~8u&mU3J#4#e4|!k$*Ps&17O98l{J_N-mca(3qvWL z*oY&>7w(>c8$V!_knJB$Az~^E^E*3*TmUj#?c0xg!m85r9Dt1Ytgq449ZQ*qHjC7-H@w;2+P_sz!}u;D>P=GL{7XMp4;NO8%EJ zB+4#?7_q&KeE%&TEl>M6My$m^hG8~lS#k`K%rPS7OAeS9|9XxTGdbBR!;4il&ML=1 z?4FOwqP-mIPtY>iR%^f6YLxZfB5?}77v{Jcqx(Yl=717+H}jk9ZFkpk!Ow_$36}EU z``HzeHaFtBtx=ywOwnt^z?ECHPRMk*Fq3%?>H$>=H!lw=Y(~S0Gj)S`B5fp`1)R+j zDZ?(trY1hGPL-K18#QdrhP$kU?j8|rs6WH`hXDf&W5GmZ=HOsw!tl9%_PM!qduig` z_UdZUJo6x=xPEexpAdEsGl_KoB=jruWi*)N<1k+qgc)eE?*6YBVjfi#v@r&%FznZm z-_{)ZA(i~ET#m&Ch_ZP6Jcf z_Q^mNTmw}GCs^p9zWEq9%Z043Us?PYx{T>A8}+=+@WQDDLBpW~w@@Ej>_JSykn-c^ zCVPAK?Aha8hcW;HO`-@t1bb*$meIolZfPOig`c6o6izX3u_0Aw+D63Vi4iHb2nZgt z2uO_h>-16nHK#{s0}A=x^F*E>g^HoW;JlSmk^=+m!Ca#ZQf0#PBgN$Q4-RHt8S<&X zOGxq2FYnDPZMWB`!H8s$*3U5fqo>Ct<#3||m#X#ktsLwag{2tSfr*+7di+ZKev1hv z%@VJ^V2D}L;DwT6h;exl#`V5yheX*>O8&5=Ogn{QKA{019{2hF=}oU7BV5cfk&FzN z1<4%0+&escDDd*)?c3`xAj}ZcaIg?^cFEt$_ch2sxw5g}+=u#pNd@{ zW&knwRCaw(QmJ**mh zY?7cc}j3usnIX+<=} zLSli$9#fkk_s2OLLlT^0gIyOXM{qvp`+T40 zd7l@WVJ?*WL0>AHT4FdLt6)4v;aF3!vI6B*#HG<}h_@>_k{M(smcTM)T*Sg@HF+Qs zQ3KQ>#EiUBz>CRAb$Zed7dab0T6sWt>o8ye_1`^&t1S2CMMZ$ zb(#Igv>2I?IoFH&A_&PFJ_dk^fZs=b>BrNoBQS!MM!g}PwR*Fe>r$JeBQnV(B7@69 zjV6Q;6|l2exdjj+!z$CKOAR2FcED4@cNZi(4}Wl?gBr-Fg^Q`_3>d9kQoW4KTnnku z&6v@!%l6xhOeRxJe3nv<4v*^4#LU9z;^NJrMA}<%Ni!lCad86@Yd7ACLPjHv*~pAj zd10wC3@f_@z`#@TVg>jADTsM=Cx!EBBXM#soa`jINnpwU{kAm8oc@7jC0+}d9@G0{ zP=?G1TJFoB%mjv#%R0R*1G8`c^4FJ7_z<`}+uFK*kqan&(2SCAUBC=wa(dFg8cIgU z^v6+ODiw&s;B^!KOUO%9@dE17R9o2!UTW}Yh_e;UG`onHp`l;`YW|E2s0?TC##SKw*FvTQcMFFmPO& zxH+{nzO)$ghGgta@*H+$iII@mW$h=Mn1di@P-AYvSif}`y9CI<6%c&7EQtAH9J;&3 zpM=}Y6KNxzkl4p{t!*j!pDJ6y)T+arYl|9R1fvstYje`3sXS0 zg1jIwe-y!3qgexasWqI2WTs3TK9_?Dx)H_`rpjn%r6&t#r2nV#KUe6m%O;u6ggVWM zOmFevd$h^Uk$@gzCSb0uH;^$p{BckjscSaliO694$q#2X)! zHln*sTeYV8r6j1+zlzMzxAKbI7ee3B}VPig@$`UbY*-&O?6@Zw@$%hXI zPq!memWu?A1ja9ICWp$N?YXQqW<_^mt|%A71x#mEi_A3j%6NF$n*JqkR8~&og=%|k z3?FtPrdBGG$OK~)m7U9@o|v@I6En)2xT(zwIGDRyVFWAnT64DP)SZSiTSsQfymw4j zF-bK_uBz&3^-5-Joi$U)$)?n7qATr12) zpQy}|MZ5yTnRY;;nyG#;aZeDlc&|5=QtOy$0kzb+mer_EA8$oLVmKsM$AJ021sP>) z52uyyTh`DwKik>a`SgP<8m(+v1!G2v;UDi$c63bsq74O15tPN^$CNM69x=b{Y=wA1 zjq%j{8_Wwn85oYsXqC(}0~Z0z^z}=;7bcD@%V*u0GD%D{O~B|i$T1uiUoQ9O2eAD` zNejP2UIsn_ed)i8CaVbs1}%TBDMUt`=`4thc+?!H1}Z~K%z_%3UfRPnYe&q4w<^A8 zY15!2b(y7m)lvb7LZWV0{su6(M$^j3E8zZ#fSGTm&ls0h-00MtKQqQa%BX6NA%)4f z+b@N_zy`yqx;u|wyWkg>nsNtsCr0Kr$V_m3UxZww?fGI5bDwo1QZq0tr#DbfuyO(nKq}&LF?`jf27{Jb&kw-hIv1;qzzpC6u&E$8rHYLXCcMcGrn#bcfh<`~ zm>3MlL_p>^jcuVY+s@qF93TUOF^9@lUlKZDQt=}Bf1LcKM259xkTW6L{c|qfkCPv&b z?o2GLjW2Bcv<)$+UZfD_=}TEgCILBSD8+#H-~ZRn&VP262eV8JJAU0nkVxEqJ}D&T z;NanjOa5ox30i$&IH&jC=%Ans4oH=$0wzif@xsWgN@Akyijx2UAOJ~3K~$8Nd1l~( z3L}o|U(sNf;Q|>MpG2A6XW_!*vUD=MIVIF!2GpapS%Q8TKnN9P6G||5`{B&$YOi$4 zlR5PU4epr5fogN`ZC-qb$P7oA_2m(nJoJonzgr~YLB_`MyBW3PX|Wh54}+^ZM6eQd z&tPhC;RoK@(P;?P(HT0Qb!U3+v29CW%$^7IFjZnEu`w~aHa@!Xp*H|E3qr4!BzKcBPeZ;ljtr?pHKAY&e$BS8>$4w|W^)2hFKtFg^@-KORh0 z3}6OILS2v>YP$RbSNM&b@}F>jjvCD#gq>|>ftKz0?fLob)wxwbra6p5W`xS%rJu)I zrjamH#9;C>!>zSIrHK*r0VGA?9}pyn+fzJ|t?EAwf*kyV+9LWbtX=pqc>6{@g+ zrEqg%VQp#Y>r0`Q>>g|C0&XiM_oP8zuSKRm7Nj+p*7C2Q98)EYNhMS@My)U?7GS@G zgM;s%pSa|I`bSnU!#2j4t$fT-Ojp4lk-2i&NG@YgR+m8;K;x`JRHod&_?k9((a8Lo zXYG}H@xJce2qO^6pHr~l#^Km65sMWzOAv?|8iTx4*uvZg3quJBr7tzC!$`Nk?W{Uu z)Gj(EzP49CS>?z~oJ@g{fmUXW%WPYVOh6?+0UD4QvNF`}k>YU?nTXGldYXR}2nCJ< zDAZ=TIWj-(7CTd8qB^~-Q)E(OKwfp@G)OkV7a7gy-xEpW0ANau|PeA>?qT&&f z#7Jb&%D~#Pz2z?+J-T{6V`Cq8p4A2YOPbgDufu>|LCk|wCvTCl`fcg^ds?E=5}A_r z{gN3r{*AiU7&bDF3d>e^Wh|z78JQj#5k>}y86N7x%#*DXW%R4H3u$G0ZtCv=g}DzYvVMaXIoTF)nRDjE*=-{zW2=H2dMl7ABfSclq_F>S zzqpJOIWkZID^pBpg@GrCOjr$_IMntSFkT2D^(LT49E94bHOF?^cmp$Cl99-GLNf6u zs}3(OpPyP9|2i1<4i7Mgpz*Q^`oQ%U_S*drw;a&Fo{hZ7zEG2w3xk7&!CQs>ZVS)!Zi~m5K>1^Sd?FsJDljYOa6m>XjnfA+MqH-v!sP#{mWe}B(s`*c;_F2w>)Mj# zO^$#{A23M9Y*F%!B;Mttq# zF4hO%|Ky|v%rif>x)OfGoK>$!+ZxU-V>O0-{|&q}8^DVzS4Pb6VX`9i1&-f4JkQli zW8;MZ0^OiM-1I=}IMnut1w~xP-F@aT-+aF7m>Arr~00+;9L$9&9>c;Uo->f@ut)f)s{0esoX_*2H8sm5nbK*9c|d5HOx* z6112_=wiTvVrmGq5bA|D+Eh>|S!Flp@q1lac9JSXfA{KT$FXedqwhKAcOGe@O_PeS z(V3yC78$-{f+NW>n%Nk<(O2|;75<|SGh*{U51$mJQgJzlNPf0CA z5+R?p8!Ck>D#brMUg8!m$tl{Pq>UK772ZC2{S%}x_>^*-grJ=m!3#XATA$((?e?8M zXiT@>RWj55;(nh*Z|3TFlClP!VvI$`XP24CWCSu8V|D~FJ-!NA)}YR4TSXab)QjY)A_8NGfyUH8+^cCW3h>~2KKucHV-4^KK0 zJ$`^^rf0M^PvZ*FRftoh&HkG<7k!FR=PB2fnapr_2j%e0?TzD`^xK6m%nF~MiHslHW2)WfVz)g) zo^!_6r!1@b@{I?=<7MjEQZAAu2Cz)A14BXsHW^xE!RdQgXSr|ANq<6FWXOx$Bmzmf z)9&8s;@PdWyEV9~F+_w6?GTm7OiabGn$eL(%zlv(dzoTeCYp_9b$KGbJTkU5$jpFw zuNd;T*gwAo|IeoDEM#o#)Y@ucDp)FQ4?I;vWk_ROnNa2sFz)q@mB_V68{4fEPMq!W z;o^(DhwcZd1K#Z=2q85RAeGT8ZQM<3jiTRUg8v`pg*2u-9=_aIU{eW+Q3bHv3Yg5Z zZ;+T*FGnZl_u)#(ruVeB$&WD|e<3m;G3>>l#_W7f#7NIym}PybGWUJNR1IG0aP+V8 zK(+woC1uQJn3;lfV(?Ppu2ujHb3(N*e9I4}tqF^3VbF^vd?-^6bss?UsOpF7m3U z9`PxNN~BILkqn&@y|2{f4>mzZVAzfEz>g`H3NyRM^BG(G0Vp;mrYv!^EE&sxFJfhX zx-jbgWjLI-hxNi7Q*O+;(A@o4Mwhk7Ebri6j20Q;#jwUOFx^3Up)eUEQ=6sYlyIe( zK&>{qpIAkTj|JF~DNJH1O1|h!vBz>(U_$qamuUuOU#7V|(a7|5Kd2fLvdGBLHB(au zY(Qk{-TtTS%ES~h@r2JVGmud=GlWbmnb1L4yg5b5`AZL?luh?l`~9FWw?Gc_blIt0mli1O|xtXrWQC#9LN|%rO#~r09nkOXk17 z`1mmZ^K#TJ{|kSp1d_6Q?8IbFQ?XDI_Q&rCn7gB7ni7uRxxvQYYh6%nI`|CFNxbeVFOH0+^fzMot>gSqMN$ zwYmtT!1W^D;!$InseRFfk1al*L1!kAOh{y$lxi+>3K=$7gv!K4m8OgD#3_oG*=8xQ zHC$-k1g6t7Un~{39`uAP<1&EG8HJnpli>6AxE;6`Yq=sn$ne9(`@Zn`X(cah-i(Fk zwzr#-5?jAWh9P5d*=S-*!jc=g+Ymt!7>b$vEMI5hCuOo|6Rg`)MZuk0=N({ z?W>|`c$9jTsz#{kNgioYp}=yEZPlnC#IVJLX=Vi{?ozXuog9}Q7z)$Z3e!ejs#t$e zr3l1gm63su)zPPc4^+E-p2!r55;9KGD9E&QfvsO<2$^hBG(TmLNxZGdSiXtJexQO% zdUWW`;K|Yko%k|o)Tvn)!vbjjM&^tSyfkB8EQX#9I5s+LCHxru&JRcI()?U2a(j1o ztqBr<%R7+w@V>gs{GhwUT9ZI#=>KzAQ3NxD3s%~+u;d8-J;LDO02y56NFXx1d%O@3 z86lxiN^kaa>j1o;zevcu{AN^Q-m3&k*iP3PPR#2<%VQJDi$Rguk;rUqAud?dxc=0L zE-PfJ$jhP$3-bcF)T_1H^9r>=3gJPtdc>9Pf0F#YJdzJ^*VwL!t=v? zxJbMbeS#r83B-uLw@Ja2CH~5fxxq%+@`DFk zlol*p|MiFK_x-EQ4or7-aR3>%%If_JcR-FfY%#N8mM#T!X}_$9{c=EF_%2BdZuPUq z?C8Ny!XoSIBI;_VQx$HNndF9c8bZ^7Ct0o5x<8P}R3`a_&pjwpY1L>lXl`6EGNOll z*3r3Ft_qjYhPOT3E_-L|4Gp|AJR5TZ9)2bYo3q;?JaGa>zRD36ww3-lKkIlin;YM) ztu>o);*7Gj6L@gag!9BZDK{lK9&y87P0Q8TI0wfpRue76(-xs`9|1s zkPHO|$39nA4?8|wUeJj$gO=H12cIa~X>Cz2!>&w9G(Pd~WBPp=j4{WtY}XM1SY8>m z4Q|;(;$^?YIxB>xqG-~yu?Ae26sn6vCCk8g^Ye3VE4=dU*K0?3oE$Ze;B3NOaRGjs zCuQIV8ESe5f*D?*WzndM%>a}GlZ7+c5?#lNqJ!*SB!bQ9D&e`!#__^zP^5R-Y1=6l z&H8>;nxhXf*?(!|nq^E}&eGp)SmxM}DA|M#1rRYtjtoYZm+5%$`PNg=7|LB<$MUTE zevtvAjBu$gnl20;H4vC?tzNsz(<#D%Y$g-W2P%PFG!-w%Dl$--A~&s03}Xc)23`cx ziP;xnGC5rEp^87CMb_pjRz_Y>`8k4_A(fCaACpV9T{lh>_TYt#jt)B)f4_At z>g+xG>=6zQKU(7pk^`4LKn4+NmYZwklQQUz2SVe4(kNtTVfm^WH$q+vHOB^6A{CsB zjdL63W@jql*^f3FjmCdMBGL!MgdA>)VGNIj2j49%JziS+_gBCB_2`a&f=q(}V8&jX zfeE;b$u=^qG5g9Y17MzRNsW1kM%lyrx(5>)W#}j{E#zV=ryoO9^?L0G9s~}?S2UUn zU{+TwS*VC2Ww_+{H|ZF**aX8O73KqQVs>ae$G++{D0-%&P1a|LL0~$f;UL@vT%N(f z)S%9E@UsXE$V`=xsm$aYjuyvt$A9I@s2SiEyE3#blZ>lCsSp{hF}5Ky_V7)b{|ha) zO4jm!^B_MZHAY>xYWj;w3|Drg95kP}Mv5C192`D-LBwFc!NbF6&vY*+EOw)kx77~Pf~(yZng1fY(&4_1 za_isU1=$MeU74r`hDF96T;?m;emC6MI^ow=WGZDF{PwnGTjnQJ=P;wHm}iX1wwS1( zZZui^A8S|l(^Q&=v)RqgX2)dy5iC+Tt)ZW(wFN2#d%=eWIw31Yr;`$PtVBA)kW7V0 zvas!7ur&swWt*totV%XU9WR)K32~h4hBBF1_hO96CUUWf@q)|!eZ22`-qV(^#rM$D z76_l`>GS+P-sczUu*KL$#7Taxcej=dja z|6e<8Aw$ep)-kdt?^sxkQ<^3-DF)-1d9GkyrqKV&GzBwai9!qn2ShROmVjd-L1=-M zNG$fq(XME8InW=&ZOSoa8XMt|uv6m~zj+5|zu!)k7)derl|AQ`CE^&$lcARlh%&ac zWx)LBDI0Vm(JV`$?o$s;C?-^r3^a)t+}X5MbIuO+6RR^}#AdyL)?A23OWLqUC&l z(APBsvg|e-b=MsU7=G6E6_-hI!wbP=q!(ZUYi2we9UljH0W_UH%{0Y$2XVu0~q=_Z;{$Vq|)m0E0J(Vh}Jl zMd-go93%Z?I8!!83EN4odf>Gf2Q3Dg4Cw`dQ%LlS`A0lC92)>k#5hmT73i)P_4`HC zPn#~0V(zI?X@X&dbJ`UE%u|$L%YtDDFJdvx{DiiH%OXd?Kcxs|T1}D(R+Efk8HXSl z2xXXLXrLx0fi#lQI(FqXE-1mV9cUc85sSo3?NT(Ow>UbilVO5%7!J+Syjh!NbGU)G zo3aO}tNldJP;d0}WUdGoaxpm*EtN_?mb2Zh!G&|_?ArE_A-^$kkK2x&J!?bfN`wwr za2n1PbHFF~C=XvejUXYIz$ulXNBAU@>h|dSN2#q$iZRJC5m(y_F=zRJCI1f&;V?h^ zQ~Dbl_m(O%KM@gw<(Mf67}R8VAY$fas_el71kCib7W~I2#|STROh@sh2uET<%CbUY z;{2wW7K>>qGLHOReEoGwN~uPT-_9NWNHW*W_LwCxWPszC_;V95OfZZVIhzC5Ps>a) zaiPl+BKi+`WapD28AnyR3h`WWgOxRcR8n3D|Nq-fbo5##jl$_wxss0=o}OZ=bo+zy-(!-cy8?MQTYANHTQCH-3O5lkGS3PExyp z{(hEW0kjpf{RIH#JsA6c@LOk-*P&F|9<$5h(-1Ky&0c>&GS|<{&0!exKm;<9V&IUN zAx(yuiF2hRftZ z#AFx&m$y1(B+00J9z(|I(wYM`UB)dYvLwi%jE4~8X27674yL7zn(NnLM&edh5J84k z!4c5Wct}CVvDZ}>Ede8_ekUTCZQL_>lse9xhPeMk|6q5roEbfP>elS+sZ*o)%Ad|Y zavKY!barLqw#3Qp4O|42m6hJ{nPiUi6;cz9Q-hcuj(om|WK}LRqcA#PfgpqTq*LZ% zhA9qstoENR0x_~jhJ2n~5pUPOPBUT-9ki>=X=^2m=$#6f{_SPim#Rqy@p9=59D-tG zvJ5eUs6mclqA5%w#~^0-rF$%nkWqL6=oAv?F_4Mr1fxd7+H77*+j=@JIFS(y1u_1X zsp}NN+_MhjM85&rcCfgL7$J($00UUr`t0G|t+#5Vjf`Xj#{db^R)knbm?1;5Op;7> z@Xw(Pggaqu-3%+hu&WeZwiantUq?AwlxkCOF;iV)mt#v^Q1BPFev>+I3F`a3uuFx0 zw{0iQDD*S{(_Hno9qk$F8_s6_J$vgfux`zsItyHr9Wa7T$#ij$aDsFKH~~JHnMvjm zAZ3h5;8xBuLI5Lx5?&G{mc??6aRMJqSBkkuL!n^xPl#=0a*m)&G|G6r5$_$KnD;T6 z{CB@{Hn~ZKv)0;Y1(V7#)=U{3bMtdbl|8^r*^!q z-TFBr> zvq&S(V-ZC%atjCBKdKCKgMtkCF)5D0j77NB9W<|7ZSz!%qn2N+k-MIj-cfZ`6Nm;K zZSjclfbxV@4V6BhQN=OaY;ZO_Hx^FBF7)Noqh}E_-_6d>uAfa+@*(5Kg>0&L?!wT} zU&Z4-Q~k{S~OutX}QD=mUZg=z@E7|<; zqmPGrIwEe|Oud7n$6+jB`pm&Ju83fo2qETg2RHWr&4;$59{g|Hc?RqrH=|8qU;kH#Yjo^U`g{E*u*Rug!Ou!i~;lTF-=SVj1i;iGRuNws4t3(SVB$QZyywxYy;gzS2AX?`7yROp(a0h~Z7b=4MCoSyvq| zxNBK$v(U=^nmeZzHG!)O&I_ev`P%6ElP6F9zMe^!leU0wpqNURb4V}{!&fR5A-dFE zg%3RGl!70t6!S^INvs3-#IO@kns;`L5+#2R*^}{jI5li@14Y^CgO~h&|Dmk|U4)JO z39=*H)!f|NOdK;M0K>umoZuJ+%w^yh0h(!!V-jP`FNBwitArLQ$q*}W2Gm^KjM=0d zbBbxo1eqo`N$!A7F(>642Q-Z*MV3rL1|-?E^cz4;w#*EpX|ksTn61a(3dC$xag0VX zi;Mk~?k199X%;khFq5;B3Hhe*aNO&Vw*YUFs(2$vpeItg&n8VluztA^V z4$2BI*q@9)B|-+bi(1{yYHVw(sK&FfvG(Ju@8A7*{mDN@;hHZFw!1^!SptaQ5n>TO zR|qeuir_SyhdUGwz<`M^<79<9N;cVdMv07!jI$$q+_|$=$cT(=&R!=nviHi0%yaIz z%wMuXX0rEo-}8OX^Zgm``@GM~awCbanS0~yz{Ps-ExjGlw-fg6Kc`0?DJob$B)veV zhI%f+lh{Lxv36MdQ!Bp#e{3>|t{}q1ZF?_PODQq_{Db1g6=)g^5h64w5FteI-y*I$ zyc{2m81CE9hLy5rNi@pMo?mRG87lq~G0$p>cCkxOLqriuUC9qz0!bTQ<$<#F0rU%`u{%-g6 zJI_4)9Y*m`u#rXMg}RaUrzH3wq+2VfHDD!gIEmIhEMm`S_@mFyfVylkdsT`n507L{ zX6J@zHqy~Zf?>^8cl5as%C$6;gB0{MV-0KXZUa=8_)frAhw{BrVwc;E0a_R)Xpt>Sl>TYB}T!12pWqI{V;3j85|M})qN zUlbc{F=YIcv+v%a&n5?exEW;Rl|V0Imw**vrpV&?agR8M3lNNA{VHO&~n$irpE2(2%6!pyFE%f$A zG6ap8Zn^vI#az-9`V`mK4#l>7#6>iJFc5Lq>Okq9SM!*yk6`xHC)VHy%$i0hh@1_0 zRVjzsfR+xnw!5+SVjweM7$vjq_h?Zs!(^C>a*4s&1c%sOCL-N!>LwAY!Iyd+#CR$) zXLsybA-wbWdi;^esg)tj$_NrB0OPe0RIyZl<; zkqUaQ{ULqPsPvj?Wj@( zF_91^EOt$f-za&`a=JNGV*JmZ{s>9k6Id0unyOEVxjfB>{Qnmq@L+8BCfV(!3)7$O z3-N|4t!01cGXTsuAsAjqWH~ITsRI()#6V4Ytck19^0ACh2=!|Wc!iFk5 zhL{5r^e&Je1@abO;V|)%IWw=$kank1-L3MD?ZNt5O@kh>4$^vjpr#bRdg%VR`yOQC zR{IILxGO^hx$3owz%!AA-D|%bs-ePokkOZa#v9GwiAJ-=+o< z3*{IO0@hsX5G#fr zTq{F3u5T>4!IAO)?b>&OojuyD-tP6zh&JtofYzcP7b*FBZf(`I{RQ3YDCryWx(_m5 zCha`9yfLnaFq%yACWHp%hS9>>oy}6HpIM{Wa=(aEq=brB{d6(b#MzZv2(b+z<^>J! za?eHA^#a0|xhZ}Zzc6XCqshs6-QX$8dw1cdeX>~)0L=ij0YEU#(qj`DO%tO*Nya?T zR_DT7OQy=Yp|E?9qgo(D|8M&qNuC#BPMC>?&@n2J56a zFG~KVfJLJlQb@jgiB14=xfs3W9eKNze8HKm$n@x;6pZhYi)_U65jSfTNyXe9yHcpL za~`Z_jr8JObL@iR$XuJGwug`jY3AmdrN1V`4nzE;%F?SZ?<0gFxf)N4c}nP`ZZx5I zDfd;-xPv>K-4!v4b=y+fK0Q{8+#GCMfzy$8EW{h_*s@e1VrX`Sr{4r;bJf#T-h!p4 zUB%Nr%SWr=b7F-89&-&Y0VL-rao(FGq3dg*jTvO_H<3Y5P_&l0;FwNd#ahB%# z`$|ZL4vucC|MA3UV}tf;H>QR!)q6u2d;j(dH=wBh`T*RZw0;C{E@J-yzSS0{IE z(^SeuDTByc?QVytVr&d+Ny}}CSGD}V_5=~{Z}Ew2#wOS)+$FYm_rp-%(^;`^s)2hS zLm169`WyP(S1|57xO-ZY8*YZhz>%ws)`x25nc7GkPGQ?MIvA=&sOSGT6|bUALyO$& zF#x^+zFto2@Mc2h6Kt66-gi9w?1%uu&C;G-7OFyO_IKX}SX+uo@lhZ=UfM?njDu1b z3XxlcF4W&fabt7Se)=CS-?_q23bK7e(yD@A+pX>fudFU&U(gEt{pp5cnoRqZ;Rz61 zyM6|;7H#H9&z1*$x9Ut%4~ow?*z`)PJh;`Bh#xbKO7K|{#K94DjE6`{ix4B zSRE%(PE~gm&xM-j4GzQfIQbj6R-2Jv$+lu>0vi!?CkVK;Da{?prHX`xfj1H1h~|F$ z;%rbUA|A+T=V6|}9XY+g70bOj5+I?OmOl1guYm0v=bT9_q`^&}XQHm7gZ5nmDLIb3 z<4riQ5?UiBVwcklUB%SMKqGJ2e|c~6309Rpc30!sh3aAA2J*N>8|pXYD$KT6Lgr4U zZVl&a@s~THxgK$l(2)U#d;*xh^sy<^NQMyX)J_B_d4Zum-HbW56KsQwc^dDfRk3XnS>tv1blI^Ty{ zH5Uq0<7HT%v36gQO6{^@BJc?;fj-kvfDkCaNqHbm%;*$qq}K(Z}(IHjK;&TR#HsEJ7MNGCn;Ozz3+;K z`ZA^UWp~q*xKIQGV%>k9AI&U<30A$-WDo?|-47m`0&iCb1%3@C+3u7JF9(sL@)U|F zVELde{MzR9Y@7ZcN+Ngy!d?c^82@jQapOUEABFv&_5R}^gSOBy;DZmbG9Oq|LJeO z433Cq)LJtFitYUEB`>)Rlm~;vj8l^Hfe)b;_BdyvNxdXMDui7xsOk-S%lQdULDWIy zA4NwPOHQ1z>|Q~aU8%xG``PJ1I5WC`K**G;CY+uQ09?F1wTg>xg22LCb5II~Ka;6OaXmv*@Q`eI`4fe;)2{kxIRSiK^2X`*IsYt1EDd?pTp$n`Hx!9TsEs+kvnVa)B#>@6 ziEzTXK>Hv8DTp}PwZ$JX3O6G&(;dy}HufFup*|2&G~$%TlIfyV+uC+R`_+?vjVN`x-b5Yihs)jB9 zVY%IbbO+x*R?`ii(Smw`!9l}b!~P?3HcWP{^+a@E;N>16HEQA8TciM=lrGYBQzy6g zjhP0Is;y0B!67^z@3+xVkQ_`k1n1ZAF40{08Jqh9`1Y0Qx=T8K@cBLe-L#IL3e~P` za^V9*a{dE!{aL*vLt{t2U3mwCWR%|<1Je-PoX+m?ZvWgM>}^0!8sUN=#fFD0pf3>B z5GUGX?FifVnv?!$el2k&7c=oQmPZw%oZycBScJ_3FNRAWm62|8@h%6QvM1P5yZ$q)bg z78HSV0&1a|5Hpggq)Z{+h2ZpGQ+p*}_1$O5orwZ`8Z2uoJ>&qqr`cKzaW*PA_zU@T z*N2Gu%cuQ^wU&01Uy}z8Z%iFfR%UDC7SLRs@R6kz3cxm=dm~C_lno^}=?77|l1VY(F!I*yaWYGII|D&qz572T-_wc(( zJ#AG^v-nrFORV4jE}4z|K68iFcj2Cek!)|X)EwR$I_tCty=cc?PwwHyUz?!Tr=0ioq&*{9HW zV`N^Af?p3lf9`ekel>B{mb71MYO7`sWm;yricjViq=3)Juz+P&Z|WqJL{nRVpP>vO znxQ9>I!Bir>PtqIUM5j7S$mSekv;i>tlI_5QOF-}m`+nmM1Q55FTt$=VpS;yHVGb_ zL1g~tTP#T`2Bvm!kKz_1fs(9)dk2)k7BO2SpIYq7Q8%3>$A<0@YeIv{%+^LK;3`Ni z4oDx6o$D&?J+>qInibY^-q9u3BMX5*zCbXs%$`FHgD^fZsX4yG)WgiH1>T1fI}=Kp zOZr!=E+>0DPs8qk8wLZG?9qvYb@XAE`yhl1g)l?7siRys_bXHYqYCOTac$6&lJ+Gx zpb;|rIa==F1aW^tkGMUrl`C9|Kd7=50&{O%4~4Yjy**3U?-B-hxx5qG07;HfF^uP#dRJXzj{_a*Gx|T#8-cjETFGwyp}6a^ z%5eqU{ChECjxgAFT&H(Ba|7GznjeeVxE={#ML#Zy`K+=0iShBU*=W%;waDLPnD0WDi z5AnwI8&m53Z4Onu-C+a+Gx6>5nP|+PrV&Z#l;j@UZZ|o1<9pA8=UL|C*Msu zDYtRb_$r+Y;*fYFe(TF%1vSdq8_bfG^8?~#Y+r0G3Q$QlqyF3UJN9jtj@Q%QnX8_K zreZn6Oo|##vwqRsW$Bkl_Zamzx7}D z?|2w=SN&7c1x=R^sS#_j134`r1VsTcO6Q`u?^hqY_%b3gpRL~3z?qXaAnc70ru6N& zRFxqA%Au+`wuckn=YPHd5<#;ItNCc@$Pn`zcy6*vN!6q8^^Q}ZY2qI(BAbu+`p$!V z&s%m0)BS$-SzKOqK~;5rch|Z<-5lG;oU0{;;zwVx9iFyZK$=v!RC&C5L{c{Z>a!-Z z9v}D$Uhy0zZYv^jpHrMNtn)LKj2>LzK&tV)f^o~h2ghTc5vbMC5tpJA9eNT z5kIsDf7&Q4Eg)J*e>kxR`Bmf30{aOPftH=?G`q!BqXi)hpa|T_nUr|owRyBk15l|? z3;v~%AAq%jZa(QhB@t#NNBL*zt^U6I@S-Kf(kY{rcfuvEQIb<~t~o~?fOT`*tkqSbUW6>U^}E#$$bo zOcgWA%%eE^Ja{z3<|9uOTqW86k&wh=Apv=-zp^if5lb zeb$JHw4r-a7L&nm))=!BJBzTJ1Xm0!Kif9(x-p&!fKjaj%=8aqeJ==oSlEa={a;!I z;iEPa)RJ^Op-@WzHVCaEK6n(@75Er27=y8cy5GfL=+qEz@wPQQd&a`c)Azj41U7~V zj08y@>hP>B)76GQk_oOxcwE1-Zeyl(ShUwI_0uS?( zGq^i+cIA27zrn84EJxyAa)S#kka`FIUP|xpVIM4qWkB^|jDCHqw7MlGqZw;Ycw5tPoBJ%Y?eq z(6vw5!4NsgJkL@GOe2j4SG3mBFj+RFzpF2zUWCnC-JlPh{V%pOoSr0m4Ow*uzVL$7 zeaev$aC%o1=wIG<(=~Day;L$qm^pcR({Fn9>bAhzCw`m@ktNkyi4&CHreBpR!HiXZHIx4-d!K!u-U@k z6S&{QwNTqAuvRMA%Fe-O48s7^_A-}A39)IG9Py(@J?j)vg|chKc{pmWU)_?`y4||J z>CHCDoc4HAtJsL0oR2mxL7_3I-@CH-9V2KwgG^WeLwUqI5Ixk}i(~?Mv`KfAMT}w4 z{E>~6bxLB%?8BJiZ`}-ynN}e7eYkBK2;f?`~ zGvZQeXjusoh>2o1SiM^5ALJ4U{9fY(lXY;wfEChi{-<0 zbt5nSyMr?O%s9>@Hq}9KddnsuU*a(p=uuyX#R}DSi4bt9WilWCHF`KH)7f`_Q)*hU60RQeT5`bmzZ_h}x#_LD z-6S?O2DtOe_xWklMl_EGJB*>w#b8U@1YRBX_y*5=(D6|;k4XD%e_9ctp84M&mz8r8 zC*cLylav&b*Rgi_1+Jdu%oh`;7hg7gTAm=!2rsuJgEGGXJ4udK^ z8#(OUl@n|W@b>%9S47`ycVQ+&8kMtMz#AT!dy5i~bpAJk6tR$1KW@>$l!Swo5ra+k z4q%FDSSv;oGNvpnl?(C1?{w=faZe(hOsrNa@;+%@ZO=CSYtp0a<-voz=XTBCaxTZx z$I{Tw4!lyxakLivFU8$W&HA{lp*Cp}Q<&2GhS9X+A}LiAE35uST<`5tI4j$5RqCIg zANWcZfb-wnw5O9_3PFVlqocw1-OQ(t14j-&C?w8@j|{$9&-A}phzytyeZ5#l=UB|R zj5TsFe?+4`xS3Jai={FKJXXR3Yffb0b~noQFiIQ+yzcEZx6@yj{7x>39DC8AK3{Gq zc~n*ir*h$+`JJ!XO%~TbrlzV>XExa+ZbS~!46st#%l0OpZ~>TXZq)d52g%dY`-17q z`AR945c<3HrM_WJZcAZUm>!{j@Jnboa_z&)>cPP4twb#5?_d&!`ujuXSTq$Bda>R* zESdyntl3h`EbBZ2q$*Knas27T=x|HukUm)g>@*#UB#hZ9R)~>2st`c!!~TSu;wNI- zPk)Du(HmyBCidh>M<&#r>v110rbk1%i3&R}#q-VceHlJQeCD>1c39~?(4z#A>t;Io z!xegRboS%^wK8N;K|J-%>yURBm)bC5aFZ^nJ>^&0$kxN5y-l-6iNC@8g3Sl^>J4ry z^Z)I9`uDtDO^T9#bx_km)EjAshwDwD*kraJ~DK)4jy?Qu`NfjKK3f%84af^xR zp$7NeUB6OFADJl$Kbtmr_mVvqTkcAn8_KiMdevN*1?`P+LB(;42=6v_i$d=fKwcw}5x7M8bzQd)@dz7=U|D#vlEXlO(EDBPZX_zncNYoe1#2tuo8x7n}s3||Ts zX|S5SRqpt*7vl5eZT!lcWJVDOzevrJE!hg^`3o^aNz(gP-&S|iy3Q+32aV-@HQB;j zO0T=Z#fW(lq(39;_4P{CLQ?Uuf7nx1T?sD}R16JYC8$SQXX&AZ#CainkjGC5La`@5s?^~7}cmGWDH>H`3C-0oxcjPDv`sat|D^#NYzyz3(d3>u3Jxtxw}G%r2;CpZ%O?goF?YYmiAm(tHO% z&nBKL`gyDNlVmM7Ls*}>EA)y2LI7QD!r}vau`lnQbS`Y}0`wbqpG^Y3TYY+L!}GXA zPe{HrmEa%M1=6brjC>*3YN4sF%EZr!nPc@Cnj6b!9LMZ=~nQm?gXuH!-D9aUz+XtN1?nV6A8-4$9Lg8~1Idoz( zmMcuS@$4$Cl}oJQYamV`%g>vQ49ti6PSa9kq6|0k4}}5LQP8T42t1!aV?@WVy=y&+ zUQ+&c7~T(6^|HeBjty}SHWaJU;Ok}xT>j<-c|B`r<))%zz7Z#lT3J%RjFIO?^-2>Ql@zQQdkOD7hfa_(|ORXtalN9H|TG0B)b>dw&KC-AhEbnMz=_D zZB$vW)<({A@6k`i=T1j{;+f^mvKIZ6Z4F~A0hbF4yAQY^`}B;)1`ET6JH!I@n>*{H z-5q$aEzxX;7*?L@htx7k)Hge#tO8{L}?MVJ3ym+#Lv~>BHO2;z0x8IcfK~7r75^4)u|w(F_(2Wt~PjCpy3} zs<89VpRZ`=9xS%avqst{BPC(GaD!V(je-W2JYeVg&HL)=~AkdGCCGiEUFg} zB$4aXuf@{ruB#F51*X_D;sY4Az& zRLPY>^!aTj<|-4K_j_HQG+8-*4(5nxc8kABc5tjP%!1P^GZy)!TcI%8um-I#J=c)| zPa9Q8lR|PsHWQuiO=xOl*xr4h_=FoyWUFYdTE!H&uMWB8AelBvrh(HPk9$ z4zUg?9#cV<|2zZND$2e-J3l7OF0*B~h+DJw(ME^X$`Ufu{pl!3d^D(d7ZxuAXYAjc zPEdjiTKa+xTeP*dK$^m^_ow>Rb9=S6oSH0H2fR)KtH6y8+WA$z-=vd*_k_@i9_P#R zHw-is@)#pkr0>@@B&X0ap1###pKANBX|Vm2Ypldo^vk`GUoo7SY5GWfG-M zNs_Z$E3mP=nI$3yAsQ-zYgNAsju&gU9m6_3bhL<-uMWvzY)Flz=fAwH?VR>OiKhz+ z2wj+d3~=D#Gcup#^4TrIX+XIaQ$tnYn0ZNz!l!eF?{?$#s^1O&Xew$6?Q%cWvk`84=QXa$-ueWA*$HHB!1bs_vtf2FGY z<$fe4RU6R&jF&`qRP3bc%fuTtL1oZ#VRTtyoT;HL^U#*74M@w=U;zoG#l;3`n>M(KwEEarb&tjFM97rQu1qU`3z&X+ zl^0`g7Q&(_j!51FT|#!rvVX8$3ah5y=1I2eS4tg!AY3e`E|ZKCPF*6r#_uf;FV27e z_DpL`sfDRyzTNk~g_^3Xyr#xW=Vk3azgnN--`}T{_%`j>XTy~8TkR0bi_}z7rmg|` z9F@a9NF5QGvUXD;rhBEaEcX1~Di)rq5i7K5t1hk7ALVtD8CbNLO=45xgerPTb^nJf zAk`T$RaK@(&P>ih3jd2N{v-Zlq)$`d)lSa|B}&Z>WufN;{+t8SV%P!+{LEc;R&V16 z=0UEdsWC=AP)=A2_yYV;l>5Ea=PLDt(_`~RW~pV9Oi0|)s_$6=d{9n={I4u?>34bLY!ykOdb-H-j*rq%fXL zJs%=1(3oG6$&F`#7$GzrLNMlr67Bplk;&%9ljx8(F|RJxEA@ki^amdgyka&sFaKtX z8w=<+Z7Y!s-(At~jSE(!%OID#HqtREB@#fiFF2Bx$eVD@2i;5TLr}+nIJ_5KAv>OVVPu4K?=1zfCy2#S0RlO-suL0%%x604E(zQusqqe{|krzHyj>q zA=3NG-U^q66e#)a5%p9N^6`=2HS#otB{H|*fgW_vRMXPu`wQCC}iqU zgp>2A;2%OAm{$hn%Sw9(Q+{nfQ|cFrJv#pVCTg$*Nz0-h=`wV6UqK=iH)m~cEFeOR z#iU#b`Qy?94nB4-_OUlMG_+qeF0g4w8OHGb_ZNS;_!-2Zi(7KMgLz9ph}z2^e>3?C zi-!F4{Bg?{H9L@D{x!DgdA;co$F$FLx6g#VZzc0pP8vklQ0%1(e)pNWRP1TL_U*Ua z?&WT?;}H+u^A7o!X~O4+&2~!wiUE#4Ixe^3^Yp5XCNvT!ud3 z>{x^yuudW)>R1C(O56}U&>|zV{*Oe~`9~NSMJlOt;DRJwtT%Pr8kwx7yh6yXgp+W* zIp!WvnKFnnaqARhgR7Hd7r(#GrFyxS4x$Ycn~;^PEQYGq*UyAo|Ms-le0OIG;_len zAl7b_-3ar-iORF^x_bZm#59wL^c?HeX<-?Pme^K{by}K8fx2mZq|Uat*rIt-ugVPp z4wZA5&-c+XHM)Q9t$k13xwSg4gaP$OC$a47QZq>84!%j0Ek>J%xBP6tVN(jTCiMl+ zRsP|v;+pC^t}Y}`f2(8B(Iv&-2?{0n`1t_;lWE|*g|Osi2^*TUPFHge?x%QY&ux0H{Z7x z%9>%nG0u+%h>B*W#+W-GgsCQcG)>FaCn_XsJLS@f#{@%24ru0t2UDQ{HQKwti-FLuhJ;+8h@JJF{+@3c?R`IAd_K_p>XnlMJ2`I=?)m z5|4>4OZ`J5z_o_pS!-#zdYc8qcYo#%s`tyfhf+DYOz%Zgz0eqj@dXb<9*T*U9UQ!R z{8~?6Ke$s!J@O9HRQAt@PsmpQcCXjEl;GFsV-P9hUlTZD`5@+@tsbkMrHUq1_NqSW0qn` z`+-4FrB{zkV^d=^&1M>c+WzUI5gMT&BM<}TX|(Ro=4$O~)UQpuVYhaV%USbGR^Hza z%!i#~Z;mamzy2^>AREyXBgB?PZ16+GIhDNHMf>_Fx|YC-NH`!N*L;$LiuBTQk0!Q2 z$!)6WC(J+Tk2op?fYeB-hh5tWdL@(TOOz&IUen7jJOdti;3?0wl{zQ%-5S5JcO&Y( z&-F8vf%F;3MqGk|PRZw2ox|)DIas7TAXvbQsHgB|TQw7;i(p-K0}m2CRh@`CpK`B$ znITr9l0c&3t|eQ>PmN?X;uge{FqI5fuVYt8EXn~3pC{V3-#4ru`u*`rjT?HBsO1h$ z0hL4ew=*y{8L$#eNmM2s-&&WVpJ8w7mVF)74NcmYCz+3#!U){e79}3~)CoWqOS^%b zpQ+TPTT_O5bjIWxB?kcVV0JbCuSjQ z4oi$47Zi~FT&#h7BmnZ3(pXFx_`)d9YSIP>F`FDNX~>7<{tWu(1SAmg2^DE=*`-UZ zmw);yX`|5^#C0oM8}Gtk3b$zr1F$Dj7+<9oZ*M$l&=$-rqp^33@Gv@Nv1UFltjkiE zBBm$tGOh^HcpnkO6@Lzo*wJ)MS4k#MZ#$Inhg#dK#oAkF&oe{RetZ^i1qQ)UT=*?` z<-458!j)~Fj@*IN&Z{B_rwP{S*Yuxsq4R3bCX3f%+8-_&Jou-|p~<99~tMUv^Kxo5xr z`*`g8Mi{QFlq*dcKfJBl1*@!YR`_Ne^- z@J*!2td0Ld!<=ng(6DRA$M$Zm6v*cYwTvE>EbESslBzm}S9kf&mY)x2ii8^#=DK8c zWzyQaUdG>LRFuIXlja;ob&eq&FKEZB%c-x)kk z5;0;P@OdR~#Fp{6tBCc)25#e)Eurp+`Dn0GXLX z{^r%l9k-1wvWQFgmYHVgP{ZG646fWp7KZHwYsv7dk z`b>Q+sGPnurb163%h1jE`WPlVxD>?u0sOjj>a|_H8>=fa39gnz9%1g)sMOv7Sh>-C zHV_yqhg*+Z680N}tdn~k1FVy4qI;Bbh3SWcAWC((`=cN3=fItUzCCXZla*$Y-A(Wxwm83gdT^`g*37 zf;yIB6Su^Ker+;0H=4Y2Nl4Wqhi(8n?cjrIozBkYAK=bo2#VZ)L|U_9?_IGt`4nw4 zKoGB3mFO%;njv2n1_hwrrhi+{v@;YUU2I4<^l8EClEWgb=cPVO`(8DZVM*jby#v z|G+XvQhZe@sk2r4cF)#^SKmjUyb;$S?E#U>xqQ6O3H(FQL4bHJ1 zuEr6_8kz2N$N&1X#cWBW2fEGpoAJN48>1K^O&<@2k$ocP_cbT4J!K5_NLGTe`_Ii| z_^^`fC!iB8)GGP>;akVk+5bM^_N`&CPbE7K&7aNT>IpH-Pu^bTVvAgssHCX8O*O?H zq?HTKyU<3jEh>kN)*pOfraoQMOb!ecdbJiQG-vWJ5_311M?cyo-{m98eq?CZcX;IO zM<4sCdL5lM&5DcE-NO$yFKW$9>;JsmPT0`<=Fw!&@;R`tDSmp$WWYn-RI=$a%rW9i zv`gH>5OqJ^D$zQ%TTcK|Qc|Zs>g%GP>D;+vw@aQ;sjU6b&K`bO0Y2O@{bSw0fhWiz z!_;YGFmMP5BS){17dpYN)SIs1(S;2?*u;i<82#rWNSN6{>7O8P(wE*tBZfn*ylCo{ z-s(y8nnbb*j^H$%B0ih(5Uv|3PP19q;bQU7Af|wR>lO)Z+h$89XqX>MoaFqSq`scW zL(xIC*|q8nG?*wdhX!grr0BkP!%S7WZ*X6p#2nM6)!lvCjm10s#$|kkguvQ@^rK8?t7{>pIXqN zh63riu~>Uh@@+5s^$P&)vk`h9`dq(Ufy`hL^%D6XfkiKiyrI4W4xSZ29gLy-(>!|m zsMfzD>|T4z|504GmTfhXcj!v-31gN&DFDAXlU9aTgVL_r>fKyuq%}4@PV)=|CEM7% zq;cEG+(Z?4-9p#U1#P^&py3o(^7KqL8w+gYEOoHTpS`h+opiz3`y66Uo)i3pgCp>@ z&$%=c?+5f(NNX-dlKCrX09uLHI8#`aX@WNHD}?|3cADBBqg##d^*@-w@pwv#9%Huul3mZbMn)=s&;2o}MF?ar+kkt}#Q6s*#g&Ij z<^RE{KpR&t3YYgc+WfqeK75eA+Sae7_YK8N)$_wVL=Gk5@Fop2L$nCCix2e_nN zfpm^Tnn=@YE3ga9YJe_gz5jXF{1QLY@&^j(iId`AC5^kKgC}g}_ThNDZ<~5rE<`a@ z2_Hox)4@`}&G=oDi`$UnojP7oTq%+--?yr>A0R{+lUlV(3q`UXi^kVJ8<>m(*f9oqvOUbd|^Ot~L=*^1y ztt)zOdalnJrk!n`*WW}n*Bn3CI5|dGIGo#6?eS{gq~s|)%_uXmfhKs+dxpgbW{b81x zk+uF+52V;ayIT14Z-CU3a+(n{9zUwhdSC)sckL*ifi9(MvO-7fxflolahpHy`A~_6 znTJN^nvQQYjHK`9ol}jpwY1GudTH0lC0dgh`B{fh?H?h#E*>3~)DsVn9N~4pl|JDq zZxN2OhH^Ij`gl^wR71ZEI=c%NN@FYULjfB2kea8xGk<0uC_716<1i%4J7F&B_vD@wrq}xIp3N}33jt;J`a!~G1ixK*kbM8%hi3S%NshJ zM|M#k`{REh-T^dD%g0prcAe#LjGOfAyxKe>fiEKa8qNoF0UA7wtFxG<)skQT^oN7P zh9G5-9{ZWolg@l}G$VUs_mEs2m+_Pn4M(Fy^u9WPza)t83j>XED1z|gBIl{%*pkKI zVZf8C|Js+KdKrdIGEbNu=(?4tJaH?XtdIS*zVtsd+xI^dj^n^_BP3^sJCQvT?rh24 z&fc3Fc6Ktdvrjg6SxJxbvd>9&)Al(J^lCEv87<7g%5b93mFF}&F? z@BnN`bJWoN`f$AV@27@k$V}6B{Qj{eU;MY*4755wdNw#igdyPkbRuCQW-&ilx`YB` z^G!ki7d0+;nPAHDI0JW5wlOhWzw?)(+JgLi$bd~_i>o~{ye}Vz(*M20U7Fyg_HRdN zCHwE_ho8k`N&=&;ZB%^_wqSREGYg0FDEc9yC!_j}V6+WC2PqA?h6`zu&Z^GtT^xE5 zaifD!H^U7h&%mP(#OwwiTFUw4Xw-XI;}Cq(;Kb2XjoG~Ew=nn?2bF-SWdri(*u-5_ zyro*|@V8Xmu`kg=?vA6l!BQ^c{u9mH3T}yCqSnnw(U7tiQ;S<6y{>?GBgr#Dj{cM-Lk+d1=SWffETg(GZ8*dF zAyl)<;juc$I-8HRgr??q%N(G z`^oSmA(6A_6TvNIRe>}|UD&}hx(Z0}gNuRlg~9tUi+xJOA3WaRG7*>F6U?e6+|cig znT}05m$Pi=flLf3FJ$ef6-T!F8-NiKO z%`LIjFY2_S8qCPJVniz3cS@G@2s5^)ZB1+Q5;ufpH_CttI-$T;q(@Ln8C zwKbBM$G-@i25yk$@JC^t1j@T7?sz%+u_C@fA!SjY|23pVzxRslHnZ%jmsd4CdPttM z7F>02t2h;!bW+Ak=0fjyK6C;1tN1beI)Mq}EzucKv-i11`p;}v0ujKU87Ryp=20Lq)zjcr58DUr} zt&c0^2J-(FAoN+DK;+I9b4^#N943#OLC-ZU5lSoW0No-(LILu3C5YGREXE64CtMmx zWmE(TcOTYajBNW=?3#Nmu_^W~uU{E&=4q>x(pXT|Q`J6<+PXbWqFfjSM1vS4KCdr5 zpvlP?3Lb_uGc4I@Qs2d;c81>{{dnwn{sAHi;}*S#IshvJ=EQX1Bx^$4Tdhds9pAs3 zh-uv!*@&4vZ-~rwf|bpGq*gSXvL9j~AM|Ylmzv{iFlEyGc5Gt+{dRqtN=9*V6JAMY z>E-mY!w);5=03UTy@Aj=E(tk5RT}Uj)r{n+4>~-eV_%M9a@p(89!YYO4bNu(`K98- zv0|D&pectK%*HrU+}ZkOc#|VSoh86GeL--8T`}GZa1K~Ue>`TG# ziJy)dLU_S`xaElUcl6t`CAkN@@@v~4E}j$Rii_k;o`#UB;_-=cNu)R z4{@XrA;^31k+6Mae9HA303E5k>F+5ZVAQUk;KXOuR!R!7Y4M!>_p>nngn}YX6dtkg z$+aQ1AVca=lUIvZQ17I2x`nWN)25w_>xPNxpV>gR#<+K|U+8Z*ccSyOw-Xt;+7run zxC?=_|8D8ZOgLutuZ3?Qy!pA6l%Yu(9Y#hjjEwi4Z6C|@&eG=ZudJQY@BcBsiqww;(c;u6+ zZYH#!%og$XND$l3CVLR!nIJfSsnyFJFhXS=ndjs2@G)gtCt0kElkNa^V_NUt znKUcruO$K=p^TuRv3c|;WJ*A7cr%qn1RUJk>P3xdb6t$MNOZR@Nkk!BVtL6a)SRs> z=KrLQgYDM9_*)vau9V|jmYEpnL~Ck;t<74?kq6mlg@BpxtrE-k= zn;PX-D_owKI)imTX&BZS0_kSTIt+~5vp>@^H}^ob{PT=CRKkX$tc(?n-qQ0$8ldCe z;5sgExb+Ci0O~<>lDYY7gLrEI zf(4Qz3&ZtbSA}{X(^4bVba*r0zLwYCF%2P_ITZW!^OLXgmah*iq`Vj%U4-;V@9k1p z+1sWh_npeO(t5j_n}7HERdCp=@(59IDdF?;4+Xp6k_s8wu${gKXazPNnp)(X2RC$x zPT-e*$ts{nc75SbFIr@+uv7R7u|deK<*2*uYI;#U@P4H}my>)EfiUA|a>@Dv4upZC zLNuC22Q;REugu9RWe(;2#x>}Uqom0512;ZLYb@;Ekg%W0w%@$_m`?wiXI1Gj%vzG`2e(nWHkB}cc4xt45RC=kY8D~t?76uJ7PKxBjP?A~gib@kF@ zyR}#5@XMxm-nka~oa7T@OBQNig{SeC^=oT7X;;sD!Pk#r2=>iC@5{gvQ!1Fv&JM^mn|S~p4_7|@Ta?3_zFyd7Tk zoE%bUs=6b6Fxu7U1xouItZ7Kto{*undHu1fg%f@aqymC+o|>3#)%=Rx5U{CQizQ_} zPA}{}Fj6Q~ql;xA#XgK?c1AQ$UIj>L0x?p4O>oHCwWUMVd>QbfE0u%-d0;`u3ZJ{3 zx|&eAM}{?vsqr>&{4JVoF`BkNJ~&5NYku0|Ivo1^T)$CdL9^egCnB<6a`eE$11Qgr zXKj0UkEtKwY~)(rG4mcgZzGl#r=e|ecK&ofyujmeajEdx4-N0eXJcE&5(^5q>H&;( zF90{CFLVGkPh-D&y?PfUo|@u3B`vz{KgcnNcx{AnTFdH;K|cU!+zoF4}#RIW}lYIMJCQyi` zX2&EWWO3zrzPGx81B+ z;M7M_i>-aTBUhf85mUQnJ}F!?*mGBTV&t6~%%TWUgfK!lBq}U0ukd(W^3}~)xQsp! z6q~-9aeCRr@Hzcdrmhbr^0P3%=t1yaeB_`q=8$2Yr6J$;yT4pRbHPl2kDh&i`3#_c z^6{hpY;&r*Q^KLze$luB^#Ti}X~n;6FAWw+iqDLXdHpSvw=U#gYsx$m_`9C=oZY$D z4bCldws;TRk?<9;4JW`gQHKFF_WoX3Wv8RY|NgN^Bqy>^p*__MQbE;bm8ZJC_$S8S z6pY@2OsjK|ioa-m+F=t%u6d%#Xh#BUT*kE4qS82sfPSjxlFq1GJjEWBWz;iegdry* zk9^WPCOnc3JU%xnh<&K3=>dpG&TDl9Ofvi>h^36j;Az~Uo-+)Xz9+g_I;ly-;!H{j z2w2RwlUqtq&hzZ?yNoJw;~HpzKo+a%*9Ih8_VDac=SzH6b#+zkJb2+j^SLdtHTf&- z2i%a^!eiUW3b4`(V%d&2lk8N=R^_bAWTkcKFWj1V>0-_Ab~|Ul;?~UJb|fq_bGc)z z^O5~-Zq(I?4?7fv(S~KKQnGJTL=L0yf!Y{~M?5B@eODZ>K6|zW;05;SQ~!2^DiDHaDg)(?PN**wx$rc?f#@wr?4>dr#rh*`voTbyGFqu zWKsq*P6u!G+@jj>p2qsoX2S!tN{$r&8>(L#Gu=&?{{@#$y~N8Vn>7BuA0nx}x>_+l z55!~Vd&Iz_L8#)|4ekS(1{6xxAmKg_+%vYq;k7fYKj4hd8#(A`Z&R8YJYVoUTMsVz+PR~ll;|j3 zUxm$l8Zw=O9PnqTb*rKa`{D4E|0P@YePN%`L~npUgD{yyUp*#@G={h=tZvfI-5Unz zn$H)P#Cv!m0tKK+-D<^o0ps|g_&8XqLbF5q%aUTk#9fHo;BzuVlRkjeH6ay);ARtX zrlAK{NMoH&YmiLKHQvs@@YPO(s1jT6;m_IL69aGwp4nJRav|0(3he49yUmdT8XsfK zvo%_!uRX>LOC!%ZBPO;UT^i2UEwnA}B)Ogn8eQLgyC<157Zhdw)%-;MoxZ9o-0Z&d z!h-~4-~P|TzY*Z=ri|ewD^;3wR0gDjC1k(IX8ECD)`H(DPOK}0Z4b?@HkRDm;bL($ zfridkX2(^Lj2h)_0x$4ukDEj}x|~yqGkS62yz$}CBZkyor~_6D-|`#&SQycBMe7F8 zMeX74Jud2Qcu|_#ycxNA-MG>W}EtcgBW;FbR*&4!4U4Z}9fe z7VttPMV~jlaPsqts8(X(G0ndoSE_^+xrV<49SSCGwVHw+x-q`rH@aQ=S$d+bO|O+w zuu*BzEwc@W)pBxx(Uky&tz9#kwMfF$U+-2x0EtNW9{(J`XY_urw z<(|+?s=tQJx9|VG+x)X^I{Nh_*%=dGL=5}9$WaZIBr&!gwZJOd&DnSrE`)4%^`MboLf+|rCv>zZfIk~@z?yy5 zANd~?5%@GvPRC=QXYld+o1F1UsfR@t6bWv=EDRD~5--0S0>q+G2IQ5H z#imjokecs%wogQ|o2W<0hn^fR7p7(4vk}!AK zb%iOh=d)QpxuHGG6F41S62rvXO6qyDe}Ie%W(&(EyQ?T$24q<;abc9X~HQ{-$ zfT$RCGDeilYtgznjsvGVlAl){4^5iWo?I3-`tw43Wj@V!Y+m>wjyFV<{M@O{Jhb0` zXLN(S&x#dGOP=mO-{6!9O0)mIz%4C)*As><=Y#Yr*6Y+_YoXmF{A>?I7*nupA7>~O zVK-rXBP8Y6H}c@a3B(?$42*EI;8XMO=sIH;G>aY%sdXM5q=7TKB&isxb@asE#|H{Z zK7Vt$sg-u)yZ}Ffq`gYS@PX~l%7flKApKFE4#ejrnPEPGeOfSig`f1=d3b)Dov%|& z@y@}w#46yhpfIx=pAxXYw~ZU%8u%S(d>VQBt7#ssmJIk7X$CTcON-lXk+~$GZOScx zD;1s)VW8LLFj%nYpJ*SomL#ynR+YiVg|oErK|g9rqM@vdlf0lHL} ziRF`9MZBlb0xyRSi~ED1ViMpMmk(V0n&im&x7=SOI%#rwcCtpWL}~&CD~g{;O3Mp3 z<+o+Ec(i@Rok)rQ6u3WTCuD84&-_d*CA0d|!aN}~LV9#$9enH1EU@C><44w4Up!DV zvZIn}+z&U6uJSj6B?8*oZDn6eu%<|rd&i6MX;$&Zq9?l|bV{U#!}+&v=W=e4{dX!I zQ>}8sj~=UKV!pO&{Gi(ftWe5muDu@>q~}2a5|9UNr(`ZxDfe)KWP6xFjJ74i`orXgwqxYPwu>i7vQ?KzvIdbEiZgf9Sy#|}ZE+1Dot~5V; zlH$71J^sb4{&P1#1iIA*bkvT=26qev>hMOt6lF^-fiC!pi%^xMwP7}_>k%eo$iwiS z&Hfze;Y8N0rCt@DocA@WQRDYRRZC-v#cwp&)=bGDt<8k!&Dk!!+V z^a-@4On2IJ{b;Fhj8mMk`cyI?AeFt|XW) zmkS*1hHxpk5yjDaCt4KVwL;1|u^YZ6hsG=Nykw!nQ;*r%9 z^DQ~lyI@Dcf~PirI&gulGIUCD(93r_AbPCoWbXzvwjPyi_$P_EEP>?kNQ`|heZUoZR(F{C139P z6Kv-XBaPu-g1I>wb`JZbpw_7iymt37FV`-k^M1(sTz(Li)Kqs_G@nKbKf8lZqwoBS zprk=}I0l8`DjQ}>)4FDSl2zC9+L%(P%4EVQ9(+m!A@qgasF ze9VnyVI=DqL_Q`}gxg<-GMdGs59J~y?|hBy z;#U))M?uPPG#c*MtwgUD4jB&m@lwxzS?Y%cA>30sE)0gErU>fC#z5Ovn(f4IUxdFH zBYM%B1O8*NEH3hXOfZ~D3+8QXC#{VtFRV4HSty<&kywF)dTT>{2~a@p6AVToG&I*? zU?-4m%*UvaYOFAMFi9n2O1&I#H+>bd=obYPSZrzNRP^0ww6F+0ySCQAS1B3inx&3( zrHerRk!sSF;*x!{zP!lCTNroSJd;9_WLa;86)N|IK0=hioIVv zU+#TrJwuTyOUJ{6lYlrs7-3f6IJQ%d{R{?XXB^*Yha>HJ5eRK~I@(o=7yxPDN{^1s zLLDOq0ra$Q;89zFk=zc(2^U(Wjv>gmmn}#que|H<;+W; zpEW;v2eS3`UM+{V!QQ>>Z|a#4Aq9i#ZmsyG0>hDIn{)7^JNVx{n?>zfSpyyGP~+b$ zhhbg|xi`WhTFLCT`Oc-3vd)!;$tElt7M+FNPHo#edSAzgv~RWr{3`7;v^`7X7jgi-7LFdwdVkLq(wMF}nJ< zB;GSb_f%3y+8f@7hHmCCCSf_j{SN>-sC3{FxSw834U2ab6fP|kXAYLt)RZ2!gUM-b z zeWrCSYM&}5)V~JQ9~HG-g;&LF%2MyP$A&IcEOIJnP!!4Xz=C@=u9mPUW0-k~o&_UT zq|%Pa?(w&C7#7XyM5i)lr!-?}W!1gsZ(O;kOU$lOCZ3atWFo4(PTFUkeKxC9 z9Xfldmq95--dE2d{Nc^ziS?!s%}x&j;|uACeJX_Se-7j4mLS466P4Q-AN66)~! z$&@jdFrFNIO{@er48mAhmN{kqql#CPNaaUYn8W>#Bqs{3-c(D)Ua)R}B0v&P+xVc` zVB1b<|A8NUx^}%HmvAQI>Ez#sHgs=JSD!BRkWtN?DlmXnc#Mwg{`+qk5k8FL&w8qE zhw`wb(MJ)*cZ9z|S1@Ixhf9oL+|C%@_=3pHWheu@n`7b9(c=r?5t36ROzzGffozqZif1asVP6j4@G_=x7RJHanCB*0v1)=d(Z}rpf5O!<2ldZHQ(0_!-Af6o+pjEsSnV~c*j~hQE>P5*jNVH(rMsfWE8`494v7H zteA_iI+LRQ^w1eokWSg5P-4Q*dF)U=Vub(#CxLumrtH!|-PpG%;JmDh1M|7*G!3&Ep{}og!8{`HWqf6iprz0&bctp#F^bbrk2e(J+`%#M61xKWl*!OL@#sxO`u3Y7{8?fuzv@sa8e8L^_ zmk|pciOZWpLs6PgXjuhiRwekRlI<~P{13(B-g8>_=L z_|pSEG^LbgXk^!Gj$uleE!ri*&;RBzCS(BbTZDoFxC6K)$$djmIF7;3oZvP&26Uq~ zI6+TbVDm=cJCL3VB0gmRl_ij{9%nP)=glqP+jlRh-MNy8t!vS~TLaHez;b)d2AhAEgBqOkqS2VS4P9-#y6l=#_>A}V%R!;_1>d7pXBrWB z>6F4(HoD^SEPL(h`h5x*gJ-Lvrm1C}qc};b*o%pCs4hr?yMe7R`g0VW)4o4PJ3i3< zWIBqxt*FukdFJ{57C;9Nd;fa6LEC2X!{n{?zFqlW=+9Tnif;|XPTI>^4k%`q42JJ7 zDOLQ34AS4qm8g3UMWcntP$CY(eDveRL0?SmNBip-_#G%rcjPoRxMR^@9&gDU&j|)to_da4U~Q z%;aGDe(l$^q(z_x0MgF{`r|Opm!^yioJ4;h11@zxZ;;o*+NHV!9LOYEc|xpZk~gV4 zy?)1=HmdmiISpO$&Kv!U^N3F@S#$JE+E``)_xVlKTZ)JBJ8miV^-#qNQIm_7Zj0tO z0yD2*@}VW~TRvw%agN|ce?Li=`13xN-e<=GDp~tv%WtD+-d}tFcqOGT(K~*xI&&)E z8vL{SED5^cROEHUTY;qV)_!O-lh*cT|a>>wV!; znqPe1d)R_*sRY!#w_aBBze8YqRX_wLrxg55^U3cs+wC}JnSv0NT9&{jq&3Qp zps)z>#5ux}#W*29H%$Pa^A}5u3pFVy7DFQ@`%jD5MIK)kk7Osk$a%A$Hi%&SQsO0x z>Wb&Lf|DnMjbTI>CZ-hRM$1QF;^pxse_qJW(FF;8cVNi}J4yb6v`YVvsQD3OWTcWR zp46RCx15p>PLmTZJwCa}PR^?me-BOr3tzuvZ4n#i0w?&mR|d*Ch%;cEL*;l~9JfXu z6N%eOd1pE!Jl;@|n1-B*O!FKkzd$99oTcYI?~4luFx^ys1QRWFMyt7_lwI@~vR-4r zJ>M4f1!%FW-1uQ%1m@jaFvcntjrSi%vBP;B@y|lLoaatMXQJF{+;j5BPtAl|y2clu zx_+|w_efI-HG+R^6?t^)I~ zP^Cv6TaQ)n9A&GdQjaJQzTT;SmbaOBm%%0_Vh6>edt9LLh!U*bfLL9SoXvn4UfXU6 z-x0>MqJ2H$}>h-A|Mo@hd{fFy9Zsa3eJNz>fP$|7orB7Tz6p=M43z zu*O!@>mu`mHq=>6vxXs{49eqffh%!i*Ol9zCZP3E8Uv5S=-oqxhPa*0m#zE`o%J4 z@L*eI7=*j+W^1I3F<^7+M4moiJ?0=~q7GeyeM_8i$qyAD?P3}iS6XYWV#XodV3W9l zH>{*X3c)d0C?mLHsbfg=XAip+Hf!lzZY;9?U>40w?nA5dyIjQA88kzFOQe6;rP|E#Qa*y| z`cFFvTM`9J<$ellY-L%*qb?C$)H6pSPENl}bla{0Goz`(Qr%4H5oAov^A%P%bxIgn z$0`2G?eE*5YKGK@1G8`Nnb*S%z?+ahiT!hU1QYw+&xp%`>iK$jM}=7PP0V*AXD=b} zT32^2B1rZ&pv@~Sy@X9d-H^OCo*M^P$R!qkc9&xGR)-aLx#Mnp)YpCV;jse=d;fJ& z+>_FH6aZ39Y|p`y6k@;{D;)4OQt-=Yf}%(!i%RM*WM1Nq1h`ihBy;=o^cIZyPA{6N z?~*1lI2iZ$Z;Q{*=4XZ8j8goMsc&pYjiH{i|DuE*rB>NgFZzB7siw+PfeqzMb!y~$ zf-6~o4iRn!vH^|;dG|+dAN{K59hs*M_aTR_e$l^OmrxKro5W#Z-?A!X_SfKw_QB=% z!B(*NG|{DQAWQ{g*NCryj%RPijE#QI1jeXy_W!gC9As8BjDHz@nk_1xecRAIO|r0< z2%bMnQ?Gw?Xs6(Jn}g%v+FG%{JvcJA#W}mAP2=N)MMx!AhaKzz(Yb3xQd`Tb>=CR3 zKolY8ct+R39kt}iH|in}u8$k$ZjiYT5G!U&A6g}nVCe5DP>?$u9LdJHAMy^BbJu$Y{2XiLkRG-s6QfDdoY110%nNe=Fh$=!x{zH@bEKJ6^)$u(Np7L4uUBh z@cR730ua~?p>Oq ztW$ZPXb#B!%w~|^$#K_Xk@fL)(7ij<{hD|YFM||=vMac9ZAVcwAc`KHd{GS(BTW8U&aePlCFi9 z9S&O5SxWl3z#Dxdpvd6ZpZDPnNv@#*$Pvyx<$6C?Wt3GHLK|jM;ftaSh499E!sWr1 zwU*xr+*~+>zDL->&|5-5-)u}H~%!z>6z$9OI; zxzv`r*$6?s$Sdy)vYoIVx7Yl;yo%4^P2WizZuR*aWxUY6yHgQhee+C!M+QPpANxi` zmfp0wI;eflX3XPl52l(K$ixS+o(0-ux_Y?;7>}yJE<#4TCuJgvi}`%QmECJ*9=-Cj zR>}t}9y{Fn*U|N90-~{Yq5My1#3jhSxf~B5{)~Gmlh2cQ#w*mhk;QX)um@R!0-z-K^&0V<}On_o=TX=Sw^yxrYS?Ie3`TDRZJgy^!60CUiT zO2BEidv{@X1pttQm%*?5_?gm@S)iBGhbNCXA!;RHLoS>XMSzsaRu-Slt8K9U%5GnJEOeG$3>JyRotJoJltkxw z-MpO(7)Kn*^jo31jP{iCR)YSPrRp--dkKk`Kl?N)EpSov?BA+2D_KR-ml;e&<1Yhy zT7g@EU|I5exJQOBa)Byt!MD#bPnj7BhRYiJ z{))^J#gC=V<1(k7=z`_NFVIBNH5A;jTHDMyW)`n&#g|pQ-o|FY{=QhA8*Y- zUVmug?L_*$@#%b;L=wQn{~&Y?{t?~<#l_5yDY<|olrRK-r*xJhB6rUpPtziv^YnV6 zWCWa$5PG7tKMaXI+R}x>qhq8u5I~^ zl53MqrF3QGfqcGk>>G9HyQJRz@k{k8A$v?Y_-LW3t&VTYi%XYWxbOaFs720zb)gyA z8v6Sne-C_Ne&+cC6ZSdL0eQqSDpFsld+*X6!*w3TZ5Q)R8~S{>Kfkw?)J2Vvr_CIq#O|&7kq`!x;|@$ z0cgc*nGYSohpUVpNJ-nEG_?zfV&J8{BNXvr=&PI>1_aQ7Pv%mGltbMCsm>-LZT=oW zCSI4+7obG^m1k#1!Ns4NmGq27@apJLJPMr^GR%&N<)A6P;m%Z&g>1xSgcv9pI~83s zG=v?*gzQlKL6E#t#6WrhTWGBeUV2lzXQJ5_J=xXST)2;kXyt0uqlLr3CNmpifrQg_ zM4QuOHg^#CSW*|Qm9%!sU|V6;=bsKVHDy?=b-sK&Rw#;d4W%GUkRFWY&ezGuS7>|v zclYVb9_s42i|Wx( z^9K!;)fs~K+)X&3Z;SK_MdT2)DV!A1qWxRqiQ)nOda0JTe_W40t5?gaf4rc-$>CnN zUAli99?@B9@$f{=?%BW9R=*7i@O|w)P5Z&A<~Uydjcr-r`h{W~Qg)R?mR!_#ihqIr zsf}eq&fJ$hxNwe%kh`sPdPXVi!NGCqR}l^T2G%`#tw^GZ%#^ge%NLC64Pbp+ar>_$ z@p3QCG(b8htNf=D&2h?3eccvBLc~-~WP>bY!3i;sOYi&rb*~PKI9QqYoIN{xK=vI- z4>}->+-$puIbJnnKGGIukG0 zTidI5xM&hDY~MNiSc~_Y_G8h}%3~Zeh+c#0ckZfr#CXS>7$3=O-aeY}i zZSsY~_LVkJJPMSPgnM{-uU^5&a{R}_IUJ!m6=&Xf`u*2PASf}(+{W4~QK1(GW24qQ z0VuRA{>c}L`qxudxFwvpODn(9v-_T>_exi!0!EPrtRAF^`%vhAtrfaKayDPLg4-40CBZFP80`h?JL$WvQtb zr1~qk-JknqBBWq%DF$*zu-u8fL9L-_IW^}HCNCoyK_v0|bF0|4%$2LF z%0vbS`Ksd8*UEQsno!NYUsO_E+d-ij{aol#>~A+}MbNVp`E@cJUyOG0wqWl%Ky?Xj zFnMo2Zm+pRj(tt0MC--YH}_axST6?Bf9~lt z!t_9Y_{#NXt@sverB`!bn0Uw?L*ZjvETgyzEF$3WCQ)U-yWm+WiZ@s3^Fdldj?(;W z!i{qb#^={!{ia6L+N%qJi%9Xi3BsWW8MWxZ`@N&tS(U?8&Ka~4!r=j5%_y%Tzf5Jh zxD1Dz{(85q^aQgt_8NtE)d~1R6Ce8H5T>qvpP9R1EegER?b{HB?Vzf-~WgZsa@3#1gUSK zL!48&k`~Ny9DejJM$TtGf1mukD>UBORtFU+2wwFK0kJ*Ljg_sU-o1+xLpRoXZDprf z*YAc1TYQzM`7iLx2ua5X37E>HX9M{&$Q@Rc%hi~1o= z4>=ek4yF^ot7aYtlafpRR9&->`7;1Wx#!H&fBK9I>n9(H+P_uY#e-Pa?_6KJn7tFo z{YZp?YPzGwvn$XdQby7#3F)zBXe^W$%Ui+7lzrI3l$iCQ?5%aPS7r2*+q;P;BNHBj zUjN;@J=t-&qeW_lT5PoXv*&?QFCGAI7#WFrl2o@6cm+$BAYHP5Rm_5no=J{?H$NJa zFCyym($U>1r-nhp-XE)#nsb+xp9EA%YI>mCf5DrfEdBWOV;NMp^OX*~*|8$w2)w^K zmz`v-No8u^To>J4(BIovX9r?1t=4NI``Ys?S(|v!apPfB*$e2Lus(CxbD7yzBSB_& z$wZ(@?j-vcMEx|HuJp+%anaQua(bBxIp>tnwC=<e^T6 zx@wQtaI8I^@YGvKBDFh0f!xE&S_#j-op6 zZ%D`x#l(dyezDk8rmR$OKNWBCM2sA0L<+81u6|QfunMA&_9%LntAP(}QhrxW(4KZR$K{=y&yOFKFHCVfw&fvSf z+6TiY7xh9A_nZZB%v5NDinpdGzP*CiJa>53!?5^!FcRaDB{b98od~#bGC%i!hrWLF z7f}e{YA{qJm)d$%M|k!s4r3ogu%(pRgX15A%v;oxGGx{^bEeUQ`$yVnwcLQr{sVU;7}hu+e!MX)VbohMo7Gpho@T+X^lFn8e>Hb;Nl_;(Va2s5uUU1#^D? zRiDf=f6us5%B!tTTJY951v~JG1S!6XvPv}kc8^lwid4pcl2VRv*a+!k(4w{6Uw+0K zCqoHTcA=4qkA-Z)0tL%`OSo84Y$vdn`JyhcswWc%w`8N=EpyJls~W|JkEW)ujI&@2 z^G#37{1B*^I|}NN$tMKTYKWr;i~!?SV~F)zNGUdq=nCk5;WAPVnKp|bs*)`FC*@`> zw}9?jGm+ziwAtn6-f%&NGh%LjYHQwt>B1U3Jphk~D#G!(HI9(~0}Vj(zbup~Q#OW; zzmZm^s0^<}WA+gmipnw>3)hPl_&j;)J5;H%ne-eKyry2&2NK!jS1~GMc_Enr8zbBC z?c&m86{51hNs9e6$`$c6KbZ7Z=)tE!Y$CX~Lnj%z$6SD9rMa?#t6&2DBGwN?h4RP{ zc(sPH*TNPtryEBhi3>@LA9aR(=d_*#ehQYi5AUrWtsWg6t-cKh*J+Gly{U*XBxWqH zObS!RFjNxILQEJlcaOj*YLF)q7&MGoVT zp&WfEh8kRc^YS&VU^-^!|5Ejpfr$Z?QE?e-3^TJY$QT;aHf_ue@iBsoXw3bDn9^0t zrace~Sihc~o=68}LQD~V%@BQ4Cp_FM+=!{hW9Drz{x%a;%uOzn#^|Im0iz2vBk&kQ z1S)nz^7M|L1^|yQ1o2zo4S)nNK7DGYjKK-{A*GESKc?hz%vDO?HyU3?ooi>rU%&~O z7=i_KWfjEb9=;z9M}wPRe|?>h!B(IZ49YOITo8%T>&fJ#gIsxmB$a)PbjeH@LD^)= z_-loko|V{@58cE+mY4s9)yta)pPVx=ATo37E9L1FF(2pqsaJ-MK!O{1bIklFZIUXz zd}rguPd}ZUoN&caNz9ZC$52$3X;@Ej^|JCY1upp;GcvPDdO2-m$oh-Myyl9`jies4 zv&)yxE+aIzOk^JI>)n0Zro?ECk@PZWmr-Ndc%Ya?r#sHe7JI5+pDM?2RJK&K=|$0! zc)}8OQOMY~s`%SibCWBeF@0s;7r~@^vDcG2ixc-yS_04$uOIfjz7`Zjq}K^VV-~fa z4|<+Y&HF8E5A(c$>oEg}*Lbs~lQfE9ZGX^-{Ih`R_k&S1e7L%{wzj%@bdU4}u3_Z$ z{>R(-ytJ9;aon=QcG-oU{X>#yG$tV?ade*eG-_=cu}RSh8J$A2gYd{u2JB_(nk}SX`;$B!y5C-_A!?0r`)my3|;7B@XVV$?Xb>hS0xiO==`x%otI+E6xR^) zHZE{C#9$+4H0^oyjxi^lqY8+LC*lDZ^ja8|K~UD}d9*;of_O9+z;3PNm{`wHh)5DnrB+#l;XX ziKM+R790Gh3kx(0w7{t{kYy!Cw#g3eN#GJrA}^rGyeB@SL1BFG{WnLhL1bd-kjRXU zj(x7ma9qYt<^emIO*Q|Up~wv4viFxDG9O;!=hUsak1mGGF@j7nGxbk8*e|E+F&v&L z6E8EFjOf6$T7UKaTWv`%Ls+)g#;^=MiB|lPm}e|7&&0?8Et)MuU~tI)Z>%sHldZ{} z&-NrxBq#%o+1Uq8jOQI9Mqc@>F$By&mkemk0#y&DxQI}2GukCXK4!selt5x)4X@Ig zQGe1oI$iEGye?NJTNSU{I)dLpP}Vy4E;eRVVP>$%VizKNHOxq#R^Ulo#)mM>XX9d3 zC&lrbv{*G9lXVD|$0cFqCB9<~TB4=5HU4VQMibG?SE=H^ZJZvife-2jBmf-(F(yh`)IG7Kevp{VV>4 z!!tyM$oxMEM23*r4gxcanb#jKQDi=n#Nfw@kr?Wfp()HfIR9KISw^Rg>fSQi@Bfn$ zWA`sp4O1&JZ4sGQsxiz9#br&2$%0H7+J4fQZ|!o72#mS76r&=uwvQT+Alqv)m zWM(m+DHadhSzYl*3uPR$<_~L_X7dvpne8D)hR%6@vxmtt(WAE(7}VJ?;1W(jp{@Yy7LaUx_H<(cHs*#crwODP^KJ$3&vzs zjLBLG%M$YlJSuMWtTBW6&$~SS5f!WWKpyj$@*%kX6@jZ@-*?dt%lF4@0{E zrZ^jKR>nrGV=+R;Ut7@5s_hSnl^ z4ga*&I}J5iE-NTAL+pL8T0I9?PW}#*fR?Ddz=gu%!Cwf%QbB3K^`0fXljKxDWFRWL z7sEsu{qrOyv(F&|=^dYR3vAh@)b$S&m|*bRl9?zBvBf$jJ4G z47{^vDG3o7lfC3u!ZCVvzO1h%!?c9_KfR{k3o#FM{p%TZyM~R-!PLP)K~`dhMlgA8 zd5D-$wrmS4GXIhEGC3LSEo+B)K^sFFBNAhnK_5ddW>@pcA%QU>vnw{{?as~_eDmq7 z!{{8 zz~du5mc+pCYYhmG;6@qb&bfclQPZMr$jckU)kR~nDzHJa!l>Y|*l+L|^^{00X6u|yM2HqT1{us?>j_(wzjB^;HFn;m8llr7RmH$G*D z&ZSP@TlM`H$JZkZvbgZ#Kqy`7zL1kQ48h2_=GzMNw z)6qP<=EKt}orV-4am(>3E(iC}v7FZ~>}RzuY99OWBaXvbtqn~c2T8G^w6r>>;P+b> zrK)nk4-keSf$+D2RcTZt3d8@fBs zU}F+fObVicKYYBs`x=OOcTEz5lV#;{D#QG0qrYueer?w5D>>v(Psiv-2E(w25|j}! zn>zzRSxPkK;Na;&jt;{Jj>G_BlJGIf#26#9eN{!K4WU@Ojh!-k?Y??UlkS*a{%aT+ z8t>m-+qFHvVP>bFn72p_L}j@1or%HMJ-tfChY^zmVrXbk7Gd(r2oA{T;ntlyb9^Em z7BClUUR?tzR*)_jf3Ygq4FJT{fGO#wT(&kKdkt{+cvM9wA-1dq{UO1a9Gz4``_g%= z!U6W4_B?y*H2|X>f!HKmmzJG;O|jMs!Nzs?y`3Q#i%sA z_4OKEm=VLnFRNl*2q>mS>M@vOeuS=np5{=q^5$XhS&A59CL-g>*_=z~DeKYXmg$#M z$wH@9i^LEt{PxP7RpnzJeE*;RI5KjLA`?p$=-U|&AFVVt`Wf7C9rKAIvmH_yaV;yV zF&|$)q@&Ew!obAoKK~p=28p@-v-V&zDyT2Xkdb*{ZLgKqGM$hiV%l$-Mq@N2Lt35@ zEmV(bDl%O1U)$Xs;$gPvqYs%aASM={e~QFR3o!gD!6un#sIN?ju}(TgV%Wxr%48Pj z@5ssC3z_l6{aWoLOw76YLJvRda07BTkRlP8jgY@zwgNCqS!NWL6Tc*m1ZTqFtN&d> zSWsAMQf5J;PdQ}d#h4quh%_=Vm{%^R($pTK8B&n=oV&TGjmj;6} zCmq+pkXWjmD#PPDe-&b~Ym}Ign}4_wOD#I|P4Veuzg}EI&m8@J0GXi2Of*J)%ogCX zvxzRI-^RpJX)-cdI&1l786=}amxvc?6_1WuM#i4@-?AEI#L2t@1JkyQ%#VA`JxgQA z_%|^uJ3OSevbEh|m6#zK^LA_hES`$byUwgbR%UvdCqa^fC4V;lPN-8klW|Q%hQAc% zajyp1m<2a7`;F&W{)F0H^b0MrE}c4cYM%B>(J)w+hbznDl7v`zE0wS>2EsEROZP|% zuEq68T`EM2_!~nEo0kUVlpkTGKc3d980xQc0+BK4GD8ej{!IqWbY9xTM8nBtd|XIr z3u3BF!)y2MAN#(4eB+Ce>%6`!r%bQRkWAU98<{1RyK9KSw66wc_R@djW9T6B?K8{w z$1Up*Hs)!@xosa$M*4D_hLRFuWWHBoWaBgEm)k+IjKZ=vhs^*O6&aA2XU6t7n;MnT z6hF@I3ohUGX^f4_M=bfDK`1?+17aK}00trrDLnL@;ovx0;FqzOASlCMA>f#kuCn}W zG`sG3r(xrNBwv`}nq{X^16DRJPI^N?vHM<@2Vm)evQ({$vdGnH54?FRCso zE=-js(D;u)+y+m5M4Q@hA4aiA6AuO5QZ_poK9KDH#GOlMn^zXc4FgS>7Se6E-OMcX z@Fz?9gss;IS&}8Wjuc{BUn_=5g_y7Gv6PImkG7B&1(QjmA zekbR@{XFGIf|+Hi`y(;1@R(&j1k;>^iM}8H;u`S~d@m=zY$uje*`J7c%lTyx86w7} zm`PzIETeUR$z`K4Cr{4Rn8C?b(D*;ahJ`g8_ej9JREeQfS$H~CRw$=snqQfa(Y!K4 zQ%hByKFnH=6vUlVVg3QcWAN(T#+dfFybAgiei(}%@c0bNbxX=7C%O32?;$Gq0dVQ` znHH?(Z)|GCMHPlq$&^bTwlNli;MB~)l#N1*IY@|4EdNX*1y8i$2Lq2QKf-XIXK z_)H400uStxZllDEFES=0WUc|Ml_X^&X4fvG_C<7t!Z_VBnlF2J+tx9ym%)-hIe$Ec zZ@c9A78Yl%Au;Kfq%kj7okfSe;d2bX)sF5e3zTFaEF&i)z<`t4l@}0_9fHE_vh%k= z*`tF4LKTY^d?4ar>{{yqXz_O^0EB;bhpyU&qu3wz*+|p@MxERi!-? zQYejVf-#XGxzmGIx7(K=H z2ullY>n%J_q}2jo&c@?EU7fq&b@l6J(_iLrb7moCGJzI7M{%M%CSUfD<1!POQB*eg zL`LTK&*=Mqt~$Gw-BktSzn9Lqw8ZJrSOtASk%`S~e%Wp>;J9ocVc9Rdt&E!fg&C0< z(ioMPd;BC4^ZE%L+-FKLw@g}jfUW(=3gR*{8iTtNYC?=O^CTQ%0=cqeqL5=+%KCwc z5pL2Yud1!hOkEX%$&AT^KsBmG@ipz}&%kmxib6}-04kbLuW6M4CcFae+_bj!T}iRMHO8l~T&{>ZTgQTL9Jmht4I&*`yq_FivV2qVbjW zmaKLgzCAqm#%E{aZ~i!U;R}zF#kn%ExQmPvphbiFa()AiEy_GJMHwew2G;*S|NiaM z=)ukVw@bdSGnXtj__3OOfd@>u0+VEBXlhR$9+;XFVsx~C4*5SOi9wAaBeSbwgGL5u zIpwI#hGhqjSYqyRP&T8|k6E(8Ky3^&^Z8^nVq%sk_g&QPH{MDZo-X+(6U7|$kx2uZ zqcHShvF_C??EIH9p=7($`8AjVJG=Ywe>nUblXZM28HS+H_22C>FcIas*{>XPztkgnAGnHbryoD32}T-eT;iT3_*Xks@R zyO^>F3y^|4*8rM!A0+1J+LenZ=E}7%J%5ciFz18eS8!TJ^c>x>l^h$FX&uu9W+XD8 zFrPjTASNS;@pUhmt2AB~v&)&)9VZ}b#0ebcg|Key$Y%fBN(^btogd$d_ovn}a{s3+ zGKYA7q}V7g_W&6L=J*Gy$KbXX*Tqm)d4M7_08mD%Gn8DWsBDq?s*6Tqa4#XZPfcn} zF{8v7W)vChk%2d7+O$p;{~TPwAA-cZd-G}*FEe(x$TmqVNp5miF=~sb%f<#bp3Qh7H6&E<=f)o#euWN7%(qwPE@55$!uP?-NZ{AWKLORRAs0|M%KQ#7>&s^xje)2<88EMVltGNlMxdhVO^SuC70M$5<|i$vT%2lW|ezOFXrVk(p^yxVkCqL>*#G z*ftZH`_3k2otFV0o>%!4KSPOiGk(Nd-UDLFs|{GIcoQ>2CI)ZOSje39Y_~}}*)r6a zw`^oi_cvA14sD>H3I1Dl2 zP>`7N#LCDM?T#rmZ8;{fP=X8MpXahd_h93TSQbQuYzQ{vcX<&jCJbv2<$CL>(eK+l z@`lL@aLyUmUCoL$eKYEkM<#LJVsW|RuY2{{a=9$KP&wQbV!+wyT#N}~iqD?qu+2LZ z3I|8WOr9A-GtScOo|B&tV9thLT^2Ajib>`$o470*sI~|+^Fq#yqh=MEooSUZ&Hp#) zzFqfd)-vB|#1+VlA!w-#$dn7f%W4vNNg_7!RXe>WA6hVzF&*zOoicAtHzq){zsted zJ~^3vHZuEGVi1{osxi0F#yHM@V5*ns{6%31m=htUgy%RU%xtKnB_`-&;t3)qk&+cjnc+xGoJ)&x$h-&4 z&;l|7KQ{;r{F^L}zI39_azJE~ri0mW{_)JpO0JL$DJq^&wy-19UrJyWFBw(a5)DX;3C8B9fN?~JlFZV?EGNp!-ZF&dDPptzFHbiqBQWh@ zD-x-uyok>DFX53a<(I54EHYTQ1bKlKLzRh#7bGmR1D|wvw2F-MmK_Q*5TETsV77k< z3WIlH#;n(`pJ+_B6^O|M7#10$GXrdr@w^IN609+NZBT3B%v72981C?wJuw!dYSWWx zWfdXjgA2>Fb+N-Lju@4$yC@abZnZhHG$e~Zw7lRP3)i_g>S97M+-1XqE;JOg$6DsN zm#&=7mQo-unL+`DQu7-0ejvoq`$&8iF)w~v$rO_&!+ie1m-rR3J#kxf@AmuM>u2xJ zzP&_X=H~tYahaEn^GSb>q$nu!E)&uD*=L#yPCIP<^+;Jl#wGx^pVxg!l%cdVTf=s< zx>QRU@1H{FpUJE?C?JE_EZ@lI(ZCQc@Ryj6g&_K)1hcJ`-W2a2=#-&=jGuQ8L2!VW zU9QI*vWqcc8EVYQ$<|4*15^eQf?|OniOMRBoP4KQ0%Txhr2mXjIA}F^PE8wk}8Q>vQ#G>S%x+&Y1C*Om|NvzWBMM z^J8!nTs4I)5A}3zDW&sdy(OCdy_#BwC!sj}zn4y^mU*bv3#nfHe`N@h%kUxI^w?AJlFc6o04cBW0;xhQ(A9HeKwhR-L znprC!&9eyoRh^6=qqxAjT}%0L07e9^lC?Dm$m-=}C|NT`rm_dX>=lTZMjWV#=Nqex zOFqiTNJVDn;Z(Nl&X2zcGE|X~JBiFLg=PC1mmOk?$><{`>!XlLRiY?asCN#De-b5IJ zH$zaSHwH(T!3IGuEHh+1yLiA0&uZxGW;u&tXqey7^X}JsuVg3mtlH1Al8wujT}S7h zd(XX>3;K{0!}_G)Wp#CZE)qsxdRP zbbk339fNdIik%4!s?tg2+YnP$7YX8R%#uGfZ1~rIoqX|Y0|uwc=5oz4-UBJfNc;bX z<1qnD10I@XP{|-}8r`hbDBELTZd z6qpxoPAK~YL0JP&9;Rh9o@@0lECYA-i@&sU74D+TIX=8I)tUvWYgH>OZgPGdcwWU} zkKuZt`U@D60VDyG8Tj!`*`L(EB+D$4xfXu8rm~De%ap`FLFQ~~DCTVT8Y$+Aa%Af1 zkby({)h{I`yM*NO)*f{EClOc;OA@W)*p#g17^^#`L`qpeBUvTw%*^!%i5|h_7piN! z>$}_k{fAY*w~2+eCSfXTAH+tlhhP~V+zrvYje!4`^c4uQGluL zujm;Z)bu&p8Gm(e;SLUx18#?~1XG=V{^#GI?@_CWQQ4F8_fq#Kz>t3-?wT*&<+B zv!Q}l(OG2etrSBt8OC&Gtm3$4<*P@NJE$RBMFOyBhbn6a_GlH;?cY;i3Ys zWvZBgUQZ?@V<1zgI~RzUtSs=$-i*mga2@BVLdyuJJdeiXvHCnZ`Rum~cjSD&s#HYB z1D{kqDCbj6W1KhBWty~nLC{#3p|5*R>Yr)m*^3RYP1|Cy`!t3>ix-I5XmK%sWB_oC z>qVt7h`ymH55)_!7oCjy27s97He#gRU)|nBGFbP&CN*qx%CquW*Ikbl}fiFMk{|oOkMJ1Xz!QR*%1RnAOfNY5)s$U)Ho!=;n^)^l-y?iq zCyD(alQ69S03ZNKL_t(K%*!e81|{gHBgA-BmNNLoLNaNaj7}~eJKf`;l-}W&&7?AB z#k#sqdtJdr0cFH+8ILy~{OOq*dw7+GB$){@m4NWnuGU)Cm zUV5wpGdLTqT0$283XoY7Zx~H6i;I~qw*WYPpu%H83|yB<#(?Ibabwz$kt*hUt9$uc z;xdTL)Po?S2u9)M6;sUBnF`BNRembN(AnC%OrJf47}s%pgP4+Zfmn#i8sQ%V!Y(}4 z&$AYkHJ!nrBNPLmX}1U4=|F6E7psZ=0pX=bU5E^pp$^1!lZ%96t2elXW{@$#u+-<& z7!-pj95a)lTD9E10xK+c-d-D2obIw;N4-{#pfagmyv%E>%6`HW$=Ha=8pM=OyOZOn zq^)FG?ef=LqX6TzYTF~Emht#tym_ELHpgGzTew5#(=XR@ITe^eY})dIhS4(lv^(bE zoOWqwj?s`oqCw9Lv&_cZn(MeUI7i9s}5VF#1@Yr4JciS~m{N>1>MD*gLfL zD_v%OHOAFlKAuddG7)n#t z$pT}JA(>1wGVq_J{-Bb`!BLM%QtAJQeZ;^3W*`JbW1?Iv^NZH_7>liH*@9?!q-To} zU`X#{_wT**CZ6dwM)pR1`zO5vq++I70M0A)rYqT68-T(;wtY``oQ$PQ4cxJ?+^Yr?WdBTa6yxrRo{ zY-q%MmnNC_qGPU6$52>iqO#em8O#1F`1i_&i*U>#ZHd-cA(kPJOdR67Y^n+51HwO$ z`lV!+A@hVYnAIDH3d$UsybTA&J;KmO>>%o4085CGP|VIEOB3bV?p&9Pjg}Fu-{agY zPvYMdv9Huio7GEIHzTOKe;KRGt^*qk9ED++HMJbTtzSOA=wF=HBSB1^OfvSUoR;V5 zx_@a-`6I_vyAwo=w35viFYD?TQ%xQzu&Bq80?QGcle-5PfXqPsrMezOkzUO!+K|cr z9~2{bX7Mw>^%M1e#T-&`m$4hklKpsm?#aw8rx0U*vkd+$8QEO(F_O6^KPDy1rs|(p zNHWYZvsZu_by+z401y8ZPR6IGJGmd#|gy6G+-7Z@ccu%tXl`fgpc_mjhhS9Ggv0o`Q`M4j5Nv6 znN9^SKrtAX5y=Q<&Lv59xM$-f4H%L!d+3pAA!0&1fto^0R@*R{Vl-kr9`FyFWSa3{ z*aNV*uC&&{z{g5XEBwBdMc$W|FbgeQZ&|gBV#qEd&Mu89%|wua@fPS4pk-n)+s34j z;=vys7fp8IbE&%ou)(7wR;;v3F*==GbmPe>Gc3Owm}P55$QUcP*Py?V0>^eCYC|K zU;{GieQc-X+Z;NO1ub&S|ChRLc*)Ue?EH_q>w9S{O~dIjuC)xyx-i19uxxiOR$5J) zljJ1ikBZl4`mt+NQWN0EA4U^6CEix1q!B3^yV?L;w z5#3}nv-;d6!-nm;`2_?DobF|}dwKa_0h1V?d;#~k0B(S=udp`%N)^nErkUu$yyMZ_ z(GnFO&n?~9g&?VB$0So8Z0c&bvvI_vEivuSFGCD!KB~y#Q*6>p?^S?Vj^8Ab=@VcS z%Luq|S%yYN!i7EiP>898lqFuY;PM|*lre!%9eCMFbihzVl+E&te>ql1R^VX49kRK- zRp<^PDMpd^W=r5j)gepcGL*}2>!bJ<7eI%BW5!^tJcykG7}$@B3@ejy=&RT^zz)DA zR|^qSI1jHa%Qm?xL&Wf6f4<(Zpt3S@Jvm1V4U#GQVX0cl%;@v|W<|`* zhUwGEPnZ03;V{5FOFY;!KKZtpY$ofz1#;GN90~y3>HCRC6v+Tej>MCF-MF#y4U%MEtTt)2i(5G;f4V9@Qp z97{alGyeP&$buv@g}&o3=ZDfPmWk2wF>`Svb41_hFJ-qDrj&_EC29I&sX7dpv=NB$ z?LHK2Wiz@a8(KGj-e1VFH@|3!e=z@Fe;=Y4!7mp8n2QSmmoI&GZu?hpj-fc&kn!LA z848zEMa+6vv|y0l0TRhy+7ZCGMZ^kjUAC-XW22=aV$GJI7Xg>OXr-8liRsRT!G#uv zgA#)*9|mMG9(!^^)|nu~5Cdyo_7E^39|%)oQY=U&9W?q5a7$c|A!>RaM~vGGbFCbt zV=~Ie*e(Z(TwqY-p=xmdd>y9bn2ha*5;2j@m$L=~jPGomF{BItDe(Pp(4BtJfJr1K zra!UYViWdF`4A(i2Sr00Fmtbq0cM#y0#OF__)L)%tw5jQ56j+ro;OO9p)5-gy0G`e zoPQ-)=Jl&l>p5O2$Y><9qgu zmX)zgL|ZJRwdG1XOE$*U=ExMGUK^+4G03n#n`>(j5mQ1e(&Qp1C5a&NmaKje17W$% z7jOY;c`G7J7-eD)!VE*qGMO0mTi_#&KeY06__7Sm9OG2Jjct(Zn+#vc-lSqlR{+`b%$a|mZJJ&}0e zXYA!*6{{s-rEO4WdcmuRKIZ!)%ZgqAHB6Be8uiH37-Sf$F-ns`ZCNVE$I8@b3`u-q zO&l>`{`sD#Hie!F?rZK6tOmi}dV<1v?!71j~{uRoyD+n*ILVbpp_0^^>#5#IqZ*iDONe0_5;51Ioy{0Ck-^I|nOeP`4^oQ*!pY%2p5vF# z#}g0#jQ{X?_n?_%Sb?w*>`!av9NUmHGw#Y^0=rea9)} z_|X4U!NhVc>11Ay2$sFpip%8YWv#qywDXTJOrK25?G;mHJ37Y@Rc*#a*$#9p=TmtX z8>*_vG0~xqvnp1KqRiG2!!D#+gNBkrSjB6uw?%$ZFWgr%D`l?`2cKlk z6_;WHEaaQfKqF*;V;0-nl#5wiTl_bJ3;nLA*Os?B&_a$-A-FKE0Y?)$gd95O;A6@? zX5!9mRAo@?PZ>7sK!ZIXcVFC)Kn|=!{AE z1q;U5*|T>dCf&fa1awfB(ICVT6AhN7$@{B~wGoo(fBpUIw_(5lUO2^&hXKT}$I6f- zL)37n{BMU-4B8k!!);78o0W)3YYBhi7-nP2WtraNwaQ2@gqi&M@>)j>79%l6%UsqX z6Or3(F&I`E{R5G1ky`AM@PZ*(h%hmAL-rX+=IjJx%pX6T4PO2Az23PC@7gpg71{#o>hDl{A=kDupU?Ofbs2C>SSp)_zK1;P z!Kd16clS9~cH#NY$wz}19AUP+yW0k&!1db{-Q=C5cVon}GCW{L9J6$T;nPNt7tJt2 zmIZF5%rr^i9>AnsVk4NsM7{H|*_*>8b0iS+M(p0$RJ!b|&M`X4Xas|yWjv8c8S)I+ zm>muozzdC$$)_xAsj8MW8xy6NSruE>9dWHzYxweV^j8;`_XM|S)5CH1k*XA1SM!hw zEC(^?B3=Gvmj`6kp(w3LZtPD*;le0p;>G&%cB_sRF(MrkQWQX18Txr)7)JK=-0%5N zRz^NXAVw2qMU7>6Q6?i9n4(ds%wU&41eZ;1t)F4n*_}DJb%to!rSooTaw74V&iMDO zjs16TTimlZr7``jlP^^aLz;_7u77FXwaC@hMcJiTe344lm@%owO8ny|lgIx7t!>pz zoMd9sER8ETBxHEMze;05vCKE}GCIZdr6v=2=_6uR6vb?ENv3CGc0@J?3MLDP7%g%d zLyTS`Q`F#6tCc)C1j7&73vJQnvJu~WghRRzFYQSAiv}0XxiIU((L#73E3hw3G%A|DMZbg1ZDL(JZ9t1TE#ZCBio5HixhJk%k^(kQQ40A;-V~7uc9ck%N26ItK@98ohA1 ztf`5}*oq$uB8!d@$W9`;2;-vA!q9Q7*@4~9c+39B-^NCXoUxO|h3zJC3V{VAnWOUm zDyfM@G7K?cuV9O^GHm_fh^Z-pp)g0GK;xK-MH|{_fR9W_$CNPTPlYjNAp`}p`r(+s zLV%h2X>2_4=+1Xfn$3mX<1M^|DI*Pl;b#LHX<^Gw$#n}2CtxBhi6!g#dQg`&Qu^@? zT(omPU_@UT%#<;QoXiOG&z+2(`2Ww(d_?9BSQ%Notiwg;7!YNBF3SE--nI0!b!}mi z-rQW;D@AFkgw&{N(+=|D(BlBd^0PvI9c=laBgJ3@7T4;{`U{I3@l9ho6prDJu z14}muRmKwY3>owfaQ{XBMDJdYz0W>2uQa2C4F)U7h{)$V-}=`2)>_Ld9IJ6;rz8x1 z#Wffvo5~W5n7*KlD{>T+?ZKs#l!yU}p|LUIEH-C#yi|Gj(W1Z0#VhD9HOc#e{LXWNgfrId�-i^t&_}Be# zdcrgNgYXaaEMI4*3{93rmJxyv={6CVi0^kp@p05NiR_dGK8N~7MLXa9aQh>~3rzjH z%E1a51{>$5i{!rIcYM!};ZNvdc0k6NuT;YM09rF@zNQs4Z{dz8hTVJ{FIX zN9MAi3`2a07DNnIg|S1~%GaxYb7fVw8_)K`MR3b2y+X;Mn4%X%OM{4o^*{x%GB-DT zFmoNC?&(Qm?I(Rg-=J4 znM^XBc5wF6$g{NV;%LJBCWm6;j~)8%%iDt=Cte6L?!rl>vN==W%N}S35kvPw{9Zmg zTfomV+`cP4WR|DiEeqr_HwRbX@B?uLUiK#6U&_yxE$)K>i0D;+3ePZ3 z%Y;FUjJF-jX{Qsa97B6#Sg3`(x=d1W4LXC8k!T_f`^*Fyv-?obnTX^HFh;6SeFJ~% z_V)JS@Z(Fd{V}M2V41?w+Fa!XG2`O2F#(!#$?MIa%?Tn(J1e@1QZ#;{rVq<9DJ_2` zVgf0AnQ6FFl4SI*<-Tkgta;KA(^JUoNRAO7$69h($4rO9GNut9W@?IGAS9~^-ERbq zsmTDzn0T*@@l(tM+*YNxpLRxOR7Zc%nr^Q6YA!s8TkAPyrQeh#msMT5$jq1?i!~T6 zc)Q--9)9r6?W+<_-#6>CXND9l)IO%F{YX3PpNUa>jMKIEv6d-KGN{ygkm7m&!5S12 zaeFKjjoB$^=oIt{tQ8cOR-ss0+N^9Jiu2nL{H-4~To^Jzqfl-EW)=%P)`D6%itFVn zjVOg_Ck5P`Wbq_exp0gNmvqcXdoLZIxDqiqPnH6+m?W7?AcJF`dulQ)WO#3xl>UGX z&XoB$26M}x{Z9!m9$;Qz2c{wz*c)S5X3)%VP!{KEjBk;!oFc>vVBpwa za7#?W!{3I7h8}$T&6jru z2R?-(AOqL_`YvOJiH5aFp~&;IJU-EhMY_pouAkX%huZDL)rc9(5n>D@ zIV}5y2iEH1Uqa@sf=o|#`A?5yI<=ZVBm=}qtl(q$59loprg1-GldG znGTq2CKse*294QQv!wG^{CLT0U6f0&R7IcQa@5ka3$u$a79+G=7cSyF%I5{gFk&db zYU{jOzpx#T~o$}xxynEw*OoLR)HXC^TNkcAAYTPopVaY!JouPkj; zwjTpjZr>UF__;-c%xAYOq2{gi)`7sxO2LEx3s)m)ahItlk~Qq8dOr^C3-5)6WV{+N z&tv#2;kU;6mCR4)E1B1NO-7H(mX}YDWd##U{a(f23(9^!KE<%iACZ9#TEh#kCWGc3 zoNAwray90eLX6%^MlQ@fmM>v4EN5^&3!a5~9Y>OBU_Hd$tQ>+~&ae}YO+ z0h9Sf1ZAC$&M!bx)KEs4fwLpH!7`KRTaKrpekqvop+p&d zk3h*k8g`t0m|MolWs?39AIT(>P10}41jM+_hYufq{q?qa6;EW%t(eaY=#*d>&q~ot7KGMrn&y% zl9vfHN|tF#=2#2MIvwSbkuv55WvFXjKn9N;bjVE6*sgRM8$Sa5L77G|&^|`}mediG z3L2J+|F>eZx#-V}O{;+xueddgsxA^QZ#<=c4qWC4E<@jb^?vv5!Kb_R6`}kQCM^63 zI2@U!91hUPBopge-Eew*Om@dGVu)E(;XkP*0YJ#u!C>KuOoQG1bg|+EW-b-}ORJ5_ z+QCL^1@??sG*yeMEtZy1HoS-02x}SHeaCL^ja&mVi75#gT$ʣxZKQ4QXHJM-j zeNMVeNSU|HG0cV9^*$Uwi@F$u`I(_c{c!@k}R2U)cu#)GaH^*!SuwpL>q9W2Z@2RKomc=k=>Bx4j@F z;u?a}_x@a^L!BsR{L=xrr9xO^`>44CEH)kn{<)SY-%dVKl1_^^PC1oO&TN;MfM z+$#NXqv^?r&Pg`1pZ%+s5?H9>(-p9^w)X61th7reY4vXOB{@EX42sfe%7`_Qg@&U7 zS0L?WG}BPGJ#-s;@^LD%IfVvF1HB}t(omTN^Xs$K*Wbhg4=>xidKloA+| zoP{i~l&O(ahn;QYaGt1!*RT#D@n@%;u*5OhWTjvb67lUmBfZjJL}Okm)=qJdxd6|4 z#}!Y^j2I*v+KqiAdey-L(MFUP{~aMsfT%#Mdw~ONjAO%PW4Wa_$a1qF^eYdj`3?5= z`DEvb2G^C{AbG5OiGFCgce)inHC%sYC*^Q6l?BPsn4Xukse(nVMtl3b9-@SoY@Rp^ zoKxB|CZ+%Y9t?JDLZT(QCX-#xihfO|0>hL*u4?-VF3gI-Lu}LQmc?(Jc6j{HDEUK; zh|2|Xw=zIS&e!Fm3ht@PnA&bhquKb zXbfn89qKG(^`%l{nGWcJ*qHNqQT&TTzWj4BYe3>tIzyxLz3@s&aUx)m{Q?tUpJI^l zUY|9Wn?fFI?9=Xj@y!&g_m#WplN15&Tc*HVB!~TWH3Uw;37xV2HB<%fXsypcV($aFI_!yoD z_^mE1>QV8E=sA;y3jJQF=Q4Ef!H+9*o810R6Xf!s`cQ$MlnkyP&hD!(HR14ET@)RdqZ@-s{>M^n{#)|yzx$_mG5Gx#@HXY@x$jMd&v;0(2l=ft2Q z!tTyVTMk?KY2xi|9O${UwwxT49MZ0N6B2=W_MdQ*ih{&s{i;!Pb`5DibwaR`gb%9e&s_jbD#bb$xt)e6=lHCiffDkd+|LKJO38k|9XbI~Ql1R^@Ff8Y87g9fh{$g06^;&WP+GJfplfDzd zFDc3nB6MCBg!~ODd0N*Y#5`_E?F%8-;12dQ;@~Ov8LbrSlYz2d)K0>Cgu$!N#QW9m zS#^7&-3y}8?t6LS#{N8)N&nKi>_INM&gnC0YSJ5nNRPwFWua)vH=1rXE0upSsfB$J zo3&)CU%307OkpOEg%ZlM_b@QS0%&DZANpT)iJR#xqmt=4hU zqyI|BL#ig|@HjFQMGN>hA#T0`$PvfHeE0uaS&6i0H;-F;2E`K6L^rJ_Gcw3_buD<* z05sU&381u*u`E2v`%o(mfb`f8Ixk>Hh69p(NdBW$wn!qRn|ZX;h*~?}=KxS|dqVm& z>h^vl_u<26SA{3m&oCy|(Z$@g%g` zQM$YGT8{XV-q{`xvV5vq84CF?wnl2j^1sbuDi!SFKQl>gLoo`IpzClW$MdHR7J%1B zOqr$eOqjhLj1=j8PBeVyPFN8E$D^IpdrNRg89-7 zEa+t};IKPYXhg?U;+Zc$@7F{s!SZ|En!GZqQo|D~^^E(t6G+Awq!MwX5KV7?F>SKmP#=W`t+8XYD6EcGQVJ&U4uP=9*58m*O3SN=-)VyGb4| z1$vltJwtjqZ_Kb1-H9d($#j@i$qCu>ey4hl2% z6J(ci{ISCNK=0r?YhF|RZtmjar`DsPnRWzSvZ>9|v2*qqeE1H@5UJky-~CEO&2}@w zX)E{UwqXcmTBXSB;Zoo*{+~3pQEvl2Td`P#G=?Bty>CWsUb*T&W=JRqDeT&~d`{ka zMR6h9S-H;2Z%| zV{=0o;4qhPDP6RQ1PC?YMg0?sdpR*hep*H6)Kh1302~e~3)}7?>eF$EvEi{bZQ{2e zh!K4=GS!B#%O+9F`0=Mcqeg64RxcCO3;b}YLj_$GxV2`Ub!nmmyZ-_y0&&Ym_y7;` zO^NFQ*Is%6)O7LyEEOJ5$ami8=%(wj&ir-c;@phIV|_u|*37Z|25g;o_UPTyK?HXY zkjS*`gl1&exn~y7ASkyos`WoPg5!65EDO3R&3~8bJeaMExp0biGgo1ONSP60s+ma8 zT;PdYa6aQiOld1Rnvm_YIb(jFsYD0+C!QXo(f&6L>GDKSikG&avWG7Aep!8G5DBPl zsKGKr%=f24NNgPLur4Gfe1qBGDepteq2xIA+V6?(CmzytjDr;w_9YC6e>uG&%0KtP zw1++{MPL_K*RMoh+gMBh#x5@(-8eyu+sbYip?9(4KdxW1m)!C1r*Hw;9iEUQUl{~D z@CTtbcohkUfF9TF960G$I1DZyX0w?r`Vk?(4D=cRiRkS#bdV<7%PVA2T!A7nTH4IG z4JPp}c*PycI_(oIJa5x5}CeDoB|Byo1^v> zl9Nu`A65kSPMRBfNE-(teQK3{EV;=2%0RuoGBSb)`58@P--`HEfg}zuF#v4$uf@hNy`uLc$poaE(}IlaWK? zC|`bn?R~v!=hVrTeppWx7`!!VPxRb&j(*F+?hHYOF@9;?U(PB5-W+ty(MTlioHwCk z#xF+ePk^`6tA#QF$$zbx@o8x?ctDUIzrK|*NAyU}s;pL)Q*Fp0)CtQt~XY~Y2 zpfQ<6uVYQHF^s_gdP*@W3Yr=JgXuoa+Y1S*0zw}~QeyHxzT|+0l8<~u;Lsq8goB0H z`o7jbb*}kHQTDg})#qEC+f$`#=;e~TKsV*so1Se707xeBoi0r>->BMv)9$d;K#6`3 zZ_aPQ`-WmSBRYC-`xhbu476v{p+82ezx^LinDEknjfi~$fb`HC5m>-cg6QpD-N!6D#F`J`=q51ZkC zUvomB_(o_KbfYif>v8z(!{he0$eW*dVzPIIp%QNcei;J{9`#3M4Q(~62e5e#nDKwY z9564yq2g-H6yjP>lQB z4%-7f$l+Gem6O6LD}sxG;b6V>#>PyOHRSUBd+(l0u>>j?tKl$;RjB%7X$wfUiQ_*pXJNX2cR$Y?Q7UW>c)3OsGs-kMMPA!#FdMIWJ+7Jj+>Wu# z<#eGt*XJxA@oK_8mR!}D!M)6?lz6p!={7Sj_H0|91Gko3CU%=kctJ?PTkCIj5D&u%Ad{+Ai301$>L@ zTZMceFLceHw`elmI)9V1K^J2O)c*n#vx+W=yjz=A}y}QEH44&yl3h;(_v| zLAOnt!GupzY8&X7n76Q{K{gUnQrBB?L8p!19>ibq?4o%L?Z8|86Qs(=T5#Ma>Eq(b!1a2KQEDpD#|))Xy6cdb9F^D zn9fl8{_4-<)hc0JrP(J_pXF;*?U$wKEiSZO>z%;y=hKwZ0Rqv6Egk4!sV@Kz;>szT z4BE_X4T$zZM`uD_x<0^k%?4u54|e^ZNmNVEIrq&VTZ7>^Oefh6y{}sb+T` zK*o*4uP~@cQnJ!$v6yBy^ZFr1uM8w@UxtF<*)5(#=Ur?(Zh6-~8gpJQxK7&xVyRwC z3yjHhNaqM{38fYfrkgOnBqJ`k$70{3l)h-xn^y;SC_W1HCqKx42G?7;^l$ zD3g`hG9#9(^9h}wuihu-Yxb`w#{@el<-=w8)cABjpA&97qKmAb=~;$lo3G?N-yTXd$G=>NZ;@`GyCp~5+C^D4@;hH!J&sMvgERKTSqYv4(E55zOeK53Sn+`~eKNc~Uo^wQ zl9sP{8Rzp34}&M5-=(o*4sv-4U!cv|zG%=i$_8ue((D;EsQBjce$1$GS>)aA0_(RL zNyagzr0?`80V$8?@StmgR~u|clOu`vaq(gr2ov6@h5~p!93gSy^t*vJ{gqcKYdDp+ zi5pec(8>4e$B9WRx@IClKTi_L5#p3c-mTHW-w3mAllo(G_<3zDnj@?$?wMdBua1S; z`~yRL!8TwA-S6cW0|_>0h`ynY(_GX85rywneOzUDs|DdVnmDu@O-c?I{zjG=RYrx5 zJZTLr7!rJ_Z$8|u`<%>se>h%lGGZHt(tNEo#N}_i!|*cdh+*9wze2yj~ba-v& zfj+QT)F4Z=KLyx;M9%xZuJpBe2Ay@_POkajhnvV7KOBF2NOH?$P;+EIqL05ei|rx( zF~ZTNo!MM>X0&-`RViItUlhLN;?iNAb#~{~Q?QtIjw!b16u>W4dTmb8b@Alpl9~!R zkQ~M_P%gq@lJ}pCHq@g@c%RRVPxKmPvFs@+62>9j{u-~SmtQ7#;P=#5vC+P4SDMmp zw@KZHK9kV7dQ&^twwxYs@1$-bc6exFqPC~?GbYReikt$bD&pJpb3bwWPWq-gDM@AqgF(d~KpI09GL zDt9-Hov~kNYY+O~Ht<=O@1GOz@R*Ld&%rvpfs24Y2nj8 z?Ge{o!*|)mqVvQZ4Yck{OAUvgKTza}PhWL#C1&bj%!+?b7R69xa|mYI!rN|dV^8-% ze}eAQy50CR?LDHkK>z77eXILU-Il6Mj*;#d#pYIhlk9YL6Y@NCKYXsR{A;b0Mewxn zsDT~A!cu5k1pv&3c8FI$7dhRuAvC&a-fgDKS-weeE;vi{?Hq}YLPb3`-S4j0s6x;5Zrt?))F!w*dB2Wn+Eaz<6v$&-WYqz zWA3-s`!+ib!g-nye@_BPQLl8qo(a!0>EBqG7V3$?7USe zHRMd%02^)upUM~a)yF2St_~hsM#(^0zE)Wh7OI0>H7i7HY(Q}&y6|Cfz}gOvx=r?c zpZv_!;?iWz!`*mPypJZKtqnA)-}?1d8oFwCR$DV*cj|Js#dOfu-Y;9$u}PRLY1;9D zS&}Z#rP+3kOS(OB+C(#1bg9YS?VhM9Ituqk@L{mL3BSqVvtm((u~XTs!mzibI2rq8 zR{MKHIE&2Bng7muLi_eLCnFQaPC*i44o~|UmVvL6PNDcMvQ}1BUAO|iQ-OT;&=sFq z>VPQ(A>7i~MRJZAOs&%eGhR2E@~6~P;fjP&1YNfn zh&ak-og7kF@0`3I-K2UJn%IaqX_eyO!ClvmLjoyAJ~H~=;47d$I%WZuk5J7C6aD&X>DOR~^iY0&JpZA#ZVrv)tSi0lbcwO1ru^$F1D9D9``6p~aQ#b}ZJ z>zbiG|FBoF_80Heuy#49W+(U8N1CFxps_K!teHVTmkEKxam@xluX8xSh2`@#A6XQg z#w7;?t=VC$S>X#Kk;OUI^(sScRHL0OYHWVfHSh%&RfG*M>^FsK29om&+mUw>LwH(PQ9Yy%SP{;w^VLHxkbM$%5t8)Wd7lF zMeVl(VtHG(W*@19_!DN6;b2s&X@Sbw1jqBlq$9;5tcZWX$S;AMlg zCi}kN!SjC|T@b6CU1zlzZRCj^hfTGn)CeVHKhRi&)St%^VX}P`fPc(JE{_?kWP7Szx+KZ?tj{jsf45NPM`^-MfIoMl;`@4pz$?#gASiG?=&)7bg%V-+Pb zg)k!k|J(vqSdG&OVRAAWSJYEvpIXGB&t2ddY*DA#gDV9_X3~2XL1K9wk=kk1ymFJ{ zyNM)3zUb(OX!eI<{p@J&UxaB=tzSO^kRa_lG;5W_76kFb(O<#@W}OgtDW0~&6w1i( zV|U>RewPgm3ClmWis3)5dW;`L+6lUE25TwM@? zN{pG=-jl%i{fWb0*^k;yW+}p3<|c_$us~#Py!s|!N3EUZ+;Vy;Lq|BC$T!d^(?l0J z!F^O!`8}t~D}OfgDXw5<`Fn-=5oTE_6QTJ!%8uVc+*D|1YQ|ErIAED*BrpkUJyh`9 z9;GnvB0Bj;6%3P7=(qE8Y+)#;38kvrPFJ#@uy$$^cy&IS)6&7f^oq61Tg3tH@<%5N z{9ldXSt>XDL(OM>Q1cQ;l)O{|s&72cO$D6(myO5qCb_u7mL)`eurQ?FSY(lBM_I*D zw!~SLj7JPQ{kelW8Q)k>?){(*x}LZ@9!%s3YWG;)$V5a5AOUunaSZ=zNBv&QbEYi; z$sh|QQ^3cD_sy2zHZdlAs-jm!$7jx_Z+N0x=YPhjI?4H{s`|nU+#$`xr%-?U~Ub=ZN1@@1M?fe0miWtCp zc9Bdw4IV0FI~U|NMoCY~fzHn8rt<2O)rIFt;(&uf4hf&Cha}iK^y|;1^F>6GiH5># zd9P%jRENUVo1MMn{0IDL`=kncfzMYU!(QK((t+<^6TC9^E%mwnu zvGBUs;(Z6?koF zjlGIK>(P+jn?C*N6XK3zD-N0%4p&3PR57eF zGbmu5ttj4qLo~i7K*hAEsf@_qTK1yd9IrNrAi08OALRC=X)j{+82@U_Yc8pJVFu#R z6AoOX4b@ok=lFuPLsMQ|$LsTs<5O~2Qq($~80tx!s zICfBx{KHFCARZIzZ@i8VjNdVVg^5xy!ki~!F!B)5_*ngMt_+aKGl*gP8zBw2Nj2e9 zk)q*0-K03h)m-;1i2l0^M!07tkAczIMUT}qwli_mPFIqc(P2E%$)Zv|t_ zhNFb5Wyh_nWpZoQJDHnt=l?bK=@QG{qFfJC-quG&gABf% z_ZP|X3{sT#3%oaK)`eqTn1E!l{req}vn$*nraBe~for_#$jBfb5vG@*)RATKk& zxOm>mDC?y3s#Z&@Z6vgry0|}%e}eMba|N$V31NEo<6y}-%*p~1f$9hks`(=%ZXs+( zkL#nCrZ{upgxOL0)D>(hkAp*6qOPL!#$rQ=Z2ad>bhl|u4y{XPwRJWnU~CK|&=3BY zg%kjoW`E2Y7X2OR?Nah5mxpIK)hP4o4V)gyzA_WH&Xch+{S)-WFnQ1AxjN;!Oc_a1 ztfpxK)t4o^w*gYVk^0jUNKpTO=-~m$9FZex&Gb88Wo&Ri;v#QgU*1&auet7li6jiO zBQ^h-wQZiFdvQKtvMw;1+j5pQ75R{FFbv|9D#@ZYDG zxNoxsq6n!Thimdb@P|07ut#6EJy{ZCqJ*0thVo3Qa9eRLHAN$if4{ubU!{$lCXNZ! zd>5MpCjqO7))-}7H$EB!2CD#`KmO!0Kzjf%CPBelT5V1yOc4LG`g|KEq#X?RoC9pV zc2c8-#ci-!qAJ#$J*sk*uxP;-nf5xyPG^^kDSr(Xyp8q`mb}kdBU9pi$*ILDu%|}8 z`Hb(K&imm&MH3ukzlZUch0?jM!nm}+utZXSz8)vC7^H^Y?*N_;#1Ldnn3c(&tO6z5 zA(Y(i@Z@FA`iTpO7^&cSw!Nan}piPp#j_AdEBPn>N&aqIyQEoknW3HPO z=)>ebGsPvm^T5KjdgP0yIlt%4J(JX#xN;l=U-D|C`1?#+6I`B=Zq0^D2*L{+W6>}7 zoDSSbKtsS&LmNGDJTwx%0Y!hvl{I^yXN?c9qQQXUTHS&%J_DUm6$j7`3Qq;(W(To>ynsDkX*0{Q<(s@v1UzdjL|7t+Z=M{;8zMmtWxU zXKp_mgE$V{yA%eW&5!XWmc{5U|xV^lvDY z9v%dXKyXP!LI)r#75`0^{T#@1x9G%>L?uE1kPC3+uEKZoanIcoLdGK*(e2lzAXUVi zjIExd)4ZlA4xY$oK)+9v5*&vx`6*VsWCkwD{ro**-|Ugp^iNyv+cI0WzMjw!={!0T zF!2@1^GN!HPfC#QoQl!kAab3dV$DNOP%u;bU*8+#zL$W(2W8c6!CyNXxj9jxje#o> z>MEwb?nfhutcE@v9~M$!b0&jdvDpvmuW?vo9nu}Z6O2V;FOy#Ev#fQ0*~Fp6ES%Jx z`uORUJCE&OlK<$PalHYe5-RGSFe&)h6u!}ya)6G0WH9$|mBob*QQvN(xmr^sokq{Ws4WnL{t@a7|;w1|$%f?EJ=Af&8`INwvH`KF> zCfa5xwfre;G70)yl8W#gG*Gr6LD#q`qqkWt4OAwQLh@pd&BeH+| zD4xalW7T7r@k(b4I!;i$t&rW+m`m-a^_H*>>8(x&(RVwGZ$bILirc|QIP@J($Slzn zyN3I6v1I3mZXwdWdMAAApP&EO>R{&c9(YAImLzAE1hE~>H{vJtm6qKr#Mg0UJ#An?d&{|rVZttrJg>u#N zxZAiz{3+)$>n=RK?+1Lt=}QRIz6~f~vrl%0bXsj=jf*SqGsVd-A;#T#Y=XcJpvC_9jBFDASF2b{~lQW1aC-QR=5UwHOCK(`f#wj0J zB?glhy2)3|^^_;Z>C0?-0QD!^zKv9NqzX3>_QS@=O8DGIUV@F3Q5MY8L%R9lf}h%a z$42IYFUF?I{FiyP!ZFvMKcg7d@SH}M@4|*CSAm}V9pj)1lu6KEB-2-NgJCDU?n6Sa zPwbhEA0E6uh%X-Tej`jcV)Ob~-WD6I4E)_U97#Or>a}}Bd-YP!XV}ZngJ7vtfQ??? zHk=eU_Sq(#GGQ#vd063U!HlPkzpD1LC2+j7?K_;jQvTsioB$HBo3G8j{&x`*n-}n@ zo;5{DGSfvT%mORi*eBKzaTQAxt6kjS+?1D|&DD)J5>J>U=A$$f=@mwvjq6l2CD&H( zSeL&pcOCROVsDIhQY%}~AkxntgEV&W8!S(>&7H-le{GD~P>Te75Qxp2r;>}3qC;#` zT*X;guM$*=<(N*y^2RJt^!U@4(NFNs^6rT4`|uhWl^eBa>*)A)|K7zF#NU_kt(I|M zUwu&=puI>p1v1BxAZ;tyAB+i=Rxb1okI5|N>~>l_k#^_bAd;>sSf=<}qA(j@n;`cr ziYI|rku;C+o<4L07g-SdysW@G4R$NWLUPL9#ccbTq+b2~EfPb>qT54gq&XNhg2OVH zw;BpgBN0$!gR`kI3T;kV*7XE#OxaJ|^~z1Y7{Relb4|nNQP4;wqV#uQwCx{;KG%j{ zFkJs`k(7NYpLl>EpogR8Cyp&Qjo+vMm~$aJf-@B7<}tRi`6)c=gNGcvM4F+QoMbru zJSFh4YwaHG&+4Rzt=6(V)^?Ikgzb=MvwUC_8b1u>TTwL0!8#9+NVmQ)@ti=UBc2Kk zmE8Jt|8@+D17v8mN5PJqpcXlV<9tl93_AQTskTTs2!JoS6jMH>@UDwdh;sFZK{O|5 zg;S5m+$taTL*7K8{XD-&h?D`iIGY{=exY%VT`$oq?9$gT zNjkvY6o!HS&FsM#<#k2nZ#K)}kWJZj(5$nqtImt5jP zL$zNk;ljC}Ak#qr9g;sna zP1)Q~rri6ocy5@ zr|)BWaB5GuHq5b(73SdA?o?JXRQ2{X60T?fGpmp358n%F<3C6AzdRY~py&xd&cNl9 z)@WD{Dq|{%H6e`J$o3A@_B0-L;=y*EStkFJ3$A9vW6 z`8mado)FsaYRtO`I6rt|irdX2&TA-ct}$PzVK7z_ez9@9GI?;adygAW=!4r$==6QM zoO3gst%vKFmPb8hBJ=}Gn&HnkZz>4G-&rbOy#LN8Ed@%7QK1b{0s^|jmM0t$D*&AT bFX>?>p5pnwY<1X+|6SEpwN<{ow2u5A1 Distance sensors** + 3. Select/Enable `lightware_grf_serial` + 4. Save the configuration + + - Manually update `default.px4` to include the configuration key: + 1. Open the `default.px4board` config file that corresponds to the board you want to build for. + For example, to add the driver to `fmu-v6x` boards you would update [/boards/px4/fmu-v6x/default.px4board ](https://github.com/PX4/PX4-Autopilot/blob/main/boards/px4/fmu-v6x/default.px4board) + 2. Add the following line and save the file: + + ```txt + CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_GRF_SERIAL=y + ``` + +2. [Build PX4](../dev_setup/building_px4.md) for your flight controller target and upload the new firmware. + +### Parameter Configuration + +You will need to configure PX4 to indicate the serial port to which the sensor is connected (as per [Serial Port Configuration](../peripherals/serial_configuration.md)) and also the orientation and other properties of the sensor. + +The [parameters to change](../advanced_config/parameters.md) are listed in the table. + +| Parameter | Description | +| -------------------------------------------------------------------------------------------------------- | -------------------------------------------------------- | +| [SENS_EN_GRF_CFG](../advanced_config/parameter_reference.md#SENS_EN_GRF_CFG) | Set to the serial port the sensor is connected to. | +| [GRF_UPDATE_CFG](../advanced_config/parameter_reference.md#GRF_UPDATE_CFG) | Set the update rate. | +| [GRF_SENS_MODEL](../advanced_config/parameter_reference.md#GRF_SENS_MODEL) | Set the update rate. | + +## Testing + +You can confirm that the sensor is correctly configured by connecting QGroundControl, and observing that [DISTANCE_SENSOR](https://mavlink.io/en/messages/common.html#DISTANCE_SENSOR) is present in the [MAVLink Inspector](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/analyze_view/mavlink_inspector.html). + +Moving the sensor around at various distances from a surface will have the `current_distance` value change. + +## Troubleshooting +If you are having problems with connecting to the sensor you may need to unassign a the default serial port. [Unassign Default Serial Port](../peripherals/serial_configuration.md) diff --git a/docs/en/sensor/sfxx_lidar.md b/docs/en/sensor/sfxx_lidar.md index e225422805..2ca57d9972 100644 --- a/docs/en/sensor/sfxx_lidar.md +++ b/docs/en/sensor/sfxx_lidar.md @@ -15,8 +15,8 @@ The following models are supported by PX4, and can be connected to either the I2 | [LW20/C](https://lightware.co.za/products/lw20-c-100-m) | 100 | I2C bus | Waterproofed (IP67) with servo for sense-and-avoid applications | | [SF30/D](https://lightwarelidar.com/shop/sf30-d-200-m/) | 200 | I2C bus | Waterproofed (IP67) | | [SF45/B](../sensor/sf45_rotating_lidar.md) | 50 | Serial | Rotary Lidar (Used for [Collision Prevention](../computer_vision/collision_prevention.md)) | -| [GRF250](https://lightwarelidar.com/shop/grf-250/) | 250 | I2C | Gimbal Range Finder | -| [GRF500](https://lightwarelidar.com/shop/grf-500/) | 500 | I2C | Gimbal Range Finder | +| [GRF250](../sensor/grf_lidar.md) | 250 | Serial or I2C | Gimbal Range Finder | +| [GRF500](../sensor/grf_lidar.md) | 500 | Serial or I2C | Gimbal Range Finder | ::: details Discontinued @@ -69,6 +69,9 @@ VTOL vehicles may choose to also set [SF1XX_MODE](../advanced_config/parameter_r ::: tip [SF45/B](../sensor/sf45_rotating_lidar.md) setup is covered in the linked document. ::: +::: tip +[GRF250/GRF500](../sensor/grf_lidar.md) setup is covered in the linked document. +::: ### Hardware diff --git a/src/drivers/distance_sensor/lightware_grf_serial/CMakeLists.txt b/src/drivers/distance_sensor/lightware_grf_serial/CMakeLists.txt new file mode 100755 index 0000000000..9a3c045be7 --- /dev/null +++ b/src/drivers/distance_sensor/lightware_grf_serial/CMakeLists.txt @@ -0,0 +1,46 @@ +############################################################################ +# +# Copyright (c) 2026 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +px4_add_module( + MODULE drivers__distance_sensor__lightware_grf_serial + MAIN lightware_grf_serial + COMPILE_FLAGS + SRCS + lightware_grf_serial.cpp + lightware_grf_serial.hpp + lightware_grf_serial_main.cpp + DEPENDS + drivers_rangefinder + px4_work_queue + MODULE_CONFIG + module.yaml + ) diff --git a/src/drivers/distance_sensor/lightware_grf_serial/Kconfig b/src/drivers/distance_sensor/lightware_grf_serial/Kconfig new file mode 100755 index 0000000000..3c89bf0974 --- /dev/null +++ b/src/drivers/distance_sensor/lightware_grf_serial/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_DISTANCE_SENSOR_LIGHTWARE_GRF_SERIAL + bool "lightware_grf_serial" + default n + ---help--- + Enable support for lightware_grf_serial diff --git a/src/drivers/distance_sensor/lightware_grf_serial/grf_commands.h b/src/drivers/distance_sensor/lightware_grf_serial/grf_commands.h new file mode 100755 index 0000000000..c278a166c6 --- /dev/null +++ b/src/drivers/distance_sensor/lightware_grf_serial/grf_commands.h @@ -0,0 +1,91 @@ +/**************************************************************************** + * + * Copyright (c) 2026 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file grf_commands.h + * @author Aaron Porter + * + * Declarations of grf serial commands for the Lightware grf series + */ + +#pragma once +#define GRF_MAX_PAYLOAD 256 +#define GRF_CRC_FIELDS 2 + +enum GRF_SERIAL_CMD { + GRF_PRODUCT_NAME = 0, + GRF_HARDWARE_VERSION = 1, + GRF_FIRMWARE_VERSION = 2, + GRF_SERIAL_NUMBER = 3, + GRF_TEXT_MESSAGE = 7, + GRF_USER_DATA = 9, + GRF_TOKEN = 10, + GRF_SAVE_PARAMETERS = 12, + GRF_RESET = 14, + GRF_STAGE_FIRMWARE = 16, + GRF_COMMIT_FIRMWARE = 17, + GRF_DISTANCE_OUTPUT = 27, + GRF_STREAM = 30, + GRF_DISTANCE_DATA_CM = 44, + GRF_DISTANCE_DATA_MM = 45, + GRF_LASER_FIRING = 50, + GRF_TEMPERATURE = 55, + GRF_AUTO_EXPOSURE = 70, + GRF_UPDATE_RATE = 74, + GRF_LOST_SIGNAL_COUNT = 78, + GRF_GPIO_MODE = 83, + GRF_GPIO_ALARM = 84, + GRF_MEDIAN_FILTER_EN = 86, + GRF_MEDIAN_FILETER_S = 87, + GRF_SMOOTH_FILTER_EN = 88, + GRF_SMOOTH_FACTOR = 89, + GRF_BAUD_RATE = 91, + GRF_I2C_ADDRESS = 92, + GRF_ROLL_AVG_EN = 93, + GRF_ROLL_AVG_SIZE = 94, + GRF_SLEEP_COMMAND = 98, + GRF_ZERO_OFFSET = 114 +}; + +// Store contents of rx'd frame +struct { + const uint8_t data_fields = 2; // useful for breaking crc's into byte separated fields + uint16_t data_len{0}; // last message payload length (1+ bytes in payload) + uint8_t data[GRF_MAX_PAYLOAD]; // payload size limited by posix serial + uint8_t msg_id{0}; // latest message's message id + uint8_t flags_lo{0}; // flags low byte + uint8_t flags_hi{0}; // flags high byte + uint16_t crc[GRF_CRC_FIELDS] = {0, 0}; + uint8_t crc_lo{0}; // crc low byte + uint8_t crc_hi{0}; // crc high byte +} rx_field; diff --git a/src/drivers/distance_sensor/lightware_grf_serial/lightware_grf_serial.cpp b/src/drivers/distance_sensor/lightware_grf_serial/lightware_grf_serial.cpp new file mode 100755 index 0000000000..403c61f562 --- /dev/null +++ b/src/drivers/distance_sensor/lightware_grf_serial/lightware_grf_serial.cpp @@ -0,0 +1,633 @@ +/************************************************************************** + * + * Copyright (c) 2026 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "lightware_grf_serial.hpp" + +#include +#include +#include +#include + +#include + +using namespace time_literals; + +GRFLaserSerial::GRFLaserSerial(const char *port, uint8_t rotation) : + ScheduledWorkItem(MODULE_NAME, px4::serial_port_to_wq(port)), + _px4_rangefinder(0, rotation), + _sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")), + _comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": com_err")) +{ + /* store port name */ + strncpy(_port, port, sizeof(_port) - 1); + + /* enforce null termination */ + _port[sizeof(_port) - 1] = '\0'; + + device::Device::DeviceId device_id; + device_id.devid_s.bus_type = device::Device::DeviceBusType_SERIAL; + + uint8_t bus_num = atoi(&_port[strlen(_port) - 1]); // Assuming '/dev/ttySx' + + if (bus_num < 10) { + device_id.devid_s.bus = bus_num; + } + + _px4_rangefinder.set_device_id(device_id.devid); + _px4_rangefinder.set_device_type(DRV_DIST_DEVTYPE_LIGHTWARE_LASER); + +} + +GRFLaserSerial::~GRFLaserSerial() +{ + stop(); + + perf_free(_sample_perf); + perf_free(_comms_errors); +} + +int GRFLaserSerial::init() +{ + param_get(param_find("GRF_RATE_CFG"), &_update_rate); + param_get(param_find("GRF_SENS_MODEL"), &_model_type); + + start(); + return PX4_OK; +} + +int GRFLaserSerial::measure() +{ + int32_t rate = (int32_t)_update_rate; + _data_output = 0x01; // raw distance (last return) + _stream_data = 5; // enable constant streaming + + // send packets to the sensor depending on the state + switch (_sensor_state) { + + case STATE_UNINIT: + // Used to probe if the sensor is alive + grf_send(GRF_PRODUCT_NAME, false, &_product_name[0], 0); + break; + + case STATE_ACK_PRODUCT_NAME: + // Update rate default to 5 readings/s + grf_send(GRF_UPDATE_RATE, true, &rate, sizeof(uint8_t)); + ScheduleDelayed(100_ms); + break; + + case STATE_ACK_UPDATE_RATE: + // Configure the data that the sensor shall output + grf_send(GRF_DISTANCE_OUTPUT, true, &_data_output, sizeof(_data_output)); + break; + + case STATE_ACK_DISTANCE_OUTPUT: + // Configure the sensor to automatically output data at the configured update rate + grf_send(GRF_STREAM, true, &_stream_data, sizeof(_stream_data)); + _sensor_state = STATE_SEND_STREAM; + break; + + default: + break; + } + + return PX4_OK; +} + +int GRFLaserSerial::collect() +{ + if (_sensor_state == STATE_UNINIT) { + + perf_begin(_sample_perf); + const int payload_length = 22; + + _crc_valid = false; + grf_get_and_handle_request(payload_length, GRF_PRODUCT_NAME); + + if (_crc_valid) { + _sensor_state = STATE_ACK_PRODUCT_NAME; + perf_end(_sample_perf); + return PX4_OK; + } + + perf_end(_sample_perf); + return -EAGAIN; + + } else if (_sensor_state == STATE_ACK_PRODUCT_NAME) { + + perf_begin(_sample_perf); + const int payload_length = 7; + + _crc_valid = false; + grf_get_and_handle_request(payload_length, GRF_UPDATE_RATE); + + if (_crc_valid) { + _sensor_state = STATE_ACK_UPDATE_RATE; + perf_end(_sample_perf); + return PX4_OK; + } + + perf_end(_sample_perf); + return -EAGAIN; + + } else if (_sensor_state == STATE_ACK_UPDATE_RATE) { + + perf_begin(_sample_perf); + const int payload_length = 10; + + _crc_valid = false; + grf_get_and_handle_request(payload_length, GRF_DISTANCE_OUTPUT); + + if (_crc_valid) { + _sensor_state = STATE_ACK_DISTANCE_OUTPUT; + perf_end(_sample_perf); + return PX4_OK; + } + + perf_end(_sample_perf); + return -EAGAIN; + + } else { + + // Stream data from sensor + perf_begin(_sample_perf); + const int payload_length = 10; + + _crc_valid = false; + grf_get_and_handle_request(payload_length, GRF_DISTANCE_DATA_CM); + + if (_crc_valid) { + grf_process_replies(); + perf_end(_sample_perf); + return PX4_OK; + } + + perf_end(_sample_perf); + return -EAGAIN; + } +} + +void GRFLaserSerial::start() +{ + /* reset the sensor state */ + _sensor_state = STATE_UNINIT; + + /* reset the report ring */ + _collect_phase = false; + + /* reset the UART receive buffer size */ + _linebuf_size = 0; + + /* reset the fail counter */ + _last_received_time = hrt_absolute_time(); + + /*Set Lidar Min/Max based on model*/ + switch (_model_type) { + case GRF250: { + _px4_rangefinder.set_min_distance(0.1f); + _px4_rangefinder.set_max_distance(250.0f); + break; + } + + case GRF500: { + _px4_rangefinder.set_min_distance(0.1f); + _px4_rangefinder.set_max_distance(500.0f); + break; + } + } + + /* schedule a cycle to start things */ + ScheduleNow(); +} + +void GRFLaserSerial::stop() +{ + ScheduleClear(); +} + +void GRFLaserSerial::Run() +{ + /* fds initialized? */ + if (_fd < 0) { + /* open fd: non-blocking read mode*/ + _fd = ::open(_port, O_RDWR | O_NOCTTY | O_NONBLOCK); + + if (_fd < 0) { + PX4_ERR("serial open failed (%i)", errno); + return; + } + + struct termios uart_config; + + int termios_state; + + /* fill the struct for the new configuration */ + tcgetattr(_fd, &uart_config); + + /* clear ONLCR flag (which appends a CR for every LF) */ + uart_config.c_oflag &= ~ONLCR; + + /* no parity, one stop bit */ + uart_config.c_cflag &= ~(CSTOPB | PARENB); + + unsigned speed = B115200; + + /* set baud rate */ + if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) { + PX4_ERR("CFG: %d ISPD", termios_state); + } + + if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) { + PX4_ERR("CFG: %d OSPD", termios_state); + } + + if ((termios_state = tcsetattr(_fd, TCSANOW, &uart_config)) < 0) { + PX4_ERR("baud %d ATTR", termios_state); + } + } + + if (_collect_phase) { + if (hrt_absolute_time() - _last_received_time >= 1_s) { + start(); + return; + } + + /* perform collection */ + if (collect() != PX4_OK && errno != EAGAIN) { + PX4_DEBUG("collect error"); + } + + if (_sensor_state != STATE_SEND_STREAM) { + /* next phase is measurement */ + _collect_phase = false; + } + + } else { + /* measurement phase */ + + if (measure() != PX4_OK) { + PX4_DEBUG("measure error"); + } + + /* next phase is collection */ + _collect_phase = true; + } + + /* schedule a fresh cycle call when the measurement is done */ + ScheduleDelayed(_interval); +} + +void GRFLaserSerial::print_info() +{ + perf_print_counter(_sample_perf); + perf_print_counter(_comms_errors); +} + +void GRFLaserSerial::grf_get_and_handle_request(const int payload_length, const GRF_SERIAL_CMD msg_id) +{ + // GRF protocol + // Start byte is 0xAA and is the start of packet + // Payload length sanity check (0-1023) bytes + // and represented by 16-bit integer (payload + + // read/write status) + // ID byte precedes the data in the payload + // CRC comprised of 16-bit checksum (not included in checksum calc.) + + int ret; + size_t max_read = sizeof(_linebuf) - _linebuf_size; + ret = ::read(_fd, &_linebuf[_linebuf_size], max_read); + + if (ret < 0 && errno != EAGAIN) { + PX4_ERR("ERROR (ack from streaming distance data): %d", ret); + _linebuf_size = 0; + perf_count(_comms_errors); + perf_end(_sample_perf); + return; + } + + if (ret > 0) { + _last_received_time = hrt_absolute_time(); + _linebuf_size += ret; + } + + // Not enough data to parse a complete packet. Gather more data in the next cycle. + if (_linebuf_size < payload_length) { + return; + } + + int index = 0; + + while (index <= _linebuf_size - payload_length && _crc_valid == false) { + bool restart_flag = false; + + while (restart_flag != true) { + switch (_parsed_state) { + case GRF_PARSED_STATE::START: { + if (_linebuf[index] == 0xAA) { + // start of frame is valid, continue + _calc_crc = grf_format_crc(_calc_crc, _start_of_frame); + _parsed_state = GRF_PARSED_STATE::FLG_LOW; + break; + + } else { + _crc_valid = false; + _parsed_state = GRF_PARSED_STATE::START; + restart_flag = true; + _calc_crc = 0; + PX4_DEBUG("Start of packet not valid: %d", _sensor_state); + break; + } + } + + case GRF_PARSED_STATE::FLG_LOW: { + rx_field.flags_lo = _linebuf[index + 1]; + _calc_crc = grf_format_crc(_calc_crc, rx_field.flags_lo); + _parsed_state = GRF_PARSED_STATE::FLG_HIGH; + break; + } + + case GRF_PARSED_STATE::FLG_HIGH: { + rx_field.flags_hi = _linebuf[index + 2]; + rx_field.data_len = (rx_field.flags_hi << 2) | (rx_field.flags_lo >> 6); + _calc_crc = grf_format_crc(_calc_crc, rx_field.flags_hi); + + // Check payload length against known max value + if (rx_field.data_len > 17) { + _parsed_state = GRF_PARSED_STATE::START; + restart_flag = true; + _calc_crc = 0; + PX4_DEBUG("Payload length error: %d", _sensor_state); + break; + + } else { + _parsed_state = GRF_PARSED_STATE::ID; + break; + } + } + + case GRF_PARSED_STATE::ID: { + rx_field.msg_id = _linebuf[index + 3]; + + if (rx_field.msg_id == msg_id) { + _calc_crc = grf_format_crc(_calc_crc, rx_field.msg_id); + _parsed_state = GRF_PARSED_STATE::DATA; + break; + } + + // Ignore message ID's that aren't searched + else { + _parsed_state = GRF_PARSED_STATE::START; + _calc_crc = 0; + restart_flag = true; + PX4_DEBUG("Non needed message ID: %d", _sensor_state); + break; + } + } + + case GRF_PARSED_STATE::DATA: { + // Process commands with & w/out data bytes + if (rx_field.data_len > 1) { + for (uint8_t i = 4; i < 3 + rx_field.data_len; ++i) { + + rx_field.data[_data_bytes_recv] = _linebuf[index + i]; + _calc_crc = grf_format_crc(_calc_crc, rx_field.data[_data_bytes_recv]); + _data_bytes_recv = _data_bytes_recv + 1; + + } + } + + else { + + _parsed_state = GRF_PARSED_STATE::CRC_LOW; + _data_bytes_recv = 0; + _calc_crc = grf_format_crc(_calc_crc, _data_bytes_recv); + } + + _parsed_state = GRF_PARSED_STATE::CRC_LOW; + _data_bytes_recv = 0; + break; + } + + case GRF_PARSED_STATE::CRC_LOW: { + rx_field.crc[0] = _linebuf[index + 3 + rx_field.data_len]; + _parsed_state = GRF_PARSED_STATE::CRC_HIGH; + break; + } + + case GRF_PARSED_STATE::CRC_HIGH: { + rx_field.crc[1] = _linebuf[index + 4 + rx_field.data_len]; + uint16_t recv_crc = (rx_field.crc[1] << 8) | rx_field.crc[0]; + + // Check the received crc bytes from the grf against our own CRC calcuation + // If it matches, we can check if sensor ready + // Only if crc match is valid and sensor ready (transmitting distance data) do we flag _init_complete + if (recv_crc == _calc_crc) { + _crc_valid = true; + _parsed_state = GRF_PARSED_STATE::START; + _calc_crc = 0; + restart_flag = true; + break; + + } else { + + _crc_valid = false; + _parsed_state = GRF_PARSED_STATE::START; + _calc_crc = 0; + restart_flag = true; + perf_count(_comms_errors); + PX4_DEBUG("CRC mismatch: %d", _sensor_state); + break; + } + } + } + } + + index++; + } + + // If we parsed successfully, remove the parsed part from the buffer if it is still large enough + if (_crc_valid && index + payload_length < _linebuf_size) { + unsigned next_after_index = index + payload_length; + memmove(&_linebuf[0], &_linebuf[next_after_index], _linebuf_size - next_after_index); + _linebuf_size -= next_after_index; + } + + // The buffer is filled. Either we can't keep up with the stream and/or it contains only invalid data. Reset to try again. + if ((unsigned)_linebuf_size >= sizeof(_linebuf)) { + _linebuf_size = 0; + perf_count(_comms_errors); + } +} + +void GRFLaserSerial::grf_send(uint8_t msg_id, bool write, int32_t *data, uint8_t data_len) +{ + uint16_t crc_val = 0; + uint8_t packet_buff[GRF_MAX_PAYLOAD]; + uint8_t data_inc = 4; + int ret = 0; + uint8_t packet_len = 0; + // Include payload ID byte in payload len + uint16_t flags = (data_len + 1) << 6; + + // If writing to the device, lsb is 1 + if (write) { + flags |= 0x01; + } + + else { + flags |= 0x0; + } + + uint8_t flags_lo = flags & 0xFF; + uint8_t flags_hi = (flags >> 8) & 0xFF; + + // Add packet bytes to format into crc based on CRC-16-CCITT 0x1021/XMODEM + crc_val = grf_format_crc(crc_val, _start_of_frame); + crc_val = grf_format_crc(crc_val, flags_lo); + crc_val = grf_format_crc(crc_val, flags_hi); + crc_val = grf_format_crc(crc_val, msg_id); + + // Write the packet header contents + payload msg ID to the output buffer + packet_buff[0] = _start_of_frame; + packet_buff[1] = flags_lo; + packet_buff[2] = flags_hi; + packet_buff[3] = msg_id; + + if (msg_id == GRF_DISTANCE_OUTPUT) { + uint8_t data_convert = data[0] & 0x00FF; + // write data bytes to the output buffer + packet_buff[data_inc] = data_convert; + // Add data bytes to crc add function + crc_val = grf_format_crc(crc_val, data_convert); + data_inc = data_inc + 1; + data_convert = data[0] >> 8; + packet_buff[data_inc] = data_convert; + crc_val = grf_format_crc(crc_val, data_convert); + data_inc = data_inc + 1; + packet_buff[data_inc] = 0; + crc_val = grf_format_crc(crc_val, packet_buff[data_inc]); + data_inc = data_inc + 1; + packet_buff[data_inc] = 0; + crc_val = grf_format_crc(crc_val, packet_buff[data_inc]); + data_inc = data_inc + 1; + } + + else if (msg_id == GRF_STREAM) { + packet_buff[data_inc] = data[0]; + //pad zeroes + crc_val = grf_format_crc(crc_val, data[0]); + data_inc = data_inc + 1; + packet_buff[data_inc] = 0; + crc_val = grf_format_crc(crc_val, packet_buff[data_inc]); + data_inc = data_inc + 1; + packet_buff[data_inc] = 0; + crc_val = grf_format_crc(crc_val, packet_buff[data_inc]); + data_inc = data_inc + 1; + packet_buff[data_inc] = 0; + crc_val = grf_format_crc(crc_val, packet_buff[data_inc]); + data_inc = data_inc + 1; + } + + else if (msg_id == GRF_UPDATE_RATE) { + // Update Rate + packet_buff[data_inc] = (uint8_t)data[0]; + // Add data bytes to crc add function + crc_val = grf_format_crc(crc_val, data[0]); + data_inc = data_inc + 1; + } + + else { + // Product Name + PX4_DEBUG("DEBUG: Product name"); + } + + uint8_t crc_lo = crc_val & 0xFF; + uint8_t crc_hi = (crc_val >> 8) & 0xFF; + + packet_buff[data_inc] = crc_lo; + data_inc = data_inc + 1; + packet_buff[data_inc] = crc_hi; + + size_t len = sizeof(packet_buff[0]) * (data_inc + 1); + packet_len = (uint8_t)len; + + // DEBUG + for (uint8_t i = 0; i < packet_len; ++i) { + PX4_DEBUG("DEBUG: Send byte: %d", packet_buff[i]); + } + + ret = ::write(_fd, packet_buff, packet_len); + + if (ret != packet_len) { + perf_count(_comms_errors); + PX4_ERR("serial write fail %d", ret); + // Flush data written, not transmitted + tcflush(_fd, TCOFLUSH); + } +} + +void GRFLaserSerial::grf_process_replies() +{ + float distance_m = -1.0f; + hrt_abstime now = hrt_absolute_time(); + + switch (rx_field.msg_id) { + case GRF_DISTANCE_DATA_CM: { + const float raw_distance = (rx_field.data[0] << 0) | (rx_field.data[1] << 8) | (rx_field.data[2] << 16); + distance_m = raw_distance * GRF_SCALE_FACTOR; + _px4_rangefinder.update(now, distance_m); + break; + } + + default: + // add case for future use + break; + } +} + +uint16_t GRFLaserSerial::grf_format_crc(uint16_t crc, uint8_t data_val) +{ + uint32_t i; + const uint16_t poly = 0x1021u; + crc ^= (uint16_t)((uint16_t) data_val << 8u); + + for (i = 0; i < 8; i++) { + if (crc & (1u << 15u)) { + crc = (uint16_t)((crc << 1u) ^ poly); + + } else { + crc = (uint16_t)(crc << 1u); + } + } + + return crc; +} diff --git a/src/drivers/distance_sensor/lightware_grf_serial/lightware_grf_serial.hpp b/src/drivers/distance_sensor/lightware_grf_serial/lightware_grf_serial.hpp new file mode 100755 index 0000000000..17c73c4d54 --- /dev/null +++ b/src/drivers/distance_sensor/lightware_grf_serial/lightware_grf_serial.hpp @@ -0,0 +1,134 @@ +/**************************************************************************** + * + * Copyright (c) 2026 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file lightware_grf_serial.hpp + * @author Aaron Porter + * + * Serial Protocol driver for the Lightware GRF rangefinder series + */ + +#pragma once + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include "grf_commands.h" + +enum GRF_SERIAL_STATE { + STATE_UNINIT = 0, + STATE_ACK_PRODUCT_NAME = 1, + STATE_ACK_UPDATE_RATE = 2, + STATE_ACK_DISTANCE_OUTPUT = 3, + STATE_SEND_STREAM = 4, +}; + +enum GRF_PARSED_STATE { + START = 0, + FLG_LOW, + FLG_HIGH, + ID, + DATA, + CRC_LOW, + CRC_HIGH +}; + +enum MODEL { + Disable = 0, + GRF250 = 1, + GRF500 = 2 +}; + +using namespace time_literals; +class GRFLaserSerial : public px4::ScheduledWorkItem +{ +public: + GRFLaserSerial(const char *port, uint8_t rotation = distance_sensor_s::ROTATION_DOWNWARD_FACING); + ~GRFLaserSerial() override; + + int init(); + void print_info(); + void grf_get_and_handle_request(const int payload_length, const GRF_SERIAL_CMD msg_id); + void grf_send(uint8_t msg_id, bool r_w, int32_t *data, uint8_t data_len); + uint16_t grf_format_crc(uint16_t crc, uint8_t data_value); + void grf_process_replies(); + +private: + + distance_sensor_s _distance{}; + static constexpr uint64_t GRF_MEAS_TIMEOUT{100_ms}; + static constexpr float GRF_SCALE_FACTOR = 0.1f; + + void start(); + void stop(); + void Run() override; + int measure(); + int collect(); + bool _crc_valid{false}; + + PX4Rangefinder _px4_rangefinder; + char _port[20] {}; + int _interval{200000}; + bool _collect_phase{false}; + int _fd{-1}; + uint8_t _linebuf[GRF_MAX_PAYLOAD] {}; + int _linebuf_size{0}; + + // GRF uses a binary protocol to include header,flags + // message ID, payload, and checksum + GRF_SERIAL_STATE _sensor_state{STATE_UNINIT}; + int _baud_rate{0}; + int32_t _product_name[16] = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; + int32_t _stream_data{0}; + int32_t _update_rate{0}; + int32_t _model_type{0}; + int32_t _data_output{0}; + const uint8_t _start_of_frame{0xAA}; + uint16_t _data_bytes_recv{0}; + uint8_t _parsed_state{0}; + uint16_t _calc_crc{0}; + + // end of GRF data members + + hrt_abstime _last_received_time{0}; + perf_counter_t _sample_perf; + perf_counter_t _comms_errors; +}; diff --git a/src/drivers/distance_sensor/lightware_grf_serial/lightware_grf_serial_main.cpp b/src/drivers/distance_sensor/lightware_grf_serial/lightware_grf_serial_main.cpp new file mode 100755 index 0000000000..08e912e2c8 --- /dev/null +++ b/src/drivers/distance_sensor/lightware_grf_serial/lightware_grf_serial_main.cpp @@ -0,0 +1,167 @@ +/**************************************************************************** + * + * Copyright (c) 2026 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "lightware_grf_serial.hpp" + +#include +#include + +namespace lightware_grf +{ + +GRFLaserSerial *g_dev{nullptr}; + +static int start(const char *port) +{ + if (g_dev != nullptr) { + PX4_WARN("already started"); + return -1; + } + + if (port == nullptr) { + PX4_ERR("no device specified"); + return -1; + } + + /* create the driver */ + g_dev = new GRFLaserSerial(port); + + if (g_dev == nullptr) { + return -1; + } + + if (g_dev->init() != PX4_OK) { + delete g_dev; + g_dev = nullptr; + return -1; + } + + return 0; +} + +static int stop() +{ + if (g_dev != nullptr) { + delete g_dev; + g_dev = nullptr; + + } else { + return -1; + } + + return 0; +} + +static int status() +{ + if (g_dev == nullptr) { + PX4_ERR("driver not running"); + return -1; + } + + g_dev->print_info(); + + return 0; +} + +static int usage() +{ + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description + +Serial bus driver for the Lightware GRF Laser rangefinder. + +### Configuration +https://docs.px4.io/main/en/sensor/grf_lidar + +### Parameters +https://docs.px4.io/main/en/advanced_config/parameter_reference#GRF_SENS_MODEL +https://docs.px4.io/main/en/advanced_config/parameter_reference#GRF_RATE_CFG +https://docs.px4.io/main/en/advanced_config/parameter_reference#SENS_EN_GRF_CFG + +### Examples + +Attempt to start driver on a specified serial device. +$ lightware_grf_serial start -d /dev/ttyS1 +Stop driver +$ lightware_grf_serial stop +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("lightware_grf_serial", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("distance_sensor"); + PRINT_MODULE_USAGE_COMMAND_DESCR("start", "Start driver"); + PRINT_MODULE_USAGE_PARAM_STRING('d', nullptr, nullptr, "Serial device", false); + PRINT_MODULE_USAGE_COMMAND_DESCR("stop", "Stop driver"); + return PX4_OK; +} + +} // namespace + +extern "C" __EXPORT int lightware_grf_serial_main(int argc, char *argv[]) +{ + const char *device_path = nullptr; + int ch; + int myoptind = 1; + const char *myoptarg = nullptr; + + while ((ch = px4_getopt(argc, argv, "d:", &myoptind, &myoptarg)) != EOF) { + switch (ch) { + case 'd': + device_path = myoptarg; + break; + + default: + lightware_grf::usage(); + return -1; + } + } + + if (myoptind >= argc) { + lightware_grf::usage(); + return -1; + } + + if (!strcmp(argv[myoptind], "start")) { + return lightware_grf::start(device_path); + + } else if (!strcmp(argv[myoptind], "stop")) { + return lightware_grf::stop(); + + } else if (!strcmp(argv[myoptind], "status")) { + return lightware_grf::status(); + } + + lightware_grf::usage(); + return -1; +} diff --git a/src/drivers/distance_sensor/lightware_grf_serial/module.yaml b/src/drivers/distance_sensor/lightware_grf_serial/module.yaml new file mode 100755 index 0000000000..7765f9802c --- /dev/null +++ b/src/drivers/distance_sensor/lightware_grf_serial/module.yaml @@ -0,0 +1,44 @@ +module_name: Lightware GRF Rangefinder (serial) +serial_config: + - command: lightware_grf_serial start -d ${SERIAL_DEV} + port_config_param: + name: SENS_EN_GRF_CFG + group: Sensors + num_instances: 1 + supports_networking: false + +parameters: + - group: Sensors + definitions: + GRF_RATE_CFG: + description: + short: Lightware GRF lidar update rate. + long: | + The Lightware GRF distance sensor can increase the update rate to enable greater resolution. + type: enum + values: + 1: 1 Hz + 2: 2 Hz + 3: 4 Hz + 4: 5 Hz + 5: 10 Hz + 6: 20 Hz + 7: 30 Hz + 8: 40 Hz + 9: 50 Hz + reboot_required: true + num_instances: 1 + default: 4 + GRF_SENS_MODEL: + description: + short: GRF Sensor model + long: | + GRF Sensor Model used to distinush between the GRF250 and GRF500 since both have different max distance range. + type: enum + values: + 0: disable + 1: GRF250 + 2: GRF500 + reboot_required: true + num_instances: 1 + default: 0 From 79bf7810d4fb2bb3f49aea32299554fe7deb57b8 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Mon, 16 Feb 2026 21:41:55 +0000 Subject: [PATCH 801/812] docs: auto-sync metadata [skip ci] Co-Authored-By: PX4 BuildBot --- .../en/advanced_config/parameter_reference.md | 63 +++ docs/en/middleware/dds_topics.md | 374 +++++++++--------- .../modules/modules_driver_distance_sensor.md | 43 ++ docs/en/sensor/grf_lidar.md | 9 +- 4 files changed, 298 insertions(+), 191 deletions(-) diff --git a/docs/en/advanced_config/parameter_reference.md b/docs/en/advanced_config/parameter_reference.md index b50fe34113..243536c8b5 100644 --- a/docs/en/advanced_config/parameter_reference.md +++ b/docs/en/advanced_config/parameter_reference.md @@ -33078,6 +33078,44 @@ Use SENS_MAG_SIDES instead | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 63 | +### GRF_RATE_CFG (`INT32`) {#GRF_RATE_CFG} + +Lightware GRF lidar update rate. + +The Lightware GRF distance sensor can increase the update rate to enable greater resolution. + +**Values:** + +- `1`: 1 Hz +- `2`: 2 Hz +- `3`: 4 Hz +- `4`: 5 Hz +- `5`: 10 Hz +- `6`: 20 Hz +- `7`: 30 Hz +- `8`: 40 Hz +- `9`: 50 Hz + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 4 | + +### GRF_SENS_MODEL (`INT32`) {#GRF_SENS_MODEL} + +GRF Sensor model. + +GRF Sensor Model used to distinush between the GRF250 and GRF500 since both have different max distance range. + +**Values:** + +- `0`: disable +- `1`: GRF250 +- `2`: GRF500 + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | + ### ILABS_MODE (`INT32`) {#ILABS_MODE} InertialLabs INS sensor mode configuration. @@ -34286,6 +34324,31 @@ Enable simulated GPS sinstance. | ------- | -------- | -------- | --------- | ------- | ---- | | ✓ | 0 | 1 | | 0 | +### SENS_EN_GRF_CFG (`INT32`) {#SENS_EN_GRF_CFG} + +Serial Configuration for Lightware GRF Rangefinder (serial). + +Configure on which serial port to run Lightware GRF Rangefinder (serial). + +**Values:** + +- `0`: Disabled +- `6`: UART 6 +- `101`: TELEM 1 +- `102`: TELEM 2 +- `103`: TELEM 3 +- `104`: TELEM/SERIAL 4 +- `201`: GPS 1 +- `202`: GPS 2 +- `203`: GPS 3 +- `300`: Radio Controller +- `301`: Wifi Port +- `401`: EXT2 + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | + ### SENS_EN_INA220 (`INT32`) {#SENS_EN_INA220} Enable INA220 Power Monitor. diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index ec937cc543..e5cdcc3c57 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -94,199 +94,199 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages -- [VehicleAirData](../msg_docs/VehicleAirData.md) -- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) -- [EstimatorStatus](../msg_docs/EstimatorStatus.md) -- [SensorAccel](../msg_docs/SensorAccel.md) -- [EscReport](../msg_docs/EscReport.md) -- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [PowerButtonState](../msg_docs/PowerButtonState.md) -- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) +- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [LogMessage](../msg_docs/LogMessage.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) - [GpioConfig](../msg_docs/GpioConfig.md) -- [EstimatorStates](../msg_docs/EstimatorStates.md) -- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) -- [GpsDump](../msg_docs/GpsDump.md) -- [LandingTargetPose](../msg_docs/LandingTargetPose.md) -- [AdcReport](../msg_docs/AdcReport.md) +- [GeofenceStatus](../msg_docs/GeofenceStatus.md) +- [ActuatorArmed](../msg_docs/ActuatorArmed.md) +- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) +- [Event](../msg_docs/Event.md) +- [CameraStatus](../msg_docs/CameraStatus.md) +- [RadioStatus](../msg_docs/RadioStatus.md) +- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) - [ActionRequest](../msg_docs/ActionRequest.md) -- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) -- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [GpsInjectData](../msg_docs/GpsInjectData.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) +- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) +- [SensorHygrometer](../msg_docs/SensorHygrometer.md) +- [Vtx](../msg_docs/Vtx.md) +- [GpioRequest](../msg_docs/GpioRequest.md) +- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) +- [LedControl](../msg_docs/LedControl.md) +- [MissionResult](../msg_docs/MissionResult.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) +- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) +- [SensorCorrection](../msg_docs/SensorCorrection.md) +- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) +- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [PowerButtonState](../msg_docs/PowerButtonState.md) +- [InputRc](../msg_docs/InputRc.md) +- [RtlStatus](../msg_docs/RtlStatus.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) +- [ButtonEvent](../msg_docs/ButtonEvent.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [RcChannels](../msg_docs/RcChannels.md) +- [EstimatorStates](../msg_docs/EstimatorStates.md) +- [SensorSelection](../msg_docs/SensorSelection.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [VehicleRoi](../msg_docs/VehicleRoi.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [LandingTargetPose](../msg_docs/LandingTargetPose.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [OrbTestMedium](../msg_docs/OrbTestMedium.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) +- [CameraCapture](../msg_docs/CameraCapture.md) +- [QshellRetval](../msg_docs/QshellRetval.md) +- [SensorMag](../msg_docs/SensorMag.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [QshellReq](../msg_docs/QshellReq.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [OrbTest](../msg_docs/OrbTest.md) +- [BatteryInfo](../msg_docs/BatteryInfo.md) +- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) +- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) +- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) +- [MagWorkerData](../msg_docs/MagWorkerData.md) +- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [VehicleAirData](../msg_docs/VehicleAirData.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) +- [Ping](../msg_docs/Ping.md) +- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [DifferentialPressure](../msg_docs/DifferentialPressure.md) +- [PpsCapture](../msg_docs/PpsCapture.md) +- [EstimatorStatus](../msg_docs/EstimatorStatus.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) +- [EventV0](../msg_docs/EventV0.md) +- [Gripper](../msg_docs/Gripper.md) - [NeuralControl](../msg_docs/NeuralControl.md) -- [UlogStream](../msg_docs/UlogStream.md) +- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) +- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) +- [GpioIn](../msg_docs/GpioIn.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) +- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [Rpm](../msg_docs/Rpm.md) +- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) +- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [CameraTrigger](../msg_docs/CameraTrigger.md) +- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) +- [AdcReport](../msg_docs/AdcReport.md) +- [LandingGearWheel](../msg_docs/LandingGearWheel.md) +- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [SensorUwb](../msg_docs/SensorUwb.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) +- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) +- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) +- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [DebugValue](../msg_docs/DebugValue.md) +- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) +- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) +- [GpioOut](../msg_docs/GpioOut.md) +- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) +- [SensorGyro](../msg_docs/SensorGyro.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [FollowTarget](../msg_docs/FollowTarget.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [RcParameterMap](../msg_docs/RcParameterMap.md) +- [FuelTankStatus](../msg_docs/FuelTankStatus.md) +- [SystemPower](../msg_docs/SystemPower.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [GainCompression](../msg_docs/GainCompression.md) +- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) +- [HealthReport](../msg_docs/HealthReport.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) +- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [VehicleImu](../msg_docs/VehicleImu.md) +- [Airspeed](../msg_docs/Airspeed.md) +- [EscReport](../msg_docs/EscReport.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [SensorsStatus](../msg_docs/SensorsStatus.md) +- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [OrbTestLarge](../msg_docs/OrbTestLarge.md) +- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) +- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) +- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) +- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [IrlockReport](../msg_docs/IrlockReport.md) +- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) +- [AirspeedWind](../msg_docs/AirspeedWind.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) +- [DeviceInformation](../msg_docs/DeviceInformation.md) +- [CellularStatus](../msg_docs/CellularStatus.md) +- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [RoverRateStatus](../msg_docs/RoverRateStatus.md) +- [SensorAccel](../msg_docs/SensorAccel.md) +- [PwmInput](../msg_docs/PwmInput.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [SensorAirflow](../msg_docs/SensorAirflow.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [ActuatorTest](../msg_docs/ActuatorTest.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [GpsDump](../msg_docs/GpsDump.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [GeneratorStatus](../msg_docs/GeneratorStatus.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) +- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) +- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [Mission](../msg_docs/Mission.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) +- [SensorBaro](../msg_docs/SensorBaro.md) +- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) - [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) - [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) -- [DebugArray](../msg_docs/DebugArray.md) -- [RoverRateStatus](../msg_docs/RoverRateStatus.md) -- [MagWorkerData](../msg_docs/MagWorkerData.md) -- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) -- [SatelliteInfo](../msg_docs/SatelliteInfo.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) -- [SensorsStatus](../msg_docs/SensorsStatus.md) -- [ParameterUpdate](../msg_docs/ParameterUpdate.md) -- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) -- [ActuatorTest](../msg_docs/ActuatorTest.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) -- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) -- [ActuatorArmed](../msg_docs/ActuatorArmed.md) -- [AirspeedWind](../msg_docs/AirspeedWind.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [FollowTarget](../msg_docs/FollowTarget.md) -- [GpioOut](../msg_docs/GpioOut.md) -- [IrlockReport](../msg_docs/IrlockReport.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) -- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) -- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) -- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [Event](../msg_docs/Event.md) -- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) -- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) -- [InputRc](../msg_docs/InputRc.md) -- [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [OrbTestLarge](../msg_docs/OrbTestLarge.md) -- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [CellularStatus](../msg_docs/CellularStatus.md) -- [GeneratorStatus](../msg_docs/GeneratorStatus.md) -- [Airspeed](../msg_docs/Airspeed.md) -- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) -- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) -- [GimbalControls](../msg_docs/GimbalControls.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) -- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) -- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) -- [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) -- [Ping](../msg_docs/Ping.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [SensorAirflow](../msg_docs/SensorAirflow.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [GpsInjectData](../msg_docs/GpsInjectData.md) -- [SystemPower](../msg_docs/SystemPower.md) -- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) -- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [Px4ioStatus](../msg_docs/Px4ioStatus.md) -- [MissionResult](../msg_docs/MissionResult.md) -- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) -- [PpsCapture](../msg_docs/PpsCapture.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [EventV0](../msg_docs/EventV0.md) -- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) -- [CameraStatus](../msg_docs/CameraStatus.md) -- [VehicleImu](../msg_docs/VehicleImu.md) -- [RcChannels](../msg_docs/RcChannels.md) -- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) -- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) -- [SensorGyroFft](../msg_docs/SensorGyroFft.md) -- [RaptorInput](../msg_docs/RaptorInput.md) -- [EstimatorBias](../msg_docs/EstimatorBias.md) -- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) -- [GeofenceStatus](../msg_docs/GeofenceStatus.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) -- [OrbTestMedium](../msg_docs/OrbTestMedium.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [SensorCorrection](../msg_docs/SensorCorrection.md) -- [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) -- [MountOrientation](../msg_docs/MountOrientation.md) -- [GpioIn](../msg_docs/GpioIn.md) -- [VehicleRoi](../msg_docs/VehicleRoi.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) -- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [SensorTemp](../msg_docs/SensorTemp.md) -- [Rpm](../msg_docs/Rpm.md) -- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) -- [SensorUwb](../msg_docs/SensorUwb.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) -- [SensorSelection](../msg_docs/SensorSelection.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [EscStatus](../msg_docs/EscStatus.md) -- [PwmInput](../msg_docs/PwmInput.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) -- [GainCompression](../msg_docs/GainCompression.md) -- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) -- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) -- [Gripper](../msg_docs/Gripper.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) - [PositionSetpoint](../msg_docs/PositionSetpoint.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) -- [Vtx](../msg_docs/Vtx.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) -- [ButtonEvent](../msg_docs/ButtonEvent.md) -- [LedControl](../msg_docs/LedControl.md) -- [LogMessage](../msg_docs/LogMessage.md) -- [RadioStatus](../msg_docs/RadioStatus.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) +- [SatelliteInfo](../msg_docs/SatelliteInfo.md) +- [UlogStream](../msg_docs/UlogStream.md) - [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [SensorMag](../msg_docs/SensorMag.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [RaptorStatus](../msg_docs/RaptorStatus.md) -- [Cpuload](../msg_docs/Cpuload.md) -- [BatteryInfo](../msg_docs/BatteryInfo.md) -- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) -- [GpioRequest](../msg_docs/GpioRequest.md) -- [CameraTrigger](../msg_docs/CameraTrigger.md) -- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) -- [QshellReq](../msg_docs/QshellReq.md) -- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) -- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) -- [SensorBaro](../msg_docs/SensorBaro.md) -- [HealthReport](../msg_docs/HealthReport.md) -- [TuneControl](../msg_docs/TuneControl.md) -- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [TecsStatus](../msg_docs/TecsStatus.md) -- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) -- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) -- [DebugValue](../msg_docs/DebugValue.md) -- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) - [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) -- [QshellRetval](../msg_docs/QshellRetval.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [Mission](../msg_docs/Mission.md) -- [DeviceInformation](../msg_docs/DeviceInformation.md) -- [RcParameterMap](../msg_docs/RcParameterMap.md) -- [LandingGearWheel](../msg_docs/LandingGearWheel.md) -- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) -- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) -- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) -- [SensorGyro](../msg_docs/SensorGyro.md) -- [RtlStatus](../msg_docs/RtlStatus.md) -- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [GimbalControls](../msg_docs/GimbalControls.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [Cpuload](../msg_docs/Cpuload.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) ::: diff --git a/docs/en/modules/modules_driver_distance_sensor.md b/docs/en/modules/modules_driver_distance_sensor.md index 4e78a7e7ff..9b82e6fc4a 100644 --- a/docs/en/modules/modules_driver_distance_sensor.md +++ b/docs/en/modules/modules_driver_distance_sensor.md @@ -98,6 +98,49 @@ leddar_one [arguments...] stop Stop driver ``` +## lightware_grf_serial + +Source: [drivers/distance_sensor/lightware_grf_serial](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/lightware_grf_serial) + +### Description + +Serial bus driver for the Lightware GRF Laser rangefinder. + +### Configuration + +https://docs.px4.io/main/en/sensor/grf_lidar + +### Parameters + +https://docs.px4.io/main/en/advanced_config/parameter_reference#GRF_SENS_MODEL +https://docs.px4.io/main/en/advanced_config/parameter_reference#GRF_RATE_CFG +https://docs.px4.io/main/en/advanced_config/parameter_reference#SENS_EN_GRF_CFG + +### Examples + +Attempt to start driver on a specified serial device. + +``` +lightware_grf_serial start -d /dev/ttyS1 +``` + +Stop driver + +``` +lightware_grf_serial stop +``` + +### Usage {#lightware_grf_serial_usage} + +``` +lightware_grf_serial [arguments...] + Commands: + start Start driver + -d Serial device + + stop Stop driver +``` + ## lightware_laser_i2c Source: [drivers/distance_sensor/lightware_laser_i2c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/lightware_laser_i2c) diff --git a/docs/en/sensor/grf_lidar.md b/docs/en/sensor/grf_lidar.md index efbc4e2718..836596e026 100644 --- a/docs/en/sensor/grf_lidar.md +++ b/docs/en/sensor/grf_lidar.md @@ -52,11 +52,11 @@ You will need to configure PX4 to indicate the serial port to which the sensor i The [parameters to change](../advanced_config/parameters.md) are listed in the table. -| Parameter | Description | -| -------------------------------------------------------------------------------------------------------- | -------------------------------------------------------- | +| Parameter | Description | +| -------------------------------------------------------------------------------------------------------- | -------------------------------------------------- | | [SENS_EN_GRF_CFG](../advanced_config/parameter_reference.md#SENS_EN_GRF_CFG) | Set to the serial port the sensor is connected to. | -| [GRF_UPDATE_CFG](../advanced_config/parameter_reference.md#GRF_UPDATE_CFG) | Set the update rate. | -| [GRF_SENS_MODEL](../advanced_config/parameter_reference.md#GRF_SENS_MODEL) | Set the update rate. | +| [GRF_UPDATE_CFG](../advanced_config/parameter_reference.md#GRF_UPDATE_CFG) | Set the update rate. | +| [GRF_SENS_MODEL](../advanced_config/parameter_reference.md#GRF_SENS_MODEL) | Set the update rate. | ## Testing @@ -65,4 +65,5 @@ You can confirm that the sensor is correctly configured by connecting QGroundCon Moving the sensor around at various distances from a surface will have the `current_distance` value change. ## Troubleshooting + If you are having problems with connecting to the sensor you may need to unassign a the default serial port. [Unassign Default Serial Port](../peripherals/serial_configuration.md) From a06f062bf7dadba551697ec0e6020344e0a5eb44 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 16 Feb 2026 21:04:06 -0800 Subject: [PATCH 802/812] nuttx: add nuttx_context dependency to jlink-nuttx build (#26505) --- platforms/nuttx/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/platforms/nuttx/CMakeLists.txt b/platforms/nuttx/CMakeLists.txt index 49e44b12ae..304273d05f 100644 --- a/platforms/nuttx/CMakeLists.txt +++ b/platforms/nuttx/CMakeLists.txt @@ -598,6 +598,7 @@ if(NOT NUTTX_DIR MATCHES "external") add_custom_target(jlink-nuttx ALL DEPENDS ${NUTTX_DIR}/tools/jlink-nuttx.so ) + add_dependencies(jlink-nuttx nuttx_context) # JLINK_RTOS_PATH used by launch.json.in set(JLINK_RTOS_PATH ${NUTTX_DIR}/tools/jlink-nuttx.so) From fd4b95879014e14cab2d5ef9922ea2478f438465 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 16 Feb 2026 21:04:18 -0800 Subject: [PATCH 803/812] ci: add geninfo negative error ignore to tests_coverage (#26506) --- Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Makefile b/Makefile index fb97276b52..df7c54f412 100644 --- a/Makefile +++ b/Makefile @@ -412,7 +412,7 @@ tests: $(call cmake-build,px4_sitl_test) # work around lcov bug #316; remove once lcov is fixed (see https://github.com/linux-test-project/lcov/issues/316) -LCOBUG = --ignore-errors mismatch +LCOBUG = --ignore-errors mismatch,negative tests_coverage: @$(MAKE) clean @$(MAKE) --no-print-directory tests PX4_CMAKE_BUILD_TYPE=Coverage From 11007dc8938dc26a6e12df7599dc363a5d039254 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 17 Feb 2026 09:26:38 +0100 Subject: [PATCH 804/812] FW auto launch: Add option to lock selected surfaces before/during launch (#25799) * FWModeManager: add option to set flag for disabling actuators during launch Signed-off-by: Silvan * Allocation: add option to each control surface to be locked for launch Signed-off-by: Silvan * FW rate control: reset integral while control surfaces are locked Signed-off-by: Silvan --------- Signed-off-by: Silvan Co-authored-by: mahima-yoga --- docs/en/flight_modes_fw/takeoff.md | 5 +++- msg/LaunchDetectionStatus.msg | 2 ++ .../ActuatorEffectivenessControlSurfaces.cpp | 14 +++++++++++ .../ActuatorEffectivenessControlSurfaces.hpp | 3 +++ .../ActuatorEffectivenessFixedWing.cpp | 12 ++++++++++ .../ActuatorEffectivenessFixedWing.hpp | 2 ++ src/modules/control_allocator/module.yaml | 24 ++++++++++++++++++- .../fw_mode_manager/FixedWingModeManager.cpp | 10 ++++++++ .../fw_mode_manager/FixedWingModeManager.hpp | 8 ++++++- .../fw_mode_manager/fw_mode_manager_params.c | 15 ++++++++++++ .../fw_rate_control/FixedwingRateControl.cpp | 12 +++++++++- .../fw_rate_control/FixedwingRateControl.hpp | 2 ++ 12 files changed, 105 insertions(+), 4 deletions(-) diff --git a/docs/en/flight_modes_fw/takeoff.md b/docs/en/flight_modes_fw/takeoff.md index 265c09f4b4..f85d7e77e6 100644 --- a/docs/en/flight_modes_fw/takeoff.md +++ b/docs/en/flight_modes_fw/takeoff.md @@ -85,6 +85,7 @@ The vehicle always respects normal FW max/min throttle settings during takeoff ( In _catapult/hand-launch mode_ the vehicle waits to detect launch (based on acceleration trigger). On launch it enables the motor(s) and climbs with the maximum climb rate [FW_T_CLMB_MAX](#FW_T_CLMB_MAX) while keeping the pitch setpoint above [FW_TKO_PITCH_MIN](#FW_TKO_PITCH_MIN). Once it reaches [MIS_TAKEOFF_ALT](#MIS_TAKEOFF_ALT) it will automatically switch to [Hold mode](../flight_modes_fw/hold.md) and loiter. +It is possible to delay the activation of the motors and control surfaces separately, see parameters [FW_LAUN_MOT_DEL](#FW_LAUN_MOT_DEL), [FW_LAUN_CS_LK_DY](#FW_LAUN_CS_LK_DY) and [CA_CS_LAUN_LK](#CA_CS_LAUN_LK). The later is also exposed in the actuator configuration page under the advanced view. All RC stick movement is ignored during the full takeoff sequence. @@ -104,7 +105,9 @@ The _launch detector_ is affected by the following parameters: | [FW_LAUN_DETCN_ON](../advanced_config/parameter_reference.md#FW_LAUN_DETCN_ON) | Enable automatic launch detection. If disabled motors spin up on arming already | | [FW_LAUN_AC_THLD](../advanced_config/parameter_reference.md#FW_LAUN_AC_THLD) | Acceleration threshold (acceleration in body-forward direction must be above this value) | | [FW_LAUN_AC_T](../advanced_config/parameter_reference.md#FW_LAUN_AC_T) | Trigger time (acceleration must be above threshold for this amount of seconds) | -| [FW_LAUN_MOT_DEL](../advanced_config/parameter_reference.md#FW_LAUN_MOT_DEL) | Delay from launch detection to motor spin up | +| [FW_LAUN_MOT_DEL](../advanced_config/parameter_reference.md#FW_LAUN_MOT_DEL) | Delay from launch detection to motor spin up +| [FW_LAUN_CS_LK_DY](../advanced_config/parameter_reference.md#FW_LAUN_CS_LK_DY) | Delay from launch detection to unlocking the control surfaces +| [CA_CS_LAUN_LK](../advanced_config/parameter_reference.md#CA_CS_LAUN_LK) | Bitmask to select which control surfaces are to be locked during launch | ## Runway Takeoff {#runway_launch} diff --git a/msg/LaunchDetectionStatus.msg b/msg/LaunchDetectionStatus.msg index 6917f4bc24..5693e5a822 100644 --- a/msg/LaunchDetectionStatus.msg +++ b/msg/LaunchDetectionStatus.msg @@ -7,3 +7,5 @@ uint8 STATE_LAUNCH_DETECTED_DISABLED_MOTOR = 1 # launch detected, but keep moto uint8 STATE_FLYING = 2 # launch detected, use normal takeoff/flying configuration uint8 launch_detection_state + +bool selected_control_surface_disarmed # [-] flag indicating whether selected actuators should kept disarmed (have to be configured in control allocation) diff --git a/src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessControlSurfaces.cpp b/src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessControlSurfaces.cpp index 8a033770ce..1a781035a4 100644 --- a/src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessControlSurfaces.cpp +++ b/src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessControlSurfaces.cpp @@ -63,6 +63,7 @@ ActuatorEffectivenessControlSurfaces::ActuatorEffectivenessControlSurfaces(Modul _spoilers_setpoint_with_slewrate.setSlewRate(kSpoilersSlewRate); _count_handle = param_find("CA_SV_CS_COUNT"); + _param_handle_ca_cs_laun_lk = param_find("CA_CS_LAUN_LK"); updateParams(); } @@ -112,6 +113,8 @@ void ActuatorEffectivenessControlSurfaces::updateParams() } } + param_get(_param_handle_ca_cs_laun_lk, &_param_ca_cs_laun_lk); + for (int i = 0; i < _count; i++) { param_get(_param_handles[i].type, (int32_t *)&_params[i].type); @@ -234,3 +237,14 @@ void ActuatorEffectivenessControlSurfaces::applySpoilers(float spoilers_control, actuator_sp(i + first_actuator_idx) += _spoilers_setpoint_with_slewrate.getState() * _params[i].scale_spoiler; } } + +void ActuatorEffectivenessControlSurfaces::applyLaunchLock(int first_actuator_idx, + ActuatorVector &actuator_sp) +{ + for (int i = 0; i < _count; ++i) { + + if (_param_ca_cs_laun_lk & (1u << i)) { + actuator_sp(i + first_actuator_idx) = NAN; + } + } +} diff --git a/src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessControlSurfaces.hpp b/src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessControlSurfaces.hpp index 8a77a08080..7da030fc18 100644 --- a/src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessControlSurfaces.hpp +++ b/src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessControlSurfaces.hpp @@ -90,6 +90,7 @@ public: void applyFlaps(float flaps_control, int first_actuator_idx, float dt, ActuatorVector &actuator_sp); void applySpoilers(float spoilers_control, int first_actuator_idx, float dt, ActuatorVector &actuator_sp); + void applyLaunchLock(int first_actuator_idx, ActuatorVector &actuator_sp); private: void updateParams() override; @@ -104,9 +105,11 @@ private: }; ParamHandles _param_handles[MAX_COUNT]; param_t _count_handle; + param_t _param_handle_ca_cs_laun_lk; Params _params[MAX_COUNT] {}; int32_t _count{0}; + int32_t _param_ca_cs_laun_lk{0}; SlewRate _flaps_setpoint_with_slewrate; SlewRate _spoilers_setpoint_with_slewrate; diff --git a/src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessFixedWing.cpp b/src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessFixedWing.cpp index e91783cf80..9a3c48e560 100644 --- a/src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessFixedWing.cpp +++ b/src/modules/control_allocator/VehicleActuatorEffectiveness/ActuatorEffectivenessFixedWing.cpp @@ -65,6 +65,18 @@ void ActuatorEffectivenessFixedWing::updateSetpoint(const matrix::Vector +#include class ActuatorEffectivenessFixedWing : public ModuleParams, public ActuatorEffectiveness { @@ -60,6 +61,7 @@ private: uORB::Subscription _flaps_setpoint_sub{ORB_ID(flaps_setpoint)}; uORB::Subscription _spoilers_setpoint_sub{ORB_ID(spoilers_setpoint)}; + uORB::Subscription _launch_detection_status_sub{ORB_ID(launch_detection_status)}; int _first_control_surface_idx{0}; ///< applies to matrix 1 diff --git a/src/modules/control_allocator/module.yaml b/src/modules/control_allocator/module.yaml index 1790484347..93e8c6ddc4 100644 --- a/src/modules/control_allocator/module.yaml +++ b/src/modules/control_allocator/module.yaml @@ -356,6 +356,22 @@ parameters: instance_start: 0 default: 0 + CA_CS_LAUN_LK: + description: + short: Control surface launch lock enabled + long: If actuator launch lock is enabled, this surface is kept at the disarmed value. + type: bitmask + bit: + 0: Control Surface 1 + 1: Control Surface 2 + 2: Control Surface 3 + 3: Control Surface 4 + 4: Control Surface 5 + 5: Control Surface 6 + 6: Control Surface 7 + 7: Control Surface 8 + default: 0 + # Tilts CA_SV_TL_COUNT: description: @@ -659,7 +675,7 @@ mixer: rules: - select_identifier: 'servo-type' # restrict torque based on servo type - apply_identifiers: ['servo-torque-roll', 'servo-torque-pitch', 'servo-torque-yaw', 'servo-scale-flap', 'servo-scale-spoiler'] + apply_identifiers: ['servo-torque-roll', 'servo-torque-pitch', 'servo-torque-yaw', 'servo-scale-flap', 'servo-scale-spoiler', 'servo-launch-lock'] items: # Convention: horizontal surfaces: up=positive, vertical: right=positive, mixed: up=positive. # By default the scale is set to 1/N, where N is the amount of actuators with an effect on @@ -858,6 +874,12 @@ mixer: label: 'Spoiler Scale' advanced: true identifier: 'servo-scale-spoiler' + - name: 'CA_CS_LAUN_LK' + label: 'Launch Lock' + advanced: true + identifier: 'servo-launch-lock' + index_offset: 0 + show_as: 'bitset' 2: # Standard VTOL title: 'Standard VTOL' diff --git a/src/modules/fw_mode_manager/FixedWingModeManager.cpp b/src/modules/fw_mode_manager/FixedWingModeManager.cpp index 1f752608ca..710fffb4f8 100644 --- a/src/modules/fw_mode_manager/FixedWingModeManager.cpp +++ b/src/modules/fw_mode_manager/FixedWingModeManager.cpp @@ -1207,6 +1207,7 @@ FixedWingModeManager::control_auto_takeoff(const hrt_abstime &now, const float c _takeoff_init_position = global_position; _takeoff_ground_alt = _current_altitude; _launch_current_yaw = _yaw; + _time_launch_detected = now; } const Vector2f launch_local_position = _global_local_proj_ref.project(_takeoff_init_position(0), @@ -1282,6 +1283,9 @@ FixedWingModeManager::control_auto_takeoff(const hrt_abstime &now, const float c launch_detection_status_s launch_detection_status; launch_detection_status.timestamp = now; launch_detection_status.launch_detection_state = _launchDetector.getLaunchDetected(); + launch_detection_status.selected_control_surface_disarmed = + hrt_elapsed_time(&_time_launch_detected) < _param_fw_laun_cs_lk_dy.get() * 1_s + || _time_launch_detected == 0; _launch_detection_status_pub.publish(launch_detection_status); } @@ -1377,6 +1381,7 @@ FixedWingModeManager::control_auto_takeoff_no_nav(const hrt_abstime &now, const if (!_launch_detected && _launchDetector.getLaunchDetected() > launch_detection_status_s::STATE_WAITING_FOR_LAUNCH) { _launch_detected = true; _takeoff_ground_alt = _current_altitude; + _time_launch_detected = now; } /* Launch has been detected, hence we have to control the plane. */ @@ -1408,6 +1413,9 @@ FixedWingModeManager::control_auto_takeoff_no_nav(const hrt_abstime &now, const launch_detection_status_s launch_detection_status; launch_detection_status.timestamp = now; launch_detection_status.launch_detection_state = _launchDetector.getLaunchDetected(); + launch_detection_status.selected_control_surface_disarmed = + hrt_elapsed_time(&_time_launch_detected) < _param_fw_laun_cs_lk_dy.get() * 1_s + || _time_launch_detected == 0; _launch_detection_status_pub.publish(launch_detection_status); } @@ -2312,6 +2320,8 @@ FixedWingModeManager::reset_takeoff_state() _launch_detected = false; + _time_launch_detected = 0; + _takeoff_ground_alt = _current_altitude; } diff --git a/src/modules/fw_mode_manager/FixedWingModeManager.hpp b/src/modules/fw_mode_manager/FixedWingModeManager.hpp index e026f8ce26..2a43968ffb 100644 --- a/src/modules/fw_mode_manager/FixedWingModeManager.hpp +++ b/src/modules/fw_mode_manager/FixedWingModeManager.hpp @@ -298,6 +298,9 @@ private: // true if a launch, specifically using the launch detector, has been detected bool _launch_detected{false}; + // [us] time stamp of (runway/catapult) launch detection + hrt_abstime _time_launch_detected{0}; + // [deg] global position of the vehicle at the time launch is detected (using launch detector) or takeoff is started (runway) Vector2d _takeoff_init_position{0, 0}; @@ -865,6 +868,10 @@ private: (ParamFloat) _param_nav_gpsf_r, (ParamFloat) _param_t_spdweight, + // Launch detection parameters + (ParamBool) _param_fw_laun_detcn_on, + (ParamFloat) _param_fw_laun_cs_lk_dy, + // external parameters (ParamBool) _param_fw_use_airspd, (ParamFloat) _param_nav_loiter_rad, @@ -881,7 +888,6 @@ private: (ParamInt) _param_fw_lnd_abort, (ParamFloat) _param_fw_tko_airspd, (ParamFloat) _param_rwto_psp, - (ParamBool) _param_fw_laun_detcn_on, (ParamFloat) _param_fw_airspd_max, (ParamFloat) _param_fw_airspd_min, (ParamFloat) _param_fw_airspd_trim, diff --git a/src/modules/fw_mode_manager/fw_mode_manager_params.c b/src/modules/fw_mode_manager/fw_mode_manager_params.c index 3a2edb6052..0d3cdf292c 100644 --- a/src/modules/fw_mode_manager/fw_mode_manager_params.c +++ b/src/modules/fw_mode_manager/fw_mode_manager_params.c @@ -580,6 +580,21 @@ PARAM_DEFINE_INT32(FW_LND_ABORT, 3); */ PARAM_DEFINE_INT32(FW_LAUN_DETCN_ON, 0); +/** + * Control surface launch delay + * + * Locks control surfaces during pre-launch (armed) and until this time since launch has passed. + * Only affects control surfaces that have corresponding flag set, and not active for runway takeoff. + * Set to 0 to disable any surface locking after arming. + * + * @unit s + * @min 0.0 + * @decimal 1 + * @increment 0.1 + * @group FW Auto Takeoff + */ +PARAM_DEFINE_FLOAT(FW_LAUN_CS_LK_DY, 0.f); + /** * Flaps setting during take-off * diff --git a/src/modules/fw_rate_control/FixedwingRateControl.cpp b/src/modules/fw_rate_control/FixedwingRateControl.cpp index 993d68bdd0..69631979a5 100644 --- a/src/modules/fw_rate_control/FixedwingRateControl.cpp +++ b/src/modules/fw_rate_control/FixedwingRateControl.cpp @@ -287,8 +287,18 @@ void FixedwingRateControl::Run() _rate_control.resetIntegral(); } + launch_detection_status_s launch_detection_status{}; + _launch_detection_status_sub.copy(&launch_detection_status); + + bool control_surfaces_locked = false; + + if (hrt_elapsed_time(&launch_detection_status.timestamp) < 100_ms + && launch_detection_status.selected_control_surface_disarmed) { + control_surfaces_locked = true; + } + // Reset integrators if the aircraft is on ground or not in a state where the fw attitude controller is run - if (_landed || !_in_fw_or_transition_wo_tailsitter_transition) { + if (_landed || !_in_fw_or_transition_wo_tailsitter_transition || control_surfaces_locked) { _gain_compression.reset(); _rate_control.resetIntegral(); diff --git a/src/modules/fw_rate_control/FixedwingRateControl.hpp b/src/modules/fw_rate_control/FixedwingRateControl.hpp index 54cf23be00..1bdab1c135 100644 --- a/src/modules/fw_rate_control/FixedwingRateControl.hpp +++ b/src/modules/fw_rate_control/FixedwingRateControl.hpp @@ -70,6 +70,7 @@ #include #include #include +#include using matrix::Eulerf; using matrix::Quatf; @@ -110,6 +111,7 @@ private: uORB::Subscription _vehicle_land_detected_sub{ORB_ID(vehicle_land_detected)}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; uORB::Subscription _vehicle_rates_sub{ORB_ID(vehicle_angular_velocity)}; + uORB::Subscription _launch_detection_status_sub{ORB_ID(launch_detection_status)}; uORB::SubscriptionMultiArray _control_allocator_status_subs{ORB_ID::control_allocator_status}; From 4331f880f5fa96b71b6baec3bd4edde545b9facc Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Tue, 17 Feb 2026 08:37:39 +0000 Subject: [PATCH 805/812] docs: auto-sync metadata [skip ci] Co-Authored-By: PX4 BuildBot --- .../en/advanced_config/parameter_reference.md | 33 ++ docs/en/flight_modes_fw/takeoff.md | 6 +- docs/en/middleware/dds_topics.md | 370 +++++++++--------- docs/en/msg_docs/LaunchDetectionStatus.md | 11 +- docs/public/config/failsafe/index.js | 2 +- docs/public/config/failsafe/index.wasm | Bin 96677 -> 96725 bytes docs/public/config/failsafe/parameters.json | 2 +- 7 files changed, 230 insertions(+), 194 deletions(-) diff --git a/docs/en/advanced_config/parameter_reference.md b/docs/en/advanced_config/parameter_reference.md index 243536c8b5..63b3f3d195 100644 --- a/docs/en/advanced_config/parameter_reference.md +++ b/docs/en/advanced_config/parameter_reference.md @@ -19596,6 +19596,18 @@ Launch is detected when acceleration in body forward direction is above FW_LAUN_ | ------ | -------- | -------- | --------- | ------- | ----- | |   | 0 | | 0.5 | 30.0 | m/s^2 | +### FW_LAUN_CS_LK_DY (`FLOAT`) {#FW_LAUN_CS_LK_DY} + +Control surface launch delay. + +Locks control surfaces during pre-launch (armed) and until this time since launch has passed. +Only affects control surfaces that have corresponding flag set, and not active for runway takeoff. +Set to 0 to disable any surface locking after arming. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.0 | | 0.1 | 0. | s | + ### FW_LAUN_DETCN_ON (`INT32`) {#FW_LAUN_DETCN_ON} Fixed-wing launch detection. @@ -21325,6 +21337,27 @@ Some are generic, while others are specifically fit to a certain vehicle with a | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | +### CA_CS_LAUN_LK (`INT32`) {#CA_CS_LAUN_LK} + +Control surface launch lock enabled. + +If actuator launch lock is enabled, this surface is kept at the disarmed value. + +**Bitmask:** + +- `0`: Control Surface 1 +- `1`: Control Surface 2 +- `2`: Control Surface 3 +- `3`: Control Surface 4 +- `4`: Control Surface 5 +- `5`: Control Surface 6 +- `6`: Control Surface 7 +- `7`: Control Surface 8 + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 255 | | 0 | + ### CA_FAILURE_MODE (`INT32`) {#CA_FAILURE_MODE} Motor failure handling mode. diff --git a/docs/en/flight_modes_fw/takeoff.md b/docs/en/flight_modes_fw/takeoff.md index f85d7e77e6..b95d0806e1 100644 --- a/docs/en/flight_modes_fw/takeoff.md +++ b/docs/en/flight_modes_fw/takeoff.md @@ -105,9 +105,9 @@ The _launch detector_ is affected by the following parameters: | [FW_LAUN_DETCN_ON](../advanced_config/parameter_reference.md#FW_LAUN_DETCN_ON) | Enable automatic launch detection. If disabled motors spin up on arming already | | [FW_LAUN_AC_THLD](../advanced_config/parameter_reference.md#FW_LAUN_AC_THLD) | Acceleration threshold (acceleration in body-forward direction must be above this value) | | [FW_LAUN_AC_T](../advanced_config/parameter_reference.md#FW_LAUN_AC_T) | Trigger time (acceleration must be above threshold for this amount of seconds) | -| [FW_LAUN_MOT_DEL](../advanced_config/parameter_reference.md#FW_LAUN_MOT_DEL) | Delay from launch detection to motor spin up -| [FW_LAUN_CS_LK_DY](../advanced_config/parameter_reference.md#FW_LAUN_CS_LK_DY) | Delay from launch detection to unlocking the control surfaces -| [CA_CS_LAUN_LK](../advanced_config/parameter_reference.md#CA_CS_LAUN_LK) | Bitmask to select which control surfaces are to be locked during launch | +| [FW_LAUN_MOT_DEL](../advanced_config/parameter_reference.md#FW_LAUN_MOT_DEL) | Delay from launch detection to motor spin up | +| [FW_LAUN_CS_LK_DY](../advanced_config/parameter_reference.md#FW_LAUN_CS_LK_DY) | Delay from launch detection to unlocking the control surfaces | +| [CA_CS_LAUN_LK](../advanced_config/parameter_reference.md#CA_CS_LAUN_LK) | Bitmask to select which control surfaces are to be locked during launch | ## Runway Takeoff {#runway_launch} diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index e5cdcc3c57..612abca650 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -94,199 +94,199 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages -- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [LogMessage](../msg_docs/LogMessage.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) -- [GpioConfig](../msg_docs/GpioConfig.md) -- [GeofenceStatus](../msg_docs/GeofenceStatus.md) -- [ActuatorArmed](../msg_docs/ActuatorArmed.md) -- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) -- [Event](../msg_docs/Event.md) -- [CameraStatus](../msg_docs/CameraStatus.md) -- [RadioStatus](../msg_docs/RadioStatus.md) -- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) -- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) -- [ActionRequest](../msg_docs/ActionRequest.md) -- [GpsInjectData](../msg_docs/GpsInjectData.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) -- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) -- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [Vtx](../msg_docs/Vtx.md) -- [GpioRequest](../msg_docs/GpioRequest.md) -- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [LedControl](../msg_docs/LedControl.md) -- [MissionResult](../msg_docs/MissionResult.md) -- [EscStatus](../msg_docs/EscStatus.md) -- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) -- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [SensorCorrection](../msg_docs/SensorCorrection.md) -- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [TecsStatus](../msg_docs/TecsStatus.md) -- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) -- [PowerButtonState](../msg_docs/PowerButtonState.md) -- [InputRc](../msg_docs/InputRc.md) -- [RtlStatus](../msg_docs/RtlStatus.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) -- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) -- [ButtonEvent](../msg_docs/ButtonEvent.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) -- [RcChannels](../msg_docs/RcChannels.md) -- [EstimatorStates](../msg_docs/EstimatorStates.md) -- [SensorSelection](../msg_docs/SensorSelection.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) -- [VehicleRoi](../msg_docs/VehicleRoi.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) -- [LandingTargetPose](../msg_docs/LandingTargetPose.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) -- [OrbTestMedium](../msg_docs/OrbTestMedium.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [QshellRetval](../msg_docs/QshellRetval.md) -- [SensorMag](../msg_docs/SensorMag.md) -- [EstimatorBias](../msg_docs/EstimatorBias.md) -- [QshellReq](../msg_docs/QshellReq.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [BatteryInfo](../msg_docs/BatteryInfo.md) -- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) -- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) -- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) -- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) -- [MountOrientation](../msg_docs/MountOrientation.md) -- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [MagWorkerData](../msg_docs/MagWorkerData.md) -- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [PwmInput](../msg_docs/PwmInput.md) +- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [GeneratorStatus](../msg_docs/GeneratorStatus.md) - [VehicleAirData](../msg_docs/VehicleAirData.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [Ping](../msg_docs/Ping.md) -- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) -- [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [PpsCapture](../msg_docs/PpsCapture.md) -- [EstimatorStatus](../msg_docs/EstimatorStatus.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [EventV0](../msg_docs/EventV0.md) -- [Gripper](../msg_docs/Gripper.md) -- [NeuralControl](../msg_docs/NeuralControl.md) -- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) +- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) +- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) +- [SensorHygrometer](../msg_docs/SensorHygrometer.md) +- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) +- [SensorGyro](../msg_docs/SensorGyro.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) - [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [GpioIn](../msg_docs/GpioIn.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) - [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) -- [UlogStreamAck](../msg_docs/UlogStreamAck.md) -- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [CameraTrigger](../msg_docs/CameraTrigger.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [EscReport](../msg_docs/EscReport.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) +- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [HealthReport](../msg_docs/HealthReport.md) +- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) +- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) +- [OrbTest](../msg_docs/OrbTest.md) +- [CellularStatus](../msg_docs/CellularStatus.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [GimbalControls](../msg_docs/GimbalControls.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) +- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) - [Rpm](../msg_docs/Rpm.md) - [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) -- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) -- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) -- [CameraTrigger](../msg_docs/CameraTrigger.md) +- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) +- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [PositionSetpoint](../msg_docs/PositionSetpoint.md) +- [DebugValue](../msg_docs/DebugValue.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) +- [Event](../msg_docs/Event.md) +- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) +- [DeviceInformation](../msg_docs/DeviceInformation.md) +- [UlogStream](../msg_docs/UlogStream.md) +- [InputRc](../msg_docs/InputRc.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [GpsDump](../msg_docs/GpsDump.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [SensorUwb](../msg_docs/SensorUwb.md) +- [OrbTestLarge](../msg_docs/OrbTestLarge.md) +- [RoverRateStatus](../msg_docs/RoverRateStatus.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) +- [SystemPower](../msg_docs/SystemPower.md) +- [ActionRequest](../msg_docs/ActionRequest.md) +- [FuelTankStatus](../msg_docs/FuelTankStatus.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [GeofenceStatus](../msg_docs/GeofenceStatus.md) +- [CameraCapture](../msg_docs/CameraCapture.md) +- [GpioIn](../msg_docs/GpioIn.md) +- [CameraStatus](../msg_docs/CameraStatus.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) +- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) +- [VehicleRoi](../msg_docs/VehicleRoi.md) +- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) +- [BatteryInfo](../msg_docs/BatteryInfo.md) +- [GpsInjectData](../msg_docs/GpsInjectData.md) +- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [RadioStatus](../msg_docs/RadioStatus.md) +- [LogMessage](../msg_docs/LogMessage.md) +- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [RcParameterMap](../msg_docs/RcParameterMap.md) +- [VehicleImu](../msg_docs/VehicleImu.md) +- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) +- [QshellRetval](../msg_docs/QshellRetval.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [SensorCorrection](../msg_docs/SensorCorrection.md) +- [SatelliteInfo](../msg_docs/SatelliteInfo.md) +- [Vtx](../msg_docs/Vtx.md) +- [GpioOut](../msg_docs/GpioOut.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) - [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) +- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) +- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [SensorBaro](../msg_docs/SensorBaro.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) +- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [Mission](../msg_docs/Mission.md) +- [FollowTarget](../msg_docs/FollowTarget.md) +- [Gripper](../msg_docs/Gripper.md) +- [DifferentialPressure](../msg_docs/DifferentialPressure.md) +- [AirspeedWind](../msg_docs/AirspeedWind.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) +- [SensorAccel](../msg_docs/SensorAccel.md) +- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [IrlockReport](../msg_docs/IrlockReport.md) +- [GpioRequest](../msg_docs/GpioRequest.md) +- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) +- [GpioConfig](../msg_docs/GpioConfig.md) +- [EventV0](../msg_docs/EventV0.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) +- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) +- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [PowerButtonState](../msg_docs/PowerButtonState.md) +- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) +- [PpsCapture](../msg_docs/PpsCapture.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [SensorsStatus](../msg_docs/SensorsStatus.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) +- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) +- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [Cpuload](../msg_docs/Cpuload.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) +- [SensorAirflow](../msg_docs/SensorAirflow.md) - [AdcReport](../msg_docs/AdcReport.md) - [LandingGearWheel](../msg_docs/LandingGearWheel.md) -- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) -- [SensorUwb](../msg_docs/SensorUwb.md) -- [RaptorStatus](../msg_docs/RaptorStatus.md) -- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) -- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) -- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) -- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [DebugValue](../msg_docs/DebugValue.md) -- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) -- [GpioOut](../msg_docs/GpioOut.md) -- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) -- [SensorGyro](../msg_docs/SensorGyro.md) -- [RaptorInput](../msg_docs/RaptorInput.md) -- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [FollowTarget](../msg_docs/FollowTarget.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [RcParameterMap](../msg_docs/RcParameterMap.md) -- [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [SystemPower](../msg_docs/SystemPower.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) -- [GainCompression](../msg_docs/GainCompression.md) -- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) -- [HealthReport](../msg_docs/HealthReport.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) -- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) -- [VehicleImu](../msg_docs/VehicleImu.md) -- [Airspeed](../msg_docs/Airspeed.md) -- [EscReport](../msg_docs/EscReport.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [SensorsStatus](../msg_docs/SensorsStatus.md) -- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) -- [OrbTestLarge](../msg_docs/OrbTestLarge.md) -- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) -- [ParameterUpdate](../msg_docs/ParameterUpdate.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) -- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) -- [IrlockReport](../msg_docs/IrlockReport.md) -- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) -- [AirspeedWind](../msg_docs/AirspeedWind.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [DeviceInformation](../msg_docs/DeviceInformation.md) -- [CellularStatus](../msg_docs/CellularStatus.md) -- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [RoverRateStatus](../msg_docs/RoverRateStatus.md) -- [SensorAccel](../msg_docs/SensorAccel.md) -- [PwmInput](../msg_docs/PwmInput.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [SensorAirflow](../msg_docs/SensorAirflow.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) -- [ActuatorTest](../msg_docs/ActuatorTest.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) -- [GpsDump](../msg_docs/GpsDump.md) -- [DebugArray](../msg_docs/DebugArray.md) -- [GeneratorStatus](../msg_docs/GeneratorStatus.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) -- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) -- [Mission](../msg_docs/Mission.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [SensorBaro](../msg_docs/SensorBaro.md) -- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) +- [RtlStatus](../msg_docs/RtlStatus.md) - [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) -- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) -- [PositionSetpoint](../msg_docs/PositionSetpoint.md) -- [SatelliteInfo](../msg_docs/SatelliteInfo.md) -- [UlogStream](../msg_docs/UlogStream.md) -- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [TuneControl](../msg_docs/TuneControl.md) -- [GimbalControls](../msg_docs/GimbalControls.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) -- [Cpuload](../msg_docs/Cpuload.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) -- [SensorTemp](../msg_docs/SensorTemp.md) +- [Ping](../msg_docs/Ping.md) +- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [EstimatorStatus](../msg_docs/EstimatorStatus.md) +- [OrbTestMedium](../msg_docs/OrbTestMedium.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [RcChannels](../msg_docs/RcChannels.md) +- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) +- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) +- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) +- [Airspeed](../msg_docs/Airspeed.md) +- [EstimatorStates](../msg_docs/EstimatorStates.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [NeuralControl](../msg_docs/NeuralControl.md) +- [SensorSelection](../msg_docs/SensorSelection.md) - [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [LedControl](../msg_docs/LedControl.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [LandingTargetPose](../msg_docs/LandingTargetPose.md) +- [GainCompression](../msg_docs/GainCompression.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [ActuatorTest](../msg_docs/ActuatorTest.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) +- [QshellReq](../msg_docs/QshellReq.md) +- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) +- [ButtonEvent](../msg_docs/ButtonEvent.md) +- [ActuatorArmed](../msg_docs/ActuatorArmed.md) +- [MissionResult](../msg_docs/MissionResult.md) +- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [MagWorkerData](../msg_docs/MagWorkerData.md) +- [SensorMag](../msg_docs/SensorMag.md) +- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) +- [Px4ioStatus](../msg_docs/Px4ioStatus.md) ::: diff --git a/docs/en/msg_docs/LaunchDetectionStatus.md b/docs/en/msg_docs/LaunchDetectionStatus.md index 49067ef229..4f18e03700 100644 --- a/docs/en/msg_docs/LaunchDetectionStatus.md +++ b/docs/en/msg_docs/LaunchDetectionStatus.md @@ -10,10 +10,11 @@ Status of the launch detection state machine (fixed-wing only). ## Fields -| Name | Type | Unit [Frame] | Range/Enum | Description | -| ---------------------- | -------- | ------------ | ---------- | -------------------------------------- | -| timestamp | `uint64` | | | time since system start (microseconds) | -| launch_detection_state | `uint8` | | | +| Name | Type | Unit [Frame] | Range/Enum | Description | +| --------------------------------- | -------- | ------------ | ---------- | ------------------------------------------------------------------------------------------------------------- | +| timestamp | `uint64` | | | time since system start (microseconds) | +| launch_detection_state | `uint8` | | | +| selected_control_surface_disarmed | `bool` | | | flag indicating whether selected actuators should kept disarmed (have to be configured in control allocation) | ## Constants @@ -39,6 +40,8 @@ uint8 STATE_LAUNCH_DETECTED_DISABLED_MOTOR = 1 # launch detected, but keep moto uint8 STATE_FLYING = 2 # launch detected, use normal takeoff/flying configuration uint8 launch_detection_state + +bool selected_control_surface_disarmed # [-] flag indicating whether selected actuators should kept disarmed (have to be configured in control allocation) ``` ::: diff --git a/docs/public/config/failsafe/index.js b/docs/public/config/failsafe/index.js index 1d4ce8cd21..d013fbdc67 100644 --- a/docs/public/config/failsafe/index.js +++ b/docs/public/config/failsafe/index.js @@ -1 +1 @@ -var Module=typeof Module!="undefined"?Module:{};var ENVIRONMENT_IS_WEB=typeof window=="object";var ENVIRONMENT_IS_WORKER=typeof importScripts=="function";var ENVIRONMENT_IS_NODE=typeof process=="object"&&typeof process.versions=="object"&&typeof process.versions.node=="string";if(ENVIRONMENT_IS_NODE){}var moduleOverrides=Object.assign({},Module);var arguments_=[];var thisProgram="./this.program";var quit_=(status,toThrow)=>{throw toThrow};var scriptDirectory="";function locateFile(path){if(Module["locateFile"]){return Module["locateFile"](path,scriptDirectory)}return scriptDirectory+path}var readAsync,readBinary;if(ENVIRONMENT_IS_NODE){var fs=require("fs");var nodePath=require("path");scriptDirectory=__dirname+"/";readBinary=filename=>{filename=isFileURI(filename)?new URL(filename):nodePath.normalize(filename);var ret=fs.readFileSync(filename);return ret};readAsync=(filename,binary=true)=>{filename=isFileURI(filename)?new URL(filename):nodePath.normalize(filename);return new Promise((resolve,reject)=>{fs.readFile(filename,binary?undefined:"utf8",(err,data)=>{if(err)reject(err);else resolve(binary?data.buffer:data)})})};if(!Module["thisProgram"]&&process.argv.length>1){thisProgram=process.argv[1].replace(/\\/g,"/")}arguments_=process.argv.slice(2);if(typeof module!="undefined"){module["exports"]=Module}process.on("uncaughtException",ex=>{if(ex!=="unwind"&&!(ex instanceof ExitStatus)&&!(ex.context instanceof ExitStatus)){throw ex}});quit_=(status,toThrow)=>{process.exitCode=status;throw toThrow}}else if(ENVIRONMENT_IS_WEB||ENVIRONMENT_IS_WORKER){if(ENVIRONMENT_IS_WORKER){scriptDirectory=self.location.href}else if(typeof document!="undefined"&&document.currentScript){scriptDirectory=document.currentScript.src}if(scriptDirectory.startsWith("blob:")){scriptDirectory=""}else{scriptDirectory=scriptDirectory.substr(0,scriptDirectory.replace(/[?#].*/,"").lastIndexOf("/")+1)}{if(ENVIRONMENT_IS_WORKER){readBinary=url=>{var xhr=new XMLHttpRequest;xhr.open("GET",url,false);xhr.responseType="arraybuffer";xhr.send(null);return new Uint8Array(xhr.response)}}readAsync=url=>{if(isFileURI(url)){return new Promise((reject,resolve)=>{var xhr=new XMLHttpRequest;xhr.open("GET",url,true);xhr.responseType="arraybuffer";xhr.onload=()=>{if(xhr.status==200||xhr.status==0&&xhr.response){resolve(xhr.response)}reject(xhr.status)};xhr.onerror=reject;xhr.send(null)})}return fetch(url,{credentials:"same-origin"}).then(response=>{if(response.ok){return response.arrayBuffer()}return Promise.reject(new Error(response.status+" : "+response.url))})}}}else{}var out=Module["print"]||console.log.bind(console);var err=Module["printErr"]||console.error.bind(console);Object.assign(Module,moduleOverrides);moduleOverrides=null;if(Module["arguments"])arguments_=Module["arguments"];if(Module["thisProgram"])thisProgram=Module["thisProgram"];if(Module["quit"])quit_=Module["quit"];var wasmBinary;if(Module["wasmBinary"])wasmBinary=Module["wasmBinary"];var wasmMemory;var ABORT=false;var EXITSTATUS;var HEAP8,HEAPU8,HEAP16,HEAPU16,HEAP32,HEAPU32,HEAPF32,HEAPF64;function updateMemoryViews(){var b=wasmMemory.buffer;Module["HEAP8"]=HEAP8=new Int8Array(b);Module["HEAP16"]=HEAP16=new Int16Array(b);Module["HEAPU8"]=HEAPU8=new Uint8Array(b);Module["HEAPU16"]=HEAPU16=new Uint16Array(b);Module["HEAP32"]=HEAP32=new Int32Array(b);Module["HEAPU32"]=HEAPU32=new Uint32Array(b);Module["HEAPF32"]=HEAPF32=new Float32Array(b);Module["HEAPF64"]=HEAPF64=new Float64Array(b)}var __ATPRERUN__=[];var __ATINIT__=[];var __ATPOSTRUN__=[];var runtimeInitialized=false;function preRun(){if(Module["preRun"]){if(typeof Module["preRun"]=="function")Module["preRun"]=[Module["preRun"]];while(Module["preRun"].length){addOnPreRun(Module["preRun"].shift())}}callRuntimeCallbacks(__ATPRERUN__)}function initRuntime(){runtimeInitialized=true;callRuntimeCallbacks(__ATINIT__)}function postRun(){if(Module["postRun"]){if(typeof Module["postRun"]=="function")Module["postRun"]=[Module["postRun"]];while(Module["postRun"].length){addOnPostRun(Module["postRun"].shift())}}callRuntimeCallbacks(__ATPOSTRUN__)}function addOnPreRun(cb){__ATPRERUN__.unshift(cb)}function addOnInit(cb){__ATINIT__.unshift(cb)}function addOnPostRun(cb){__ATPOSTRUN__.unshift(cb)}var runDependencies=0;var runDependencyWatcher=null;var dependenciesFulfilled=null;function addRunDependency(id){runDependencies++;Module["monitorRunDependencies"]?.(runDependencies)}function removeRunDependency(id){runDependencies--;Module["monitorRunDependencies"]?.(runDependencies);if(runDependencies==0){if(runDependencyWatcher!==null){clearInterval(runDependencyWatcher);runDependencyWatcher=null}if(dependenciesFulfilled){var callback=dependenciesFulfilled;dependenciesFulfilled=null;callback()}}}function abort(what){Module["onAbort"]?.(what);what="Aborted("+what+")";err(what);ABORT=true;EXITSTATUS=1;what+=". Build with -sASSERTIONS for more info.";var e=new WebAssembly.RuntimeError(what);throw e}var dataURIPrefix="data:application/octet-stream;base64,";var isDataURI=filename=>filename.startsWith(dataURIPrefix);var isFileURI=filename=>filename.startsWith("file://");function findWasmBinary(){var f="index.wasm";if(!isDataURI(f)){return locateFile(f)}return f}var wasmBinaryFile;function getBinarySync(file){if(file==wasmBinaryFile&&wasmBinary){return new Uint8Array(wasmBinary)}if(readBinary){return readBinary(file)}throw"both async and sync fetching of the wasm failed"}function getBinaryPromise(binaryFile){if(!wasmBinary){return readAsync(binaryFile).then(response=>new Uint8Array(response),()=>getBinarySync(binaryFile))}return Promise.resolve().then(()=>getBinarySync(binaryFile))}function instantiateArrayBuffer(binaryFile,imports,receiver){return getBinaryPromise(binaryFile).then(binary=>WebAssembly.instantiate(binary,imports)).then(receiver,reason=>{err(`failed to asynchronously prepare wasm: ${reason}`);abort(reason)})}function instantiateAsync(binary,binaryFile,imports,callback){if(!binary&&typeof WebAssembly.instantiateStreaming=="function"&&!isDataURI(binaryFile)&&!isFileURI(binaryFile)&&!ENVIRONMENT_IS_NODE&&typeof fetch=="function"){return fetch(binaryFile,{credentials:"same-origin"}).then(response=>{var result=WebAssembly.instantiateStreaming(response,imports);return result.then(callback,function(reason){err(`wasm streaming compile failed: ${reason}`);err("falling back to ArrayBuffer instantiation");return instantiateArrayBuffer(binaryFile,imports,callback)})})}return instantiateArrayBuffer(binaryFile,imports,callback)}function getWasmImports(){return{a:wasmImports}}function createWasm(){var info=getWasmImports();function receiveInstance(instance,module){wasmExports=instance.exports;wasmMemory=wasmExports["w"];updateMemoryViews();wasmTable=wasmExports["C"];addOnInit(wasmExports["x"]);removeRunDependency("wasm-instantiate");return wasmExports}addRunDependency("wasm-instantiate");function receiveInstantiationResult(result){receiveInstance(result["instance"])}if(Module["instantiateWasm"]){try{return Module["instantiateWasm"](info,receiveInstance)}catch(e){err(`Module.instantiateWasm callback failed with error: ${e}`);return false}}if(!wasmBinaryFile)wasmBinaryFile=findWasmBinary();instantiateAsync(wasmBinary,wasmBinaryFile,info,receiveInstantiationResult);return{}}function ExitStatus(status){this.name="ExitStatus";this.message=`Program terminated with exit(${status})`;this.status=status}var callRuntimeCallbacks=callbacks=>{while(callbacks.length>0){callbacks.shift()(Module)}};var noExitRuntime=Module["noExitRuntime"]||true;class ExceptionInfo{constructor(excPtr){this.excPtr=excPtr;this.ptr=excPtr-24}set_type(type){HEAPU32[this.ptr+4>>2]=type}get_type(){return HEAPU32[this.ptr+4>>2]}set_destructor(destructor){HEAPU32[this.ptr+8>>2]=destructor}get_destructor(){return HEAPU32[this.ptr+8>>2]}set_caught(caught){caught=caught?1:0;HEAP8[this.ptr+12]=caught}get_caught(){return HEAP8[this.ptr+12]!=0}set_rethrown(rethrown){rethrown=rethrown?1:0;HEAP8[this.ptr+13]=rethrown}get_rethrown(){return HEAP8[this.ptr+13]!=0}init(type,destructor){this.set_adjusted_ptr(0);this.set_type(type);this.set_destructor(destructor)}set_adjusted_ptr(adjustedPtr){HEAPU32[this.ptr+16>>2]=adjustedPtr}get_adjusted_ptr(){return HEAPU32[this.ptr+16>>2]}get_exception_ptr(){var isPointer=___cxa_is_pointer_type(this.get_type());if(isPointer){return HEAPU32[this.excPtr>>2]}var adjusted=this.get_adjusted_ptr();if(adjusted!==0)return adjusted;return this.excPtr}}var exceptionLast=0;var uncaughtExceptionCount=0;var ___cxa_throw=(ptr,type,destructor)=>{var info=new ExceptionInfo(ptr);info.init(type,destructor);exceptionLast=ptr;uncaughtExceptionCount++;throw exceptionLast};var __abort_js=()=>{abort("")};var __embind_register_bigint=(primitiveType,name,size,minRange,maxRange)=>{};var embind_init_charCodes=()=>{var codes=new Array(256);for(var i=0;i<256;++i){codes[i]=String.fromCharCode(i)}embind_charCodes=codes};var embind_charCodes;var readLatin1String=ptr=>{var ret="";var c=ptr;while(HEAPU8[c]){ret+=embind_charCodes[HEAPU8[c++]]}return ret};var awaitingDependencies={};var registeredTypes={};var typeDependencies={};var BindingError;var throwBindingError=message=>{throw new BindingError(message)};var InternalError;var throwInternalError=message=>{throw new InternalError(message)};var whenDependentTypesAreResolved=(myTypes,dependentTypes,getTypeConverters)=>{myTypes.forEach(function(type){typeDependencies[type]=dependentTypes});function onComplete(typeConverters){var myTypeConverters=getTypeConverters(typeConverters);if(myTypeConverters.length!==myTypes.length){throwInternalError("Mismatched type converter count")}for(var i=0;i{if(registeredTypes.hasOwnProperty(dt)){typeConverters[i]=registeredTypes[dt]}else{unregisteredTypes.push(dt);if(!awaitingDependencies.hasOwnProperty(dt)){awaitingDependencies[dt]=[]}awaitingDependencies[dt].push(()=>{typeConverters[i]=registeredTypes[dt];++registered;if(registered===unregisteredTypes.length){onComplete(typeConverters)}})}});if(0===unregisteredTypes.length){onComplete(typeConverters)}};function sharedRegisterType(rawType,registeredInstance,options={}){var name=registeredInstance.name;if(!rawType){throwBindingError(`type "${name}" must have a positive integer typeid pointer`)}if(registeredTypes.hasOwnProperty(rawType)){if(options.ignoreDuplicateRegistrations){return}else{throwBindingError(`Cannot register type '${name}' twice`)}}registeredTypes[rawType]=registeredInstance;delete typeDependencies[rawType];if(awaitingDependencies.hasOwnProperty(rawType)){var callbacks=awaitingDependencies[rawType];delete awaitingDependencies[rawType];callbacks.forEach(cb=>cb())}}function registerType(rawType,registeredInstance,options={}){if(!("argPackAdvance"in registeredInstance)){throw new TypeError("registerType registeredInstance requires argPackAdvance")}return sharedRegisterType(rawType,registeredInstance,options)}var GenericWireTypeSize=8;var __embind_register_bool=(rawType,name,trueValue,falseValue)=>{name=readLatin1String(name);registerType(rawType,{name:name,fromWireType:function(wt){return!!wt},toWireType:function(destructors,o){return o?trueValue:falseValue},argPackAdvance:GenericWireTypeSize,readValueFromPointer:function(pointer){return this["fromWireType"](HEAPU8[pointer])},destructorFunction:null})};var shallowCopyInternalPointer=o=>({count:o.count,deleteScheduled:o.deleteScheduled,preservePointerOnDelete:o.preservePointerOnDelete,ptr:o.ptr,ptrType:o.ptrType,smartPtr:o.smartPtr,smartPtrType:o.smartPtrType});var throwInstanceAlreadyDeleted=obj=>{function getInstanceTypeName(handle){return handle.$$.ptrType.registeredClass.name}throwBindingError(getInstanceTypeName(obj)+" instance already deleted")};var finalizationRegistry=false;var detachFinalizer=handle=>{};var runDestructor=$$=>{if($$.smartPtr){$$.smartPtrType.rawDestructor($$.smartPtr)}else{$$.ptrType.registeredClass.rawDestructor($$.ptr)}};var releaseClassHandle=$$=>{$$.count.value-=1;var toDelete=0===$$.count.value;if(toDelete){runDestructor($$)}};var downcastPointer=(ptr,ptrClass,desiredClass)=>{if(ptrClass===desiredClass){return ptr}if(undefined===desiredClass.baseClass){return null}var rv=downcastPointer(ptr,ptrClass,desiredClass.baseClass);if(rv===null){return null}return desiredClass.downcast(rv)};var registeredPointers={};var getInheritedInstanceCount=()=>Object.keys(registeredInstances).length;var getLiveInheritedInstances=()=>{var rv=[];for(var k in registeredInstances){if(registeredInstances.hasOwnProperty(k)){rv.push(registeredInstances[k])}}return rv};var deletionQueue=[];var flushPendingDeletes=()=>{while(deletionQueue.length){var obj=deletionQueue.pop();obj.$$.deleteScheduled=false;obj["delete"]()}};var delayFunction;var setDelayFunction=fn=>{delayFunction=fn;if(deletionQueue.length&&delayFunction){delayFunction(flushPendingDeletes)}};var init_embind=()=>{Module["getInheritedInstanceCount"]=getInheritedInstanceCount;Module["getLiveInheritedInstances"]=getLiveInheritedInstances;Module["flushPendingDeletes"]=flushPendingDeletes;Module["setDelayFunction"]=setDelayFunction};var registeredInstances={};var getBasestPointer=(class_,ptr)=>{if(ptr===undefined){throwBindingError("ptr should not be undefined")}while(class_.baseClass){ptr=class_.upcast(ptr);class_=class_.baseClass}return ptr};var getInheritedInstance=(class_,ptr)=>{ptr=getBasestPointer(class_,ptr);return registeredInstances[ptr]};var makeClassHandle=(prototype,record)=>{if(!record.ptrType||!record.ptr){throwInternalError("makeClassHandle requires ptr and ptrType")}var hasSmartPtrType=!!record.smartPtrType;var hasSmartPtr=!!record.smartPtr;if(hasSmartPtrType!==hasSmartPtr){throwInternalError("Both smartPtrType and smartPtr must be specified")}record.count={value:1};return attachFinalizer(Object.create(prototype,{$$:{value:record,writable:true}}))};function RegisteredPointer_fromWireType(ptr){var rawPointer=this.getPointee(ptr);if(!rawPointer){this.destructor(ptr);return null}var registeredInstance=getInheritedInstance(this.registeredClass,rawPointer);if(undefined!==registeredInstance){if(0===registeredInstance.$$.count.value){registeredInstance.$$.ptr=rawPointer;registeredInstance.$$.smartPtr=ptr;return registeredInstance["clone"]()}else{var rv=registeredInstance["clone"]();this.destructor(ptr);return rv}}function makeDefaultHandle(){if(this.isSmartPointer){return makeClassHandle(this.registeredClass.instancePrototype,{ptrType:this.pointeeType,ptr:rawPointer,smartPtrType:this,smartPtr:ptr})}else{return makeClassHandle(this.registeredClass.instancePrototype,{ptrType:this,ptr:ptr})}}var actualType=this.registeredClass.getActualType(rawPointer);var registeredPointerRecord=registeredPointers[actualType];if(!registeredPointerRecord){return makeDefaultHandle.call(this)}var toType;if(this.isConst){toType=registeredPointerRecord.constPointerType}else{toType=registeredPointerRecord.pointerType}var dp=downcastPointer(rawPointer,this.registeredClass,toType.registeredClass);if(dp===null){return makeDefaultHandle.call(this)}if(this.isSmartPointer){return makeClassHandle(toType.registeredClass.instancePrototype,{ptrType:toType,ptr:dp,smartPtrType:this,smartPtr:ptr})}else{return makeClassHandle(toType.registeredClass.instancePrototype,{ptrType:toType,ptr:dp})}}var attachFinalizer=handle=>{if("undefined"===typeof FinalizationRegistry){attachFinalizer=handle=>handle;return handle}finalizationRegistry=new FinalizationRegistry(info=>{releaseClassHandle(info.$$)});attachFinalizer=handle=>{var $$=handle.$$;var hasSmartPtr=!!$$.smartPtr;if(hasSmartPtr){var info={$$:$$};finalizationRegistry.register(handle,info,handle)}return handle};detachFinalizer=handle=>finalizationRegistry.unregister(handle);return attachFinalizer(handle)};var init_ClassHandle=()=>{Object.assign(ClassHandle.prototype,{isAliasOf(other){if(!(this instanceof ClassHandle)){return false}if(!(other instanceof ClassHandle)){return false}var leftClass=this.$$.ptrType.registeredClass;var left=this.$$.ptr;other.$$=other.$$;var rightClass=other.$$.ptrType.registeredClass;var right=other.$$.ptr;while(leftClass.baseClass){left=leftClass.upcast(left);leftClass=leftClass.baseClass}while(rightClass.baseClass){right=rightClass.upcast(right);rightClass=rightClass.baseClass}return leftClass===rightClass&&left===right},clone(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.preservePointerOnDelete){this.$$.count.value+=1;return this}else{var clone=attachFinalizer(Object.create(Object.getPrototypeOf(this),{$$:{value:shallowCopyInternalPointer(this.$$)}}));clone.$$.count.value+=1;clone.$$.deleteScheduled=false;return clone}},delete(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.deleteScheduled&&!this.$$.preservePointerOnDelete){throwBindingError("Object already scheduled for deletion")}detachFinalizer(this);releaseClassHandle(this.$$);if(!this.$$.preservePointerOnDelete){this.$$.smartPtr=undefined;this.$$.ptr=undefined}},isDeleted(){return!this.$$.ptr},deleteLater(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.deleteScheduled&&!this.$$.preservePointerOnDelete){throwBindingError("Object already scheduled for deletion")}deletionQueue.push(this);if(deletionQueue.length===1&&delayFunction){delayFunction(flushPendingDeletes)}this.$$.deleteScheduled=true;return this}})};function ClassHandle(){}var createNamedFunction=(name,body)=>Object.defineProperty(body,"name",{value:name});var ensureOverloadTable=(proto,methodName,humanName)=>{if(undefined===proto[methodName].overloadTable){var prevFunc=proto[methodName];proto[methodName]=function(...args){if(!proto[methodName].overloadTable.hasOwnProperty(args.length)){throwBindingError(`Function '${humanName}' called with an invalid number of arguments (${args.length}) - expects one of (${proto[methodName].overloadTable})!`)}return proto[methodName].overloadTable[args.length].apply(this,args)};proto[methodName].overloadTable=[];proto[methodName].overloadTable[prevFunc.argCount]=prevFunc}};var exposePublicSymbol=(name,value,numArguments)=>{if(Module.hasOwnProperty(name)){if(undefined===numArguments||undefined!==Module[name].overloadTable&&undefined!==Module[name].overloadTable[numArguments]){throwBindingError(`Cannot register public name '${name}' twice`)}ensureOverloadTable(Module,name,name);if(Module.hasOwnProperty(numArguments)){throwBindingError(`Cannot register multiple overloads of a function with the same number of arguments (${numArguments})!`)}Module[name].overloadTable[numArguments]=value}else{Module[name]=value;if(undefined!==numArguments){Module[name].numArguments=numArguments}}};var char_0=48;var char_9=57;var makeLegalFunctionName=name=>{if(undefined===name){return"_unknown"}name=name.replace(/[^a-zA-Z0-9_]/g,"$");var f=name.charCodeAt(0);if(f>=char_0&&f<=char_9){return`_${name}`}return name};function RegisteredClass(name,constructor,instancePrototype,rawDestructor,baseClass,getActualType,upcast,downcast){this.name=name;this.constructor=constructor;this.instancePrototype=instancePrototype;this.rawDestructor=rawDestructor;this.baseClass=baseClass;this.getActualType=getActualType;this.upcast=upcast;this.downcast=downcast;this.pureVirtualFunctions=[]}var upcastPointer=(ptr,ptrClass,desiredClass)=>{while(ptrClass!==desiredClass){if(!ptrClass.upcast){throwBindingError(`Expected null or instance of ${desiredClass.name}, got an instance of ${ptrClass.name}`)}ptr=ptrClass.upcast(ptr);ptrClass=ptrClass.baseClass}return ptr};function constNoSmartPtrRawPointerToWireType(destructors,handle){if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}return 0}if(!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;var ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);return ptr}function genericPointerToWireType(destructors,handle){var ptr;if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}if(this.isSmartPointer){ptr=this.rawConstructor();if(destructors!==null){destructors.push(this.rawDestructor,ptr)}return ptr}else{return 0}}if(!handle||!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}if(!this.isConst&&handle.$$.ptrType.isConst){throwBindingError(`Cannot convert argument of type ${handle.$$.smartPtrType?handle.$$.smartPtrType.name:handle.$$.ptrType.name} to parameter type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);if(this.isSmartPointer){if(undefined===handle.$$.smartPtr){throwBindingError("Passing raw pointer to smart pointer is illegal")}switch(this.sharingPolicy){case 0:if(handle.$$.smartPtrType===this){ptr=handle.$$.smartPtr}else{throwBindingError(`Cannot convert argument of type ${handle.$$.smartPtrType?handle.$$.smartPtrType.name:handle.$$.ptrType.name} to parameter type ${this.name}`)}break;case 1:ptr=handle.$$.smartPtr;break;case 2:if(handle.$$.smartPtrType===this){ptr=handle.$$.smartPtr}else{var clonedHandle=handle["clone"]();ptr=this.rawShare(ptr,Emval.toHandle(()=>clonedHandle["delete"]()));if(destructors!==null){destructors.push(this.rawDestructor,ptr)}}break;default:throwBindingError("Unsupporting sharing policy")}}return ptr}function nonConstNoSmartPtrRawPointerToWireType(destructors,handle){if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}return 0}if(!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}if(handle.$$.ptrType.isConst){throwBindingError(`Cannot convert argument of type ${handle.$$.ptrType.name} to parameter type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;var ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);return ptr}function readPointer(pointer){return this["fromWireType"](HEAPU32[pointer>>2])}var init_RegisteredPointer=()=>{Object.assign(RegisteredPointer.prototype,{getPointee(ptr){if(this.rawGetPointee){ptr=this.rawGetPointee(ptr)}return ptr},destructor(ptr){this.rawDestructor?.(ptr)},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,fromWireType:RegisteredPointer_fromWireType})};function RegisteredPointer(name,registeredClass,isReference,isConst,isSmartPointer,pointeeType,sharingPolicy,rawGetPointee,rawConstructor,rawShare,rawDestructor){this.name=name;this.registeredClass=registeredClass;this.isReference=isReference;this.isConst=isConst;this.isSmartPointer=isSmartPointer;this.pointeeType=pointeeType;this.sharingPolicy=sharingPolicy;this.rawGetPointee=rawGetPointee;this.rawConstructor=rawConstructor;this.rawShare=rawShare;this.rawDestructor=rawDestructor;if(!isSmartPointer&®isteredClass.baseClass===undefined){if(isConst){this["toWireType"]=constNoSmartPtrRawPointerToWireType;this.destructorFunction=null}else{this["toWireType"]=nonConstNoSmartPtrRawPointerToWireType;this.destructorFunction=null}}else{this["toWireType"]=genericPointerToWireType}}var replacePublicSymbol=(name,value,numArguments)=>{if(!Module.hasOwnProperty(name)){throwInternalError("Replacing nonexistent public symbol")}if(undefined!==Module[name].overloadTable&&undefined!==numArguments){Module[name].overloadTable[numArguments]=value}else{Module[name]=value;Module[name].argCount=numArguments}};var dynCallLegacy=(sig,ptr,args)=>{sig=sig.replace(/p/g,"i");var f=Module["dynCall_"+sig];return f(ptr,...args)};var wasmTableMirror=[];var wasmTable;var getWasmTableEntry=funcPtr=>{var func=wasmTableMirror[funcPtr];if(!func){if(funcPtr>=wasmTableMirror.length)wasmTableMirror.length=funcPtr+1;wasmTableMirror[funcPtr]=func=wasmTable.get(funcPtr)}return func};var dynCall=(sig,ptr,args=[])=>{if(sig.includes("j")){return dynCallLegacy(sig,ptr,args)}var rtn=getWasmTableEntry(ptr)(...args);return rtn};var getDynCaller=(sig,ptr)=>(...args)=>dynCall(sig,ptr,args);var embind__requireFunction=(signature,rawFunction)=>{signature=readLatin1String(signature);function makeDynCaller(){if(signature.includes("j")){return getDynCaller(signature,rawFunction)}return getWasmTableEntry(rawFunction)}var fp=makeDynCaller();if(typeof fp!="function"){throwBindingError(`unknown function pointer with signature ${signature}: ${rawFunction}`)}return fp};var extendError=(baseErrorType,errorName)=>{var errorClass=createNamedFunction(errorName,function(message){this.name=errorName;this.message=message;var stack=new Error(message).stack;if(stack!==undefined){this.stack=this.toString()+"\n"+stack.replace(/^Error(:[^\n]*)?\n/,"")}});errorClass.prototype=Object.create(baseErrorType.prototype);errorClass.prototype.constructor=errorClass;errorClass.prototype.toString=function(){if(this.message===undefined){return this.name}else{return`${this.name}: ${this.message}`}};return errorClass};var UnboundTypeError;var getTypeName=type=>{var ptr=___getTypeName(type);var rv=readLatin1String(ptr);_free(ptr);return rv};var throwUnboundTypeError=(message,types)=>{var unboundTypes=[];var seen={};function visit(type){if(seen[type]){return}if(registeredTypes[type]){return}if(typeDependencies[type]){typeDependencies[type].forEach(visit);return}unboundTypes.push(type);seen[type]=true}types.forEach(visit);throw new UnboundTypeError(`${message}: `+unboundTypes.map(getTypeName).join([", "]))};var __embind_register_class=(rawType,rawPointerType,rawConstPointerType,baseClassRawType,getActualTypeSignature,getActualType,upcastSignature,upcast,downcastSignature,downcast,name,destructorSignature,rawDestructor)=>{name=readLatin1String(name);getActualType=embind__requireFunction(getActualTypeSignature,getActualType);upcast&&=embind__requireFunction(upcastSignature,upcast);downcast&&=embind__requireFunction(downcastSignature,downcast);rawDestructor=embind__requireFunction(destructorSignature,rawDestructor);var legalFunctionName=makeLegalFunctionName(name);exposePublicSymbol(legalFunctionName,function(){throwUnboundTypeError(`Cannot construct ${name} due to unbound types`,[baseClassRawType])});whenDependentTypesAreResolved([rawType,rawPointerType,rawConstPointerType],baseClassRawType?[baseClassRawType]:[],base=>{base=base[0];var baseClass;var basePrototype;if(baseClassRawType){baseClass=base.registeredClass;basePrototype=baseClass.instancePrototype}else{basePrototype=ClassHandle.prototype}var constructor=createNamedFunction(name,function(...args){if(Object.getPrototypeOf(this)!==instancePrototype){throw new BindingError("Use 'new' to construct "+name)}if(undefined===registeredClass.constructor_body){throw new BindingError(name+" has no accessible constructor")}var body=registeredClass.constructor_body[args.length];if(undefined===body){throw new BindingError(`Tried to invoke ctor of ${name} with invalid number of parameters (${args.length}) - expected (${Object.keys(registeredClass.constructor_body).toString()}) parameters instead!`)}return body.apply(this,args)});var instancePrototype=Object.create(basePrototype,{constructor:{value:constructor}});constructor.prototype=instancePrototype;var registeredClass=new RegisteredClass(name,constructor,instancePrototype,rawDestructor,baseClass,getActualType,upcast,downcast);if(registeredClass.baseClass){registeredClass.baseClass.__derivedClasses??=[];registeredClass.baseClass.__derivedClasses.push(registeredClass)}var referenceConverter=new RegisteredPointer(name,registeredClass,true,false,false);var pointerConverter=new RegisteredPointer(name+"*",registeredClass,false,false,false);var constPointerConverter=new RegisteredPointer(name+" const*",registeredClass,false,true,false);registeredPointers[rawType]={pointerType:pointerConverter,constPointerType:constPointerConverter};replacePublicSymbol(legalFunctionName,constructor);return[referenceConverter,pointerConverter,constPointerConverter]})};var heap32VectorToArray=(count,firstElement)=>{var array=[];for(var i=0;i>2])}return array};var runDestructors=destructors=>{while(destructors.length){var ptr=destructors.pop();var del=destructors.pop();del(ptr)}};function usesDestructorStack(argTypes){for(var i=1;i0?", ":"")+argsListWired}invokerFnBody+=(returns||isAsync?"var rv = ":"")+"invoker(fn"+(argsListWired.length>0?", ":"")+argsListWired+");\n";if(needsDestructorStack){invokerFnBody+="runDestructors(destructors);\n"}else{for(var i=isClassMethodFunc?1:2;i{var rawArgTypes=heap32VectorToArray(argCount,rawArgTypesAddr);invoker=embind__requireFunction(invokerSignature,invoker);whenDependentTypesAreResolved([],[rawClassType],classType=>{classType=classType[0];var humanName=`constructor ${classType.name}`;if(undefined===classType.registeredClass.constructor_body){classType.registeredClass.constructor_body=[]}if(undefined!==classType.registeredClass.constructor_body[argCount-1]){throw new BindingError(`Cannot register multiple constructors with identical number of parameters (${argCount-1}) for class '${classType.name}'! Overload resolution is currently only performed using the parameter count, not actual type info!`)}classType.registeredClass.constructor_body[argCount-1]=()=>{throwUnboundTypeError(`Cannot construct ${classType.name} due to unbound types`,rawArgTypes)};whenDependentTypesAreResolved([],rawArgTypes,argTypes=>{argTypes.splice(1,0,null);classType.registeredClass.constructor_body[argCount-1]=craftInvokerFunction(humanName,argTypes,null,invoker,rawConstructor);return[]});return[]})};var getFunctionName=signature=>{signature=signature.trim();const argsIndex=signature.indexOf("(");if(argsIndex!==-1){return signature.substr(0,argsIndex)}else{return signature}};var __embind_register_class_function=(rawClassType,methodName,argCount,rawArgTypesAddr,invokerSignature,rawInvoker,context,isPureVirtual,isAsync)=>{var rawArgTypes=heap32VectorToArray(argCount,rawArgTypesAddr);methodName=readLatin1String(methodName);methodName=getFunctionName(methodName);rawInvoker=embind__requireFunction(invokerSignature,rawInvoker);whenDependentTypesAreResolved([],[rawClassType],classType=>{classType=classType[0];var humanName=`${classType.name}.${methodName}`;if(methodName.startsWith("@@")){methodName=Symbol[methodName.substring(2)]}if(isPureVirtual){classType.registeredClass.pureVirtualFunctions.push(methodName)}function unboundTypesHandler(){throwUnboundTypeError(`Cannot call ${humanName} due to unbound types`,rawArgTypes)}var proto=classType.registeredClass.instancePrototype;var method=proto[methodName];if(undefined===method||undefined===method.overloadTable&&method.className!==classType.name&&method.argCount===argCount-2){unboundTypesHandler.argCount=argCount-2;unboundTypesHandler.className=classType.name;proto[methodName]=unboundTypesHandler}else{ensureOverloadTable(proto,methodName,humanName);proto[methodName].overloadTable[argCount-2]=unboundTypesHandler}whenDependentTypesAreResolved([],rawArgTypes,argTypes=>{var memberFunction=craftInvokerFunction(humanName,argTypes,classType,rawInvoker,context,isAsync);if(undefined===proto[methodName].overloadTable){memberFunction.argCount=argCount-2;proto[methodName]=memberFunction}else{proto[methodName].overloadTable[argCount-2]=memberFunction}return[]});return[]})};var validateThis=(this_,classType,humanName)=>{if(!(this_ instanceof Object)){throwBindingError(`${humanName} with invalid "this": ${this_}`)}if(!(this_ instanceof classType.registeredClass.constructor)){throwBindingError(`${humanName} incompatible with "this" of type ${this_.constructor.name}`)}if(!this_.$$.ptr){throwBindingError(`cannot call emscripten binding method ${humanName} on deleted object`)}return upcastPointer(this_.$$.ptr,this_.$$.ptrType.registeredClass,classType.registeredClass)};var __embind_register_class_property=(classType,fieldName,getterReturnType,getterSignature,getter,getterContext,setterArgumentType,setterSignature,setter,setterContext)=>{fieldName=readLatin1String(fieldName);getter=embind__requireFunction(getterSignature,getter);whenDependentTypesAreResolved([],[classType],classType=>{classType=classType[0];var humanName=`${classType.name}.${fieldName}`;var desc={get(){throwUnboundTypeError(`Cannot access ${humanName} due to unbound types`,[getterReturnType,setterArgumentType])},enumerable:true,configurable:true};if(setter){desc.set=()=>throwUnboundTypeError(`Cannot access ${humanName} due to unbound types`,[getterReturnType,setterArgumentType])}else{desc.set=v=>throwBindingError(humanName+" is a read-only property")}Object.defineProperty(classType.registeredClass.instancePrototype,fieldName,desc);whenDependentTypesAreResolved([],setter?[getterReturnType,setterArgumentType]:[getterReturnType],types=>{var getterReturnType=types[0];var desc={get(){var ptr=validateThis(this,classType,humanName+" getter");return getterReturnType["fromWireType"](getter(getterContext,ptr))},enumerable:true};if(setter){setter=embind__requireFunction(setterSignature,setter);var setterArgumentType=types[1];desc.set=function(v){var ptr=validateThis(this,classType,humanName+" setter");var destructors=[];setter(setterContext,ptr,setterArgumentType["toWireType"](destructors,v));runDestructors(destructors)}}Object.defineProperty(classType.registeredClass.instancePrototype,fieldName,desc);return[]});return[]})};var emval_freelist=[];var emval_handles=[];var __emval_decref=handle=>{if(handle>9&&0===--emval_handles[handle+1]){emval_handles[handle]=undefined;emval_freelist.push(handle)}};var count_emval_handles=()=>emval_handles.length/2-5-emval_freelist.length;var init_emval=()=>{emval_handles.push(0,1,undefined,1,null,1,true,1,false,1);Module["count_emval_handles"]=count_emval_handles};var Emval={toValue:handle=>{if(!handle){throwBindingError("Cannot use deleted val. handle = "+handle)}return emval_handles[handle]},toHandle:value=>{switch(value){case undefined:return 2;case null:return 4;case true:return 6;case false:return 8;default:{const handle=emval_freelist.pop()||emval_handles.length;emval_handles[handle]=value;emval_handles[handle+1]=1;return handle}}}};var EmValType={name:"emscripten::val",fromWireType:handle=>{var rv=Emval.toValue(handle);__emval_decref(handle);return rv},toWireType:(destructors,value)=>Emval.toHandle(value),argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction:null};var __embind_register_emval=rawType=>registerType(rawType,EmValType);var embindRepr=v=>{if(v===null){return"null"}var t=typeof v;if(t==="object"||t==="array"||t==="function"){return v.toString()}else{return""+v}};var floatReadValueFromPointer=(name,width)=>{switch(width){case 4:return function(pointer){return this["fromWireType"](HEAPF32[pointer>>2])};case 8:return function(pointer){return this["fromWireType"](HEAPF64[pointer>>3])};default:throw new TypeError(`invalid float width (${width}): ${name}`)}};var __embind_register_float=(rawType,name,size)=>{name=readLatin1String(name);registerType(rawType,{name:name,fromWireType:value=>value,toWireType:(destructors,value)=>value,argPackAdvance:GenericWireTypeSize,readValueFromPointer:floatReadValueFromPointer(name,size),destructorFunction:null})};var __embind_register_function=(name,argCount,rawArgTypesAddr,signature,rawInvoker,fn,isAsync)=>{var argTypes=heap32VectorToArray(argCount,rawArgTypesAddr);name=readLatin1String(name);name=getFunctionName(name);rawInvoker=embind__requireFunction(signature,rawInvoker);exposePublicSymbol(name,function(){throwUnboundTypeError(`Cannot call ${name} due to unbound types`,argTypes)},argCount-1);whenDependentTypesAreResolved([],argTypes,argTypes=>{var invokerArgsArray=[argTypes[0],null].concat(argTypes.slice(1));replacePublicSymbol(name,craftInvokerFunction(name,invokerArgsArray,null,rawInvoker,fn,isAsync),argCount-1);return[]})};var integerReadValueFromPointer=(name,width,signed)=>{switch(width){case 1:return signed?pointer=>HEAP8[pointer]:pointer=>HEAPU8[pointer];case 2:return signed?pointer=>HEAP16[pointer>>1]:pointer=>HEAPU16[pointer>>1];case 4:return signed?pointer=>HEAP32[pointer>>2]:pointer=>HEAPU32[pointer>>2];default:throw new TypeError(`invalid integer width (${width}): ${name}`)}};var __embind_register_integer=(primitiveType,name,size,minRange,maxRange)=>{name=readLatin1String(name);if(maxRange===-1){maxRange=4294967295}var fromWireType=value=>value;if(minRange===0){var bitshift=32-8*size;fromWireType=value=>value<>>bitshift}var isUnsignedType=name.includes("unsigned");var checkAssertions=(value,toTypeName)=>{};var toWireType;if(isUnsignedType){toWireType=function(destructors,value){checkAssertions(value,this.name);return value>>>0}}else{toWireType=function(destructors,value){checkAssertions(value,this.name);return value}}registerType(primitiveType,{name:name,fromWireType:fromWireType,toWireType:toWireType,argPackAdvance:GenericWireTypeSize,readValueFromPointer:integerReadValueFromPointer(name,size,minRange!==0),destructorFunction:null})};var __embind_register_memory_view=(rawType,dataTypeIndex,name)=>{var typeMapping=[Int8Array,Uint8Array,Int16Array,Uint16Array,Int32Array,Uint32Array,Float32Array,Float64Array];var TA=typeMapping[dataTypeIndex];function decodeMemoryView(handle){var size=HEAPU32[handle>>2];var data=HEAPU32[handle+4>>2];return new TA(HEAP8.buffer,data,size)}name=readLatin1String(name);registerType(rawType,{name:name,fromWireType:decodeMemoryView,argPackAdvance:GenericWireTypeSize,readValueFromPointer:decodeMemoryView},{ignoreDuplicateRegistrations:true})};var __embind_register_optional=(rawOptionalType,rawType)=>{__embind_register_emval(rawOptionalType)};var stringToUTF8Array=(str,heap,outIdx,maxBytesToWrite)=>{if(!(maxBytesToWrite>0))return 0;var startIdx=outIdx;var endIdx=outIdx+maxBytesToWrite-1;for(var i=0;i=55296&&u<=57343){var u1=str.charCodeAt(++i);u=65536+((u&1023)<<10)|u1&1023}if(u<=127){if(outIdx>=endIdx)break;heap[outIdx++]=u}else if(u<=2047){if(outIdx+1>=endIdx)break;heap[outIdx++]=192|u>>6;heap[outIdx++]=128|u&63}else if(u<=65535){if(outIdx+2>=endIdx)break;heap[outIdx++]=224|u>>12;heap[outIdx++]=128|u>>6&63;heap[outIdx++]=128|u&63}else{if(outIdx+3>=endIdx)break;heap[outIdx++]=240|u>>18;heap[outIdx++]=128|u>>12&63;heap[outIdx++]=128|u>>6&63;heap[outIdx++]=128|u&63}}heap[outIdx]=0;return outIdx-startIdx};var stringToUTF8=(str,outPtr,maxBytesToWrite)=>stringToUTF8Array(str,HEAPU8,outPtr,maxBytesToWrite);var lengthBytesUTF8=str=>{var len=0;for(var i=0;i=55296&&c<=57343){len+=4;++i}else{len+=3}}return len};var UTF8Decoder=typeof TextDecoder!="undefined"?new TextDecoder:undefined;var UTF8ArrayToString=(heapOrArray,idx,maxBytesToRead)=>{var endIdx=idx+maxBytesToRead;var endPtr=idx;while(heapOrArray[endPtr]&&!(endPtr>=endIdx))++endPtr;if(endPtr-idx>16&&heapOrArray.buffer&&UTF8Decoder){return UTF8Decoder.decode(heapOrArray.subarray(idx,endPtr))}var str="";while(idx>10,56320|ch&1023)}}return str};var UTF8ToString=(ptr,maxBytesToRead)=>ptr?UTF8ArrayToString(HEAPU8,ptr,maxBytesToRead):"";var __embind_register_std_string=(rawType,name)=>{name=readLatin1String(name);var stdStringIsUTF8=name==="std::string";registerType(rawType,{name:name,fromWireType(value){var length=HEAPU32[value>>2];var payload=value+4;var str;if(stdStringIsUTF8){var decodeStartPtr=payload;for(var i=0;i<=length;++i){var currentBytePtr=payload+i;if(i==length||HEAPU8[currentBytePtr]==0){var maxRead=currentBytePtr-decodeStartPtr;var stringSegment=UTF8ToString(decodeStartPtr,maxRead);if(str===undefined){str=stringSegment}else{str+=String.fromCharCode(0);str+=stringSegment}decodeStartPtr=currentBytePtr+1}}}else{var a=new Array(length);for(var i=0;i>2]=length;if(stdStringIsUTF8&&valueIsOfTypeString){stringToUTF8(value,ptr,length+1)}else{if(valueIsOfTypeString){for(var i=0;i255){_free(ptr);throwBindingError("String has UTF-16 code units that do not fit in 8 bits")}HEAPU8[ptr+i]=charCode}}else{for(var i=0;i{var endPtr=ptr;var idx=endPtr>>1;var maxIdx=idx+maxBytesToRead/2;while(!(idx>=maxIdx)&&HEAPU16[idx])++idx;endPtr=idx<<1;if(endPtr-ptr>32&&UTF16Decoder)return UTF16Decoder.decode(HEAPU8.subarray(ptr,endPtr));var str="";for(var i=0;!(i>=maxBytesToRead/2);++i){var codeUnit=HEAP16[ptr+i*2>>1];if(codeUnit==0)break;str+=String.fromCharCode(codeUnit)}return str};var stringToUTF16=(str,outPtr,maxBytesToWrite)=>{maxBytesToWrite??=2147483647;if(maxBytesToWrite<2)return 0;maxBytesToWrite-=2;var startPtr=outPtr;var numCharsToWrite=maxBytesToWrite>1]=codeUnit;outPtr+=2}HEAP16[outPtr>>1]=0;return outPtr-startPtr};var lengthBytesUTF16=str=>str.length*2;var UTF32ToString=(ptr,maxBytesToRead)=>{var i=0;var str="";while(!(i>=maxBytesToRead/4)){var utf32=HEAP32[ptr+i*4>>2];if(utf32==0)break;++i;if(utf32>=65536){var ch=utf32-65536;str+=String.fromCharCode(55296|ch>>10,56320|ch&1023)}else{str+=String.fromCharCode(utf32)}}return str};var stringToUTF32=(str,outPtr,maxBytesToWrite)=>{maxBytesToWrite??=2147483647;if(maxBytesToWrite<4)return 0;var startPtr=outPtr;var endPtr=startPtr+maxBytesToWrite-4;for(var i=0;i=55296&&codeUnit<=57343){var trailSurrogate=str.charCodeAt(++i);codeUnit=65536+((codeUnit&1023)<<10)|trailSurrogate&1023}HEAP32[outPtr>>2]=codeUnit;outPtr+=4;if(outPtr+4>endPtr)break}HEAP32[outPtr>>2]=0;return outPtr-startPtr};var lengthBytesUTF32=str=>{var len=0;for(var i=0;i=55296&&codeUnit<=57343)++i;len+=4}return len};var __embind_register_std_wstring=(rawType,charSize,name)=>{name=readLatin1String(name);var decodeString,encodeString,readCharAt,lengthBytesUTF;if(charSize===2){decodeString=UTF16ToString;encodeString=stringToUTF16;lengthBytesUTF=lengthBytesUTF16;readCharAt=pointer=>HEAPU16[pointer>>1]}else if(charSize===4){decodeString=UTF32ToString;encodeString=stringToUTF32;lengthBytesUTF=lengthBytesUTF32;readCharAt=pointer=>HEAPU32[pointer>>2]}registerType(rawType,{name:name,fromWireType:value=>{var length=HEAPU32[value>>2];var str;var decodeStartPtr=value+4;for(var i=0;i<=length;++i){var currentBytePtr=value+4+i*charSize;if(i==length||readCharAt(currentBytePtr)==0){var maxReadBytes=currentBytePtr-decodeStartPtr;var stringSegment=decodeString(decodeStartPtr,maxReadBytes);if(str===undefined){str=stringSegment}else{str+=String.fromCharCode(0);str+=stringSegment}decodeStartPtr=currentBytePtr+charSize}}_free(value);return str},toWireType:(destructors,value)=>{if(!(typeof value=="string")){throwBindingError(`Cannot pass non-string to C++ string type ${name}`)}var length=lengthBytesUTF(value);var ptr=_malloc(4+length+charSize);HEAPU32[ptr>>2]=length/charSize;encodeString(value,ptr+4,length+charSize);if(destructors!==null){destructors.push(_free,ptr)}return ptr},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction(ptr){_free(ptr)}})};var __embind_register_void=(rawType,name)=>{name=readLatin1String(name);registerType(rawType,{isVoid:true,name:name,argPackAdvance:0,fromWireType:()=>undefined,toWireType:(destructors,o)=>undefined})};var __emscripten_memcpy_js=(dest,src,num)=>HEAPU8.copyWithin(dest,src,src+num);var requireRegisteredType=(rawType,humanName)=>{var impl=registeredTypes[rawType];if(undefined===impl){throwBindingError(`${humanName} has unknown type ${getTypeName(rawType)}`)}return impl};var __emval_take_value=(type,arg)=>{type=requireRegisteredType(type,"_emval_take_value");var v=type["readValueFromPointer"](arg);return Emval.toHandle(v)};var _emscripten_date_now=()=>Date.now();var abortOnCannotGrowMemory=requestedSize=>{abort("OOM")};var _emscripten_resize_heap=requestedSize=>{var oldSize=HEAPU8.length;requestedSize>>>=0;abortOnCannotGrowMemory(requestedSize)};var printCharBuffers=[null,[],[]];var printChar=(stream,curr)=>{var buffer=printCharBuffers[stream];if(curr===0||curr===10){(stream===1?out:err)(UTF8ArrayToString(buffer,0));buffer.length=0}else{buffer.push(curr)}};var _fd_write=(fd,iov,iovcnt,pnum)=>{var num=0;for(var i=0;i>2];var len=HEAPU32[iov+4>>2];iov+=8;for(var j=0;j>2]=num;return 0};embind_init_charCodes();BindingError=Module["BindingError"]=class BindingError extends Error{constructor(message){super(message);this.name="BindingError"}};InternalError=Module["InternalError"]=class InternalError extends Error{constructor(message){super(message);this.name="InternalError"}};init_ClassHandle();init_embind();init_RegisteredPointer();UnboundTypeError=Module["UnboundTypeError"]=extendError(Error,"UnboundTypeError");init_emval();var wasmImports={f:___cxa_throw,q:__abort_js,p:__embind_register_bigint,u:__embind_register_bool,l:__embind_register_class,h:__embind_register_class_constructor,e:__embind_register_class_function,a:__embind_register_class_property,t:__embind_register_emval,k:__embind_register_float,c:__embind_register_function,d:__embind_register_integer,b:__embind_register_memory_view,o:__embind_register_optional,j:__embind_register_std_string,g:__embind_register_std_wstring,m:__embind_register_void,s:__emscripten_memcpy_js,n:__emval_take_value,v:_emscripten_date_now,r:_emscripten_resize_heap,i:_fd_write};var wasmExports=createWasm();var ___wasm_call_ctors=()=>(___wasm_call_ctors=wasmExports["x"])();var _param_get=Module["_param_get"]=(a0,a1)=>(_param_get=Module["_param_get"]=wasmExports["y"])(a0,a1);var _param_set_used=Module["_param_set_used"]=a0=>(_param_set_used=Module["_param_set_used"]=wasmExports["z"])(a0);var __Znwm=Module["__Znwm"]=a0=>(__Znwm=Module["__Znwm"]=wasmExports["A"])(a0);var __ZdlPvm=Module["__ZdlPvm"]=(a0,a1)=>(__ZdlPvm=Module["__ZdlPvm"]=wasmExports["B"])(a0,a1);var _malloc=a0=>(_malloc=wasmExports["D"])(a0);var __ZNSt12length_errorD1Ev=Module["__ZNSt12length_errorD1Ev"]=a0=>(__ZNSt12length_errorD1Ev=Module["__ZNSt12length_errorD1Ev"]=wasmExports["E"])(a0);var ___cxa_allocate_exception=Module["___cxa_allocate_exception"]=a0=>(___cxa_allocate_exception=Module["___cxa_allocate_exception"]=wasmExports["F"])(a0);var __ZNSt20bad_array_new_lengthD1Ev=Module["__ZNSt20bad_array_new_lengthD1Ev"]=a0=>(__ZNSt20bad_array_new_lengthD1Ev=Module["__ZNSt20bad_array_new_lengthD1Ev"]=wasmExports["G"])(a0);var __ZNSt20bad_array_new_lengthC1Ev=Module["__ZNSt20bad_array_new_lengthC1Ev"]=a0=>(__ZNSt20bad_array_new_lengthC1Ev=Module["__ZNSt20bad_array_new_lengthC1Ev"]=wasmExports["H"])(a0);var __ZNSt12out_of_rangeD1Ev=Module["__ZNSt12out_of_rangeD1Ev"]=a0=>(__ZNSt12out_of_rangeD1Ev=Module["__ZNSt12out_of_rangeD1Ev"]=wasmExports["I"])(a0);var ___cxa_pure_virtual=Module["___cxa_pure_virtual"]=()=>(___cxa_pure_virtual=Module["___cxa_pure_virtual"]=wasmExports["J"])();var ___getTypeName=a0=>(___getTypeName=wasmExports["K"])(a0);var __ZNSt9exceptionD2Ev=Module["__ZNSt9exceptionD2Ev"]=a0=>(__ZNSt9exceptionD2Ev=Module["__ZNSt9exceptionD2Ev"]=wasmExports["L"])(a0);var _free=a0=>(_free=wasmExports["M"])(a0);var _getTempRet0=Module["_getTempRet0"]=()=>(_getTempRet0=Module["_getTempRet0"]=wasmExports["N"])();var _setTempRet0=Module["_setTempRet0"]=a0=>(_setTempRet0=Module["_setTempRet0"]=wasmExports["O"])(a0);var __ZSt15get_new_handlerv=Module["__ZSt15get_new_handlerv"]=()=>(__ZSt15get_new_handlerv=Module["__ZSt15get_new_handlerv"]=wasmExports["P"])();var __Znam=Module["__Znam"]=a0=>(__Znam=Module["__Znam"]=wasmExports["Q"])(a0);var __ZdlPv=Module["__ZdlPv"]=a0=>(__ZdlPv=Module["__ZdlPv"]=wasmExports["R"])(a0);var __ZdaPv=Module["__ZdaPv"]=a0=>(__ZdaPv=Module["__ZdaPv"]=wasmExports["S"])(a0);var __ZdaPvm=Module["__ZdaPvm"]=(a0,a1)=>(__ZdaPvm=Module["__ZdaPvm"]=wasmExports["T"])(a0,a1);var __ZnwmSt11align_val_t=Module["__ZnwmSt11align_val_t"]=(a0,a1)=>(__ZnwmSt11align_val_t=Module["__ZnwmSt11align_val_t"]=wasmExports["U"])(a0,a1);var __ZnamSt11align_val_t=Module["__ZnamSt11align_val_t"]=(a0,a1)=>(__ZnamSt11align_val_t=Module["__ZnamSt11align_val_t"]=wasmExports["V"])(a0,a1);var __ZdlPvSt11align_val_t=Module["__ZdlPvSt11align_val_t"]=(a0,a1)=>(__ZdlPvSt11align_val_t=Module["__ZdlPvSt11align_val_t"]=wasmExports["W"])(a0,a1);var __ZdlPvmSt11align_val_t=Module["__ZdlPvmSt11align_val_t"]=(a0,a1,a2)=>(__ZdlPvmSt11align_val_t=Module["__ZdlPvmSt11align_val_t"]=wasmExports["X"])(a0,a1,a2);var __ZdaPvSt11align_val_t=Module["__ZdaPvSt11align_val_t"]=(a0,a1)=>(__ZdaPvSt11align_val_t=Module["__ZdaPvSt11align_val_t"]=wasmExports["Y"])(a0,a1);var __ZdaPvmSt11align_val_t=Module["__ZdaPvmSt11align_val_t"]=(a0,a1,a2)=>(__ZdaPvmSt11align_val_t=Module["__ZdaPvmSt11align_val_t"]=wasmExports["Z"])(a0,a1,a2);var __ZSt14set_unexpectedPFvvE=Module["__ZSt14set_unexpectedPFvvE"]=a0=>(__ZSt14set_unexpectedPFvvE=Module["__ZSt14set_unexpectedPFvvE"]=wasmExports["_"])(a0);var __ZSt13set_terminatePFvvE=Module["__ZSt13set_terminatePFvvE"]=a0=>(__ZSt13set_terminatePFvvE=Module["__ZSt13set_terminatePFvvE"]=wasmExports["$"])(a0);var __ZSt15set_new_handlerPFvvE=Module["__ZSt15set_new_handlerPFvvE"]=a0=>(__ZSt15set_new_handlerPFvvE=Module["__ZSt15set_new_handlerPFvvE"]=wasmExports["aa"])(a0);var __ZSt14get_unexpectedv=Module["__ZSt14get_unexpectedv"]=()=>(__ZSt14get_unexpectedv=Module["__ZSt14get_unexpectedv"]=wasmExports["ba"])();var __ZSt10unexpectedv=Module["__ZSt10unexpectedv"]=()=>(__ZSt10unexpectedv=Module["__ZSt10unexpectedv"]=wasmExports["ca"])();var __ZSt13get_terminatev=Module["__ZSt13get_terminatev"]=()=>(__ZSt13get_terminatev=Module["__ZSt13get_terminatev"]=wasmExports["da"])();var __ZSt9terminatev=Module["__ZSt9terminatev"]=()=>(__ZSt9terminatev=Module["__ZSt9terminatev"]=wasmExports["ea"])();var ___cxa_current_primary_exception=Module["___cxa_current_primary_exception"]=()=>(___cxa_current_primary_exception=Module["___cxa_current_primary_exception"]=wasmExports["fa"])();var ___cxa_rethrow_primary_exception=Module["___cxa_rethrow_primary_exception"]=a0=>(___cxa_rethrow_primary_exception=Module["___cxa_rethrow_primary_exception"]=wasmExports["ga"])(a0);var ___cxa_uncaught_exception=Module["___cxa_uncaught_exception"]=()=>(___cxa_uncaught_exception=Module["___cxa_uncaught_exception"]=wasmExports["ha"])();var ___cxa_uncaught_exceptions=Module["___cxa_uncaught_exceptions"]=()=>(___cxa_uncaught_exceptions=Module["___cxa_uncaught_exceptions"]=wasmExports["ia"])();var ___cxa_free_exception=Module["___cxa_free_exception"]=a0=>(___cxa_free_exception=Module["___cxa_free_exception"]=wasmExports["ja"])(a0);var ___cxa_init_primary_exception=Module["___cxa_init_primary_exception"]=(a0,a1,a2)=>(___cxa_init_primary_exception=Module["___cxa_init_primary_exception"]=wasmExports["ka"])(a0,a1,a2);var ___cxa_deleted_virtual=Module["___cxa_deleted_virtual"]=()=>(___cxa_deleted_virtual=Module["___cxa_deleted_virtual"]=wasmExports["la"])();var ___dynamic_cast=Module["___dynamic_cast"]=(a0,a1,a2,a3)=>(___dynamic_cast=Module["___dynamic_cast"]=wasmExports["ma"])(a0,a1,a2,a3);var __ZNSt9type_infoD2Ev=Module["__ZNSt9type_infoD2Ev"]=a0=>(__ZNSt9type_infoD2Ev=Module["__ZNSt9type_infoD2Ev"]=wasmExports["na"])(a0);var ___cxa_is_pointer_type=a0=>(___cxa_is_pointer_type=wasmExports["oa"])(a0);var __ZNSt9exceptionD0Ev=Module["__ZNSt9exceptionD0Ev"]=a0=>(__ZNSt9exceptionD0Ev=Module["__ZNSt9exceptionD0Ev"]=wasmExports["pa"])(a0);var __ZNSt9exceptionD1Ev=Module["__ZNSt9exceptionD1Ev"]=a0=>(__ZNSt9exceptionD1Ev=Module["__ZNSt9exceptionD1Ev"]=wasmExports["qa"])(a0);var __ZNKSt9exception4whatEv=Module["__ZNKSt9exception4whatEv"]=a0=>(__ZNKSt9exception4whatEv=Module["__ZNKSt9exception4whatEv"]=wasmExports["ra"])(a0);var __ZNSt13bad_exceptionD0Ev=Module["__ZNSt13bad_exceptionD0Ev"]=a0=>(__ZNSt13bad_exceptionD0Ev=Module["__ZNSt13bad_exceptionD0Ev"]=wasmExports["sa"])(a0);var __ZNSt13bad_exceptionD1Ev=Module["__ZNSt13bad_exceptionD1Ev"]=a0=>(__ZNSt13bad_exceptionD1Ev=Module["__ZNSt13bad_exceptionD1Ev"]=wasmExports["ta"])(a0);var __ZNKSt13bad_exception4whatEv=Module["__ZNKSt13bad_exception4whatEv"]=a0=>(__ZNKSt13bad_exception4whatEv=Module["__ZNKSt13bad_exception4whatEv"]=wasmExports["ua"])(a0);var __ZNSt9bad_allocC2Ev=Module["__ZNSt9bad_allocC2Ev"]=a0=>(__ZNSt9bad_allocC2Ev=Module["__ZNSt9bad_allocC2Ev"]=wasmExports["va"])(a0);var __ZNSt9bad_allocD0Ev=Module["__ZNSt9bad_allocD0Ev"]=a0=>(__ZNSt9bad_allocD0Ev=Module["__ZNSt9bad_allocD0Ev"]=wasmExports["wa"])(a0);var __ZNSt9bad_allocD1Ev=Module["__ZNSt9bad_allocD1Ev"]=a0=>(__ZNSt9bad_allocD1Ev=Module["__ZNSt9bad_allocD1Ev"]=wasmExports["xa"])(a0);var __ZNKSt9bad_alloc4whatEv=Module["__ZNKSt9bad_alloc4whatEv"]=a0=>(__ZNKSt9bad_alloc4whatEv=Module["__ZNKSt9bad_alloc4whatEv"]=wasmExports["ya"])(a0);var __ZNSt20bad_array_new_lengthC2Ev=Module["__ZNSt20bad_array_new_lengthC2Ev"]=a0=>(__ZNSt20bad_array_new_lengthC2Ev=Module["__ZNSt20bad_array_new_lengthC2Ev"]=wasmExports["za"])(a0);var __ZNSt20bad_array_new_lengthD0Ev=Module["__ZNSt20bad_array_new_lengthD0Ev"]=a0=>(__ZNSt20bad_array_new_lengthD0Ev=Module["__ZNSt20bad_array_new_lengthD0Ev"]=wasmExports["Aa"])(a0);var __ZNKSt20bad_array_new_length4whatEv=Module["__ZNKSt20bad_array_new_length4whatEv"]=a0=>(__ZNKSt20bad_array_new_length4whatEv=Module["__ZNKSt20bad_array_new_length4whatEv"]=wasmExports["Ba"])(a0);var __ZNSt13bad_exceptionD2Ev=Module["__ZNSt13bad_exceptionD2Ev"]=a0=>(__ZNSt13bad_exceptionD2Ev=Module["__ZNSt13bad_exceptionD2Ev"]=wasmExports["Ca"])(a0);var __ZNSt9bad_allocC1Ev=Module["__ZNSt9bad_allocC1Ev"]=a0=>(__ZNSt9bad_allocC1Ev=Module["__ZNSt9bad_allocC1Ev"]=wasmExports["Da"])(a0);var __ZNSt9bad_allocD2Ev=Module["__ZNSt9bad_allocD2Ev"]=a0=>(__ZNSt9bad_allocD2Ev=Module["__ZNSt9bad_allocD2Ev"]=wasmExports["Ea"])(a0);var __ZNSt20bad_array_new_lengthD2Ev=Module["__ZNSt20bad_array_new_lengthD2Ev"]=a0=>(__ZNSt20bad_array_new_lengthD2Ev=Module["__ZNSt20bad_array_new_lengthD2Ev"]=wasmExports["Fa"])(a0);var __ZNSt11logic_errorD2Ev=Module["__ZNSt11logic_errorD2Ev"]=a0=>(__ZNSt11logic_errorD2Ev=Module["__ZNSt11logic_errorD2Ev"]=wasmExports["Ga"])(a0);var __ZNSt11logic_errorD0Ev=Module["__ZNSt11logic_errorD0Ev"]=a0=>(__ZNSt11logic_errorD0Ev=Module["__ZNSt11logic_errorD0Ev"]=wasmExports["Ha"])(a0);var __ZNSt11logic_errorD1Ev=Module["__ZNSt11logic_errorD1Ev"]=a0=>(__ZNSt11logic_errorD1Ev=Module["__ZNSt11logic_errorD1Ev"]=wasmExports["Ia"])(a0);var __ZNKSt11logic_error4whatEv=Module["__ZNKSt11logic_error4whatEv"]=a0=>(__ZNKSt11logic_error4whatEv=Module["__ZNKSt11logic_error4whatEv"]=wasmExports["Ja"])(a0);var __ZNSt13runtime_errorD2Ev=Module["__ZNSt13runtime_errorD2Ev"]=a0=>(__ZNSt13runtime_errorD2Ev=Module["__ZNSt13runtime_errorD2Ev"]=wasmExports["Ka"])(a0);var __ZNSt13runtime_errorD0Ev=Module["__ZNSt13runtime_errorD0Ev"]=a0=>(__ZNSt13runtime_errorD0Ev=Module["__ZNSt13runtime_errorD0Ev"]=wasmExports["La"])(a0);var __ZNSt13runtime_errorD1Ev=Module["__ZNSt13runtime_errorD1Ev"]=a0=>(__ZNSt13runtime_errorD1Ev=Module["__ZNSt13runtime_errorD1Ev"]=wasmExports["Ma"])(a0);var __ZNKSt13runtime_error4whatEv=Module["__ZNKSt13runtime_error4whatEv"]=a0=>(__ZNKSt13runtime_error4whatEv=Module["__ZNKSt13runtime_error4whatEv"]=wasmExports["Na"])(a0);var __ZNSt12domain_errorD0Ev=Module["__ZNSt12domain_errorD0Ev"]=a0=>(__ZNSt12domain_errorD0Ev=Module["__ZNSt12domain_errorD0Ev"]=wasmExports["Oa"])(a0);var __ZNSt12domain_errorD1Ev=Module["__ZNSt12domain_errorD1Ev"]=a0=>(__ZNSt12domain_errorD1Ev=Module["__ZNSt12domain_errorD1Ev"]=wasmExports["Pa"])(a0);var __ZNSt16invalid_argumentD0Ev=Module["__ZNSt16invalid_argumentD0Ev"]=a0=>(__ZNSt16invalid_argumentD0Ev=Module["__ZNSt16invalid_argumentD0Ev"]=wasmExports["Qa"])(a0);var __ZNSt16invalid_argumentD1Ev=Module["__ZNSt16invalid_argumentD1Ev"]=a0=>(__ZNSt16invalid_argumentD1Ev=Module["__ZNSt16invalid_argumentD1Ev"]=wasmExports["Ra"])(a0);var __ZNSt12length_errorD0Ev=Module["__ZNSt12length_errorD0Ev"]=a0=>(__ZNSt12length_errorD0Ev=Module["__ZNSt12length_errorD0Ev"]=wasmExports["Sa"])(a0);var __ZNSt12out_of_rangeD0Ev=Module["__ZNSt12out_of_rangeD0Ev"]=a0=>(__ZNSt12out_of_rangeD0Ev=Module["__ZNSt12out_of_rangeD0Ev"]=wasmExports["Ta"])(a0);var __ZNSt11range_errorD0Ev=Module["__ZNSt11range_errorD0Ev"]=a0=>(__ZNSt11range_errorD0Ev=Module["__ZNSt11range_errorD0Ev"]=wasmExports["Ua"])(a0);var __ZNSt11range_errorD1Ev=Module["__ZNSt11range_errorD1Ev"]=a0=>(__ZNSt11range_errorD1Ev=Module["__ZNSt11range_errorD1Ev"]=wasmExports["Va"])(a0);var __ZNSt14overflow_errorD0Ev=Module["__ZNSt14overflow_errorD0Ev"]=a0=>(__ZNSt14overflow_errorD0Ev=Module["__ZNSt14overflow_errorD0Ev"]=wasmExports["Wa"])(a0);var __ZNSt14overflow_errorD1Ev=Module["__ZNSt14overflow_errorD1Ev"]=a0=>(__ZNSt14overflow_errorD1Ev=Module["__ZNSt14overflow_errorD1Ev"]=wasmExports["Xa"])(a0);var __ZNSt15underflow_errorD0Ev=Module["__ZNSt15underflow_errorD0Ev"]=a0=>(__ZNSt15underflow_errorD0Ev=Module["__ZNSt15underflow_errorD0Ev"]=wasmExports["Ya"])(a0);var __ZNSt15underflow_errorD1Ev=Module["__ZNSt15underflow_errorD1Ev"]=a0=>(__ZNSt15underflow_errorD1Ev=Module["__ZNSt15underflow_errorD1Ev"]=wasmExports["Za"])(a0);var __ZNSt12domain_errorD2Ev=Module["__ZNSt12domain_errorD2Ev"]=a0=>(__ZNSt12domain_errorD2Ev=Module["__ZNSt12domain_errorD2Ev"]=wasmExports["_a"])(a0);var __ZNSt16invalid_argumentD2Ev=Module["__ZNSt16invalid_argumentD2Ev"]=a0=>(__ZNSt16invalid_argumentD2Ev=Module["__ZNSt16invalid_argumentD2Ev"]=wasmExports["$a"])(a0);var __ZNSt12length_errorD2Ev=Module["__ZNSt12length_errorD2Ev"]=a0=>(__ZNSt12length_errorD2Ev=Module["__ZNSt12length_errorD2Ev"]=wasmExports["ab"])(a0);var __ZNSt12out_of_rangeD2Ev=Module["__ZNSt12out_of_rangeD2Ev"]=a0=>(__ZNSt12out_of_rangeD2Ev=Module["__ZNSt12out_of_rangeD2Ev"]=wasmExports["bb"])(a0);var __ZNSt11range_errorD2Ev=Module["__ZNSt11range_errorD2Ev"]=a0=>(__ZNSt11range_errorD2Ev=Module["__ZNSt11range_errorD2Ev"]=wasmExports["cb"])(a0);var __ZNSt14overflow_errorD2Ev=Module["__ZNSt14overflow_errorD2Ev"]=a0=>(__ZNSt14overflow_errorD2Ev=Module["__ZNSt14overflow_errorD2Ev"]=wasmExports["db"])(a0);var __ZNSt15underflow_errorD2Ev=Module["__ZNSt15underflow_errorD2Ev"]=a0=>(__ZNSt15underflow_errorD2Ev=Module["__ZNSt15underflow_errorD2Ev"]=wasmExports["eb"])(a0);var __ZNSt9type_infoD0Ev=Module["__ZNSt9type_infoD0Ev"]=a0=>(__ZNSt9type_infoD0Ev=Module["__ZNSt9type_infoD0Ev"]=wasmExports["fb"])(a0);var __ZNSt9type_infoD1Ev=Module["__ZNSt9type_infoD1Ev"]=a0=>(__ZNSt9type_infoD1Ev=Module["__ZNSt9type_infoD1Ev"]=wasmExports["gb"])(a0);var __ZNSt8bad_castC2Ev=Module["__ZNSt8bad_castC2Ev"]=a0=>(__ZNSt8bad_castC2Ev=Module["__ZNSt8bad_castC2Ev"]=wasmExports["hb"])(a0);var __ZNSt8bad_castD2Ev=Module["__ZNSt8bad_castD2Ev"]=a0=>(__ZNSt8bad_castD2Ev=Module["__ZNSt8bad_castD2Ev"]=wasmExports["ib"])(a0);var __ZNSt8bad_castD0Ev=Module["__ZNSt8bad_castD0Ev"]=a0=>(__ZNSt8bad_castD0Ev=Module["__ZNSt8bad_castD0Ev"]=wasmExports["jb"])(a0);var __ZNSt8bad_castD1Ev=Module["__ZNSt8bad_castD1Ev"]=a0=>(__ZNSt8bad_castD1Ev=Module["__ZNSt8bad_castD1Ev"]=wasmExports["kb"])(a0);var __ZNKSt8bad_cast4whatEv=Module["__ZNKSt8bad_cast4whatEv"]=a0=>(__ZNKSt8bad_cast4whatEv=Module["__ZNKSt8bad_cast4whatEv"]=wasmExports["lb"])(a0);var __ZNSt10bad_typeidC2Ev=Module["__ZNSt10bad_typeidC2Ev"]=a0=>(__ZNSt10bad_typeidC2Ev=Module["__ZNSt10bad_typeidC2Ev"]=wasmExports["mb"])(a0);var __ZNSt10bad_typeidD2Ev=Module["__ZNSt10bad_typeidD2Ev"]=a0=>(__ZNSt10bad_typeidD2Ev=Module["__ZNSt10bad_typeidD2Ev"]=wasmExports["nb"])(a0);var __ZNSt10bad_typeidD0Ev=Module["__ZNSt10bad_typeidD0Ev"]=a0=>(__ZNSt10bad_typeidD0Ev=Module["__ZNSt10bad_typeidD0Ev"]=wasmExports["ob"])(a0);var __ZNSt10bad_typeidD1Ev=Module["__ZNSt10bad_typeidD1Ev"]=a0=>(__ZNSt10bad_typeidD1Ev=Module["__ZNSt10bad_typeidD1Ev"]=wasmExports["pb"])(a0);var __ZNKSt10bad_typeid4whatEv=Module["__ZNKSt10bad_typeid4whatEv"]=a0=>(__ZNKSt10bad_typeid4whatEv=Module["__ZNKSt10bad_typeid4whatEv"]=wasmExports["qb"])(a0);var __ZNSt8bad_castC1Ev=Module["__ZNSt8bad_castC1Ev"]=a0=>(__ZNSt8bad_castC1Ev=Module["__ZNSt8bad_castC1Ev"]=wasmExports["rb"])(a0);var __ZNSt10bad_typeidC1Ev=Module["__ZNSt10bad_typeidC1Ev"]=a0=>(__ZNSt10bad_typeidC1Ev=Module["__ZNSt10bad_typeidC1Ev"]=wasmExports["sb"])(a0);var dynCall_jiji=Module["dynCall_jiji"]=(a0,a1,a2,a3,a4)=>(dynCall_jiji=Module["dynCall_jiji"]=wasmExports["tb"])(a0,a1,a2,a3,a4);var __ZTIPK16failsafe_flags_s=Module["__ZTIPK16failsafe_flags_s"]=48400;var __ZTIP16failsafe_flags_s=Module["__ZTIP16failsafe_flags_s"]=48384;var __ZTI16failsafe_flags_s=Module["__ZTI16failsafe_flags_s"]=48376;var __ZTIb=Module["__ZTIb"]=31224;var __ZTIh=Module["__ZTIh"]=31380;var __ZTINSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE=Module["__ZTINSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE"]=48476;var __ZTINSt3__28optionalINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEEEE=Module["__ZTINSt3__28optionalINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEEEE"]=48624;var __ZTIPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTIPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=48680;var __ZTIPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTIPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=48664;var __ZTINSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTINSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=48488;var __ZTISt12length_error=Module["__ZTISt12length_error"]=33340;var __ZTVSt12length_error=Module["__ZTVSt12length_error"]=33300;var __ZTISt20bad_array_new_length=Module["__ZTISt20bad_array_new_length"]=33112;var __ZTISt12out_of_range=Module["__ZTISt12out_of_range"]=33392;var __ZTVSt12out_of_range=Module["__ZTVSt12out_of_range"]=33352;var __ZTVN10__cxxabiv117__class_type_infoE=Module["__ZTVN10__cxxabiv117__class_type_infoE"]=32612;var __ZTVN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTVN10__cxxabiv121__vmi_class_type_infoE"]=32744;var __ZTVN10__cxxabiv120__si_class_type_infoE=Module["__ZTVN10__cxxabiv120__si_class_type_infoE"]=32652;var __ZTS16failsafe_flags_s=Module["__ZTS16failsafe_flags_s"]=28132;var __ZTSP16failsafe_flags_s=Module["__ZTSP16failsafe_flags_s"]=28151;var __ZTVN10__cxxabiv119__pointer_type_infoE=Module["__ZTVN10__cxxabiv119__pointer_type_infoE"]=32864;var __ZTSPK16failsafe_flags_s=Module["__ZTSPK16failsafe_flags_s"]=28171;var __ZTIi=Module["__ZTIi"]=31588;var __ZTSNSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE=Module["__ZTSNSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE"]=28220;var __ZTSNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=28287;var __ZTIv=Module["__ZTIv"]=31116;var __ZTIf=Module["__ZTIf"]=32060;var __ZTSNSt3__28optionalINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEEEE=Module["__ZTSNSt3__28optionalINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEEEE"]=28385;var __ZTSNSt3__227__optional_move_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTSNSt3__227__optional_move_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=28463;var __ZTSNSt3__227__optional_copy_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTSNSt3__227__optional_copy_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=28565;var __ZTSNSt3__220__optional_move_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTSNSt3__220__optional_move_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=28667;var __ZTSNSt3__220__optional_copy_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTSNSt3__220__optional_copy_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=28762;var __ZTSNSt3__223__optional_storage_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTSNSt3__223__optional_storage_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=28857;var __ZTSNSt3__224__optional_destruct_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTSNSt3__224__optional_destruct_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=28955;var __ZTINSt3__224__optional_destruct_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTINSt3__224__optional_destruct_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=48540;var __ZTINSt3__223__optional_storage_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTINSt3__223__optional_storage_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=48548;var __ZTINSt3__220__optional_copy_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTINSt3__220__optional_copy_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=48560;var __ZTINSt3__220__optional_move_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTINSt3__220__optional_move_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=48572;var __ZTINSt3__227__optional_copy_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTINSt3__227__optional_copy_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=48584;var __ZTINSt3__227__optional_move_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTINSt3__227__optional_move_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=48596;var __ZTSNSt3__218__sfinae_ctor_baseILb1ELb1EEE=Module["__ZTSNSt3__218__sfinae_ctor_baseILb1ELb1EEE"]=29054;var __ZTINSt3__218__sfinae_ctor_baseILb1ELb1EEE=Module["__ZTINSt3__218__sfinae_ctor_baseILb1ELb1EEE"]=48608;var __ZTSNSt3__220__sfinae_assign_baseILb1ELb1EEE=Module["__ZTSNSt3__220__sfinae_assign_baseILb1ELb1EEE"]=29093;var __ZTINSt3__220__sfinae_assign_baseILb1ELb1EEE=Module["__ZTINSt3__220__sfinae_assign_baseILb1ELb1EEE"]=48616;var __ZTSPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=29134;var __ZTSPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=29221;var __ZTIm=Module["__ZTIm"]=31744;var __ZTIc=Module["__ZTIc"]=31328;var __ZTIa=Module["__ZTIa"]=31432;var __ZTIs=Module["__ZTIs"]=31484;var __ZTIt=Module["__ZTIt"]=31536;var __ZTIj=Module["__ZTIj"]=31640;var __ZTIl=Module["__ZTIl"]=31692;var __ZTIx=Module["__ZTIx"]=31796;var __ZTIy=Module["__ZTIy"]=31848;var __ZTId=Module["__ZTId"]=32112;var __ZTINSt3__212basic_stringIhNS_11char_traitsIhEENS_9allocatorIhEEEE=Module["__ZTINSt3__212basic_stringIhNS_11char_traitsIhEENS_9allocatorIhEEEE"]=29424;var __ZTINSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE=Module["__ZTINSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE"]=29496;var __ZTINSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE=Module["__ZTINSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE"]=29572;var __ZTINSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE=Module["__ZTINSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE"]=29648;var __ZTSNSt3__212basic_stringIhNS_11char_traitsIhEENS_9allocatorIhEEEE=Module["__ZTSNSt3__212basic_stringIhNS_11char_traitsIhEENS_9allocatorIhEEEE"]=29360;var __ZTSNSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE=Module["__ZTSNSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE"]=29432;var __ZTSNSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE=Module["__ZTSNSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE"]=29504;var __ZTSNSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE=Module["__ZTSNSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE"]=29580;var __ZTVSt11logic_error=Module["__ZTVSt11logic_error"]=33124;var __ZTVSt9exception=Module["__ZTVSt9exception"]=32960;var __ZTVSt13runtime_error=Module["__ZTVSt13runtime_error"]=33144;var __ZTISt9exception=Module["__ZTISt9exception"]=32996;var ___cxa_unexpected_handler=Module["___cxa_unexpected_handler"]=48984;var ___cxa_terminate_handler=Module["___cxa_terminate_handler"]=48980;var ___cxa_new_handler=Module["___cxa_new_handler"]=51228;var __ZTIN10__cxxabiv116__shim_type_infoE=Module["__ZTIN10__cxxabiv116__shim_type_infoE"]=30724;var __ZTIN10__cxxabiv117__class_type_infoE=Module["__ZTIN10__cxxabiv117__class_type_infoE"]=30772;var __ZTIN10__cxxabiv117__pbase_type_infoE=Module["__ZTIN10__cxxabiv117__pbase_type_infoE"]=30820;var __ZTIDn=Module["__ZTIDn"]=31168;var __ZTIN10__cxxabiv119__pointer_type_infoE=Module["__ZTIN10__cxxabiv119__pointer_type_infoE"]=30868;var __ZTIN10__cxxabiv120__function_type_infoE=Module["__ZTIN10__cxxabiv120__function_type_infoE"]=30920;var __ZTIN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTIN10__cxxabiv129__pointer_to_member_type_infoE"]=30980;var __ZTSN10__cxxabiv116__shim_type_infoE=Module["__ZTSN10__cxxabiv116__shim_type_infoE"]=30688;var __ZTISt9type_info=Module["__ZTISt9type_info"]=33660;var __ZTSN10__cxxabiv117__class_type_infoE=Module["__ZTSN10__cxxabiv117__class_type_infoE"]=30736;var __ZTSN10__cxxabiv117__pbase_type_infoE=Module["__ZTSN10__cxxabiv117__pbase_type_infoE"]=30784;var __ZTSN10__cxxabiv119__pointer_type_infoE=Module["__ZTSN10__cxxabiv119__pointer_type_infoE"]=30832;var __ZTSN10__cxxabiv120__function_type_infoE=Module["__ZTSN10__cxxabiv120__function_type_infoE"]=30880;var __ZTSN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTSN10__cxxabiv129__pointer_to_member_type_infoE"]=30932;var __ZTVN10__cxxabiv116__shim_type_infoE=Module["__ZTVN10__cxxabiv116__shim_type_infoE"]=31004;var __ZTVN10__cxxabiv123__fundamental_type_infoE=Module["__ZTVN10__cxxabiv123__fundamental_type_infoE"]=31032;var __ZTIN10__cxxabiv123__fundamental_type_infoE=Module["__ZTIN10__cxxabiv123__fundamental_type_infoE"]=31100;var __ZTSN10__cxxabiv123__fundamental_type_infoE=Module["__ZTSN10__cxxabiv123__fundamental_type_infoE"]=31060;var __ZTSv=Module["__ZTSv"]=31112;var __ZTSPv=Module["__ZTSPv"]=31124;var __ZTIPv=Module["__ZTIPv"]=31128;var __ZTSPKv=Module["__ZTSPKv"]=31144;var __ZTIPKv=Module["__ZTIPKv"]=31148;var __ZTSDn=Module["__ZTSDn"]=31164;var __ZTSPDn=Module["__ZTSPDn"]=31176;var __ZTIPDn=Module["__ZTIPDn"]=31180;var __ZTSPKDn=Module["__ZTSPKDn"]=31196;var __ZTIPKDn=Module["__ZTIPKDn"]=31204;var __ZTSb=Module["__ZTSb"]=31220;var __ZTSPb=Module["__ZTSPb"]=31232;var __ZTIPb=Module["__ZTIPb"]=31236;var __ZTSPKb=Module["__ZTSPKb"]=31252;var __ZTIPKb=Module["__ZTIPKb"]=31256;var __ZTSw=Module["__ZTSw"]=31272;var __ZTIw=Module["__ZTIw"]=31276;var __ZTSPw=Module["__ZTSPw"]=31284;var __ZTIPw=Module["__ZTIPw"]=31288;var __ZTSPKw=Module["__ZTSPKw"]=31304;var __ZTIPKw=Module["__ZTIPKw"]=31308;var __ZTSc=Module["__ZTSc"]=31324;var __ZTSPc=Module["__ZTSPc"]=31336;var __ZTIPc=Module["__ZTIPc"]=31340;var __ZTSPKc=Module["__ZTSPKc"]=31356;var __ZTIPKc=Module["__ZTIPKc"]=31360;var __ZTSh=Module["__ZTSh"]=31376;var __ZTSPh=Module["__ZTSPh"]=31388;var __ZTIPh=Module["__ZTIPh"]=31392;var __ZTSPKh=Module["__ZTSPKh"]=31408;var __ZTIPKh=Module["__ZTIPKh"]=31412;var __ZTSa=Module["__ZTSa"]=31428;var __ZTSPa=Module["__ZTSPa"]=31440;var __ZTIPa=Module["__ZTIPa"]=31444;var __ZTSPKa=Module["__ZTSPKa"]=31460;var __ZTIPKa=Module["__ZTIPKa"]=31464;var __ZTSs=Module["__ZTSs"]=31480;var __ZTSPs=Module["__ZTSPs"]=31492;var __ZTIPs=Module["__ZTIPs"]=31496;var __ZTSPKs=Module["__ZTSPKs"]=31512;var __ZTIPKs=Module["__ZTIPKs"]=31516;var __ZTSt=Module["__ZTSt"]=31532;var __ZTSPt=Module["__ZTSPt"]=31544;var __ZTIPt=Module["__ZTIPt"]=31548;var __ZTSPKt=Module["__ZTSPKt"]=31564;var __ZTIPKt=Module["__ZTIPKt"]=31568;var __ZTSi=Module["__ZTSi"]=31584;var __ZTSPi=Module["__ZTSPi"]=31596;var __ZTIPi=Module["__ZTIPi"]=31600;var __ZTSPKi=Module["__ZTSPKi"]=31616;var __ZTIPKi=Module["__ZTIPKi"]=31620;var __ZTSj=Module["__ZTSj"]=31636;var __ZTSPj=Module["__ZTSPj"]=31648;var __ZTIPj=Module["__ZTIPj"]=31652;var __ZTSPKj=Module["__ZTSPKj"]=31668;var __ZTIPKj=Module["__ZTIPKj"]=31672;var __ZTSl=Module["__ZTSl"]=31688;var __ZTSPl=Module["__ZTSPl"]=31700;var __ZTIPl=Module["__ZTIPl"]=31704;var __ZTSPKl=Module["__ZTSPKl"]=31720;var __ZTIPKl=Module["__ZTIPKl"]=31724;var __ZTSm=Module["__ZTSm"]=31740;var __ZTSPm=Module["__ZTSPm"]=31752;var __ZTIPm=Module["__ZTIPm"]=31756;var __ZTSPKm=Module["__ZTSPKm"]=31772;var __ZTIPKm=Module["__ZTIPKm"]=31776;var __ZTSx=Module["__ZTSx"]=31792;var __ZTSPx=Module["__ZTSPx"]=31804;var __ZTIPx=Module["__ZTIPx"]=31808;var __ZTSPKx=Module["__ZTSPKx"]=31824;var __ZTIPKx=Module["__ZTIPKx"]=31828;var __ZTSy=Module["__ZTSy"]=31844;var __ZTSPy=Module["__ZTSPy"]=31856;var __ZTIPy=Module["__ZTIPy"]=31860;var __ZTSPKy=Module["__ZTSPKy"]=31876;var __ZTIPKy=Module["__ZTIPKy"]=31880;var __ZTSn=Module["__ZTSn"]=31896;var __ZTIn=Module["__ZTIn"]=31900;var __ZTSPn=Module["__ZTSPn"]=31908;var __ZTIPn=Module["__ZTIPn"]=31912;var __ZTSPKn=Module["__ZTSPKn"]=31928;var __ZTIPKn=Module["__ZTIPKn"]=31932;var __ZTSo=Module["__ZTSo"]=31948;var __ZTIo=Module["__ZTIo"]=31952;var __ZTSPo=Module["__ZTSPo"]=31960;var __ZTIPo=Module["__ZTIPo"]=31964;var __ZTSPKo=Module["__ZTSPKo"]=31980;var __ZTIPKo=Module["__ZTIPKo"]=31984;var __ZTSDh=Module["__ZTSDh"]=32e3;var __ZTIDh=Module["__ZTIDh"]=32004;var __ZTSPDh=Module["__ZTSPDh"]=32012;var __ZTIPDh=Module["__ZTIPDh"]=32016;var __ZTSPKDh=Module["__ZTSPKDh"]=32032;var __ZTIPKDh=Module["__ZTIPKDh"]=32040;var __ZTSf=Module["__ZTSf"]=32056;var __ZTSPf=Module["__ZTSPf"]=32068;var __ZTIPf=Module["__ZTIPf"]=32072;var __ZTSPKf=Module["__ZTSPKf"]=32088;var __ZTIPKf=Module["__ZTIPKf"]=32092;var __ZTSd=Module["__ZTSd"]=32108;var __ZTSPd=Module["__ZTSPd"]=32120;var __ZTIPd=Module["__ZTIPd"]=32124;var __ZTSPKd=Module["__ZTSPKd"]=32140;var __ZTIPKd=Module["__ZTIPKd"]=32144;var __ZTSe=Module["__ZTSe"]=32160;var __ZTIe=Module["__ZTIe"]=32164;var __ZTSPe=Module["__ZTSPe"]=32172;var __ZTIPe=Module["__ZTIPe"]=32176;var __ZTSPKe=Module["__ZTSPKe"]=32192;var __ZTIPKe=Module["__ZTIPKe"]=32196;var __ZTSg=Module["__ZTSg"]=32212;var __ZTIg=Module["__ZTIg"]=32216;var __ZTSPg=Module["__ZTSPg"]=32224;var __ZTIPg=Module["__ZTIPg"]=32228;var __ZTSPKg=Module["__ZTSPKg"]=32244;var __ZTIPKg=Module["__ZTIPKg"]=32248;var __ZTSDu=Module["__ZTSDu"]=32264;var __ZTIDu=Module["__ZTIDu"]=32268;var __ZTSPDu=Module["__ZTSPDu"]=32276;var __ZTIPDu=Module["__ZTIPDu"]=32280;var __ZTSPKDu=Module["__ZTSPKDu"]=32296;var __ZTIPKDu=Module["__ZTIPKDu"]=32304;var __ZTSDs=Module["__ZTSDs"]=32320;var __ZTIDs=Module["__ZTIDs"]=32324;var __ZTSPDs=Module["__ZTSPDs"]=32332;var __ZTIPDs=Module["__ZTIPDs"]=32336;var __ZTSPKDs=Module["__ZTSPKDs"]=32352;var __ZTIPKDs=Module["__ZTIPKDs"]=32360;var __ZTSDi=Module["__ZTSDi"]=32376;var __ZTIDi=Module["__ZTIDi"]=32380;var __ZTSPDi=Module["__ZTSPDi"]=32388;var __ZTIPDi=Module["__ZTIPDi"]=32392;var __ZTSPKDi=Module["__ZTSPKDi"]=32408;var __ZTIPKDi=Module["__ZTIPKDi"]=32416;var __ZTVN10__cxxabiv117__array_type_infoE=Module["__ZTVN10__cxxabiv117__array_type_infoE"]=32432;var __ZTIN10__cxxabiv117__array_type_infoE=Module["__ZTIN10__cxxabiv117__array_type_infoE"]=32496;var __ZTSN10__cxxabiv117__array_type_infoE=Module["__ZTSN10__cxxabiv117__array_type_infoE"]=32460;var __ZTVN10__cxxabiv120__function_type_infoE=Module["__ZTVN10__cxxabiv120__function_type_infoE"]=32508;var __ZTVN10__cxxabiv116__enum_type_infoE=Module["__ZTVN10__cxxabiv116__enum_type_infoE"]=32536;var __ZTIN10__cxxabiv116__enum_type_infoE=Module["__ZTIN10__cxxabiv116__enum_type_infoE"]=32600;var __ZTSN10__cxxabiv116__enum_type_infoE=Module["__ZTSN10__cxxabiv116__enum_type_infoE"]=32564;var __ZTIN10__cxxabiv120__si_class_type_infoE=Module["__ZTIN10__cxxabiv120__si_class_type_infoE"]=32732;var __ZTSN10__cxxabiv120__si_class_type_infoE=Module["__ZTSN10__cxxabiv120__si_class_type_infoE"]=32692;var __ZTIN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTIN10__cxxabiv121__vmi_class_type_infoE"]=32824;var __ZTSN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTSN10__cxxabiv121__vmi_class_type_infoE"]=32784;var __ZTVN10__cxxabiv117__pbase_type_infoE=Module["__ZTVN10__cxxabiv117__pbase_type_infoE"]=32836;var __ZTVN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTVN10__cxxabiv129__pointer_to_member_type_infoE"]=32892;var __ZTVSt9bad_alloc=Module["__ZTVSt9bad_alloc"]=32920;var __ZTVSt20bad_array_new_length=Module["__ZTVSt20bad_array_new_length"]=32940;var __ZTISt9bad_alloc=Module["__ZTISt9bad_alloc"]=33072;var __ZTSSt9exception=Module["__ZTSSt9exception"]=32980;var __ZTVSt13bad_exception=Module["__ZTVSt13bad_exception"]=33004;var __ZTISt13bad_exception=Module["__ZTISt13bad_exception"]=33044;var __ZTSSt13bad_exception=Module["__ZTSSt13bad_exception"]=33024;var __ZTSSt9bad_alloc=Module["__ZTSSt9bad_alloc"]=33056;var __ZTSSt20bad_array_new_length=Module["__ZTSSt20bad_array_new_length"]=33084;var __ZTISt11logic_error=Module["__ZTISt11logic_error"]=33220;var __ZTISt13runtime_error=Module["__ZTISt13runtime_error"]=33460;var __ZTVSt12domain_error=Module["__ZTVSt12domain_error"]=33164;var __ZTISt12domain_error=Module["__ZTISt12domain_error"]=33232;var __ZTSSt12domain_error=Module["__ZTSSt12domain_error"]=33184;var __ZTSSt11logic_error=Module["__ZTSSt11logic_error"]=33201;var __ZTVSt16invalid_argument=Module["__ZTVSt16invalid_argument"]=33244;var __ZTISt16invalid_argument=Module["__ZTISt16invalid_argument"]=33288;var __ZTSSt16invalid_argument=Module["__ZTSSt16invalid_argument"]=33264;var __ZTSSt12length_error=Module["__ZTSSt12length_error"]=33320;var __ZTSSt12out_of_range=Module["__ZTSSt12out_of_range"]=33372;var __ZTVSt11range_error=Module["__ZTVSt11range_error"]=33404;var __ZTISt11range_error=Module["__ZTISt11range_error"]=33472;var __ZTSSt11range_error=Module["__ZTSSt11range_error"]=33424;var __ZTSSt13runtime_error=Module["__ZTSSt13runtime_error"]=33440;var __ZTVSt14overflow_error=Module["__ZTVSt14overflow_error"]=33484;var __ZTISt14overflow_error=Module["__ZTISt14overflow_error"]=33524;var __ZTSSt14overflow_error=Module["__ZTSSt14overflow_error"]=33504;var __ZTVSt15underflow_error=Module["__ZTVSt15underflow_error"]=33536;var __ZTISt15underflow_error=Module["__ZTISt15underflow_error"]=33576;var __ZTSSt15underflow_error=Module["__ZTSSt15underflow_error"]=33556;var __ZTVSt8bad_cast=Module["__ZTVSt8bad_cast"]=33588;var __ZTVSt10bad_typeid=Module["__ZTVSt10bad_typeid"]=33608;var __ZTISt8bad_cast=Module["__ZTISt8bad_cast"]=33680;var __ZTISt10bad_typeid=Module["__ZTISt10bad_typeid"]=33708;var __ZTVSt9type_info=Module["__ZTVSt9type_info"]=33628;var __ZTSSt9type_info=Module["__ZTSSt9type_info"]=33644;var __ZTSSt8bad_cast=Module["__ZTSSt8bad_cast"]=33668;var __ZTSSt10bad_typeid=Module["__ZTSSt10bad_typeid"]=33692;var calledRun;dependenciesFulfilled=function runCaller(){if(!calledRun)run();if(!calledRun)dependenciesFulfilled=runCaller};function run(){if(runDependencies>0){return}preRun();if(runDependencies>0){return}function doRun(){if(calledRun)return;calledRun=true;Module["calledRun"]=true;if(ABORT)return;initRuntime();Module["onRuntimeInitialized"]?.();postRun()}if(Module["setStatus"]){Module["setStatus"]("Running...");setTimeout(function(){setTimeout(function(){Module["setStatus"]("")},1);doRun()},1)}else{doRun()}}if(Module["preInit"]){if(typeof Module["preInit"]=="function")Module["preInit"]=[Module["preInit"]];while(Module["preInit"].length>0){Module["preInit"].pop()()}}run(); +var Module=typeof Module!="undefined"?Module:{};var ENVIRONMENT_IS_WEB=typeof window=="object";var ENVIRONMENT_IS_WORKER=typeof importScripts=="function";var ENVIRONMENT_IS_NODE=typeof process=="object"&&typeof process.versions=="object"&&typeof process.versions.node=="string";if(ENVIRONMENT_IS_NODE){}var moduleOverrides=Object.assign({},Module);var arguments_=[];var thisProgram="./this.program";var quit_=(status,toThrow)=>{throw toThrow};var scriptDirectory="";function locateFile(path){if(Module["locateFile"]){return Module["locateFile"](path,scriptDirectory)}return scriptDirectory+path}var readAsync,readBinary;if(ENVIRONMENT_IS_NODE){var fs=require("fs");var nodePath=require("path");scriptDirectory=__dirname+"/";readBinary=filename=>{filename=isFileURI(filename)?new URL(filename):nodePath.normalize(filename);var ret=fs.readFileSync(filename);return ret};readAsync=(filename,binary=true)=>{filename=isFileURI(filename)?new URL(filename):nodePath.normalize(filename);return new Promise((resolve,reject)=>{fs.readFile(filename,binary?undefined:"utf8",(err,data)=>{if(err)reject(err);else resolve(binary?data.buffer:data)})})};if(!Module["thisProgram"]&&process.argv.length>1){thisProgram=process.argv[1].replace(/\\/g,"/")}arguments_=process.argv.slice(2);if(typeof module!="undefined"){module["exports"]=Module}process.on("uncaughtException",ex=>{if(ex!=="unwind"&&!(ex instanceof ExitStatus)&&!(ex.context instanceof ExitStatus)){throw ex}});quit_=(status,toThrow)=>{process.exitCode=status;throw toThrow}}else if(ENVIRONMENT_IS_WEB||ENVIRONMENT_IS_WORKER){if(ENVIRONMENT_IS_WORKER){scriptDirectory=self.location.href}else if(typeof document!="undefined"&&document.currentScript){scriptDirectory=document.currentScript.src}if(scriptDirectory.startsWith("blob:")){scriptDirectory=""}else{scriptDirectory=scriptDirectory.substr(0,scriptDirectory.replace(/[?#].*/,"").lastIndexOf("/")+1)}{if(ENVIRONMENT_IS_WORKER){readBinary=url=>{var xhr=new XMLHttpRequest;xhr.open("GET",url,false);xhr.responseType="arraybuffer";xhr.send(null);return new Uint8Array(xhr.response)}}readAsync=url=>{if(isFileURI(url)){return new Promise((reject,resolve)=>{var xhr=new XMLHttpRequest;xhr.open("GET",url,true);xhr.responseType="arraybuffer";xhr.onload=()=>{if(xhr.status==200||xhr.status==0&&xhr.response){resolve(xhr.response)}reject(xhr.status)};xhr.onerror=reject;xhr.send(null)})}return fetch(url,{credentials:"same-origin"}).then(response=>{if(response.ok){return response.arrayBuffer()}return Promise.reject(new Error(response.status+" : "+response.url))})}}}else{}var out=Module["print"]||console.log.bind(console);var err=Module["printErr"]||console.error.bind(console);Object.assign(Module,moduleOverrides);moduleOverrides=null;if(Module["arguments"])arguments_=Module["arguments"];if(Module["thisProgram"])thisProgram=Module["thisProgram"];if(Module["quit"])quit_=Module["quit"];var wasmBinary;if(Module["wasmBinary"])wasmBinary=Module["wasmBinary"];var wasmMemory;var ABORT=false;var EXITSTATUS;var HEAP8,HEAPU8,HEAP16,HEAPU16,HEAP32,HEAPU32,HEAPF32,HEAPF64;function updateMemoryViews(){var b=wasmMemory.buffer;Module["HEAP8"]=HEAP8=new Int8Array(b);Module["HEAP16"]=HEAP16=new Int16Array(b);Module["HEAPU8"]=HEAPU8=new Uint8Array(b);Module["HEAPU16"]=HEAPU16=new Uint16Array(b);Module["HEAP32"]=HEAP32=new Int32Array(b);Module["HEAPU32"]=HEAPU32=new Uint32Array(b);Module["HEAPF32"]=HEAPF32=new Float32Array(b);Module["HEAPF64"]=HEAPF64=new Float64Array(b)}var __ATPRERUN__=[];var __ATINIT__=[];var __ATPOSTRUN__=[];var runtimeInitialized=false;function preRun(){if(Module["preRun"]){if(typeof Module["preRun"]=="function")Module["preRun"]=[Module["preRun"]];while(Module["preRun"].length){addOnPreRun(Module["preRun"].shift())}}callRuntimeCallbacks(__ATPRERUN__)}function initRuntime(){runtimeInitialized=true;callRuntimeCallbacks(__ATINIT__)}function postRun(){if(Module["postRun"]){if(typeof Module["postRun"]=="function")Module["postRun"]=[Module["postRun"]];while(Module["postRun"].length){addOnPostRun(Module["postRun"].shift())}}callRuntimeCallbacks(__ATPOSTRUN__)}function addOnPreRun(cb){__ATPRERUN__.unshift(cb)}function addOnInit(cb){__ATINIT__.unshift(cb)}function addOnPostRun(cb){__ATPOSTRUN__.unshift(cb)}var runDependencies=0;var runDependencyWatcher=null;var dependenciesFulfilled=null;function addRunDependency(id){runDependencies++;Module["monitorRunDependencies"]?.(runDependencies)}function removeRunDependency(id){runDependencies--;Module["monitorRunDependencies"]?.(runDependencies);if(runDependencies==0){if(runDependencyWatcher!==null){clearInterval(runDependencyWatcher);runDependencyWatcher=null}if(dependenciesFulfilled){var callback=dependenciesFulfilled;dependenciesFulfilled=null;callback()}}}function abort(what){Module["onAbort"]?.(what);what="Aborted("+what+")";err(what);ABORT=true;EXITSTATUS=1;what+=". Build with -sASSERTIONS for more info.";var e=new WebAssembly.RuntimeError(what);throw e}var dataURIPrefix="data:application/octet-stream;base64,";var isDataURI=filename=>filename.startsWith(dataURIPrefix);var isFileURI=filename=>filename.startsWith("file://");function findWasmBinary(){var f="index.wasm";if(!isDataURI(f)){return locateFile(f)}return f}var wasmBinaryFile;function getBinarySync(file){if(file==wasmBinaryFile&&wasmBinary){return new Uint8Array(wasmBinary)}if(readBinary){return readBinary(file)}throw"both async and sync fetching of the wasm failed"}function getBinaryPromise(binaryFile){if(!wasmBinary){return readAsync(binaryFile).then(response=>new Uint8Array(response),()=>getBinarySync(binaryFile))}return Promise.resolve().then(()=>getBinarySync(binaryFile))}function instantiateArrayBuffer(binaryFile,imports,receiver){return getBinaryPromise(binaryFile).then(binary=>WebAssembly.instantiate(binary,imports)).then(receiver,reason=>{err(`failed to asynchronously prepare wasm: ${reason}`);abort(reason)})}function instantiateAsync(binary,binaryFile,imports,callback){if(!binary&&typeof WebAssembly.instantiateStreaming=="function"&&!isDataURI(binaryFile)&&!isFileURI(binaryFile)&&!ENVIRONMENT_IS_NODE&&typeof fetch=="function"){return fetch(binaryFile,{credentials:"same-origin"}).then(response=>{var result=WebAssembly.instantiateStreaming(response,imports);return result.then(callback,function(reason){err(`wasm streaming compile failed: ${reason}`);err("falling back to ArrayBuffer instantiation");return instantiateArrayBuffer(binaryFile,imports,callback)})})}return instantiateArrayBuffer(binaryFile,imports,callback)}function getWasmImports(){return{a:wasmImports}}function createWasm(){var info=getWasmImports();function receiveInstance(instance,module){wasmExports=instance.exports;wasmMemory=wasmExports["w"];updateMemoryViews();wasmTable=wasmExports["C"];addOnInit(wasmExports["x"]);removeRunDependency("wasm-instantiate");return wasmExports}addRunDependency("wasm-instantiate");function receiveInstantiationResult(result){receiveInstance(result["instance"])}if(Module["instantiateWasm"]){try{return Module["instantiateWasm"](info,receiveInstance)}catch(e){err(`Module.instantiateWasm callback failed with error: ${e}`);return false}}if(!wasmBinaryFile)wasmBinaryFile=findWasmBinary();instantiateAsync(wasmBinary,wasmBinaryFile,info,receiveInstantiationResult);return{}}function ExitStatus(status){this.name="ExitStatus";this.message=`Program terminated with exit(${status})`;this.status=status}var callRuntimeCallbacks=callbacks=>{while(callbacks.length>0){callbacks.shift()(Module)}};var noExitRuntime=Module["noExitRuntime"]||true;class ExceptionInfo{constructor(excPtr){this.excPtr=excPtr;this.ptr=excPtr-24}set_type(type){HEAPU32[this.ptr+4>>2]=type}get_type(){return HEAPU32[this.ptr+4>>2]}set_destructor(destructor){HEAPU32[this.ptr+8>>2]=destructor}get_destructor(){return HEAPU32[this.ptr+8>>2]}set_caught(caught){caught=caught?1:0;HEAP8[this.ptr+12]=caught}get_caught(){return HEAP8[this.ptr+12]!=0}set_rethrown(rethrown){rethrown=rethrown?1:0;HEAP8[this.ptr+13]=rethrown}get_rethrown(){return HEAP8[this.ptr+13]!=0}init(type,destructor){this.set_adjusted_ptr(0);this.set_type(type);this.set_destructor(destructor)}set_adjusted_ptr(adjustedPtr){HEAPU32[this.ptr+16>>2]=adjustedPtr}get_adjusted_ptr(){return HEAPU32[this.ptr+16>>2]}get_exception_ptr(){var isPointer=___cxa_is_pointer_type(this.get_type());if(isPointer){return HEAPU32[this.excPtr>>2]}var adjusted=this.get_adjusted_ptr();if(adjusted!==0)return adjusted;return this.excPtr}}var exceptionLast=0;var uncaughtExceptionCount=0;var ___cxa_throw=(ptr,type,destructor)=>{var info=new ExceptionInfo(ptr);info.init(type,destructor);exceptionLast=ptr;uncaughtExceptionCount++;throw exceptionLast};var __abort_js=()=>{abort("")};var __embind_register_bigint=(primitiveType,name,size,minRange,maxRange)=>{};var embind_init_charCodes=()=>{var codes=new Array(256);for(var i=0;i<256;++i){codes[i]=String.fromCharCode(i)}embind_charCodes=codes};var embind_charCodes;var readLatin1String=ptr=>{var ret="";var c=ptr;while(HEAPU8[c]){ret+=embind_charCodes[HEAPU8[c++]]}return ret};var awaitingDependencies={};var registeredTypes={};var typeDependencies={};var BindingError;var throwBindingError=message=>{throw new BindingError(message)};var InternalError;var throwInternalError=message=>{throw new InternalError(message)};var whenDependentTypesAreResolved=(myTypes,dependentTypes,getTypeConverters)=>{myTypes.forEach(function(type){typeDependencies[type]=dependentTypes});function onComplete(typeConverters){var myTypeConverters=getTypeConverters(typeConverters);if(myTypeConverters.length!==myTypes.length){throwInternalError("Mismatched type converter count")}for(var i=0;i{if(registeredTypes.hasOwnProperty(dt)){typeConverters[i]=registeredTypes[dt]}else{unregisteredTypes.push(dt);if(!awaitingDependencies.hasOwnProperty(dt)){awaitingDependencies[dt]=[]}awaitingDependencies[dt].push(()=>{typeConverters[i]=registeredTypes[dt];++registered;if(registered===unregisteredTypes.length){onComplete(typeConverters)}})}});if(0===unregisteredTypes.length){onComplete(typeConverters)}};function sharedRegisterType(rawType,registeredInstance,options={}){var name=registeredInstance.name;if(!rawType){throwBindingError(`type "${name}" must have a positive integer typeid pointer`)}if(registeredTypes.hasOwnProperty(rawType)){if(options.ignoreDuplicateRegistrations){return}else{throwBindingError(`Cannot register type '${name}' twice`)}}registeredTypes[rawType]=registeredInstance;delete typeDependencies[rawType];if(awaitingDependencies.hasOwnProperty(rawType)){var callbacks=awaitingDependencies[rawType];delete awaitingDependencies[rawType];callbacks.forEach(cb=>cb())}}function registerType(rawType,registeredInstance,options={}){if(!("argPackAdvance"in registeredInstance)){throw new TypeError("registerType registeredInstance requires argPackAdvance")}return sharedRegisterType(rawType,registeredInstance,options)}var GenericWireTypeSize=8;var __embind_register_bool=(rawType,name,trueValue,falseValue)=>{name=readLatin1String(name);registerType(rawType,{name:name,fromWireType:function(wt){return!!wt},toWireType:function(destructors,o){return o?trueValue:falseValue},argPackAdvance:GenericWireTypeSize,readValueFromPointer:function(pointer){return this["fromWireType"](HEAPU8[pointer])},destructorFunction:null})};var shallowCopyInternalPointer=o=>({count:o.count,deleteScheduled:o.deleteScheduled,preservePointerOnDelete:o.preservePointerOnDelete,ptr:o.ptr,ptrType:o.ptrType,smartPtr:o.smartPtr,smartPtrType:o.smartPtrType});var throwInstanceAlreadyDeleted=obj=>{function getInstanceTypeName(handle){return handle.$$.ptrType.registeredClass.name}throwBindingError(getInstanceTypeName(obj)+" instance already deleted")};var finalizationRegistry=false;var detachFinalizer=handle=>{};var runDestructor=$$=>{if($$.smartPtr){$$.smartPtrType.rawDestructor($$.smartPtr)}else{$$.ptrType.registeredClass.rawDestructor($$.ptr)}};var releaseClassHandle=$$=>{$$.count.value-=1;var toDelete=0===$$.count.value;if(toDelete){runDestructor($$)}};var downcastPointer=(ptr,ptrClass,desiredClass)=>{if(ptrClass===desiredClass){return ptr}if(undefined===desiredClass.baseClass){return null}var rv=downcastPointer(ptr,ptrClass,desiredClass.baseClass);if(rv===null){return null}return desiredClass.downcast(rv)};var registeredPointers={};var getInheritedInstanceCount=()=>Object.keys(registeredInstances).length;var getLiveInheritedInstances=()=>{var rv=[];for(var k in registeredInstances){if(registeredInstances.hasOwnProperty(k)){rv.push(registeredInstances[k])}}return rv};var deletionQueue=[];var flushPendingDeletes=()=>{while(deletionQueue.length){var obj=deletionQueue.pop();obj.$$.deleteScheduled=false;obj["delete"]()}};var delayFunction;var setDelayFunction=fn=>{delayFunction=fn;if(deletionQueue.length&&delayFunction){delayFunction(flushPendingDeletes)}};var init_embind=()=>{Module["getInheritedInstanceCount"]=getInheritedInstanceCount;Module["getLiveInheritedInstances"]=getLiveInheritedInstances;Module["flushPendingDeletes"]=flushPendingDeletes;Module["setDelayFunction"]=setDelayFunction};var registeredInstances={};var getBasestPointer=(class_,ptr)=>{if(ptr===undefined){throwBindingError("ptr should not be undefined")}while(class_.baseClass){ptr=class_.upcast(ptr);class_=class_.baseClass}return ptr};var getInheritedInstance=(class_,ptr)=>{ptr=getBasestPointer(class_,ptr);return registeredInstances[ptr]};var makeClassHandle=(prototype,record)=>{if(!record.ptrType||!record.ptr){throwInternalError("makeClassHandle requires ptr and ptrType")}var hasSmartPtrType=!!record.smartPtrType;var hasSmartPtr=!!record.smartPtr;if(hasSmartPtrType!==hasSmartPtr){throwInternalError("Both smartPtrType and smartPtr must be specified")}record.count={value:1};return attachFinalizer(Object.create(prototype,{$$:{value:record,writable:true}}))};function RegisteredPointer_fromWireType(ptr){var rawPointer=this.getPointee(ptr);if(!rawPointer){this.destructor(ptr);return null}var registeredInstance=getInheritedInstance(this.registeredClass,rawPointer);if(undefined!==registeredInstance){if(0===registeredInstance.$$.count.value){registeredInstance.$$.ptr=rawPointer;registeredInstance.$$.smartPtr=ptr;return registeredInstance["clone"]()}else{var rv=registeredInstance["clone"]();this.destructor(ptr);return rv}}function makeDefaultHandle(){if(this.isSmartPointer){return makeClassHandle(this.registeredClass.instancePrototype,{ptrType:this.pointeeType,ptr:rawPointer,smartPtrType:this,smartPtr:ptr})}else{return makeClassHandle(this.registeredClass.instancePrototype,{ptrType:this,ptr:ptr})}}var actualType=this.registeredClass.getActualType(rawPointer);var registeredPointerRecord=registeredPointers[actualType];if(!registeredPointerRecord){return makeDefaultHandle.call(this)}var toType;if(this.isConst){toType=registeredPointerRecord.constPointerType}else{toType=registeredPointerRecord.pointerType}var dp=downcastPointer(rawPointer,this.registeredClass,toType.registeredClass);if(dp===null){return makeDefaultHandle.call(this)}if(this.isSmartPointer){return makeClassHandle(toType.registeredClass.instancePrototype,{ptrType:toType,ptr:dp,smartPtrType:this,smartPtr:ptr})}else{return makeClassHandle(toType.registeredClass.instancePrototype,{ptrType:toType,ptr:dp})}}var attachFinalizer=handle=>{if("undefined"===typeof FinalizationRegistry){attachFinalizer=handle=>handle;return handle}finalizationRegistry=new FinalizationRegistry(info=>{releaseClassHandle(info.$$)});attachFinalizer=handle=>{var $$=handle.$$;var hasSmartPtr=!!$$.smartPtr;if(hasSmartPtr){var info={$$:$$};finalizationRegistry.register(handle,info,handle)}return handle};detachFinalizer=handle=>finalizationRegistry.unregister(handle);return attachFinalizer(handle)};var init_ClassHandle=()=>{Object.assign(ClassHandle.prototype,{isAliasOf(other){if(!(this instanceof ClassHandle)){return false}if(!(other instanceof ClassHandle)){return false}var leftClass=this.$$.ptrType.registeredClass;var left=this.$$.ptr;other.$$=other.$$;var rightClass=other.$$.ptrType.registeredClass;var right=other.$$.ptr;while(leftClass.baseClass){left=leftClass.upcast(left);leftClass=leftClass.baseClass}while(rightClass.baseClass){right=rightClass.upcast(right);rightClass=rightClass.baseClass}return leftClass===rightClass&&left===right},clone(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.preservePointerOnDelete){this.$$.count.value+=1;return this}else{var clone=attachFinalizer(Object.create(Object.getPrototypeOf(this),{$$:{value:shallowCopyInternalPointer(this.$$)}}));clone.$$.count.value+=1;clone.$$.deleteScheduled=false;return clone}},delete(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.deleteScheduled&&!this.$$.preservePointerOnDelete){throwBindingError("Object already scheduled for deletion")}detachFinalizer(this);releaseClassHandle(this.$$);if(!this.$$.preservePointerOnDelete){this.$$.smartPtr=undefined;this.$$.ptr=undefined}},isDeleted(){return!this.$$.ptr},deleteLater(){if(!this.$$.ptr){throwInstanceAlreadyDeleted(this)}if(this.$$.deleteScheduled&&!this.$$.preservePointerOnDelete){throwBindingError("Object already scheduled for deletion")}deletionQueue.push(this);if(deletionQueue.length===1&&delayFunction){delayFunction(flushPendingDeletes)}this.$$.deleteScheduled=true;return this}})};function ClassHandle(){}var createNamedFunction=(name,body)=>Object.defineProperty(body,"name",{value:name});var ensureOverloadTable=(proto,methodName,humanName)=>{if(undefined===proto[methodName].overloadTable){var prevFunc=proto[methodName];proto[methodName]=function(...args){if(!proto[methodName].overloadTable.hasOwnProperty(args.length)){throwBindingError(`Function '${humanName}' called with an invalid number of arguments (${args.length}) - expects one of (${proto[methodName].overloadTable})!`)}return proto[methodName].overloadTable[args.length].apply(this,args)};proto[methodName].overloadTable=[];proto[methodName].overloadTable[prevFunc.argCount]=prevFunc}};var exposePublicSymbol=(name,value,numArguments)=>{if(Module.hasOwnProperty(name)){if(undefined===numArguments||undefined!==Module[name].overloadTable&&undefined!==Module[name].overloadTable[numArguments]){throwBindingError(`Cannot register public name '${name}' twice`)}ensureOverloadTable(Module,name,name);if(Module.hasOwnProperty(numArguments)){throwBindingError(`Cannot register multiple overloads of a function with the same number of arguments (${numArguments})!`)}Module[name].overloadTable[numArguments]=value}else{Module[name]=value;if(undefined!==numArguments){Module[name].numArguments=numArguments}}};var char_0=48;var char_9=57;var makeLegalFunctionName=name=>{if(undefined===name){return"_unknown"}name=name.replace(/[^a-zA-Z0-9_]/g,"$");var f=name.charCodeAt(0);if(f>=char_0&&f<=char_9){return`_${name}`}return name};function RegisteredClass(name,constructor,instancePrototype,rawDestructor,baseClass,getActualType,upcast,downcast){this.name=name;this.constructor=constructor;this.instancePrototype=instancePrototype;this.rawDestructor=rawDestructor;this.baseClass=baseClass;this.getActualType=getActualType;this.upcast=upcast;this.downcast=downcast;this.pureVirtualFunctions=[]}var upcastPointer=(ptr,ptrClass,desiredClass)=>{while(ptrClass!==desiredClass){if(!ptrClass.upcast){throwBindingError(`Expected null or instance of ${desiredClass.name}, got an instance of ${ptrClass.name}`)}ptr=ptrClass.upcast(ptr);ptrClass=ptrClass.baseClass}return ptr};function constNoSmartPtrRawPointerToWireType(destructors,handle){if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}return 0}if(!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;var ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);return ptr}function genericPointerToWireType(destructors,handle){var ptr;if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}if(this.isSmartPointer){ptr=this.rawConstructor();if(destructors!==null){destructors.push(this.rawDestructor,ptr)}return ptr}else{return 0}}if(!handle||!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}if(!this.isConst&&handle.$$.ptrType.isConst){throwBindingError(`Cannot convert argument of type ${handle.$$.smartPtrType?handle.$$.smartPtrType.name:handle.$$.ptrType.name} to parameter type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);if(this.isSmartPointer){if(undefined===handle.$$.smartPtr){throwBindingError("Passing raw pointer to smart pointer is illegal")}switch(this.sharingPolicy){case 0:if(handle.$$.smartPtrType===this){ptr=handle.$$.smartPtr}else{throwBindingError(`Cannot convert argument of type ${handle.$$.smartPtrType?handle.$$.smartPtrType.name:handle.$$.ptrType.name} to parameter type ${this.name}`)}break;case 1:ptr=handle.$$.smartPtr;break;case 2:if(handle.$$.smartPtrType===this){ptr=handle.$$.smartPtr}else{var clonedHandle=handle["clone"]();ptr=this.rawShare(ptr,Emval.toHandle(()=>clonedHandle["delete"]()));if(destructors!==null){destructors.push(this.rawDestructor,ptr)}}break;default:throwBindingError("Unsupporting sharing policy")}}return ptr}function nonConstNoSmartPtrRawPointerToWireType(destructors,handle){if(handle===null){if(this.isReference){throwBindingError(`null is not a valid ${this.name}`)}return 0}if(!handle.$$){throwBindingError(`Cannot pass "${embindRepr(handle)}" as a ${this.name}`)}if(!handle.$$.ptr){throwBindingError(`Cannot pass deleted object as a pointer of type ${this.name}`)}if(handle.$$.ptrType.isConst){throwBindingError(`Cannot convert argument of type ${handle.$$.ptrType.name} to parameter type ${this.name}`)}var handleClass=handle.$$.ptrType.registeredClass;var ptr=upcastPointer(handle.$$.ptr,handleClass,this.registeredClass);return ptr}function readPointer(pointer){return this["fromWireType"](HEAPU32[pointer>>2])}var init_RegisteredPointer=()=>{Object.assign(RegisteredPointer.prototype,{getPointee(ptr){if(this.rawGetPointee){ptr=this.rawGetPointee(ptr)}return ptr},destructor(ptr){this.rawDestructor?.(ptr)},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,fromWireType:RegisteredPointer_fromWireType})};function RegisteredPointer(name,registeredClass,isReference,isConst,isSmartPointer,pointeeType,sharingPolicy,rawGetPointee,rawConstructor,rawShare,rawDestructor){this.name=name;this.registeredClass=registeredClass;this.isReference=isReference;this.isConst=isConst;this.isSmartPointer=isSmartPointer;this.pointeeType=pointeeType;this.sharingPolicy=sharingPolicy;this.rawGetPointee=rawGetPointee;this.rawConstructor=rawConstructor;this.rawShare=rawShare;this.rawDestructor=rawDestructor;if(!isSmartPointer&®isteredClass.baseClass===undefined){if(isConst){this["toWireType"]=constNoSmartPtrRawPointerToWireType;this.destructorFunction=null}else{this["toWireType"]=nonConstNoSmartPtrRawPointerToWireType;this.destructorFunction=null}}else{this["toWireType"]=genericPointerToWireType}}var replacePublicSymbol=(name,value,numArguments)=>{if(!Module.hasOwnProperty(name)){throwInternalError("Replacing nonexistent public symbol")}if(undefined!==Module[name].overloadTable&&undefined!==numArguments){Module[name].overloadTable[numArguments]=value}else{Module[name]=value;Module[name].argCount=numArguments}};var dynCallLegacy=(sig,ptr,args)=>{sig=sig.replace(/p/g,"i");var f=Module["dynCall_"+sig];return f(ptr,...args)};var wasmTableMirror=[];var wasmTable;var getWasmTableEntry=funcPtr=>{var func=wasmTableMirror[funcPtr];if(!func){if(funcPtr>=wasmTableMirror.length)wasmTableMirror.length=funcPtr+1;wasmTableMirror[funcPtr]=func=wasmTable.get(funcPtr)}return func};var dynCall=(sig,ptr,args=[])=>{if(sig.includes("j")){return dynCallLegacy(sig,ptr,args)}var rtn=getWasmTableEntry(ptr)(...args);return rtn};var getDynCaller=(sig,ptr)=>(...args)=>dynCall(sig,ptr,args);var embind__requireFunction=(signature,rawFunction)=>{signature=readLatin1String(signature);function makeDynCaller(){if(signature.includes("j")){return getDynCaller(signature,rawFunction)}return getWasmTableEntry(rawFunction)}var fp=makeDynCaller();if(typeof fp!="function"){throwBindingError(`unknown function pointer with signature ${signature}: ${rawFunction}`)}return fp};var extendError=(baseErrorType,errorName)=>{var errorClass=createNamedFunction(errorName,function(message){this.name=errorName;this.message=message;var stack=new Error(message).stack;if(stack!==undefined){this.stack=this.toString()+"\n"+stack.replace(/^Error(:[^\n]*)?\n/,"")}});errorClass.prototype=Object.create(baseErrorType.prototype);errorClass.prototype.constructor=errorClass;errorClass.prototype.toString=function(){if(this.message===undefined){return this.name}else{return`${this.name}: ${this.message}`}};return errorClass};var UnboundTypeError;var getTypeName=type=>{var ptr=___getTypeName(type);var rv=readLatin1String(ptr);_free(ptr);return rv};var throwUnboundTypeError=(message,types)=>{var unboundTypes=[];var seen={};function visit(type){if(seen[type]){return}if(registeredTypes[type]){return}if(typeDependencies[type]){typeDependencies[type].forEach(visit);return}unboundTypes.push(type);seen[type]=true}types.forEach(visit);throw new UnboundTypeError(`${message}: `+unboundTypes.map(getTypeName).join([", "]))};var __embind_register_class=(rawType,rawPointerType,rawConstPointerType,baseClassRawType,getActualTypeSignature,getActualType,upcastSignature,upcast,downcastSignature,downcast,name,destructorSignature,rawDestructor)=>{name=readLatin1String(name);getActualType=embind__requireFunction(getActualTypeSignature,getActualType);upcast&&=embind__requireFunction(upcastSignature,upcast);downcast&&=embind__requireFunction(downcastSignature,downcast);rawDestructor=embind__requireFunction(destructorSignature,rawDestructor);var legalFunctionName=makeLegalFunctionName(name);exposePublicSymbol(legalFunctionName,function(){throwUnboundTypeError(`Cannot construct ${name} due to unbound types`,[baseClassRawType])});whenDependentTypesAreResolved([rawType,rawPointerType,rawConstPointerType],baseClassRawType?[baseClassRawType]:[],base=>{base=base[0];var baseClass;var basePrototype;if(baseClassRawType){baseClass=base.registeredClass;basePrototype=baseClass.instancePrototype}else{basePrototype=ClassHandle.prototype}var constructor=createNamedFunction(name,function(...args){if(Object.getPrototypeOf(this)!==instancePrototype){throw new BindingError("Use 'new' to construct "+name)}if(undefined===registeredClass.constructor_body){throw new BindingError(name+" has no accessible constructor")}var body=registeredClass.constructor_body[args.length];if(undefined===body){throw new BindingError(`Tried to invoke ctor of ${name} with invalid number of parameters (${args.length}) - expected (${Object.keys(registeredClass.constructor_body).toString()}) parameters instead!`)}return body.apply(this,args)});var instancePrototype=Object.create(basePrototype,{constructor:{value:constructor}});constructor.prototype=instancePrototype;var registeredClass=new RegisteredClass(name,constructor,instancePrototype,rawDestructor,baseClass,getActualType,upcast,downcast);if(registeredClass.baseClass){registeredClass.baseClass.__derivedClasses??=[];registeredClass.baseClass.__derivedClasses.push(registeredClass)}var referenceConverter=new RegisteredPointer(name,registeredClass,true,false,false);var pointerConverter=new RegisteredPointer(name+"*",registeredClass,false,false,false);var constPointerConverter=new RegisteredPointer(name+" const*",registeredClass,false,true,false);registeredPointers[rawType]={pointerType:pointerConverter,constPointerType:constPointerConverter};replacePublicSymbol(legalFunctionName,constructor);return[referenceConverter,pointerConverter,constPointerConverter]})};var heap32VectorToArray=(count,firstElement)=>{var array=[];for(var i=0;i>2])}return array};var runDestructors=destructors=>{while(destructors.length){var ptr=destructors.pop();var del=destructors.pop();del(ptr)}};function usesDestructorStack(argTypes){for(var i=1;i0?", ":"")+argsListWired}invokerFnBody+=(returns||isAsync?"var rv = ":"")+"invoker(fn"+(argsListWired.length>0?", ":"")+argsListWired+");\n";if(needsDestructorStack){invokerFnBody+="runDestructors(destructors);\n"}else{for(var i=isClassMethodFunc?1:2;i{var rawArgTypes=heap32VectorToArray(argCount,rawArgTypesAddr);invoker=embind__requireFunction(invokerSignature,invoker);whenDependentTypesAreResolved([],[rawClassType],classType=>{classType=classType[0];var humanName=`constructor ${classType.name}`;if(undefined===classType.registeredClass.constructor_body){classType.registeredClass.constructor_body=[]}if(undefined!==classType.registeredClass.constructor_body[argCount-1]){throw new BindingError(`Cannot register multiple constructors with identical number of parameters (${argCount-1}) for class '${classType.name}'! Overload resolution is currently only performed using the parameter count, not actual type info!`)}classType.registeredClass.constructor_body[argCount-1]=()=>{throwUnboundTypeError(`Cannot construct ${classType.name} due to unbound types`,rawArgTypes)};whenDependentTypesAreResolved([],rawArgTypes,argTypes=>{argTypes.splice(1,0,null);classType.registeredClass.constructor_body[argCount-1]=craftInvokerFunction(humanName,argTypes,null,invoker,rawConstructor);return[]});return[]})};var getFunctionName=signature=>{signature=signature.trim();const argsIndex=signature.indexOf("(");if(argsIndex!==-1){return signature.substr(0,argsIndex)}else{return signature}};var __embind_register_class_function=(rawClassType,methodName,argCount,rawArgTypesAddr,invokerSignature,rawInvoker,context,isPureVirtual,isAsync)=>{var rawArgTypes=heap32VectorToArray(argCount,rawArgTypesAddr);methodName=readLatin1String(methodName);methodName=getFunctionName(methodName);rawInvoker=embind__requireFunction(invokerSignature,rawInvoker);whenDependentTypesAreResolved([],[rawClassType],classType=>{classType=classType[0];var humanName=`${classType.name}.${methodName}`;if(methodName.startsWith("@@")){methodName=Symbol[methodName.substring(2)]}if(isPureVirtual){classType.registeredClass.pureVirtualFunctions.push(methodName)}function unboundTypesHandler(){throwUnboundTypeError(`Cannot call ${humanName} due to unbound types`,rawArgTypes)}var proto=classType.registeredClass.instancePrototype;var method=proto[methodName];if(undefined===method||undefined===method.overloadTable&&method.className!==classType.name&&method.argCount===argCount-2){unboundTypesHandler.argCount=argCount-2;unboundTypesHandler.className=classType.name;proto[methodName]=unboundTypesHandler}else{ensureOverloadTable(proto,methodName,humanName);proto[methodName].overloadTable[argCount-2]=unboundTypesHandler}whenDependentTypesAreResolved([],rawArgTypes,argTypes=>{var memberFunction=craftInvokerFunction(humanName,argTypes,classType,rawInvoker,context,isAsync);if(undefined===proto[methodName].overloadTable){memberFunction.argCount=argCount-2;proto[methodName]=memberFunction}else{proto[methodName].overloadTable[argCount-2]=memberFunction}return[]});return[]})};var validateThis=(this_,classType,humanName)=>{if(!(this_ instanceof Object)){throwBindingError(`${humanName} with invalid "this": ${this_}`)}if(!(this_ instanceof classType.registeredClass.constructor)){throwBindingError(`${humanName} incompatible with "this" of type ${this_.constructor.name}`)}if(!this_.$$.ptr){throwBindingError(`cannot call emscripten binding method ${humanName} on deleted object`)}return upcastPointer(this_.$$.ptr,this_.$$.ptrType.registeredClass,classType.registeredClass)};var __embind_register_class_property=(classType,fieldName,getterReturnType,getterSignature,getter,getterContext,setterArgumentType,setterSignature,setter,setterContext)=>{fieldName=readLatin1String(fieldName);getter=embind__requireFunction(getterSignature,getter);whenDependentTypesAreResolved([],[classType],classType=>{classType=classType[0];var humanName=`${classType.name}.${fieldName}`;var desc={get(){throwUnboundTypeError(`Cannot access ${humanName} due to unbound types`,[getterReturnType,setterArgumentType])},enumerable:true,configurable:true};if(setter){desc.set=()=>throwUnboundTypeError(`Cannot access ${humanName} due to unbound types`,[getterReturnType,setterArgumentType])}else{desc.set=v=>throwBindingError(humanName+" is a read-only property")}Object.defineProperty(classType.registeredClass.instancePrototype,fieldName,desc);whenDependentTypesAreResolved([],setter?[getterReturnType,setterArgumentType]:[getterReturnType],types=>{var getterReturnType=types[0];var desc={get(){var ptr=validateThis(this,classType,humanName+" getter");return getterReturnType["fromWireType"](getter(getterContext,ptr))},enumerable:true};if(setter){setter=embind__requireFunction(setterSignature,setter);var setterArgumentType=types[1];desc.set=function(v){var ptr=validateThis(this,classType,humanName+" setter");var destructors=[];setter(setterContext,ptr,setterArgumentType["toWireType"](destructors,v));runDestructors(destructors)}}Object.defineProperty(classType.registeredClass.instancePrototype,fieldName,desc);return[]});return[]})};var emval_freelist=[];var emval_handles=[];var __emval_decref=handle=>{if(handle>9&&0===--emval_handles[handle+1]){emval_handles[handle]=undefined;emval_freelist.push(handle)}};var count_emval_handles=()=>emval_handles.length/2-5-emval_freelist.length;var init_emval=()=>{emval_handles.push(0,1,undefined,1,null,1,true,1,false,1);Module["count_emval_handles"]=count_emval_handles};var Emval={toValue:handle=>{if(!handle){throwBindingError("Cannot use deleted val. handle = "+handle)}return emval_handles[handle]},toHandle:value=>{switch(value){case undefined:return 2;case null:return 4;case true:return 6;case false:return 8;default:{const handle=emval_freelist.pop()||emval_handles.length;emval_handles[handle]=value;emval_handles[handle+1]=1;return handle}}}};var EmValType={name:"emscripten::val",fromWireType:handle=>{var rv=Emval.toValue(handle);__emval_decref(handle);return rv},toWireType:(destructors,value)=>Emval.toHandle(value),argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction:null};var __embind_register_emval=rawType=>registerType(rawType,EmValType);var embindRepr=v=>{if(v===null){return"null"}var t=typeof v;if(t==="object"||t==="array"||t==="function"){return v.toString()}else{return""+v}};var floatReadValueFromPointer=(name,width)=>{switch(width){case 4:return function(pointer){return this["fromWireType"](HEAPF32[pointer>>2])};case 8:return function(pointer){return this["fromWireType"](HEAPF64[pointer>>3])};default:throw new TypeError(`invalid float width (${width}): ${name}`)}};var __embind_register_float=(rawType,name,size)=>{name=readLatin1String(name);registerType(rawType,{name:name,fromWireType:value=>value,toWireType:(destructors,value)=>value,argPackAdvance:GenericWireTypeSize,readValueFromPointer:floatReadValueFromPointer(name,size),destructorFunction:null})};var __embind_register_function=(name,argCount,rawArgTypesAddr,signature,rawInvoker,fn,isAsync)=>{var argTypes=heap32VectorToArray(argCount,rawArgTypesAddr);name=readLatin1String(name);name=getFunctionName(name);rawInvoker=embind__requireFunction(signature,rawInvoker);exposePublicSymbol(name,function(){throwUnboundTypeError(`Cannot call ${name} due to unbound types`,argTypes)},argCount-1);whenDependentTypesAreResolved([],argTypes,argTypes=>{var invokerArgsArray=[argTypes[0],null].concat(argTypes.slice(1));replacePublicSymbol(name,craftInvokerFunction(name,invokerArgsArray,null,rawInvoker,fn,isAsync),argCount-1);return[]})};var integerReadValueFromPointer=(name,width,signed)=>{switch(width){case 1:return signed?pointer=>HEAP8[pointer]:pointer=>HEAPU8[pointer];case 2:return signed?pointer=>HEAP16[pointer>>1]:pointer=>HEAPU16[pointer>>1];case 4:return signed?pointer=>HEAP32[pointer>>2]:pointer=>HEAPU32[pointer>>2];default:throw new TypeError(`invalid integer width (${width}): ${name}`)}};var __embind_register_integer=(primitiveType,name,size,minRange,maxRange)=>{name=readLatin1String(name);if(maxRange===-1){maxRange=4294967295}var fromWireType=value=>value;if(minRange===0){var bitshift=32-8*size;fromWireType=value=>value<>>bitshift}var isUnsignedType=name.includes("unsigned");var checkAssertions=(value,toTypeName)=>{};var toWireType;if(isUnsignedType){toWireType=function(destructors,value){checkAssertions(value,this.name);return value>>>0}}else{toWireType=function(destructors,value){checkAssertions(value,this.name);return value}}registerType(primitiveType,{name:name,fromWireType:fromWireType,toWireType:toWireType,argPackAdvance:GenericWireTypeSize,readValueFromPointer:integerReadValueFromPointer(name,size,minRange!==0),destructorFunction:null})};var __embind_register_memory_view=(rawType,dataTypeIndex,name)=>{var typeMapping=[Int8Array,Uint8Array,Int16Array,Uint16Array,Int32Array,Uint32Array,Float32Array,Float64Array];var TA=typeMapping[dataTypeIndex];function decodeMemoryView(handle){var size=HEAPU32[handle>>2];var data=HEAPU32[handle+4>>2];return new TA(HEAP8.buffer,data,size)}name=readLatin1String(name);registerType(rawType,{name:name,fromWireType:decodeMemoryView,argPackAdvance:GenericWireTypeSize,readValueFromPointer:decodeMemoryView},{ignoreDuplicateRegistrations:true})};var __embind_register_optional=(rawOptionalType,rawType)=>{__embind_register_emval(rawOptionalType)};var stringToUTF8Array=(str,heap,outIdx,maxBytesToWrite)=>{if(!(maxBytesToWrite>0))return 0;var startIdx=outIdx;var endIdx=outIdx+maxBytesToWrite-1;for(var i=0;i=55296&&u<=57343){var u1=str.charCodeAt(++i);u=65536+((u&1023)<<10)|u1&1023}if(u<=127){if(outIdx>=endIdx)break;heap[outIdx++]=u}else if(u<=2047){if(outIdx+1>=endIdx)break;heap[outIdx++]=192|u>>6;heap[outIdx++]=128|u&63}else if(u<=65535){if(outIdx+2>=endIdx)break;heap[outIdx++]=224|u>>12;heap[outIdx++]=128|u>>6&63;heap[outIdx++]=128|u&63}else{if(outIdx+3>=endIdx)break;heap[outIdx++]=240|u>>18;heap[outIdx++]=128|u>>12&63;heap[outIdx++]=128|u>>6&63;heap[outIdx++]=128|u&63}}heap[outIdx]=0;return outIdx-startIdx};var stringToUTF8=(str,outPtr,maxBytesToWrite)=>stringToUTF8Array(str,HEAPU8,outPtr,maxBytesToWrite);var lengthBytesUTF8=str=>{var len=0;for(var i=0;i=55296&&c<=57343){len+=4;++i}else{len+=3}}return len};var UTF8Decoder=typeof TextDecoder!="undefined"?new TextDecoder:undefined;var UTF8ArrayToString=(heapOrArray,idx,maxBytesToRead)=>{var endIdx=idx+maxBytesToRead;var endPtr=idx;while(heapOrArray[endPtr]&&!(endPtr>=endIdx))++endPtr;if(endPtr-idx>16&&heapOrArray.buffer&&UTF8Decoder){return UTF8Decoder.decode(heapOrArray.subarray(idx,endPtr))}var str="";while(idx>10,56320|ch&1023)}}return str};var UTF8ToString=(ptr,maxBytesToRead)=>ptr?UTF8ArrayToString(HEAPU8,ptr,maxBytesToRead):"";var __embind_register_std_string=(rawType,name)=>{name=readLatin1String(name);var stdStringIsUTF8=name==="std::string";registerType(rawType,{name:name,fromWireType(value){var length=HEAPU32[value>>2];var payload=value+4;var str;if(stdStringIsUTF8){var decodeStartPtr=payload;for(var i=0;i<=length;++i){var currentBytePtr=payload+i;if(i==length||HEAPU8[currentBytePtr]==0){var maxRead=currentBytePtr-decodeStartPtr;var stringSegment=UTF8ToString(decodeStartPtr,maxRead);if(str===undefined){str=stringSegment}else{str+=String.fromCharCode(0);str+=stringSegment}decodeStartPtr=currentBytePtr+1}}}else{var a=new Array(length);for(var i=0;i>2]=length;if(stdStringIsUTF8&&valueIsOfTypeString){stringToUTF8(value,ptr,length+1)}else{if(valueIsOfTypeString){for(var i=0;i255){_free(ptr);throwBindingError("String has UTF-16 code units that do not fit in 8 bits")}HEAPU8[ptr+i]=charCode}}else{for(var i=0;i{var endPtr=ptr;var idx=endPtr>>1;var maxIdx=idx+maxBytesToRead/2;while(!(idx>=maxIdx)&&HEAPU16[idx])++idx;endPtr=idx<<1;if(endPtr-ptr>32&&UTF16Decoder)return UTF16Decoder.decode(HEAPU8.subarray(ptr,endPtr));var str="";for(var i=0;!(i>=maxBytesToRead/2);++i){var codeUnit=HEAP16[ptr+i*2>>1];if(codeUnit==0)break;str+=String.fromCharCode(codeUnit)}return str};var stringToUTF16=(str,outPtr,maxBytesToWrite)=>{maxBytesToWrite??=2147483647;if(maxBytesToWrite<2)return 0;maxBytesToWrite-=2;var startPtr=outPtr;var numCharsToWrite=maxBytesToWrite>1]=codeUnit;outPtr+=2}HEAP16[outPtr>>1]=0;return outPtr-startPtr};var lengthBytesUTF16=str=>str.length*2;var UTF32ToString=(ptr,maxBytesToRead)=>{var i=0;var str="";while(!(i>=maxBytesToRead/4)){var utf32=HEAP32[ptr+i*4>>2];if(utf32==0)break;++i;if(utf32>=65536){var ch=utf32-65536;str+=String.fromCharCode(55296|ch>>10,56320|ch&1023)}else{str+=String.fromCharCode(utf32)}}return str};var stringToUTF32=(str,outPtr,maxBytesToWrite)=>{maxBytesToWrite??=2147483647;if(maxBytesToWrite<4)return 0;var startPtr=outPtr;var endPtr=startPtr+maxBytesToWrite-4;for(var i=0;i=55296&&codeUnit<=57343){var trailSurrogate=str.charCodeAt(++i);codeUnit=65536+((codeUnit&1023)<<10)|trailSurrogate&1023}HEAP32[outPtr>>2]=codeUnit;outPtr+=4;if(outPtr+4>endPtr)break}HEAP32[outPtr>>2]=0;return outPtr-startPtr};var lengthBytesUTF32=str=>{var len=0;for(var i=0;i=55296&&codeUnit<=57343)++i;len+=4}return len};var __embind_register_std_wstring=(rawType,charSize,name)=>{name=readLatin1String(name);var decodeString,encodeString,readCharAt,lengthBytesUTF;if(charSize===2){decodeString=UTF16ToString;encodeString=stringToUTF16;lengthBytesUTF=lengthBytesUTF16;readCharAt=pointer=>HEAPU16[pointer>>1]}else if(charSize===4){decodeString=UTF32ToString;encodeString=stringToUTF32;lengthBytesUTF=lengthBytesUTF32;readCharAt=pointer=>HEAPU32[pointer>>2]}registerType(rawType,{name:name,fromWireType:value=>{var length=HEAPU32[value>>2];var str;var decodeStartPtr=value+4;for(var i=0;i<=length;++i){var currentBytePtr=value+4+i*charSize;if(i==length||readCharAt(currentBytePtr)==0){var maxReadBytes=currentBytePtr-decodeStartPtr;var stringSegment=decodeString(decodeStartPtr,maxReadBytes);if(str===undefined){str=stringSegment}else{str+=String.fromCharCode(0);str+=stringSegment}decodeStartPtr=currentBytePtr+charSize}}_free(value);return str},toWireType:(destructors,value)=>{if(!(typeof value=="string")){throwBindingError(`Cannot pass non-string to C++ string type ${name}`)}var length=lengthBytesUTF(value);var ptr=_malloc(4+length+charSize);HEAPU32[ptr>>2]=length/charSize;encodeString(value,ptr+4,length+charSize);if(destructors!==null){destructors.push(_free,ptr)}return ptr},argPackAdvance:GenericWireTypeSize,readValueFromPointer:readPointer,destructorFunction(ptr){_free(ptr)}})};var __embind_register_void=(rawType,name)=>{name=readLatin1String(name);registerType(rawType,{isVoid:true,name:name,argPackAdvance:0,fromWireType:()=>undefined,toWireType:(destructors,o)=>undefined})};var __emscripten_memcpy_js=(dest,src,num)=>HEAPU8.copyWithin(dest,src,src+num);var requireRegisteredType=(rawType,humanName)=>{var impl=registeredTypes[rawType];if(undefined===impl){throwBindingError(`${humanName} has unknown type ${getTypeName(rawType)}`)}return impl};var __emval_take_value=(type,arg)=>{type=requireRegisteredType(type,"_emval_take_value");var v=type["readValueFromPointer"](arg);return Emval.toHandle(v)};var _emscripten_date_now=()=>Date.now();var abortOnCannotGrowMemory=requestedSize=>{abort("OOM")};var _emscripten_resize_heap=requestedSize=>{var oldSize=HEAPU8.length;requestedSize>>>=0;abortOnCannotGrowMemory(requestedSize)};var printCharBuffers=[null,[],[]];var printChar=(stream,curr)=>{var buffer=printCharBuffers[stream];if(curr===0||curr===10){(stream===1?out:err)(UTF8ArrayToString(buffer,0));buffer.length=0}else{buffer.push(curr)}};var _fd_write=(fd,iov,iovcnt,pnum)=>{var num=0;for(var i=0;i>2];var len=HEAPU32[iov+4>>2];iov+=8;for(var j=0;j>2]=num;return 0};embind_init_charCodes();BindingError=Module["BindingError"]=class BindingError extends Error{constructor(message){super(message);this.name="BindingError"}};InternalError=Module["InternalError"]=class InternalError extends Error{constructor(message){super(message);this.name="InternalError"}};init_ClassHandle();init_embind();init_RegisteredPointer();UnboundTypeError=Module["UnboundTypeError"]=extendError(Error,"UnboundTypeError");init_emval();var wasmImports={f:___cxa_throw,q:__abort_js,p:__embind_register_bigint,u:__embind_register_bool,l:__embind_register_class,h:__embind_register_class_constructor,e:__embind_register_class_function,a:__embind_register_class_property,t:__embind_register_emval,k:__embind_register_float,c:__embind_register_function,d:__embind_register_integer,b:__embind_register_memory_view,o:__embind_register_optional,j:__embind_register_std_string,g:__embind_register_std_wstring,m:__embind_register_void,s:__emscripten_memcpy_js,n:__emval_take_value,v:_emscripten_date_now,r:_emscripten_resize_heap,i:_fd_write};var wasmExports=createWasm();var ___wasm_call_ctors=()=>(___wasm_call_ctors=wasmExports["x"])();var _param_get=Module["_param_get"]=(a0,a1)=>(_param_get=Module["_param_get"]=wasmExports["y"])(a0,a1);var _param_set_used=Module["_param_set_used"]=a0=>(_param_set_used=Module["_param_set_used"]=wasmExports["z"])(a0);var __Znwm=Module["__Znwm"]=a0=>(__Znwm=Module["__Znwm"]=wasmExports["A"])(a0);var __ZdlPvm=Module["__ZdlPvm"]=(a0,a1)=>(__ZdlPvm=Module["__ZdlPvm"]=wasmExports["B"])(a0,a1);var _malloc=a0=>(_malloc=wasmExports["D"])(a0);var __ZNSt12length_errorD1Ev=Module["__ZNSt12length_errorD1Ev"]=a0=>(__ZNSt12length_errorD1Ev=Module["__ZNSt12length_errorD1Ev"]=wasmExports["E"])(a0);var ___cxa_allocate_exception=Module["___cxa_allocate_exception"]=a0=>(___cxa_allocate_exception=Module["___cxa_allocate_exception"]=wasmExports["F"])(a0);var __ZNSt20bad_array_new_lengthD1Ev=Module["__ZNSt20bad_array_new_lengthD1Ev"]=a0=>(__ZNSt20bad_array_new_lengthD1Ev=Module["__ZNSt20bad_array_new_lengthD1Ev"]=wasmExports["G"])(a0);var __ZNSt20bad_array_new_lengthC1Ev=Module["__ZNSt20bad_array_new_lengthC1Ev"]=a0=>(__ZNSt20bad_array_new_lengthC1Ev=Module["__ZNSt20bad_array_new_lengthC1Ev"]=wasmExports["H"])(a0);var __ZNSt12out_of_rangeD1Ev=Module["__ZNSt12out_of_rangeD1Ev"]=a0=>(__ZNSt12out_of_rangeD1Ev=Module["__ZNSt12out_of_rangeD1Ev"]=wasmExports["I"])(a0);var ___cxa_pure_virtual=Module["___cxa_pure_virtual"]=()=>(___cxa_pure_virtual=Module["___cxa_pure_virtual"]=wasmExports["J"])();var ___getTypeName=a0=>(___getTypeName=wasmExports["K"])(a0);var __ZNSt9exceptionD2Ev=Module["__ZNSt9exceptionD2Ev"]=a0=>(__ZNSt9exceptionD2Ev=Module["__ZNSt9exceptionD2Ev"]=wasmExports["L"])(a0);var _free=a0=>(_free=wasmExports["M"])(a0);var _getTempRet0=Module["_getTempRet0"]=()=>(_getTempRet0=Module["_getTempRet0"]=wasmExports["N"])();var _setTempRet0=Module["_setTempRet0"]=a0=>(_setTempRet0=Module["_setTempRet0"]=wasmExports["O"])(a0);var __ZSt15get_new_handlerv=Module["__ZSt15get_new_handlerv"]=()=>(__ZSt15get_new_handlerv=Module["__ZSt15get_new_handlerv"]=wasmExports["P"])();var __Znam=Module["__Znam"]=a0=>(__Znam=Module["__Znam"]=wasmExports["Q"])(a0);var __ZdlPv=Module["__ZdlPv"]=a0=>(__ZdlPv=Module["__ZdlPv"]=wasmExports["R"])(a0);var __ZdaPv=Module["__ZdaPv"]=a0=>(__ZdaPv=Module["__ZdaPv"]=wasmExports["S"])(a0);var __ZdaPvm=Module["__ZdaPvm"]=(a0,a1)=>(__ZdaPvm=Module["__ZdaPvm"]=wasmExports["T"])(a0,a1);var __ZnwmSt11align_val_t=Module["__ZnwmSt11align_val_t"]=(a0,a1)=>(__ZnwmSt11align_val_t=Module["__ZnwmSt11align_val_t"]=wasmExports["U"])(a0,a1);var __ZnamSt11align_val_t=Module["__ZnamSt11align_val_t"]=(a0,a1)=>(__ZnamSt11align_val_t=Module["__ZnamSt11align_val_t"]=wasmExports["V"])(a0,a1);var __ZdlPvSt11align_val_t=Module["__ZdlPvSt11align_val_t"]=(a0,a1)=>(__ZdlPvSt11align_val_t=Module["__ZdlPvSt11align_val_t"]=wasmExports["W"])(a0,a1);var __ZdlPvmSt11align_val_t=Module["__ZdlPvmSt11align_val_t"]=(a0,a1,a2)=>(__ZdlPvmSt11align_val_t=Module["__ZdlPvmSt11align_val_t"]=wasmExports["X"])(a0,a1,a2);var __ZdaPvSt11align_val_t=Module["__ZdaPvSt11align_val_t"]=(a0,a1)=>(__ZdaPvSt11align_val_t=Module["__ZdaPvSt11align_val_t"]=wasmExports["Y"])(a0,a1);var __ZdaPvmSt11align_val_t=Module["__ZdaPvmSt11align_val_t"]=(a0,a1,a2)=>(__ZdaPvmSt11align_val_t=Module["__ZdaPvmSt11align_val_t"]=wasmExports["Z"])(a0,a1,a2);var __ZSt14set_unexpectedPFvvE=Module["__ZSt14set_unexpectedPFvvE"]=a0=>(__ZSt14set_unexpectedPFvvE=Module["__ZSt14set_unexpectedPFvvE"]=wasmExports["_"])(a0);var __ZSt13set_terminatePFvvE=Module["__ZSt13set_terminatePFvvE"]=a0=>(__ZSt13set_terminatePFvvE=Module["__ZSt13set_terminatePFvvE"]=wasmExports["$"])(a0);var __ZSt15set_new_handlerPFvvE=Module["__ZSt15set_new_handlerPFvvE"]=a0=>(__ZSt15set_new_handlerPFvvE=Module["__ZSt15set_new_handlerPFvvE"]=wasmExports["aa"])(a0);var __ZSt14get_unexpectedv=Module["__ZSt14get_unexpectedv"]=()=>(__ZSt14get_unexpectedv=Module["__ZSt14get_unexpectedv"]=wasmExports["ba"])();var __ZSt10unexpectedv=Module["__ZSt10unexpectedv"]=()=>(__ZSt10unexpectedv=Module["__ZSt10unexpectedv"]=wasmExports["ca"])();var __ZSt13get_terminatev=Module["__ZSt13get_terminatev"]=()=>(__ZSt13get_terminatev=Module["__ZSt13get_terminatev"]=wasmExports["da"])();var __ZSt9terminatev=Module["__ZSt9terminatev"]=()=>(__ZSt9terminatev=Module["__ZSt9terminatev"]=wasmExports["ea"])();var ___cxa_current_primary_exception=Module["___cxa_current_primary_exception"]=()=>(___cxa_current_primary_exception=Module["___cxa_current_primary_exception"]=wasmExports["fa"])();var ___cxa_rethrow_primary_exception=Module["___cxa_rethrow_primary_exception"]=a0=>(___cxa_rethrow_primary_exception=Module["___cxa_rethrow_primary_exception"]=wasmExports["ga"])(a0);var ___cxa_uncaught_exception=Module["___cxa_uncaught_exception"]=()=>(___cxa_uncaught_exception=Module["___cxa_uncaught_exception"]=wasmExports["ha"])();var ___cxa_uncaught_exceptions=Module["___cxa_uncaught_exceptions"]=()=>(___cxa_uncaught_exceptions=Module["___cxa_uncaught_exceptions"]=wasmExports["ia"])();var ___cxa_free_exception=Module["___cxa_free_exception"]=a0=>(___cxa_free_exception=Module["___cxa_free_exception"]=wasmExports["ja"])(a0);var ___cxa_init_primary_exception=Module["___cxa_init_primary_exception"]=(a0,a1,a2)=>(___cxa_init_primary_exception=Module["___cxa_init_primary_exception"]=wasmExports["ka"])(a0,a1,a2);var ___cxa_deleted_virtual=Module["___cxa_deleted_virtual"]=()=>(___cxa_deleted_virtual=Module["___cxa_deleted_virtual"]=wasmExports["la"])();var ___dynamic_cast=Module["___dynamic_cast"]=(a0,a1,a2,a3)=>(___dynamic_cast=Module["___dynamic_cast"]=wasmExports["ma"])(a0,a1,a2,a3);var __ZNSt9type_infoD2Ev=Module["__ZNSt9type_infoD2Ev"]=a0=>(__ZNSt9type_infoD2Ev=Module["__ZNSt9type_infoD2Ev"]=wasmExports["na"])(a0);var ___cxa_is_pointer_type=a0=>(___cxa_is_pointer_type=wasmExports["oa"])(a0);var __ZNSt9exceptionD0Ev=Module["__ZNSt9exceptionD0Ev"]=a0=>(__ZNSt9exceptionD0Ev=Module["__ZNSt9exceptionD0Ev"]=wasmExports["pa"])(a0);var __ZNSt9exceptionD1Ev=Module["__ZNSt9exceptionD1Ev"]=a0=>(__ZNSt9exceptionD1Ev=Module["__ZNSt9exceptionD1Ev"]=wasmExports["qa"])(a0);var __ZNKSt9exception4whatEv=Module["__ZNKSt9exception4whatEv"]=a0=>(__ZNKSt9exception4whatEv=Module["__ZNKSt9exception4whatEv"]=wasmExports["ra"])(a0);var __ZNSt13bad_exceptionD0Ev=Module["__ZNSt13bad_exceptionD0Ev"]=a0=>(__ZNSt13bad_exceptionD0Ev=Module["__ZNSt13bad_exceptionD0Ev"]=wasmExports["sa"])(a0);var __ZNSt13bad_exceptionD1Ev=Module["__ZNSt13bad_exceptionD1Ev"]=a0=>(__ZNSt13bad_exceptionD1Ev=Module["__ZNSt13bad_exceptionD1Ev"]=wasmExports["ta"])(a0);var __ZNKSt13bad_exception4whatEv=Module["__ZNKSt13bad_exception4whatEv"]=a0=>(__ZNKSt13bad_exception4whatEv=Module["__ZNKSt13bad_exception4whatEv"]=wasmExports["ua"])(a0);var __ZNSt9bad_allocC2Ev=Module["__ZNSt9bad_allocC2Ev"]=a0=>(__ZNSt9bad_allocC2Ev=Module["__ZNSt9bad_allocC2Ev"]=wasmExports["va"])(a0);var __ZNSt9bad_allocD0Ev=Module["__ZNSt9bad_allocD0Ev"]=a0=>(__ZNSt9bad_allocD0Ev=Module["__ZNSt9bad_allocD0Ev"]=wasmExports["wa"])(a0);var __ZNSt9bad_allocD1Ev=Module["__ZNSt9bad_allocD1Ev"]=a0=>(__ZNSt9bad_allocD1Ev=Module["__ZNSt9bad_allocD1Ev"]=wasmExports["xa"])(a0);var __ZNKSt9bad_alloc4whatEv=Module["__ZNKSt9bad_alloc4whatEv"]=a0=>(__ZNKSt9bad_alloc4whatEv=Module["__ZNKSt9bad_alloc4whatEv"]=wasmExports["ya"])(a0);var __ZNSt20bad_array_new_lengthC2Ev=Module["__ZNSt20bad_array_new_lengthC2Ev"]=a0=>(__ZNSt20bad_array_new_lengthC2Ev=Module["__ZNSt20bad_array_new_lengthC2Ev"]=wasmExports["za"])(a0);var __ZNSt20bad_array_new_lengthD0Ev=Module["__ZNSt20bad_array_new_lengthD0Ev"]=a0=>(__ZNSt20bad_array_new_lengthD0Ev=Module["__ZNSt20bad_array_new_lengthD0Ev"]=wasmExports["Aa"])(a0);var __ZNKSt20bad_array_new_length4whatEv=Module["__ZNKSt20bad_array_new_length4whatEv"]=a0=>(__ZNKSt20bad_array_new_length4whatEv=Module["__ZNKSt20bad_array_new_length4whatEv"]=wasmExports["Ba"])(a0);var __ZNSt13bad_exceptionD2Ev=Module["__ZNSt13bad_exceptionD2Ev"]=a0=>(__ZNSt13bad_exceptionD2Ev=Module["__ZNSt13bad_exceptionD2Ev"]=wasmExports["Ca"])(a0);var __ZNSt9bad_allocC1Ev=Module["__ZNSt9bad_allocC1Ev"]=a0=>(__ZNSt9bad_allocC1Ev=Module["__ZNSt9bad_allocC1Ev"]=wasmExports["Da"])(a0);var __ZNSt9bad_allocD2Ev=Module["__ZNSt9bad_allocD2Ev"]=a0=>(__ZNSt9bad_allocD2Ev=Module["__ZNSt9bad_allocD2Ev"]=wasmExports["Ea"])(a0);var __ZNSt20bad_array_new_lengthD2Ev=Module["__ZNSt20bad_array_new_lengthD2Ev"]=a0=>(__ZNSt20bad_array_new_lengthD2Ev=Module["__ZNSt20bad_array_new_lengthD2Ev"]=wasmExports["Fa"])(a0);var __ZNSt11logic_errorD2Ev=Module["__ZNSt11logic_errorD2Ev"]=a0=>(__ZNSt11logic_errorD2Ev=Module["__ZNSt11logic_errorD2Ev"]=wasmExports["Ga"])(a0);var __ZNSt11logic_errorD0Ev=Module["__ZNSt11logic_errorD0Ev"]=a0=>(__ZNSt11logic_errorD0Ev=Module["__ZNSt11logic_errorD0Ev"]=wasmExports["Ha"])(a0);var __ZNSt11logic_errorD1Ev=Module["__ZNSt11logic_errorD1Ev"]=a0=>(__ZNSt11logic_errorD1Ev=Module["__ZNSt11logic_errorD1Ev"]=wasmExports["Ia"])(a0);var __ZNKSt11logic_error4whatEv=Module["__ZNKSt11logic_error4whatEv"]=a0=>(__ZNKSt11logic_error4whatEv=Module["__ZNKSt11logic_error4whatEv"]=wasmExports["Ja"])(a0);var __ZNSt13runtime_errorD2Ev=Module["__ZNSt13runtime_errorD2Ev"]=a0=>(__ZNSt13runtime_errorD2Ev=Module["__ZNSt13runtime_errorD2Ev"]=wasmExports["Ka"])(a0);var __ZNSt13runtime_errorD0Ev=Module["__ZNSt13runtime_errorD0Ev"]=a0=>(__ZNSt13runtime_errorD0Ev=Module["__ZNSt13runtime_errorD0Ev"]=wasmExports["La"])(a0);var __ZNSt13runtime_errorD1Ev=Module["__ZNSt13runtime_errorD1Ev"]=a0=>(__ZNSt13runtime_errorD1Ev=Module["__ZNSt13runtime_errorD1Ev"]=wasmExports["Ma"])(a0);var __ZNKSt13runtime_error4whatEv=Module["__ZNKSt13runtime_error4whatEv"]=a0=>(__ZNKSt13runtime_error4whatEv=Module["__ZNKSt13runtime_error4whatEv"]=wasmExports["Na"])(a0);var __ZNSt12domain_errorD0Ev=Module["__ZNSt12domain_errorD0Ev"]=a0=>(__ZNSt12domain_errorD0Ev=Module["__ZNSt12domain_errorD0Ev"]=wasmExports["Oa"])(a0);var __ZNSt12domain_errorD1Ev=Module["__ZNSt12domain_errorD1Ev"]=a0=>(__ZNSt12domain_errorD1Ev=Module["__ZNSt12domain_errorD1Ev"]=wasmExports["Pa"])(a0);var __ZNSt16invalid_argumentD0Ev=Module["__ZNSt16invalid_argumentD0Ev"]=a0=>(__ZNSt16invalid_argumentD0Ev=Module["__ZNSt16invalid_argumentD0Ev"]=wasmExports["Qa"])(a0);var __ZNSt16invalid_argumentD1Ev=Module["__ZNSt16invalid_argumentD1Ev"]=a0=>(__ZNSt16invalid_argumentD1Ev=Module["__ZNSt16invalid_argumentD1Ev"]=wasmExports["Ra"])(a0);var __ZNSt12length_errorD0Ev=Module["__ZNSt12length_errorD0Ev"]=a0=>(__ZNSt12length_errorD0Ev=Module["__ZNSt12length_errorD0Ev"]=wasmExports["Sa"])(a0);var __ZNSt12out_of_rangeD0Ev=Module["__ZNSt12out_of_rangeD0Ev"]=a0=>(__ZNSt12out_of_rangeD0Ev=Module["__ZNSt12out_of_rangeD0Ev"]=wasmExports["Ta"])(a0);var __ZNSt11range_errorD0Ev=Module["__ZNSt11range_errorD0Ev"]=a0=>(__ZNSt11range_errorD0Ev=Module["__ZNSt11range_errorD0Ev"]=wasmExports["Ua"])(a0);var __ZNSt11range_errorD1Ev=Module["__ZNSt11range_errorD1Ev"]=a0=>(__ZNSt11range_errorD1Ev=Module["__ZNSt11range_errorD1Ev"]=wasmExports["Va"])(a0);var __ZNSt14overflow_errorD0Ev=Module["__ZNSt14overflow_errorD0Ev"]=a0=>(__ZNSt14overflow_errorD0Ev=Module["__ZNSt14overflow_errorD0Ev"]=wasmExports["Wa"])(a0);var __ZNSt14overflow_errorD1Ev=Module["__ZNSt14overflow_errorD1Ev"]=a0=>(__ZNSt14overflow_errorD1Ev=Module["__ZNSt14overflow_errorD1Ev"]=wasmExports["Xa"])(a0);var __ZNSt15underflow_errorD0Ev=Module["__ZNSt15underflow_errorD0Ev"]=a0=>(__ZNSt15underflow_errorD0Ev=Module["__ZNSt15underflow_errorD0Ev"]=wasmExports["Ya"])(a0);var __ZNSt15underflow_errorD1Ev=Module["__ZNSt15underflow_errorD1Ev"]=a0=>(__ZNSt15underflow_errorD1Ev=Module["__ZNSt15underflow_errorD1Ev"]=wasmExports["Za"])(a0);var __ZNSt12domain_errorD2Ev=Module["__ZNSt12domain_errorD2Ev"]=a0=>(__ZNSt12domain_errorD2Ev=Module["__ZNSt12domain_errorD2Ev"]=wasmExports["_a"])(a0);var __ZNSt16invalid_argumentD2Ev=Module["__ZNSt16invalid_argumentD2Ev"]=a0=>(__ZNSt16invalid_argumentD2Ev=Module["__ZNSt16invalid_argumentD2Ev"]=wasmExports["$a"])(a0);var __ZNSt12length_errorD2Ev=Module["__ZNSt12length_errorD2Ev"]=a0=>(__ZNSt12length_errorD2Ev=Module["__ZNSt12length_errorD2Ev"]=wasmExports["ab"])(a0);var __ZNSt12out_of_rangeD2Ev=Module["__ZNSt12out_of_rangeD2Ev"]=a0=>(__ZNSt12out_of_rangeD2Ev=Module["__ZNSt12out_of_rangeD2Ev"]=wasmExports["bb"])(a0);var __ZNSt11range_errorD2Ev=Module["__ZNSt11range_errorD2Ev"]=a0=>(__ZNSt11range_errorD2Ev=Module["__ZNSt11range_errorD2Ev"]=wasmExports["cb"])(a0);var __ZNSt14overflow_errorD2Ev=Module["__ZNSt14overflow_errorD2Ev"]=a0=>(__ZNSt14overflow_errorD2Ev=Module["__ZNSt14overflow_errorD2Ev"]=wasmExports["db"])(a0);var __ZNSt15underflow_errorD2Ev=Module["__ZNSt15underflow_errorD2Ev"]=a0=>(__ZNSt15underflow_errorD2Ev=Module["__ZNSt15underflow_errorD2Ev"]=wasmExports["eb"])(a0);var __ZNSt9type_infoD0Ev=Module["__ZNSt9type_infoD0Ev"]=a0=>(__ZNSt9type_infoD0Ev=Module["__ZNSt9type_infoD0Ev"]=wasmExports["fb"])(a0);var __ZNSt9type_infoD1Ev=Module["__ZNSt9type_infoD1Ev"]=a0=>(__ZNSt9type_infoD1Ev=Module["__ZNSt9type_infoD1Ev"]=wasmExports["gb"])(a0);var __ZNSt8bad_castC2Ev=Module["__ZNSt8bad_castC2Ev"]=a0=>(__ZNSt8bad_castC2Ev=Module["__ZNSt8bad_castC2Ev"]=wasmExports["hb"])(a0);var __ZNSt8bad_castD2Ev=Module["__ZNSt8bad_castD2Ev"]=a0=>(__ZNSt8bad_castD2Ev=Module["__ZNSt8bad_castD2Ev"]=wasmExports["ib"])(a0);var __ZNSt8bad_castD0Ev=Module["__ZNSt8bad_castD0Ev"]=a0=>(__ZNSt8bad_castD0Ev=Module["__ZNSt8bad_castD0Ev"]=wasmExports["jb"])(a0);var __ZNSt8bad_castD1Ev=Module["__ZNSt8bad_castD1Ev"]=a0=>(__ZNSt8bad_castD1Ev=Module["__ZNSt8bad_castD1Ev"]=wasmExports["kb"])(a0);var __ZNKSt8bad_cast4whatEv=Module["__ZNKSt8bad_cast4whatEv"]=a0=>(__ZNKSt8bad_cast4whatEv=Module["__ZNKSt8bad_cast4whatEv"]=wasmExports["lb"])(a0);var __ZNSt10bad_typeidC2Ev=Module["__ZNSt10bad_typeidC2Ev"]=a0=>(__ZNSt10bad_typeidC2Ev=Module["__ZNSt10bad_typeidC2Ev"]=wasmExports["mb"])(a0);var __ZNSt10bad_typeidD2Ev=Module["__ZNSt10bad_typeidD2Ev"]=a0=>(__ZNSt10bad_typeidD2Ev=Module["__ZNSt10bad_typeidD2Ev"]=wasmExports["nb"])(a0);var __ZNSt10bad_typeidD0Ev=Module["__ZNSt10bad_typeidD0Ev"]=a0=>(__ZNSt10bad_typeidD0Ev=Module["__ZNSt10bad_typeidD0Ev"]=wasmExports["ob"])(a0);var __ZNSt10bad_typeidD1Ev=Module["__ZNSt10bad_typeidD1Ev"]=a0=>(__ZNSt10bad_typeidD1Ev=Module["__ZNSt10bad_typeidD1Ev"]=wasmExports["pb"])(a0);var __ZNKSt10bad_typeid4whatEv=Module["__ZNKSt10bad_typeid4whatEv"]=a0=>(__ZNKSt10bad_typeid4whatEv=Module["__ZNKSt10bad_typeid4whatEv"]=wasmExports["qb"])(a0);var __ZNSt8bad_castC1Ev=Module["__ZNSt8bad_castC1Ev"]=a0=>(__ZNSt8bad_castC1Ev=Module["__ZNSt8bad_castC1Ev"]=wasmExports["rb"])(a0);var __ZNSt10bad_typeidC1Ev=Module["__ZNSt10bad_typeidC1Ev"]=a0=>(__ZNSt10bad_typeidC1Ev=Module["__ZNSt10bad_typeidC1Ev"]=wasmExports["sb"])(a0);var dynCall_jiji=Module["dynCall_jiji"]=(a0,a1,a2,a3,a4)=>(dynCall_jiji=Module["dynCall_jiji"]=wasmExports["tb"])(a0,a1,a2,a3,a4);var __ZTIPK16failsafe_flags_s=Module["__ZTIPK16failsafe_flags_s"]=48448;var __ZTIP16failsafe_flags_s=Module["__ZTIP16failsafe_flags_s"]=48432;var __ZTI16failsafe_flags_s=Module["__ZTI16failsafe_flags_s"]=48424;var __ZTIb=Module["__ZTIb"]=31256;var __ZTIh=Module["__ZTIh"]=31412;var __ZTINSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE=Module["__ZTINSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE"]=48524;var __ZTINSt3__28optionalINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEEEE=Module["__ZTINSt3__28optionalINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEEEE"]=48672;var __ZTIPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTIPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=48728;var __ZTIPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTIPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=48712;var __ZTINSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTINSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=48536;var __ZTISt12length_error=Module["__ZTISt12length_error"]=33372;var __ZTVSt12length_error=Module["__ZTVSt12length_error"]=33332;var __ZTISt20bad_array_new_length=Module["__ZTISt20bad_array_new_length"]=33144;var __ZTISt12out_of_range=Module["__ZTISt12out_of_range"]=33424;var __ZTVSt12out_of_range=Module["__ZTVSt12out_of_range"]=33384;var __ZTVN10__cxxabiv117__class_type_infoE=Module["__ZTVN10__cxxabiv117__class_type_infoE"]=32644;var __ZTVN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTVN10__cxxabiv121__vmi_class_type_infoE"]=32776;var __ZTVN10__cxxabiv120__si_class_type_infoE=Module["__ZTVN10__cxxabiv120__si_class_type_infoE"]=32684;var __ZTS16failsafe_flags_s=Module["__ZTS16failsafe_flags_s"]=28163;var __ZTSP16failsafe_flags_s=Module["__ZTSP16failsafe_flags_s"]=28182;var __ZTVN10__cxxabiv119__pointer_type_infoE=Module["__ZTVN10__cxxabiv119__pointer_type_infoE"]=32896;var __ZTSPK16failsafe_flags_s=Module["__ZTSPK16failsafe_flags_s"]=28202;var __ZTIi=Module["__ZTIi"]=31620;var __ZTSNSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE=Module["__ZTSNSt3__212basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEE"]=28251;var __ZTSNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=28318;var __ZTIv=Module["__ZTIv"]=31148;var __ZTIf=Module["__ZTIf"]=32092;var __ZTSNSt3__28optionalINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEEEE=Module["__ZTSNSt3__28optionalINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEEEE"]=28416;var __ZTSNSt3__227__optional_move_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTSNSt3__227__optional_move_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=28494;var __ZTSNSt3__227__optional_copy_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTSNSt3__227__optional_copy_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=28596;var __ZTSNSt3__220__optional_move_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTSNSt3__220__optional_move_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=28698;var __ZTSNSt3__220__optional_copy_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTSNSt3__220__optional_copy_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=28793;var __ZTSNSt3__223__optional_storage_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTSNSt3__223__optional_storage_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=28888;var __ZTSNSt3__224__optional_destruct_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTSNSt3__224__optional_destruct_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=28986;var __ZTINSt3__224__optional_destruct_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTINSt3__224__optional_destruct_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=48588;var __ZTINSt3__223__optional_storage_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTINSt3__223__optional_storage_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=48596;var __ZTINSt3__220__optional_copy_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTINSt3__220__optional_copy_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=48608;var __ZTINSt3__220__optional_move_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTINSt3__220__optional_move_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=48620;var __ZTINSt3__227__optional_copy_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTINSt3__227__optional_copy_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=48632;var __ZTINSt3__227__optional_move_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE=Module["__ZTINSt3__227__optional_move_assign_baseINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEELb0EEE"]=48644;var __ZTSNSt3__218__sfinae_ctor_baseILb1ELb1EEE=Module["__ZTSNSt3__218__sfinae_ctor_baseILb1ELb1EEE"]=29085;var __ZTINSt3__218__sfinae_ctor_baseILb1ELb1EEE=Module["__ZTINSt3__218__sfinae_ctor_baseILb1ELb1EEE"]=48656;var __ZTSNSt3__220__sfinae_assign_baseILb1ELb1EEE=Module["__ZTSNSt3__220__sfinae_assign_baseILb1ELb1EEE"]=29124;var __ZTINSt3__220__sfinae_assign_baseILb1ELb1EEE=Module["__ZTINSt3__220__sfinae_assign_baseILb1ELb1EEE"]=48664;var __ZTSPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSPNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=29165;var __ZTSPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE=Module["__ZTSPKNSt3__26vectorINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEENS4_IS6_EEEE"]=29252;var __ZTIm=Module["__ZTIm"]=31776;var __ZTIc=Module["__ZTIc"]=31360;var __ZTIa=Module["__ZTIa"]=31464;var __ZTIs=Module["__ZTIs"]=31516;var __ZTIt=Module["__ZTIt"]=31568;var __ZTIj=Module["__ZTIj"]=31672;var __ZTIl=Module["__ZTIl"]=31724;var __ZTIx=Module["__ZTIx"]=31828;var __ZTIy=Module["__ZTIy"]=31880;var __ZTId=Module["__ZTId"]=32144;var __ZTINSt3__212basic_stringIhNS_11char_traitsIhEENS_9allocatorIhEEEE=Module["__ZTINSt3__212basic_stringIhNS_11char_traitsIhEENS_9allocatorIhEEEE"]=29456;var __ZTINSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE=Module["__ZTINSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE"]=29528;var __ZTINSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE=Module["__ZTINSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE"]=29604;var __ZTINSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE=Module["__ZTINSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE"]=29680;var __ZTSNSt3__212basic_stringIhNS_11char_traitsIhEENS_9allocatorIhEEEE=Module["__ZTSNSt3__212basic_stringIhNS_11char_traitsIhEENS_9allocatorIhEEEE"]=29392;var __ZTSNSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE=Module["__ZTSNSt3__212basic_stringIwNS_11char_traitsIwEENS_9allocatorIwEEEE"]=29464;var __ZTSNSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE=Module["__ZTSNSt3__212basic_stringIDsNS_11char_traitsIDsEENS_9allocatorIDsEEEE"]=29536;var __ZTSNSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE=Module["__ZTSNSt3__212basic_stringIDiNS_11char_traitsIDiEENS_9allocatorIDiEEEE"]=29612;var __ZTVSt11logic_error=Module["__ZTVSt11logic_error"]=33156;var __ZTVSt9exception=Module["__ZTVSt9exception"]=32992;var __ZTVSt13runtime_error=Module["__ZTVSt13runtime_error"]=33176;var __ZTISt9exception=Module["__ZTISt9exception"]=33028;var ___cxa_unexpected_handler=Module["___cxa_unexpected_handler"]=49032;var ___cxa_terminate_handler=Module["___cxa_terminate_handler"]=49028;var ___cxa_new_handler=Module["___cxa_new_handler"]=51276;var __ZTIN10__cxxabiv116__shim_type_infoE=Module["__ZTIN10__cxxabiv116__shim_type_infoE"]=30756;var __ZTIN10__cxxabiv117__class_type_infoE=Module["__ZTIN10__cxxabiv117__class_type_infoE"]=30804;var __ZTIN10__cxxabiv117__pbase_type_infoE=Module["__ZTIN10__cxxabiv117__pbase_type_infoE"]=30852;var __ZTIDn=Module["__ZTIDn"]=31200;var __ZTIN10__cxxabiv119__pointer_type_infoE=Module["__ZTIN10__cxxabiv119__pointer_type_infoE"]=30900;var __ZTIN10__cxxabiv120__function_type_infoE=Module["__ZTIN10__cxxabiv120__function_type_infoE"]=30952;var __ZTIN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTIN10__cxxabiv129__pointer_to_member_type_infoE"]=31012;var __ZTSN10__cxxabiv116__shim_type_infoE=Module["__ZTSN10__cxxabiv116__shim_type_infoE"]=30720;var __ZTISt9type_info=Module["__ZTISt9type_info"]=33692;var __ZTSN10__cxxabiv117__class_type_infoE=Module["__ZTSN10__cxxabiv117__class_type_infoE"]=30768;var __ZTSN10__cxxabiv117__pbase_type_infoE=Module["__ZTSN10__cxxabiv117__pbase_type_infoE"]=30816;var __ZTSN10__cxxabiv119__pointer_type_infoE=Module["__ZTSN10__cxxabiv119__pointer_type_infoE"]=30864;var __ZTSN10__cxxabiv120__function_type_infoE=Module["__ZTSN10__cxxabiv120__function_type_infoE"]=30912;var __ZTSN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTSN10__cxxabiv129__pointer_to_member_type_infoE"]=30964;var __ZTVN10__cxxabiv116__shim_type_infoE=Module["__ZTVN10__cxxabiv116__shim_type_infoE"]=31036;var __ZTVN10__cxxabiv123__fundamental_type_infoE=Module["__ZTVN10__cxxabiv123__fundamental_type_infoE"]=31064;var __ZTIN10__cxxabiv123__fundamental_type_infoE=Module["__ZTIN10__cxxabiv123__fundamental_type_infoE"]=31132;var __ZTSN10__cxxabiv123__fundamental_type_infoE=Module["__ZTSN10__cxxabiv123__fundamental_type_infoE"]=31092;var __ZTSv=Module["__ZTSv"]=31144;var __ZTSPv=Module["__ZTSPv"]=31156;var __ZTIPv=Module["__ZTIPv"]=31160;var __ZTSPKv=Module["__ZTSPKv"]=31176;var __ZTIPKv=Module["__ZTIPKv"]=31180;var __ZTSDn=Module["__ZTSDn"]=31196;var __ZTSPDn=Module["__ZTSPDn"]=31208;var __ZTIPDn=Module["__ZTIPDn"]=31212;var __ZTSPKDn=Module["__ZTSPKDn"]=31228;var __ZTIPKDn=Module["__ZTIPKDn"]=31236;var __ZTSb=Module["__ZTSb"]=31252;var __ZTSPb=Module["__ZTSPb"]=31264;var __ZTIPb=Module["__ZTIPb"]=31268;var __ZTSPKb=Module["__ZTSPKb"]=31284;var __ZTIPKb=Module["__ZTIPKb"]=31288;var __ZTSw=Module["__ZTSw"]=31304;var __ZTIw=Module["__ZTIw"]=31308;var __ZTSPw=Module["__ZTSPw"]=31316;var __ZTIPw=Module["__ZTIPw"]=31320;var __ZTSPKw=Module["__ZTSPKw"]=31336;var __ZTIPKw=Module["__ZTIPKw"]=31340;var __ZTSc=Module["__ZTSc"]=31356;var __ZTSPc=Module["__ZTSPc"]=31368;var __ZTIPc=Module["__ZTIPc"]=31372;var __ZTSPKc=Module["__ZTSPKc"]=31388;var __ZTIPKc=Module["__ZTIPKc"]=31392;var __ZTSh=Module["__ZTSh"]=31408;var __ZTSPh=Module["__ZTSPh"]=31420;var __ZTIPh=Module["__ZTIPh"]=31424;var __ZTSPKh=Module["__ZTSPKh"]=31440;var __ZTIPKh=Module["__ZTIPKh"]=31444;var __ZTSa=Module["__ZTSa"]=31460;var __ZTSPa=Module["__ZTSPa"]=31472;var __ZTIPa=Module["__ZTIPa"]=31476;var __ZTSPKa=Module["__ZTSPKa"]=31492;var __ZTIPKa=Module["__ZTIPKa"]=31496;var __ZTSs=Module["__ZTSs"]=31512;var __ZTSPs=Module["__ZTSPs"]=31524;var __ZTIPs=Module["__ZTIPs"]=31528;var __ZTSPKs=Module["__ZTSPKs"]=31544;var __ZTIPKs=Module["__ZTIPKs"]=31548;var __ZTSt=Module["__ZTSt"]=31564;var __ZTSPt=Module["__ZTSPt"]=31576;var __ZTIPt=Module["__ZTIPt"]=31580;var __ZTSPKt=Module["__ZTSPKt"]=31596;var __ZTIPKt=Module["__ZTIPKt"]=31600;var __ZTSi=Module["__ZTSi"]=31616;var __ZTSPi=Module["__ZTSPi"]=31628;var __ZTIPi=Module["__ZTIPi"]=31632;var __ZTSPKi=Module["__ZTSPKi"]=31648;var __ZTIPKi=Module["__ZTIPKi"]=31652;var __ZTSj=Module["__ZTSj"]=31668;var __ZTSPj=Module["__ZTSPj"]=31680;var __ZTIPj=Module["__ZTIPj"]=31684;var __ZTSPKj=Module["__ZTSPKj"]=31700;var __ZTIPKj=Module["__ZTIPKj"]=31704;var __ZTSl=Module["__ZTSl"]=31720;var __ZTSPl=Module["__ZTSPl"]=31732;var __ZTIPl=Module["__ZTIPl"]=31736;var __ZTSPKl=Module["__ZTSPKl"]=31752;var __ZTIPKl=Module["__ZTIPKl"]=31756;var __ZTSm=Module["__ZTSm"]=31772;var __ZTSPm=Module["__ZTSPm"]=31784;var __ZTIPm=Module["__ZTIPm"]=31788;var __ZTSPKm=Module["__ZTSPKm"]=31804;var __ZTIPKm=Module["__ZTIPKm"]=31808;var __ZTSx=Module["__ZTSx"]=31824;var __ZTSPx=Module["__ZTSPx"]=31836;var __ZTIPx=Module["__ZTIPx"]=31840;var __ZTSPKx=Module["__ZTSPKx"]=31856;var __ZTIPKx=Module["__ZTIPKx"]=31860;var __ZTSy=Module["__ZTSy"]=31876;var __ZTSPy=Module["__ZTSPy"]=31888;var __ZTIPy=Module["__ZTIPy"]=31892;var __ZTSPKy=Module["__ZTSPKy"]=31908;var __ZTIPKy=Module["__ZTIPKy"]=31912;var __ZTSn=Module["__ZTSn"]=31928;var __ZTIn=Module["__ZTIn"]=31932;var __ZTSPn=Module["__ZTSPn"]=31940;var __ZTIPn=Module["__ZTIPn"]=31944;var __ZTSPKn=Module["__ZTSPKn"]=31960;var __ZTIPKn=Module["__ZTIPKn"]=31964;var __ZTSo=Module["__ZTSo"]=31980;var __ZTIo=Module["__ZTIo"]=31984;var __ZTSPo=Module["__ZTSPo"]=31992;var __ZTIPo=Module["__ZTIPo"]=31996;var __ZTSPKo=Module["__ZTSPKo"]=32012;var __ZTIPKo=Module["__ZTIPKo"]=32016;var __ZTSDh=Module["__ZTSDh"]=32032;var __ZTIDh=Module["__ZTIDh"]=32036;var __ZTSPDh=Module["__ZTSPDh"]=32044;var __ZTIPDh=Module["__ZTIPDh"]=32048;var __ZTSPKDh=Module["__ZTSPKDh"]=32064;var __ZTIPKDh=Module["__ZTIPKDh"]=32072;var __ZTSf=Module["__ZTSf"]=32088;var __ZTSPf=Module["__ZTSPf"]=32100;var __ZTIPf=Module["__ZTIPf"]=32104;var __ZTSPKf=Module["__ZTSPKf"]=32120;var __ZTIPKf=Module["__ZTIPKf"]=32124;var __ZTSd=Module["__ZTSd"]=32140;var __ZTSPd=Module["__ZTSPd"]=32152;var __ZTIPd=Module["__ZTIPd"]=32156;var __ZTSPKd=Module["__ZTSPKd"]=32172;var __ZTIPKd=Module["__ZTIPKd"]=32176;var __ZTSe=Module["__ZTSe"]=32192;var __ZTIe=Module["__ZTIe"]=32196;var __ZTSPe=Module["__ZTSPe"]=32204;var __ZTIPe=Module["__ZTIPe"]=32208;var __ZTSPKe=Module["__ZTSPKe"]=32224;var __ZTIPKe=Module["__ZTIPKe"]=32228;var __ZTSg=Module["__ZTSg"]=32244;var __ZTIg=Module["__ZTIg"]=32248;var __ZTSPg=Module["__ZTSPg"]=32256;var __ZTIPg=Module["__ZTIPg"]=32260;var __ZTSPKg=Module["__ZTSPKg"]=32276;var __ZTIPKg=Module["__ZTIPKg"]=32280;var __ZTSDu=Module["__ZTSDu"]=32296;var __ZTIDu=Module["__ZTIDu"]=32300;var __ZTSPDu=Module["__ZTSPDu"]=32308;var __ZTIPDu=Module["__ZTIPDu"]=32312;var __ZTSPKDu=Module["__ZTSPKDu"]=32328;var __ZTIPKDu=Module["__ZTIPKDu"]=32336;var __ZTSDs=Module["__ZTSDs"]=32352;var __ZTIDs=Module["__ZTIDs"]=32356;var __ZTSPDs=Module["__ZTSPDs"]=32364;var __ZTIPDs=Module["__ZTIPDs"]=32368;var __ZTSPKDs=Module["__ZTSPKDs"]=32384;var __ZTIPKDs=Module["__ZTIPKDs"]=32392;var __ZTSDi=Module["__ZTSDi"]=32408;var __ZTIDi=Module["__ZTIDi"]=32412;var __ZTSPDi=Module["__ZTSPDi"]=32420;var __ZTIPDi=Module["__ZTIPDi"]=32424;var __ZTSPKDi=Module["__ZTSPKDi"]=32440;var __ZTIPKDi=Module["__ZTIPKDi"]=32448;var __ZTVN10__cxxabiv117__array_type_infoE=Module["__ZTVN10__cxxabiv117__array_type_infoE"]=32464;var __ZTIN10__cxxabiv117__array_type_infoE=Module["__ZTIN10__cxxabiv117__array_type_infoE"]=32528;var __ZTSN10__cxxabiv117__array_type_infoE=Module["__ZTSN10__cxxabiv117__array_type_infoE"]=32492;var __ZTVN10__cxxabiv120__function_type_infoE=Module["__ZTVN10__cxxabiv120__function_type_infoE"]=32540;var __ZTVN10__cxxabiv116__enum_type_infoE=Module["__ZTVN10__cxxabiv116__enum_type_infoE"]=32568;var __ZTIN10__cxxabiv116__enum_type_infoE=Module["__ZTIN10__cxxabiv116__enum_type_infoE"]=32632;var __ZTSN10__cxxabiv116__enum_type_infoE=Module["__ZTSN10__cxxabiv116__enum_type_infoE"]=32596;var __ZTIN10__cxxabiv120__si_class_type_infoE=Module["__ZTIN10__cxxabiv120__si_class_type_infoE"]=32764;var __ZTSN10__cxxabiv120__si_class_type_infoE=Module["__ZTSN10__cxxabiv120__si_class_type_infoE"]=32724;var __ZTIN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTIN10__cxxabiv121__vmi_class_type_infoE"]=32856;var __ZTSN10__cxxabiv121__vmi_class_type_infoE=Module["__ZTSN10__cxxabiv121__vmi_class_type_infoE"]=32816;var __ZTVN10__cxxabiv117__pbase_type_infoE=Module["__ZTVN10__cxxabiv117__pbase_type_infoE"]=32868;var __ZTVN10__cxxabiv129__pointer_to_member_type_infoE=Module["__ZTVN10__cxxabiv129__pointer_to_member_type_infoE"]=32924;var __ZTVSt9bad_alloc=Module["__ZTVSt9bad_alloc"]=32952;var __ZTVSt20bad_array_new_length=Module["__ZTVSt20bad_array_new_length"]=32972;var __ZTISt9bad_alloc=Module["__ZTISt9bad_alloc"]=33104;var __ZTSSt9exception=Module["__ZTSSt9exception"]=33012;var __ZTVSt13bad_exception=Module["__ZTVSt13bad_exception"]=33036;var __ZTISt13bad_exception=Module["__ZTISt13bad_exception"]=33076;var __ZTSSt13bad_exception=Module["__ZTSSt13bad_exception"]=33056;var __ZTSSt9bad_alloc=Module["__ZTSSt9bad_alloc"]=33088;var __ZTSSt20bad_array_new_length=Module["__ZTSSt20bad_array_new_length"]=33116;var __ZTISt11logic_error=Module["__ZTISt11logic_error"]=33252;var __ZTISt13runtime_error=Module["__ZTISt13runtime_error"]=33492;var __ZTVSt12domain_error=Module["__ZTVSt12domain_error"]=33196;var __ZTISt12domain_error=Module["__ZTISt12domain_error"]=33264;var __ZTSSt12domain_error=Module["__ZTSSt12domain_error"]=33216;var __ZTSSt11logic_error=Module["__ZTSSt11logic_error"]=33233;var __ZTVSt16invalid_argument=Module["__ZTVSt16invalid_argument"]=33276;var __ZTISt16invalid_argument=Module["__ZTISt16invalid_argument"]=33320;var __ZTSSt16invalid_argument=Module["__ZTSSt16invalid_argument"]=33296;var __ZTSSt12length_error=Module["__ZTSSt12length_error"]=33352;var __ZTSSt12out_of_range=Module["__ZTSSt12out_of_range"]=33404;var __ZTVSt11range_error=Module["__ZTVSt11range_error"]=33436;var __ZTISt11range_error=Module["__ZTISt11range_error"]=33504;var __ZTSSt11range_error=Module["__ZTSSt11range_error"]=33456;var __ZTSSt13runtime_error=Module["__ZTSSt13runtime_error"]=33472;var __ZTVSt14overflow_error=Module["__ZTVSt14overflow_error"]=33516;var __ZTISt14overflow_error=Module["__ZTISt14overflow_error"]=33556;var __ZTSSt14overflow_error=Module["__ZTSSt14overflow_error"]=33536;var __ZTVSt15underflow_error=Module["__ZTVSt15underflow_error"]=33568;var __ZTISt15underflow_error=Module["__ZTISt15underflow_error"]=33608;var __ZTSSt15underflow_error=Module["__ZTSSt15underflow_error"]=33588;var __ZTVSt8bad_cast=Module["__ZTVSt8bad_cast"]=33620;var __ZTVSt10bad_typeid=Module["__ZTVSt10bad_typeid"]=33640;var __ZTISt8bad_cast=Module["__ZTISt8bad_cast"]=33712;var __ZTISt10bad_typeid=Module["__ZTISt10bad_typeid"]=33740;var __ZTVSt9type_info=Module["__ZTVSt9type_info"]=33660;var __ZTSSt9type_info=Module["__ZTSSt9type_info"]=33676;var __ZTSSt8bad_cast=Module["__ZTSSt8bad_cast"]=33700;var __ZTSSt10bad_typeid=Module["__ZTSSt10bad_typeid"]=33724;var calledRun;dependenciesFulfilled=function runCaller(){if(!calledRun)run();if(!calledRun)dependenciesFulfilled=runCaller};function run(){if(runDependencies>0){return}preRun();if(runDependencies>0){return}function doRun(){if(calledRun)return;calledRun=true;Module["calledRun"]=true;if(ABORT)return;initRuntime();Module["onRuntimeInitialized"]?.();postRun()}if(Module["setStatus"]){Module["setStatus"]("Running...");setTimeout(function(){setTimeout(function(){Module["setStatus"]("")},1);doRun()},1)}else{doRun()}}if(Module["preInit"]){if(typeof Module["preInit"]=="function")Module["preInit"]=[Module["preInit"]];while(Module["preInit"].length>0){Module["preInit"].pop()()}}run(); diff --git a/docs/public/config/failsafe/index.wasm b/docs/public/config/failsafe/index.wasm index 6a5d0d87079bb2eb9b32eb9acf5c12b39e0bbb9d..f80b40753dcccf4d09d58574b55b85185ef72db5 100644 GIT binary patch delta 28783 zcma)F33yaR@~?g~2}ve_K`}tMUIIe6Ps5qa>*0oQqk@8ff?~LWpn?iB913WJ=tBn- z*U`llT~~sMyQn}Sctl0T6%{r5kE)C`W?Gb@d^*Iu{k>CEnvZKX*_JL>d2VT3 z>Ts4!n)G_tO zK6HO#qdp#8CHTQ9@%pO*kI}3Om3ls44RuwFnmc}Vf8tOGADQ?;i-L8YybNzlknNRu zvaJ-QW12K`rzBm|KPHWsiOus|&u5daRwKNQO?uIMz4Bg9Ub?bExj~_S~{C zgXZ%}Row4en8D)G>&PmGSOPDt(#p0LW_YDnrTd_7SKP@0k3LyEF*#MKt!{ow8}+5T zA!W4s-94O=qrP-A>!z!%?y$O@)bH-%x(wMakWU1XSdSq?>T#dEdfaEDKn@7xxIo(a zxz9{L_qp58eO~Zqt1sQ({kGcbHmc8%!Sw^`OLtZMbhWkksrrqSdc)m)Q5W@U@h=y3 zRvjKZpzJt*s?UzoQBPhgvOT_M<5j%ar{(C))nc}mm#gl`1|1u1uC@ky9oySk`E44J z;^pb{EYwA=+hBBZ(Hbi+)AFXraqk}+bZZ$EdYK-!@@mUgSr*yMG@Y1qb9M26OX^th zTdFO+rMh@b!}7S)f)#A#Hfe93f09kU23(K2otuqP6>g|mzoxuK8DuM6aIYs%m}goE z8De4;?nli=sIS~hn|CnXESqY&QLS!snomeDYptu?x0|P_3inX+er?&v>hP{$`-tPs z=JUl?*f%gm*}j?DTBr-wxg%Qqs4CrTdkEY7D*IV3dZv$8U%3V8_oRGfj3RD?*U?pO ztBh&c%#a5!c8mcgY+m;;E%4~0Zdu#*?)Mq~+>%1> z=XLZBsjw?3EA#|IJuTAP3q8SbG#n0xz1%D*^w>!{IZx-$*9V^d;OV#pEWNxCyKFhi32m6TZlIm zy3e)jqqe)>x9pe#rmSZ{q1&d_RJFrh-Ku;1hC&a^eYsV3uYy7k1lr!b4Don{BHt#S zgTg|yJy|rQc)Siv$-1;n=!lsu(!}m=L=)baM|jqNd6m36b5;iF zMYc6d*O{N8W(k2ldVlNmxMKw#{fgVVb*Coc_Vgm#Bb_MEtgHAycV6o@==pH#v=(Mu zwl%!=cx=n|=B3B+*!Q>YXl*KVJ#9Mw5AkBUN8OQaV)7TZ>6o>-(9_nUo|fNMJRMR` z(3=ZAw$cfCJSFGP)|Nu|qc+#3%MPJ4-cX#Jctgv0L-(r8Ikvb%B^Ci^7{^}oj5GWu zb9*{0ob31!DI_*d=h=8Cb-?|x?U>l1;XVJ*aM!hK*qp82cyiO_?32M=*KPuih9m8^ zo1;PT(ZK9%b?(uyr~T%nGsAS}cSuz{s!QE}bQo<$Mzu!hSK6FGd?rO7#E zTXL@0#D~xQo%URC4n610VVZlo)76d7%%fe$OrV+NO82JD?;0_2EXLx2#MKhxPU^DL zcr(&fZhBYtX8pQemc$doCak|IzP;-@%L-S!$vt}1J5b=!T^Jmy=hNZpzmDpm)DCy_ zWtUuD6SVMgXe$XVdL=90nT9We2BlD%O+H%S>*eRS6QK!q{C`fhH6Ewr%!udzJB0i#bc#Bw^yH@NmJ3TBzIAt zUP+_T+(+&UeR?H1Xgagp6McGyx}e!5&!4Ib!p6n0)7lg^4qb z#o2wEtN6`TO0WFMo!0LWy;2VF`d;$4Azxu*D=ws#=uOp#A=g)PjB4>Qj!I#*rK?s8 z(`dEDVL%|eQD{eupd{9>sM^x&*GRt&CdMFdh z`YO_8VUG!pcVN8wMMm`@(%Zuxt+-D~*rSE&xljyO6r+z#lYTme+7ct%93y)?hKk0h zV#}i+ilH{dsMg1*?vJ4gV^js<;^J(-3Kg0$@W>CX62-3Cqf~8kp;v?a^N+WLaTL=EbeK8sPjEuW4toAuF?sk71oOaeQ?v`P^a;}KG zy;)XSOhlOxQ5yeehEW=S-Y`nzd8*3Kl~Ed>WfjF_6d4(7|I{$no;QrOGK{_FidgH- zvZ65&Q6r-2Ppw9ktj5UNt5GGZvF}_NRh}%XFeanW$oTofGTb``ooz%v3(NiIvi#YT zWrbrb!-nOa3$r|Df%lwmM0-TWfpcZ-@nl)~G1Dh8{qjF0qWpXj>XGB#0DG}8oVp8q(trihqohzc+lVv#&;ml&U zv+7S7=_)qTvjnUXBRzDkfK}css|y5h806FI|CE6BEMRi&5v&&hN6r? z(S=rCE7B+BP_sxMTkg>vvMlnC7ud=bvFqu|6&^-%pVccoI>42J6($VukCtls*}Ye< zkltHXdUTPgR=N)iJ*Ey6uN}5Vsl9Ha+)1j+y*alPE=hmM<>X!85xKRpXv8-RuO#bi zPfZr>ol(u)JtHQ^u4gqlJ&8NaeYRj^U}cu15T)H8x_kX zzBB6fbFz1w9jWKD6|#4#CVOX{xvzRONA{e(Q@F1dj9zGNbyn?L9cTGG3p48AR%efS z#aFdb!W`0tce+20X>Dy;={6kuxjIn%+t@mB>i>#QUwKTas^Z@#{zs|*EB@r_D?I9e z+jYuiK9lpx;AqR8KP8}w+-*}PHs-up3i*7t$Bwg=?bS4-2`}c3;+9iSs?amPDE(YL zf3n_iRO!NGtu*-?=v!P z1t%DQ&c z_gjWPR>pmf3cOV6M!-LIGTaC#khlbkQnzS&dLwTCtDczE>lI4J*(CM1+{4q; z$1w64|M|!YrQ>boC++n&%pkp6wkX#X>P)!v0)+0>GmOY@E+le2kS8ug`8JUIE<_oB zy<0-!WV3>^ay5dgbgBT$Q?%0iS@+MBZm1gx@I5{f%Gu+7rgUSSCcy9tPC{|6JiNlA6{iiN zCoOi&{<=QhbHfQsm!Gusfs-*O)8s5C^L3dLFVocT)7)3-LnqnG?3>l39=9Jz)*gN2 zq@_0Uyt!K9gF=$VUwshesOFwx~=~gyBPm7JO~ ztxZj~u<9;z$ot|*KbGiA70x>&Y*2B{(4Sb z6$=L>7gjyDmnw35&AY}I3kURuYWJ~uE#o({um*9~&N zyDKfm#sfCn3NE%PJ#KVW<6($`&*Y0ZXDk_z9oCslQK3nJcsT&}ry{wM?(uOjX4m4X zzIGp7m39_WNvzZ`UFk7QYvonECa>}bOn*3!=?|Q(sbRVrOlu`pye6^oznQvA*EBgx zPsyy*uq*(}T8R~}Nv!;Dme%LzPpRZmYPc4HYpqm@*Q8SZfa~4f^A<|dCpBExgKMqq ziPvOL{(x&~{CQj@VN%0&1Gv`8mv~LSJZd!B0aQuO$znsrhk{UHki@@|uPQz<*8h^mFT9^*0 zJ$y-H)G#dp(=%BNuVgX)fafYPowImK=Awq@cJMrtxbT|y8{;D{;Ek;H!ZW3|p6lIF zYcFYiCO6?VPdNXZ#~~T(gxWkL9Z{oK8T2}njqsXBoeT1`(k%}^HhOFid;S%!e_dJ- z%q@X%DuNUH;)GuT^D~(UFJ~gWI?9;{-^AFF>CRqvO_IFKoa6t;xOW#`-2CigB=(wM z8HttdOND9eY7elI^DQ+4GzWpF=ElnUvh;%}dPMg@ulq}A{g<+B{SP73K_fClp$;xbQL4+Uv# z3e~)<__&8%N8X6s51ty(s4UE#MtdE8PO=l)diZlIpDuU1KHX%@HoQvkTizSy#mw80 z)Zh$@11O`BR)hHqEamU#gT(Yi$tuKD;Veqx=oDo+db|6`(~X7}$G9e2K0A^1Q$ALZ z|F-o|Mk1@y)jlGFS6YHXPfw< zG5Jx;eehY`tT4twVgnw^7qvJXeYS1aaEt>UP!99EqIndyNgu(usuadmrQF=Dx>=>d z6q)x7%h5m8;``Lrw#oYx2DVS-xfNT}d}T2fWy-DIs+$$XSeQJ&<>+N%6J~H%7q#_8 zV=SV|y|<`Ia$$@^p~`c&7F`lL^Clc;-h>~DJ;<8JVN5o^*N0=$Ozzxr@N6v7jFoQ? zVqVmm*X7u1nU`nIj+@0Y+3^sIsWn-#UQ;nwlHjg+;q=u!aavC7B^qi!9aGypN!L<) zG^W`kvMmR1)kf=(d_J_Lw%TVgfE3PE8?{ZY`l+*&HgDpbZZ?K1ukNw8Twl#&uI0qu zzM=DrVNb}sznfR^T1wkcS`y2agV*s|GrhgG%4d;72&ayX%KQTF<36?K**wB$Ss^ky z^DBGojlSm5+9n<5ukXZpz_rD(=Zx20zs<^=<#3F%2+~-uqxU5FJBbUC_i#>!QeV}S zi!7^=cnq%{Z(DX6f9=yKk0F^BWm=8u*D+p3m$`adYIeDCKuP1h4!<7TNp|9ro*qiJ zd^Io9>=??IdH658sKlVP`i_i5YpFisuHTkbuZ*9EJ5n>A+@-qA{dimYKr@yM4}V@M zj+4?YX8Bx=uU0-LN=x_Xugs$^e~ETTs&-s`MLxaH4LsK=^x-GU=1&w1$8-_ZDBZA< z>1Ho2U%R7Yx3Gt{Q_eUu@u=p#@`#T*Jl@Z z=*~z298f)u*M&;N0RDPju=Q`KF_q7+(+~+ILgrbVt=Fa!n`IP5_M-MAmjv zgQPxH>Ww46bW$DDx%V>*h(>npGGoqy>u$O+f8mU|-EWyTdms_xjzx55)iRE&4I=k- zR?U;94Fswmw+(8#K`n@(3L;;`P$dR+V+>Uh>DmQU-pH~ps(I4v7^(xe4a4yUwJ3(V zBl2Dhwb`JqkD>NP(z}A{Xk=(tHB9{!S>IK)8T0q=l}{y;{@3@)cge*>MDm}+WUf*& z|4$#}K7P_aai4lbiTtD={XzNEMWp{8N$#dvssBW}c2f*uZHm0rO|_9`mqkRaA}3Jsxth;KWHbws1T?IniZ{cF1R*Q&k zA)={^iMA{z8hs1V>M&8sVi^=Y!?5AE2&{ZDks<>dFxSvjFn+*X!5;!mrO!|NpI z7=Eph6`}^W5skjqbg*wT!WuDb__e~U$8AO!!)}FwLl}Rnp&1XFT%oyDXl8XeNk?m}sUU+5w^x5j0b1_JM|B(?IhTEInT4hd8@@n@dVz>x3qh01_=SdM0%%4H%|fA> z4H|~s2%0eCZ!|Oow-d2^S}8;~3Q-h949f#i3FGq&Q5ghn7n(ew*$*0q%?8aO#?Ll1 zM?rH$Xl4sd!W}XTApy<-QPVq!M$a)snRl33uo*Udju7=TL;_m`n$e73WN0RVX1vfW z5}JI_FpTYzXL}{%7c)(Ws1QV}g=n!5Z3Yp;*nF92JLBgXL9c*jhtL?SKL8qr%>&I5 z#?Lb}$3RmhH1kAGa%hP$1_ln8X$09zcq#)SkLMw(1=N^Wc13HFZ4`CCy&-DgB z9dwg~?s^fn2s8|v4w_H_cbIO7Hh`#5h^7nCGazEv3=owueukmh3z}DiW`@vIf`(x? zfaWOUZ!k2p)C}s_5(?4i;Wr3TgQaFBjx8Y?aI=|-%%waNHw(T8h&nKAIQKBjhJcRY z0~Q#%sX}LV&TP<4H*^bPbYYqaoZNgk~pf2H_?{$U8_B*$#mW=Rf{XCA{x(DO+*tS zPxVp5J2J~I;WOZsi--mi(KSRgn23fD(G){LC6V;Ls)=e9$?mI~Tt0dkQ9Cm0%*)1q z76Hcg!pp*cynwM`@d(E)>^)=Abu;o8-Z)R(HXq?f!=`VK$Upk3mK|6rdzm2}x3KrM z)22_EHhcCw_Orw|rv}%pi#zY-OZovmX&Di##ecq9M%0#!x8TjsfA%jodyV%_K44Xm z5&cy6X3X|Iu;qH$GQ)!ZWJVt8r`pI2`j?*pPl|ldPqh^AkXqovNMbg?chmw`MzXV2 z_vXTTxfvSQiLpaikGw>mim$OyN-rT)MEpX8aImyN4;1Hm_D~Q+? zvLnE@p-quyIjTv2p67xUJpa9TLa&>)V4-NRc|~lZyLMs3!o~SBZk%o=dWXU3uU1*U zohmbOdyZ<^l^MM|hsYl$D#O(BS)H(w$nqM(ZH!+jqoPTXcXL!r2?M^JLzD?{cqLJ9 z;+q9gUm}Vv;?Y{9%%UR^WfM`3^wC9YEZ^Vem%`#6&0kpJD`Fha!gvJ*WH724KR~h&ahp5O)^v_&_pEZ)`p^c4m=C>xQ zLqt8a>GxnGDV-0~xQsgMdGnC1?`zIwxO5t;PvO9^P>Nynu4o<(Y!%JJfsgr6r*L3z zT_TH!PF+sa@L%us^5qhFdDtU}x_2)QEM{XSa+0qgdVBBQ?4`n(XvxLg&dvVrGQrc6 zJxzISY@m~k++e*)(lMuWpkeTHYg4|B_M0h87%rXO+Aw%a7=%mrj5lrnRgrCuN=>^G z_?LkH*LWfh{M1#EFC3K`8V3B|f&V-3KTqTtT;?oJA-ewh>z#{a1@iUiwnS|wt;>F* ztr^H=ZOu%NpJ?Q^>T38Gv@m7nFas|h%Vjul$57MmZrY*1KK5BeR6K_N8xEYFVA|hy zF$|`I(J2tRU^E8pi_v}pd|dF^0zO6H(+_<94Y~zF7YYYj1Mmw7Zv&$RXpaS>TfnFR z7(EHPaZum{=-vn2D743+-2hAM>BR#q3#9iXdONf?H>YiE>OfEjQ}{jvrvm;q6j%ay z0^ly-Z2&*cCjk*n1iUHuA47XS2H+cpaBm7mQVfQ#fzd7y3(1t9wlWII4s2C@h18}<+I(N9FF(vPT4x@q?WpZVak4}8{x&lBKtyWtc0=U`Po zbO=hc1Mzea?*Z{`Al?Atxlm#bl=vaZ2>%#-nt{)i;PX%LnF>DlfX_52F=&XYA9@qS zeh?1>@lzlk1mdM29uFnPL5clP;wA9$fKN8~YyzL&;4>e521AJtS&3&r{2Q2e0r5Hz zcL4Ep5cfg9-caI2DDepR90tB6_$&vX7T|Lw_;iF4*AG?oLu)}?0pe5;-wfi5Ks*e@ zHu|-I5>Y4-0-tw*PXwQt;1dTv+2C_Al=zL6$OrLm5T69|t3iA$gV%hY(*?xw=og26 zcR`71;PX)nVJ-L5t+3Az|J0{Ex(FsnNP&m*FuAmWIK{vR9IGe~r zL@st@KFWzGgDBghY=H6{vqIhgF?H_RffLoNp#1@iVma@`K}MnsUFWa}yX(n`y$+ZZk}od#x$&nr6y&DBqcC+VN%vLiB{h z7(_iTF^F&E(nd6+smTSrA%ci@XBmYQrn)Dl@E5rqMxDN0SRu!01Ni9vG7!=zyP<4} zvVoK#qBsD43mSrNP(FjT^FZ)@81XU)xLMlaz*WNy-8|tFbsDxZ4r_|E!=+!hFp9r2 z&h#q;{h9`{|91s$}R{8=7Yf-xF2_t3x3qOSQHNj z7GA=F!ll28-zVBAYaK5AsUC+UdvhYq41Voo?Ej7u4p!;U(oGaMkdqfwt}m0)aVq;5 z!X{8`_(-C^Jv^Xq+DN&`=L9&>K}7$-!80(ITaL2<+>ZmNg#X^`RanC7FOmHp z)$a>oc`!*HgQCueerDvy!El@~j5<$`V8&COGU-XKtL}D zcpL)S#AZN7NP+J~;i#iVaOz=W&Nke4(*++6927s2uY0%dYjP89M-t7uXhok%BZ$`R zzPVpGm)ESdlY}WQzVny|&Ok-N} zaKUejaU2?9#I6 z#{tj?gj!xo{O>BzQrZ5F^MdT&sI$4gu}QD&Qd>WnVN9$4r9|SbtR4&7TNf=-nE8c;k&K5aS9OovOz_n6_124i>GjQhoHBvQBH4J6KZ6%D8 z70KQ|(X32cksA(FN%wsHf_Rxqrw?Z-iJUqZUt@?#6blOH3>SPj=RK2V49t=Ri8>Jp zcgllllHJSA4w)NUh{8C+T4o7jsu0t(_2Vdi7Qx9uZL()Mb(;|#@(>MxAI<_Dze>-p zLzLXX9C-(|G4)52@-bsPp2bW@XC7 zdz1t}gr8lC_Eaf*1ZRp#g#$yx-$r$h?mQq{&y{ef(&;8qO}_pCikEOclmotJS{qY1 z2HUf78y+hmu&pP^k!b6tql^u{gAuP16Cg^1H@Owu;JG+b9v^uhQQk*nbk6;A>+ObaQhvkcZ_K9xm-8 zyE5u5M1G;j+*Sk2#fI~B-OI$`+s<4$Tf;d?GSYCMVyp>Qj))C7&QJp{U5qL2-OkL! zMY4OVbS~fmqbkKf6+EuzG+8<)cz8GZqkGUMltoFtq2BvAV*3UJRGG{`2_A`IY ze$U|P4hY;O@mJN$+hk<XcI$9W=?tv6gcX0X{tJ8?u!=_HC}KQD)NzP4m!;lRITW}?nV zMzE7&a!XDd*-hcVJD1BqbB>_=zsn^l9?B+6*%2tRdw`jd#|O&P_nU4Ql=cyaRO#G{ zkadErDbWBNm1AXQ9H;SMBWMh!dJ~p%h`CGzp2PN?D>EIc(i&^z$4G~Q@II`OgC&|S z1Ve)Fbv4FwtMMDO3gx$muO35EY$I|~e}ji!i*^Lu(|rHS-|GC=i{{~`|<@#d4{k$|5 z(PS~s)c)<;o@5;@rVwci_EiC%s&L4TEIqNfih88MY&iF>oRHZ|=>(|FzXW?u^W!-;0= z+$R8sTn;Cd~Khu9KHt=ihOlUbA`{l#F zrr&>tn}^Bi&51tjMbx7?QAIDJZ?VsQ>nnUhGyuuo?O^1LHv(P*qmN+!<8YyBjq(#P z`r0s}Ebw_6d@h4R{{)}C;1dLWBPscf_)4R3pN^&sV}HDeVDX){Mxo}-h~kLoQ#kQg zK$i)@GsY2d;Qu_L+)8+g-$on0*NM3m>L1|}Xly7y>y!u4_jolM%`bHGo-qZG>ixoyCUQ1qV5%}sC0U|bcW;wy7= zdYc10&{7B{^k=5)Fr)a35oOOTZwA^Ynhuw+H>jpq~MH3-mXE{soCN9Otea z8Gkr%N_JY0U<4t^M%><~qy4GiiMHez1#U)pMBt8-59i+l3f&3k-y8~gMWG@6Cv=dl zmD8fV%#@Qg%tQ`OV-vUMOoxVjVO;OB=1$W=ndv5$`kT2CQK3noI2+;GHj0aIbRS8W zhD#gbO4ve{wj{Vhd}Yb*_c5@San)=Xdj@-$U!95Q-ic;ypO%h2g0Gr#_fb6jDJYgC z5k*OGvRp(;`gfH8zebcm>F9SBfJ_u@D-!5Q~!PAOr4H`2s;xZ(W$Co z=vkAZa$XfM>86NcPx9wd6m?RO$ekfK&5b$T#n{88QDgxpUuA4@VK)?r5-!`irJN1n(tP7xOW!evlrtDB`HLK{p{VnUC_v6{?RX>$0;%Ro z7?>h6Z@>I^e5Y`?lzVfYFf*$sOp;f!z>VUUqq?8K^Ml>skG~K>;lLQ-G7Wf|U?J{Cp4?*VWXj3!tEeOG81An(^2XB{PG&itQ zOekF1TWmO7I-`~GZ%@PY_GOA&INtwTS&QTSw>LF+ulEO-H9ZQ~|Caa@Tknwwr!0_a zV!6N=Th=z`Ao^t?ayc=I=%^w(kYfUjPmoS{bh!BlD5o`1b%3a_Gu*-l@T8MOM&>hdz&qKH*Y@n^dBBlW=JS zLVqV6)JN16T32BK*>T%Yi=x{KE!s1$1Qebk#z&h~!UKEv!?$Blk^L z&DE!oB8I*Y*~djBQpLs15&sO;B4Zq1W5X{E7y*`*VCh0+uRf76GgNbx8p)rbT3APW zNABb1zavF6R0~xU*~i7&NEH{eBmV1Ei_kEzd`Cuke84oYYyg%T_?skG;siS3aVZ1s z*=Fn0P_&n$?1yp~-hBL6wJLE%L`h~bLUbEet2xTuScVsn&%Xpa@CO{sSKvIIiHN-k z1WZ7ggz^TIx1ekX1(IM5twaI-=27BMqV4eV?LhE6ynSD^SK^v?9Q~8UX%p?hNI#S^ zobxQ&<54aZ4?r}#0nxrXM9+3JNt7;(50MjC-IeI|?cH*=q;dINb^`>$%VB`if<(7B z=#&!&_)UPnFZb4P>GLSRN0}q8gJ>)IH-^D3H@=V#$~!^0^zk53h-28@Al!`dOT;>< zcmrB3-a8z)6%79?{fLHvp=(C!^!1tO^Cals#ZuV=&4+eT+3{6+5Rxq$uM(FL4L%AN zumM5Z_0lmvSR$#)f^*EFqn8XQl!Gs-PX>$v-y%G{51~vL zliR4Wm{*L-+`CkpV2l#sTJl8;*d!5cpy_ z;md=$CfPxCjd7M%Mf|f==g{l$TmNh|Zx$GzG0L`>8<(nRptK4V%`7r|{4lzlP212UnMLD{l9^Mmiggx-|Y#E{_Y z6U}Sg<&nx+s$pmbPLs#5Q2Ql;P;fL5mJ5c_XL&T2g$yCFpT@Q1wxe8lmKP>kd zTqEA-Y^L>9JSu*K^?Ax%Cqnd$>^Y);Bh&E+g5-*}hH$wk77i4`5Jq>D3Eg!gUKuBf z8!Qi2Amf=O22rk`laC09zQ8BiFT>$?0(`Q-Lqyp?JS|_Q6Mf9zbraDG@+CG=YrroD z{4&5Vh5{X-KoJy3f&%wJP#F}6LQV?c{TR;sz9|rEAZR-TZGfOSzt*~zpFq%HAZ~%6D*)dE1%Aev`EMwYB3^}PDwblT%*2Di z_e7DX(_WUs4jzCab-?EvD59=~-<^*`{}Pl*V3+}hPk>=HvR?0k;c1NQb1*yx`k5$` zQI=q)ev_GcFt`}}-VcG{Yhd^*7=8eTKZ3y&lpd7VfZ>~9I06ix1izi&cLez1awsqZg4RROLJ0Z-g8YD2f!}1n3m|7U;2*OBY<~$r9D-G6LxEB#5QGAopuhkq zumFO_L4h&|`Vsuzg`j?b&jNfn;M-?n|9^vR^*R*z7Kd{dY@rvH;w30@32b2#6nP7Z z{2huk0(>ywZ2(^nMfO0Ezg~y^?*}3PLv%gI{aF z;{jg)_~VeX{5tIaAK@69192KNaW@pG#8O-b1$IJ#tDwLd2;!fV@ShJMC=T$07|>Y2 zmqE_75D@P`fm2wD&!9jLC{O|gdP0Hwpg?aZFcX4?K!N8W=qm_%1#-FqJ{9ng1H?a| zKm`=o0R=vXEo`4*!k`V;nv~1G#eqbfK9_UA*RtO(iFe4kTQVlLei>yD$+Sw7Aqw0I zcpHnj0E_5jJ$=VnhZ5nEt7rycosUacf_3p+~@^2Sd# z1jj|8^58*Hs64n#A|qS(62;1c6D4n17WiGRM`7oP89?BG89-nG1a~k42^=;dvC{^j z^TBc0{|~n^0-tVWvSeLMLexnH<87TJ6btcr}w|Sk-_2KBjL31`#HHY8 ziFJuOUu|+sqY!*{HUkJG%k3l_NJ=&Xy;<&cL^~T||KE$~c^gtUokUR7nT!kGt0sHq zcqA)9bPz%RbB&1h{JJG4A4!2JQbzS(F;h>OJ4>Li2?lEX&wfb6S%$05ZQMS|Fe`n&GW=uq+_JZV%0=#jN~p>X@QfcET3}Z w|C-NNm-7~!qnNOpA8trLbK3GLMS90+%NNH#FH0gFuC{!MqstZlq?Y>sKe{jbV*mgE delta 28797 zcma)F33yaR@~?g~2}y>)aAU&p60U%NT!u55*TW6r5?n<xt}w+?(V|qVl_!*c-pa5@(;!`X&f>or7Ny7OiE}b7vO<<)Il5Aa{k`&} z%PG?$U2)FR@=$)x3Q~6u>EqHW&BG72m1$8;Q(q$^w zEs1M5lr@tkeMnl@u_%Rg8u={EbBV@1(kkVmW{R`PmtyR9?f7i5;_7y*#>9_yd#Ub#cDOSXPRM+CFd%x-^F7hQ*I04u(~%NmF-X(ye`C+K7eNJkGU!Ht7p$nAfpM&zqz7ZVW<#Y4+`QyA zYKOZvd8FFs9!<_xJKT&~X{x{-Qmdod=gzOilubhUL@0^1nKGz0x5=%|ZPp28pHNN< zrLCXaO!IS_Kl-`NW`CC2;r{HmRe{^M4pRo!38)?JgLTqWLDApqG*;?)cYEDV>Tg9q z)V)r%|M??j$N3xj>^L3uYjIE3MoN%bOO*t-q_^rA4LSWq5d&pSNt4X_3uyH;ov2@_bRh z1~shsQ|B#x>U`0tMrCmgk1yd_Zj<)r`p4VktIyA2_qwJd)J8Ydv`-U$N9klMU6Jp} z72z3HLb^<`jqXQHhpA$>RkQY{nPpQ|Gpg2XX0w|U%)8d5?(SwOYNLCkS)aB%$!hSb z;Q0~9i_PbYyoc-S4*{5w_XX4!*y&Od0s$VKCFd;XMY9{*ZcwQ0Q5o@s5;b+^j@S6cK^E8K5dbV!C!wzFcD+ot6tmG7=-*){&iDi7=3)-tO{#VQXJ+TPrB z@puPBzfC*_2UeNo$*Q5n<8@d|W~(-#EoQVx6T7=%sk|_^@Tg^43Oy_UDueCuBHn>?|7tjT3lJaN3V8Ux9*rKZcop%J<^DB&3hFe=+184 z1}z_JozmR&%eIDA?~iTS-rTe}?)#qB9jxQ4Tu+wxoNno+BIs%v)*`e)8x{f z!ClqvW^4_|+ifyigW|1$#o6let>LX}*C$=(}DkuG)9ILC0%(#wu(c@VxgHYhEoiNoz#oO<4KsKYv*dE51lLO zow>^jl`V!#jm92|V-Ne5Sh}4*j(isRp7bg!)Pi(aO;1-X+4{#XNML5^5bIud!RkPi zO#09AVAH^4GE*i`|FlopN>@^@zagWc)`jDvF|n_{vH$Y^yMNZLBs(Ov9X$n zEteRvIVR!d%O#A2gmRIv<)Q>P(6eol1FkdOy{BjQ#7?Moa*KQRNVHM2-Jg2)Nb;lR z&vkqB>h2>`^*7Y{MOnR@srY4;N*}6pC--?m?~&JA$4mY;&E>#LCX_19TNFCx9^f~6I=DZXH7LA?@V74ieK zVxzC0kFhqyQ0rr;zs6Y67%KMK^*$9$RHt_0!pS z+j^6|f>(deM~EbS@MC3r{SEaNcZkz9bR2f+L$Qa7*u$RK!>-uFj@ZMgShr5bC_Gq? zn<;XEX_-XQ(+!IyW+7c8SFF)T7JF>c@v@g4SUjC8aZ=eQ46i(w%d7PGg;v)Px7{?>RNnzfhf*czW{6~=TF8XbSS zy4lvHv*=G(jQ*db8;@VE;!oa8D;iS~H7dUQO{4#vjQ%A<^_`4<^l}~Fc`~hnn2rLY z$apFoHCq&2k%XOUaWLn{vj6 zn^e3jDuz{`sPBr3jhCx<*OO^Yf(qHwefs;Wt8g3kZ+D5&-;2b;%O!sA$+Sj7qU`ZL zeg5haFPlQ=#pvRT?ke0!V>Aij>{D+k)tVZnjX%*cyxi4+miIICD`H1mUwjgOpE+ugtli%?6kUP ziHDgS3GG|r(E)y_0Lnj79@8#uz0b5hwbY}-O9fcyK05f6+EDcHkd;b3?l#UDuS(r} zb6Voe^kfd_@_G-;sg_hDK5%#?cV~O5l4}1N(bRow*o4?=tt!PQafmtI<`2K7Cyr{r zHN_`rN%6V)!(%zVPloU1{L0HCVyVS{jky1^WF99=YWr-3WS*)@=2;hyuO7`IJSX!M zj<5M6=bA&FRsE31Nk7lr^cpzi*`s#&%9lypL%MRA``xJ4)~Tg#qZ>X`8;X9qp+=l4 zDLQ}CDW%GbejfW@rAmuF8TUJn+TeDcc)ic0z|uMVa_3A8r~>!piDR$fG+HwGe747q zvz6`DG$@r{<`YFNCY@EG{2!ElrMADOKJ|mr1vRzO z{ZMtn>K~O}$pp@6`aSyWk4kS!)Rqp1AJ7+sRQQw9FENSqg$o|PM<4o0>30*gS99iQ zp1yG5!i8Qn{2smbXQkg{I_Z$#qj&wR^wye}G~-s`Q%V;z*|aKl_ubYkbmWxM7ZQUM z4Eb-;TTUzeOQQDrlXT^2rPtNg3H~HqaoW=7YWfp(<(EotDN+7Jz3D5Zz50uq{&>CY zu+o-Zne30(<%gNNmLHEFR{nZ=^%3sg&u=Qf(p%(te+fSyI-<1FkCrHZNa_5eEMUhQ z%qTvpv`2p-&lN{m+Cy8IzU*tI^i1&y#AL6J$X#&8u~+4>}y6k!GFC? zeoinw9-Dky+~HH&XP)}S(&5vVE;!9^Fex`y)#r$`FvVOKgY0K}^+*Il4X-h}l z!YOHux&B&hnN}Mrl#a7Wo;SKjr=*Qy=0^XO%nGIBZRIEJ^*2f9NTTn*-#t08xTS$;KS{2fN@`KvJlVE(1fl|6Cif%z}9v@RWkm%&_?copQ= zV6M5EwJq*61|3bf3UWM{d#}cP6wK$6W%05>HEfdSjqbm|JYVZ7Vrxt@I>T2J>wx)C z-K!wyPc!d2dKIykz3YEhd)MZf-*w?tfbKD<+;laSE$=eMK5;eX1Tagk){`}0K72Ku z?}PdN)tCvnM&}n-V`?xXzN-w-g50za_w!uxmCULE`X*T?>cZ2Oez}5|bCM>%rPn5D zOYb>t=`$5d`*ckqu1Mlc6|cbxrIU3nA@1MFUa9i5rCDTc?HB5Q617L4J#FdG-u+6~ z(RGFT!%p^QE6!LlKkDiFLOse}yx@$bKiRKz1Km)FWyxCU^`|ZU*?y%P>Bd6*fVYIT zXAJQgog&2YC7jXc)Oq<5k5-&HsXSw`WA@kb>F!5PTYBwTOK&(Eb26!yIGJ}#m3WyZ zexK&HN^d&LUZ#9{YHhART2p)Uma~>VcgQ_Gy;&`$ZA;c(U4GWmOWf8onunP5Ro{$>U|!TBWEq0|E1EcFKg8%*6Kak#m-s!&tEE?5o_fe zqpT2LHAyDHa`<3glMnRn{j0jWXJ&M1QI3S6!3$uEt0=LKPTYa%`Kp#2pK0UidJSWi( zoG;or`!C8@rSbR@clMm^YJ=P5?nl*zqO!Z&d#sAn?oapLl8PXM@7?%%&g0l|oVnqP zxuWU!O|q<$=ZkjFvlFZ%r;EM|Z}HZOUF?~(hP(L>ZLO2%-9vw9WgYz3^(}AS@YFAs zZ<|t{s*$s8(&etR{C4Z)3U|h;0q(KoDKRk~htgDtz@$XH902R{pn8YlZiU{!22YN@_l&R?DS$O)lkEr0&0RR3&{6%xi~lLq zz4f8gOU#s9N0r1vNW7Tp@Zvh-e@e8@i~EDv8vdTbAG2uoc5s+1svTSDOs1z!M&Z{7jn7ZVg-PEdGtloJ%bv9X=h zow4fHB-v0e+ZIN-e=Mli?9$yOcI#jnji0-36r{AP-oei~4O7)Yvp;yu)q+0wanXf> z?0DDqJnYm5SS@^cH57cb^`#+Ra0NQaBQer}@* zgoUKl&}8Ma9J@v`>7^hImjjb(ZckkAlZp_(k-cC zS@?owC)i#)UWeWD&o>U?hBMAwPyQu#xoECBwP+{4C9bse*^l{Sr%Jh=upC^1dYzc1 zYXv(;t2zCX`A!&@rBEr(YKm5cE_b4p@4JAP$(jkaf5;^Hp7~ z;bv7nnv=WP=VO+e8`f%;m&PnFjahE)UO6gR8Zs|@LzV5xbg2Znz~zrY3S%}E8k_zO zo88BAO(ZLV&3+p1=j3U5j7hAv(o$8JvDy8mb&I-oEM%iACBQK;TO~RNR zAh-1ky2(h4j>*njjy_Qhz3hdy9UP!dZvB@_Y&r{@IzeV9_p=vtstu8n%eEZ7Sp0~L zx7+8%wuyd7^t*X4riRF1`Kmr_K4|jkKk`j-FOtvX_#-~?F7SPE>{{cs*Kf1LOFWYC zCPBKv>*%+V{2j%|$Tz2)My1}W2^X1GV{s{7JKnbJ6#i(aaV}FbEXuGN*QsILkS=ib z%MG*E8V{8;#_RAcw4G!pF6!=~nwGEXYMZ^n+QlCJ%RVeIXsuY7o@hOwx45fc&a7R) z_skurDNm^fbb0El@9VkH0cPPJ^q9oT4YYAM>tteVf~uqodn>^E6fJMmP62VE60Iw`OsUnEWYT$ByR%E%i_4Zyl>i>7N$I z8;BftJiyhT~IA%JL7donxNWJS+hcvF|-$OLKbEl~@@45Z%yYl8voz?Ze z$us&BF>haF@^z|(z)tdGv!u!W!D z&4{sTMxKtby76PPqn zMpCPU5HteQ8EXiDV%uIgH892M?MT~*gq7PW`D^GL7#UiqGEz;`Tcpf_@^t4dW1 zBiD3Ofe^PFGoQ#ikLW%ka^@4Qm`^nFKB8%1qSf=IQ(KLVx7&Og*9tUW(D4HgiLSUFS z8JHc+pKLJYz?2DQvS1DY!?b%s0G;9n_ZX1(elrSZ1$2*q8sBe5foXGrX@5V_$hij7 z1DH-s8#-4oIlwUOE?_1x|1N`>aX%63rzrxuOF&_On3fCBYUbw}P!x*R3MN-D#lSFa z1~6sJpJ6b2fY~LO8G<=tFd-q%1n4X`m}x)>3(Y9dLhjK_0X11@MuBPbfa%2ic?Q!5 zm~MiZCzz4IFpcLWPw*+spU;>OQ650k1Tng4JAPM#0Opq1?gVEP?U)`Q#J zVfg)k>m#^3MA^;2Fl`Djp&8s@iUG|7C{I9B1e6aD)20FxW&Tuy*$B*f!AuoQDKJdC z6PP{Bztdn20JCoqg=pl^I|XzSpnZ#o`rT_rBH;lZiF<`#{{b@+HJLV)TNq&(515f) zdcS)N&JmnhIXS@fGq`(VxJiQRN5bfLmjTWbpjipa09d}P_V-k&>gLEVJymbvb_-qPc8m1yrP`>9$jn}9sBnuzMBR8+6H$-I zKYOX69ayA4e33k59#MZHx|N6q644+cnrINTI-+~4ROO9K=&e$3?6jDu9WQM%uZ{oQ z3>wcDel7gxP}sENiN!q}J-6r7dACo^n|s%6aofC`?+Kf>^&`7`s}}9qC|Ycwqv!U# zZSs_flV{AB&3=}cXIJsMbaH2JYtRSuK8uOiEdH}&F;QDG-hvlD|0!N#)*7#!JkZJ` zGyABnOBZ&+OO1la3)b@i0EkyE$`JwmJ(TB1AK(}OQl!TC-PmkY9V33dozg=mKpM- zWkfxRPY*=Bi756G_f~_lhz>-QMMT-sMi;EKd~4=J*-;Qtm^XPM+B43S&kZN4MMRrh zqTbn*yKf2+ZRu5)bifem+NRtPG;2Gd9?>;Sy2a4DJ4A(EqDYS6=L{$M%erf_C$%Q3 zK|~F-Y4?Z5QaW#^a2a*(<;6p`4maa6Tr!f)r*Pm@DA@=q6wAYb0V7O#-Ya`%w5fCm}KgQHgjE#KYsD>#6 zz<(b6wPT1l@cZxBh|;QIs3-V;0Y4x7|BU4kTKc%+$m*V6$gLBo0|+hT-<_cOpaOtLQQX^3bR6gKZ@>PrWh z@(koH!z)@W%bw^9tj4|rB-|w$fref*d=3pf5cCWTS%!D{AM`i?gWf~WTf(3LFvt&s z?tz?g=$QgNb3?Fb4-|Gq!Zg>Y?4gpm04DE&%^OFen}Tmf%0t-pq+tTNCk096OThA)-^G4Ws#V z@n~CboknzU!RoB6sZ!4#d>ebfzhy6-%;i_vL$H_ZyVl@RSaJA`e*WoP4+lm_Odbw& z#MaRZTgO~%9WThnMU-`&(NC4w{ZuO>aMSNhIoE7fbm(_xuXz~2btvycIUVH~lvyZS zqpXec6yzO5xwA3We+dZP>KetfBzr;hnNNCD^5+&@mOFp#VSN6)I;PzU-n%)^A?=6` zW0%&Db3f!9gPear&P$N5InPB8ZS`SinLS+Eg1b6_z{|E30fENHf5=Kmd5eH$!X2`h!eox5x zJLFssIWr-rFO2vfo*0q`V%Gtq7UjCdDDJO(*mg5Ml+RzXfGjJz4;939=0JsU-wTBTez=%bV^B(wdkaI8OD9GsvIkjQLhit?w zfZqi86ogL$_+&c2^Kz#>z!uuoMLQQpOoW`5!9NE6ILJ8+In5#GN0YRR+%ZJe35^8! zo#tkOeFJCoBWFU0sEw@kntf}?S|8sx4FPV2@WX*?;0u1?V;6-3_23ImHYf5B(Go1p zi6{r5>}<*qrGVf;c^pf1FUpSWM2KiV+-fh5&xxo6&S_yAQ~%PWE9v(mOuad9yMg1I z1OD?8a5DrKBH9b!GyweoZjJeIJ`@nqQvi;K!nc7N3!DP(1>p7ow+gr%;9do82;+En z{vJEl69B#fUtUfExi^P2lbYt`=~wVQ#%-UTNUT7Ul@xOpyK;2cMr{hWM{Hn({t0=q&W& z;A7xF3jTQT)4|UNe+BqK@auuU2>koO{}Kkh+!oQ%zq=DH{8-VxWFp`1h-Ns(kS86Y zeO?c3!yexk8`HirQ^Kc%ixk=So`5b ze|xN7?=$8EpWU$!*8d0CwOZ$}0LPh+9xogwC*#0zQLroPK6B)!8^zG5-Y&SZ;4e}} zoj!d`&yPZ0H<1^09va4SCpj<4##0vb%3LW6{w+t=f7BT-$&7W`?+-Uaxj|<2puS@{ z2SY^9ivZi{h}^@^m{i-5TgVzNJ@u?v9j?QjJ0hFlW4& zPl11lIZ@}oIh;{gm;DHiv6k?|fj#0S@^pjVCgYGaoM?94rM%xrN&Bjh`jsFdin`rv;7LrE&WM)txb-2mtd<1v&oMfw_dT0iZQ%?4+ zILJ4Kz<&-ihRntUd0oagC+oA}Mt=HGWAK`OL`fgD=<{YO(}xo6z)|HB^8$76rbN!r z9GZri(nb_S^&$vffV5d3Sz{CkcQJyWj&vHW8igvmnGQF>@p>@4VIfXFy;1)&>KYMJ z-B!f^tO8AxrR_KyWNAhnw~m=_U&;!!^_p}uPr9@siswYLoVaY~iSg3UP+++<$jN@a z5fh@$@`hZ714Gdta~~RYR?2?iIHNHG`brrNJcfzs!G7`x2KZ*|nA`Ef8o@~&y+K|` z)~jQ=4CQ1ei6!B{2O=O(ZxE+)z-i0bNFt{OdVCsF?UbCj!r8rqAI^Toq!R-<@vDs$G>2SstsU?-C$%RbkH=!l1?E0$&} z09*4VcnzX6*P0FP9c|`rej8JN4fSPhiP)j8z>?l7&W`kES&H5Io=Y>%N?#*Ai8_C8 zW!}|m;wy@SZ^Nz5M16#m-GYNW44AB~i8S?apP0ZwYR8~W!UW3`c*USZ)(#-T=p`5nEC8@F) zqt1<3lut>FK!G_jne+5HG1zt{$POCLK8B5J>kTF**&UL1?>OzG=i!oDFti!%%m^r1 zwUxR9=nu+w1l@vZsIQiKrS_u!HeS{C0Y*U=gl9F4Ukn7bdBsmRk}^9q@LKjS&t$z~ z8qjnod_lsj%59HG&+>v_%Ph_des_xj{u>#Uc2MAff?iOtMik^^2d*_Ex=2>Vpx~V{ zGWo%ejhs;SH!^9$CFhaA7>?Q6UnUn(XS~z(h>rd(Jq`zQ#6Y4CrN=}KdWv5QOv0-< zD12LQljRw8UNV!_@reU+oYfLNg~BCW2Abuw5j)fHj%J9~%hsHyzmT4W1KVU|qRu-; zv2)gVM5m$bVBx?^X1!+`iwRLN>arU9dKqL zFzqStl&CAVNG&7dIHw1Qfb1?9>WAku!LR99AlI54muN>WOd^8B(`{@5u=|Pd@}l^wv1D{yj1& z%d`dh1uiY39GRRA`=*%Hqu-ZFX6s`jC#rvkGsvf?_YZ-vvk_5&A}Sb4R7OPIWVV(% z%|##uPMe{0A~M^f&IBpLfv3zW(Y0_`=^*W+I?4Exz%w#wO9RWK3}^2}9x??Z8wre4 zjmJKZZhRuG9Oo-&X@Z%wsiO&28euE^up7}DB03>k+5u;Vbn}4IaFk>{13Nnt{h5d& zk-~AR`&~O*5)FxD1-kPc||2hf~ao zYz6$$M6-hKmU$QsJlNi}D~^mDuNn>BIo{0k339fMI;Gg)*U5Ua^&iKH%j?|{v+29e zM*J4pmcoHL=9Vn5I8r!XH45!)W>y1rG0m1^b8<(RdK(j1lpJkpChd>CP5Z7`#;>+B zp=NumnzwtKc5e+e*N>x{5q;Q$s6{iPiXKECW3_#0}7Hh{OIhh;iSCzxW78{~Khw73k044u0eij#uapGONpi^HH8ggJ+PI zyI-jFi*Jct~;*OdOv*8Wy(0*|m`GmU*ujYu@cc(y&|bZ>HS-1+Moh z&C#5G5dp=)966X2_pK}8eWeZ{hw$KNBj?LhGh+8*5)Oe6EHVZ=b+#Lq>NF8X*y$N5 zpQIXvo-p|+r&!3O&&kIyw%#vU+opXtZ}F}z#wTbay`UL^zK zIGrT^C=CoAYC66Y?r|0jS|Gu)&Ho;T{U)C-sB$HWJ6J>NDLt7%XZw8 zdjfGLAPNkZh|b=YKiUTsEJ_Z%;GVu2wt1)};|q2~qb!5^24qHw?wIZo+9 zOqFq_bZm};LR1=fPZT;%TVaHq&JrM%1}Z>bCq1@xcch8FXkvQ45|P+2@TZ%4aJ)on zIf0Ebx5FhFGKa$@V_F*j_7J9CNrt$E(|tddcX7J!b4|?2tGJ(er+eZ0H_9up^?C^* zO9MZPA__RRyxZ(|(5@BYmx>WYCl%4V*(S_*1IdK&Q1huzht@Q5o^+^K z9Cdmi@OjqsBzrhBBfJRb1SY_%F6!%IV z)W;c5KQiy{JBs#a#3d0u zfgZmmWjK2k>eq7_A}25thskmEiOOpbJ<-LaRO+DN?>iH{yQxcdB!$aYvVO$DVh*NX zFi3QN{f^mRfj$}Z?U;t^QC6UAZWcHdXao)kvK@v?<`~~d@5m)VxMXS21dlHR=%V~L zBAYne|NLH@c{p%0;`Srbj;JT(%{3iydi#vLW55@V5f4G6`kT+|R*46w)Yl{TvH(8s zVR(f3h}mwGc6q^PByX7?sCm8l{PP{Gw?;DQ!hu(AFupVsUr_AE0cE7Pyl_c$gm{Q> z;1+z#HRLAaivA5}Ji+W9v^SPwf%jj7efU-Q#M|L?XYd>uxv1Y9*$1QgSil(YF{0JG z5!p;eIntz7h;ng^eg=%s;9_>+RC*farzp3gJce>-z+A_CINm6nB8HU(-!LJUzBk=$ z)VGOY`N1tPC=`#6NcuYFR67K-_?)b7TYrKc{7oCdHX@SY2(QnAzXG==UxWXYD9Y1+ z!$&EZ{V@_)u62yzxpW+pqy+1>ljPiqHfNjttfkKY^O2eCh*z;b;uky;u zg1t=!gwDwbgiAh;IMda2q5p&5diENbi+#S%CF)vqvhVg>bNqWh*BtkL?rY+LZ~K@s zY9gb+QTfbqSJru)K0i$re%5hJy>k)|5G5hzZHMl?Ya+gMYA>rZFIb2vv{~{MgMu5z znwz?Q5&sO;C^P`cx&pkYS0$h!s*7yl+gL;YK>1}h5j&za4UL#@co zsbbT0W>|}Hp|}a}=a1%e5u(Rr%@GwLhnA0+`MtIVI7bW%2SS(#fetdDZw|o?;~;T^ zWx@B54s9e8qD;H^z+gN4{a@j3YlEIGbWVAK@sNCuPV_o|%uPgpkzdPC4p z;`^*7FyJW|a7@;CnZ6r}o`wO7q32u3Ysz%?3+Es(7mRgKG#~V@uwgU+{YPvVPr`so z+4akU_rQP>7%&P3gkiuW7_b|9&fWpPTmeOc!I%d{H-r8*3^<8+W)BP)1Os-!fPpZ; zg#n#lz(g1jfB_q!=hHjjm*0S*3@~nj0o_4g4+H)K1Bzh4w{RjFb0JG!#hPHL7!q}A z%3QF6n_(6U3pw3UehPX2 z#kkoRw=QN1hk~z)U?PP@v;u-(gWw1RdqM9CdOgs?c!4kB1+KyiJc}22E$BYbccNqQ zVnC=YxDp2J#T2>|iq=5UeNglT6x9X&dkCBe`omB(3-nK6KoaO*V+PHI0iW>5hNvt! z0S5dX1`L1!_d?N)Fkm|roq)g(peP&knV=5?{dE{{6jS)0FrXO>c(I`@#SS-diW-kqIaOE zE9kd@9t8a*81NYkcoPPM8o+>OU_fgaa5oG{fdPYIKwB8F28!N>qGzF~F6bKcG|(T0 z0b60f6UKlLm0&Wgn`(ld`L~&TOOZH`sFQjlhj%UdydcpHIrAl5V(UVbEs#lj-=v2E zcYxjy>6r)Q2oes|k)SDD(#Tx4WT&+z8a_F+h4#o#eTjDZi4us&$HzXRz(0`ocu^v2 zJGfh-xHA3e7-QfJldlPmkn7xV-~hsqC_Won86c{NBU;zoTo-T0A!{oRS9LiK=K1Hv zh1IvnyZk)H#AW+X{~GnTP(Nzox2%IEe#?5Gw}dBIT_sJQlQq!9XMz4E=jhavI4$f< zMErW#oyXhmj!!?fYQKM$d2wdJqWyOdJwn`ic?KQAJ}OE zU?%~e3%!F8`D06C;JTJ3LskcdooOfi4?EG05_p9^K}2^ihG;+X$k96H2=Gf&qD|>U zQxQSldYz#kz!Br0_(*Q}b>^%yKn_#UUui}s zj`I&BfDTGzOXSB#ZrKPmo0*XboDsp{KvGR3Z;B`;+9-~VXdy!7DAL4DMNibp3E?eX7McN_!sP||5BJI=`^IJ;aEE6|# zowgGH$eaIlOWzuce}BwB`L6z#e`U>ox%H{ge4_DN&5xH^MIZiY?pE{f4}@l!AE(Fo z{Nr_gmS4W!fAKlSXME}$^W(V9c|?zIHP5%?5v|Abnb|~zcz$#?QD_S)*Ucs>gW?C~ z7z3W2V}5~mP<}*drqrIT;vMJ!$|ETGSN8v!V|d&FuD80|j0@KrziB$d<@l|{|CFUK zJ%4^T!{HwjayPilc$27-C78MnpR;_L2M`1rADJ{?rK%N?h4WQPVAnazryTh|>hsm& oECpvIGPbi{A$^vaigf;Y%NNJLAWI@$e%|sW+GUD=HA{W}ADP)m_5c6? diff --git a/docs/public/config/failsafe/parameters.json b/docs/public/config/failsafe/parameters.json index 193d313184..b0fefe7e3c 100644 --- a/docs/public/config/failsafe/parameters.json +++ b/docs/public/config/failsafe/parameters.json @@ -1 +1 @@ -{"parameters": [{"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets first 4 characters of a total of 8. Valid characters are A-Z, 0-9, \" \". Example \"PX4 \" -> 1347957792\nFor CALLSIGN shorter than 8 characters use the null terminator at the end '\\0'.", "name": "ADSB_CALLSIGN_1", "rebootRequired": true, "shortDesc": "First 4 characters of CALLSIGN", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets second 4 characters of a total of 8. Valid characters are A-Z, 0-9, \" \" only. Example \"TEST\" -> 1413829460\nFor CALLSIGN shorter than 8 characters use the null terminator at the end '\\0'.", "name": "ADSB_CALLSIGN_2", "rebootRequired": true, "shortDesc": "Second 4 characters of CALLSIGN", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets the vehicle emergency state", "max": 6, "min": 0, "name": "ADSB_EMERGC", "rebootRequired": true, "shortDesc": "ADSB-Out Emergency State", "type": "Int32", "values": [{"description": "NoEmergency", "value": 0}, {"description": "General", "value": 1}, {"description": "Medical", "value": 2}, {"description": "LowFuel", "value": 3}, {"description": "NoCommunications", "value": 4}, {"description": "Interference", "value": 5}, {"description": "Downed", "value": 6}]}, {"category": "Standard", "default": 14, "group": "ADSB", "longDesc": "Configure the emitter type of the vehicle.", "max": 15, "min": 0, "name": "ADSB_EMIT_TYPE", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Emitter Type", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "Light", "value": 1}, {"description": "Small", "value": 2}, {"description": "Large", "value": 3}, {"description": "HighVortex", "value": 4}, {"description": "Heavy", "value": 5}, {"description": "Performance", "value": 6}, {"description": "Rotorcraft", "value": 7}, {"description": "RESERVED", "value": 8}, {"description": "Glider", "value": 9}, {"description": "LightAir", "value": 10}, {"description": "Parachute", "value": 11}, {"description": "UltraLight", "value": 12}, {"description": "RESERVED", "value": 13}, {"description": "UAV", "value": 14}, {"description": "Space", "value": 15}, {"description": "RESERVED", "value": 16}, {"description": "EmergencySurf", "value": 17}, {"description": "ServiceSurf", "value": 18}, {"description": "PointObstacle", "value": 19}]}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets GPS lataral offset encoding", "max": 7, "min": 0, "name": "ADSB_GPS_OFF_LAT", "rebootRequired": true, "shortDesc": "ADSB-Out GPS Offset lat", "type": "Int32", "values": [{"description": "NoData", "value": 0}, {"description": "LatLeft2M", "value": 1}, {"description": "LatLeft4M", "value": 2}, {"description": "LatLeft6M", "value": 3}, {"description": "LatRight0M", "value": 4}, {"description": "LatRight2M", "value": 5}, {"description": "LatRight4M", "value": 6}, {"description": "LatRight6M", "value": 7}]}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets GPS longitudinal offset encoding", "max": 1, "min": 0, "name": "ADSB_GPS_OFF_LON", "rebootRequired": true, "shortDesc": "ADSB-Out GPS Offset lon", "type": "Int32", "values": [{"description": "NoData", "value": 0}, {"description": "AppliedBySensor", "value": 1}]}, {"category": "Standard", "default": 1194684, "group": "ADSB", "longDesc": "Defines the ICAO ID of the vehicle", "max": 16777215, "min": -1, "name": "ADSB_ICAO_ID", "rebootRequired": true, "shortDesc": "ADSB-Out ICAO configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "This vehicle is always tracked. Use 0 to disable.", "max": 16777215, "min": 0, "name": "ADSB_ICAO_SPECL", "rebootRequired": true, "shortDesc": "ADSB-In Special ICAO configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Enable Identification of Position feature", "name": "ADSB_IDENT", "rebootRequired": true, "shortDesc": "ADSB-Out Ident Configuration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "ADSB", "longDesc": "Report the length and width of the vehicle in meters. In most cases, use '1' for the smallest vehicle size.", "max": 15, "min": 0, "name": "ADSB_LEN_WIDTH", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Size Configuration", "type": "Int32", "values": [{"description": "SizeUnknown", "value": 0}, {"description": "Len15_Wid23", "value": 1}, {"description": "Len25_Wid28", "value": 2}, {"description": "Len25_Wid34", "value": 3}, {"description": "Len35_Wid33", "value": 4}, {"description": "Len35_Wid38", "value": 5}, {"description": "Len45_Wid39", "value": 6}, {"description": "Len45_Wid45", "value": 7}, {"description": "Len55_Wid45", "value": 8}, {"description": "Len55_Wid52", "value": 9}, {"description": "Len65_Wid59", "value": 10}, {"description": "Len65_Wid67", "value": 11}, {"description": "Len75_Wid72", "value": 12}, {"description": "Len75_Wid80", "value": 13}, {"description": "Len85_Wid80", "value": 14}, {"description": "Len85_Wid90", "value": 15}]}, {"category": "Standard", "default": 25, "group": "ADSB", "longDesc": "Change number of targets to track", "max": 50, "min": 0, "name": "ADSB_LIST_MAX", "rebootRequired": true, "shortDesc": "ADSB-In Vehicle List Size", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Informs ADSB vehicles of this vehicle's max speed capability", "max": 6, "min": 0, "name": "ADSB_MAX_SPEED", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Max Speed", "type": "Int32", "values": [{"description": "UnknownMaxSpeed", "value": 0}, {"description": "75Kts", "value": 1}, {"description": "150Kts", "value": 2}, {"description": "300Kts", "value": 3}, {"description": "600Kts", "value": 4}, {"description": "1200Kts", "value": 5}, {"description": "Over1200Kts", "value": 6}]}, {"category": "Standard", "default": 1200, "group": "ADSB", "longDesc": "This parameter defines the squawk code. Value should be between 0000 and 7777.", "max": 7777, "min": 0, "name": "ADSB_SQUAWK", "rebootRequired": true, "shortDesc": "ADSB-Out squawk code configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 1.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC1", "shortDesc": "SIM Channel 1 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 10.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC10", "shortDesc": "SIM Channel 10 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 11.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC11", "shortDesc": "SIM Channel 11 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 12.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC12", "shortDesc": "SIM Channel 12 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 13.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC13", "shortDesc": "SIM Channel 13 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 14.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC14", "shortDesc": "SIM Channel 14 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 15.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC15", "shortDesc": "SIM Channel 15 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 16.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC16", "shortDesc": "SIM Channel 16 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 2.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC2", "shortDesc": "SIM Channel 2 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 3.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC3", "shortDesc": "SIM Channel 3 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 4.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC4", "shortDesc": "SIM Channel 4 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 5.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC5", "shortDesc": "SIM Channel 5 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 6.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC6", "shortDesc": "SIM Channel 6 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 7.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC7", "shortDesc": "SIM Channel 7 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 8.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC8", "shortDesc": "SIM Channel 8 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 9.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC9", "shortDesc": "SIM Channel 9 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"bitmask": [{"description": "SIM Channel 1", "index": 0}, {"description": "SIM Channel 2", "index": 1}, {"description": "SIM Channel 3", "index": 2}, {"description": "SIM Channel 4", "index": 3}, {"description": "SIM Channel 5", "index": 4}, {"description": "SIM Channel 6", "index": 5}, {"description": "SIM Channel 7", "index": 6}, {"description": "SIM Channel 8", "index": 7}, {"description": "SIM Channel 9", "index": 8}, {"description": "SIM Channel 10", "index": 9}, {"description": "SIM Channel 11", "index": 10}, {"description": "SIM Channel 12", "index": 11}, {"description": "SIM Channel 13", "index": 12}, {"description": "SIM Channel 14", "index": 13}, {"description": "SIM Channel 15", "index": 14}, {"description": "SIM Channel 16", "index": 15}], "category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Allows to reverse the output range for each channel.\nNote: this is only useful for servos.", "max": 65535, "min": 0, "name": "PWM_MAIN_REV", "shortDesc": "Reverse Output Range for SIM", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Airspeed Validator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 5, "min": 1, "name": "ASPD_BETA_GATE", "shortDesc": "Gate size for sideslip angle fusion", "type": "Int32", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Airspeed Validator", "longDesc": "Sideslip measurement noise of the internal wind estimator(s) of the airspeed selector.", "max": 1.0, "min": 0.0, "name": "ASPD_BETA_NOISE", "shortDesc": "Wind estimator sideslip measurement noise", "type": "Float", "units": "rad"}, {"bitmask": [{"description": "Only data missing check (triggers if more than 1s no data)", "index": 0}, {"description": "Data stuck (triggers if data is exactly constant for 2s in FW mode)", "index": 1}, {"description": "Innovation check (see ASPD_FS_INNOV)", "index": 2}, {"description": "Load factor check (triggers if measurement is below stall speed)", "index": 3}, {"description": "First principle check (airspeed change vs. throttle and pitch)", "index": 4}], "category": "Standard", "default": 7, "group": "Airspeed Validator", "longDesc": "Controls which checks are run to check airspeed data for validity. Only applied if ASPD_PRIMARY > 0.\nNote: The missing data check (bit 0) is implicitly always enabled when ASPD_DO_CHECKS > 0, even if bit 0 is not explicitly set.", "max": 31, "min": 0, "name": "ASPD_DO_CHECKS", "shortDesc": "Enable checks on airspeed sensors", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Airspeed Validator", "name": "ASPD_FALLBACK", "shortDesc": "Fallback options", "type": "Int32", "values": [{"description": "Fallback only to other airspeed sensors", "value": 0}, {"description": "Fallback to groundspeed-minus-windspeed airspeed estimation", "value": 1}, {"description": "Fallback to thrust based airspeed estimation", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Airspeed Validator", "longDesc": "Window for comparing airspeed change to throttle and pitch change.\nTriggers when the airspeed change within this window is negative while throttle increases\nand the vehicle pitches down.\nIs meant to catch degrading airspeed blockages as can happen when flying through icing conditions.\nRelies on FW_THR_TRIM being set accurately.", "min": 0.0, "name": "ASPD_FP_T_WINDOW", "shortDesc": "First principle airspeed check time window", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Airspeed Validator", "longDesc": "This specifies the minimum airspeed innovation required to trigger a failsafe. Larger values make the check less sensitive,\nsmaller values make it more sensitive. Large innovations indicate an inconsistency between predicted (groundspeed - windspeeed)\nand measured airspeed.\nThe time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the ASPD_FS_INTEG parameter.", "max": 10.0, "min": 0.5, "name": "ASPD_FS_INNOV", "shortDesc": "Airspeed failure innovation threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Airspeed Validator", "longDesc": "This sets the time integral of airspeed innovation exceedance above ASPD_FS_INNOV required to trigger a failsafe.\nLarger values make the check less sensitive, smaller positive values make it more sensitive.", "max": 50.0, "min": 0.0, "name": "ASPD_FS_INTEG", "shortDesc": "Airspeed failure innovation integral threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Airspeed Validator", "longDesc": "Delay before switching back to using airspeed sensor if checks indicate sensor is good.\nSet to a negative value to disable the re-enabling in flight.", "min": -1.0, "name": "ASPD_FS_T_START", "shortDesc": "Airspeed failsafe start delay", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Airspeed Validator", "longDesc": "Delay before stopping use of airspeed sensor if checks indicate sensor is bad.", "min": 0.0, "name": "ASPD_FS_T_STOP", "shortDesc": "Airspeed failsafe stop delay", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Airspeed Validator", "name": "ASPD_PRIMARY", "rebootRequired": true, "shortDesc": "Index or primary airspeed measurement source", "type": "Int32", "values": [{"description": "Groundspeed minus windspeed", "value": 0}, {"description": "First airspeed sensor", "value": 1}, {"description": "Second airspeed sensor", "value": 2}, {"description": "Third airspeed sensor", "value": 3}, {"description": "Thrust based airspeed", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the first airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_1", "shortDesc": "Scale of airspeed sensor 1", "type": "Float", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the second airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_2", "shortDesc": "Scale of airspeed sensor 2", "type": "Float", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the third airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_3", "shortDesc": "Scale of airspeed sensor 3", "type": "Float", "volatile": true}, {"category": "Standard", "default": 2, "group": "Airspeed Validator", "name": "ASPD_SCALE_APPLY", "shortDesc": "Controls when to apply the new estimated airspeed scale(s)", "type": "Int32", "values": [{"description": "Do not automatically apply the estimated scale", "value": 0}, {"description": "Apply the estimated scale after disarm", "value": 1}, {"description": "Apply the estimated scale in air", "value": 2}]}, {"category": "Standard", "decimalPlaces": 5, "default": 0.0001, "group": "Airspeed Validator", "longDesc": "Airspeed scale process noise of the internal wind estimator(s) of the airspeed selector.\nWhen unaided, the scale uncertainty (1-sigma, unitless) increases by this amount every second.", "max": 0.1, "min": 0.0, "name": "ASPD_SCALE_NSD", "shortDesc": "Wind estimator true airspeed scale process noise spectral density", "type": "Float", "units": "1/s/sqrt(Hz)"}, {"category": "Standard", "default": 4, "group": "Airspeed Validator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 5, "min": 1, "name": "ASPD_TAS_GATE", "shortDesc": "Gate size for true airspeed fusion", "type": "Int32", "units": "SD"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.4, "group": "Airspeed Validator", "longDesc": "True airspeed measurement noise of the internal wind estimator(s) of the airspeed selector.", "max": 4.0, "min": 0.0, "name": "ASPD_TAS_NOISE", "shortDesc": "Wind estimator true airspeed measurement noise", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Airspeed Validator", "longDesc": "The airspeed alternative derived from groundspeed and heading will be declared valid\nas soon and as long the horizontal wind uncertainty is below this value.", "max": 5.0, "min": 0.01, "name": "ASPD_WERR_THR", "shortDesc": "Horizontal wind uncertainty threshold for valid ground-minus-wind", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Airspeed Validator", "longDesc": "Wind process noise of the internal wind estimator(s) of the airspeed selector.\nWhen unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second.", "max": 1.0, "min": 0.0, "name": "ASPD_WIND_NSD", "shortDesc": "Wind estimator wind process noise spectral density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "name": "ATT_ACC_COMP", "shortDesc": "Acceleration compensation based on GPS velocity", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Attitude Q estimator", "max": 2.0, "min": 0.0, "name": "ATT_BIAS_MAX", "shortDesc": "Gyro bias limit", "type": "Float", "units": "rad/s"}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "longDesc": "Enable standalone quaternion based attitude estimator.", "name": "ATT_EN", "shortDesc": "standalone attitude estimator enable (unsupported)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "longDesc": "Set to 1 to use heading estimate from vision.\nSet to 2 to use heading from motion capture.", "max": 2, "min": 0, "name": "ATT_EXT_HDG_M", "shortDesc": "External heading usage mode (from Motion capture/Vision)", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Vision", "value": 1}, {"description": "Motion Capture", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Attitude Q estimator", "longDesc": "This parameter is not used in normal operation,\nas the declination is looked up based on the\nGPS coordinates of the vehicle.", "name": "ATT_MAG_DECL", "shortDesc": "Magnetic declination, in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 1, "group": "Attitude Q estimator", "name": "ATT_MAG_DECL_A", "shortDesc": "Automatic GPS based declination compensation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_ACC", "shortDesc": "Complimentary filter accelerometer weight", "type": "Float"}, {"category": "Standard", "default": 0.1, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_EXT_HDG", "shortDesc": "Complimentary filter external heading weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_GYRO_BIAS", "shortDesc": "Complimentary filter gyroscope bias weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Attitude Q estimator", "longDesc": "Set to 0 to avoid using the magnetometer.", "max": 1.0, "min": 0.0, "name": "ATT_W_MAG", "shortDesc": "Complimentary filter magnetometer weight", "type": "Float"}, {"category": "Standard", "default": 2, "group": "Autotune", "longDesc": "After the auto-tuning sequence is completed,\na new set of gains is available and can be applied\nimmediately or after landing.", "name": "FW_AT_APPLY", "shortDesc": "Controls when to apply the new gains", "type": "Int32", "values": [{"description": "Do not apply the new gains (logging only)", "value": 0}, {"description": "Apply the new gains after disarm", "value": 1}, {"description": "Apply the new gains in air", "value": 2}]}, {"bitmask": [{"description": "roll", "index": 0}, {"description": "pitch", "index": 1}, {"description": "yaw", "index": 2}], "category": "Standard", "default": 3, "group": "Autotune", "longDesc": "Defines which axes will be tuned during the auto-tuning sequence\nSet bits in the following positions to enable:\n0 : Roll\n1 : Pitch\n2 : Yaw", "max": 7, "min": 1, "name": "FW_AT_AXES", "shortDesc": "Tuning axes selection", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "Defines which RC_MAP_AUXn parameter maps the manual control channel used to enable/disable auto tuning.", "max": 6, "min": 0, "name": "FW_AT_MAN_AUX", "shortDesc": "Enable/disable auto tuning using a manual control AUX input", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Aux1", "value": 1}, {"description": "Aux2", "value": 2}, {"description": "Aux3", "value": 3}, {"description": "Aux4", "value": 4}, {"description": "Aux5", "value": 5}, {"description": "Aux6", "value": 6}]}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Autotune", "longDesc": "Can be set lower or higher than the end frequency", "max": 30.0, "min": 0.1, "name": "FW_AT_SYSID_F0", "shortDesc": "Start frequency of the injected signal", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Autotune", "longDesc": "Can be set lower or higher than the start frequency", "max": 30.0, "min": 0.1, "name": "FW_AT_SYSID_F1", "shortDesc": "End frequency of the injected signal", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 0, "default": 10.0, "group": "Autotune", "longDesc": "Duration of the input signal sent on each axis during system identification", "max": 120.0, "min": 5.0, "name": "FW_AT_SYSID_TIME", "shortDesc": "Maneuver time for each axis", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Autotune", "longDesc": "Type of signal used during system identification to excite the system.", "name": "FW_AT_SYSID_TYPE", "shortDesc": "Input signal type", "type": "Int32", "values": [{"description": "Step", "value": 0}, {"description": "Linear sine sweep", "value": 1}, {"description": "Logarithmic sine sweep", "value": 2}]}, {"category": "Standard", "default": 1, "group": "Autotune", "longDesc": "After the auto-tuning sequence is completed,\na new set of gains is available and can be applied\nimmediately or after landing.\nWARNING Applying the gains in air is dangerous as there is no\nguarantee that those new gains will be able to stabilize\nthe drone properly.", "name": "MC_AT_APPLY", "shortDesc": "Controls when to apply the new gains", "type": "Int32", "values": [{"description": "Do not apply the new gains (logging only)", "value": 0}, {"description": "Apply the new gains after disarm", "value": 1}, {"description": "WARNING Apply the new gains in air", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Autotune", "name": "MC_AT_EN", "shortDesc": "Multicopter autotune module enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.14, "group": "Autotune", "max": 0.5, "min": 0.01, "name": "MC_AT_RISE_TIME", "shortDesc": "Desired angular rate closed-loop rise time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.7, "group": "Autotune", "max": 6.0, "min": 0.1, "name": "MC_AT_SYSID_AMP", "shortDesc": "Amplitude of the injected signal", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 1 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT1_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 1 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT1_N_CELLS", "shortDesc": "Number of cells for battery 1", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT1_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 1", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module / Analog'\nmeans that measurements are expected to come from either analog (ADC) inputs\nor an I2C power monitor (e.g. INA226). Analog inputs are voltage and current\nmeasurements read from the board's ADC channels, typically from an onboard\nvoltage divider and current shunt, or an external analog power module.\nI2C power monitors are digital sensors on the I2C bus.\nIf the value is set to 'External' then the system expects to receive MAVLink\nor CAN battery status messages, or the battery data is published by an external driver.\nIf the value is set to 'ESCs', the battery information are taken from the esc_status message.\nThis requires the ESC to provide both voltage as well as current (via ESC telemetry).", "name": "BAT1_SOURCE", "rebootRequired": true, "shortDesc": "Battery 1 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module / Analog", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full.\nFor a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT1_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty.\nThe voltage should be chosen above the steep dropoff at 3.5V. A typical\nlithium battery can only be discharged under high load down to 10% before\nit drops off to a voltage level damaging the cells.", "name": "BAT1_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 2 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT2_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 2 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT2_N_CELLS", "shortDesc": "Number of cells for battery 2", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT2_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 2", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": -1, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module / Analog'\nmeans that measurements are expected to come from either analog (ADC) inputs\nor an I2C power monitor (e.g. INA226). Analog inputs are voltage and current\nmeasurements read from the board's ADC channels, typically from an onboard\nvoltage divider and current shunt, or an external analog power module.\nI2C power monitors are digital sensors on the I2C bus.\nIf the value is set to 'External' then the system expects to receive MAVLink\nor CAN battery status messages, or the battery data is published by an external driver.\nIf the value is set to 'ESCs', the battery information are taken from the esc_status message.\nThis requires the ESC to provide both voltage as well as current (via ESC telemetry).", "name": "BAT2_SOURCE", "rebootRequired": true, "shortDesc": "Battery 2 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module / Analog", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full.\nFor a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT2_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty.\nThe voltage should be chosen above the steep dropoff at 3.5V. A typical\nlithium battery can only be discharged under high load down to 10% before\nit drops off to a voltage level damaging the cells.", "name": "BAT2_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 3 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT3_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 3 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT3_N_CELLS", "shortDesc": "Number of cells for battery 3", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT3_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 3", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": -1, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module / Analog'\nmeans that measurements are expected to come from either analog (ADC) inputs\nor an I2C power monitor (e.g. INA226). Analog inputs are voltage and current\nmeasurements read from the board's ADC channels, typically from an onboard\nvoltage divider and current shunt, or an external analog power module.\nI2C power monitors are digital sensors on the I2C bus.\nIf the value is set to 'External' then the system expects to receive MAVLink\nor CAN battery status messages, or the battery data is published by an external driver.\nIf the value is set to 'ESCs', the battery information are taken from the esc_status message.\nThis requires the ESC to provide both voltage as well as current (via ESC telemetry).", "name": "BAT3_SOURCE", "rebootRequired": true, "shortDesc": "Battery 3 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module / Analog", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full.\nFor a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT3_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty.\nThe voltage should be chosen above the steep dropoff at 3.5V. A typical\nlithium battery can only be discharged under high load down to 10% before\nit drops off to a voltage level damaging the cells.", "name": "BAT3_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 15.0, "group": "Battery Calibration", "increment": 0.1, "longDesc": "This value is used to initialize the in-flight average current estimation,\nwhich in turn is used for estimating remaining flight time and RTL triggering.", "max": 500.0, "min": 0.0, "name": "BAT_AVRG_CURRENT", "shortDesc": "Expected battery current in flight", "type": "Float", "units": "A"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.07, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as critically low.\nThis has to be lower than the low threshold. This threshold commonly\nwill trigger RTL.", "max": 0.5, "min": 0.05, "name": "BAT_CRIT_THR", "shortDesc": "Critical threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as dangerously low.\nThis has to be lower than the critical threshold. This threshold commonly\nwill trigger landing.", "max": 0.5, "min": 0.03, "name": "BAT_EMERGEN_THR", "shortDesc": "Emergency threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as low.\nThis has to be higher than the critical threshold.", "max": 0.5, "min": 0.12, "name": "BAT_LOW_THR", "shortDesc": "Low threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Camera trigger", "longDesc": "This parameter sets the time the trigger needs to pulled high or low.", "max": 3000.0, "min": 0.1, "name": "TRIG_ACT_TIME", "rebootRequired": true, "shortDesc": "Camera trigger activation time", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "Camera trigger", "increment": 1.0, "longDesc": "Sets the distance at which to trigger the camera.", "min": 0.0, "name": "TRIG_DISTANCE", "rebootRequired": true, "shortDesc": "Camera trigger distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 4, "group": "Camera trigger", "longDesc": "Selects the trigger interface", "name": "TRIG_INTERFACE", "rebootRequired": true, "shortDesc": "Camera trigger Interface", "type": "Int32", "values": [{"description": "GPIO", "value": 1}, {"description": "Seagull MAP2 (over PWM)", "value": 2}, {"description": "MAVLink (Camera Protocol v1)", "value": 3}, {"description": "Generic PWM (IR trigger, servo)", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Camera trigger", "longDesc": "This parameter sets the time between two consecutive trigger events", "max": 10000.0, "min": 4.0, "name": "TRIG_INTERVAL", "rebootRequired": true, "shortDesc": "Camera trigger interval", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Camera trigger", "longDesc": "This parameter sets the minimum time between two consecutive trigger events\nthe specific camera setup is supporting.", "max": 10000.0, "min": 1.0, "name": "TRIG_MIN_INTERVA", "rebootRequired": true, "shortDesc": "Minimum camera trigger interval", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "Camera trigger", "max": 4, "min": 0, "name": "TRIG_MODE", "rebootRequired": true, "shortDesc": "Camera trigger mode", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Time based, on command", "value": 1}, {"description": "Time based, always on", "value": 2}, {"description": "Distance based, always on", "value": 3}, {"description": "Distance based, on command (Survey mode)", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Camera trigger", "longDesc": "This parameter sets the polarity of the trigger (0 = active low, 1 = active high )", "max": 1, "min": 0, "name": "TRIG_POLARITY", "rebootRequired": true, "shortDesc": "Camera trigger polarity", "type": "Int32", "values": [{"description": "Active low", "value": 0}, {"description": "Active high", "value": 1}]}, {"category": "Standard", "default": 1500, "group": "Camera trigger", "max": 2000, "min": 1000, "name": "TRIG_PWM_NEUTRAL", "rebootRequired": true, "shortDesc": "PWM neutral output on trigger pin", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 1900, "group": "Camera trigger", "max": 2000, "min": 1000, "name": "TRIG_PWM_SHOOT", "rebootRequired": true, "shortDesc": "PWM output to trigger shot", "type": "Int32", "units": "us"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 782097 will disable the buzzer audio notification.\nSetting this parameter to 782090 will disable the startup tune, while keeping\nall others enabled.", "max": 782097, "min": 0, "name": "CBRK_BUZZER", "rebootRequired": true, "shortDesc": "Circuit breaker for disabling buzzer", "type": "Int32"}, {"category": "Developer", "default": 121212, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 121212 will disable the flight termination action if triggered\nby the FailureDetector logic or if FMU is lost.\nThis circuit breaker does not affect the RC loss, data link loss, geofence,\nand takeoff failure detection safety logic.", "max": 121212, "min": 0, "name": "CBRK_FLIGHTTERM", "rebootRequired": true, "shortDesc": "Circuit breaker for flight termination", "type": "Int32"}, {"category": "Developer", "default": 22027, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 22027 will disable IO safety.\nWARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 22027, "min": 0, "name": "CBRK_IO_SAFETY", "shortDesc": "Circuit breaker for IO safety", "type": "Int32"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 894281 will disable the power valid\nchecks in the commander.\nWARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 894281, "min": 0, "name": "CBRK_SUPPLY_CHK", "shortDesc": "Circuit breaker for power supply check", "type": "Int32"}, {"category": "Developer", "default": 197848, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 197848 will disable the USB connected\nchecks in the commander, setting it to 0 keeps them enabled (recommended).\nWe are generally recommending to not fly with the USB link\nconnected and production vehicles should set this parameter to\nzero to prevent users from flying USB powered. However, for R&D purposes\nit has proven over the years to work just fine.", "max": 197848, "min": 0, "name": "CBRK_USB_CHK", "shortDesc": "Circuit breaker for USB link check", "type": "Int32"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 159753 will enable arming in fixed-wing\nmode for VTOLs.\nWARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 159753, "min": 0, "name": "CBRK_VTOLARMING", "shortDesc": "Circuit breaker for arming in fixed-wing mode check", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Note: actuator failure needs to be enabled and configured via FD_ACT_*\nparameters.", "max": 3, "min": 0, "name": "COM_ACT_FAIL_ACT", "shortDesc": "Set the actuator failure failsafe mode", "type": "Int32", "values": [{"description": "Warning only", "value": 0}, {"description": "Hold mode", "value": 1}, {"description": "Land mode", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Terminate", "value": 4}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Set 0 to prevent accidental use of the vehicle e.g. for safety or maintenance reasons.", "name": "COM_ARMABLE", "shortDesc": "Flag to allow arming", "type": "Int32", "values": [{"description": "Disallow arming", "value": 0}, {"description": "Allow arming", "value": 1}]}, {"category": "Standard", "default": 10, "group": "Commander", "longDesc": "Used if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_ID", "shortDesc": "Arm authorizer system id", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Methods:\n- one arm: request authorization and arm when authorization is received\n- two step arm: 1st arm command request an authorization and\n2nd arm command arm the drone if authorized\nUsed if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_MET", "shortDesc": "Arm authorization method", "type": "Int32", "values": [{"description": "one arm", "value": 0}, {"description": "two step arm", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "By default off. The default allows to arm the vehicle without a arm authorization.", "name": "COM_ARM_AUTH_REQ", "shortDesc": "Require arm authorization to arm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "increment": 0.1, "longDesc": "Timeout for authorizer answer.\nUsed if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_TO", "shortDesc": "Arm authorization timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Commander", "increment": 0.01, "longDesc": "Threshold for battery percentage below arming is prohibited.\nA negative value means BAT_CRIT_THR is the threshold.", "max": 0.9, "min": -1.0, "name": "COM_ARM_BAT_MIN", "shortDesc": "Minimum battery level for arming", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "If this parameter is set, the system will check ESC's online status and failures.\nThis param is specific for ESCs reporting status. It shall be used only if ESCs support telemetry.", "name": "COM_ARM_CHK_ESCS", "shortDesc": "Enable checks on ESCs that report telemetry", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This check detects if there are hardfault files present on the\nSD card. If so, and the parameter is enabled, arming is prevented.", "name": "COM_ARM_HFLT_CHK", "shortDesc": "Enable FMU SD card hardfault detection check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "Commander", "increment": 0.05, "max": 1.0, "min": 0.1, "name": "COM_ARM_IMU_ACC", "shortDesc": "Maximum accelerometer inconsistency between IMU units that will allow arming", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Commander", "increment": 0.01, "max": 0.3, "min": 0.02, "name": "COM_ARM_IMU_GYR", "shortDesc": "Maximum rate gyro inconsistency between IMU units that will allow arming", "type": "Float", "units": "rad/s"}, {"category": "Standard", "default": 60, "group": "Commander", "longDesc": "Set -1 to disable the check.", "max": 180, "min": 3, "name": "COM_ARM_MAG_ANG", "shortDesc": "Maximum magnetic field inconsistency between units that will allow arming", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Commander", "longDesc": "Check if the estimator detects a strong magnetic\ndisturbance (check enabled by EKF2_MAG_CHECK)", "name": "COM_ARM_MAG_STR", "shortDesc": "Enable mag strength preflight check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Deny arming", "value": 1}, {"description": "Warning only", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The default allows to arm the vehicle without a valid mission.", "name": "COM_ARM_MIS_REQ", "shortDesc": "Require valid mission to arm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "This check detects if the Open Drone ID system is missing.\nDepending on the value of the parameter, the check can be\ndisabled, warn only or deny arming.", "name": "COM_ARM_ODID", "shortDesc": "Enable Drone ID system detection and health check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Enforce Open Drone ID system presence", "value": 2}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This check detects if the FMU SD card is missing.\nDepending on the value of the parameter, the check can be\ndisabled, warn only or deny arming.", "name": "COM_ARM_SDCARD", "shortDesc": "Enable FMU SD card detection check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Enforce SD card presence", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "0: Arming/disarming triggers on switch transition.\n1: Arming/disarming triggers when holding the momentary button down like the stick gesture.", "name": "COM_ARM_SWISBTN", "shortDesc": "Arm switch is a momentary button", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Configures whether arming is allowed without GNSS, for modes that require a global position\n(specifically, in those modes when a check defined by EKF2_GPS_CHECK fails).\nThe settings deny arming and warn, allow arming and warn, or silently allow arming.", "name": "COM_ARM_WO_GPS", "shortDesc": "Arming without GNSS configuration", "type": "Int32", "values": [{"description": "Deny arming", "value": 0}, {"description": "Allow arming (with warning)", "value": 1}, {"description": "Allow arming (no warning)", "value": 2}]}, {"category": "Standard", "default": 95.0, "group": "Commander", "increment": 1.0, "longDesc": "The check fails if the CPU load is above this threshold for 2s.\nA negative value disables the check.", "max": 100.0, "min": -1.0, "name": "COM_CPU_MAX", "shortDesc": "Maximum allowed CPU load to still arm", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Commander", "increment": 0.1, "longDesc": "A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be\nautomatically disarmed in case a landing situation has been detected during this period.\nA zero or negative value means that automatic disarming triggered by landing detection is disabled.", "name": "COM_DISARM_LAND", "shortDesc": "Time-out for auto disarm after landing", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "0: Disallow disarming when not landed\n1: Allow disarming in multicopter flight in modes where\nthe thrust is directly controlled by thr throttle stick\ne.g. Stabilized, Acro", "name": "COM_DISARM_MAN", "shortDesc": "Allow disarming via switch/stick/button on multicopters in manual thrust modes", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Commander", "increment": 0.1, "longDesc": "A non-zero, positive value specifies the time in seconds, within which the\nvehicle is expected to take off after arming. In case the vehicle didn't takeoff\nwithin the timeout it disarms again.\nA negative value disables autmoatic disarming triggered by a pre-takeoff timeout.", "name": "COM_DISARM_PRFLT", "shortDesc": "Time-out for auto disarm if not taking off", "type": "Float", "units": "s"}, {"bitmask": [{"description": "Mission", "index": 0}, {"description": "Auto modes", "index": 1}, {"description": "Offboard", "index": 2}, {"description": "External Mode", "index": 3}, {"description": "Altitude Cruise", "index": 4}], "category": "Standard", "default": 0, "group": "Commander", "longDesc": "Specify modes in which ground control station connection loss is ignored and no failsafe action is triggered.\nSee also COM_RCL_EXCEPT.", "max": 31, "min": 0, "name": "COM_DLL_EXCEPT", "shortDesc": "Datalink loss exceptions", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10, "group": "Commander", "increment": 1, "longDesc": "After this amount of seconds without datalink, the GCS connection lost mode triggers", "max": 300, "min": 5, "name": "COM_DL_LOSS_T", "shortDesc": "GCS connection loss time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "longDesc": "Before entering failsafe (RTL, Land, Hold), wait COM_FAIL_ACT_T seconds in Hold mode\nfor the user to realize.\nDuring that time the user can switch modes, but cannot take over control via the stick override feature (see COM_RC_OVERRIDE).\nAfterwards the configured failsafe action is triggered and the user may use stick override.\nA zero value disables the delay.", "max": 25.0, "min": 0.0, "name": "COM_FAIL_ACT_T", "shortDesc": "Delay between failsafe condition triggered and failsafe reaction", "type": "Float", "units": "s"}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This number is incremented automatically after every flight on\ndisarming in order to remember the next flight UUID.\nThe first flight is 0.", "min": 0, "name": "COM_FLIGHT_UUID", "shortDesc": "Next flight UUID", "type": "Int32", "volatile": true}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE1", "shortDesc": "Mode slot 1", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "Altitude Cruise", "value": 16}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE2", "shortDesc": "Mode slot 2", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "Altitude Cruise", "value": 16}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE3", "shortDesc": "Mode slot 3", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "Altitude Cruise", "value": 16}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE4", "shortDesc": "Mode slot 4", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "Altitude Cruise", "value": 16}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE5", "shortDesc": "Mode slot 5", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "Altitude Cruise", "value": 16}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE6", "shortDesc": "Mode slot 6", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "Altitude Cruise", "value": 16}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when the remaining flight time is below\nthe estimated time it takes to reach the RTL destination.", "name": "COM_FLTT_LOW_ACT", "shortDesc": "Remaining flight time low failsafe", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Return", "value": 3}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Describes the intended use of the vehicle.\nCan be used by ground control software or log post processing.\nThis param does not influence the behavior within the firmware. This means for example the control logic is independent of the setting of this param (but depends on other params).", "name": "COM_FLT_PROFILE", "shortDesc": "User Flight Profile", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Pro User", "value": 100}, {"description": "Flight Tester", "value": 200}, {"description": "Developer", "value": 300}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "The vehicle aborts the current operation and returns to launch when\nthe time since takeoff is above this value. It is not possible to resume the\nmission or switch to any auto mode other than RTL or Land. Taking over in any manual\nmode is still possible.\nStarting from 90% of the maximum flight time, a warning message will be sent\nevery 1 minute with the remaining time until automatic RTL.\nSet to -1 to disable.", "min": -1, "name": "COM_FLT_TIME_MAX", "shortDesc": "Maximum allowed flight time", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Force safety when the vehicle disarms", "name": "COM_FORCE_SAFETY", "shortDesc": "Enable force safety", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 120, "group": "Commander", "longDesc": "After this amount of seconds without datalink the data link lost mode triggers", "max": 3600, "min": 60, "name": "COM_HLDL_LOSS_T", "shortDesc": "High Latency Datalink loss time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "After a data link loss: after this number of seconds with a healthy datalink the 'datalink loss'\nflag is set back to false", "max": 60, "min": 0, "name": "COM_HLDL_REG_T", "shortDesc": "High Latency Datalink regain time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Set home position automatically if possible.\nDuring missions, the latitude/longitude of the home position is locked and will not reset during intermediate landings.\nIt will only update once the mission is complete or landed outside of a mission.\nHowever, the altitude is still being adjusted to correct for GNSS vertical drift in the first 2 minutes after takeoff.", "name": "COM_HOME_EN", "rebootRequired": true, "shortDesc": "Home position enabled", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "If set to true, the autopilot is allowed to set its home position after takeoff\nThe true home position is back-computed if a local position is estimate if available.\nIf no local position is available, home is set to the current position.", "name": "COM_HOME_IN_AIR", "shortDesc": "Allows setting the home position after takeoff", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when an imbalanced propeller is detected by the failure detector.\nSee also FD_IMB_PROP_THR to set the failure threshold.", "name": "COM_IMB_PROP_ACT", "shortDesc": "Imbalanced propeller failsafe mode", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Warning", "value": 0}, {"description": "Return", "value": 1}, {"description": "Land", "value": 2}]}, {"category": "Standard", "default": 5.0, "group": "Commander", "increment": 0.1, "longDesc": "Use RC_MAP_KILL_SW to map a kill switch.", "max": 30.0, "min": 0.0, "name": "COM_KILL_DISARM", "shortDesc": "Timeout value for disarming when kill switch is engaged", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Commander", "longDesc": "A non-zero, positive value specifies the timeframe in seconds within failure detector is allowed to disarm the vehicle\nif attitude exceeds the limits defined in FD_FAIL_P and FD_FAIL_R.\nThe check is not executed for flight modes that do support acrobatic maneuvers, e.g: Acro (MC/FW) and Manual (FW).\nA zero or negative value means that the check is disabled.", "max": 5.0, "min": -1.0, "name": "COM_LKDOWN_TKO", "shortDesc": "Timeout for detecting a failure after takeoff", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Action the system takes at critical battery. See also BAT_CRIT_THR and BAT_EMERGEN_THR\nfor definition of battery states.", "name": "COM_LOW_BAT_ACT", "shortDesc": "Battery failsafe mode", "type": "Int32", "values": [{"description": "Warning", "value": 0}, {"description": "Land mode", "value": 2}, {"description": "Return at critical level, land at emergency level", "value": 3}]}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE0_HASH", "shortDesc": "External mode identifier 0", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE1_HASH", "shortDesc": "External mode identifier 1", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE2_HASH", "shortDesc": "External mode identifier 2", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE3_HASH", "shortDesc": "External mode identifier 3", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE4_HASH", "shortDesc": "External mode identifier 4", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE5_HASH", "shortDesc": "External mode identifier 5", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE6_HASH", "shortDesc": "External mode identifier 6", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE7_HASH", "shortDesc": "External mode identifier 7", "type": "Int32", "volatile": true}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "By default disabled for safety reasons", "name": "COM_MODE_ARM_CHK", "shortDesc": "Allow external mode registration while armed", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "If set, enables the actuator test interface via MAVLink (ACTUATOR_TEST), that\nallows spinning the motors and moving the servos for testing purposes.", "name": "COM_MOT_TEST_EN", "shortDesc": "Enable Actuator Testing", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 5.0, "group": "Commander", "increment": 0.01, "max": 60.0, "min": 0.0, "name": "COM_OBC_LOSS_T", "shortDesc": "Time-out to wait when onboard computer connection is lost before warning about loss connection", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The offboard loss failsafe will only be entered after a timeout,\nset by COM_OF_LOSS_T in seconds.", "name": "COM_OBL_RC_ACT", "shortDesc": "Set offboard loss failsafe mode", "type": "Int32", "values": [{"description": "Position mode", "value": 0}, {"description": "Altitude mode", "value": 1}, {"description": "Stabilized", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Land mode", "value": 4}, {"description": "Hold mode", "value": 5}, {"description": "Terminate", "value": 6}, {"description": "Disarm", "value": 7}]}, {"category": "Standard", "default": 1.0, "group": "Commander", "increment": 0.01, "longDesc": "See COM_OBL_RC_ACT to configure action.", "max": 60.0, "min": 0.0, "name": "COM_OF_LOSS_T", "shortDesc": "Time-out to wait when offboard connection is lost before triggering offboard lost action", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "name": "COM_PARACHUTE", "shortDesc": "Expect and require a healthy MAVLink parachute system", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "longDesc": "This is the horizontal position error (EPH) threshold that will trigger a failsafe.\nIf the previous position error was below this threshold, there is an additional\nfactor of 2.5 applied (threshold for invalidation 2.5 times the one for validation).\nOnly used for multicopters and VTOLs in hover mode.\nIndependent from estimator positioning data timeout threshold (see EKF2_NOAID_TOUT).\nSet to -1 to disable.", "max": 400.0, "min": -1.0, "name": "COM_POS_FS_EPH", "shortDesc": "Horizontal position error threshold for hovering systems", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when the estimated position has an accuracy below the specified threshold.\nSee COM_POS_LOW_EPH to set the failsafe threshold.\nThe failsafe action is only executed if the vehicle is in auto mission or auto loiter mode,\notherwise it is only a warning.", "name": "COM_POS_LOW_ACT", "shortDesc": "Low position accuracy action", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold", "value": 2}, {"description": "Return", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land", "value": 5}]}, {"category": "Standard", "default": -1.0, "group": "Commander", "longDesc": "This triggers the action specified in COM_POS_LOW_ACT if the estimated position accuracy is below this threshold.\nLocal position has to be still declared valid, which requires some kind of velocity aiding or large dead-reckoning time (EKF2_NOAID_TOUT),\nand a high failsafe threshold (COM_POS_FS_EPH).\nSet to -1 to disable.", "max": 1000.0, "min": -1.0, "name": "COM_POS_LOW_EPH", "shortDesc": "Low position accuracy failsafe threshold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This configures a check to verify the expected number of 5V rail power supplies are present. By default only one is expected.\nNote: CBRK_SUPPLY_CHK disables all power checks including this one.", "max": 4, "min": 0, "name": "COM_POWER_COUNT", "shortDesc": "Required number of redundant power modules", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Condition to enter the prearmed state, an intermediate state between disarmed and armed\nin which non-throttling actuators are active.", "name": "COM_PREARM_MODE", "shortDesc": "Condition to enter prearmed mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Safety button", "value": 1}, {"description": "Always", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "name": "COM_QC_ACT", "shortDesc": "Set action after a quadchute", "type": "Int32", "values": [{"description": "Warning only", "value": -1}, {"description": "Return mode", "value": 0}, {"description": "Land mode", "value": 1}, {"description": "Hold mode", "value": 2}]}, {"category": "Standard", "default": 95.0, "group": "Commander", "increment": 1.0, "longDesc": "The check fails if the RAM usage is above this threshold.\nA negative value disables the check.", "max": 100.0, "min": -1.0, "name": "COM_RAM_MAX", "shortDesc": "Maximum allowed RAM usage to pass checks", "type": "Float", "units": "%"}, {"bitmask": [{"description": "Mission", "index": 0}, {"description": "Auto modes", "index": 1}, {"description": "Offboard", "index": 2}, {"description": "External Mode", "index": 3}, {"description": "Altitude Cruise", "index": 4}], "category": "Standard", "default": 0, "group": "Commander", "longDesc": "Specify modes in which stick input is ignored and no failsafe action is triggered.\nExternal modes requiring stick input will still failsafe.\nAuto modes are: Hold, Takeoff, Land, RTL, Descend, Follow Target, Precland, Orbit.", "max": 31, "min": 0, "name": "COM_RCL_EXCEPT", "shortDesc": "Manual control loss exceptions", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "Commander", "longDesc": "Selects stick input selection behavior:\neither a traditional remote control receiver (RC) or a MAVLink joystick (MANUAL_CONTROL message)\nPriority sources are immediately switched to whenever they get valid.\n0 RC only. Requires valid RC calibration.\n1 MAVLink only. RC and related checks are disabled.\n2 Switches only if current source becomes invalid.\n3 Locks to the first valid source until reboot.\n4 Ignores all sources.\n5 RC priority, then MAVLink (lower instance before higher)\n6 MAVLink priority (lower instance before higher), then RC\n7 RC priority, then MAVLink (higher instance before lower)\n8 MAVLink priority (higher instance before lower), then RC", "max": 8, "min": 0, "name": "COM_RC_IN_MODE", "shortDesc": "Manual control input source configuration", "type": "Int32", "values": [{"description": "RC only", "value": 0}, {"description": "MAVLink only", "value": 1}, {"description": "RC or MAVLink with fallback", "value": 2}, {"description": "RC or MAVLink keep first", "value": 3}, {"description": "Disable manual control", "value": 4}, {"description": "Prio: RC > MAVL 1 > MAVL 2", "value": 5}, {"description": "Prio: MAVL 1 > MAVL 2 > RC", "value": 6}, {"description": "Prio: RC > MAVL 2 > MAVL 1", "value": 7}, {"description": "Prio: MAVL 2 > MAVL 1 > RC", "value": 8}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Commander", "increment": 0.1, "longDesc": "The time in seconds without a new setpoint from RC or Joystick, after which the connection is considered lost.\nThis must be kept short as the vehicle will use the last supplied setpoint until the timeout triggers.\nEnsure the value is not set lower than the update interval of the RC or Joystick.", "max": 35.0, "min": 0.0, "name": "COM_RC_LOSS_T", "shortDesc": "Manual control loss timeout", "type": "Float", "units": "s"}, {"bitmask": [{"description": "Enable override during auto modes (except for in critical battery reaction)", "index": 0}, {"description": "Enable override during offboard mode", "index": 1}], "category": "Standard", "default": 1, "group": "Commander", "longDesc": "When enabled, moving the sticks more than COM_RC_STICK_OV\nimmediately gives control back to the pilot by switching to Position mode and\nif position is unavailable Altitude mode.\nNote: Only has an effect on multicopters, and VTOLs in multicopter mode.", "max": 3, "min": 0, "name": "COM_RC_OVERRIDE", "shortDesc": "Enable manual control stick override", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 0, "default": 30.0, "group": "Commander", "increment": 0.05, "longDesc": "If COM_RC_OVERRIDE is enabled and the joystick input is moved more than this threshold\nthe autopilot the pilot takes over control.", "max": 80.0, "min": 5.0, "name": "COM_RC_STICK_OV", "shortDesc": "Stick override threshold", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "increment": 0.1, "longDesc": "The minimal time from arming the motors until moving the vehicle is possible is COM_SPOOLUP_TIME seconds.\nGoal:\n- Motors and propellers spool up to idle speed before getting commanded to spin faster\n- Timeout for ESCs and smart batteries to successfulyy do failure checks\ne.g. for stuck rotors before the vehicle is off the ground", "max": 30.0, "min": 0.0, "name": "COM_SPOOLUP_TIME", "shortDesc": "Enforced delay between arming and further navigation", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The mode transition after TAKEOFF has completed successfully.", "name": "COM_TAKEOFF_ACT", "shortDesc": "Action after TAKEOFF has been accepted", "type": "Int32", "values": [{"description": "Hold", "value": 0}, {"description": "Mission (if valid)", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Allows to start the vehicle by throwing it into the air.", "name": "COM_THROW_EN", "shortDesc": "Enable throw-start", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "increment": 0.1, "longDesc": "When the throw launch is enabled, the drone will only allow motors to spin after this speed\nis exceeded before detecting the freefall. This is a safety feature to ensure the drone does\nnot turn on after accidental drop or a rapid movement before the throw.\nSet to 0 to disable.", "min": 0.0, "name": "COM_THROW_SPEED", "shortDesc": "Minimum speed for the throw start", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "longDesc": "This is the horizontal velocity error (EVH) threshold that will trigger a failsafe.\nThe default is appropriate for a multicopter. Can be increased for a fixed-wing.\nIf the previous velocity error was below this threshold, there is an additional\nfactor of 2.5 applied (threshold for invalidation 2.5 times the one for validation).", "min": 0.0, "name": "COM_VEL_FS_EVH", "shortDesc": "Horizontal velocity error threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Commander", "increment": 0.1, "longDesc": "Wind speed threshold above which an automatic failsafe action is triggered.\nFailsafe action can be specified with COM_WIND_MAX_ACT.", "min": -1.0, "name": "COM_WIND_MAX", "shortDesc": "High wind speed failsafe threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when a wind speed above the specified threshold is detected.\nSee COM_WIND_MAX to set the failsafe threshold.\nIf enabled, it is not possible to resume the mission or switch to any auto mode other than\nRTL or Land if this threshold is exceeded. Taking over in any manual\nmode is still possible.", "name": "COM_WIND_MAX_ACT", "shortDesc": "High wind failsafe mode", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold", "value": 2}, {"description": "Return", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Commander", "increment": 0.1, "longDesc": "A warning is triggered if the currently estimated wind speed is above this value.\nWarning is sent periodically (every 1 minute).\nSet to -1 to disable.", "min": -1.0, "name": "COM_WIND_WARN", "shortDesc": "Wind speed warning threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The GCS connection loss failsafe will only be entered after a timeout,\nset by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected\naction will be executed.", "max": 6, "min": 0, "name": "NAV_DLL_ACT", "shortDesc": "Set GCS connection loss failsafe mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Hold mode", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Terminate", "value": 5}, {"description": "Disarm", "value": 6}]}, {"category": "Standard", "default": 2, "group": "Commander", "longDesc": "The manual control loss failsafe will only be entered after a timeout,\nset by COM_RC_LOSS_T in seconds.", "max": 6, "min": 1, "name": "NAV_RCL_ACT", "shortDesc": "Set manual control loss failsafe mode", "type": "Int32", "values": [{"description": "Hold mode", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Terminate", "value": 5}, {"description": "Disarm", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "max": 0.5, "min": 0.0, "name": "EKF2_ABIAS_INIT", "rebootRequired": true, "shortDesc": "1-sigma IMU accelerometer switch-on bias", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "EKF2", "longDesc": "If the magnitude of the IMU accelerometer vector exceeds this value, the EKF accel bias state estimation will be inhibited. This reduces the adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale factor errors on the accel bias estimates.", "max": 200.0, "min": 20.0, "name": "EKF2_ABL_ACCLIM", "shortDesc": "Maximum IMU accel magnitude that allows IMU bias learning", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "If the magnitude of the IMU angular rate vector exceeds this value, the EKF accel bias state estimation will be inhibited. This reduces the adverse effect of rapid rotation rates and associated errors on the accel bias estimates.", "max": 20.0, "min": 2.0, "name": "EKF2_ABL_GYRLIM", "shortDesc": "Maximum IMU gyro angular rate magnitude that allows IMU bias learning", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "EKF2", "longDesc": "The ekf accel bias states will be limited to within a range equivalent to +- of this value.", "max": 0.8, "min": 0.0, "name": "EKF2_ABL_LIM", "shortDesc": "Accelerometer bias learning limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay. This parameter controls the time constant of the decay.", "max": 1.0, "min": 0.1, "name": "EKF2_ABL_TAU", "shortDesc": "Accel bias learning inhibit time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.003, "group": "EKF2", "max": 0.01, "min": 0.0, "name": "EKF2_ACC_B_NOISE", "shortDesc": "Process noise for IMU accelerometer bias prediction", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.35, "group": "EKF2", "max": 1.0, "min": 0.01, "name": "EKF2_ACC_NOISE", "shortDesc": "Accelerometer noise for covariance prediction", "type": "Float", "units": "m/s^2"}, {"bitmask": [{"description": "Horizontal position", "index": 0}, {"description": "Vertical position", "index": 1}], "category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Horizontal position fusion 1 : Vertical position fusion", "max": 3, "min": 0, "name": "EKF2_AGP_CTRL", "shortDesc": "Aux global position (AGP) sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_AGP_DELAY", "rebootRequired": true, "shortDesc": "Aux global position estimator delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_AGP_GATE", "shortDesc": "Gate size for aux global position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Automatic: reset on fusion timeout if no other source of position is available Dead-reckoning: reset on fusion timeout if no source of velocity is available", "name": "EKF2_AGP_MODE", "shortDesc": "Fusion reset mode", "type": "Int32", "values": [{"description": "Automatic", "value": 0}, {"description": "Dead-reckoning", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.9, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_AGP_NOISE", "shortDesc": "Measurement noise for aux global position measurements", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "EKF2", "max": 0.5, "min": 0.0, "name": "EKF2_ANGERR_INIT", "rebootRequired": true, "shortDesc": "1-sigma tilt angle uncertainty after gravity vector alignment", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "longDesc": "Airspeed data is fused for wind estimation if above this threshold. Set to 0 to disable airspeed fusion. For reliable wind estimation both sideslip (see EKF2_FUSE_BETA) and airspeed fusion should be enabled. Only applies to fixed-wing vehicles (or VTOLs in fixed-wing mode).", "min": 0.0, "name": "EKF2_ARSP_THR", "shortDesc": "Airspeed fusion threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "max": 50.0, "min": 5.0, "name": "EKF2_ASPD_MAX", "shortDesc": "Maximum airspeed used for baro static pressure compensation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_ASP_DELAY", "rebootRequired": true, "shortDesc": "Airspeed measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_AVEL_DELAY", "rebootRequired": true, "shortDesc": "Auxiliary Velocity Estimate delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "If this parameter is enabled then the estimator will make use of the barometric height measurements to estimate its height in addition to other height sources (if activated).", "name": "EKF2_BARO_CTRL", "shortDesc": "Barometric sensor height aiding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_BARO_DELAY", "rebootRequired": true, "shortDesc": "Barometer measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_BARO_GATE", "shortDesc": "Gate size for barometric and GPS height fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.5, "group": "EKF2", "max": 15.0, "min": 0.01, "name": "EKF2_BARO_NOISE", "shortDesc": "Measurement noise for barometric altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by bluff body drag along the forward/reverse axis when flying a multi-copter which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis.", "max": 200.0, "min": 0.0, "name": "EKF2_BCOEF_X", "shortDesc": "X-axis ballistic coefficient used for multi-rotor wind estimation", "type": "Float", "units": "kg/m^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by bluff body drag along the right/left axis when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis.", "max": 200.0, "min": 0.0, "name": "EKF2_BCOEF_Y", "shortDesc": "Y-axis ballistic coefficient used for multi-rotor wind estimation", "type": "Float", "units": "kg/m^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_BETA_GATE", "shortDesc": "Gate size for synthetic sideslip fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 1.0, "min": 0.1, "name": "EKF2_BETA_NOISE", "shortDesc": "Noise for synthetic sideslip fusion", "type": "Float", "units": "m/s"}, {"bitmask": [{"description": "use geo_lookup declination", "index": 0}, {"description": "save EKF2_MAG_DECL on disarm", "index": 1}], "category": "Standard", "default": 3, "group": "EKF2", "longDesc": "Set bits in the following positions to enable functions. 0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value. 1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms.", "max": 3, "min": 0, "name": "EKF2_DECL_TYPE", "rebootRequired": true, "shortDesc": "Integer bitmask controlling handling of magnetic declination", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 200.0, "group": "EKF2", "longDesc": "Defines the delay between the current time and the delayed-time horizon. This value should be at least as large as the largest EKF2_XXX_DELAY parameter.", "max": 1000.0, "min": 0.0, "name": "EKF2_DELAY_MAX", "rebootRequired": true, "shortDesc": "Maximum delay of all the aiding sensors", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Activate wind speed estimation using specific-force measurements and a drag model defined by EKF2_BCOEF_[XY] and EKF2_MCOEF. Only use on vehicles that have their thrust aligned with the Z axis and no thrust in the XY plane.", "name": "EKF2_DRAG_CTRL", "shortDesc": "Multirotor wind estimation selection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 2.5, "group": "EKF2", "longDesc": "Used by the multi-rotor specific drag force model. Increasing this makes the multi-rotor wind estimates adjust more slowly.", "max": 10.0, "min": 0.5, "name": "EKF2_DRAG_NOISE", "shortDesc": "Specific drag force observation noise variance", "type": "Float", "units": "(m/s^2)^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.4, "group": "EKF2", "max": 5.0, "min": 0.5, "name": "EKF2_EAS_NOISE", "shortDesc": "Measurement noise for airspeed fusion", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "EKF2", "name": "EKF2_EN", "shortDesc": "EKF2 enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "When enabled, constant position fusion is enabled when the vehicle is landed and armed. This is intended for IC engine warmup (e.g., fuel engines on catapult) to allow mode transitions to auto/takeoff despite vibrations from running engines.", "name": "EKF2_ENGINE_WRM", "shortDesc": "Enable constant position fusion during engine warmup", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.05, "name": "EKF2_EVA_NOISE", "shortDesc": "Measurement noise for vision angle measurements", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_EVP_GATE", "shortDesc": "Gate size for vision position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_EVP_NOISE", "shortDesc": "Measurement noise for vision position measurements", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_EVV_GATE", "shortDesc": "Gate size for vision velocity estimate fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_EVV_NOISE", "shortDesc": "Measurement noise for vision velocity measurements", "type": "Float", "units": "m/s"}, {"bitmask": [{"description": "Horizontal position", "index": 0}, {"description": "Vertical position", "index": 1}, {"description": "3D velocity", "index": 2}, {"description": "Yaw", "index": 3}], "category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Horizontal position fusion 1 : Vertical position fusion 2 : 3D velocity fusion 3 : Yaw", "max": 15, "min": 0, "name": "EKF2_EV_CTRL", "shortDesc": "External vision (EV) sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_EV_DELAY", "rebootRequired": true, "shortDesc": "Vision Position Estimator delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "If set to 0 (default) the measurement noise is taken from the vision message and the EV noise parameters are used as a lower bound. If set to 1 the observation noise is set from the parameters directly,", "name": "EKF2_EV_NOISE_MD", "shortDesc": "External vision (EV) noise mode", "type": "Int32", "values": [{"description": "EV reported variance (parameter lower bound)", "value": 0}, {"description": "EV noise parameters", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_X", "shortDesc": "X position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_Y", "shortDesc": "Y position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_Z", "shortDesc": "Z position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0, "group": "EKF2", "longDesc": "External vision will only be started and fused if the quality metric is above this threshold. The quality metric is a completely optional field provided by some VIO systems.", "max": 100, "min": 0, "name": "EKF2_EV_QMIN", "shortDesc": "External vision (EV) minimum quality (optional)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "For reliable wind estimation both sideslip and airspeed fusion (see EKF2_ARSP_THR) should be enabled. Only applies to vehicles in fixed-wing mode or with airspeed fusion active. Note: side slip fusion is currently not supported for tailsitters.", "name": "EKF2_FUSE_BETA", "shortDesc": "Enable synthetic sideslip fusion", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "max": 0.2, "min": 0.0, "name": "EKF2_GBIAS_INIT", "rebootRequired": true, "shortDesc": "1-sigma IMU gyro switch-on bias", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "EKF2", "longDesc": "Sets the value of deadzone applied to negative baro innovations. Deadzone is enabled when EKF2_GND_EFF_DZ > 0.", "max": 10.0, "min": 0.0, "name": "EKF2_GND_EFF_DZ", "shortDesc": "Baro deadzone range for height fusion", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "EKF2", "longDesc": "Sets the maximum distance to the ground level where negative baro innovations are expected.", "max": 5.0, "min": 0.0, "name": "EKF2_GND_MAX_HGT", "shortDesc": "Height above ground level for ground effect zone", "type": "Float", "units": "m"}, {"bitmask": [{"description": "Sat count (EKF2_REQ_NSATS)", "index": 0}, {"description": "PDOP (EKF2_REQ_PDOP)", "index": 1}, {"description": "EPH (EKF2_REQ_EPH)", "index": 2}, {"description": "EPV (EKF2_REQ_EPV)", "index": 3}, {"description": "Speed accuracy (EKF2_REQ_SACC)", "index": 4}, {"description": "Horizontal position drift (EKF2_REQ_HDRIFT)", "index": 5}, {"description": "Vertical position drift (EKF2_REQ_VDRIFT)", "index": 6}, {"description": "Horizontal speed offset (EKF2_REQ_HDRIFT)", "index": 7}, {"description": "Vertical speed offset (EKF2_REQ_VDRIFT)", "index": 8}, {"description": "Spoofing", "index": 9}, {"description": "GPS fix type (EKF2_REQ_FIX)", "index": 10}, {"description": "Jamming", "index": 11}], "category": "Standard", "default": 2047, "group": "EKF2", "longDesc": "Each threshold value is defined by the parameter indicated next to the check. Drift and offset checks only run when the vehicle is on ground and stationary.", "max": 4095, "min": 0, "name": "EKF2_GPS_CHECK", "shortDesc": "Integer bitmask controlling GPS checks", "type": "Int32"}, {"bitmask": [{"description": "Lon/lat", "index": 0}, {"description": "Altitude", "index": 1}, {"description": "3D velocity", "index": 2}, {"description": "Dual antenna heading", "index": 3}], "category": "Standard", "default": 7, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Longitude and latitude fusion 1 : Altitude fusion 2 : 3D velocity fusion 3 : Dual antenna heading fusion", "max": 15, "min": 0, "name": "EKF2_GPS_CTRL", "shortDesc": "GNSS sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 110.0, "group": "EKF2", "longDesc": "GPS measurement delay relative to IMU measurement if PPS time correction is not available/enabled (PPS_CAP_ENABLE).", "max": 300.0, "min": 0.0, "name": "EKF2_GPS_DELAY", "rebootRequired": true, "shortDesc": "GPS measurement delay relative to IMU measurement", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Automatic: reset on fusion timeout if no other source of position is available. Dead-reckoning: reset on fusion timeout if no source of velocity is available.", "name": "EKF2_GPS_MODE", "shortDesc": "Fusion reset mode", "type": "Int32", "values": [{"description": "Automatic", "value": 0}, {"description": "Dead-reckoning", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward (roll) axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_X", "shortDesc": "X position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Right (pitch) axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_Y", "shortDesc": "Y position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Down (yaw) axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_Z", "shortDesc": "Z position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_GPS_P_GATE", "shortDesc": "Gate size for GNSS position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "max": 10.0, "min": 0.01, "name": "EKF2_GPS_P_NOISE", "shortDesc": "Measurement noise for GNSS position", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_GPS_V_GATE", "shortDesc": "Gate size for GNSS velocity fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 5.0, "min": 0.01, "name": "EKF2_GPS_V_NOISE", "shortDesc": "Measurement noise for GNSS velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 360.0, "min": 0.0, "name": "EKF2_GPS_YAW_OFF", "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "EKF2", "max": 10.0, "min": 0.1, "name": "EKF2_GRAV_NOISE", "shortDesc": "Accelerometer measurement noise for gravity based observations", "type": "Float", "units": "g0"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "EKF2", "longDesc": "If no airspeed measurements are available, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes.", "max": 100.0, "min": 0.0, "name": "EKF2_GSF_TAS", "shortDesc": "Default value of true airspeed used in EKF-GSF AHRS calculation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "EKF2", "longDesc": "The ekf gyro bias states will be limited to within a range equivalent to +- of this value.", "max": 0.4, "min": 0.0, "name": "EKF2_GYR_B_LIM", "shortDesc": "Gyro bias learning limit", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.001, "group": "EKF2", "max": 0.01, "min": 0.0, "name": "EKF2_GYR_B_NOISE", "shortDesc": "Process noise for IMU rate gyro bias prediction", "type": "Float", "units": "rad/s^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.015, "group": "EKF2", "max": 0.1, "min": 0.0001, "name": "EKF2_GYR_NOISE", "shortDesc": "Rate gyro noise for covariance prediction", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.6, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_HDG_GATE", "shortDesc": "Gate size for heading fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 1.0, "min": 0.01, "name": "EKF2_HEAD_NOISE", "shortDesc": "Measurement noise for magnetic heading fusion", "type": "Float", "units": "rad"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "When multiple height sources are enabled at the same time, the height estimate will always converge towards the reference height source selected by this parameter. The range sensor and vision options should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level. If GPS is set as reference but altitude fusion is disabled in EKF2_GPS_CTRL, the GPS altitude is still used to initiaize the bias of the other height sensors.", "name": "EKF2_HGT_REF", "rebootRequired": true, "shortDesc": "Determines the reference source of height data used by the EKF", "type": "Int32", "values": [{"description": "Barometric pressure", "value": 0}, {"description": "GPS", "value": 1}, {"description": "Range sensor", "value": 2}, {"description": "Vision", "value": 3}]}, {"bitmask": [{"description": "Gyro Bias", "index": 0}, {"description": "Accel Bias", "index": 1}, {"description": "Gravity vector fusion", "index": 2}], "category": "Standard", "default": 7, "group": "EKF2", "max": 7, "min": 0, "name": "EKF2_IMU_CTRL", "shortDesc": "IMU control", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_X", "shortDesc": "X position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_Y", "shortDesc": "Y position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_Z", "shortDesc": "Z position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "EKF2", "name": "EKF2_LOG_VERBOSE", "shortDesc": "Verbose logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "The heading is assumed to be observable when the body acceleration is greater than this parameter when a global position/velocity aiding source is active.", "max": 5.0, "min": 0.0, "name": "EKF2_MAG_ACCLIM", "shortDesc": "Horizontal acceleration threshold used for heading observability check", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.0001, "group": "EKF2", "max": 0.1, "min": 0.0, "name": "EKF2_MAG_B_NOISE", "shortDesc": "Process noise for body magnetic field prediction", "type": "Float", "units": "gauss/s"}, {"bitmask": [{"description": "Strength (EKF2_MAG_CHK_STR)", "index": 0}, {"description": "Inclination (EKF2_MAG_CHK_INC)", "index": 1}, {"description": "Wait for WMM", "index": 2}], "category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Bitmask to set which check is used to decide whether the magnetometer data is valid. If GNSS data is received, the magnetic field is compared to a World Magnetic Model (WMM), otherwise an average value is used. This check is useful to reject occasional hard iron disturbance. Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Magnetic field strength. Set tolerance using EKF2_MAG_CHK_STR 1 : Magnetic field inclination. Set tolerance using EKF2_MAG_CHK_INC 2 : Wait for GNSS to find the theoretical strength and inclination using the WMM", "max": 7, "min": 0, "name": "EKF2_MAG_CHECK", "shortDesc": "Magnetic field strength test selection", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "longDesc": "Maximum allowed deviation from the expected magnetic field inclination to pass the check.", "max": 90.0, "min": 0.0, "name": "EKF2_MAG_CHK_INC", "shortDesc": "Magnetic field inclination check tolerance", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "longDesc": "Maximum allowed deviation from the expected magnetic field strength to pass the check.", "max": 1.0, "min": 0.0, "name": "EKF2_MAG_CHK_STR", "shortDesc": "Magnetic field strength check tolerance", "type": "Float", "units": "gauss"}, {"category": "System", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "name": "EKF2_MAG_DECL", "shortDesc": "Magnetic declination", "type": "Float", "units": "deg", "volatile": true}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_MAG_DELAY", "rebootRequired": true, "shortDesc": "Magnetometer measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.001, "group": "EKF2", "max": 0.1, "min": 0.0, "name": "EKF2_MAG_E_NOISE", "shortDesc": "Process noise for earth magnetic field prediction", "type": "Float", "units": "gauss/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_MAG_GATE", "shortDesc": "Gate size for magnetometer XYZ component fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "EKF2", "max": 1.0, "min": 0.001, "name": "EKF2_MAG_NOISE", "shortDesc": "Measurement noise for magnetometer 3-axis fusion", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. The fusion of magnetometer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight. If set to 'Magnetic heading' magnetic heading fusion is used at all times. If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GNSS velocity measurements to align the yaw angle. If set to 'Init' the magnetometer is only used to initalize the heading.", "name": "EKF2_MAG_TYPE", "rebootRequired": true, "shortDesc": "Type of magnetometer fusion", "type": "Int32", "values": [{"description": "Automatic", "value": 0}, {"description": "Magnetic heading", "value": 1}, {"description": "None", "value": 5}, {"description": "Init", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the propeller axis of rotation is lost when passing through the rotor disc. This changes the momentum of the flow which creates a drag reaction force. When comparing un-ducted propellers of the same diameter, the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with propeller selection. Momentum drag is significantly higher for ducted rotors. To account for the drag produced by the body which scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y parameters. Set this parameter to zero to turn off the momentum drag model for both axis.", "max": 1.0, "min": 0.0, "name": "EKF2_MCOEF", "shortDesc": "Propeller momentum drag coefficient for multi-rotor wind estimation", "type": "Float", "units": "1/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.01, "group": "EKF2", "longDesc": "If the vehicle is on ground, is not moving as determined by the motion test and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is available at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground.", "min": 0.01, "name": "EKF2_MIN_RNG", "shortDesc": "Expected range finder reading when on ground", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Maximum number of IMUs to use for Multi-EKF. Set 0 to disable. Requires SENS_IMU_MODE 0.", "max": 4, "min": 0, "name": "EKF2_MULTI_IMU", "rebootRequired": true, "shortDesc": "Multi-EKF IMUs", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Maximum number of magnetometers to use for Multi-EKF. Set 0 to disable. Requires SENS_MAG_MODE 0.", "max": 4, "min": 0, "name": "EKF2_MULTI_MAG", "rebootRequired": true, "shortDesc": "Multi-EKF Magnetometers", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "EKF2", "max": 50.0, "min": 0.5, "name": "EKF2_NOAID_NOISE", "shortDesc": "Measurement noise for non-aiding position hold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 5000000, "group": "EKF2", "longDesc": "Maximum lapsed time from last fusion of measurements that constrain velocity drift before the EKF will report the horizontal nav solution as invalid", "max": 10000000, "min": 500000, "name": "EKF2_NOAID_TOUT", "shortDesc": "Maximum inertial dead-reckoning time", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Enable optical flow fusion.", "name": "EKF2_OF_CTRL", "shortDesc": "Optical flow aiding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "longDesc": "Assumes measurement is timestamped at trailing edge of integration period", "max": 300.0, "min": 0.0, "name": "EKF2_OF_DELAY", "rebootRequired": true, "shortDesc": "Optical flow measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_OF_GATE", "shortDesc": "Gate size for optical flow fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Auto: use gyro from optical flow message if available, internal gyro otherwise. Internal: always use internal gyro", "name": "EKF2_OF_GYR_SRC", "shortDesc": "Optical flow angular rate compensation source", "type": "Int32", "values": [{"description": "Auto", "value": 0}, {"description": "Internal", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "Measurement noise for the optical flow sensor when it's reported quality metric is at the minimum", "min": 0.05, "name": "EKF2_OF_N_MAX", "shortDesc": "Optical flow maximum noise", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "EKF2", "longDesc": "Measurement noise for the optical flow sensor when it's reported quality metric is at the maximum", "min": 0.05, "name": "EKF2_OF_N_MIN", "shortDesc": "Optical flow minimum noise", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_X", "shortDesc": "X position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_Y", "shortDesc": "Y position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_Z", "shortDesc": "Z position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Optical Flow data will only be used in air if the sensor reports a quality metric >= EKF2_OF_QMIN", "max": 255, "min": 0, "name": "EKF2_OF_QMIN", "shortDesc": "In air optical flow minimum quality", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Optical Flow data will only be used on the ground if the sensor reports a quality metric >= EKF2_OF_QMIN_GND", "max": 255, "min": 0, "name": "EKF2_OF_QMIN_GND", "shortDesc": "On ground optical flow minimum quality", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_XN", "shortDesc": "Static pressure position error coefficient for the negative X axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forward flight, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_XP", "shortDesc": "Static pressure position error coefficient for the positive X axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the negative Y (LH) body axis. If the baro height estimate rises during sideways flight to the left, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_YN", "shortDesc": "Pressure position error coefficient for the negative Y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the positive Y (RH) body axis. If the baro height estimate rises during sideways flight to the right, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_YP", "shortDesc": "Pressure position error coefficient for the positive Y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the Z body axis.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_Z", "shortDesc": "Static pressure position error coefficient for the Z axis", "type": "Float"}, {"category": "Standard", "default": 10000, "group": "EKF2", "longDesc": "EKF prediction period in microseconds. This should ideally be an integer multiple of the IMU time delta. Actual filter update will be an integer multiple of IMU update.", "max": 20000, "min": 1000, "name": "EKF2_PREDICT_US", "shortDesc": "EKF prediction period", "type": "Int32", "units": "us"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "max": 100.0, "min": 2.0, "name": "EKF2_REQ_EPH", "shortDesc": "Required EPH to use GPS", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 100.0, "min": 2.0, "name": "EKF2_REQ_EPV", "shortDesc": "Required EPV to use GPS", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "EKF2", "longDesc": "Minimum GPS fix type required for GPS usage.", "name": "EKF2_REQ_FIX", "shortDesc": "Required GPS fix", "type": "Int32", "values": [{"description": "No fix required", "value": 0}, {"description": "2D fix", "value": 2}, {"description": "3D fix", "value": 3}, {"description": "RTCM code differential", "value": 4}, {"description": "RTK float", "value": 5}, {"description": "RTK fixed", "value": 6}, {"description": "Extrapolated", "value": 8}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "EKF2", "longDesc": "Minimum continuous period without GPS failure required to mark a healthy GPS status. It can be reduced to speed up initialization, but it's recommended to keep this unchanged for a vehicle.", "min": 0.1, "name": "EKF2_REQ_GPS_H", "rebootRequired": true, "shortDesc": "Required GPS health time on startup", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "max": 1.0, "min": 0.1, "name": "EKF2_REQ_HDRIFT", "shortDesc": "Maximum horizontal drift speed to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 6, "group": "EKF2", "max": 12, "min": 4, "name": "EKF2_REQ_NSATS", "shortDesc": "Required satellite count to use GPS", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "EKF2", "max": 5.0, "min": 1.5, "name": "EKF2_REQ_PDOP", "shortDesc": "Maximum PDOP to use GPS", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "max": 5.0, "min": 0.5, "name": "EKF2_REQ_SACC", "shortDesc": "Required speed accuracy to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "max": 1.5, "min": 0.1, "name": "EKF2_REQ_VDRIFT", "shortDesc": "Maximum vertical drift speed to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 5.0, "group": "EKF2", "longDesc": "If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1).", "max": 10.0, "min": 1.0, "name": "EKF2_RNG_A_HMAX", "shortDesc": "Maximum height above ground allowed for conditional range aid mode", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1).", "max": 2.0, "min": 0.1, "name": "EKF2_RNG_A_VMAX", "shortDesc": "Maximum horizontal velocity allowed for conditional range aid mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "WARNING: Range finder measurements are less reliable and can experience unexpected errors. For these reasons, if accurate control of height relative to ground is required, it is recommended to use the MPC_ALT_MODE parameter instead, unless baro errors are severe enough to cause problems with landing and takeoff. If this parameter is enabled then the estimator will make use of the range finder measurements to estimate its height in addition to other height sources (if activated). Range sensor aiding can be enabled (i.e.: always use) or set in \"conditional\" mode. Conditional mode: This enables the range finder to be used during low speed (< EKF2_RNG_A_VMAX) and low altitude (< EKF2_RNG_A_HMAX) operation, eg takeoff and landing, where baro interference from rotor wash is excessive and can corrupt EKF state estimates. It is intended to be used where a vertical takeoff and landing is performed, and horizontal flight does not occur until above EKF2_RNG_A_HMAX.", "name": "EKF2_RNG_CTRL", "shortDesc": "Range sensor height aiding", "type": "Int32", "values": [{"description": "Disable range fusion", "value": 0}, {"description": "Enabled (conditional mode)", "value": 1}, {"description": "Enabled", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_RNG_DELAY", "rebootRequired": true, "shortDesc": "Range finder measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Limit for fog detection. If the range finder measures a distance greater than this value, the measurement is considered to not be blocked by fog or rain. If there's a jump from larger than RNG_FOG to smaller than EKF2_RNG_FOG, the measurement may gets rejected. 0 - disabled", "max": 20.0, "min": 0.0, "name": "EKF2_RNG_FOG", "shortDesc": "Maximum distance at which the range finder could detect fog (m)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_RNG_GATE", "shortDesc": "Gate size for range finder fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "To be used, the time derivative of the distance sensor measurements projected on the vertical axis needs to be statistically consistent with the estimated vertical velocity of the drone. Decrease this value to make the filter more robust against range finder faulty data (stuck, reflections, ...). Note: tune the range finder noise parameters (EKF2_RNG_NOISE and EKF2_RNG_SFE) before tuning this gate.", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_K_GATE", "shortDesc": "Gate size used for range finder kinematic consistency check", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "min": 0.01, "name": "EKF2_RNG_NOISE", "shortDesc": "Measurement noise for range finder fusion", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "max": 0.75, "min": -0.75, "name": "EKF2_RNG_PITCH", "shortDesc": "Range sensor pitch offset", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_X", "shortDesc": "X position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_Y", "shortDesc": "Y position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_Z", "shortDesc": "Z position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "Minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (s)", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_QLTY_T", "shortDesc": "Minumum range validity period", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0.05, "group": "EKF2", "longDesc": "Specifies the increase in range finder noise with range.", "max": 0.2, "min": 0.0, "name": "EKF2_RNG_SFE", "shortDesc": "Range finder range dependent noise scaler", "type": "Float", "units": "m/m"}, {"category": "Standard", "default": 0.2, "group": "EKF2", "longDesc": "EKF2 instances have to be better than the selected by at least this amount before their relative score can be reduced.", "name": "EKF2_SEL_ERR_RED", "shortDesc": "Selector error reduce threshold", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "EKF2 selector acceleration error threshold for comparing accelerometers. Acceleration vector differences larger than this will result in accumulated velocity error.", "name": "EKF2_SEL_IMU_ACC", "shortDesc": "Selector acceleration threshold", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 15.0, "group": "EKF2", "longDesc": "EKF2 selector maximum accumulated angular error threshold for comparing gyros. Accumulated angular error larger than this will result in the sensor being declared faulty.", "name": "EKF2_SEL_IMU_ANG", "shortDesc": "Selector angular threshold", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 7.0, "group": "EKF2", "longDesc": "EKF2 selector angular rate error threshold for comparing gyros. Angular rate vector differences larger than this will result in accumulated angular error.", "name": "EKF2_SEL_IMU_RAT", "shortDesc": "Selector angular rate threshold", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 2.0, "group": "EKF2", "longDesc": "EKF2 selector maximum accumulated velocity threshold for comparing accelerometers. Accumulated velocity error larger than this will result in the sensor being declared faulty.", "name": "EKF2_SEL_IMU_VEL", "shortDesc": "Selector angular threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Use for vehicles where the measured body Z magnetic field is subject to strong magnetic interference. For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter will only have an effect if the global position of the drone is known. For 3D mag fusion the magnetometer Z measurement will simply be ignored instead of fusing the synthetic value.", "name": "EKF2_SYNT_MAG_Z", "shortDesc": "Enable synthetic magnetometer Z component measurement", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_TAS_GATE", "shortDesc": "Gate size for TAS fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "EKF2", "longDesc": "Controls how tightly the output track the EKF states", "max": 1.0, "min": 0.1, "name": "EKF2_TAU_POS", "shortDesc": "Output predictor position time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "EKF2", "max": 1.0, "name": "EKF2_TAU_VEL", "shortDesc": "Time constant of the velocity output prediction and smoothing filter", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "min": 0.0, "name": "EKF2_TERR_GRAD", "shortDesc": "Magnitude of terrain gradient", "type": "Float", "units": "m/m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "min": 0.5, "name": "EKF2_TERR_NOISE", "shortDesc": "Terrain altitude process noise", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "max": 299792458.0, "name": "EKF2_VEL_LIM", "shortDesc": "Velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "EKF2", "longDesc": "When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second.", "max": 1.0, "min": 0.0, "name": "EKF2_WIND_NSD", "shortDesc": "Process noise spectral density for wind velocity prediction", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "default": 0, "group": "Events", "longDesc": "Enable/disable event task for RC Loss. When enabled, an alarm tune will be\nplayed via buzzer or ESCs, if supported. The alarm will sound after a disarm,\nif the vehicle was previously armed and only if the vehicle had RC signal at\nsome point. Particularly useful for locating crashed drones without a GPS\nsensor.", "name": "EV_TSK_RC_LOSS", "rebootRequired": true, "shortDesc": "RC Loss Alarm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Events", "longDesc": "Enable/disable event task for displaying the vehicle status using arm-mounted\nLEDs. When enabled and if the vehicle supports it, LEDs will flash\nindicating various vehicle status changes. Currently PX4 has not implemented\nany specific status events.\n-", "name": "EV_TSK_STAT_DIS", "rebootRequired": true, "shortDesc": "Status Display", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "Applies to both directions in all manual modes with attitude stabilization but without altitude control", "max": 90.0, "min": 0.0, "name": "FW_MAN_P_MAX", "shortDesc": "Maximum manual pitch angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 45.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "Applies to both directions in all manual modes with attitude stabilization", "max": 90.0, "min": 0.0, "name": "FW_MAN_R_MAX", "shortDesc": "Maximum manual roll angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "This is the maximally added yaw rate setpoint from the yaw stick in any attitude controlled flight mode.\nIt is added to the yaw rate setpoint generated by the controller for turn coordination.", "min": 0.0, "name": "FW_MAN_YR_MAX", "shortDesc": "Maximum manually added yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "An airframe specific offset of the pitch setpoint in degrees, the value is\nadded to the pitch setpoint and should correspond to the pitch at\ntypical cruise speed of the airframe.", "max": 90.0, "min": -90.0, "name": "FW_PSP_OFF", "shortDesc": "Pitch setpoint offset (pitch at level flight)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 60.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_P_RMAX_NEG", "shortDesc": "Maximum negative / down pitch rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 60.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_P_RMAX_POS", "shortDesc": "Maximum positive / up pitch rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "longDesc": "This defines the latency between a pitch step input and the achieved setpoint\n(inverse to a P gain). Smaller systems may require smaller values.", "max": 1.0, "min": 0.2, "name": "FW_P_TC", "shortDesc": "Attitude pitch time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 70.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_R_RMAX", "shortDesc": "Maximum roll rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "longDesc": "This defines the latency between a roll step input and the achieved setpoint\n(inverse to a P gain). Smaller systems may require smaller values.", "max": 1.0, "min": 0.2, "name": "FW_R_TC", "shortDesc": "Attitude Roll Time Constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Attitude Control", "increment": 0.05, "max": 10.0, "min": 0.0, "name": "FW_WR_FF", "shortDesc": "Wheel steering rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "FW Attitude Control", "increment": 0.005, "longDesc": "This gain defines how much control response will result out of a steady\nstate error. It trims any constant error.", "max": 10.0, "min": 0.0, "name": "FW_WR_I", "shortDesc": "Wheel steering rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_WR_IMAX", "shortDesc": "Wheel steering rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "FW Attitude Control", "increment": 0.005, "longDesc": "This defines how much the wheel steering input will be commanded depending on the\ncurrent body angular rate error.", "max": 10.0, "min": 0.0, "name": "FW_WR_P", "shortDesc": "Wheel steering rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "FW Attitude Control", "longDesc": "Only enabled during automatic runway takeoff and landing.\nIn all manual modes the wheel is directly controlled with yaw stick.", "name": "FW_W_EN", "shortDesc": "Enable wheel steering controller", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "This limits the maximum wheel steering rate the controller will output (in degrees per\nsecond).", "max": 90.0, "min": 0.0, "name": "FW_W_RMAX", "shortDesc": "Maximum wheel steering rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 50.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_Y_RMAX", "shortDesc": "Maximum yaw rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Auto Landing", "increment": 0.01, "longDesc": "Sets a fraction of full flaps during landing.\nAlso applies to flaperons if enabled in the mixer/allocation.", "max": 1.0, "min": 0.0, "name": "FW_FLAPS_LND_SCL", "shortDesc": "Flaps setting during landing", "type": "Float", "units": "norm"}, {"bitmask": [{"description": "Abort if terrain is not found (only applies to mission landings)", "index": 0}, {"description": "Abort if terrain times out (after a first successful measurement)", "index": 1}], "category": "Standard", "default": 3, "group": "FW Auto Landing", "longDesc": "Terrain estimation:\nbit 0: Abort if terrain is not found\nbit 1: Abort if terrain times out (after a first successful measurement)\nThe last estimate is always used as ground, whether the last valid measurement or the land waypoint, depending on the\nselected abort criteria, until an abort condition is entered. If FW_LND_USETER == 0, these bits are ignored.\nTODO: Extend automatic abort conditions\ne.g. glide slope tracking error (horizontal and vertical)", "max": 3, "min": 0, "name": "FW_LND_ABORT", "shortDesc": "Bit mask to set the automatic landing abort conditions", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "The calibrated airspeed setpoint during landing.\nIf set <= 0, landing airspeed = FW_AIRSPD_MIN by default.", "min": -1.0, "name": "FW_LND_AIRSPD", "shortDesc": "Landing airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Typically the desired landing slope angle when landing configuration (flaps, airspeed) is enabled.\nSet this value within the vehicle's performance limits.", "max": 45.0, "min": 1.0, "name": "FW_LND_ANG", "shortDesc": "Maximum landing slope angle", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "FW Auto Landing", "longDesc": "Allows to deploy the landing configuration (flaps, landing airspeed, etc.) already in\nthe loiter-down waypoint before the final approach.\nOtherwise is enabled only in the final approach.", "name": "FW_LND_EARLYCFG", "shortDesc": "Early landing configuration deployment", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * |z-velocity|) is taken as the flare altitude", "min": 0.0, "name": "FW_LND_FLALT", "shortDesc": "Landing flare altitude (relative to landing altitude)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Maximum pitch during landing flare.", "max": 45.0, "min": 0.0, "name": "FW_LND_FL_PMAX", "shortDesc": "Flare, maximum pitch", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Minimum pitch during landing flare.", "max": 15.0, "min": -5.0, "name": "FW_LND_FL_PMIN", "shortDesc": "Flare, minimum pitch", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "TECS will attempt to control the aircraft to this sink rate via pitch angle (throttle killed during flare)", "max": 2.0, "min": 0.0, "name": "FW_LND_FL_SINK", "shortDesc": "Landing flare sink rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "Multiplied by the descent rate to calculate a dynamic altitude at which\nto trigger the flare.\nNOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * descent rate) is taken as the flare altitude", "max": 5.0, "min": 0.1, "name": "FW_LND_FL_TIME", "shortDesc": "Landing flare time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 2, "group": "FW Auto Landing", "longDesc": "Approach angle nudging: shifts the touchdown point laterally while keeping the approach entrance point constant\nApproach path nudging: shifts the touchdown point laterally along with the entire approach path\nThis is useful for manually adjusting the landing point in real time when map or GNSS errors cause an offset from the\ndesired landing vector. Nudging is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is\nrelative to the vehicle heading (stick deflection to the right = land point moves to the right as seen by the vehicle).", "max": 2, "min": 0, "name": "FW_LND_NUDGE", "shortDesc": "Landing touchdown nudging option", "type": "Int32", "values": [{"description": "Disable nudging", "value": 0}, {"description": "Nudge approach angle", "value": 1}, {"description": "Nudge approach path", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "FW Auto Landing", "increment": 1.0, "max": 10.0, "min": 0.0, "name": "FW_LND_TD_OFF", "shortDesc": "Maximum lateral position offset for the touchdown point", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "This is the time after the start of flaring that we expect the vehicle to touch the runway.\nAt this time, a 0.5s clamp down ramp will engage, constraining the pitch setpoint to RWTO_PSP.\nIf enabled, ensure that RWTO_PSP is configured appropriately for full gear contact on ground roll.\nSet to -1.0 to disable touchdown clamping. E.g. it may not be desirable to clamp on belly landings.\nThe touchdown time will be constrained to be greater than or equal to the flare time (FW_LND_FL_TIME).", "max": 5.0, "min": -1.0, "name": "FW_LND_TD_TIME", "shortDesc": "Landing touchdown time (since flare start)", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "The TECS altitude time constant (FW_T_ALT_TC) is multiplied by this value.", "max": 1.0, "min": 0.2, "name": "FW_LND_THRTC_SC", "shortDesc": "Altitude time constant factor for landing and low-height flight", "type": "Float", "units": ""}, {"category": "Standard", "default": 1, "group": "FW Auto Landing", "longDesc": "This is critical for detecting when to flare, and should be enabled if possible.\nIf enabled and no measurement is found within a given timeout, the landing waypoint altitude will be used OR the landing\nwill be aborted, depending on the criteria set in FW_LND_ABORT.\nIf disabled, FW_LND_ABORT terrain based criteria are ignored.", "max": 2, "min": 0, "name": "FW_LND_USETER", "shortDesc": "Use terrain estimation during landing", "type": "Int32", "values": [{"description": "Disable the terrain estimate", "value": 0}, {"description": "Use the terrain estimate to trigger the flare (only)", "value": 1}, {"description": "Calculate landing glide slope relative to the terrain estimate", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Auto Landing", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "FW_SPOILERS_LND", "shortDesc": "Spoiler landing setting", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Auto Takeoff", "increment": 0.01, "longDesc": "Sets a fraction of full flaps during take-off.\nAlso applies to flaperons if enabled in the mixer/allocation.", "max": 1.0, "min": 0.0, "name": "FW_FLAPS_TO_SCL", "shortDesc": "Flaps setting during take-off", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "FW Auto Takeoff", "increment": 0.05, "longDesc": "Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds.", "max": 5.0, "min": 0.0, "name": "FW_LAUN_AC_T", "shortDesc": "Trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Auto Takeoff", "increment": 0.5, "longDesc": "Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds.", "min": 0.0, "name": "FW_LAUN_AC_THLD", "shortDesc": "Trigger acceleration threshold", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 0, "group": "FW Auto Takeoff", "longDesc": "Enables automatic launch detection based on measured acceleration. Use for hand- or catapult-launched vehicles.\nNot compatible with runway takeoff.", "name": "FW_LAUN_DETCN_ON", "shortDesc": "Fixed-wing launch detection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Auto Takeoff", "increment": 0.5, "longDesc": "Start the motor(s) this amount of seconds after launch is detected.", "max": 10.0, "min": 0.0, "name": "FW_LAUN_MOT_DEL", "shortDesc": "Motor delay", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Takeoff", "increment": 0.1, "longDesc": "The calibrated airspeed setpoint during the takeoff climbout.\nIf set <= 0, FW_AIRSPD_MIN will be set by default.", "min": -1.0, "name": "FW_TKO_AIRSPD", "shortDesc": "Takeoff Airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW Auto Takeoff", "increment": 0.5, "max": 80.0, "min": -5.0, "name": "FW_TKO_PITCH_MIN", "shortDesc": "Minimum pitch during takeoff", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 30, "group": "FW General", "longDesc": "The time the system should do open loop loiter and wait for GPS recovery\nbefore it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R.\nDoes only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0.", "min": 0, "name": "FW_GPSF_LT", "shortDesc": "GPS failure loiter time", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW General", "increment": 0.5, "longDesc": "Roll angle in GPS failure loiter mode.", "max": 60.0, "min": 0.0, "name": "FW_GPSF_R", "shortDesc": "GPS failure fixed roll angle", "type": "Float", "units": "deg"}, {"bitmask": [{"description": "Alternative stick configuration (height rate on throttle stick, airspeed on pitch stick)", "index": 0}, {"description": "Enable airspeed setpoint via sticks in altitude and position flight mode", "index": 1}], "category": "Standard", "default": 2, "group": "FW General", "longDesc": "Applies in manual Position and Altitude flight modes.", "max": 3, "min": 0, "name": "FW_POS_STK_CONF", "shortDesc": "Custom stick configuration", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW General", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 80.0, "min": 0.0, "name": "FW_P_LIM_MAX", "shortDesc": "Maximum pitch angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -30.0, "group": "FW General", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 0.0, "min": -60.0, "name": "FW_P_LIM_MIN", "shortDesc": "Minimum pitch angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 50.0, "group": "FW General", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 75.0, "min": 35.0, "name": "FW_R_LIM", "shortDesc": "Maximum roll angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW General", "increment": 0.01, "longDesc": "This is the minimum throttle while on the ground (\"landed\") in auto modes.", "max": 1.0, "min": 0.0, "name": "FW_THR_IDLE", "shortDesc": "Idle throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW General", "increment": 0.01, "longDesc": "Applies in any altitude controlled flight mode.\nShould be set accordingly to achieve FW_T_CLMB_MAX.", "max": 1.0, "min": 0.0, "name": "FW_THR_MAX", "shortDesc": "Throttle limit max", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW General", "increment": 0.01, "longDesc": "Applies in any altitude controlled flight mode.\nUsually set to 0 but can be increased to prevent the motor from stopping when\ndescending, which can increase achievable descent rates.", "max": 1.0, "min": 0.0, "name": "FW_THR_MIN", "shortDesc": "Throttle limit min", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "FW General", "increment": 0.01, "longDesc": "In auto modes: default climb rate output by controller to achieve altitude setpoints.\nIn manual modes: maximum climb rate setpoint.", "min": 0.1, "name": "FW_T_CLMB_R_SP", "shortDesc": "Default target climbrate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "FW General", "increment": 0.01, "longDesc": "In auto modes: default sink rate output by controller to achieve altitude setpoints.\nIn manual modes: maximum sink rate setpoint.", "min": 0.1, "name": "FW_T_SINK_R_SP", "shortDesc": "Default target sinkrate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW General", "increment": 1.0, "longDesc": "Adjusts the amount of weighting that the pitch control\napplies to speed vs height errors.\n0 -> control height only\n2 -> control speed only (gliders)", "max": 2.0, "min": 0.0, "name": "FW_T_SPDWEIGHT", "shortDesc": "Speed <--> Altitude weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "FW General", "increment": 1.0, "longDesc": "This is used to constrain a minimum altitude below which we keep wings level to avoid wing tip strike. It's safer\nto give a slight margin here (> 0m)", "min": 0.0, "name": "FW_WING_HEIGHT", "shortDesc": "Height (AGL) of the wings when the aircraft is on the ground", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "FW General", "increment": 0.1, "longDesc": "This is used for limiting the roll setpoint near the ground. (if multiple wings, take the longest span)", "min": 0.1, "name": "FW_WING_SPAN", "shortDesc": "The aircraft's wing span (length from tip to tip)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "FW Lateral Control", "increment": 1.0, "longDesc": "Maximum change in roll angle setpoint per second.\nApplied in all Auto modes, plus manual Position & Altitude modes.", "min": 0.0, "name": "FW_PN_R_SLEW_MAX", "shortDesc": "Path navigation roll slew rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "longDesc": "The controller will increase the commanded airspeed to maintain\nthis minimum groundspeed to the next waypoint.", "max": 40.0, "min": 0.0, "name": "FW_GND_SPD_MIN", "shortDesc": "Minimum groundspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "Maximum slew rate for the commanded throttle", "max": 1.0, "min": 0.0, "name": "FW_THR_SLEW_MAX", "shortDesc": "Throttle max slew rate", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "min": 2.0, "name": "FW_T_ALT_TC", "shortDesc": "Altitude error time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW Longitudinal Control", "longDesc": "Minimum altitude error needed to descend with max airspeed and minimal throttle.\nA negative value disables fast descend.", "min": -1.0, "name": "FW_T_F_ALT_ERR", "shortDesc": "Fast descend: minimum altitude error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW Longitudinal Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_T_HRATE_FF", "shortDesc": "Height rate feed forward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW Longitudinal Control", "increment": 0.05, "longDesc": "Increase it to trim out speed and height offsets faster,\nwith the downside of possible overshoots and oscillations.", "max": 2.0, "min": 0.0, "name": "FW_T_I_GAIN_PIT", "shortDesc": "Integrator gain pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW Longitudinal Control", "increment": 0.1, "max": 2.0, "min": 0.0, "name": "FW_T_PTCH_DAMP", "shortDesc": "Pitch damping gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Longitudinal Control", "increment": 0.5, "longDesc": "Is used to compensate for the additional drag created by turning.\nIncrease this gain if the aircraft initially loses energy in turns\nand reduce if the aircraft initially gains energy in turns.", "max": 20.0, "min": 0.0, "name": "FW_T_RLL2THR", "shortDesc": "Roll -> Throttle feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Longitudinal Control", "increment": 0.01, "max": 3.0, "min": 0.5, "name": "FW_T_SEB_R_FF", "shortDesc": "Specific total energy balance rate feedforward gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "max": 15.0, "min": 1.0, "name": "FW_T_SINK_MAX", "shortDesc": "Maximum descent rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Longitudinal Control", "increment": 0.1, "longDesc": "For the airspeed filter in TECS.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_DEV_STD", "shortDesc": "Airspeed rate measurement standard deviation", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Longitudinal Control", "increment": 0.1, "longDesc": "This is defining the noise in the airspeed rate for the constant airspeed rate model\nof the TECS airspeed filter.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_PRC_STD", "shortDesc": "Process noise standard deviation for the airspeed rate", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.07, "group": "FW Longitudinal Control", "increment": 0.1, "longDesc": "For the airspeed filter in TECS.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_STD", "shortDesc": "Airspeed measurement standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "This filter is applied to the specific total energy rate used for throttle damping.", "max": 2.0, "min": 0.0, "name": "FW_T_STE_R_TC", "shortDesc": "Specific total energy rate first order filter time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "min": 2.0, "name": "FW_T_TAS_TC", "shortDesc": "True airspeed error time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "This is the damping gain for the throttle demand loop.", "max": 1.0, "min": 0.0, "name": "FW_T_THR_DAMPING", "shortDesc": "Throttle damping factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.02, "group": "FW Longitudinal Control", "increment": 0.005, "longDesc": "Increase it to trim out speed and height offsets faster,\nwith the downside of possible overshoots and oscillations.", "max": 1.0, "min": 0.0, "name": "FW_T_THR_INTEG", "shortDesc": "Integrator gain throttle", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW Longitudinal Control", "increment": 1.0, "longDesc": "Height above ground threshold below which tighter altitude\ntracking gets enabled (see FW_LND_THRTC_SC). Below this height, TECS smoothly\n(1 sec / sec) transitions the altitude tracking time constant from FW_T_ALT_TC\nto FW_LND_THRTC_SC*FW_T_ALT_TC.\n-1 to disable.", "min": -1.0, "name": "FW_T_THR_LOW_HGT", "shortDesc": "Low-height threshold for tighter altitude tracking", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 7.0, "group": "FW Longitudinal Control", "increment": 0.5, "longDesc": "This is the maximum vertical acceleration\neither up or down that the controller will use to correct speed\nor height errors.", "max": 10.0, "min": 1.0, "name": "FW_T_VERT_ACC", "shortDesc": "Maximum vertical acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "Multiplying this factor with the current absolute wind estimate gives the airspeed offset\nadded to the minimum airspeed setpoint limit. This helps to make the\nsystem more robust against disturbances (turbulence) in high wind.", "min": 0.0, "name": "FW_WIND_ARSP_SC", "shortDesc": "Wind-based airspeed scaling factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "FW NPFG Control", "increment": 0.01, "longDesc": "Damping ratio of NPFG control law.", "max": 1.0, "min": 0.1, "name": "NPFG_DAMPING", "shortDesc": "NPFG damping ratio", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Avoids limit cycling from a too aggressively tuned period/damping combination.\nIf false, also disables upper bound NPFG_PERIOD_UB.", "name": "NPFG_LB_PERIOD", "shortDesc": "Enable automatic lower bound on the NPFG period", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW NPFG Control", "increment": 0.1, "longDesc": "Period of NPFG control law.", "max": 100.0, "min": 1.0, "name": "NPFG_PERIOD", "shortDesc": "NPFG period", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "FW NPFG Control", "increment": 0.1, "longDesc": "Multiplied by period for conservative minimum period bounding (when period lower\nbounding is enabled). 1.0 bounds at marginal stability.", "max": 10.0, "min": 1.0, "name": "NPFG_PERIOD_SF", "shortDesc": "Period safety factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW NPFG Control", "increment": 0.05, "longDesc": "Time constant of roll controller command / response, modeled as first order delay.\nUsed to determine lower period bound. Setting zero disables automatic period bounding.", "max": 2.0, "min": 0.0, "name": "NPFG_ROLL_TC", "shortDesc": "Roll time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.32, "group": "FW NPFG Control", "increment": 0.01, "longDesc": "Multiplied by the track error boundary to determine when the aircraft switches\nto the next waypoint and/or path segment. Should be less than 1.", "max": 1.0, "min": 0.1, "name": "NPFG_SW_DST_MLT", "shortDesc": "NPFG switch distance multiplier", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Adapts period to maintain track keeping in variable winds and path curvature.", "name": "NPFG_UB_PERIOD", "shortDesc": "Enable automatic upper bound on the NPFG period", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Factor applied to the minimum and stall airspeed when flaps are fully deployed.", "max": 1.0, "min": 0.5, "name": "FW_AIRSPD_FLP_SC", "shortDesc": "Airspeed scale with full flaps", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The maximal airspeed (calibrated airspeed) the user is able to command.", "min": 0.5, "name": "FW_AIRSPD_MAX", "shortDesc": "Maximum Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The minimal airspeed (calibrated airspeed) the user is able to command.\nFurther, if the airspeed falls below this value, the TECS controller will try to\nincrease airspeed more aggressively.\nHas to be set according to the vehicle's stall speed (which should be set in FW_AIRSPD_STALL),\nwith some margin between the stall speed and minimum airspeed.\nThis value corresponds to the desired minimum speed with the default load factor (level flight, default weight),\nand is automatically adpated to the current load factor (calculated from roll setpoint and WEIGHT_GROSS/WEIGHT_BASE).", "min": 0.5, "name": "FW_AIRSPD_MIN", "shortDesc": "Minimum Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 7.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The stall airspeed (calibrated airspeed) of the vehicle.\nIt is used for airspeed sensor failure detection and for the control\nsurface scaling airspeed limits.", "min": 0.5, "name": "FW_AIRSPD_STALL", "shortDesc": "Stall Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The trim CAS (calibrated airspeed) of the vehicle. If an airspeed controller is active,\nthis is the default airspeed setpoint that the controller will try to achieve.\nThis value corresponds to the trim airspeed with the default load factor (level flight, default weight).", "min": 0.5, "name": "FW_AIRSPD_TRIM", "shortDesc": "Trim (Cruise) Airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW Performance", "increment": 1.0, "longDesc": "Altitude in standard atmosphere at which the vehicle in normal configuration (WEIGHT_BASE) is still able to achieve a maximum climb rate of\n0.5m/s at maximum throttle (FW_THR_MAX). Used to compensate for air density in FW_T_CLMB_MAX.\nSet negative to disable.", "min": -1.0, "name": "FW_SERVICE_CEIL", "shortDesc": "Service ceiling", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at maximum airspeed FW_AIRSPD_MAX\nSet to 0 to disable mapping of airspeed to trim throttle.", "max": 1.0, "min": 0.0, "name": "FW_THR_ASPD_MAX", "shortDesc": "Throttle at max airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at minimum airspeed FW_AIRSPD_MIN\nSet to 0 to disable mapping of airspeed to trim throttle below FW_AIRSPD_TRIM.", "max": 1.0, "min": 0.0, "name": "FW_THR_ASPD_MIN", "shortDesc": "Throttle at min airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at FW_AIRSPD_TRIM", "max": 1.0, "min": 0.0, "name": "FW_THR_TRIM", "shortDesc": "Trim throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the maximum calibrated climb rate that the aircraft can achieve with\nthe throttle set to FW_THR_MAX and the airspeed set to the\ntrim value. For electric aircraft make sure this number can be\nachieved towards the end of flight when the battery voltage has reduced.", "min": 1.0, "name": "FW_T_CLMB_MAX", "shortDesc": "Maximum climb rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the minimum calibrated sink rate of the aircraft with the throttle\nset to THR_MIN and flown at the same airspeed as used\nto measure FW_T_CLMB_MAX.", "min": 1.0, "name": "FW_T_SINK_MIN", "shortDesc": "Minimum descent rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the weight of the vehicle at which it's performance limits were derived. A zero or negative value\ndisables trim throttle and minimum airspeed compensation based on weight.", "name": "WEIGHT_BASE", "shortDesc": "Vehicle base weight", "type": "Float", "units": "kg"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Performance", "increment": 0.1, "longDesc": "This is the actual weight of the vehicle at any time. This value will differ from WEIGHT_BASE in case weight was added\nor removed from the base weight. Examples are the addition of payloads or larger batteries. A zero or negative value\ndisables trim throttle and minimum airspeed compensation based on weight.", "name": "WEIGHT_GROSS", "shortDesc": "Vehicle gross weight", "type": "Float", "units": "kg"}, {"category": "Standard", "default": 90.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_X_MAX", "shortDesc": "Acro body roll max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "If this parameter is set to 1, the yaw rate controller is enabled in Fixed-wing Acro mode.\nOtherwise the pilot commands directly the yaw actuator.\nIt is disabled by default because an active yaw rate controller will fight against the\nnatural turn coordination of the plane.", "name": "FW_ACRO_YAW_EN", "shortDesc": "Enable yaw rate controller in Acro", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 90.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_Y_MAX", "shortDesc": "Acro body pitch max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 45.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_Z_MAX", "shortDesc": "Acro body yaw max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "longDesc": "This enables a logic that automatically adjusts the output of the rate controller to take\ninto account the real torque produced by an aerodynamic control surface given\nthe current deviation from the trim airspeed (FW_AIRSPD_TRIM).\nEnable when using aerodynamic control surfaces (e.g.: plane)\nDisable when using rotor wings (e.g.: autogyro)", "name": "FW_ARSP_SCALE_EN", "shortDesc": "Enable airspeed scaling", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "This compensates for voltage drop of the battery over time by attempting to\nnormalize performance across the operating range of the battery.", "name": "FW_BAT_SCALE_EN", "shortDesc": "Enable throttle scale by battery level", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_P_VMAX", "shortDesc": "Pitch trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_P_VMIN", "shortDesc": "Pitch trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_R_VMAX", "shortDesc": "Roll trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_R_VMIN", "shortDesc": "Roll trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_Y_VMAX", "shortDesc": "Yaw trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_Y_VMIN", "shortDesc": "Yaw trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "name": "FW_GC_EN", "shortDesc": "Enable rate gain compression", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW Rate Control", "increment": 0.01, "longDesc": "The range of the compression gain is between this parameter and 1.0", "max": 1.0, "min": 0.0, "name": "FW_GC_GAIN_MIN", "shortDesc": "Compression gain lower limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired pitch actuator command in full manual mode. This parameter allows\nto adjust the throws of the control surfaces.", "min": 0.0, "name": "FW_MAN_P_SC", "shortDesc": "Manual pitch scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired roll actuator command in full manual mode. This parameter allows\nto adjust the throws of the control surfaces.", "max": 1.0, "min": 0.0, "name": "FW_MAN_R_SC", "shortDesc": "Manual roll scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows\nto adjust the throws of the control surfaces.", "min": 0.0, "name": "FW_MAN_Y_SC", "shortDesc": "Manual yaw scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "longDesc": "Pitch rate differential gain.", "max": 10.0, "min": 0.0, "name": "FW_PR_D", "shortDesc": "Pitch rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output", "max": 10.0, "min": 0.0, "name": "FW_PR_FF", "shortDesc": "Pitch rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_PR_I", "shortDesc": "Pitch rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_PR_IMAX", "shortDesc": "Pitch rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.08, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_PR_P", "shortDesc": "Pitch rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This gain can be used to counteract the \"adverse yaw\" effect for fixed wings.\nWhen the plane enters a roll it will tend to yaw the nose out of the turn.\nThis gain enables the use of a yaw actuator to counteract this effect.", "min": 0.0, "name": "FW_RLL_TO_YAW_FF", "shortDesc": "Roll control to yaw control feedforward gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_RR_D", "shortDesc": "Roll rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output.", "max": 10.0, "min": 0.0, "name": "FW_RR_FF", "shortDesc": "Roll rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW Rate Control", "increment": 0.01, "max": 10.0, "min": 0.0, "name": "FW_RR_I", "shortDesc": "Roll rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_RR_IMAX", "shortDesc": "Roll integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_RR_P", "shortDesc": "Roll rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "Chose source for manual setting of spoilers in manual flight modes.", "name": "FW_SPOILERS_MAN", "shortDesc": "Spoiler input in manual flight", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Flaps channel", "value": 1}, {"description": "Aux1", "value": 2}]}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "longDesc": "If set to 1, the airspeed measurement data, if valid, is used in the following controllers:\n- Rate controller: output scaling\n- Attitude controller: coordinated turn controller\n- Position controller: airspeed setpoint tracking, takeoff logic\n- VTOL: transition logic", "name": "FW_USE_AIRSPD", "shortDesc": "Use airspeed for control", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_YR_D", "shortDesc": "Yaw rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output", "max": 10.0, "min": 0.0, "name": "FW_YR_FF", "shortDesc": "Yaw rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.1, "group": "FW Rate Control", "increment": 0.5, "max": 10.0, "min": 0.0, "name": "FW_YR_I", "shortDesc": "Yaw rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_YR_IMAX", "shortDesc": "Yaw rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_YR_P", "shortDesc": "Yaw rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "Failure Detector", "longDesc": "If enabled, failure detector will verify that for motors, a minimum amount of ESC current per throttle\nlevel is being consumed.\nOtherwise this indicates an motor failure.", "name": "FD_ACT_EN", "rebootRequired": true, "shortDesc": "Enable Actuator Failure check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Failure Detector", "increment": 1.0, "longDesc": "threshold = FD_ACT_MOT_C2T * thrust + FD_ACT_HIGH_OFF", "max": 30.0, "min": 0.0, "name": "FD_ACT_HIGH_OFF", "shortDesc": "Overcurrent motor failure limit offset", "type": "Float", "units": "A"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Failure Detector", "increment": 1.0, "longDesc": "threshold = FD_ACT_MOT_C2T * thrust - FD_ACT_LOW_OFF", "max": 30.0, "min": 0.0, "name": "FD_ACT_LOW_OFF", "shortDesc": "Undercurrent motor failure limit offset", "type": "Float", "units": "A"}, {"category": "Standard", "decimalPlaces": 2, "default": 35.0, "group": "Failure Detector", "increment": 1.0, "longDesc": "Determines the slope between expected steady state current and linearized, normalized thrust command.\nE.g. FD_ACT_MOT_C2T A represents the expected steady state current at 100%.\nFD_ACT_LOW_OFF and FD_ACT_HIGH_OFF offset the threshold from that slope.", "max": 50.0, "min": 0.0, "name": "FD_ACT_MOT_C2T", "shortDesc": "Motor Failure Current/Throttle Scale", "type": "Float", "units": "A/%"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Failure Detector", "increment": 0.01, "longDesc": "Failure detection per motor only triggers above this thrust value.\nSet to 1 to disable the detection.", "max": 1.0, "min": 0.0, "name": "FD_ACT_MOT_THR", "shortDesc": "Motor Failure Thrust Threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 1000, "group": "Failure Detector", "increment": 100, "longDesc": "Motor failure only triggers after current thresholds are exceeded for this time.", "max": 10000, "min": 10, "name": "FD_ACT_MOT_TOUT", "shortDesc": "Motor Failure Hysteresis Time", "type": "Int32", "units": "ms"}, {"category": "Standard", "default": 1, "group": "Failure Detector", "longDesc": "If enabled, failure detector will verify that all the ESCs have successfully armed when the vehicle has transitioned to the armed state.\nTimeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback is received the failure detector will auto disarm the vehicle.", "name": "FD_ESCS_EN", "shortDesc": "Enable checks on ESCs that report their arming state", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Failure Detector", "longDesc": "Enabled on either AUX5 or MAIN5 depending on board.\nExternal ATS is required by ASTM F3322-18.", "name": "FD_EXT_ATS_EN", "rebootRequired": true, "shortDesc": "Enable PWM input on for engaging failsafe from an external automatic trigger system (ATS)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1900, "group": "Failure Detector", "longDesc": "External ATS is required by ASTM F3322-18.", "name": "FD_EXT_ATS_TRIG", "shortDesc": "The PWM threshold from external automatic trigger system for engaging failsafe", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 60, "group": "Failure Detector", "longDesc": "Maximum pitch angle before FailureDetector triggers the attitude_failure flag.\nThe flag triggers flight termination (if @CBRK_FLIGHTTERM = 0),\nwhich sets outputs to their failsafe values.\nOn takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM),\nwhich disarms motors but does not set outputs to failsafe values.\nSetting this parameter to 0 disables the check", "max": 180, "min": 0, "name": "FD_FAIL_P", "shortDesc": "FailureDetector Max Pitch", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Failure Detector", "longDesc": "Seconds (decimal) that pitch has to exceed FD_FAIL_P before being considered as a failure.", "max": 5.0, "min": 0.02, "name": "FD_FAIL_P_TTRI", "shortDesc": "Pitch failure trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 60, "group": "Failure Detector", "longDesc": "Maximum roll angle before FailureDetector triggers the attitude_failure flag.\nThe flag triggers flight termination (if @CBRK_FLIGHTTERM = 0),\nwhich sets outputs to their failsafe values.\nOn takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM),\nwhich disarms motors but does not set outputs to failsafe values.\nSetting this parameter to 0 disables the check", "max": 180, "min": 0, "name": "FD_FAIL_R", "shortDesc": "FailureDetector Max Roll", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Failure Detector", "longDesc": "Seconds (decimal) that roll has to exceed FD_FAIL_R before being considered as a failure.", "max": 5.0, "min": 0.02, "name": "FD_FAIL_R_TTRI", "shortDesc": "Roll failure trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 30, "group": "Failure Detector", "increment": 1, "longDesc": "Value at which the imbalanced propeller metric (based on horizontal and\nvertical acceleration variance) triggers a failure\nSetting this value to 0 disables the feature.", "max": 1000, "min": 0, "name": "FD_IMB_PROP_THR", "shortDesc": "Imbalanced propeller check threshold", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 1000.0, "group": "Flight Task Orbit", "increment": 0.5, "max": 10000.0, "min": 1.0, "name": "MC_ORBIT_RAD_MAX", "shortDesc": "Maximum radius of orbit", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Flight Task Orbit", "name": "MC_ORBIT_YAW_MOD", "shortDesc": "Yaw behaviour during orbit flight", "type": "Int32", "values": [{"description": "Front to Circle Center", "value": 0}, {"description": "Hold Initial Heading", "value": 1}, {"description": "Uncontrolled", "value": 2}, {"description": "Hold Front Tangent to Circle", "value": 3}, {"description": "Manually (yaw stick) Controlled", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Follow target", "longDesc": "Maintain altitude or track target's altitude. When maintaining the altitude,\nthe drone can crash into terrain when the target moves uphill. When tracking\nthe target's altitude, the follow altitude FLW_TGT_HT should be high enough\nto prevent terrain collisions due to GPS inaccuracies of the target.", "name": "FLW_TGT_ALT_M", "shortDesc": "Altitude control mode", "type": "Int32", "values": [{"description": "2D Tracking: Maintain constant altitude relative to home and track XY position only", "value": 0}, {"description": "2D + Terrain: Maintain constant altitude relative to terrain below and track XY position", "value": 1}, {"description": "3D Tracking: Track target's altitude (be aware that GPS altitude bias usually makes this useless)", "value": 2}]}, {"category": "Standard", "default": 8.0, "group": "Follow target", "longDesc": "The distance in meters to follow the target at", "min": 1.0, "name": "FLW_TGT_DST", "shortDesc": "Distance to follow target from", "type": "Float", "units": "m"}, {"category": "Standard", "default": 180.0, "group": "Follow target", "longDesc": "Angle to follow the target from. 0.0 Equals straight in front of the target's\ncourse (direction of motion) and the angle increases in clockwise direction,\nmeaning Right-side would be 90.0 degrees while Left-side is -90.0 degrees\nNote: When the user force sets the angle out of the min/max range, it will be\nwrapped (e.g. 480 -> 120) in the range to gracefully handle the out of range.", "max": 180.0, "min": -180.0, "name": "FLW_TGT_FA", "shortDesc": "Follow Angle setting in degrees", "type": "Float"}, {"category": "Standard", "default": 8.0, "group": "Follow target", "longDesc": "Following height above the target", "min": 8.0, "name": "FLW_TGT_HT", "shortDesc": "Follow target height", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Follow target", "longDesc": "This is the maximum tangential velocity the drone will circle around the target whenever\nan orbit angle setpoint changes. Higher value means more aggressive follow behavior.", "max": 20.0, "min": 0.0, "name": "FLW_TGT_MAX_VEL", "shortDesc": "Maximum tangential velocity setting for generating the follow orbit trajectory", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Follow target", "longDesc": "lower values increase the responsiveness to changing position, but also ignore less noise", "max": 1.0, "min": 0.0, "name": "FLW_TGT_RS", "shortDesc": "Responsiveness to target movement in Target Estimator", "type": "Float"}, {"bitmask": [{"description": "GPS (with QZSS)", "index": 0}, {"description": "SBAS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "BeiDou", "index": 3}, {"description": "GLONASS", "index": 4}, {"description": "NAVIC", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "longDesc": "This integer bitmask controls the set of GNSS systems used by the receiver. Check your\nreceiver's documentation on how many systems are supported to be used in parallel.\nCurrently this functionality is just implemented for u-blox receivers.\nWhen no bits are set, the receiver's default configuration should be used.\nSet bits true to enable:\n0 : Use GPS (with QZSS)\n1 : Use SBAS (multiple GPS augmentation systems)\n2 : Use Galileo\n3 : Use BeiDou\n4 : Use GLONASS\n5 : Use NAVIC", "max": 63, "min": 0, "name": "GPS_1_GNSS", "rebootRequired": true, "shortDesc": "GNSS Systems for Primary GPS (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Select the GPS protocol over serial.\nAuto-detection will probe all protocols, and thus is a bit slower.", "max": 7, "min": 0, "name": "GPS_1_PROTOCOL", "rebootRequired": true, "shortDesc": "Protocol for Main GPS", "type": "Int32", "values": [{"description": "Auto detect", "value": 0}, {"description": "u-blox", "value": 1}, {"description": "MTK", "value": 2}, {"description": "Ashtech / Trimble", "value": 3}, {"description": "Emlid Reach", "value": 4}, {"description": "Femtomes", "value": 5}, {"description": "NMEA (generic)", "value": 6}]}, {"bitmask": [{"description": "GPS (with QZSS)", "index": 0}, {"description": "SBAS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "BeiDou", "index": 3}, {"description": "GLONASS", "index": 4}, {"description": "NAVIC", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "longDesc": "This integer bitmask controls the set of GNSS systems used by the receiver. Check your\nreceiver's documentation on how many systems are supported to be used in parallel.\nCurrently this functionality is just implemented for u-blox receivers.\nWhen no bits are set, the receiver's default configuration should be used.\nSet bits true to enable:\n0 : Use GPS (with QZSS)\n1 : Use SBAS (multiple GPS augmentation systems)\n2 : Use Galileo\n3 : Use BeiDou\n4 : Use GLONASS\n5 : Use NAVIC", "max": 63, "min": 0, "name": "GPS_2_GNSS", "rebootRequired": true, "shortDesc": "GNSS Systems for Secondary GPS (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Select the GPS protocol over serial.\nAuto-detection will probe all protocols, and thus is a bit slower.", "max": 6, "min": 0, "name": "GPS_2_PROTOCOL", "rebootRequired": true, "shortDesc": "Protocol for Secondary GPS", "type": "Int32", "values": [{"description": "Auto detect", "value": 0}, {"description": "u-blox", "value": 1}, {"description": "MTK", "value": 2}, {"description": "Ashtech / Trimble", "value": 3}, {"description": "Emlid Reach", "value": 4}, {"description": "Femtomes", "value": 5}, {"description": "NMEA (generic)", "value": 6}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Some UBX modules have a FLASH that allows to store persistent configuration that will be loaded on start.\nPX4 does override all configuration parameters it needs in RAM, which takes precedence over the values in FLASH.\nHowever, configuration parameters that are not overriden by PX4 can still cause unexpected problems during flight.\nTo avoid these kind of problems a clean config can be reached by wiping the FLASH on boot.\nNote: Currently only supported on UBX.", "name": "GPS_CFG_WIPE", "rebootRequired": true, "shortDesc": "Wipes the flash config of UBX modules", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "If this is set to 1, all GPS communication data will be published via uORB,\nand written to the log file as gps_dump message.\nIf this is set to 2, the main GPS is configured to output RTCM data,\nwhich is then logged as gps_dump and can be used for PPK.", "max": 2, "min": 0, "name": "GPS_DUMP_COMM", "shortDesc": "Log GPS communication data", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Full communication", "value": 1}, {"description": "RTCM output (PPK)", "value": 2}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Enable publication of satellite info (ORB_ID(satellite_info)) if possible.\nNot available on MTK.", "name": "GPS_SAT_INFO", "rebootRequired": true, "shortDesc": "Enable sat info (if available)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 230400, "group": "GPS", "longDesc": "Select a baudrate for the F9P's UART2 port.\nIn GPS_UBX_MODE 1, 2, and 3, the F9P's UART2 port is configured to send/receive RTCM corrections.\nSet this to 57600 if you want to attach a telemetry radio on UART2.", "min": 0, "name": "GPS_UBX_BAUD2", "rebootRequired": true, "shortDesc": "u-blox F9P UART2 Baudrate", "type": "Int32", "units": "B/s"}, {"bitmask": [{"description": "Enable I2C input protocol UBX", "index": 0}, {"description": "Enable I2C input protocol NMEA", "index": 1}, {"description": "Enable I2C input protocol RTCM3X", "index": 2}, {"description": "Enable I2C output protocol UBX", "index": 3}, {"description": "Enable I2C output protocol NMEA", "index": 4}, {"description": "Enable I2C output protocol RTCM3X", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "max": 32, "min": 0, "name": "GPS_UBX_CFG_INTF", "rebootRequired": true, "shortDesc": "u-blox protocol configuration for interfaces", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "When set to 0 (default), default DGNSS timeout set by u-blox will be used.", "max": 255, "min": 0, "name": "GPS_UBX_DGNSS_TO", "rebootRequired": true, "shortDesc": "u-blox GPS DGNSS timeout", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 7, "group": "GPS", "longDesc": "u-blox receivers support different dynamic platform models to adjust the navigation engine to\nthe expected application environment.", "max": 9, "min": 0, "name": "GPS_UBX_DYNMODEL", "rebootRequired": true, "shortDesc": "u-blox GPS dynamic platform model", "type": "Int32", "values": [{"description": "stationary", "value": 2}, {"description": "automotive", "value": 4}, {"description": "airborne with <1g acceleration", "value": 6}, {"description": "airborne with <2g acceleration", "value": 7}, {"description": "airborne with <4g acceleration", "value": 8}]}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Enables or disables the high sensitivity mode for the u-blox jamming detection\n(CFG-SEC-JAMDET_SENSITIVITY_HI). When enabled, the receiver uses a\nmore sensitive algorithm to detect jamming. Disabling this may reduce false\npositives in electrically noisy environments.", "name": "GPS_UBX_JAM_DET", "rebootRequired": true, "shortDesc": "u-blox GPS jamming detection high sensitivity mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "When set to 0 (default), default minimum satellite signal level set by u-blox wll be used.", "max": 255, "min": 0, "name": "GPS_UBX_MIN_CNO", "rebootRequired": true, "shortDesc": "u-blox GPS minimum satellite signal level for navigation", "type": "Int32", "units": "dBHz"}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "When set to 0 (default), default minimum elevation set by u-blox will be used.", "max": 127, "min": 0, "name": "GPS_UBX_MIN_ELEV", "rebootRequired": true, "shortDesc": "u-blox GPS minimum elevation for a GNSS satellite to be used in navigation", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Select the u-blox configuration setup. Most setups will use the default, including RTK and\ndual GPS without heading.\nIf rover has RTCM corrections from a static base (or other static correction source) coming in on UART2, then select Mode 5.\nThe Heading mode requires 2 F9P devices to be attached. The main GPS will act as rover and output\nheading information, whereas the secondary will act as moving base.\nModes 1 and 2 require each F9P UART1 to be connected to the Autopilot. In addition, UART2 on the\nF9P units are connected to each other.\nModes 3 and 4 only require UART1 on each F9P connected to the Autopilot or Can Node. UART RX DMA is required.\nRTK is still possible with this setup.\nMode 6 is intended for use with a ground control station (not necessarily an RTK correction base).", "max": 1, "min": 0, "name": "GPS_UBX_MODE", "rebootRequired": true, "shortDesc": "u-blox GPS Mode", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Heading (Rover With Moving Base UART1 Connected To Autopilot, UART2 Connected To Moving Base)", "value": 1}, {"description": "Moving Base (UART1 Connected To Autopilot, UART2 Connected To Rover)", "value": 2}, {"description": "Heading (Rover With Moving Base UART1 Connected to Autopilot Or Can Node At 921600)", "value": 3}, {"description": "Moving Base (Moving Base UART1 Connected to Autopilot Or Can Node At 921600)", "value": 4}, {"description": "Rover with Static Base on UART2 (similar to Default, except coming in on UART2)", "value": 5}, {"description": "Ground Control Station (UART2 outputs NMEA)", "value": 6}]}, {"category": "Standard", "default": 0, "group": "GPS", "name": "GPS_UBX_PPK", "rebootRequired": true, "shortDesc": "Enable MSM7 message output for PPK workflow", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Configure the output rate of u-blox GPS receivers (protocol v27+).\nWhen set to 0, automatic rate selection is used based on the receiver model.\nDefault rates: M9N=8Hz, F9P L1L2=5Hz, F9P L1L5=5Hz, Others=10Hz.\nNote: Higher rates reduce satellite count (e.g., >8Hz limits to 16 SVs on M9N).\nMax rates vary by model and RTK mode: F9P L1L2=5-7Hz, F9P L1L5=7-8Hz, X20=25Hz.\nHigh rates at 115200 baud may cause dropouts.", "max": 25, "min": 0, "name": "GPS_UBX_RATE", "rebootRequired": true, "shortDesc": "u-blox GPS output rate", "type": "Int32", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "GPS", "longDesc": "Heading offset angle for dual antenna GPS setups that support heading estimation.\nSet this to 0 if the antennas are parallel to the forward-facing direction\nof the vehicle and the rover (or Unicore primary) antenna is in front.\nThe offset angle increases clockwise.\nSet this to 90 if the rover (or Unicore primary, or Septentrio Mosaic Aux)\nantenna is placed on the right side of the vehicle and the moving base\nantenna is on the left side.\n(Note: the Unicore primary antenna is the one connected on the right as seen\nfrom the top).", "max": 360.0, "min": 0.0, "name": "GPS_YAW_OFFSET", "rebootRequired": true, "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Geofence", "longDesc": "Note: Setting this value to 4 enables flight termination,\nwhich will kill the vehicle on violation of the fence.", "max": 5, "min": 0, "name": "GF_ACTION", "shortDesc": "Geofence violation action", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold mode", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land mode", "value": 5}]}, {"category": "Standard", "default": 0.0, "group": "Geofence", "increment": 1.0, "longDesc": "Maximum horizontal distance in meters the vehicle can be from Home before triggering a geofence action.\nDisabled if 0.", "max": 10000.0, "min": 0.0, "name": "GF_MAX_HOR_DIST", "shortDesc": "Max horizontal distance from Home", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0.0, "group": "Geofence", "increment": 1.0, "longDesc": "Maximum vertical distance in meters the vehicle can be from Home before triggering a geofence action.\nDisabled if 0.", "max": 10000.0, "min": 0.0, "name": "GF_MAX_VER_DIST", "shortDesc": "Max vertical distance from Home", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geofence", "longDesc": "WARNING: This experimental feature may cause flyaways. Use at your own risk.\nPredict the motion of the vehicle and trigger the breach if it is determined that the current trajectory\nwould result in a breach happening before the vehicle can make evasive maneuvers.\nThe vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing).", "name": "GF_PREDICT", "shortDesc": "[EXPERIMENTAL] Use Pre-emptive geofence triggering", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Geofence", "longDesc": "Select which position source should be used. Selecting GPS instead of global position makes sure that there is\nno dependence on the position estimator\n0 = global position, 1 = GPS", "max": 1, "min": 0, "name": "GF_SOURCE", "shortDesc": "Geofence source", "type": "Int32", "values": [{"description": "GPOS", "value": 0}, {"description": "GPS", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines which mixer implementation to use.\nSome are generic, while others are specifically fit to a certain vehicle with a fixed set of actuators.\n'Custom' should only be used if noting else can be used.", "name": "CA_AIRFRAME", "shortDesc": "Airframe selection", "type": "Int32", "values": [{"description": "Multirotor", "value": 0}, {"description": "Fixed-wing", "value": 1}, {"description": "Standard VTOL", "value": 2}, {"description": "Tiltrotor VTOL", "value": 3}, {"description": "Tailsitter VTOL", "value": 4}, {"description": "Rover (Ackermann)", "value": 5}, {"description": "Rover (Differential)", "value": 6}, {"description": "Motors (6DOF)", "value": 7}, {"description": "Multirotor with Tilt", "value": 8}, {"description": "Custom", "value": 9}, {"description": "Helicopter (tail ESC)", "value": 10}, {"description": "Helicopter (tail Servo)", "value": 11}, {"description": "Helicopter (Coaxial)", "value": 12}, {"description": "Rover (Mecanum)", "value": 13}, {"description": "Spacecraft 2D", "value": 14}, {"description": "Spacecraft 3D", "value": 15}]}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "This is used to specify how to handle motor failures\nreported by failure detector.", "name": "CA_FAILURE_MODE", "shortDesc": "Motor failure handling mode", "type": "Int32", "values": [{"description": "Ignore", "value": 0}, {"description": "Remove first failed motor from effectiveness", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": -0.05, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 0 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C0", "shortDesc": "Collective pitch curve at position 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0725, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 1 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C1", "shortDesc": "Collective pitch curve at position 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 2 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C2", "shortDesc": "Collective pitch curve at position 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.325, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 3 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C3", "shortDesc": "Collective pitch curve at position 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.45, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 4 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C4", "shortDesc": "Collective pitch curve at position 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Same definition as the proportional gain but for integral.", "max": 10.0, "min": 0.0, "name": "CA_HELI_RPM_I", "shortDesc": "Integral gain for rpm control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Ratio between rpm error devided by 1000 to how much normalized output gets added to correct for it.\nmotor_command = throttle_curve + CA_HELI_RPM_P * (rpm_setpoint - rpm_measurement) / 1000", "max": 10.0, "min": 0.0, "name": "CA_HELI_RPM_P", "shortDesc": "Proportional gain for rpm control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": 1500.0, "group": "Geometry", "increment": 1.0, "longDesc": "Requires rpm feedback for the controller.", "max": 10000.0, "min": 100.0, "name": "CA_HELI_RPM_SP", "shortDesc": "Setpoint for main rotor rpm", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 0.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C0", "shortDesc": "Throttle curve at position 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 1.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C1", "shortDesc": "Throttle curve at position 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 2.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C2", "shortDesc": "Throttle curve at position 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 3.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C3", "shortDesc": "Throttle curve at position 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 4.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C4", "shortDesc": "Throttle curve at position 4", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Default configuration is for a clockwise turning main rotor and\npositive thrust of the tail rotor is expected to rotate the vehicle clockwise.\nSet this parameter to true if the tail rotor provides thrust in counter-clockwise direction\nwhich is mostly the case when the main rotor turns counter-clockwise.", "name": "CA_HELI_YAW_CCW", "shortDesc": "Main rotor turns counter-clockwise", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to specify which collective pitch command results in the least amount of rotor drag.\nThis is used to increase the accuracy of the yaw drag torque compensation based on collective pitch\nby aligning the lowest rotor drag with zero compensation.\nFor symmetric profile blades this is the command that results in exactly 0\u00b0 collective blade angle.\nFor lift profile blades this is typically a command resulting in slightly negative collective blade angle.\ntail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O)", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_CP_O", "shortDesc": "Offset for yaw compensation based on collective pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to add a proportional factor of the collective pitch command to the yaw command.\nA negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction.\ntail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O)", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_CP_S", "shortDesc": "Scale for yaw compensation based on collective pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to add a proportional factor of the throttle command to the yaw command.\nA negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction.\ntail_output += CA_HELI_YAW_TH_S * throttle", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_TH_S", "shortDesc": "Scale for yaw compensation based on throttle", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Ice shedding prevents ice buildup in VTOL aircraft motors by\nperiodically spinning inactive rotors. When enabled (period\n> 0), every cycle lasts for the defined period and includes\na 2\u2011second spin at 0.01 motor output. If period <= 0, the\nfeature is disabled.", "min": 0.0, "name": "CA_ICE_PERIOD", "shortDesc": "Ice shedding cycle period", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Used to linearize mechanical output of swashplate servos to avoid axis coupling and binding with 4 servo redundancy.\nThis requires a symmetric setup where the servo horn is exactly centered with a 0 command.\nSetting to zero disables feature.", "max": 75.0, "min": 0.0, "name": "CA_MAX_SVO_THROW", "shortDesc": "Throw angle of swashplate servo at maximum commands for linearization", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Geometry", "longDesc": "Selects the algorithm and desaturation method.\nIf set to Automatic, the selection is based on the airframe (CA_AIRFRAME).", "name": "CA_METHOD", "shortDesc": "Control allocation method", "type": "Int32", "values": [{"description": "Pseudo-inverse with output clipping", "value": 0}, {"description": "Pseudo-inverse with sequential desaturation technique", "value": 1}, {"description": "Automatic", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R0_SLEW", "shortDesc": "Motor 0 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R10_SLEW", "shortDesc": "Motor 10 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R11_SLEW", "shortDesc": "Motor 11 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R1_SLEW", "shortDesc": "Motor 1 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R2_SLEW", "shortDesc": "Motor 2 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R3_SLEW", "shortDesc": "Motor 3 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R4_SLEW", "shortDesc": "Motor 4 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R5_SLEW", "shortDesc": "Motor 5 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R6_SLEW", "shortDesc": "Motor 6 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R7_SLEW", "shortDesc": "Motor 7 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R8_SLEW", "shortDesc": "Motor 8 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R9_SLEW", "shortDesc": "Motor 9 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AX", "shortDesc": "Axis of rotor 0 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AY", "shortDesc": "Axis of rotor 0 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AZ", "shortDesc": "Axis of rotor 0 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR0_CT", "shortDesc": "Thrust coefficient of rotor 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR0_KM", "shortDesc": "Moment coefficient of rotor 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PX", "shortDesc": "Position of rotor 0 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PY", "shortDesc": "Position of rotor 0 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PZ", "shortDesc": "Position of rotor 0 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR0_TILT", "shortDesc": "Rotor 0 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AX", "shortDesc": "Axis of rotor 10 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AY", "shortDesc": "Axis of rotor 10 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AZ", "shortDesc": "Axis of rotor 10 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR10_CT", "shortDesc": "Thrust coefficient of rotor 10", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR10_KM", "shortDesc": "Moment coefficient of rotor 10", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PX", "shortDesc": "Position of rotor 10 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PY", "shortDesc": "Position of rotor 10 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PZ", "shortDesc": "Position of rotor 10 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR10_TILT", "shortDesc": "Rotor 10 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AX", "shortDesc": "Axis of rotor 11 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AY", "shortDesc": "Axis of rotor 11 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AZ", "shortDesc": "Axis of rotor 11 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR11_CT", "shortDesc": "Thrust coefficient of rotor 11", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR11_KM", "shortDesc": "Moment coefficient of rotor 11", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PX", "shortDesc": "Position of rotor 11 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PY", "shortDesc": "Position of rotor 11 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PZ", "shortDesc": "Position of rotor 11 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR11_TILT", "shortDesc": "Rotor 11 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AX", "shortDesc": "Axis of rotor 1 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AY", "shortDesc": "Axis of rotor 1 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AZ", "shortDesc": "Axis of rotor 1 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR1_CT", "shortDesc": "Thrust coefficient of rotor 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR1_KM", "shortDesc": "Moment coefficient of rotor 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PX", "shortDesc": "Position of rotor 1 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PY", "shortDesc": "Position of rotor 1 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PZ", "shortDesc": "Position of rotor 1 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR1_TILT", "shortDesc": "Rotor 1 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AX", "shortDesc": "Axis of rotor 2 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AY", "shortDesc": "Axis of rotor 2 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AZ", "shortDesc": "Axis of rotor 2 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR2_CT", "shortDesc": "Thrust coefficient of rotor 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR2_KM", "shortDesc": "Moment coefficient of rotor 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PX", "shortDesc": "Position of rotor 2 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PY", "shortDesc": "Position of rotor 2 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PZ", "shortDesc": "Position of rotor 2 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR2_TILT", "shortDesc": "Rotor 2 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AX", "shortDesc": "Axis of rotor 3 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AY", "shortDesc": "Axis of rotor 3 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AZ", "shortDesc": "Axis of rotor 3 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR3_CT", "shortDesc": "Thrust coefficient of rotor 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR3_KM", "shortDesc": "Moment coefficient of rotor 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PX", "shortDesc": "Position of rotor 3 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PY", "shortDesc": "Position of rotor 3 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PZ", "shortDesc": "Position of rotor 3 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR3_TILT", "shortDesc": "Rotor 3 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AX", "shortDesc": "Axis of rotor 4 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AY", "shortDesc": "Axis of rotor 4 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AZ", "shortDesc": "Axis of rotor 4 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR4_CT", "shortDesc": "Thrust coefficient of rotor 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR4_KM", "shortDesc": "Moment coefficient of rotor 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PX", "shortDesc": "Position of rotor 4 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PY", "shortDesc": "Position of rotor 4 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PZ", "shortDesc": "Position of rotor 4 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR4_TILT", "shortDesc": "Rotor 4 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AX", "shortDesc": "Axis of rotor 5 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AY", "shortDesc": "Axis of rotor 5 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AZ", "shortDesc": "Axis of rotor 5 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR5_CT", "shortDesc": "Thrust coefficient of rotor 5", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR5_KM", "shortDesc": "Moment coefficient of rotor 5", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PX", "shortDesc": "Position of rotor 5 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PY", "shortDesc": "Position of rotor 5 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PZ", "shortDesc": "Position of rotor 5 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR5_TILT", "shortDesc": "Rotor 5 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AX", "shortDesc": "Axis of rotor 6 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AY", "shortDesc": "Axis of rotor 6 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AZ", "shortDesc": "Axis of rotor 6 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR6_CT", "shortDesc": "Thrust coefficient of rotor 6", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR6_KM", "shortDesc": "Moment coefficient of rotor 6", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PX", "shortDesc": "Position of rotor 6 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PY", "shortDesc": "Position of rotor 6 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PZ", "shortDesc": "Position of rotor 6 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR6_TILT", "shortDesc": "Rotor 6 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AX", "shortDesc": "Axis of rotor 7 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AY", "shortDesc": "Axis of rotor 7 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AZ", "shortDesc": "Axis of rotor 7 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR7_CT", "shortDesc": "Thrust coefficient of rotor 7", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR7_KM", "shortDesc": "Moment coefficient of rotor 7", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PX", "shortDesc": "Position of rotor 7 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PY", "shortDesc": "Position of rotor 7 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PZ", "shortDesc": "Position of rotor 7 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR7_TILT", "shortDesc": "Rotor 7 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AX", "shortDesc": "Axis of rotor 8 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AY", "shortDesc": "Axis of rotor 8 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AZ", "shortDesc": "Axis of rotor 8 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR8_CT", "shortDesc": "Thrust coefficient of rotor 8", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR8_KM", "shortDesc": "Moment coefficient of rotor 8", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PX", "shortDesc": "Position of rotor 8 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PY", "shortDesc": "Position of rotor 8 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PZ", "shortDesc": "Position of rotor 8 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR8_TILT", "shortDesc": "Rotor 8 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AX", "shortDesc": "Axis of rotor 9 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AY", "shortDesc": "Axis of rotor 9 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AZ", "shortDesc": "Axis of rotor 9 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR9_CT", "shortDesc": "Thrust coefficient of rotor 9", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR9_KM", "shortDesc": "Moment coefficient of rotor 9", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PX", "shortDesc": "Position of rotor 9 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PY", "shortDesc": "Position of rotor 9 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PZ", "shortDesc": "Position of rotor 9 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR9_TILT", "shortDesc": "Rotor 9 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_ROTOR_COUNT", "shortDesc": "Total number of rotors", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}, {"description": "5", "value": 5}, {"description": "6", "value": 6}, {"description": "7", "value": 7}, {"description": "8", "value": 8}, {"description": "9", "value": 9}, {"description": "10", "value": 10}, {"description": "11", "value": 11}, {"description": "12", "value": 12}]}, {"bitmask": [{"description": "Motor 1", "index": 0}, {"description": "Motor 2", "index": 1}, {"description": "Motor 3", "index": 2}, {"description": "Motor 4", "index": 3}, {"description": "Motor 5", "index": 4}, {"description": "Motor 6", "index": 5}, {"description": "Motor 7", "index": 6}, {"description": "Motor 8", "index": 7}, {"description": "Motor 9", "index": 8}, {"description": "Motor 10", "index": 9}, {"description": "Motor 11", "index": 10}, {"description": "Motor 12", "index": 11}], "category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Configure motors to be bidirectional/reversible. Note that the output driver needs to support this as well.", "max": 4095, "min": 0, "name": "CA_R_REV", "shortDesc": "Bidirectional/Reversible motors", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG0", "shortDesc": "Angle for swash plate servo 0", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 140.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG1", "shortDesc": "Angle for swash plate servo 1", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 220.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG2", "shortDesc": "Angle for swash plate servo 2", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG3", "shortDesc": "Angle for swash plate servo 3", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L0", "shortDesc": "Arm length for swash plate servo 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L1", "shortDesc": "Arm length for swash plate servo 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L2", "shortDesc": "Arm length for swash plate servo 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L3", "shortDesc": "Arm length for swash plate servo 3", "type": "Float"}, {"category": "Standard", "default": 3, "group": "Geometry", "name": "CA_SP0_COUNT", "shortDesc": "Number of swash plates servos", "type": "Int32", "values": [{"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV0_SLEW", "shortDesc": "Servo 0 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV1_SLEW", "shortDesc": "Servo 1 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV2_SLEW", "shortDesc": "Servo 2 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV3_SLEW", "shortDesc": "Servo 3 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV4_SLEW", "shortDesc": "Servo 4 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV5_SLEW", "shortDesc": "Servo 5 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV6_SLEW", "shortDesc": "Servo 6 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV7_SLEW", "shortDesc": "Servo 7 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_FLAP", "shortDesc": "Control Surface 0 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_SPOIL", "shortDesc": "Control Surface 0 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_TRIM", "shortDesc": "Control Surface 0 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_P", "shortDesc": "Control Surface 0 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_R", "shortDesc": "Control Surface 0 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_Y", "shortDesc": "Control Surface 0 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS0_TYPE", "shortDesc": "Control Surface 0 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_FLAP", "shortDesc": "Control Surface 1 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_SPOIL", "shortDesc": "Control Surface 1 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_TRIM", "shortDesc": "Control Surface 1 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_P", "shortDesc": "Control Surface 1 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_R", "shortDesc": "Control Surface 1 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_Y", "shortDesc": "Control Surface 1 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS1_TYPE", "shortDesc": "Control Surface 1 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_FLAP", "shortDesc": "Control Surface 2 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_SPOIL", "shortDesc": "Control Surface 2 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_TRIM", "shortDesc": "Control Surface 2 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_P", "shortDesc": "Control Surface 2 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_R", "shortDesc": "Control Surface 2 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_Y", "shortDesc": "Control Surface 2 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS2_TYPE", "shortDesc": "Control Surface 2 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_FLAP", "shortDesc": "Control Surface 3 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_SPOIL", "shortDesc": "Control Surface 3 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_TRIM", "shortDesc": "Control Surface 3 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_P", "shortDesc": "Control Surface 3 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_R", "shortDesc": "Control Surface 3 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_Y", "shortDesc": "Control Surface 3 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS3_TYPE", "shortDesc": "Control Surface 3 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_FLAP", "shortDesc": "Control Surface 4 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_SPOIL", "shortDesc": "Control Surface 4 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_TRIM", "shortDesc": "Control Surface 4 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_P", "shortDesc": "Control Surface 4 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_R", "shortDesc": "Control Surface 4 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_Y", "shortDesc": "Control Surface 4 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS4_TYPE", "shortDesc": "Control Surface 4 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_FLAP", "shortDesc": "Control Surface 5 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_SPOIL", "shortDesc": "Control Surface 5 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_TRIM", "shortDesc": "Control Surface 5 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_P", "shortDesc": "Control Surface 5 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_R", "shortDesc": "Control Surface 5 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_Y", "shortDesc": "Control Surface 5 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS5_TYPE", "shortDesc": "Control Surface 5 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_FLAP", "shortDesc": "Control Surface 6 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_SPOIL", "shortDesc": "Control Surface 6 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_TRIM", "shortDesc": "Control Surface 6 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_P", "shortDesc": "Control Surface 6 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_R", "shortDesc": "Control Surface 6 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_Y", "shortDesc": "Control Surface 6 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS6_TYPE", "shortDesc": "Control Surface 6 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_FLAP", "shortDesc": "Control Surface 7 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_SPOIL", "shortDesc": "Control Surface 7 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_TRIM", "shortDesc": "Control Surface 7 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_P", "shortDesc": "Control Surface 7 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_R", "shortDesc": "Control Surface 7 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_Y", "shortDesc": "Control Surface 7 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS7_TYPE", "shortDesc": "Control Surface 7 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS_COUNT", "shortDesc": "Total number of Control Surfaces", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}, {"description": "5", "value": 5}, {"description": "6", "value": 6}, {"description": "7", "value": 7}, {"description": "8", "value": 8}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Geometry", "max": 5.0, "min": 0.0, "name": "CA_SV_FLAP_SLEW", "shortDesc": "Control Surface slew rate for normalized flaps setpoint", "type": "Float"}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL0_CT", "shortDesc": "Tilt 0 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL0_MAXA", "shortDesc": "Tilt Servo 0 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL0_MINA", "shortDesc": "Tilt Servo 0 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle.\nFor example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front',\nthe motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL0_TD", "shortDesc": "Tilt Servo 0 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL1_CT", "shortDesc": "Tilt 1 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL1_MAXA", "shortDesc": "Tilt Servo 1 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL1_MINA", "shortDesc": "Tilt Servo 1 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle.\nFor example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front',\nthe motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL1_TD", "shortDesc": "Tilt Servo 1 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL2_CT", "shortDesc": "Tilt 2 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL2_MAXA", "shortDesc": "Tilt Servo 2 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL2_MINA", "shortDesc": "Tilt Servo 2 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle.\nFor example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front',\nthe motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL2_TD", "shortDesc": "Tilt Servo 2 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL3_CT", "shortDesc": "Tilt 3 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL3_MAXA", "shortDesc": "Tilt Servo 3 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL3_MINA", "shortDesc": "Tilt Servo 3 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle.\nFor example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front',\nthe motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL3_TD", "shortDesc": "Tilt Servo 3 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_TL_COUNT", "shortDesc": "Total number of Tilt Servos", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Hover Thrust Estimator", "longDesc": "Sets the number of standard deviations used\nby the innovation consistency test.", "max": 10.0, "min": 1.0, "name": "HTE_ACC_GATE", "shortDesc": "Gate size for acceleration fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Hover Thrust Estimator", "longDesc": "Sets the number of standard deviations used\nby the innovation consistency test.", "max": 1.0, "min": 0.0, "name": "HTE_HT_ERR_INIT", "shortDesc": "1-sigma initial hover thrust uncertainty", "type": "Float", "units": "normalized_thrust"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0036, "group": "Hover Thrust Estimator", "longDesc": "Reduce to make the hover thrust estimate\nmore stable, increase if the real hover thrust\nis expected to change quickly over time.", "max": 1.0, "min": 0.0001, "name": "HTE_HT_NOISE", "shortDesc": "Hover thrust process noise", "type": "Float", "units": "normalized_thrust/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Hover Thrust Estimator", "longDesc": "Defines the range of the hover thrust estimate around MPC_THR_HOVER.\nA value of 0.2 with MPC_THR_HOVER at 0.5 results in a range of [0.3, 0.7].\nSet to a large value if the vehicle operates in varying physical conditions that\naffect the required hover thrust strongly (e.g. differently sized payloads).", "max": 0.4, "min": 0.01, "name": "HTE_THR_RANGE", "shortDesc": "Max deviation from MPC_THR_HOVER", "type": "Float", "units": "normalized_thrust"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Hover Thrust Estimator", "longDesc": "Above this speed, the measurement noise is linearly increased\nto reduce the sensitivity of the estimator from biased measurement.\nSet to a low value on vehicles with large lifting surfaces.", "max": 20.0, "min": 1.0, "name": "HTE_VXY_THR", "shortDesc": "Horizontal velocity threshold for sensitivity reduction", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Hover Thrust Estimator", "longDesc": "Above this speed, the measurement noise is linearly increased\nto reduce the sensitivity of the estimator from biased measurement.\nSet to a low value on vehicles affected by air drag when climbing or descending.", "max": 10.0, "min": 1.0, "name": "HTE_VZ_THR", "shortDesc": "Vertical velocity threshold for sensitivity reduction", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.0, "group": "Land Detector", "longDesc": "Maximum airspeed allowed in the landed state", "max": 30.0, "min": 2.0, "name": "LNDFW_AIRSPD_MAX", "shortDesc": "Fixed-wing land detector: Max airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Land Detector", "longDesc": "Maximum allowed norm of the angular velocity in the landed state.\nOnly used if neither airspeed nor groundspeed can be used for landing detection.", "name": "LNDFW_ROT_MAX", "shortDesc": "Fixed-wing land detector: max rotational speed", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Land Detector", "longDesc": "Time the land conditions (speeds and acceleration) have to be satisfied to detect a landing.", "min": 0.1, "name": "LNDFW_TRIG_TIME", "rebootRequired": true, "shortDesc": "Fixed-wing land detection trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Land Detector", "longDesc": "Maximum horizontal velocity allowed in the landed state.\nA factor of 0.7 is applied in case of airspeed-less flying\n(either because no sensor is present or sensor data got invalid in flight).", "max": 20.0, "min": 0.5, "name": "LNDFW_VEL_XY_MAX", "shortDesc": "Fixed-wing land detector: Max horizontal velocity threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Land Detector", "longDesc": "Maximum vertical velocity allowed in the landed state.", "max": 20.0, "min": 0.1, "name": "LNDFW_VEL_Z_MAX", "shortDesc": "Fixed-wing land detector: Max vertiacal velocity threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 8.0, "group": "Land Detector", "longDesc": "Maximum horizontal (x,y body axes) acceleration allowed in the landed state", "max": 30.0, "min": 2.0, "name": "LNDFW_XYACC_MAX", "shortDesc": "Fixed-wing land detector: Max horizontal acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Land Detector", "longDesc": "The height above ground below which ground effect creates barometric altitude errors.\nA negative value indicates no ground effect.", "min": -1.0, "name": "LNDMC_ALT_GND", "shortDesc": "Ground effect altitude for multicopters", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Land Detector", "longDesc": "Maximum allowed norm of the angular velocity (roll, pitch) in the landed state.", "name": "LNDMC_ROT_MAX", "shortDesc": "Multicopter max rotational speed", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Land Detector", "longDesc": "Total time it takes to go through all three land detection stages:\nground contact, maybe landed, landed\nwhen all necessary conditions are constantly met.", "max": 10.0, "min": 0.1, "name": "LNDMC_TRIG_TIME", "shortDesc": "Multicopter land detection trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Land Detector", "longDesc": "Maximum horizontal velocity allowed in the landed state", "name": "LNDMC_XY_VEL_MAX", "shortDesc": "Multicopter max horizontal velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "Land Detector", "longDesc": "Vertical velocity threshold to detect landing.\nHas to be set lower than the expected minimal speed for landing,\nwhich is either MPC_LAND_SPEED or MPC_LAND_CRWL.\nThis is enforced by an automatic check.", "min": 0.0, "name": "LNDMC_Z_VEL_MAX", "shortDesc": "Multicopter vertical velocity threshold", "type": "Float", "units": "m/s"}, {"category": "System", "default": 0, "group": "Land Detector", "longDesc": "Total flight time of this autopilot. Higher 32 bits of the value.\nFlight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO.", "min": 0, "name": "LND_FLIGHT_T_HI", "shortDesc": "Total flight time in microseconds", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Land Detector", "longDesc": "Total flight time of this autopilot. Lower 32 bits of the value.\nFlight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO.", "min": 0, "name": "LND_FLIGHT_T_LO", "shortDesc": "Total flight time in microseconds", "type": "Int32", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Landing Target Estimator", "longDesc": "Variance of acceleration measurement used for landing target position prediction.\nHigher values results in tighter following of the measurements and more lenient outlier rejection", "min": 0.01, "name": "LTEST_ACC_UNC", "shortDesc": "Acceleration uncertainty", "type": "Float", "units": "(m/s^2)^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.005, "group": "Landing Target Estimator", "longDesc": "Variance of the landing target measurement from the driver.\nHigher values result in less aggressive following of the measurement and a smoother output as well as fewer rejected measurements.", "name": "LTEST_MEAS_UNC", "shortDesc": "Landing target measurement uncertainty", "type": "Float", "units": "tan(rad)^2"}, {"category": "Standard", "default": 0, "group": "Landing Target Estimator", "longDesc": "Configure the mode of the landing target. Depending on the mode, the landing target observations are used differently to aid position estimation.\nMode Moving: The landing target may be moving around while in the field of view of the vehicle. Landing target measurements are not used to aid positioning.\nMode Stationary: The landing target is stationary. Measured velocity w.r.t. the landing target is used to aid velocity estimation.", "max": 1, "min": 0, "name": "LTEST_MODE", "shortDesc": "Landing target mode", "type": "Int32", "values": [{"description": "Moving", "value": 0}, {"description": "Stationary", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Landing Target Estimator", "longDesc": "Initial variance of the relative landing target position in x and y direction", "min": 0.001, "name": "LTEST_POS_UNC_IN", "shortDesc": "Initial landing target position uncertainty", "type": "Float", "units": "m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Landing Target Estimator", "longDesc": "Landing target x measurements are scaled by this factor before being used", "min": 0.01, "name": "LTEST_SCALE_X", "shortDesc": "Scale factor for sensor measurements in sensor x axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Landing Target Estimator", "longDesc": "Landing target y measurements are scaled by this factor before being used", "min": 0.01, "name": "LTEST_SCALE_Y", "shortDesc": "Scale factor for sensor measurements in sensor y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_X", "rebootRequired": true, "shortDesc": "X Position of IRLOCK in body frame (forward)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_Y", "rebootRequired": true, "shortDesc": "Y Position of IRLOCK in body frame (right)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_Z", "rebootRequired": true, "shortDesc": "Z Position of IRLOCK in body frame (downward)", "type": "Float", "units": "m"}, {"category": "Standard", "default": 2, "group": "Landing Target Estimator", "longDesc": "Default orientation of Yaw 90\u00b0", "max": 40, "min": -1, "name": "LTEST_SENS_ROT", "rebootRequired": true, "shortDesc": "Rotation of IRLOCK sensor relative to airframe", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Landing Target Estimator", "longDesc": "Initial variance of the relative landing target velocity in x and y directions", "min": 0.001, "name": "LTEST_VEL_UNC_IN", "shortDesc": "Initial landing target velocity uncertainty", "type": "Float", "units": "(m/s)^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.012, "group": "Local Position Estimator", "longDesc": "Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)\nLarger than data sheet to account for tilt error.", "max": 2.0, "min": 1e-05, "name": "LPE_ACC_XY", "shortDesc": "Accelerometer xy noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.02, "group": "Local Position Estimator", "longDesc": "Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)", "max": 2.0, "min": 1e-05, "name": "LPE_ACC_Z", "shortDesc": "Accelerometer z noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Local Position Estimator", "max": 100.0, "min": 0.01, "name": "LPE_BAR_Z", "shortDesc": "Barometric presssure altitude z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Local Position Estimator", "name": "LPE_EN", "shortDesc": "Local position estimator enable (unsupported)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Local Position Estimator", "max": 5.0, "min": 1.0, "name": "LPE_EPH_MAX", "shortDesc": "Max EPH allowed for GPS initialization", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 5.0, "group": "Local Position Estimator", "max": 5.0, "min": 1.0, "name": "LPE_EPV_MAX", "shortDesc": "Max EPV allowed for GPS initialization", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Local Position Estimator", "longDesc": "By initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable", "max": 1, "min": 0, "name": "LPE_FAKE_ORIGIN", "shortDesc": "Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow)", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Local Position Estimator", "max": 2.0, "min": 0.0, "name": "LPE_FGYRO_HP", "shortDesc": "Flow gyro high pass filter cut off frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_FLW_OFF_Z", "shortDesc": "Optical flow z offset from center", "type": "Float", "units": "m"}, {"category": "Standard", "default": 150, "group": "Local Position Estimator", "max": 255, "min": 0, "name": "LPE_FLW_QMIN", "shortDesc": "Optical flow minimum quality threshold", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 7.0, "group": "Local Position Estimator", "max": 10.0, "min": 0.1, "name": "LPE_FLW_R", "shortDesc": "Optical flow rotation (roll/pitch) noise gain", "type": "Float", "units": "m/s/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 7.0, "group": "Local Position Estimator", "max": 10.0, "min": 0.0, "name": "LPE_FLW_RR", "shortDesc": "Optical flow angular velocity noise gain", "type": "Float", "units": "m/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.3, "group": "Local Position Estimator", "max": 10.0, "min": 0.1, "name": "LPE_FLW_SCALE", "shortDesc": "Optical flow scale", "type": "Float", "units": "m"}, {"bitmask": [{"description": "fuse GPS, requires GPS for alt. init", "index": 0}, {"description": "fuse optical flow", "index": 1}, {"description": "fuse vision position", "index": 2}, {"description": "fuse landing target", "index": 3}, {"description": "fuse land detector", "index": 4}, {"description": "pub agl as lpos down", "index": 5}, {"description": "flow gyro compensation", "index": 6}, {"description": "fuse baro", "index": 7}], "category": "Standard", "default": 145, "group": "Local Position Estimator", "longDesc": "Set bits in the following positions to enable:\n0 : Set to true to fuse GPS data if available, also requires GPS for altitude init\n1 : Set to true to fuse optical flow data if available\n2 : Set to true to fuse vision position\n3 : Set to true to enable landing target\n4 : Set to true to fuse land detector\n5 : Set to true to publish AGL as local position down component\n6 : Set to true to enable flow gyro compensation\n7 : Set to true to enable baro fusion\ndefault (145 - GPS, baro, land detector)", "max": 255, "min": 0, "name": "LPE_FUSION", "shortDesc": "Integer bitmask controlling data fusion", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.29, "group": "Local Position Estimator", "max": 0.4, "min": 0.0, "name": "LPE_GPS_DELAY", "shortDesc": "GPS delay compensaton", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Local Position Estimator", "longDesc": "EPV used if greater than this value.", "max": 2.0, "min": 0.01, "name": "LPE_GPS_VXY", "shortDesc": "GPS xy velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Local Position Estimator", "max": 2.0, "min": 0.01, "name": "LPE_GPS_VZ", "shortDesc": "GPS z velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Local Position Estimator", "max": 5.0, "min": 0.01, "name": "LPE_GPS_XY", "shortDesc": "Minimum GPS xy standard deviation, uses reported EPH if greater", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Local Position Estimator", "max": 200.0, "min": 0.01, "name": "LPE_GPS_Z", "shortDesc": "Minimum GPS z standard deviation, uses reported EPV if greater", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Local Position Estimator", "max": 10.0, "min": 0.01, "name": "LPE_LAND_VXY", "shortDesc": "Land detector xy velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Local Position Estimator", "max": 10.0, "min": 0.001, "name": "LPE_LAND_Z", "shortDesc": "Land detector z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 8, "default": 47.397742, "group": "Local Position Estimator", "max": 90.0, "min": -90.0, "name": "LPE_LAT", "shortDesc": "Local origin latitude for nav w/o GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_LDR_OFF_Z", "shortDesc": "Lidar z offset from center of vehicle +down", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_LDR_Z", "shortDesc": "Lidar z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 8, "default": 8.545594, "group": "Local Position Estimator", "max": 180.0, "min": -180.0, "name": "LPE_LON", "shortDesc": "Local origin longitude for nav w/o GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0001, "group": "Local Position Estimator", "max": 10.0, "min": 0.0, "name": "LPE_LT_COV", "shortDesc": "Minimum landing target standard covariance, uses reported covariance if greater", "type": "Float", "units": "m^2"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0, "name": "LPE_PN_B", "shortDesc": "Accel bias propagation noise density", "type": "Float", "units": "m/s^3/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Increase to trust measurements more.\nDecrease to trust model more.", "max": 1.0, "min": 0.0, "name": "LPE_PN_P", "shortDesc": "Position propagation noise density", "type": "Float", "units": "m/s/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0, "name": "LPE_PN_T", "shortDesc": "Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001)", "type": "Float", "units": "m/s/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Increase to trust measurements more.\nDecrease to trust model more.", "max": 1.0, "min": 0.0, "name": "LPE_PN_V", "shortDesc": "Velocity propagation noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_SNR_OFF_Z", "shortDesc": "Sonar z offset from center of vehicle +down", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_SNR_Z", "shortDesc": "Sonar z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Local Position Estimator", "longDesc": "Used to calculate increased terrain random walk nosie due to movement.", "max": 100.0, "min": 0.0, "name": "LPE_T_MAX_GRADE", "shortDesc": "Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg)", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0001, "name": "LPE_VIC_P", "shortDesc": "Vicon position standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Set to zero to enable automatic compensation from measurement timestamps", "max": 0.1, "min": 0.0, "name": "LPE_VIS_DELAY", "shortDesc": "Vision delay compensation", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_VIS_XY", "shortDesc": "Vision xy standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "Local Position Estimator", "max": 100.0, "min": 0.01, "name": "LPE_VIS_Z", "shortDesc": "Vision z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.3, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_VXY_PUB", "shortDesc": "Required velocity xy standard deviation to publish position", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 5.0, "group": "Local Position Estimator", "max": 1000.0, "min": 5.0, "name": "LPE_X_LP", "shortDesc": "Cut frequency for state publication", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Local Position Estimator", "max": 5.0, "min": 0.3, "name": "LPE_Z_PUB", "shortDesc": "Required z standard deviation to publish altitude/ terrain", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone\non the local network.", "name": "MAV_0_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 0", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink\ninstance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_0_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 0", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the\nmessage is either broadcast or the target is not the autopilot.\nThis allows for example a GCS to talk to a camera that is connected to the\nautopilot via MAVLink (on a different link than the GCS).", "name": "MAV_0_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 0", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the\nHIGH_LATENCY2 stream for instance 0, configured in iridium mode.\nThis parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_0_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 0", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the\nvehicle's attitude) and their sending rates.", "name": "MAV_0_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 0", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to\n`txbuf` field reported by radio_status.\nRequires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_0_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 0", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1200, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec.\nIf the configured streams exceed the maximum rate, the sending rate of\neach stream is automatically decreased.\nIf this is set to 0 a value of half of the theoretical maximum bandwidth is used.\nThis corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on\n8N1-configured links).", "min": 0, "name": "MAV_0_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 0", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 14550, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 0,\nselected remote port will be set and used in MAVLink instance 0.", "name": "MAV_0_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 0", "type": "Int32"}, {"category": "Standard", "default": 14556, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 0,\nselected udp port will be set and used in MAVLink instance 0.", "name": "MAV_0_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 0", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone\non the local network.", "name": "MAV_1_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 1", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink\ninstance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_1_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 1", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the\nmessage is either broadcast or the target is not the autopilot.\nThis allows for example a GCS to talk to a camera that is connected to the\nautopilot via MAVLink (on a different link than the GCS).", "name": "MAV_1_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 1", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the\nHIGH_LATENCY2 stream for instance 1, configured in iridium mode.\nThis parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_1_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 1", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the\nvehicle's attitude) and their sending rates.", "name": "MAV_1_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 1", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to\n`txbuf` field reported by radio_status.\nRequires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_1_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 1", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec.\nIf the configured streams exceed the maximum rate, the sending rate of\neach stream is automatically decreased.\nIf this is set to 0 a value of half of the theoretical maximum bandwidth is used.\nThis corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on\n8N1-configured links).", "min": 0, "name": "MAV_1_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 1", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 1,\nselected remote port will be set and used in MAVLink instance 1.", "name": "MAV_1_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 1", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 1,\nselected udp port will be set and used in MAVLink instance 1.", "name": "MAV_1_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 1", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone\non the local network.", "name": "MAV_2_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 2", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink\ninstance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_2_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 2", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the\nmessage is either broadcast or the target is not the autopilot.\nThis allows for example a GCS to talk to a camera that is connected to the\nautopilot via MAVLink (on a different link than the GCS).", "name": "MAV_2_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the\nHIGH_LATENCY2 stream for instance 2, configured in iridium mode.\nThis parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_2_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 2", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the\nvehicle's attitude) and their sending rates.", "name": "MAV_2_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 2", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to\n`txbuf` field reported by radio_status.\nRequires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_2_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec.\nIf the configured streams exceed the maximum rate, the sending rate of\neach stream is automatically decreased.\nIf this is set to 0 a value of half of the theoretical maximum bandwidth is used.\nThis corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on\n8N1-configured links).", "min": 0, "name": "MAV_2_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 2", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 2,\nselected remote port will be set and used in MAVLink instance 2.", "name": "MAV_2_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 2", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 2,\nselected udp port will be set and used in MAVLink instance 2.", "name": "MAV_2_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 2", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "max": 250, "min": 1, "name": "MAV_COMP_ID", "rebootRequired": true, "shortDesc": "MAVLink component ID", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If set to 1 incoming external setpoint messages will be directly forwarded\nto the controllers if in offboard control mode", "name": "MAV_FWDEXTSP", "shortDesc": "Forward external setpoint messages", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "Disabling the parameter hash check functionality will make the mavlink instance\nstream parameters continuously.", "name": "MAV_HASH_CHK_EN", "shortDesc": "Parameter hash check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "The mavlink heartbeat message will not be forwarded if this parameter is set to 'disabled'.\nThe main reason for disabling heartbeats to be forwarded is because they confuse dronekit.", "name": "MAV_HB_FORW_EN", "shortDesc": "Heartbeat message forwarding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "name": "MAV_PROTO_VER", "shortDesc": "MAVLink protocol version", "type": "Int32", "values": [{"description": "Version 1 with auto-upgrade to v2 if detected", "value": 1}, {"description": "Version 2", "value": 2}]}, {"category": "Standard", "default": 5, "group": "MAVLink", "longDesc": "If the connected radio stops reporting RADIO_STATUS for a certain time,\na warning is triggered and, if MAV_X_RADIO_CTL is enabled, the software-flow\ncontrol is reset.", "max": 250, "min": 1, "name": "MAV_RADIO_TOUT", "shortDesc": "Timeout in seconds for the RADIO_STATUS reports coming in", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "When non-zero the MAVLink app will attempt to configure the\nSiK radio to this ID and re-set the parameter to 0. If the value\nis negative it will reset the complete radio config to\nfactory defaults. Only applies if this mavlink instance is going through a SiK radio", "max": 240, "min": -1, "name": "MAV_SIK_RADIO_ID", "shortDesc": "MAVLink SiK Radio ID", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "max": 250, "min": 1, "name": "MAV_SYS_ID", "rebootRequired": true, "shortDesc": "MAVLink system ID", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "TELEM2 on Skynode only.", "name": "MAV_S_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink forwarding on TELEM2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 11, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the\nvehicle's attitude) and their sending rates.", "name": "MAV_S_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for SOM to FMU communication channel", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Onboard", "value": 2}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "max": 22, "min": 0, "name": "MAV_TYPE", "shortDesc": "MAVLink airframe type", "type": "Int32", "values": [{"description": "Generic micro air vehicle", "value": 0}, {"description": "Fixed wing aircraft", "value": 1}, {"description": "Quadrotor", "value": 2}, {"description": "Coaxial helicopter", "value": 3}, {"description": "Normal helicopter with tail rotor", "value": 4}, {"description": "Airship, controlled", "value": 7}, {"description": "Free balloon, uncontrolled", "value": 8}, {"description": "Ground rover", "value": 10}, {"description": "Surface vessel, boat, ship", "value": 11}, {"description": "Submarine", "value": 12}, {"description": "Hexarotor", "value": 13}, {"description": "Octorotor", "value": 14}, {"description": "Tricopter", "value": 15}, {"description": "VTOL Two-rotor Tailsitter", "value": 19}, {"description": "VTOL Quad-rotor Tailsitter", "value": 20}, {"description": "VTOL Tiltrotor", "value": 21}, {"description": "VTOL Standard (separate fixed rotors for hover and cruise flight)", "value": 22}, {"description": "VTOL Tailsitter", "value": 23}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If set to 1 incoming HIL GPS messages are parsed.", "name": "MAV_USEHILGPS", "shortDesc": "Use/Accept HIL GPS message even if not in HIL mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Magnetometer Bias Estimator", "longDesc": "This enables continuous calibration of the magnetometers\nbefore takeoff using gyro data.", "name": "MBE_ENABLE", "rebootRequired": true, "shortDesc": "Enable online mag bias calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 18.0, "group": "Magnetometer Bias Estimator", "increment": 0.1, "longDesc": "Increase to make the estimator more responsive\nDecrease to make the estimator more robust to noise", "max": 100.0, "min": 0.1, "name": "MBE_LEARN_GAIN", "shortDesc": "Mag bias estimator learning gain", "type": "Float"}, {"category": "Standard", "default": 1, "group": "Manual Control", "longDesc": "This determines if moving the left stick to the lower right\narms and to the lower left disarms the vehicle.", "name": "MAN_ARM_GESTURE", "shortDesc": "Enable arm/disarm stick gesture", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Manual Control", "increment": 0.01, "longDesc": "Range around stick center ignored to prevent\nvehicle drift from stick hardware inaccuracy.\nDoes not apply to any precise constant input like\nthrottle and attitude or rate piloting.", "max": 1.0, "min": 0.0, "name": "MAN_DEADZONE", "shortDesc": "Deadzone for sticks (only specific use cases)", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Manual Control", "longDesc": "The timeout for holding the left stick to the lower left\nand the right stick to the lower right at the same time until the gesture\nkills the actuators one-way.\nA negative value disables the feature.", "max": 15.0, "min": -1.0, "name": "MAN_KILL_GEST_T", "shortDesc": "Trigger time for kill stick gesture", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mission", "longDesc": "Ensure:\ngripper: NAV_CMD_DO_GRIPPER\nhas released before continuing mission.\nwinch: CMD_DO_WINCH\nhas delivered before continuing mission.\ngimbal: CMD_DO_GIMBAL_MANAGER_PITCHYAW\nhas reached the commanded orientation before beginning to take pictures.", "min": 0.0, "name": "MIS_COMMAND_TOUT", "shortDesc": "Timeout to allow the payload to execute the mission command", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10000.0, "group": "Mission", "increment": 100.0, "longDesc": "There will be a warning message if the current waypoint is more distant than MIS_DIST_1WP from Home.\nHas no effect on mission validity.\nSet a value of zero or less to disable.", "max": 100000.0, "min": -1.0, "name": "MIS_DIST_1WP", "shortDesc": "Maximal horizontal distance from Home to first waypoint", "type": "Float", "units": "m"}, {"category": "Standard", "default": 30, "group": "Mission", "longDesc": "Minimum altitude above landing point that the vehicle will climb to after an aborted landing.\nThen vehicle will loiter in this altitude until further command is received.\nOnly applies to fixed-wing vehicles.", "min": 0, "name": "MIS_LND_ABRT_ALT", "shortDesc": "Landing abort min altitude", "type": "Int32", "units": "m"}, {"category": "Standard", "default": 0, "group": "Mission", "longDesc": "If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading towards the flight direction.\nIf disabled, the vehicle will yaw towards the ROI.", "max": 1, "min": 0, "name": "MIS_MNT_YAW_CTL", "shortDesc": "Enable yaw control of the mount. (Only affects multicopters and ROI mission items)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Enable", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "Mission", "increment": 0.5, "longDesc": "This is the relative altitude the system will take off to\nif not otherwise specified.", "min": 0.0, "name": "MIS_TAKEOFF_ALT", "shortDesc": "Default take-off altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Mission", "longDesc": "Specifies if a mission has to contain a takeoff and/or mission landing.\nValidity of configured takeoffs/landings is checked independently of the setting here.", "name": "MIS_TKO_LAND_REQ", "shortDesc": "Mission takeoff/landing required", "type": "Int32", "values": [{"description": "No requirements", "value": 0}, {"description": "Require a takeoff", "value": 1}, {"description": "Require a landing", "value": 2}, {"description": "Require a takeoff and a landing", "value": 3}, {"description": "Require both a takeoff and a landing, or neither", "value": 4}, {"description": "Same as previous when landed, in-air require landing only if no valid VTOL approach is present", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": 12.0, "group": "Mission", "increment": 1.0, "max": 90.0, "min": 0.0, "name": "MIS_YAW_ERR", "shortDesc": "Max yaw error in degrees needed for waypoint heading acceptance", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 1.0, "longDesc": "If set > 0 it will ignore the target heading for normal waypoint acceptance. If the\nwaypoint forces the heading the timeout will matter. For example on VTOL forwards transition.\nMainly useful for VTOLs that have less yaw authority and might not reach target\nyaw in wind. Disabled by default.", "max": 20.0, "min": -1.0, "name": "MIS_YAW_TMT", "shortDesc": "Time in seconds we wait on reaching target heading at a waypoint if it is forced", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Mission", "max": 4, "min": 0, "name": "MPC_YAW_MODE", "shortDesc": "Heading behavior in autonomous modes", "type": "Int32", "values": [{"description": "towards waypoint", "value": 0}, {"description": "towards home", "value": 1}, {"description": "away from home", "value": 2}, {"description": "along trajectory", "value": 3}, {"description": "towards waypoint (yaw first)", "value": 4}, {"description": "yaw fixed", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Mission", "increment": 0.5, "longDesc": "Default acceptance radius, overridden by acceptance radius of waypoint if set.\nFor fixed wing the npfg switch distance is used for horizontal acceptance.", "max": 200.0, "min": 0.05, "name": "NAV_ACC_RAD", "shortDesc": "Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Mission", "name": "NAV_FORCE_VT", "shortDesc": "Force VTOL mode takeoff and land", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Mission", "longDesc": "Altitude acceptance used for the last waypoint before a fixed-wing landing. This is usually smaller\nthan the standard vertical acceptance because close to the ground higher accuracy is required.", "max": 200.0, "min": 0.05, "name": "NAV_FW_ALTL_RAD", "shortDesc": "FW Altitude Acceptance Radius before a landing", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Mission", "increment": 0.5, "longDesc": "Acceptance radius for fixedwing altitude.", "max": 200.0, "min": 0.05, "name": "NAV_FW_ALT_RAD", "shortDesc": "FW Altitude Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 80.0, "group": "Mission", "increment": 0.5, "longDesc": "Default value of loiter radius in fixed-wing mode (e.g. for Loiter mode).\nThe direction of the loiter can be set via the sign: A positive value for\nclockwise, negative for counter-clockwise.", "max": 10000.0, "min": -10000.0, "name": "NAV_LOITER_RAD", "shortDesc": "Loiter radius (FW only)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.8, "group": "Mission", "increment": 0.5, "longDesc": "Acceptance radius for multicopter altitude.", "max": 200.0, "min": 0.05, "name": "NAV_MC_ALT_RAD", "shortDesc": "MC Altitude Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 1.0, "longDesc": "Minimum height above ground the vehicle is allowed to descend to during Mission and RTL,\nexcluding landing commands.\nRequires a distance sensor to be set up.\nNote: only prevents the vehicle from descending further, but does not force it to climb.\nSet to a negative value to disable.", "min": -1.0, "name": "NAV_MIN_GND_DIST", "shortDesc": "Minimum height above ground during Mission and RTL", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 0.5, "longDesc": "This is the minimum altitude above Home the system will always obey in Loiter (Hold) mode if switched into this\nmode without specifying an altitude (e.g. through Loiter switch on RC).\nDoesn't affect Loiters that are part of Missions or that are entered through a reposition setpoint (\"Go to\").\nSet to a negative value to disable.", "min": -1.0, "name": "NAV_MIN_LTR_ALT", "shortDesc": "Minimum Loiter altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Mission", "longDesc": "Enabling this will allow the system to respond\nto transponder data from e.g. ADSB transponders", "name": "NAV_TRAFF_AVOID", "shortDesc": "Set traffic avoidance mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warn only", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Position Hold mode", "value": 4}]}, {"category": "Standard", "default": 500.0, "group": "Mission", "longDesc": "Defines a crosstrack horizontal distance", "min": 500.0, "name": "NAV_TRAFF_A_HOR", "shortDesc": "Set NAV TRAFFIC AVOID horizontal distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 500.0, "group": "Mission", "max": 500.0, "min": 10.0, "name": "NAV_TRAFF_A_VER", "shortDesc": "Set NAV TRAFFIC AVOID vertical distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 60, "group": "Mission", "longDesc": "Minimum acceptable time until collsion.\nAssumes constant speed over 3d distance.", "max": 900000000, "min": 1, "name": "NAV_TRAFF_COLL_T", "shortDesc": "Estimated time until collision", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Mixer Output", "longDesc": "The air-mode enables the mixer to increase the total thrust of the multirotor\nin order to keep attitude and rate control even at low and high throttle.\nThis function should be disabled during tuning as it will help the controller\nto diverge if the closed-loop is unstable (i.e. the vehicle is not tuned yet).\nEnabling air-mode for yaw requires the use of an arming switch.", "name": "MC_AIRMODE", "shortDesc": "Multicopter air-mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Roll/Pitch", "value": 1}, {"description": "Roll/Pitch/Yaw", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Mount", "longDesc": "Set to true for servo gimbal, false for passthrough.\nThis is required for a gimbal which is not capable of stabilizing itself\nand relies on the IMU's attitude estimation.", "name": "MNT_DO_STAB", "shortDesc": "Stabilize the mount", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Stabilize all axis", "value": 1}, {"description": "Stabilize yaw for absolute/lock mode.", "value": 2}, {"description": "Stabilize pitch for absolute/lock mode.", "value": 3}]}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "max": 90.0, "min": -90.0, "name": "MNT_LND_P_MAX", "shortDesc": "Pitch maximum when landed", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -90.0, "group": "Mount", "max": 90.0, "min": -90.0, "name": "MNT_LND_P_MIN", "shortDesc": "Pitch minimum when landed", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_PITCH", "shortDesc": "Auxiliary channel to control pitch (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_ROLL", "shortDesc": "Auxiliary channel to control roll (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_YAW", "shortDesc": "Auxiliary channel to control yaw (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 154, "group": "Mount", "longDesc": "If MNT_MODE_OUT is MAVLink protocol v2, mount configure/control commands will be sent with this component ID.", "name": "MNT_MAV_COMPID", "shortDesc": "Mavlink Component ID of the mount", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Mount", "longDesc": "If MNT_MODE_OUT is MAVLink gimbal protocol v1, mount configure/control commands will be sent with this target ID.", "name": "MNT_MAV_SYSID", "shortDesc": "Mavlink System ID of the mount", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 45.0, "group": "Mount", "longDesc": "Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX).", "name": "MNT_MAX_PITCH", "shortDesc": "Max positive angle of pitch setpoint (only in MNT_MODE_OUT=AUX)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -45.0, "group": "Mount", "longDesc": "Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX).", "name": "MNT_MIN_PITCH", "shortDesc": "Min negative angle of pitch setpoint (only in MNT_MODE_OUT=AUX)", "type": "Float", "units": "deg"}, {"category": "Standard", "default": -1, "group": "Mount", "longDesc": "This is the protocol used between the ground station and the autopilot.\nRecommended is Auto, RC only or MAVLink gimbal protocol v2.\nThe rest will be deprecated.", "max": 4, "min": -1, "name": "MNT_MODE_IN", "rebootRequired": true, "shortDesc": "Mount input mode", "type": "Int32", "values": [{"description": "DISABLED", "value": -1}, {"description": "Auto (RC and MAVLink gimbal protocol v2)", "value": 0}, {"description": "RC", "value": 1}, {"description": "MAVLINK_ROI (protocol v1, to be deprecated)", "value": 2}, {"description": "MAVLINK_DO_MOUNT (protocol v1, to be deprecated)", "value": 3}, {"description": "MAVlink gimbal protocol v2", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Mount", "longDesc": "This is the protocol used between the autopilot and a connected gimbal.\nRecommended is the MAVLink gimbal protocol v2 if the gimbal supports it.", "max": 2, "min": 0, "name": "MNT_MODE_OUT", "rebootRequired": true, "shortDesc": "Mount output mode", "type": "Int32", "values": [{"description": "AUX", "value": 0}, {"description": "MAVLink gimbal protocol v1", "value": 1}, {"description": "MAVLink gimbal protocol v2", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "longDesc": "Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX). Note that only symmetric angular ranges are supported.", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_ROLL", "shortDesc": "Range of roll channel output (only in MNT_MODE_OUT=AUX)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 360.0, "group": "Mount", "longDesc": "Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX). Note that only symmetric angular ranges are supported.", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_YAW", "shortDesc": "Range of yaw channel output (only in MNT_MODE_OUT=AUX)", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 30.0, "group": "Mount", "longDesc": "Full stick input [-1..1] translats to [-pitch rate..pitch rate].", "max": 90.0, "min": 1.0, "name": "MNT_RATE_PITCH", "shortDesc": "Angular pitch rate for manual input in degrees/second", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 30.0, "group": "Mount", "longDesc": "Full stick input [-1..1] translats to [-yaw rate..yaw rate].", "max": 90.0, "min": 1.0, "name": "MNT_RATE_YAW", "shortDesc": "Angular yaw rate for manual input in degrees/second", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 1, "group": "Mount", "max": 1, "min": 0, "name": "MNT_RC_IN_MODE", "shortDesc": "Input mode for RC gimbal input", "type": "Int32", "values": [{"description": "Angle", "value": 0}, {"description": "Angular rate", "value": 1}]}, {"category": "Standard", "default": 0.3, "group": "Mount", "longDesc": "Use when no angular position feedback is available.\nWith MNT_MODE_OUT set to AUX, the mount operates in open-loop and directly commands the servo output.\nParameters must be tuned for the specific servo to approximate its speed and response.", "min": 0.0, "name": "MNT_TAU", "shortDesc": "Alpha filter time constant defining the convergence rate (in seconds) for open-loop AUX mount control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "Exponential factor for tuning the input curve shape.\n0 Purely linear input curve\n1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MC_ACRO_EXPO", "shortDesc": "Acro mode roll, pitch expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "Exponential factor for tuning the input curve shape.\n0 Purely linear input curve\n1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MC_ACRO_EXPO_Y", "shortDesc": "Acro mode yaw expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_P_MAX", "shortDesc": "Acro mode maximum pitch rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_R_MAX", "shortDesc": "Acro mode maximum roll rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using MC_ACRO_EXPO.\n0 Pure Expo function\n0.7 reasonable shape enhancement for intuitive stick feel\n0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "MC_ACRO_SUPEXPO", "shortDesc": "Acro mode roll, pitch super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y.\n0 Pure Expo function\n0.7 reasonable shape enhancement for intuitive stick feel\n0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "MC_ACRO_SUPEXPOY", "shortDesc": "Acro mode yaw super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_Y_MAX", "shortDesc": "Acro mode maximum yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 220.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limit for pitch rate in manual and auto modes (except acro).\nHas effect for large rotations in autonomous mode, to avoid large control\noutput and mixer saturation.\nThis is not only limited by the vehicle's properties, but also by the maximum\nmeasurement rate of the gyro.", "max": 1800.0, "min": 0.0, "name": "MC_PITCHRATE_MAX", "shortDesc": "Max pitch rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 12.0, "min": 0.0, "name": "MC_PITCH_P", "shortDesc": "Pitch P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 220.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limit for roll rate in manual and auto modes (except acro).\nHas effect for large rotations in autonomous mode, to avoid large control\noutput and mixer saturation.\nThis is not only limited by the vehicle's properties, but also by the maximum\nmeasurement rate of the gyro.", "max": 1800.0, "min": 0.0, "name": "MC_ROLLRATE_MAX", "shortDesc": "Max roll rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 12.0, "min": 0.0, "name": "MC_ROLL_P", "shortDesc": "Roll P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 200.0, "group": "Multicopter Attitude Control", "increment": 5.0, "max": 1800.0, "min": 0.0, "name": "MC_YAWRATE_MAX", "shortDesc": "Max yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.8, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 5.0, "min": 0.0, "name": "MC_YAW_P", "shortDesc": "Yaw P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "A fraction [0,1] deprioritizing yaw compared to roll and pitch in non-linear attitude control.\nDeprioritizing yaw is necessary because multicopters have much less control authority\nin yaw compared to the other axes and it makes sense because yaw is not critical for\nstable hovering or 3D navigation.\nFor yaw control tuning use MC_YAW_P. This ratio has no impact on the yaw gain.", "max": 1.0, "min": 0.0, "name": "MC_YAW_WEIGHT", "shortDesc": "Yaw weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": 20.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limits the acceleration of the yaw setpoint to avoid large\ncontrol output and mixer saturation.", "max": 360.0, "min": 5.0, "name": "MPC_YAWRAUTO_ACC", "shortDesc": "Maximum yaw acceleration in autonomous modes", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 0, "default": 60.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limits the rate of change of the yaw setpoint to avoid large\ncontrol output and mixer saturation.", "max": 360.0, "min": 5.0, "name": "MPC_YAWRAUTO_MAX", "shortDesc": "Maximum yaw rate in autonomous modes", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0.4, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "max": 1.0, "min": 0.0, "name": "CP_DELAY", "shortDesc": "Average delay of the range sensor message plus the tracking delay of the position controller in seconds", "type": "Float", "units": "s"}, {"category": "Standard", "default": -1.0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode. Collision avoidance is disabled by setting this parameter to a negative value", "max": 15.0, "min": -1.0, "name": "CP_DIST", "shortDesc": "Minimum distance the vehicle should keep to all obstacles", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "name": "CP_GO_NO_DATA", "shortDesc": "Boolean to allow moving into directions where there is no sensor data (outside FOV)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 30.0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "max": 90.0, "min": 0.0, "name": "CP_GUIDE_ANG", "shortDesc": "Angle left/right from the commanded setpoint by which the collision prevention algorithm can choose to change the setpoint direction", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Position Control", "longDesc": "Setting this parameter to 0 disables the filter", "max": 2.0, "min": 0.0, "name": "MC_MAN_TILT_TAU", "shortDesc": "Manual tilt input filter time constant", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Multicopter Position Control", "longDesc": "Set to decouple tilt from vertical acceleration.\nThis provides smoother flight but slightly worse tracking in position and auto modes.\nUnset if accurate position tracking during dynamic maneuvers is more important than a smooth flight.", "name": "MPC_ACC_DECOUPLE", "shortDesc": "Acceleration to tilt coupling", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 15.0, "min": 2.0, "name": "MPC_ACC_DOWN_MAX", "shortDesc": "Maximum downwards acceleration in climb rate controlled modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "When piloting manually, this parameter is only used in MPC_POS_MODE Acceleration based.", "max": 15.0, "min": 2.0, "name": "MPC_ACC_HOR", "shortDesc": "Acceleration for autonomous and for manual modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "MPC_POS_MODE\n1 just deceleration\n4 not used, use MPC_ACC_HOR instead", "max": 15.0, "min": 2.0, "name": "MPC_ACC_HOR_MAX", "shortDesc": "Maximum horizontal acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 15.0, "min": 2.0, "name": "MPC_ACC_UP_MAX", "shortDesc": "Maximum upwards acceleration in climb rate controlled modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 2, "group": "Multicopter Position Control", "longDesc": "Control height\n0: relative earth frame origin which may drift due to sensors\n1: relative to ground (requires distance sensor) which changes with terrain variation.\nIt will revert to relative earth frame if the distance to ground estimate becomes invalid.\n2: relative to ground (requires distance sensor) when stationary\nand relative to earth frame when moving horizontally.\nThe speed threshold is MPC_HOLD_MAX_XY", "max": 2, "min": 0, "name": "MPC_ALT_MODE", "shortDesc": "Altitude reference mode", "type": "Int32", "values": [{"description": "Altitude following", "value": 0}, {"description": "Terrain following", "value": 1}, {"description": "Terrain hold", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.8, "group": "Multicopter Position Control", "longDesc": "Only used with MPC_POS_MODE Direct velocity or MPC_ALT_MODE 2", "max": 3.0, "min": 0.0, "name": "MPC_HOLD_MAX_XY", "shortDesc": "Maximum horizontal velocity for which position hold is enabled (use 0 to disable check)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "longDesc": "Only used with MPC_ALT_MODE 1", "max": 3.0, "min": 0.0, "name": "MPC_HOLD_MAX_Z", "shortDesc": "Maximum vertical velocity for which position hold is enabled (use 0 to disable check)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Limit the maximum jerk of the vehicle (how fast the acceleration can change).\nA lower value leads to smoother vehicle motions but also limited agility.", "max": 80.0, "min": 1.0, "name": "MPC_JERK_AUTO", "shortDesc": "Jerk limit in autonomous modes", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 0, "default": 8.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Limit the maximum jerk (acceleration change) of the vehicle.\nA lower value leads to smoother motions but limits agility.\nSetting this to the maximum value essentially disables the limit.\nOnly used with MPC_POS_MODE Acceleration based.", "max": 500.0, "min": 0.5, "name": "MPC_JERK_MAX", "shortDesc": "Maximum horizontal and vertical jerk in Position/Altitude mode", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Multicopter Position Control", "longDesc": "Below this altitude descending velocity gets limited to a value\nbetween \"MPC_Z_VEL_MAX_DN\" (or \"MPC_Z_V_AUTO_DN\") and \"MPC_LAND_SPEED\"\nValue needs to be higher than \"MPC_LAND_ALT2\"", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT1", "shortDesc": "Altitude for 1. step of slow landing (descend)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "longDesc": "Below this altitude descending velocity gets\nlimited to \"MPC_LAND_SPEED\"\nValue needs to be lower than \"MPC_LAND_ALT1\"", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT2", "shortDesc": "Altitude for 2. step of slow landing (landing)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Multicopter Position Control", "longDesc": "If a valid distance sensor measurement to the ground is available,\nlimit descending velocity to \"MPC_LAND_CRWL\" below this altitude.", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT3", "shortDesc": "Altitude for 3. step of slow landing", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.3, "group": "Multicopter Position Control", "longDesc": "Used below MPC_LAND_ALT3 if distance sensor data is availabe.", "min": 0.1, "name": "MPC_LAND_CRWL", "shortDesc": "Land crawl descend rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "When nudging is enabled (see MPC_LAND_RC_HELP), this defines the maximum\nallowed horizontal displacement from the original landing point.\n- If inside of the radius, only allow nudging inputs that do not move the vehicle outside of it.\n- If outside of the radius, only allow nudging inputs that move the vehicle back towards it.\nSet it to -1 for infinite radius.", "min": -1.0, "name": "MPC_LAND_RADIUS", "shortDesc": "User assisted landing radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Using stick input the vehicle can be moved horizontally and yawed.\nThe descend speed is amended:\nstick full up - 0\nstick centered - MPC_LAND_SPEED\nstick full down - 2 * MPC_LAND_SPEED\nManual override during auto modes has to be disabled to use this feature (see COM_RC_OVERRIDE).", "max": 1, "min": 0, "name": "MPC_LAND_RC_HELP", "shortDesc": "Enable nudging based on user input during autonomous land routine", "type": "Int32", "values": [{"description": "Nudging disabled", "value": 0}, {"description": "Nudging enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.7, "group": "Multicopter Position Control", "min": 0.6, "name": "MPC_LAND_SPEED", "shortDesc": "Landing descend rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The value is mapped to the lowest throttle stick position in Stabilized mode.\nToo low collective thrust leads to loss of roll/pitch/yaw torque control authority.\nAirmode is used to keep torque authority with zero thrust (see MC_AIRMODE).", "max": 1.0, "min": 0.0, "name": "MPC_MANTHR_MIN", "shortDesc": "Minimum collective thrust in Stabilized mode", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 0, "default": 35.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 70.0, "min": 1.0, "name": "MPC_MAN_TILT_MAX", "shortDesc": "Maximal tilt angle in Stabilized, Altitude and Altitude Cruise mode", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 150.0, "group": "Multicopter Position Control", "increment": 10.0, "max": 400.0, "min": 0.0, "name": "MPC_MAN_Y_MAX", "shortDesc": "Max manual yaw rate for Stabilized, Altitude, Position mode", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Not used in Stabilized mode\nSetting this parameter to 0 disables the filter", "max": 5.0, "min": 0.0, "name": "MPC_MAN_Y_TAU", "shortDesc": "Manual yaw rate input filter time constant", "type": "Float", "units": "s"}, {"category": "Standard", "default": 4, "group": "Multicopter Position Control", "longDesc": "The supported sub-modes are:\nDirect velocity:\nSticks directly map to velocity setpoints without smoothing.\nAlso applies to vertical direction and Altitude mode.\nUseful for velocity control tuning.\nAcceleration based:\nSticks map to acceleration and there's a virtual brake drag", "name": "MPC_POS_MODE", "shortDesc": "Position/Altitude mode variant", "type": "Int32", "values": [{"description": "Direct velocity", "value": 0}, {"description": "Acceleration based", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Defines how the throttle stick is mapped to collective thrust in Stabilized mode.\nRescale to hover thrust estimate:\nStick input is linearly rescaled, such that a centered throttle stick corresponds to the hover thrust estimator's output.\nNo rescale:\nDirectly map the stick 1:1 to the output.\nCan be useful with very low hover thrust which leads to much distortion and the upper half getting sensitive.\nRescale to hover thrust parameter:\nSimilar to rescaling to the hover thrust estimate, but it uses the hover thrust parameter value (see MPC_THR_HOVER) instead of estimated value.\nWith MPC_THR_HOVER 0.5 it's equivalent to No rescale.", "name": "MPC_THR_CURVE", "shortDesc": "Thrust curve mapping in Stabilized Mode", "type": "Int32", "values": [{"description": "Rescale to estimate", "value": 0}, {"description": "No rescale", "value": 1}, {"description": "Rescale to parameter", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Mapped to center throttle stick in Stabilized mode (see MPC_THR_CURVE).\nUsed for initialization of the hover thrust estimator (see MPC_USE_HTE).\nThe estimated hover thrust is used as base for zero vertical acceleration in altitude control.\nThe hover thrust is important for land detection to work correctly.", "max": 0.8, "min": 0.1, "name": "MPC_THR_HOVER", "shortDesc": "Vertical thrust required to hover", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Control", "increment": 0.05, "longDesc": "Limit allowed thrust e.g. for indoor test of overpowered vehicle.", "max": 1.0, "min": 0.0, "name": "MPC_THR_MAX", "shortDesc": "Maximum collective thrust in climb rate controlled modes", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.12, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Too low thrust leads to loss of roll/pitch/yaw torque control authority.\nWith airmode enabled this parameters can be set to 0\nwhile still keeping torque authority (see MC_AIRMODE).", "max": 0.5, "min": 0.05, "name": "MPC_THR_MIN", "shortDesc": "Minimum collective thrust in climb rate controlled modes", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Margin that is kept for horizontal control when higher priority vertical thrust is saturated.\nTo avoid completely starving horizontal control with high vertical error.", "max": 0.5, "min": 0.0, "name": "MPC_THR_XY_MARG", "shortDesc": "Horizontal thrust margin", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Absolute maximum for all velocity or acceleration controlled modes.\nAny higher value is truncated.", "max": 89.0, "min": 20.0, "name": "MPC_TILTMAX_AIR", "shortDesc": "Maximum tilt angle in air", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 12.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Tighter tilt limit during takeoff to avoid tip over.", "max": 89.0, "min": 5.0, "name": "MPC_TILTMAX_LND", "shortDesc": "Maximum tilt during inital takeoff ramp", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 3.0, "group": "Multicopter Position Control", "longDesc": "Increasing this value will make climb rate controlled takeoff slower.\nIf it's too slow the drone might scratch the ground and tip over.\nA time constant of 0 disables the ramp", "max": 5.0, "min": 0.0, "name": "MPC_TKO_RAMP_T", "shortDesc": "Smooth takeoff ramp time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.5, "group": "Multicopter Position Control", "max": 5.0, "min": 1.0, "name": "MPC_TKO_SPEED", "shortDesc": "Takeoff climb rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "Multicopter Position Control", "longDesc": "Disable to use the fixed parameter MPC_THR_HOVER instead of the hover thrust estimate in the position controller.\nThis parameter does not influence Stabilized mode throttle curve (see MPC_THR_CURVE).", "name": "MPC_USE_HTE", "shortDesc": "Use hover thrust estimate for altitude control", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VELD_LP", "shortDesc": "Velocity derivative low pass cutoff frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_LP", "shortDesc": "Velocity low pass cutoff frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Must be smaller than MPC_XY_VEL_MAX.\nThe maximum sideways and backward speed can be set differently\nusing MPC_VEL_MAN_SIDE and MPC_VEL_MAN_BACK, respectively.", "max": 20.0, "min": 3.0, "name": "MPC_VEL_MANUAL", "shortDesc": "Maximum horizontal velocity setpoint in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a negative value or larger than\nMPC_VEL_MANUAL then MPC_VEL_MANUAL is used.", "max": 20.0, "min": -1.0, "name": "MPC_VEL_MAN_BACK", "shortDesc": "Maximum backward velocity in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a negative value or larger than\nMPC_VEL_MANUAL then MPC_VEL_MANUAL is used.", "max": 20.0, "min": -1.0, "name": "MPC_VEL_MAN_SIDE", "shortDesc": "Maximum sideways velocity in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_NF_BW", "shortDesc": "Velocity notch filter bandwidth", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "The center frequency for the 2nd order notch filter on the velocity.\nA value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_NF_FRQ", "shortDesc": "Velocity notch filter frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 0, "default": 5.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "e.g. in Missions, RTL, Goto if the waypoint does not specify differently", "max": 20.0, "min": 3.0, "name": "MPC_XY_CRUISE", "shortDesc": "Default horizontal velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "The integration speed of the trajectory setpoint is linearly\nreduced with the horizontal position tracking error. When the\nerror is above this parameter, the integration of the\ntrajectory is stopped to wait for the drone.\nThis value can be adjusted depending on the tracking\ncapabilities of the vehicle.", "max": 10.0, "min": 0.1, "name": "MPC_XY_ERR_MAX", "shortDesc": "Maximum horizontal error allowed by the trajectory generator", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.95, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective velocity in m/s per m position error", "max": 2.0, "min": 0.0, "name": "MPC_XY_P", "shortDesc": "Proportional gain for horizontal position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Multicopter Position Control", "increment": 0.1, "max": 1.0, "min": 0.1, "name": "MPC_XY_TRAJ_P", "shortDesc": "Proportional gain for horizontal trajectory position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -10.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a value greater than zero, other parameters are automatically set (such as\nMPC_XY_VEL_MAX or MPC_VEL_MANUAL).\nIf set to a negative value, the existing individual parameters are used.", "max": 20.0, "min": -20.0, "name": "MPC_XY_VEL_ALL", "shortDesc": "Overall Horizontal Velocity Limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative", "max": 2.0, "min": 0.1, "name": "MPC_XY_VEL_D_ACC", "shortDesc": "Differential gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as correction acceleration in m/s^2 per m velocity integral\nAllows to eliminate steady state errors in disturbances like wind.", "max": 60.0, "min": 0.0, "name": "MPC_XY_VEL_I_ACC", "shortDesc": "Integral gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 12.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Absolute maximum for all velocity controlled modes.\nAny higher value is truncated.", "max": 20.0, "min": 0.0, "name": "MPC_XY_VEL_MAX", "shortDesc": "Maximum horizontal velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.8, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s velocity error", "max": 5.0, "min": 1.2, "name": "MPC_XY_VEL_P_ACC", "shortDesc": "Proportional gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective velocity in m/s per m position error", "max": 1.5, "min": 0.1, "name": "MPC_Z_P", "shortDesc": "Proportional gain for vertical position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -3.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "If set to a value greater than zero, other parameters are automatically set (such as\nMPC_Z_VEL_MAX_UP or MPC_LAND_SPEED).\nIf set to a negative value, the existing individual parameters are used.", "max": 8.0, "min": -3.0, "name": "MPC_Z_VEL_ALL", "shortDesc": "Overall Vertical Velocity Limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative", "max": 2.0, "min": 0.0, "name": "MPC_Z_VEL_D_ACC", "shortDesc": "Differential gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m velocity integral", "max": 3.0, "min": 0.2, "name": "MPC_Z_VEL_I_ACC", "shortDesc": "Integral gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Absolute maximum for all climb rate controlled modes.\nIn manually piloted modes full stick deflection commands this velocity.\nFor default autonomous velocity see MPC_Z_V_AUTO_UP", "max": 4.0, "min": 0.5, "name": "MPC_Z_VEL_MAX_DN", "shortDesc": "Maximum descent velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Absolute maximum for all climb rate controlled modes.\nIn manually piloted modes full stick deflection commands this velocity.\nFor default autonomous velocity see MPC_Z_V_AUTO_UP", "max": 8.0, "min": 0.5, "name": "MPC_Z_VEL_MAX_UP", "shortDesc": "Maximum ascent velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s velocity error", "max": 15.0, "min": 2.0, "name": "MPC_Z_VEL_P_ACC", "shortDesc": "Proportional gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "For manual modes and offboard, see MPC_Z_VEL_MAX_DN", "max": 4.0, "min": 0.5, "name": "MPC_Z_V_AUTO_DN", "shortDesc": "Descent velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "For manually controlled modes and offboard see MPC_Z_VEL_MAX_UP", "max": 8.0, "min": 0.5, "name": "MPC_Z_V_AUTO_UP", "shortDesc": "Ascent velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": -0.4, "group": "Multicopter Position Control", "increment": 0.05, "longDesc": "Changes the overall responsiveness of the vehicle.\nThe higher the value, the faster the vehicle will react.\nIf set to a value greater than zero, other parameters are automatically set (such as\nthe acceleration or jerk limits).\nIf set to a negative value, the existing individual parameters are used.", "max": 1.0, "min": -1.0, "name": "SYS_VEHICLE_RESP", "shortDesc": "Responsiveness", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "name": "WV_EN", "shortDesc": "Enable weathervane", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1.0, "group": "Multicopter Position Control", "max": 5.0, "min": 0.0, "name": "WV_ROLL_MIN", "shortDesc": "Minimum roll angle setpoint for weathervane controller to demand a yaw-rate", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 90.0, "group": "Multicopter Position Control", "max": 120.0, "min": 0.0, "name": "WV_YRATE_MAX", "shortDesc": "Maximum yawrate the weathervane controller is allowed to demand", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if\nno aux channel is mapped and\nno limit is commanded through MAVLink.", "min": 0.1, "name": "MC_SLOW_DEF_HVEL", "shortDesc": "Default horizontal velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if\nno aux channel is mapped and\nno limit is commanded through MAVLink.", "min": 0.1, "name": "MC_SLOW_DEF_VVEL", "shortDesc": "Default vertical velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if\nno aux channel is mapped and\nno limit is commanded through MAVLink.", "min": 1.0, "name": "MC_SLOW_DEF_YAWR", "shortDesc": "Default yaw rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_HVEL", "shortDesc": "Manual input mapped to scale horizontal velocity in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_PTCH", "shortDesc": "RC_MAP_AUX{N} to allow for gimbal pitch rate control in position slow mode", "type": "Int32", "values": [{"description": "No pitch rate input", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_VVEL", "shortDesc": "Manual input mapped to scale vertical velocity in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_YAWR", "shortDesc": "Manual input mapped to scale yaw rate in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this velocity.", "min": 0.1, "name": "MC_SLOW_MIN_HVEL", "shortDesc": "Horizontal velocity lower limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this velocity.", "min": 0.1, "name": "MC_SLOW_MIN_VVEL", "shortDesc": "Vertical velocity lower limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 3.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this rate.", "min": 1.0, "name": "MC_SLOW_MIN_YAWR", "shortDesc": "Yaw rate lower limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0, "group": "Multicopter Rate Control", "longDesc": "This compensates for voltage drop of the battery over time by attempting to\nnormalize performance across the operating range of the battery. The copter\nshould constantly behave as if it was fully charged with reduced max acceleration\nat lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery,\nit will still be 0.5 at 60% battery.", "name": "MC_BAT_SCALE_EN", "shortDesc": "Battery power level scaler", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 4, "default": 0.003, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "min": 0.0, "name": "MC_PITCHRATE_D", "shortDesc": "Pitch rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_PITCHRATE_FF", "shortDesc": "Pitch rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_PITCHRATE_I", "shortDesc": "Pitch rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller.\nThis gain scales the P, I and D terms of the controller:\noutput = MC_PITCHRATE_K * (MC_PITCHRATE_P * error\n+ MC_PITCHRATE_I * error_integral\n+ MC_PITCHRATE_D * error_derivative)\nSet MC_PITCHRATE_P=1 to implement a PID in the ideal form.\nSet MC_PITCHRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_PITCHRATE_K", "shortDesc": "Pitch rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.6, "min": 0.01, "name": "MC_PITCHRATE_P", "shortDesc": "Pitch rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes.", "min": 0.0, "name": "MC_PR_INT_LIM", "shortDesc": "Pitch rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.003, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "max": 0.01, "min": 0.0, "name": "MC_ROLLRATE_D", "shortDesc": "Roll rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_ROLLRATE_FF", "shortDesc": "Roll rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_ROLLRATE_I", "shortDesc": "Roll rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller.\nThis gain scales the P, I and D terms of the controller:\noutput = MC_ROLLRATE_K * (MC_ROLLRATE_P * error\n+ MC_ROLLRATE_I * error_integral\n+ MC_ROLLRATE_D * error_derivative)\nSet MC_ROLLRATE_P=1 to implement a PID in the ideal form.\nSet MC_ROLLRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_ROLLRATE_K", "shortDesc": "Roll rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.5, "min": 0.01, "name": "MC_ROLLRATE_P", "shortDesc": "Roll rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes.", "min": 0.0, "name": "MC_RR_INT_LIM", "shortDesc": "Roll rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "min": 0.0, "name": "MC_YAWRATE_D", "shortDesc": "Yaw rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_YAWRATE_FF", "shortDesc": "Yaw rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_YAWRATE_I", "shortDesc": "Yaw rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller.\nThis gain scales the P, I and D terms of the controller:\noutput = MC_YAWRATE_K * (MC_YAWRATE_P * error\n+ MC_YAWRATE_I * error_integral\n+ MC_YAWRATE_D * error_derivative)\nSet MC_YAWRATE_P=1 to implement a PID in the ideal form.\nSet MC_YAWRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_YAWRATE_K", "shortDesc": "Yaw rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.6, "min": 0.0, "name": "MC_YAWRATE_P", "shortDesc": "Yaw rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 2.0, "group": "Multicopter Rate Control", "longDesc": "Reduces vibrations by lowering high frequency torque caused by rotor acceleration.\n0 disables the filter", "max": 10.0, "min": 0.0, "name": "MC_YAW_TQ_CUTOFF", "shortDesc": "Low pass filter cutoff frequency for yaw torque setpoint", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes.", "min": 0.0, "name": "MC_YR_INT_LIM", "shortDesc": "Yaw rate integrator limit", "type": "Float"}, {"category": "Standard", "default": 0, "group": "OSD", "longDesc": "Controls the vertical position of the crosshair display.\nResolution is limited by OSD to 15 discrete values. Negative\nvalues will display the crosshairs below the horizon", "max": 8, "min": -8, "name": "OSD_CH_HEIGHT", "shortDesc": "OSD Crosshairs Height", "type": "Int32"}, {"category": "Standard", "default": 500, "group": "OSD", "longDesc": "Amount of time in milliseconds to dwell at the beginning of the display, when scrolling.", "max": 10000, "min": 100, "name": "OSD_DWELL_TIME", "shortDesc": "OSD Dwell Time (ms)", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "OSD", "longDesc": "Minimum security of log level to display on the OSD.", "name": "OSD_LOG_LEVEL", "shortDesc": "OSD Warning Level", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "OSD", "longDesc": "Forward RC stick input to VTX when disarmed", "max": 1, "min": 0, "name": "OSD_RC_STICK", "shortDesc": "OSD RC Stick commands", "type": "Int32"}, {"category": "Standard", "default": 125, "group": "OSD", "longDesc": "Scroll rate in milliseconds for OSD messages longer than available character width.\nThis is lower-bounded by the nominal loop rate of this module.", "max": 1000, "min": 100, "name": "OSD_SCROLL_RATE", "shortDesc": "OSD Scroll Rate (ms)", "type": "Int32"}, {"bitmask": [{"description": "CRAFT_NAME", "index": 0}, {"description": "DISARMED", "index": 1}, {"description": "GPS_LAT", "index": 2}, {"description": "GPS_LON", "index": 3}, {"description": "GPS_SATS", "index": 4}, {"description": "GPS_SPEED", "index": 5}, {"description": "HOME_DIST", "index": 6}, {"description": "HOME_DIR", "index": 7}, {"description": "MAIN_BATT_VOLTAGE", "index": 8}, {"description": "CURRENT_DRAW", "index": 9}, {"description": "MAH_DRAWN", "index": 10}, {"description": "RSSI_VALUE", "index": 11}, {"description": "ALTITUDE", "index": 12}, {"description": "NUMERICAL_VARIO", "index": 13}, {"description": "(unused) FLYMODE", "index": 14}, {"description": "(unused) ESC_TMP", "index": 15}, {"description": "(unused) PITCH_ANGLE", "index": 16}, {"description": "(unused) ROLL_ANGLE", "index": 17}, {"description": "CROSSHAIRS", "index": 18}, {"description": "AVG_CELL_VOLTAGE", "index": 19}, {"description": "(unused) HORIZON_SIDEBARS", "index": 20}, {"description": "POWER", "index": 21}], "category": "Standard", "default": 16383, "group": "OSD", "longDesc": "Configure / toggle support display options.", "max": 4194303, "min": 0, "name": "OSD_SYMBOLS", "shortDesc": "OSD Symbol Selection", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "PWM Outputs", "increment": 0.1, "longDesc": "Parameter used to model the nonlinear relationship between\nmotor control signal (e.g. PWM) and static thrust.\nThe model is: rel_thrust = factor * rel_signal^2 + (1-factor) * rel_signal,\nwhere rel_thrust is the normalized thrust between 0 and 1, and\nrel_signal is the relative motor control signal between 0 and 1.", "max": 1.0, "min": 0.0, "name": "THR_MDL_FAC", "shortDesc": "Thrust to motor control signal model parameter", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Payload Deliverer", "longDesc": "Maximum time Gripper will wait while the successful griper actuation isn't recognised.\nIf the gripper has no feedback sensor, it will simply wait for\nthis time before considering gripper actuation successful and publish a\n'VehicleCommandAck' signaling successful gripper action", "min": 0.0, "name": "PD_GRIPPER_TO", "shortDesc": "Timeout for successful gripper actuation acknowledgement", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Payload Deliverer", "max": 0, "min": -1, "name": "PD_GRIPPER_TYPE", "shortDesc": "Type of Gripper (Servo, etc.)", "type": "Int32", "values": [{"description": "Undefined", "value": -1}, {"description": "Servo", "value": 0}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Precision Land", "increment": 0.5, "longDesc": "Time after which the landing target is considered lost without any new measurements.", "max": 50.0, "min": 0.0, "name": "PLD_BTOUT", "shortDesc": "Landing Target Timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Precision Land", "increment": 0.1, "longDesc": "Allow final approach (without horizontal positioning) if losing landing target closer than this to the ground.", "max": 10.0, "min": 0.0, "name": "PLD_FAPPR_ALT", "shortDesc": "Final approach altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Precision Land", "increment": 0.1, "longDesc": "Start descending if closer above landing target than this.", "max": 10.0, "min": 0.0, "name": "PLD_HACC_RAD", "shortDesc": "Horizontal acceptance radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "Precision Land", "longDesc": "Maximum number of times to search for the landing target if it is lost during the precision landing.", "max": 100, "min": 0, "name": "PLD_MAX_SRCH", "shortDesc": "Maximum number of search attempts", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Precision Land", "increment": 0.1, "longDesc": "Altitude above home to which to climb when searching for the landing target.", "max": 100.0, "min": 0.0, "name": "PLD_SRCH_ALT", "shortDesc": "Search altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Precision Land", "increment": 0.1, "longDesc": "Time allowed to search for the landing target before falling back to normal landing.", "max": 100.0, "min": 0.0, "name": "PLD_SRCH_TOUT", "shortDesc": "Search timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Pure Pursuit", "increment": 0.01, "longDesc": "Lower value -> More aggressive controller (beware overshoot/oscillations)", "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_GAIN", "shortDesc": "Tuning parameter for the pure pursuit controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Pure Pursuit", "increment": 0.01, "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_MAX", "shortDesc": "Maximum lookahead distance for the pure pursuit controller", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Pure Pursuit", "increment": 0.01, "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_MIN", "shortDesc": "Minimum lookahead distance for the pure pursuit controller", "type": "Float", "units": "m"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC10_MAX", "shortDesc": "RC channel 10 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC10_MIN", "shortDesc": "RC channel 10 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC10_REV", "shortDesc": "RC channel 10 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC10_TRIM", "shortDesc": "RC channel 10 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC11_MAX", "shortDesc": "RC channel 11 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC11_MIN", "shortDesc": "RC channel 11 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC11_REV", "shortDesc": "RC channel 11 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC11_TRIM", "shortDesc": "RC channel 11 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC12_MAX", "shortDesc": "RC channel 12 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC12_MIN", "shortDesc": "RC channel 12 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC12_REV", "shortDesc": "RC channel 12 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC12_TRIM", "shortDesc": "RC channel 12 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC13_MAX", "shortDesc": "RC channel 13 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC13_MIN", "shortDesc": "RC channel 13 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC13_REV", "shortDesc": "RC channel 13 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC13_TRIM", "shortDesc": "RC channel 13 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC14_MAX", "shortDesc": "RC channel 14 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC14_MIN", "shortDesc": "RC channel 14 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC14_REV", "shortDesc": "RC channel 14 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC14_TRIM", "shortDesc": "RC channel 14 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC15_MAX", "shortDesc": "RC channel 15 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC15_MIN", "shortDesc": "RC channel 15 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC15_REV", "shortDesc": "RC channel 15 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC15_TRIM", "shortDesc": "RC channel 15 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC16_MAX", "shortDesc": "RC channel 16 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC16_MIN", "shortDesc": "RC channel 16 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC16_REV", "shortDesc": "RC channel 16 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC16_TRIM", "shortDesc": "RC channel 16 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC17_MAX", "shortDesc": "RC channel 17 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC17_MIN", "shortDesc": "RC channel 17 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC17_REV", "shortDesc": "RC channel 17 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC17_TRIM", "shortDesc": "RC channel 17 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC18_MAX", "shortDesc": "RC channel 18 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC18_MIN", "shortDesc": "RC channel 18 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC18_REV", "shortDesc": "RC channel 18 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC18_TRIM", "shortDesc": "RC channel 18 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for RC channel 1", "max": 2200.0, "min": 1500.0, "name": "RC1_MAX", "shortDesc": "RC channel 1 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for RC channel 1", "max": 1500.0, "min": 800.0, "name": "RC1_MIN", "shortDesc": "RC channel 1 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC1_REV", "shortDesc": "RC channel 1 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC1_TRIM", "shortDesc": "RC channel 1 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC2_MAX", "shortDesc": "RC channel 2 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC2_MIN", "shortDesc": "RC channel 2 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC2_REV", "shortDesc": "RC channel 2 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC2_TRIM", "shortDesc": "RC channel 2 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC3_MAX", "shortDesc": "RC channel 3 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC3_MIN", "shortDesc": "RC channel 3 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC3_REV", "shortDesc": "RC channel 3 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC3_TRIM", "shortDesc": "RC channel 3 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC4_MAX", "shortDesc": "RC channel 4 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC4_MIN", "shortDesc": "RC channel 4 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC4_REV", "shortDesc": "RC channel 4 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC4_TRIM", "shortDesc": "RC channel 4 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC5_MAX", "shortDesc": "RC channel 5 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC5_MIN", "shortDesc": "RC channel 5 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC5_REV", "shortDesc": "RC channel 5 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC5_TRIM", "shortDesc": "RC channel 5 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC6_MAX", "shortDesc": "RC channel 6 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC6_MIN", "shortDesc": "RC channel 6 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC6_REV", "shortDesc": "RC channel 6 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC6_TRIM", "shortDesc": "RC channel 6 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC7_MAX", "shortDesc": "RC channel 7 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC7_MIN", "shortDesc": "RC channel 7 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC7_REV", "shortDesc": "RC channel 7 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC7_TRIM", "shortDesc": "RC channel 7 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC8_MAX", "shortDesc": "RC channel 8 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC8_MIN", "shortDesc": "RC channel 8 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC8_REV", "shortDesc": "RC channel 8 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC8_TRIM", "shortDesc": "RC channel 8 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC9_MAX", "shortDesc": "RC channel 9 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC9_MIN", "shortDesc": "RC channel 9 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC9_REV", "shortDesc": "RC channel 9 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC9_TRIM", "shortDesc": "RC channel 9 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "This parameter is used by Ground Station software to save the number\nof channels which were used during RC calibration. It is only meant\nfor ground station use.", "max": 18, "min": 0, "name": "RC_CHAN_CNT", "shortDesc": "RC channel count", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Use RC_MAP_FAILSAFE to specify which channel is used to indicate RC loss via this threshold.\nBy default this is the throttle channel.\nSet to a PWM value slightly above the PWM value for the channel (e.g. throttle) in a failsafe event,\nbut below the minimum PWM value for the channel during normal operation.\nNote: The default value of 0 disables the feature (it is below the expected range).", "max": 2200, "min": 0, "name": "RC_FAILS_THR", "shortDesc": "Failsafe channel PWM threshold", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX1", "shortDesc": "AUX1 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX2", "shortDesc": "AUX2 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX3", "shortDesc": "AUX3 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX4", "shortDesc": "AUX4 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX5", "shortDesc": "AUX5 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX6", "shortDesc": "AUX6 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_ENG_MOT", "shortDesc": "RC channel to engage the main motor (for helicopters)", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Configures which RC channel is used by the receiver to indicate the signal was lost\n(on receivers that use output a fixed signal value to report lost signal).\nIf set to 0, the channel mapped to throttle is used.\nUse RC_FAILS_THR to set the threshold indicating lost signal. By default it's below\nthe expected range and hence disabled.", "max": 18, "min": 0, "name": "RC_MAP_FAILSAFE", "shortDesc": "Failsafe channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel.\nSet to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM1", "shortDesc": "PARAM1 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel.\nSet to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM2", "shortDesc": "PARAM2 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel.\nSet to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM3", "shortDesc": "PARAM3 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates\nwhich channel should be used for reading pitch inputs from.\nA value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_PITCH", "shortDesc": "Pitch control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates\nwhich channel should be used for reading roll inputs from.\nA value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_ROLL", "shortDesc": "Roll control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates\nwhich channel should be used for reading throttle inputs from.\nA value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_THROTTLE", "shortDesc": "Throttle control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates\nwhich channel should be used for reading yaw inputs from.\nA value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_YAW", "shortDesc": "Yaw control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "0: do not read RSSI from input channel\n1-18: read RSSI from specified input channel\nSpecify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters.", "max": 18, "min": 0, "name": "RC_RSSI_PWM_CHAN", "shortDesc": "PWM input channel that provides RSSI", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 2000, "group": "Radio Calibration", "longDesc": "Only used if RC_RSSI_PWM_CHAN > 0", "max": 2000, "min": 0, "name": "RC_RSSI_PWM_MAX", "shortDesc": "Max input value for RSSI reading", "type": "Int32"}, {"category": "Standard", "default": 1000, "group": "Radio Calibration", "longDesc": "Only used if RC_RSSI_PWM_CHAN > 0", "max": 2000, "min": 0, "name": "RC_RSSI_PWM_MIN", "shortDesc": "Min input value for RSSI reading", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs\nfor straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_PITCH", "shortDesc": "Pitch trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs\nfor straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_ROLL", "shortDesc": "Roll trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs\nfor straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_YAW", "shortDesc": "Yaw trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.75, "group": "Radio Switches", "longDesc": "0-1 indicate where in the full channel range the threshold sits\n0 : min\n1 : max\nsign indicates polarity of comparison\npositive : true when channel>th\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channel The rover starts to cut the corner earlier.", "max": 100.0, "min": 1.0, "name": "RA_ACC_RAD_GAIN", "shortDesc": "Tuning parameter for corner cutting", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Ackermann", "increment": 0.01, "longDesc": "The controller scales the acceptance radius based on the angle between\nthe previous, current and next waypoint.\nHigher value -> smoother trajectory at the cost of how close the rover gets\nto the waypoint (Set to -1 to disable corner cutting).", "max": 100.0, "min": -1.0, "name": "RA_ACC_RAD_MAX", "shortDesc": "Maximum acceptance radius for the waypoints", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Ackermann", "increment": 0.01, "max": 1.5708, "min": 0.0, "name": "RA_MAX_STR_ANG", "shortDesc": "Maximum steering angle", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Ackermann", "increment": 0.01, "longDesc": "Set to -1 to disable.", "max": 1000.0, "min": -1.0, "name": "RA_STR_RATE_LIM", "shortDesc": "Steering rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Ackermann", "increment": 0.001, "longDesc": "Distance from the front to the rear axle.", "max": 100.0, "min": 0.0, "name": "RA_WHEEL_BASE", "shortDesc": "Wheel base", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Attitude Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_P", "shortDesc": "Proportional gain for closed loop yaw controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.174533, "group": "Rover Differential", "increment": 0.01, "longDesc": "This threshold is used for the state machine to switch from driving to turning based on the\nerror between the desired and actual yaw. It is also used as the threshold whether the rover should come\nto a smooth stop at the next waypoint. This slow down effect is active if the angle between the\nline segments from prevWP-currWP and currWP-nextWP is smaller then 180 - RD_TRANS_DRV_TRN.", "max": 3.14159, "min": 0.001, "name": "RD_TRANS_DRV_TRN", "shortDesc": "Yaw error threshhold to switch from driving to spot turning", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0872665, "group": "Rover Differential", "increment": 0.01, "longDesc": "This threshold is used for the state machine to switch from turning to driving based on the\nerror between the desired and actual yaw.", "max": 3.14159, "min": 0.001, "name": "RD_TRANS_TRN_DRV", "shortDesc": "Yaw error threshhold to switch from spot turning to driving", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Differential", "increment": 0.001, "longDesc": "Distance from the center of the right wheel to the center of the left wheel.", "max": 100.0, "min": 0.0, "name": "RD_WHEEL_TRACK", "shortDesc": "Wheel track", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Rover Differential", "increment": 0.01, "longDesc": "Assign value <1.0 to decrease stick response for yaw control.", "max": 1.0, "min": 0.1, "name": "RD_YAW_STK_GAIN", "shortDesc": "Yaw stick gain for Manual mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.17, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "Threshold for the angle between the active cruise direction and the cruise direction given\nby the stick inputs.\nThis can be understood as a deadzone for the combined stick inputs for forward/backwards\nand lateral speed which defines a course direction.", "max": 3.14, "min": 0.0, "name": "RM_COURSE_CTL_TH", "shortDesc": "Threshold to update course control in manual position mode", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Mecanum", "increment": 0.001, "longDesc": "Distance from the center of the right wheel to the center of the left wheel.", "max": 100.0, "min": 0.0, "name": "RM_WHEEL_TRACK", "shortDesc": "Wheel track", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "Assign value <1.0 to decrease stick response for yaw control.", "max": 1.0, "min": 0.1, "name": "RM_YAW_STK_GAIN", "shortDesc": "Yaw stick gain for Manual mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap how quickly the magnitude of yaw rate setpoints can increase.\nSet to -1 to disable.", "max": 10000.0, "min": -1.0, "name": "RO_YAW_ACCEL_LIM", "shortDesc": "Yaw acceleration limit", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap how quickly the magnitude of yaw rate setpoints can decrease.\nSet to -1 to disable.", "max": 10000.0, "min": -1.0, "name": "RO_YAW_DECEL_LIM", "shortDesc": "Yaw deceleration limit", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Rate Control", "longDesc": "Exponential factor for tuning the input curve shape.\n0 Purely linear input curve\n1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "RO_YAW_EXPO", "shortDesc": "Yaw rate expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Multiplicative correction factor for the feedforward mapping of the yaw rate controller.\nIncrease this value (x > 1) if the measured yaw rate is lower than the setpoint, decrease (0 < x < 1) otherwise.\nNote: Tuning this is particularly useful for skid-steered rovers, or rovers with misaligned wheels/steering axes\nthat cause a lot of friction when turning.", "max": 10000.0, "min": 0.01, "name": "RO_YAW_RATE_CORR", "shortDesc": "Yaw rate correction factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_I", "shortDesc": "Integral gain for closed loop yaw rate controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap yaw rate setpoints and map controller inputs to yaw rate setpoints\nin Acro, Stabilized and Position mode.", "max": 10000.0, "min": 0.0, "name": "RO_YAW_RATE_LIM", "shortDesc": "Yaw rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_P", "shortDesc": "Proportional gain for closed loop yaw rate controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "The minimum threshold for the yaw rate measurement not to be interpreted as zero.", "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_TH", "shortDesc": "Yaw rate measurement threshold", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Percentage of stick input range that will be interpreted as zero around the stick centered value.", "max": 1.0, "min": 0.0, "name": "RO_YAW_STICK_DZ", "shortDesc": "Yaw stick deadzone", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Rate Control", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using RO_YAW_EXPO.\n0 Pure Expo function\n0.7 reasonable shape enhancement for intuitive stick feel\n0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "RO_YAW_SUPEXPO", "shortDesc": "Yaw rate super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable.\nFor mecanum rovers this limit is used for longitudinal and lateral acceleration.", "max": 100.0, "min": -1.0, "name": "RO_ACCEL_LIM", "shortDesc": "Acceleration limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable.\nNote that if it is disabled the rover will not slow down when approaching waypoints in auto modes.\nFor mecanum rovers this limit is used for longitudinal and lateral deceleration.", "max": 100.0, "min": -1.0, "name": "RO_DECEL_LIM", "shortDesc": "Deceleration limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable.\nNote that if it is disabled the rover will not slow down when approaching waypoints in auto modes.\nFor mecanum rovers this limit is used for longitudinal and lateral jerk.", "max": 100.0, "min": -1.0, "name": "RO_JERK_LIM", "shortDesc": "Jerk limit", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Used to linearly map speeds [m/s] to throttle values [-1. 1].", "max": 100.0, "min": 0.0, "name": "RO_MAX_THR_SPEED", "shortDesc": "Speed the rover drives at maximum throttle", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.001, "max": 100.0, "min": 0.0, "name": "RO_SPEED_I", "shortDesc": "Integral gain for ground speed controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Used to cap speed setpoints and map controller inputs to speed setpoints in Position mode.", "max": 100.0, "min": -1.0, "name": "RO_SPEED_LIM", "shortDesc": "Speed limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_SPEED_P", "shortDesc": "Proportional gain for ground speed controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Reduced_speed = RO_MAX_THR_SPEED * (1 - normalized_course_error * RO_SPEED_RED)\nThe normalized course error is the angle between the current course and the bearing setpoint\ninterpolated from [0, 180] -> [0, 1].\nHigher value -> More speed reduction.\nNote: This is also used to calculate the speed at which the vehicle arrives at a waypoint in auto modes.\nSet to -1 to disable bearing error based speed reduction.", "max": 100.0, "min": -1.0, "name": "RO_SPEED_RED", "shortDesc": "Tuning parameter for the speed reduction based on the course error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable.\nThe minimum threshold for the speed measurement not to be interpreted as zero.", "max": 100.0, "min": 0.0, "name": "RO_SPEED_TH", "shortDesc": "Speed measurement threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Runway Takeoff", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "RWTO_MAX_THR", "shortDesc": "Throttle during runway takeoff", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 1, "group": "Runway Takeoff", "longDesc": "This is useful when map, GNSS, or yaw errors on ground are misaligned with what the operator intends for takeoff course.\nParticularly useful for skinny runways or if the wheel servo is a bit off trim.", "name": "RWTO_NUDGE", "shortDesc": "Enable use of yaw stick for nudging the wheel during runway ground roll", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Runway Takeoff", "increment": 0.5, "longDesc": "A taildragger with steerable wheel might need to pitch up\na little to keep its wheel on the ground before airspeed\nto takeoff is reached.", "max": 20.0, "min": -10.0, "name": "RWTO_PSP", "shortDesc": "Pitch setpoint during taxi / before takeoff rotation airspeed is reached", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Runway Takeoff", "increment": 0.1, "max": 15.0, "min": 1.0, "name": "RWTO_RAMP_TIME", "shortDesc": "Throttle ramp up time for runway takeoff", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Runway Takeoff", "increment": 0.1, "longDesc": "The calibrated airspeed threshold during the takeoff ground roll when the plane should start rotating (pitching up).\nMust be less than the takeoff airspeed, will otherwise be capped at the takeoff airpeed (see FW_TKO_AIRSPD).\nIf set <= 0.0, defaults to 0.9 * takeoff airspeed (see FW_TKO_AIRSPD)", "min": -1.0, "name": "RWTO_ROT_AIRSPD", "shortDesc": "Takeoff rotation airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Runway Takeoff", "increment": 0.1, "longDesc": "This is the time desired to linearly ramp in takeoff pitch constraints during the takeoff rotation", "min": 0.1, "name": "RWTO_ROT_TIME", "shortDesc": "Takeoff rotation time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Runway Takeoff", "name": "RWTO_TKOFF", "shortDesc": "Runway takeoff with landing gear", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"bitmask": [{"description": "SD card logging", "index": 0}, {"description": "Mavlink logging", "index": 1}], "category": "Standard", "default": 3, "group": "SD Logging", "longDesc": "If no logging is set the logger will not be started. Set bits true to enable: 0: SD card logging 1: Mavlink logging", "max": 3, "min": 0, "name": "SDLOG_BACKEND", "rebootRequired": true, "shortDesc": "Logging Backend (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "When enabled, logging will not start from boot if battery power is not detected (e.g. powered via USB on a test bench). This prevents extraneous flight logs from being created during bench testing. Note that this only applies to log-from-boot modes. This has no effect on arm-based modes.", "name": "SDLOG_BOOT_BAT", "shortDesc": "Battery-only Logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum. Note: this does not apply to mission log files.", "max": 1000, "min": 0, "name": "SDLOG_DIRS_MAX", "rebootRequired": true, "shortDesc": "Maximum number of log directories to keep", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "If enabled, a small additional \"mission\" log file will be written to the SD card. The log contains just those messages that are useful for tasks like generating flight statistics and geotagging. The different modes can be used to further reduce the logged data (and thus the log file size). For example, choose geotagging mode to only log data required for geotagging. Note that the normal/full log is still created, and contains all the data in the mission log (and more).", "name": "SDLOG_MISSION", "rebootRequired": true, "shortDesc": "Mission Log", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "All mission messages", "value": 1}, {"description": "Geotagging messages", "value": 2}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming. Note: The logging start/end points that can be configured here only apply to SD logging. The mavlink backend is started/stopped independently of these points.", "name": "SDLOG_MODE", "rebootRequired": true, "shortDesc": "Logging Mode", "type": "Int32", "values": [{"description": "when armed until disarm (default)", "value": 0}, {"description": "from boot until disarm", "value": 1}, {"description": "from boot until shutdown", "value": 2}, {"description": "while manual input AUX1 >30%", "value": 3}, {"description": "from 1st armed until shutdown", "value": 4}]}, {"bitmask": [{"description": "Default set (general log analysis)", "index": 0}, {"description": "Estimator replay (EKF2)", "index": 1}, {"description": "Thermal calibration", "index": 2}, {"description": "System identification", "index": 3}, {"description": "High rate", "index": 4}, {"description": "Debug", "index": 5}, {"description": "Sensor comparison", "index": 6}, {"description": "Computer Vision and Avoidance", "index": 7}, {"description": "Raw FIFO high-rate IMU (Gyro)", "index": 8}, {"description": "Raw FIFO high-rate IMU (Accel)", "index": 9}, {"description": "Mavlink tunnel message logging", "index": 10}, {"description": "High rate sensors", "index": 11}], "category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "This integer bitmask controls the set and rates of logged topics. The default allows for general log analysis while keeping the log file size reasonably small. Enabling multiple sets leads to higher bandwidth requirements and larger log files. Set bits true to enable: 0 : Default set (used for general log analysis) 1 : Full rate estimator (EKF2) replay topics 2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data) 3 : Topics for system identification (high rate actuator control and IMU data) 4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) 5 : Debugging topics (debug_*.msg topics, for custom code) 6 : Topics for sensor comparison (low rate raw IMU, Baro and magnetometer data) 7 : Topics for computer vision and collision prevention 8 : Raw FIFO high-rate IMU (Gyro) 9 : Raw FIFO high-rate IMU (Accel) 10: Logging of mavlink tunnel message (useful for payload communication debugging)", "max": 4095, "min": 0, "name": "SDLOG_PROFILE", "rebootRequired": true, "shortDesc": "Logging topic profile (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets", "max": 1000, "min": -1000, "name": "SDLOG_UTC_OFFSET", "shortDesc": "UTC offset (unit: min)", "type": "Int32", "units": "min"}, {"category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "If set to 1, add an ID to the log, which uniquely identifies the vehicle", "name": "SDLOG_UUID", "shortDesc": "Log UUID", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 60.0, "group": "SITL", "increment": 1.0, "max": 86400.0, "min": 1.0, "name": "SIM_BAT_DRAIN", "shortDesc": "Simulator Battery drain interval", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "SITL", "longDesc": "Enable or disable the internal battery simulation. This is useful\nwhen the battery is simulated externally and interfaced with PX4\nthrough MAVLink for example.", "name": "SIM_BAT_ENABLE", "shortDesc": "Simulator Battery enabled", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 50.0, "group": "SITL", "increment": 0.1, "longDesc": "Can be used to alter the battery level during SITL- or HITL-simulation on the fly.\nParticularly useful for testing different low-battery behaviour.", "max": 100.0, "min": 0.0, "name": "SIM_BAT_MIN_PCT", "shortDesc": "Simulator Battery minimal percentage", "type": "Float", "units": "%"}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC0_ID", "shortDesc": "Accelerometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC0_PRIO", "shortDesc": "Accelerometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC0_ROT", "shortDesc": "Accelerometer 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_XOFF", "shortDesc": "Accelerometer 0 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_XSCALE", "shortDesc": "Accelerometer 0 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_YOFF", "shortDesc": "Accelerometer 0 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_YSCALE", "shortDesc": "Accelerometer 0 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_ZOFF", "shortDesc": "Accelerometer 0 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_ZSCALE", "shortDesc": "Accelerometer 0 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC1_ID", "shortDesc": "Accelerometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC1_PRIO", "shortDesc": "Accelerometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC1_ROT", "shortDesc": "Accelerometer 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_XOFF", "shortDesc": "Accelerometer 1 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_XSCALE", "shortDesc": "Accelerometer 1 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_YOFF", "shortDesc": "Accelerometer 1 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_YSCALE", "shortDesc": "Accelerometer 1 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_ZOFF", "shortDesc": "Accelerometer 1 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_ZSCALE", "shortDesc": "Accelerometer 1 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC2_ID", "shortDesc": "Accelerometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC2_PRIO", "shortDesc": "Accelerometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC2_ROT", "shortDesc": "Accelerometer 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_XOFF", "shortDesc": "Accelerometer 2 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_XSCALE", "shortDesc": "Accelerometer 2 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_YOFF", "shortDesc": "Accelerometer 2 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_YSCALE", "shortDesc": "Accelerometer 2 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_ZOFF", "shortDesc": "Accelerometer 2 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_ZSCALE", "shortDesc": "Accelerometer 2 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC3_ID", "shortDesc": "Accelerometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC3_PRIO", "shortDesc": "Accelerometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC3_ROT", "shortDesc": "Accelerometer 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_XOFF", "shortDesc": "Accelerometer 3 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_XSCALE", "shortDesc": "Accelerometer 3 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_YOFF", "shortDesc": "Accelerometer 3 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_YSCALE", "shortDesc": "Accelerometer 3 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_ZOFF", "shortDesc": "Accelerometer 3 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_ZSCALE", "shortDesc": "Accelerometer 3 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO0_ID", "shortDesc": "Barometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO0_OFF", "shortDesc": "Barometer 0 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO0_PRIO", "shortDesc": "Barometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO1_ID", "shortDesc": "Barometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO1_OFF", "shortDesc": "Barometer 1 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO1_PRIO", "shortDesc": "Barometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO2_ID", "shortDesc": "Barometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO2_OFF", "shortDesc": "Barometer 2 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO2_PRIO", "shortDesc": "Barometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO3_ID", "shortDesc": "Barometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO3_OFF", "shortDesc": "Barometer 3 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO3_PRIO", "shortDesc": "Barometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO0_ID", "shortDesc": "Gyroscope 0 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO0_PRIO", "shortDesc": "Gyroscope 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO0_ROT", "shortDesc": "Gyroscope 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_XOFF", "shortDesc": "Gyroscope 0 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_YOFF", "shortDesc": "Gyroscope 0 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_ZOFF", "shortDesc": "Gyroscope 0 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO1_ID", "shortDesc": "Gyroscope 1 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO1_PRIO", "shortDesc": "Gyroscope 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO1_ROT", "shortDesc": "Gyroscope 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_XOFF", "shortDesc": "Gyroscope 1 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_YOFF", "shortDesc": "Gyroscope 1 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_ZOFF", "shortDesc": "Gyroscope 1 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO2_ID", "shortDesc": "Gyroscope 2 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO2_PRIO", "shortDesc": "Gyroscope 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO2_ROT", "shortDesc": "Gyroscope 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_XOFF", "shortDesc": "Gyroscope 2 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_YOFF", "shortDesc": "Gyroscope 2 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_ZOFF", "shortDesc": "Gyroscope 2 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO3_ID", "shortDesc": "Gyroscope 3 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO3_PRIO", "shortDesc": "Gyroscope 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO3_ROT", "shortDesc": "Gyroscope 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_XOFF", "shortDesc": "Gyroscope 3 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_YOFF", "shortDesc": "Gyroscope 3 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_ZOFF", "shortDesc": "Gyroscope 3 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG0_ID", "shortDesc": "Magnetometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_PITCH", "shortDesc": "Magnetometer 0 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG0_PRIO", "shortDesc": "Magnetometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_ROLL", "shortDesc": "Magnetometer 0 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.\nSet to \"Custom Euler Angle\" to define the rotation using CAL_MAG0_ROLL, CAL_MAG0_PITCH and CAL_MAG0_YAW.", "max": 100, "min": -1, "name": "CAL_MAG0_ROT", "shortDesc": "Magnetometer 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nX component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG0_XCOMP", "shortDesc": "Magnetometer 0 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_XODIAG", "shortDesc": "Magnetometer 0 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_XOFF", "shortDesc": "Magnetometer 0 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_XSCALE", "shortDesc": "Magnetometer 0 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_YAW", "shortDesc": "Magnetometer 0 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nY component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG0_YCOMP", "shortDesc": "Magnetometer 0 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_YODIAG", "shortDesc": "Magnetometer 0 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_YOFF", "shortDesc": "Magnetometer 0 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_YSCALE", "shortDesc": "Magnetometer 0 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nZ component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG0_ZCOMP", "shortDesc": "Magnetometer 0 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_ZODIAG", "shortDesc": "Magnetometer 0 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_ZOFF", "shortDesc": "Magnetometer 0 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_ZSCALE", "shortDesc": "Magnetometer 0 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG1_ID", "shortDesc": "Magnetometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_PITCH", "shortDesc": "Magnetometer 1 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG1_PRIO", "shortDesc": "Magnetometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_ROLL", "shortDesc": "Magnetometer 1 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.\nSet to \"Custom Euler Angle\" to define the rotation using CAL_MAG1_ROLL, CAL_MAG1_PITCH and CAL_MAG1_YAW.", "max": 100, "min": -1, "name": "CAL_MAG1_ROT", "shortDesc": "Magnetometer 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nX component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG1_XCOMP", "shortDesc": "Magnetometer 1 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_XODIAG", "shortDesc": "Magnetometer 1 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_XOFF", "shortDesc": "Magnetometer 1 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_XSCALE", "shortDesc": "Magnetometer 1 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_YAW", "shortDesc": "Magnetometer 1 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nY component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG1_YCOMP", "shortDesc": "Magnetometer 1 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_YODIAG", "shortDesc": "Magnetometer 1 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_YOFF", "shortDesc": "Magnetometer 1 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_YSCALE", "shortDesc": "Magnetometer 1 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nZ component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG1_ZCOMP", "shortDesc": "Magnetometer 1 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_ZODIAG", "shortDesc": "Magnetometer 1 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_ZOFF", "shortDesc": "Magnetometer 1 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_ZSCALE", "shortDesc": "Magnetometer 1 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG2_ID", "shortDesc": "Magnetometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_PITCH", "shortDesc": "Magnetometer 2 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG2_PRIO", "shortDesc": "Magnetometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_ROLL", "shortDesc": "Magnetometer 2 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.\nSet to \"Custom Euler Angle\" to define the rotation using CAL_MAG2_ROLL, CAL_MAG2_PITCH and CAL_MAG2_YAW.", "max": 100, "min": -1, "name": "CAL_MAG2_ROT", "shortDesc": "Magnetometer 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nX component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG2_XCOMP", "shortDesc": "Magnetometer 2 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_XODIAG", "shortDesc": "Magnetometer 2 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_XOFF", "shortDesc": "Magnetometer 2 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_XSCALE", "shortDesc": "Magnetometer 2 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_YAW", "shortDesc": "Magnetometer 2 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nY component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG2_YCOMP", "shortDesc": "Magnetometer 2 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_YODIAG", "shortDesc": "Magnetometer 2 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_YOFF", "shortDesc": "Magnetometer 2 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_YSCALE", "shortDesc": "Magnetometer 2 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nZ component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG2_ZCOMP", "shortDesc": "Magnetometer 2 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_ZODIAG", "shortDesc": "Magnetometer 2 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_ZOFF", "shortDesc": "Magnetometer 2 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_ZSCALE", "shortDesc": "Magnetometer 2 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG3_ID", "shortDesc": "Magnetometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_PITCH", "shortDesc": "Magnetometer 3 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG3_PRIO", "shortDesc": "Magnetometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_ROLL", "shortDesc": "Magnetometer 3 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.\nSet to \"Custom Euler Angle\" to define the rotation using CAL_MAG3_ROLL, CAL_MAG3_PITCH and CAL_MAG3_YAW.", "max": 100, "min": -1, "name": "CAL_MAG3_ROT", "shortDesc": "Magnetometer 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nX component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG3_XCOMP", "shortDesc": "Magnetometer 3 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_XODIAG", "shortDesc": "Magnetometer 3 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_XOFF", "shortDesc": "Magnetometer 3 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_XSCALE", "shortDesc": "Magnetometer 3 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_YAW", "shortDesc": "Magnetometer 3 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nY component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG3_YCOMP", "shortDesc": "Magnetometer 3 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_YODIAG", "shortDesc": "Magnetometer 3 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_YOFF", "shortDesc": "Magnetometer 3 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_YSCALE", "shortDesc": "Magnetometer 3 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nZ component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG3_ZCOMP", "shortDesc": "Magnetometer 3 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_ZODIAG", "shortDesc": "Magnetometer 3 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_ZOFF", "shortDesc": "Magnetometer 3 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_ZSCALE", "shortDesc": "Magnetometer 3 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "name": "CAL_MAG_COMP_TYP", "shortDesc": "Type of magnetometer compensation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Throttle-based compensation", "value": 1}, {"description": "Current-based compensation (battery_status instance 0)", "value": 2}, {"description": "Current-based compensation (battery_status instance 1)", "value": 3}]}, {"category": "Standard", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Pick the appropriate scaling from the datasheet.\nthis number defines the (linear) conversion from voltage\nto Pascal (pa). For the MPXV7002DP this is 1000.\nNOTE: If the sensor always registers zero, try switching\nthe static and dynamic tubes.", "name": "SENS_DPRES_ANSC", "shortDesc": "Differential pressure sensor analog scaling", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "The offset (zero-reading) in Pascal", "name": "SENS_DPRES_OFF", "shortDesc": "Differential pressure sensor offset", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Reverse the raw measurements of all differential pressure sensors.\nThis can be enabled if the sensors have static and dynamic ports swapped.", "name": "SENS_DPRES_REV", "shortDesc": "Reverse differential pressure sensor readings", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 100.0, "group": "Sensor Calibration", "increment": 0.1, "longDesc": "This parameter defines the maximum distance from ground at which the optical flow sensor operates reliably.\nThe height setpoint will be limited to be no greater than this value when the navigation system\nis completely reliant on optical flow data and the height above ground estimate is valid.\nThe sensor may be usable above this height, but accuracy will progressively degrade.", "max": 100.0, "min": 1.0, "name": "SENS_FLOW_MAXHGT", "shortDesc": "Maximum height above ground when reliant on optical flow", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 8.0, "group": "Sensor Calibration", "longDesc": "Optical flow data will not fused by the estimators if the magnitude of the flow rate exceeds this value and\ncontrol loops will be instructed to limit ground speed such that the flow rate produced by movement over ground\nis less than 50% of this value.", "min": 1.0, "name": "SENS_FLOW_MAXR", "shortDesc": "Magnitude of maximum angular flow rate reliably measurable by the optical flow sensor", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Sensor Calibration", "increment": 0.1, "longDesc": "This parameter defines the minimum distance from ground at which the optical flow sensor operates reliably.\nThe sensor may be usable below this height, but accuracy will progressively reduce to loss of focus.", "max": 1.0, "min": 0.0, "name": "SENS_FLOW_MINHGT", "shortDesc": "Minimum height above ground when reliant on optical flow", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "Model with Pitot\nCAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed.\nCAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor.\nModel without Pitot (1.5 mm tubes)\nCAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed.\nCAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor.\nTube Pressure Drop\nCAL_AIR_TUBED_MM: Diameter in mm of the pitot and tubes, must have the same diameter.\nCAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor and the static + dynamic port length of the pitot.", "name": "CAL_AIR_CMODEL", "shortDesc": "Airspeed sensor compensation model for the SDP3x", "type": "Int32", "values": [{"description": "Model with Pitot", "value": 0}, {"description": "Model without Pitot (1.5 mm tubes)", "value": 1}, {"description": "Tube Pressure Drop", "value": 2}]}, {"category": "Standard", "default": 1.5, "group": "Sensors", "max": 100.0, "min": 1.5, "name": "CAL_AIR_TUBED_MM", "shortDesc": "Airspeed sensor tube diameter. Only used for the Tube Pressure Drop Compensation", "type": "Float", "units": "mm"}, {"category": "Standard", "default": 0.2, "group": "Sensors", "longDesc": "See the CAL_AIR_CMODEL explanation on how this parameter should be set.", "max": 2.0, "min": 0.01, "name": "CAL_AIR_TUBELEN", "shortDesc": "Airspeed sensor tube length", "type": "Float", "units": "m"}, {"category": "Developer", "default": 63, "group": "Sensors", "longDesc": "Use SENS_MAG_SIDES instead", "name": "CAL_MAG_SIDES", "shortDesc": "For legacy QGC support only", "type": "Int32"}, {"category": "Standard", "default": 30.0, "group": "Sensors", "longDesc": "The cutoff frequency for the 2nd order butterworth filter on the primary accelerometer.\nThis only affects the signal sent to the controllers, not the estimators. 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_ACCEL_CUTOFF", "rebootRequired": true, "shortDesc": "Low pass filter cutoff frequency for accel", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The cutoff frequency for the 2nd order butterworth filter used on\nthe time derivative of the measured angular velocity, also known as\nthe D-term filter in the rate controller. The D-term uses the derivative of\nthe rate and thus is the most susceptible to noise. Therefore, using\na D-term filter allows to increase IMU_GYRO_CUTOFF, which\nleads to reduced control latency and permits to increase the P gains.\nA value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_DGYRO_CUTOFF", "rebootRequired": true, "shortDesc": "Cutoff frequency for angular acceleration (D-Term filter)", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 1, "group": "Sensors", "name": "IMU_GYRO_CAL_EN", "rebootRequired": true, "shortDesc": "IMU gyro auto calibration enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Sensors", "increment": 0.1, "longDesc": "The cutoff frequency for the 2nd order butterworth filter on the primary gyro.\nThis only affects the angular velocity sent to the controllers, not the estimators.\nIt applies also to the angular acceleration (D-Term filter), see IMU_DGYRO_CUTOFF.\nA value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_CUTOFF", "rebootRequired": true, "shortDesc": "Low pass filter cutoff frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "Sensors", "increment": 0.1, "longDesc": "Bandwidth per notch filter when using dynamic notch filtering with ESC RPM.", "max": 30.0, "min": 5.0, "name": "IMU_GYRO_DNF_BW", "shortDesc": "IMU gyro ESC notch filter bandwidth", "type": "Float", "units": "Hz"}, {"bitmask": [{"description": "ESC RPM", "index": 0}, {"description": "FFT", "index": 1}], "category": "Standard", "default": 0, "group": "Sensors", "longDesc": "Enable bank of dynamically updating notch filters.\nRequires ESC RPM feedback or onboard FFT (IMU_GYRO_FFT_EN).", "max": 3, "min": 0, "name": "IMU_GYRO_DNF_EN", "shortDesc": "IMU gyro dynamic notch filtering", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "Sensors", "longDesc": "ESC RPM number of harmonics (multiples of RPM) for ESC RPM dynamic notch filtering.", "max": 7, "min": 1, "name": "IMU_GYRO_DNF_HMC", "shortDesc": "IMU gyro dynamic notch filter harmonics", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "Sensors", "increment": 0.1, "longDesc": "Minimum notch filter frequency in Hz.", "name": "IMU_GYRO_DNF_MIN", "shortDesc": "IMU gyro dynamic notch filter minimum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "name": "IMU_GYRO_FFT_EN", "rebootRequired": true, "shortDesc": "IMU gyro FFT enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 512, "group": "Sensors", "name": "IMU_GYRO_FFT_LEN", "rebootRequired": true, "shortDesc": "IMU gyro FFT length", "type": "Int32", "units": "Hz", "values": [{"description": "256", "value": 256}, {"description": "512", "value": 512}, {"description": "1024", "value": 1024}, {"description": "4096", "value": 4096}]}, {"category": "Standard", "default": 150.0, "group": "Sensors", "max": 1000.0, "min": 1.0, "name": "IMU_GYRO_FFT_MAX", "rebootRequired": true, "shortDesc": "IMU gyro FFT maximum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 30.0, "group": "Sensors", "max": 1000.0, "min": 1.0, "name": "IMU_GYRO_FFT_MIN", "rebootRequired": true, "shortDesc": "IMU gyro FFT minimum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 10.0, "group": "Sensors", "max": 30.0, "min": 1.0, "name": "IMU_GYRO_FFT_SNR", "shortDesc": "IMU gyro FFT SNR", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The frequency width of the stop band for the 2nd order notch filter on the primary gyro.\nSee \"IMU_GYRO_NF0_FRQ\" to activate the filter and to set the notch frequency.\nApplies to both angular velocity and angular acceleration sent to the controllers.", "max": 100.0, "min": 0.0, "name": "IMU_GYRO_NF0_BW", "rebootRequired": true, "shortDesc": "Notch filter bandwidth for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "increment": 0.1, "longDesc": "The center frequency for the 2nd order notch filter on the primary gyro.\nThis filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency.\nThis only affects the signal sent to the controllers, not the estimators.\nApplies to both angular velocity and angular acceleration sent to the controllers.\nSee \"IMU_GYRO_NF0_BW\" to set the bandwidth of the filter.\nA value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_NF0_FRQ", "rebootRequired": true, "shortDesc": "Notch filter frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The frequency width of the stop band for the 2nd order notch filter on the primary gyro.\nSee \"IMU_GYRO_NF1_FRQ\" to activate the filter and to set the notch frequency.\nApplies to both angular velocity and angular acceleration sent to the controllers.", "max": 100.0, "min": 0.0, "name": "IMU_GYRO_NF1_BW", "rebootRequired": true, "shortDesc": "Notch filter 1 bandwidth for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "increment": 0.1, "longDesc": "The center frequency for the 2nd order notch filter on the primary gyro.\nThis filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency.\nThis only affects the signal sent to the controllers, not the estimators.\nApplies to both angular velocity and angular acceleration sent to the controllers.\nSee \"IMU_GYRO_NF1_BW\" to set the bandwidth of the filter.\nA value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_NF1_FRQ", "rebootRequired": true, "shortDesc": "Notch filter 2 frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 400, "group": "Sensors", "longDesc": "The maximum rate the gyro control data (vehicle_angular_velocity) will be\nallowed to publish at. This is the loop rate for the rate controller and outputs.\nNote: sensor data is always read and filtered at the full raw rate (eg commonly 8 kHz) regardless of this setting.", "max": 2000, "min": 100, "name": "IMU_GYRO_RATEMAX", "rebootRequired": true, "shortDesc": "Gyro control data maximum publication rate (inner loop rate)", "type": "Int32", "units": "Hz", "values": [{"description": "100 Hz", "value": 100}, {"description": "250 Hz", "value": 250}, {"description": "400 Hz", "value": 400}, {"description": "800 Hz", "value": 800}, {"description": "1000 Hz", "value": 1000}, {"description": "2000 Hz", "value": 2000}]}, {"category": "Standard", "default": 200, "group": "Sensors", "longDesc": "The rate at which raw IMU data is integrated to produce delta angles and delta velocities.\nRecommended to set this to a multiple of the estimator update period (currently 10 ms for ekf2).", "max": 1000, "min": 100, "name": "IMU_INTEG_RATE", "rebootRequired": true, "shortDesc": "IMU integration rate", "type": "Int32", "units": "Hz", "values": [{"description": "100 Hz", "value": 100}, {"description": "200 Hz", "value": 200}, {"description": "250 Hz", "value": 250}, {"description": "400 Hz", "value": 400}]}, {"category": "Standard", "default": 1013.25, "group": "Sensors", "max": 1500.0, "min": 500.0, "name": "SENS_BARO_QNH", "shortDesc": "QNH for barometer", "type": "Float", "units": "hPa"}, {"category": "Standard", "default": 20.0, "group": "Sensors", "longDesc": "Barometric air data maximum publication rate. This is an upper bound,\nactual barometric data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_BARO_RATE", "shortDesc": "Baro max rate", "type": "Float", "units": "Hz"}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically calibrate barometer based on the GNSS height", "name": "SENS_BAR_AUTOCAL", "shortDesc": "Barometer auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "This parameter defines the rotation of the FMU board relative to the platform.", "max": 40, "min": -1, "name": "SENS_BOARD_ROT", "rebootRequired": true, "shortDesc": "Board rotation", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "longDesc": "Rotation from flight controller board to vehicle body frame.\nThis parameter gets set during the \"level horizon\" calibration or can be\nset manually.", "max": 45.0, "min": -45.0, "name": "SENS_BOARD_X_OFF", "shortDesc": "Board rotation X (roll) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "longDesc": "Rotation from flight controller board to vehicle body frame.\nThis parameter gets set during the \"level horizon\" calibration or can be\nset manually.", "max": 45.0, "min": -45.0, "name": "SENS_BOARD_Y_OFF", "shortDesc": "Board rotation Y (pitch) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "longDesc": "Rotation from flight controller board to vehicle body frame.\nHas to be set manually (not set by any calibration).", "max": 45.0, "min": -45.0, "name": "SENS_BOARD_Z_OFF", "shortDesc": "Board rotation Z (yaw) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_AGPSIM", "rebootRequired": true, "shortDesc": "Simulate Aux Global Position (AGP)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_ARSPDSIM", "rebootRequired": true, "shortDesc": "Enable simulated airspeed sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_BAROSIM", "rebootRequired": true, "shortDesc": "Enable simulated barometer sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_GPSSIM", "rebootRequired": true, "shortDesc": "Enable simulated GPS sinstance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_MAGSIM", "rebootRequired": true, "shortDesc": "Enable simulated magnetometer sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": -1, "group": "Sensors", "name": "SENS_EN_THERMAL", "shortDesc": "Thermal control of sensor temperature", "type": "Int32", "values": [{"description": "Thermal control unavailable", "value": -1}, {"description": "Thermal control off", "value": 0}, {"description": "Thermal control enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Probe for optional external I2C devices.", "name": "SENS_EXT_I2C_PRB", "shortDesc": "External I2C probe", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 70.0, "group": "Sensors", "longDesc": "Optical flow data maximum publication rate. This is an upper bound,\nactual optical flow data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_FLOW_RATE", "rebootRequired": true, "shortDesc": "Optical flow max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "This parameter defines the yaw rotation of the optical flow relative to the vehicle body frame.\nZero rotation is defined as X on flow board pointing towards front of vehicle.", "name": "SENS_FLOW_ROT", "shortDesc": "Optical flow rotation", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Sensors", "max": 1.5, "min": 0.5, "name": "SENS_FLOW_SCALE", "shortDesc": "Optical flow scale factor", "type": "Float"}, {"bitmask": [{"description": "use speed accuracy", "index": 0}, {"description": "use hpos accuracy", "index": 1}, {"description": "use vpos accuracy", "index": 2}], "category": "Standard", "default": 7, "group": "Sensors", "longDesc": "Set bits in the following positions to set which GPS accuracy metrics will be used to calculate the blending weight. Set to zero to disable and always used first GPS instance.\n0 : Set to true to use speed accuracy\n1 : Set to true to use horizontal position accuracy\n2 : Set to true to use vertical position accuracy", "max": 7, "min": 0, "name": "SENS_GPS_MASK", "shortDesc": "Multi GPS Blending Control Mask", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "When no blending is active, this defines the preferred GPS receiver instance.\nThe GPS selection logic waits until the primary receiver is available to\nsend data to the EKF even if a secondary instance is already available.\nThe secondary instance is then only used if the primary one times out.\nAccepted values:\n-1 : Auto (equal priority for all instances)\n0 : Main serial GPS instance\n1 : Secondary serial GPS instance\n2-127 : UAVCAN module node ID\nThis parameter has no effect if blending is active.", "max": 127, "min": -1, "name": "SENS_GPS_PRIME", "shortDesc": "Multi GPS primary instance", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Sensors", "longDesc": "Sets the longest time constant that will be applied to the calculation of GPS position and height offsets used to correct data from multiple GPS data for steady state position differences.", "max": 100.0, "min": 1.0, "name": "SENS_GPS_TAU", "shortDesc": "Multi GPS Blending Time Constant", "type": "Float", "units": "s"}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically initialize IMU (accel/gyro) calibration from bias estimates if available.", "name": "SENS_IMU_AUTOCAL", "shortDesc": "IMU auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Notify the user if the IMU is clipping", "name": "SENS_IMU_CLPNOTI", "shortDesc": "IMU notify clipping", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "name": "SENS_IMU_MODE", "rebootRequired": true, "shortDesc": "Sensors hub IMU mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Publish primary IMU selection", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "For systems with an external barometer, this should be set to false to make sure that the external is used.", "name": "SENS_INT_BARO_EN", "rebootRequired": true, "shortDesc": "Enable internal barometers", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically initialize magnetometer calibration from bias estimate if available.", "name": "SENS_MAG_AUTOCAL", "shortDesc": "Magnetometer auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Sensors", "longDesc": "During calibration attempt to automatically determine the rotation of external magnetometers.", "name": "SENS_MAG_AUTOROT", "shortDesc": "Automatically set external rotations", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "name": "SENS_MAG_MODE", "rebootRequired": true, "shortDesc": "Sensors hub mag mode", "type": "Int32", "values": [{"description": "Publish all magnetometers", "value": 0}, {"description": "Publish primary magnetometer", "value": 1}]}, {"category": "Standard", "default": 15.0, "group": "Sensors", "longDesc": "Magnetometer data maximum publication rate. This is an upper bound,\nactual magnetometer data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_MAG_RATE", "rebootRequired": true, "shortDesc": "Magnetometer max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 63, "group": "Sensors", "longDesc": "If set to two side calibration, only the offsets are estimated, the scale\ncalibration is left unchanged. Thus an initial six side calibration is\nrecommended.\nBits:\nORIENTATION_TAIL_DOWN = 1\nORIENTATION_NOSE_DOWN = 2\nORIENTATION_LEFT = 4\nORIENTATION_RIGHT = 8\nORIENTATION_UPSIDE_DOWN = 16\nORIENTATION_RIGHTSIDE_UP = 32", "max": 63, "min": 34, "name": "SENS_MAG_SIDES", "shortDesc": "Bitfield selecting mag sides for calibration", "type": "Int32", "values": [{"description": "Two side calibration", "value": 34}, {"description": "Three side calibration", "value": 38}, {"description": "Six side calibration", "value": 63}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SIM_ARSPD_FAIL", "rebootRequired": true, "shortDesc": "Dynamically simulate failure of airspeed sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Septentrio", "longDesc": "By default, the receiver is automatically configured. Sometimes it may be used for multiple purposes.\nIf the offered parameters aren't sufficient, this parameter can be disabled to have full control of the receiver configuration.\nA good way to use this is to enable automatic configuration, let the receiver be configured, and then disable it to make manual adjustments.", "name": "SEP_AUTO_CONFIG", "rebootRequired": true, "shortDesc": "Toggle automatic receiver configuration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"bitmask": [{"description": "GPS", "index": 0}, {"description": "GLONASS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "SBAS", "index": 3}, {"description": "BeiDou", "index": 4}], "category": "Standard", "default": 0, "group": "Septentrio", "longDesc": "Choice of which constellations the receiver should use for PVT computation.\nWhen this is 0, the constellation usage isn't changed.", "max": 63, "min": 0, "name": "SEP_CONST_USAGE", "rebootRequired": true, "shortDesc": "Usage of different constellations", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Septentrio", "longDesc": "Log raw communication between the driver and connected receivers.\nFor example, \"To receiver\" will log all commands and corrections sent by the driver to the receiver.", "max": 3, "min": 0, "name": "SEP_DUMP_COMM", "shortDesc": "Log GPS communication data", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "From receiver", "value": 1}, {"description": "To receiver", "value": 2}, {"description": "Both", "value": 3}]}, {"category": "Standard", "default": 0, "group": "Septentrio", "longDesc": "Setup and expected use of the hardware.\n- Default: Use two receivers as completely separate instances.\n- Moving base: Use two receivers in a rover & moving base setup for heading.", "max": 1, "min": 0, "name": "SEP_HARDW_SETUP", "rebootRequired": true, "shortDesc": "Setup and expected use of the hardware", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Moving base", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Septentrio", "longDesc": "When the receiver is already set up to log data, this decides whether extra logged data should be added or overwrite existing data.", "name": "SEP_LOG_FORCE", "rebootRequired": true, "shortDesc": "Whether to overwrite or add to existing logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Septentrio", "longDesc": "Select the frequency at which the connected receiver should log data to its internal storage.", "max": 10, "min": 0, "name": "SEP_LOG_HZ", "rebootRequired": true, "shortDesc": "Logging frequency for the receiver", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "0.1 Hz", "value": 1}, {"description": "0.2 Hz", "value": 2}, {"description": "0.5 Hz", "value": 3}, {"description": "1 Hz", "value": 4}, {"description": "2 Hz", "value": 5}, {"description": "5 Hz", "value": 6}, {"description": "10 Hz", "value": 7}, {"description": "20 Hz", "value": 8}, {"description": "25 Hz", "value": 9}, {"description": "50 Hz", "value": 10}]}, {"category": "Standard", "default": 2, "group": "Septentrio", "longDesc": "Select the level of detail that needs to be logged by the receiver.", "max": 3, "min": 0, "name": "SEP_LOG_LEVEL", "rebootRequired": true, "shortDesc": "Logging level for the receiver", "type": "Int32", "values": [{"description": "Lite", "value": 0}, {"description": "Basic", "value": 1}, {"description": "Default", "value": 2}, {"description": "Full", "value": 3}]}, {"category": "Standard", "default": 1, "group": "Septentrio", "longDesc": "The output frequency of the main SBF blocks needed for PVT information.", "max": 3, "min": 0, "name": "SEP_OUTP_HZ", "rebootRequired": true, "shortDesc": "Output frequency of main SBF blocks", "type": "Int32", "values": [{"description": "5 Hz", "value": 0}, {"description": "10 Hz", "value": 1}, {"description": "20 Hz", "value": 2}, {"description": "25 Hz", "value": 3}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Septentrio", "longDesc": "Vertical offsets can be compensated for by adjusting the Pitch offset.\nNote that this can be interpreted as the \"roll\" angle in case the antennas are aligned along the perpendicular axis.\nThis occurs in situations where the two antenna ARPs may not be exactly at the same height in the vehicle reference frame.\nSince pitch is defined as the right-handed rotation about the vehicle Y axis,\na situation where the main antenna is mounted lower than the aux antenna (assuming the default antenna setup) will result in a positive pitch.", "max": 90.0, "min": -90.0, "name": "SEP_PITCH_OFFS", "rebootRequired": true, "shortDesc": "Pitch offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Septentrio", "longDesc": "Enable publication of satellite info (ORB_ID(satellite_info)) if possible.", "name": "SEP_SAT_INFO", "rebootRequired": true, "shortDesc": "Enable sat info", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "Septentrio", "longDesc": "The stream the autopilot sets up on the receiver to output the logging data.\nSet this to another value if the default stream is already used for another purpose.", "max": 10, "min": 1, "name": "SEP_STREAM_LOG", "rebootRequired": true, "shortDesc": "Logging stream used during automatic configuration", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Septentrio", "longDesc": "The stream the autopilot sets up on the receiver to output the main data.\nSet this to another value if the default stream is already used for another purpose.", "max": 10, "min": 1, "name": "SEP_STREAM_MAIN", "rebootRequired": true, "shortDesc": "Main stream used during automatic configuration", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Septentrio", "longDesc": "Heading offset angle for dual antenna GPS setups that support heading estimation.\nSet this to 0 if the antennas are parallel to the forward-facing direction\nof the vehicle and the rover antenna is in front.\nThe offset angle increases clockwise.\nSet this to 90 if the rover antenna is placed on the\nright side of the vehicle and the moving base antenna is on the left side.", "max": 360.0, "min": -360.0, "name": "SEP_YAW_OFFS", "rebootRequired": true, "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 4, "default": 100.0, "group": "Simulation In Hardware", "increment": 0.01, "max": 1000.0, "min": 0.0, "name": "SIH_DISTSNSR_MAX", "shortDesc": "distance sensor maximum range", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.01, "max": 10.0, "min": 0.0, "name": "SIH_DISTSNSR_MIN", "shortDesc": "distance sensor minimum range", "type": "Float", "units": "m"}, {"category": "Standard", "default": -1.0, "group": "Simulation In Hardware", "longDesc": "Absolute value superior to 10000 will disable distance sensor", "name": "SIH_DISTSNSR_OVR", "shortDesc": "if >= 0 the distance sensor measures will be overridden by this value", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nIt represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IXX", "shortDesc": "Vehicle inertia about X axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nThis value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IXY", "shortDesc": "Vehicle cross term inertia xy", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nThis value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IXZ", "shortDesc": "Vehicle cross term inertia xz", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nIt represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IYY", "shortDesc": "Vehicle inertia about Y axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nThis value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IYZ", "shortDesc": "Vehicle cross term inertia yz", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nIt represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IZZ", "shortDesc": "Vehicle inertia about Z axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "Physical coefficient representing the friction with air particules.\nThe greater this value, the slower the quad will move.\nDrag force function of velocity: D=-KDV*V.\nThe maximum freefall velocity can be computed as V=10*MASS/KDV [m/s]", "min": 0.0, "name": "SIH_KDV", "shortDesc": "First order drag coefficient", "type": "Float", "units": "N/(m/s)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "Physical coefficient representing the friction with air particules during rotations.\nThe greater this value, the slower the quad will rotate.\nAerodynamic moment function of body rate: Ma=-KDW*W_B.\nThis value can be set to 0 if unknown.", "min": 0.0, "name": "SIH_KDW", "shortDesc": "First order angular damper coefficient", "type": "Float", "units": "Nm/(rad/s)"}, {"category": "Standard", "decimalPlaces": 2, "default": 489.4, "group": "Simulation In Hardware", "increment": 0.01, "longDesc": "This value represents the Above Mean Sea Level (AMSL) altitude where the simulation begins.\nIf using FlightGear as a visual animation,\nthis value can be tweaked such that the vehicle lies on the ground at takeoff.\nLAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others\nto represent a physical ground location on Earth.", "max": 8848.0, "min": -420.0, "name": "SIH_LOC_H0", "shortDesc": "Initial AMSL ground altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 47.397742, "group": "Simulation In Hardware", "longDesc": "This value represents the North-South location on Earth where the simulation begins.\nLAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others\nto represent a physical ground location on Earth.", "max": 90.0, "min": -90.0, "name": "SIH_LOC_LAT0", "shortDesc": "Initial geodetic latitude", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 8.545594, "group": "Simulation In Hardware", "longDesc": "This value represents the East-West location on Earth where the simulation begins.\nLAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others\nto represent a physical ground location on Earth.", "max": 180.0, "min": -180.0, "name": "SIH_LOC_LON0", "shortDesc": "Initial geodetic longitude", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the arm length generating the pitching moment\nThis value can be measured with a ruler.\nThis corresponds to half the distance between the front and rear motors.", "min": 0.0, "name": "SIH_L_PITCH", "shortDesc": "Pitch arm length", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the arm length generating the rolling moment\nThis value can be measured with a ruler.\nThis corresponds to half the distance between the left and right motors.", "min": 0.0, "name": "SIH_L_ROLL", "shortDesc": "Roll arm length", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Simulation In Hardware", "increment": 0.1, "longDesc": "This value can be measured by weighting the quad on a scale.", "min": 0.0, "name": "SIH_MASS", "shortDesc": "Vehicle mass", "type": "Float", "units": "kg"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the maximum torque delivered by one propeller\nwhen the motor is running at full speed.\nThis value is usually about few percent of the maximum thrust force.", "min": 0.0, "name": "SIH_Q_MAX", "shortDesc": "Max propeller torque", "type": "Float", "units": "Nm"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "Simulation In Hardware", "increment": 0.5, "longDesc": "This is the maximum force delivered by one propeller\nwhen the motor is running at full speed.\nThis value is usually about 5 times the mass of the quadrotor.", "min": 0.0, "name": "SIH_T_MAX", "shortDesc": "Max propeller thrust force", "type": "Float", "units": "N"}, {"category": "Standard", "default": 0.05, "group": "Simulation In Hardware", "longDesc": "the time taken for the thruster to step from 0 to 100% should be about 4 times tau", "name": "SIH_T_TAU", "shortDesc": "thruster time constant tau", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Simulation In Hardware", "name": "SIH_VEHICLE_TYPE", "rebootRequired": true, "shortDesc": "Vehicle type", "type": "Int32", "values": [{"description": "Quadcopter", "value": 0}, {"description": "Fixed-Wing", "value": 1}, {"description": "Tailsitter", "value": 2}, {"description": "Standard VTOL", "value": 3}, {"description": "Hexacopter", "value": 4}, {"description": "Rover Ackermann", "value": 5}]}, {"bitmask": [{"description": "Stuck", "index": 0}, {"description": "Drift", "index": 1}], "category": "Standard", "default": 0, "group": "Simulator", "longDesc": "Stuck: freeze the measurement to the current location\nDrift: add a linearly growing bias to the sensor data", "max": 3, "min": 0, "name": "SIM_AGP_FAIL", "shortDesc": "AGP failure mode", "type": "Int32"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_BARO_OFF_P", "shortDesc": "simulated barometer pressure offset", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_BARO_OFF_T", "shortDesc": "simulated barometer temperature offset", "type": "Float", "units": "celcius"}, {"category": "Standard", "default": 10, "group": "Simulator", "max": 50, "min": 0, "name": "SIM_GPS_USED", "shortDesc": "simulated GPS number of satellites used", "type": "Int32"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_X", "shortDesc": "simulated magnetometer X offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_Y", "shortDesc": "simulated magnetometer Y offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_Z", "shortDesc": "simulated magnetometer Z offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "Set to 1 to reset parameters on next system startup (setting defaults).\nPlatform-specific values are used if available.\nRC* parameters are preserved.", "name": "SYS_AUTOCONFIG", "shortDesc": "Automatically configure default values", "type": "Int32", "values": [{"description": "Keep parameters", "value": 0}, {"description": "Reset parameters to airframe defaults", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "CHANGING THIS VALUE REQUIRES A RESTART. Defines the auto-start script used to bootstrap the system.", "max": 9999999, "min": 0, "name": "SYS_AUTOSTART", "rebootRequired": true, "shortDesc": "Auto-start script index", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled, update the bootloader on the next boot.\nWARNING: do not cut the power during an update process, otherwise you will\nhave to recover using some alternative method (e.g. JTAG).\nInstructions:\n- Insert an SD card\n- Enable this parameter\n- Reboot the board (plug the power or send a reboot command)\n- Wait until the board comes back up (or at least 2 minutes)\n- If it does not come back, check the file bootlog.txt on the SD card", "name": "SYS_BL_UPDATE", "rebootRequired": true, "shortDesc": "Bootloader update", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing\n1 : Set to 1 to start a calibration at next boot\nThis parameter is reset to zero when the temperature calibration starts.\ndefault (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_ACCEL", "shortDesc": "Enable auto start of accelerometer thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing\n1 : Set to 1 to start a calibration at next boot\nThis parameter is reset to zero when the temperature calibration starts.\ndefault (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_BARO", "shortDesc": "Enable auto start of barometer thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing\n1 : Set to 1 to start a calibration at next boot\nThis parameter is reset to zero when the temperature calibration starts.\ndefault (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_GYRO", "shortDesc": "Enable auto start of rate gyro thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 24, "group": "System", "longDesc": "A temperature increase greater than this value is required during calibration.\nCalibration will complete for each sensor when the temperature increase above the starting temperature exceeds the value set by SYS_CAL_TDEL.\nIf the temperature rise is insufficient, the calibration will continue indefinitely and the board will need to be repowered to exit.", "min": 10, "name": "SYS_CAL_TDEL", "shortDesc": "Required temperature rise during thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 10, "group": "System", "longDesc": "Temperature calibration will not start if the temperature of any sensor is higher than the value set by SYS_CAL_TMAX.", "name": "SYS_CAL_TMAX", "shortDesc": "Maximum starting temperature for thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 5, "group": "System", "longDesc": "Temperature calibration for each sensor will ignore data if the temperature is lower than the value set by SYS_CAL_TMIN.", "name": "SYS_CAL_TMIN", "shortDesc": "Minimum starting temperature for thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If the board supports persistent storage (i.e., the KConfig variable DATAMAN_PERSISTENT_STORAGE is set),\nthe 'Default storage' backend uses a file on persistent storage. If not supported, this backend uses\nnon-persistent storage in RAM.", "name": "SYS_DM_BACKEND", "rebootRequired": true, "shortDesc": "Dataman storage backend", "type": "Int32", "values": [{"description": "Dataman disabled", "value": -1}, {"description": "Default storage", "value": 0}, {"description": "RAM storage", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled, future sensor calibrations will be stored to /fs/mtd_caldata.\nNote: this is only supported on boards with a separate calibration storage\n/fs/mtd_caldata.", "name": "SYS_FAC_CAL_MODE", "shortDesc": "Enable factory calibration mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "All sensors", "value": 1}, {"description": "All sensors except mag", "value": 2}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled allows MAVLink INJECT_FAILURE commands.\nWARNING: the failures can easily cause crashes and are to be used with caution!", "name": "SYS_FAILURE_EN", "shortDesc": "Enable failure injection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "Disable this if the board has no barometer, such as some of the Omnibus\nF4 SD variants.\nIf disabled, the preflight checks will not check for the presence of a\nbarometer.", "name": "SYS_HAS_BARO", "rebootRequired": true, "shortDesc": "Control if the vehicle has a barometer", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "Disable this if the system has no GPS.\nIf disabled, the sensors hub will not process sensor_gps,\nand GPS will not be available for the rest of the system.", "name": "SYS_HAS_GPS", "rebootRequired": true, "shortDesc": "Control if the vehicle has a GPS", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "0: System has no magnetometer, preflight checks should pass without one.\n1-N: Require the presence of N magnetometer sensors for check to pass.", "name": "SYS_HAS_MAG", "rebootRequired": true, "shortDesc": "Control if and how many magnetometers are expected", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "Set this to 0 if the board has no airspeed sensor.\nIf set to 0, the preflight checks will not check for the presence of an\nairspeed sensor.", "max": 1, "min": 0, "name": "SYS_HAS_NUM_ASPD", "shortDesc": "Control if the vehicle has an airspeed sensor", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "The preflight check will fail if fewer than this number of distance sensors with valid data is present.\nDisable the check with 0.", "max": 4, "min": 0, "name": "SYS_HAS_NUM_DIST", "shortDesc": "Number of distance sensors to check being available", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "The preflight check will fail if fewer than this number of optical flow sensors with valid data are present.", "max": 1, "min": 0, "name": "SYS_HAS_NUM_OF", "shortDesc": "Number of optical flow sensors required to be available", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "While enabled the system will boot in Hardware-In-The-Loop (HITL)\nor Simulation-In-Hardware (SIH) mode and not enable all sensors and checks.\nWhen disabled the same vehicle can be flown normally.\nSet to 'external HITL', if the system should perform as if it were a real\nvehicle (the only difference to a real system is then only the parameter\nvalue, which can be used for log analysis).", "name": "SYS_HITL", "rebootRequired": true, "shortDesc": "Enable HITL/SIH mode on next boot", "type": "Int32", "values": [{"description": "external HITL", "value": -1}, {"description": "HITL and SIH disabled", "value": 0}, {"description": "HITL enabled", "value": 1}, {"description": "SIH enabled", "value": 2}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "This is used internally only: an airframe configuration might set an expected\nparameter version value via PARAM_DEFAULTS_VER. This is checked on bootup\nagainst SYS_PARAM_VER, and if they do not match, parameters are reset and\nreloaded from the airframe configuration.", "min": 0, "name": "SYS_PARAM_VER", "shortDesc": "Parameter version", "type": "Int32"}, {"category": "Standard", "default": 1.0, "group": "System", "longDesc": "Set to 0 to disable, 1 for maximum brightness", "name": "SYS_RGB_MAXBRT", "shortDesc": "RGB Led brightness limit", "type": "Float", "units": "%"}, {"category": "Standard", "default": 1, "group": "System", "name": "SYS_STCK_EN", "shortDesc": "Enable stack checking", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "Testing", "name": "TEST_1", "shortDesc": "TEST_1", "type": "Int32"}, {"category": "Standard", "default": 4, "group": "Testing", "name": "TEST_2", "shortDesc": "TEST_2", "type": "Int32"}, {"category": "Standard", "default": 5.0, "group": "Testing", "name": "TEST_3", "shortDesc": "TEST_3", "type": "Float"}, {"category": "Standard", "default": 0.01, "group": "Testing", "name": "TEST_D", "shortDesc": "TEST_D", "type": "Float"}, {"category": "Standard", "default": 2.0, "group": "Testing", "name": "TEST_DEV", "shortDesc": "TEST_DEV", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_D_LP", "shortDesc": "TEST_D_LP", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_HP", "shortDesc": "TEST_HP", "type": "Float"}, {"category": "Standard", "default": 0.1, "group": "Testing", "name": "TEST_I", "shortDesc": "TEST_I", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_I_MAX", "shortDesc": "TEST_I_MAX", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_LP", "shortDesc": "TEST_LP", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_MAX", "shortDesc": "TEST_MAX", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_MEAN", "shortDesc": "TEST_MEAN", "type": "Float"}, {"category": "Standard", "default": -1.0, "group": "Testing", "name": "TEST_MIN", "shortDesc": "TEST_MIN", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "Testing", "name": "TEST_P", "shortDesc": "TEST_P", "type": "Float"}, {"category": "Standard", "default": 12345678, "group": "Testing", "name": "TEST_PARAMS", "shortDesc": "TEST_PARAMS", "type": "Int32"}, {"category": "Standard", "default": 16, "group": "Testing", "name": "TEST_RC2_X", "shortDesc": "TEST_RC2_X", "type": "Int32"}, {"category": "Standard", "default": 8, "group": "Testing", "name": "TEST_RC_X", "shortDesc": "TEST_RC_X", "type": "Int32"}, {"category": "Standard", "default": 0.5, "group": "Testing", "name": "TEST_TRIM", "shortDesc": "TEST_TRIM", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A0_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A0_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A0_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A1_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A1_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A1_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A2_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A2_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A2_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A3_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A3_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A3_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_A_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for accelerometer sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B0_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B0_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B0_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B0_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B1_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B1_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B1_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B1_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B2_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B2_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B2_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B2_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B3_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B3_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B3_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B3_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_B_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for barometric pressure sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G0_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G0_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G0_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G1_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G1_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G1_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G2_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G2_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G2_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G3_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G3_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G3_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_G_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for rate gyro sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M0_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M0_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M0_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M1_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M1_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M1_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M2_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M2_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M2_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M3_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M3_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M3_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_M_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for magnetometer sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_MGM_PITCH", "shortDesc": "Pitch gain for manual inputs in manual control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_MGM_ROLL", "shortDesc": "Roll gain for manual inputs in manual control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_MGM_THRTL", "shortDesc": "Throttle gain for manual inputs in manual control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_MGM_YAW", "shortDesc": "Yaw gain for manual inputs in manual control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_PITCH_D", "shortDesc": "Pitch differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_PITCH_P", "shortDesc": "Pitch proportional gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 100.0, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_RGM_PITCH", "shortDesc": "Pitch gain for manual inputs in rate control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 100.0, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_RGM_ROLL", "shortDesc": "Roll gain for manual inputs in rate control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_RGM_THRTL", "shortDesc": "Throttle gain for manual inputs in rate control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 100.0, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_RGM_YAW", "shortDesc": "Yaw gain for manual inputs in rate control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.5, "group": "UUV Attitude Control", "name": "UUV_ROLL_D", "shortDesc": "Roll differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_ROLL_P", "shortDesc": "Roll proportional gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_SGM_PITCH", "shortDesc": "Pitch gain for manual inputs in attitude control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_SGM_ROLL", "shortDesc": "Roll gain for manual inputs in attitude control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_SGM_THRTL", "shortDesc": "Throttle gain for manual inputs in attitude control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_SGM_YAW", "shortDesc": "Yaw gain for manual inputs in attitude control mode", "type": "Float"}, {"category": "Standard", "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_SP_MAX_AGE", "shortDesc": "Maximum time (in seconds) before resetting setpoint", "type": "Float"}, {"category": "Standard", "default": 0, "group": "UUV Attitude Control", "max": 1, "min": 0, "name": "UUV_STICK_MODE", "shortDesc": "Stick mode selector (0=Heave/sway control, roll/pitch leveled; 1=Pitch/roll control)", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "UUV Attitude Control", "max": 1.0, "min": 0.0, "name": "UUV_THRUST_SAT", "shortDesc": "UUV Thrust setpoint Saturation", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "UUV Attitude Control", "max": 1.0, "min": 0.0, "name": "UUV_TORQUE_SAT", "shortDesc": "UUV Torque setpoint Saturation", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_YAW_D", "shortDesc": "Yaw differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_YAW_P", "shortDesc": "Yawh proportional gain", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_X_D", "shortDesc": "Gain of D controller X", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_X_P", "shortDesc": "Gain of P controller X", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_Y_D", "shortDesc": "Gain of D controller Y", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_Y_P", "shortDesc": "Gain of P controller Y", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_Z_D", "shortDesc": "Gain of D controller Z", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_Z_P", "shortDesc": "Gain of P controller Z", "type": "Float"}, {"category": "Standard", "default": 0.5, "group": "UUV Position Control", "name": "UUV_PGM_VEL", "shortDesc": "Gain for position control velocity setpoint update", "type": "Float"}, {"category": "Standard", "default": 1, "group": "UUV Position Control", "name": "UUV_POS_MODE", "shortDesc": "Stabilization mode(1) or Position Control(0)", "type": "Int32", "values": [{"description": "Moves position setpoint in world frame", "value": 0}, {"description": "Moves position setpoint in body frame", "value": 1}]}, {"category": "Standard", "default": 0.1, "group": "UUV Position Control", "name": "UUV_POS_STICK_DB", "shortDesc": "Deadband for changing position setpoint", "type": "Float"}, {"category": "Standard", "default": 1, "group": "UUV Position Control", "name": "UUV_STAB_MODE", "shortDesc": "Stabilization mode(1) or Position Control(0)", "type": "Int32", "values": [{"description": "Tracks previous attitude setpoint", "value": 0}, {"description": "Tracks horizontal attitude (allows yaw change)", "value": 1}]}, {"category": "Standard", "default": 2130706433, "group": "UXRCE-DDS Client", "longDesc": "If ethernet is enabled and is the selected configuration for uXRCE-DDS,\nthe selected Agent IP address will be set and used.\nDecimal dot notation is not supported. IP address must be provided\nin int32 format. For example, 192.168.1.2 is mapped to -1062731518;\n127.0.0.1 is mapped to 2130706433.", "name": "UXRCE_DDS_AG_IP", "rebootRequired": true, "shortDesc": "uXRCE-DDS Agent IP address", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "uXRCE-DDS domain ID", "name": "UXRCE_DDS_DOM_ID", "rebootRequired": true, "shortDesc": "uXRCE-DDS domain ID", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "This is used to enable flow control for the serial uXRCE instance.\nUsed for reliable high bandwidth communication.", "name": "UXRCE_DDS_FLCTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for UXRCE interface", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "UXRCE-DDS Client", "longDesc": "uXRCE-DDS key, must be different from zero.\nIn a single agent - multi client configuration, each client\nmust have a unique session key.", "name": "UXRCE_DDS_KEY", "rebootRequired": true, "shortDesc": "uXRCE-DDS session key", "type": "Int32"}, {"category": "System", "default": -1, "group": "UXRCE-DDS Client", "longDesc": "Defines an index-based namespace for DDS messages, e.g, uav_0, uav_1, up to uav_9999\nA value less than zero leaves the namespace empty", "max": 9999, "min": -1, "name": "UXRCE_DDS_NS_IDX", "rebootRequired": true, "shortDesc": "Define an index-based message namespace", "type": "Int32"}, {"category": "Standard", "default": 8888, "group": "UXRCE-DDS Client", "longDesc": "If ethernet is enabled and is the selected configuration for uXRCE-DDS,\nthe selected UDP port will be set and used.", "max": 65535, "min": 0, "name": "UXRCE_DDS_PRT", "rebootRequired": true, "shortDesc": "uXRCE-DDS UDP port", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "Set the participant configuration on the Agent's system.\n0: Use the default configuration.\n1: Restrict messages to localhost\n(use in combination with ROS_LOCALHOST_ONLY=1).\n2: Use a custom participant with the profile name \"px4_participant\".", "max": 2, "min": 0, "name": "UXRCE_DDS_PTCFG", "rebootRequired": true, "shortDesc": "uXRCE-DDS participant configuration", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Localhost-only", "value": 1}, {"description": "Custom participant", "value": 2}]}, {"category": "System", "default": -1, "group": "UXRCE-DDS Client", "longDesc": "Specifies after how many seconds without receiving data the DDS connection is reestablished.\nA value less than one disables the RX rate timeout.", "name": "UXRCE_DDS_RX_TO", "rebootRequired": true, "shortDesc": "RX rate timeout configuration", "type": "Int32", "units": "s"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "When enabled along with UXRCE_DDS_SYNCT, uxrce_dds_client will set the system clock using the agents UTC timestamp.", "name": "UXRCE_DDS_SYNCC", "rebootRequired": true, "shortDesc": "Enable uXRCE-DDS system clock synchronization", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "UXRCE-DDS Client", "longDesc": "When enabled, uxrce_dds_client will synchronize the timestamps of the incoming and outgoing messages measuring the offset between the Agent OS time and the PX4 time.", "name": "UXRCE_DDS_SYNCT", "rebootRequired": true, "shortDesc": "Enable uXRCE-DDS timestamp synchronization", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 3, "group": "UXRCE-DDS Client", "longDesc": "Specifies after how many seconds without sending data the DDS connection is reestablished.\nA value less than one disables the TX rate timeout.", "name": "UXRCE_DDS_TX_TO", "rebootRequired": true, "shortDesc": "TX rate timeout configuration", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 8.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Airspeed at which we can start blending both fw and mc controls. Set to 0 to disable.", "max": 30.0, "min": 0.0, "name": "VT_ARSP_BLEND", "shortDesc": "Transition blending airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Airspeed at which we can switch to fw mode", "max": 30.0, "min": 0.0, "name": "VT_ARSP_TRANS", "shortDesc": "Transition airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Time in seconds it takes to tilt form VT_TILT_FW to VT_TILT_MC.", "max": 10.0, "min": 0.1, "name": "VT_BT_TILT_DUR", "shortDesc": "Duration motor tilt up in backtransition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "VTOL Attitude Control", "increment": 0.05, "max": 0.3, "min": 0.0, "name": "VT_B_DEC_I", "shortDesc": "Backtransition deceleration setpoint to tilt I gain", "type": "Float", "units": "rad s/m"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Used to calculate back transition distance in an auto mode.\nFor standard vtol and tiltrotors a controller is used to track this value during the transition.", "max": 10.0, "min": 0.5, "name": "VT_B_DEC_MSS", "shortDesc": "Approximate deceleration during back transition", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Transition is also declared over if the groundspeed drops below MPC_XY_CRUISE.", "max": 20.0, "min": 0.1, "name": "VT_B_TRANS_DUR", "shortDesc": "Maximum duration of a back transition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "This sets the duration during which the MC motors ramp up to the commanded thrust during the back transition stage.", "max": 20.0, "min": 0.0, "name": "VT_B_TRANS_RAMP", "shortDesc": "Back transition MC motor ramp up time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "VTOL Attitude Control", "longDesc": "If set to 1 the control surfaces are locked at the disarmed value in multicopter mode.", "name": "VT_ELEV_MC_LOCK", "shortDesc": "Lock control surfaces in hover", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Prevents downforce from pitching the body down when facing wind.\nUses puller/pusher (standard VTOL), or forward-tilt (tiltrotor VTOL) to accelerate forward instead.\nOnly active if demanded pitch is below VT_PITCH_MIN.\nUse VT_FWD_THRUST_SC to tune it.\nDescend mode is treated as Landing too.\nOnly active (if enabled) in height-rate controlled modes.", "name": "VT_FWD_THRUST_EN", "shortDesc": "Use fixed-wing actuation in hover to accelerate forward", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled (except LANDING)", "value": 1}, {"description": "Enabled if above MPC_LAND_ALT1", "value": 2}, {"description": "Enabled if above MPC_LAND_ALT2", "value": 3}, {"description": "Enabled constantly", "value": 4}, {"description": "Enabled if above MPC_LAND_ALT1 (except LANDING)", "value": 5}, {"description": "Enabled if above MPC_LAND_ALT2 (except LANDING)", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Scale applied to the demanded pitch (below VT_PITCH_MIN) to get the fixed-wing forward actuation in hover mode.\nEnabled via VT_FWD_THRUST_EN.", "max": 5.0, "min": 0.0, "name": "VT_FWD_THRUST_SC", "shortDesc": "Fixed-wing actuation thrust scale in hover", "type": "Float"}, {"bitmask": [{"description": "Yaw", "index": 0}, {"description": "Roll", "index": 1}, {"description": "Pitch", "index": 2}], "category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Enable differential thrust seperately for roll, pitch, yaw in forward (fixed-wing) mode.\nThe effectiveness of differential thrust around the corresponding axis can be\ntuned by setting VT_FW_DIFTHR_S_R / VT_FW_DIFTHR_S_P / VT_FW_DIFTHR_S_Y.", "max": 7, "min": 0, "name": "VT_FW_DIFTHR_EN", "shortDesc": "Differential thrust in forwards flight", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_P", "shortDesc": "Pitch differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_R", "shortDesc": "Roll differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_Y", "shortDesc": "Yaw differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Minimum altitude for fixed-wing flight. When the vehicle is in fixed-wing mode\nand the altitude drops below this altitude (relative altitude above local origin),\nit will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT.", "max": 200.0, "min": 0.0, "name": "VT_FW_MIN_ALT", "shortDesc": "Quad-chute altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "increment": 1, "longDesc": "Maximum height above the ground (if available, otherwise above\nHome if available, otherwise above the local origin) where triggering a quad-chute is possible.\nAt high altitudes there is a big risk to deplete the battery and therefore crash if quad-chuting there.", "min": 0, "name": "VT_FW_QC_HMAX", "shortDesc": "Quad-chute maximum height", "type": "Int32", "units": "m"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Absolute pitch threshold for quad-chute triggering in FW mode.\nAbove this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT.\nSet to 0 do disable this threshold.", "max": 180, "min": 0, "name": "VT_FW_QC_P", "shortDesc": "Quad-chute max pitch threshold", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Absolute roll threshold for quad-chute triggering in FW mode.\nAbove this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT.\nSet to 0 do disable this threshold.", "max": 180, "min": 0, "name": "VT_FW_QC_R", "shortDesc": "Quad-chute max roll threshold", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Time in seconds used for a transition", "max": 20.0, "min": 0.1, "name": "VT_F_TRANS_DUR", "shortDesc": "Duration of a front transition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_F_TRANS_THR", "shortDesc": "Target throttle value for the transition to fixed-wing flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.0, "group": "VTOL Attitude Control", "increment": 0.5, "longDesc": "The duration of the front transition when there is no airspeed feedback available.\nWhen airspeed is used, transition timeout is declared if airspeed does not\nreach VT_ARSP_BLEND after this time.", "max": 30.0, "min": 1.0, "name": "VT_F_TR_OL_TM", "shortDesc": "Airspeed-less front transition time (open loop)", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Overrides VT_PITCH_MIN when the vehicle is in LAND mode (hovering).\nDuring landing it can be beneficial to reduce the pitch angle to reduce the generated lift in head wind.", "max": 45.0, "min": -10.0, "name": "VT_LND_PITCH_MIN", "shortDesc": "Minimum pitch angle during hover landing", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Any pitch setpoint below this value is translated to a forward force by the fixed-wing forward actuation if\nVT_FWD_TRHUST_EN is set.", "max": 45.0, "min": -10.0, "name": "VT_PITCH_MIN", "shortDesc": "Minimum pitch angle during hover", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.33, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Defines the slew rate of the puller/pusher throttle during transitions.\nZero will deactivate the slew rate limiting and thus produce an instant throttle\nrise to the transition throttle VT_F_TRANS_THR.", "min": 0.0, "name": "VT_PSHER_SLEW", "shortDesc": "Pusher throttle ramp up slew rate", "type": "Float", "units": "1/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Altitude error threshold for quad-chute triggering during fixed-wing flight.\nThe check is only active if altitude is controlled and the vehicle is below the current altitude reference.\nThe altitude error is relative to the highest altitude the vehicle has achieved since it has flown below the current\naltitude reference.\nSet to 0 do disable.", "max": 200.0, "min": 0.0, "name": "VT_QC_ALT_LOSS", "shortDesc": "Quad-chute uncommanded descent threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Altitude loss threshold for quad-chute triggering during VTOL transition to fixed-wing flight\nin altitude-controlled flight modes.\nActive until 5s after completing transition to fixed-wing.\nIf the current altitude is more than this value below the altitude at the beginning of the\ntransition, it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT.\nSet to 0 do disable this threshold.", "max": 50.0, "min": 0.0, "name": "VT_QC_T_ALT_LOSS", "shortDesc": "Quad-chute transition altitude loss threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.1, "max": 1.0, "min": -1.0, "name": "VT_SPOILER_MC_LD", "shortDesc": "Spoiler setting while landing (hover)", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_FW", "shortDesc": "Normalized tilt in FW", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_MC", "shortDesc": "Normalized tilt in Hover", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.4, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_TRANS", "shortDesc": "Normalized tilt in transition to FW", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Minimum time in seconds for front transition.", "max": 20.0, "min": 0.0, "name": "VT_TRANS_MIN_TM", "shortDesc": "Front transition minimum time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Time in seconds it takes to tilt form VT_TILT_TRANS to VT_TILT_FW.", "max": 5.0, "min": 0.1, "name": "VT_TRANS_P2_DUR", "shortDesc": "Duration of front transition phase 2", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 15.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Time in seconds after which transition will be cancelled.", "max": 30.0, "min": 0.1, "name": "VT_TRANS_TIMEOUT", "shortDesc": "Front transition timeout", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "max": 2, "min": 0, "name": "VT_TYPE", "rebootRequired": true, "shortDesc": "VTOL Type (Tailsitter=0, Tiltrotor=1, Standard=2)", "type": "Int32", "values": [{"description": "Tailsitter", "value": 0}, {"description": "Tiltrotor", "value": 1}, {"description": "Standard", "value": 2}]}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "The desired gain to convert roll sp into yaw rate sp.", "max": 3.0, "min": 0.0, "name": "WV_GAIN", "shortDesc": "Weather-vane roll angle to yawrate", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 80.0, "group": "VTOL Takeoff", "increment": 1.0, "longDesc": "Altitude relative to home at which vehicle will loiter after front transition.", "max": 300.0, "min": 20.0, "name": "VTO_LOITER_ALT", "shortDesc": "VTOL Takeoff relative loiter altitude", "type": "Float", "units": "m"}], "translation": {"items": {"parameters": {"list": {"items": {"bitmask": {"list": {"key": "index", "translate": ["description"]}}, "values": {"list": {"key": "value", "translate": ["description"]}}}, "key": "name", "translate": ["shortDesc", "longDesc"], "translate-global": ["category", "group"]}}}}, "version": 1} \ No newline at end of file +{"parameters": [{"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets first 4 characters of a total of 8. Valid characters are A-Z, 0-9, \" \". Example \"PX4 \" -> 1347957792\nFor CALLSIGN shorter than 8 characters use the null terminator at the end '\\0'.", "name": "ADSB_CALLSIGN_1", "rebootRequired": true, "shortDesc": "First 4 characters of CALLSIGN", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets second 4 characters of a total of 8. Valid characters are A-Z, 0-9, \" \" only. Example \"TEST\" -> 1413829460\nFor CALLSIGN shorter than 8 characters use the null terminator at the end '\\0'.", "name": "ADSB_CALLSIGN_2", "rebootRequired": true, "shortDesc": "Second 4 characters of CALLSIGN", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets the vehicle emergency state", "max": 6, "min": 0, "name": "ADSB_EMERGC", "rebootRequired": true, "shortDesc": "ADSB-Out Emergency State", "type": "Int32", "values": [{"description": "NoEmergency", "value": 0}, {"description": "General", "value": 1}, {"description": "Medical", "value": 2}, {"description": "LowFuel", "value": 3}, {"description": "NoCommunications", "value": 4}, {"description": "Interference", "value": 5}, {"description": "Downed", "value": 6}]}, {"category": "Standard", "default": 14, "group": "ADSB", "longDesc": "Configure the emitter type of the vehicle.", "max": 15, "min": 0, "name": "ADSB_EMIT_TYPE", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Emitter Type", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "Light", "value": 1}, {"description": "Small", "value": 2}, {"description": "Large", "value": 3}, {"description": "HighVortex", "value": 4}, {"description": "Heavy", "value": 5}, {"description": "Performance", "value": 6}, {"description": "Rotorcraft", "value": 7}, {"description": "RESERVED", "value": 8}, {"description": "Glider", "value": 9}, {"description": "LightAir", "value": 10}, {"description": "Parachute", "value": 11}, {"description": "UltraLight", "value": 12}, {"description": "RESERVED", "value": 13}, {"description": "UAV", "value": 14}, {"description": "Space", "value": 15}, {"description": "RESERVED", "value": 16}, {"description": "EmergencySurf", "value": 17}, {"description": "ServiceSurf", "value": 18}, {"description": "PointObstacle", "value": 19}]}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets GPS lataral offset encoding", "max": 7, "min": 0, "name": "ADSB_GPS_OFF_LAT", "rebootRequired": true, "shortDesc": "ADSB-Out GPS Offset lat", "type": "Int32", "values": [{"description": "NoData", "value": 0}, {"description": "LatLeft2M", "value": 1}, {"description": "LatLeft4M", "value": 2}, {"description": "LatLeft6M", "value": 3}, {"description": "LatRight0M", "value": 4}, {"description": "LatRight2M", "value": 5}, {"description": "LatRight4M", "value": 6}, {"description": "LatRight6M", "value": 7}]}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Sets GPS longitudinal offset encoding", "max": 1, "min": 0, "name": "ADSB_GPS_OFF_LON", "rebootRequired": true, "shortDesc": "ADSB-Out GPS Offset lon", "type": "Int32", "values": [{"description": "NoData", "value": 0}, {"description": "AppliedBySensor", "value": 1}]}, {"category": "Standard", "default": 1194684, "group": "ADSB", "longDesc": "Defines the ICAO ID of the vehicle", "max": 16777215, "min": -1, "name": "ADSB_ICAO_ID", "rebootRequired": true, "shortDesc": "ADSB-Out ICAO configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "This vehicle is always tracked. Use 0 to disable.", "max": 16777215, "min": 0, "name": "ADSB_ICAO_SPECL", "rebootRequired": true, "shortDesc": "ADSB-In Special ICAO configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Enable Identification of Position feature", "name": "ADSB_IDENT", "rebootRequired": true, "shortDesc": "ADSB-Out Ident Configuration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "ADSB", "longDesc": "Report the length and width of the vehicle in meters. In most cases, use '1' for the smallest vehicle size.", "max": 15, "min": 0, "name": "ADSB_LEN_WIDTH", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Size Configuration", "type": "Int32", "values": [{"description": "SizeUnknown", "value": 0}, {"description": "Len15_Wid23", "value": 1}, {"description": "Len25_Wid28", "value": 2}, {"description": "Len25_Wid34", "value": 3}, {"description": "Len35_Wid33", "value": 4}, {"description": "Len35_Wid38", "value": 5}, {"description": "Len45_Wid39", "value": 6}, {"description": "Len45_Wid45", "value": 7}, {"description": "Len55_Wid45", "value": 8}, {"description": "Len55_Wid52", "value": 9}, {"description": "Len65_Wid59", "value": 10}, {"description": "Len65_Wid67", "value": 11}, {"description": "Len75_Wid72", "value": 12}, {"description": "Len75_Wid80", "value": 13}, {"description": "Len85_Wid80", "value": 14}, {"description": "Len85_Wid90", "value": 15}]}, {"category": "Standard", "default": 25, "group": "ADSB", "longDesc": "Change number of targets to track", "max": 50, "min": 0, "name": "ADSB_LIST_MAX", "rebootRequired": true, "shortDesc": "ADSB-In Vehicle List Size", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "ADSB", "longDesc": "Informs ADSB vehicles of this vehicle's max speed capability", "max": 6, "min": 0, "name": "ADSB_MAX_SPEED", "rebootRequired": true, "shortDesc": "ADSB-Out Vehicle Max Speed", "type": "Int32", "values": [{"description": "UnknownMaxSpeed", "value": 0}, {"description": "75Kts", "value": 1}, {"description": "150Kts", "value": 2}, {"description": "300Kts", "value": 3}, {"description": "600Kts", "value": 4}, {"description": "1200Kts", "value": 5}, {"description": "Over1200Kts", "value": 6}]}, {"category": "Standard", "default": 1200, "group": "ADSB", "longDesc": "This parameter defines the squawk code. Value should be between 0000 and 7777.", "max": 7777, "min": 0, "name": "ADSB_SQUAWK", "rebootRequired": true, "shortDesc": "ADSB-Out squawk code configuration", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 1.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC1", "shortDesc": "SIM Channel 1 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 10.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC10", "shortDesc": "SIM Channel 10 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 11.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC11", "shortDesc": "SIM Channel 11 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 12.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC12", "shortDesc": "SIM Channel 12 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 13.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC13", "shortDesc": "SIM Channel 13 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 14.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC14", "shortDesc": "SIM Channel 14 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 15.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC15", "shortDesc": "SIM Channel 15 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 16.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC16", "shortDesc": "SIM Channel 16 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 2.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC2", "shortDesc": "SIM Channel 2 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 3.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC3", "shortDesc": "SIM Channel 3 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 4.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC4", "shortDesc": "SIM Channel 4 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 5.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC5", "shortDesc": "SIM Channel 5 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 6.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC6", "shortDesc": "SIM Channel 6 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 7.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC7", "shortDesc": "SIM Channel 7 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 8.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC8", "shortDesc": "SIM Channel 8 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Select what should be output on SIM Channel 9.\nThe default failsafe value is set according to the selected function:\n- 'Min' for ConstantMin\n- 'Max' for ConstantMax\n- 'Max' for Parachute\n- ('Max'+'Min')/2 for Servos\n- 'Disarmed' for the rest", "name": "PWM_MAIN_FUNC9", "shortDesc": "SIM Channel 9 Output Function", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Constant Min", "value": 1}, {"description": "Constant Max", "value": 2}, {"description": "Motor 1", "value": 101}, {"description": "Motor 2", "value": 102}, {"description": "Motor 3", "value": 103}, {"description": "Motor 4", "value": 104}, {"description": "Motor 5", "value": 105}, {"description": "Motor 6", "value": 106}, {"description": "Motor 7", "value": 107}, {"description": "Motor 8", "value": 108}, {"description": "Motor 9", "value": 109}, {"description": "Motor 10", "value": 110}, {"description": "Motor 11", "value": 111}, {"description": "Motor 12", "value": 112}, {"description": "Servo 1", "value": 201}, {"description": "Servo 2", "value": 202}, {"description": "Servo 3", "value": 203}, {"description": "Servo 4", "value": 204}, {"description": "Servo 5", "value": 205}, {"description": "Servo 6", "value": 206}, {"description": "Servo 7", "value": 207}, {"description": "Servo 8", "value": 208}, {"description": "Peripheral via Actuator Set 1", "value": 301}, {"description": "Peripheral via Actuator Set 2", "value": 302}, {"description": "Peripheral via Actuator Set 3", "value": 303}, {"description": "Peripheral via Actuator Set 4", "value": 304}, {"description": "Peripheral via Actuator Set 5", "value": 305}, {"description": "Peripheral via Actuator Set 6", "value": 306}, {"description": "Landing Gear", "value": 400}, {"description": "Parachute", "value": 401}, {"description": "RC Roll", "value": 402}, {"description": "RC Pitch", "value": 403}, {"description": "RC Throttle", "value": 404}, {"description": "RC Yaw", "value": 405}, {"description": "RC Flaps", "value": 406}, {"description": "RC AUX 1", "value": 407}, {"description": "RC AUX 2", "value": 408}, {"description": "RC AUX 3", "value": 409}, {"description": "RC AUX 4", "value": 410}, {"description": "RC AUX 5", "value": 411}, {"description": "RC AUX 6", "value": 412}, {"description": "Gimbal Roll", "value": 420}, {"description": "Gimbal Pitch", "value": 421}, {"description": "Gimbal Yaw", "value": 422}, {"description": "Gripper", "value": 430}, {"description": "Landing Gear Wheel", "value": 440}, {"description": "IC Engine Ignition", "value": 450}, {"description": "IC Engine Throttle", "value": 451}, {"description": "IC Engine Choke", "value": 452}, {"description": "IC Engine Starter", "value": 453}]}, {"bitmask": [{"description": "SIM Channel 1", "index": 0}, {"description": "SIM Channel 2", "index": 1}, {"description": "SIM Channel 3", "index": 2}, {"description": "SIM Channel 4", "index": 3}, {"description": "SIM Channel 5", "index": 4}, {"description": "SIM Channel 6", "index": 5}, {"description": "SIM Channel 7", "index": 6}, {"description": "SIM Channel 8", "index": 7}, {"description": "SIM Channel 9", "index": 8}, {"description": "SIM Channel 10", "index": 9}, {"description": "SIM Channel 11", "index": 10}, {"description": "SIM Channel 12", "index": 11}, {"description": "SIM Channel 13", "index": 12}, {"description": "SIM Channel 14", "index": 13}, {"description": "SIM Channel 15", "index": 14}, {"description": "SIM Channel 16", "index": 15}], "category": "Standard", "default": 0, "group": "Actuator Outputs", "longDesc": "Allows to reverse the output range for each channel.\nNote: this is only useful for servos.", "max": 65535, "min": 0, "name": "PWM_MAIN_REV", "shortDesc": "Reverse Output Range for SIM", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Airspeed Validator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 5, "min": 1, "name": "ASPD_BETA_GATE", "shortDesc": "Gate size for sideslip angle fusion", "type": "Int32", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Airspeed Validator", "longDesc": "Sideslip measurement noise of the internal wind estimator(s) of the airspeed selector.", "max": 1.0, "min": 0.0, "name": "ASPD_BETA_NOISE", "shortDesc": "Wind estimator sideslip measurement noise", "type": "Float", "units": "rad"}, {"bitmask": [{"description": "Only data missing check (triggers if more than 1s no data)", "index": 0}, {"description": "Data stuck (triggers if data is exactly constant for 2s in FW mode)", "index": 1}, {"description": "Innovation check (see ASPD_FS_INNOV)", "index": 2}, {"description": "Load factor check (triggers if measurement is below stall speed)", "index": 3}, {"description": "First principle check (airspeed change vs. throttle and pitch)", "index": 4}], "category": "Standard", "default": 7, "group": "Airspeed Validator", "longDesc": "Controls which checks are run to check airspeed data for validity. Only applied if ASPD_PRIMARY > 0.\nNote: The missing data check (bit 0) is implicitly always enabled when ASPD_DO_CHECKS > 0, even if bit 0 is not explicitly set.", "max": 31, "min": 0, "name": "ASPD_DO_CHECKS", "shortDesc": "Enable checks on airspeed sensors", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Airspeed Validator", "name": "ASPD_FALLBACK", "shortDesc": "Fallback options", "type": "Int32", "values": [{"description": "Fallback only to other airspeed sensors", "value": 0}, {"description": "Fallback to groundspeed-minus-windspeed airspeed estimation", "value": 1}, {"description": "Fallback to thrust based airspeed estimation", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Airspeed Validator", "longDesc": "Window for comparing airspeed change to throttle and pitch change.\nTriggers when the airspeed change within this window is negative while throttle increases\nand the vehicle pitches down.\nIs meant to catch degrading airspeed blockages as can happen when flying through icing conditions.\nRelies on FW_THR_TRIM being set accurately.", "min": 0.0, "name": "ASPD_FP_T_WINDOW", "shortDesc": "First principle airspeed check time window", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Airspeed Validator", "longDesc": "This specifies the minimum airspeed innovation required to trigger a failsafe. Larger values make the check less sensitive,\nsmaller values make it more sensitive. Large innovations indicate an inconsistency between predicted (groundspeed - windspeeed)\nand measured airspeed.\nThe time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the ASPD_FS_INTEG parameter.", "max": 10.0, "min": 0.5, "name": "ASPD_FS_INNOV", "shortDesc": "Airspeed failure innovation threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Airspeed Validator", "longDesc": "This sets the time integral of airspeed innovation exceedance above ASPD_FS_INNOV required to trigger a failsafe.\nLarger values make the check less sensitive, smaller positive values make it more sensitive.", "max": 50.0, "min": 0.0, "name": "ASPD_FS_INTEG", "shortDesc": "Airspeed failure innovation integral threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Airspeed Validator", "longDesc": "Delay before switching back to using airspeed sensor if checks indicate sensor is good.\nSet to a negative value to disable the re-enabling in flight.", "min": -1.0, "name": "ASPD_FS_T_START", "shortDesc": "Airspeed failsafe start delay", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Airspeed Validator", "longDesc": "Delay before stopping use of airspeed sensor if checks indicate sensor is bad.", "min": 0.0, "name": "ASPD_FS_T_STOP", "shortDesc": "Airspeed failsafe stop delay", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Airspeed Validator", "name": "ASPD_PRIMARY", "rebootRequired": true, "shortDesc": "Index or primary airspeed measurement source", "type": "Int32", "values": [{"description": "Groundspeed minus windspeed", "value": 0}, {"description": "First airspeed sensor", "value": 1}, {"description": "Second airspeed sensor", "value": 2}, {"description": "Third airspeed sensor", "value": 3}, {"description": "Thrust based airspeed", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the first airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_1", "shortDesc": "Scale of airspeed sensor 1", "type": "Float", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the second airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_2", "shortDesc": "Scale of airspeed sensor 2", "type": "Float", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Airspeed Validator", "longDesc": "This is the scale IAS --> CAS of the third airspeed sensor instance", "max": 2.0, "min": 0.5, "name": "ASPD_SCALE_3", "shortDesc": "Scale of airspeed sensor 3", "type": "Float", "volatile": true}, {"category": "Standard", "default": 2, "group": "Airspeed Validator", "name": "ASPD_SCALE_APPLY", "shortDesc": "Controls when to apply the new estimated airspeed scale(s)", "type": "Int32", "values": [{"description": "Do not automatically apply the estimated scale", "value": 0}, {"description": "Apply the estimated scale after disarm", "value": 1}, {"description": "Apply the estimated scale in air", "value": 2}]}, {"category": "Standard", "decimalPlaces": 5, "default": 0.0001, "group": "Airspeed Validator", "longDesc": "Airspeed scale process noise of the internal wind estimator(s) of the airspeed selector.\nWhen unaided, the scale uncertainty (1-sigma, unitless) increases by this amount every second.", "max": 0.1, "min": 0.0, "name": "ASPD_SCALE_NSD", "shortDesc": "Wind estimator true airspeed scale process noise spectral density", "type": "Float", "units": "1/s/sqrt(Hz)"}, {"category": "Standard", "default": 4, "group": "Airspeed Validator", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "max": 5, "min": 1, "name": "ASPD_TAS_GATE", "shortDesc": "Gate size for true airspeed fusion", "type": "Int32", "units": "SD"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.4, "group": "Airspeed Validator", "longDesc": "True airspeed measurement noise of the internal wind estimator(s) of the airspeed selector.", "max": 4.0, "min": 0.0, "name": "ASPD_TAS_NOISE", "shortDesc": "Wind estimator true airspeed measurement noise", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Airspeed Validator", "longDesc": "The airspeed alternative derived from groundspeed and heading will be declared valid\nas soon and as long the horizontal wind uncertainty is below this value.", "max": 5.0, "min": 0.01, "name": "ASPD_WERR_THR", "shortDesc": "Horizontal wind uncertainty threshold for valid ground-minus-wind", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Airspeed Validator", "longDesc": "Wind process noise of the internal wind estimator(s) of the airspeed selector.\nWhen unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second.", "max": 1.0, "min": 0.0, "name": "ASPD_WIND_NSD", "shortDesc": "Wind estimator wind process noise spectral density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "name": "ATT_ACC_COMP", "shortDesc": "Acceleration compensation based on GPS velocity", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Attitude Q estimator", "max": 2.0, "min": 0.0, "name": "ATT_BIAS_MAX", "shortDesc": "Gyro bias limit", "type": "Float", "units": "rad/s"}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "longDesc": "Enable standalone quaternion based attitude estimator.", "name": "ATT_EN", "shortDesc": "standalone attitude estimator enable (unsupported)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Attitude Q estimator", "longDesc": "Set to 1 to use heading estimate from vision.\nSet to 2 to use heading from motion capture.", "max": 2, "min": 0, "name": "ATT_EXT_HDG_M", "shortDesc": "External heading usage mode (from Motion capture/Vision)", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Vision", "value": 1}, {"description": "Motion Capture", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Attitude Q estimator", "longDesc": "This parameter is not used in normal operation,\nas the declination is looked up based on the\nGPS coordinates of the vehicle.", "name": "ATT_MAG_DECL", "shortDesc": "Magnetic declination, in degrees", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 1, "group": "Attitude Q estimator", "name": "ATT_MAG_DECL_A", "shortDesc": "Automatic GPS based declination compensation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_ACC", "shortDesc": "Complimentary filter accelerometer weight", "type": "Float"}, {"category": "Standard", "default": 0.1, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_EXT_HDG", "shortDesc": "Complimentary filter external heading weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Attitude Q estimator", "max": 1.0, "min": 0.0, "name": "ATT_W_GYRO_BIAS", "shortDesc": "Complimentary filter gyroscope bias weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Attitude Q estimator", "longDesc": "Set to 0 to avoid using the magnetometer.", "max": 1.0, "min": 0.0, "name": "ATT_W_MAG", "shortDesc": "Complimentary filter magnetometer weight", "type": "Float"}, {"category": "Standard", "default": 2, "group": "Autotune", "longDesc": "After the auto-tuning sequence is completed,\na new set of gains is available and can be applied\nimmediately or after landing.", "name": "FW_AT_APPLY", "shortDesc": "Controls when to apply the new gains", "type": "Int32", "values": [{"description": "Do not apply the new gains (logging only)", "value": 0}, {"description": "Apply the new gains after disarm", "value": 1}, {"description": "Apply the new gains in air", "value": 2}]}, {"bitmask": [{"description": "roll", "index": 0}, {"description": "pitch", "index": 1}, {"description": "yaw", "index": 2}], "category": "Standard", "default": 3, "group": "Autotune", "longDesc": "Defines which axes will be tuned during the auto-tuning sequence\nSet bits in the following positions to enable:\n0 : Roll\n1 : Pitch\n2 : Yaw", "max": 7, "min": 1, "name": "FW_AT_AXES", "shortDesc": "Tuning axes selection", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Autotune", "longDesc": "Defines which RC_MAP_AUXn parameter maps the manual control channel used to enable/disable auto tuning.", "max": 6, "min": 0, "name": "FW_AT_MAN_AUX", "shortDesc": "Enable/disable auto tuning using a manual control AUX input", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Aux1", "value": 1}, {"description": "Aux2", "value": 2}, {"description": "Aux3", "value": 3}, {"description": "Aux4", "value": 4}, {"description": "Aux5", "value": 5}, {"description": "Aux6", "value": 6}]}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Autotune", "longDesc": "Can be set lower or higher than the end frequency", "max": 30.0, "min": 0.1, "name": "FW_AT_SYSID_F0", "shortDesc": "Start frequency of the injected signal", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Autotune", "longDesc": "Can be set lower or higher than the start frequency", "max": 30.0, "min": 0.1, "name": "FW_AT_SYSID_F1", "shortDesc": "End frequency of the injected signal", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 0, "default": 10.0, "group": "Autotune", "longDesc": "Duration of the input signal sent on each axis during system identification", "max": 120.0, "min": 5.0, "name": "FW_AT_SYSID_TIME", "shortDesc": "Maneuver time for each axis", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Autotune", "longDesc": "Type of signal used during system identification to excite the system.", "name": "FW_AT_SYSID_TYPE", "shortDesc": "Input signal type", "type": "Int32", "values": [{"description": "Step", "value": 0}, {"description": "Linear sine sweep", "value": 1}, {"description": "Logarithmic sine sweep", "value": 2}]}, {"category": "Standard", "default": 1, "group": "Autotune", "longDesc": "After the auto-tuning sequence is completed,\na new set of gains is available and can be applied\nimmediately or after landing.\nWARNING Applying the gains in air is dangerous as there is no\nguarantee that those new gains will be able to stabilize\nthe drone properly.", "name": "MC_AT_APPLY", "shortDesc": "Controls when to apply the new gains", "type": "Int32", "values": [{"description": "Do not apply the new gains (logging only)", "value": 0}, {"description": "Apply the new gains after disarm", "value": 1}, {"description": "WARNING Apply the new gains in air", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Autotune", "name": "MC_AT_EN", "shortDesc": "Multicopter autotune module enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.14, "group": "Autotune", "max": 0.5, "min": 0.01, "name": "MC_AT_RISE_TIME", "shortDesc": "Desired angular rate closed-loop rise time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.7, "group": "Autotune", "max": 6.0, "min": 0.1, "name": "MC_AT_SYSID_AMP", "shortDesc": "Amplitude of the injected signal", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 1 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT1_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 1 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT1_N_CELLS", "shortDesc": "Number of cells for battery 1", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT1_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 1", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module / Analog'\nmeans that measurements are expected to come from either analog (ADC) inputs\nor an I2C power monitor (e.g. INA226). Analog inputs are voltage and current\nmeasurements read from the board's ADC channels, typically from an onboard\nvoltage divider and current shunt, or an external analog power module.\nI2C power monitors are digital sensors on the I2C bus.\nIf the value is set to 'External' then the system expects to receive MAVLink\nor CAN battery status messages, or the battery data is published by an external driver.\nIf the value is set to 'ESCs', the battery information are taken from the esc_status message.\nThis requires the ESC to provide both voltage as well as current (via ESC telemetry).", "name": "BAT1_SOURCE", "rebootRequired": true, "shortDesc": "Battery 1 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module / Analog", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full.\nFor a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT1_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty.\nThe voltage should be chosen above the steep dropoff at 3.5V. A typical\nlithium battery can only be discharged under high load down to 10% before\nit drops off to a voltage level damaging the cells.", "name": "BAT1_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 2 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT2_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 2 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT2_N_CELLS", "shortDesc": "Number of cells for battery 2", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT2_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 2", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": -1, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module / Analog'\nmeans that measurements are expected to come from either analog (ADC) inputs\nor an I2C power monitor (e.g. INA226). Analog inputs are voltage and current\nmeasurements read from the board's ADC channels, typically from an onboard\nvoltage divider and current shunt, or an external analog power module.\nI2C power monitors are digital sensors on the I2C bus.\nIf the value is set to 'External' then the system expects to receive MAVLink\nor CAN battery status messages, or the battery data is published by an external driver.\nIf the value is set to 'ESCs', the battery information are taken from the esc_status message.\nThis requires the ESC to provide both voltage as well as current (via ESC telemetry).", "name": "BAT2_SOURCE", "rebootRequired": true, "shortDesc": "Battery 2 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module / Analog", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full.\nFor a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT2_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty.\nThe voltage should be chosen above the steep dropoff at 3.5V. A typical\nlithium battery can only be discharged under high load down to 10% before\nit drops off to a voltage level damaging the cells.", "name": "BAT2_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Battery Calibration", "increment": 50.0, "longDesc": "Defines the capacity of battery 3 in mAh.", "max": 100000.0, "min": -1.0, "name": "BAT3_CAPACITY", "rebootRequired": true, "shortDesc": "Battery 3 capacity", "type": "Float", "units": "mAh"}, {"category": "Standard", "default": 0, "group": "Battery Calibration", "longDesc": "Defines the number of cells the attached battery consists of.", "name": "BAT3_N_CELLS", "shortDesc": "Number of cells for battery 3", "type": "Int32", "values": [{"description": "Unknown", "value": 0}, {"description": "1S Battery", "value": 1}, {"description": "2S Battery", "value": 2}, {"description": "3S Battery", "value": 3}, {"description": "4S Battery", "value": 4}, {"description": "5S Battery", "value": 5}, {"description": "6S Battery", "value": 6}, {"description": "7S Battery", "value": 7}, {"description": "8S Battery", "value": 8}, {"description": "9S Battery", "value": 9}, {"description": "10S Battery", "value": 10}, {"description": "11S Battery", "value": 11}, {"description": "12S Battery", "value": 12}, {"description": "13S Battery", "value": 13}, {"description": "14S Battery", "value": 14}, {"description": "15S Battery", "value": 15}, {"description": "16S Battery", "value": 16}]}, {"category": "Standard", "decimalPlaces": 4, "default": -1.0, "group": "Battery Calibration", "increment": 0.0005, "longDesc": "If non-negative, then this will be used instead of the online estimated internal resistance.", "max": 0.2, "min": -1.0, "name": "BAT3_R_INTERNAL", "rebootRequired": true, "shortDesc": "Explicitly defines the per cell internal resistance for battery 3", "type": "Float", "units": "Ohm"}, {"category": "Standard", "default": -1, "group": "Battery Calibration", "longDesc": "This parameter controls the source of battery data. The value 'Power Module / Analog'\nmeans that measurements are expected to come from either analog (ADC) inputs\nor an I2C power monitor (e.g. INA226). Analog inputs are voltage and current\nmeasurements read from the board's ADC channels, typically from an onboard\nvoltage divider and current shunt, or an external analog power module.\nI2C power monitors are digital sensors on the I2C bus.\nIf the value is set to 'External' then the system expects to receive MAVLink\nor CAN battery status messages, or the battery data is published by an external driver.\nIf the value is set to 'ESCs', the battery information are taken from the esc_status message.\nThis requires the ESC to provide both voltage as well as current (via ESC telemetry).", "name": "BAT3_SOURCE", "rebootRequired": true, "shortDesc": "Battery 3 monitoring source", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Power Module / Analog", "value": 0}, {"description": "External", "value": 1}, {"description": "ESCs", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 4.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered full.\nFor a more accurate estimate set this below the nominal voltage of e.g. 4.2V", "name": "BAT3_V_CHARGED", "rebootRequired": true, "shortDesc": "Full cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.6, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Defines the voltage where a single cell of the battery is considered empty.\nThe voltage should be chosen above the steep dropoff at 3.5V. A typical\nlithium battery can only be discharged under high load down to 10% before\nit drops off to a voltage level damaging the cells.", "name": "BAT3_V_EMPTY", "rebootRequired": true, "shortDesc": "Empty cell voltage", "type": "Float", "units": "V"}, {"category": "Standard", "decimalPlaces": 2, "default": 15.0, "group": "Battery Calibration", "increment": 0.1, "longDesc": "This value is used to initialize the in-flight average current estimation,\nwhich in turn is used for estimating remaining flight time and RTL triggering.", "max": 500.0, "min": 0.0, "name": "BAT_AVRG_CURRENT", "shortDesc": "Expected battery current in flight", "type": "Float", "units": "A"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.07, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as critically low.\nThis has to be lower than the low threshold. This threshold commonly\nwill trigger RTL.", "max": 0.5, "min": 0.05, "name": "BAT_CRIT_THR", "shortDesc": "Critical threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as dangerously low.\nThis has to be lower than the critical threshold. This threshold commonly\nwill trigger landing.", "max": 0.5, "min": 0.03, "name": "BAT_EMERGEN_THR", "shortDesc": "Emergency threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "Battery Calibration", "increment": 0.01, "longDesc": "Sets the threshold when the battery will be reported as low.\nThis has to be higher than the critical threshold.", "max": 0.5, "min": 0.12, "name": "BAT_LOW_THR", "shortDesc": "Low threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Camera trigger", "longDesc": "This parameter sets the time the trigger needs to pulled high or low.", "max": 3000.0, "min": 0.1, "name": "TRIG_ACT_TIME", "rebootRequired": true, "shortDesc": "Camera trigger activation time", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "Camera trigger", "increment": 1.0, "longDesc": "Sets the distance at which to trigger the camera.", "min": 0.0, "name": "TRIG_DISTANCE", "rebootRequired": true, "shortDesc": "Camera trigger distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 4, "group": "Camera trigger", "longDesc": "Selects the trigger interface", "name": "TRIG_INTERFACE", "rebootRequired": true, "shortDesc": "Camera trigger Interface", "type": "Int32", "values": [{"description": "GPIO", "value": 1}, {"description": "Seagull MAP2 (over PWM)", "value": 2}, {"description": "MAVLink (Camera Protocol v1)", "value": 3}, {"description": "Generic PWM (IR trigger, servo)", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Camera trigger", "longDesc": "This parameter sets the time between two consecutive trigger events", "max": 10000.0, "min": 4.0, "name": "TRIG_INTERVAL", "rebootRequired": true, "shortDesc": "Camera trigger interval", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Camera trigger", "longDesc": "This parameter sets the minimum time between two consecutive trigger events\nthe specific camera setup is supporting.", "max": 10000.0, "min": 1.0, "name": "TRIG_MIN_INTERVA", "rebootRequired": true, "shortDesc": "Minimum camera trigger interval", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "Camera trigger", "max": 4, "min": 0, "name": "TRIG_MODE", "rebootRequired": true, "shortDesc": "Camera trigger mode", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Time based, on command", "value": 1}, {"description": "Time based, always on", "value": 2}, {"description": "Distance based, always on", "value": 3}, {"description": "Distance based, on command (Survey mode)", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Camera trigger", "longDesc": "This parameter sets the polarity of the trigger (0 = active low, 1 = active high )", "max": 1, "min": 0, "name": "TRIG_POLARITY", "rebootRequired": true, "shortDesc": "Camera trigger polarity", "type": "Int32", "values": [{"description": "Active low", "value": 0}, {"description": "Active high", "value": 1}]}, {"category": "Standard", "default": 1500, "group": "Camera trigger", "max": 2000, "min": 1000, "name": "TRIG_PWM_NEUTRAL", "rebootRequired": true, "shortDesc": "PWM neutral output on trigger pin", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 1900, "group": "Camera trigger", "max": 2000, "min": 1000, "name": "TRIG_PWM_SHOOT", "rebootRequired": true, "shortDesc": "PWM output to trigger shot", "type": "Int32", "units": "us"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 782097 will disable the buzzer audio notification.\nSetting this parameter to 782090 will disable the startup tune, while keeping\nall others enabled.", "max": 782097, "min": 0, "name": "CBRK_BUZZER", "rebootRequired": true, "shortDesc": "Circuit breaker for disabling buzzer", "type": "Int32"}, {"category": "Developer", "default": 121212, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 121212 will disable the flight termination action if triggered\nby the FailureDetector logic or if FMU is lost.\nThis circuit breaker does not affect the RC loss, data link loss, geofence,\nand takeoff failure detection safety logic.", "max": 121212, "min": 0, "name": "CBRK_FLIGHTTERM", "rebootRequired": true, "shortDesc": "Circuit breaker for flight termination", "type": "Int32"}, {"category": "Developer", "default": 22027, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 22027 will disable IO safety.\nWARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 22027, "min": 0, "name": "CBRK_IO_SAFETY", "shortDesc": "Circuit breaker for IO safety", "type": "Int32"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 894281 will disable the power valid\nchecks in the commander.\nWARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 894281, "min": 0, "name": "CBRK_SUPPLY_CHK", "shortDesc": "Circuit breaker for power supply check", "type": "Int32"}, {"category": "Developer", "default": 197848, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 197848 will disable the USB connected\nchecks in the commander, setting it to 0 keeps them enabled (recommended).\nWe are generally recommending to not fly with the USB link\nconnected and production vehicles should set this parameter to\nzero to prevent users from flying USB powered. However, for R&D purposes\nit has proven over the years to work just fine.", "max": 197848, "min": 0, "name": "CBRK_USB_CHK", "shortDesc": "Circuit breaker for USB link check", "type": "Int32"}, {"category": "Developer", "default": 0, "group": "Circuit Breaker", "longDesc": "Setting this parameter to 159753 will enable arming in fixed-wing\nmode for VTOLs.\nWARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "max": 159753, "min": 0, "name": "CBRK_VTOLARMING", "shortDesc": "Circuit breaker for arming in fixed-wing mode check", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Note: actuator failure needs to be enabled and configured via FD_ACT_*\nparameters.", "max": 3, "min": 0, "name": "COM_ACT_FAIL_ACT", "shortDesc": "Set the actuator failure failsafe mode", "type": "Int32", "values": [{"description": "Warning only", "value": 0}, {"description": "Hold mode", "value": 1}, {"description": "Land mode", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Terminate", "value": 4}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Set 0 to prevent accidental use of the vehicle e.g. for safety or maintenance reasons.", "name": "COM_ARMABLE", "shortDesc": "Flag to allow arming", "type": "Int32", "values": [{"description": "Disallow arming", "value": 0}, {"description": "Allow arming", "value": 1}]}, {"category": "Standard", "default": 10, "group": "Commander", "longDesc": "Used if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_ID", "shortDesc": "Arm authorizer system id", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Methods:\n- one arm: request authorization and arm when authorization is received\n- two step arm: 1st arm command request an authorization and\n2nd arm command arm the drone if authorized\nUsed if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_MET", "shortDesc": "Arm authorization method", "type": "Int32", "values": [{"description": "one arm", "value": 0}, {"description": "two step arm", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "By default off. The default allows to arm the vehicle without a arm authorization.", "name": "COM_ARM_AUTH_REQ", "shortDesc": "Require arm authorization to arm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "increment": 0.1, "longDesc": "Timeout for authorizer answer.\nUsed if arm authorization is requested by COM_ARM_AUTH_REQ.", "name": "COM_ARM_AUTH_TO", "shortDesc": "Arm authorization timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Commander", "increment": 0.01, "longDesc": "Threshold for battery percentage below arming is prohibited.\nA negative value means BAT_CRIT_THR is the threshold.", "max": 0.9, "min": -1.0, "name": "COM_ARM_BAT_MIN", "shortDesc": "Minimum battery level for arming", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "If this parameter is set, the system will check ESC's online status and failures.\nThis param is specific for ESCs reporting status. It shall be used only if ESCs support telemetry.", "name": "COM_ARM_CHK_ESCS", "shortDesc": "Enable checks on ESCs that report telemetry", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This check detects if there are hardfault files present on the\nSD card. If so, and the parameter is enabled, arming is prevented.", "name": "COM_ARM_HFLT_CHK", "shortDesc": "Enable FMU SD card hardfault detection check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "Commander", "increment": 0.05, "max": 1.0, "min": 0.1, "name": "COM_ARM_IMU_ACC", "shortDesc": "Maximum accelerometer inconsistency between IMU units that will allow arming", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Commander", "increment": 0.01, "max": 0.3, "min": 0.02, "name": "COM_ARM_IMU_GYR", "shortDesc": "Maximum rate gyro inconsistency between IMU units that will allow arming", "type": "Float", "units": "rad/s"}, {"category": "Standard", "default": 60, "group": "Commander", "longDesc": "Set -1 to disable the check.", "max": 180, "min": 3, "name": "COM_ARM_MAG_ANG", "shortDesc": "Maximum magnetic field inconsistency between units that will allow arming", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Commander", "longDesc": "Check if the estimator detects a strong magnetic\ndisturbance (check enabled by EKF2_MAG_CHECK)", "name": "COM_ARM_MAG_STR", "shortDesc": "Enable mag strength preflight check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Deny arming", "value": 1}, {"description": "Warning only", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The default allows to arm the vehicle without a valid mission.", "name": "COM_ARM_MIS_REQ", "shortDesc": "Require valid mission to arm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "This check detects if the Open Drone ID system is missing.\nDepending on the value of the parameter, the check can be\ndisabled, warn only or deny arming.", "name": "COM_ARM_ODID", "shortDesc": "Enable Drone ID system detection and health check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Enforce Open Drone ID system presence", "value": 2}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This check detects if the FMU SD card is missing.\nDepending on the value of the parameter, the check can be\ndisabled, warn only or deny arming.", "name": "COM_ARM_SDCARD", "shortDesc": "Enable FMU SD card detection check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warning only", "value": 1}, {"description": "Enforce SD card presence", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "0: Arming/disarming triggers on switch transition.\n1: Arming/disarming triggers when holding the momentary button down like the stick gesture.", "name": "COM_ARM_SWISBTN", "shortDesc": "Arm switch is a momentary button", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Configures whether arming is allowed without GNSS, for modes that require a global position\n(specifically, in those modes when a check defined by EKF2_GPS_CHECK fails).\nThe settings deny arming and warn, allow arming and warn, or silently allow arming.", "name": "COM_ARM_WO_GPS", "shortDesc": "Arming without GNSS configuration", "type": "Int32", "values": [{"description": "Deny arming", "value": 0}, {"description": "Allow arming (with warning)", "value": 1}, {"description": "Allow arming (no warning)", "value": 2}]}, {"category": "Standard", "default": 95.0, "group": "Commander", "increment": 1.0, "longDesc": "The check fails if the CPU load is above this threshold for 2s.\nA negative value disables the check.", "max": 100.0, "min": -1.0, "name": "COM_CPU_MAX", "shortDesc": "Maximum allowed CPU load to still arm", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Commander", "increment": 0.1, "longDesc": "A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be\nautomatically disarmed in case a landing situation has been detected during this period.\nA zero or negative value means that automatic disarming triggered by landing detection is disabled.", "name": "COM_DISARM_LAND", "shortDesc": "Time-out for auto disarm after landing", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "0: Disallow disarming when not landed\n1: Allow disarming in multicopter flight in modes where\nthe thrust is directly controlled by thr throttle stick\ne.g. Stabilized, Acro", "name": "COM_DISARM_MAN", "shortDesc": "Allow disarming via switch/stick/button on multicopters in manual thrust modes", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Commander", "increment": 0.1, "longDesc": "A non-zero, positive value specifies the time in seconds, within which the\nvehicle is expected to take off after arming. In case the vehicle didn't takeoff\nwithin the timeout it disarms again.\nA negative value disables autmoatic disarming triggered by a pre-takeoff timeout.", "name": "COM_DISARM_PRFLT", "shortDesc": "Time-out for auto disarm if not taking off", "type": "Float", "units": "s"}, {"bitmask": [{"description": "Mission", "index": 0}, {"description": "Auto modes", "index": 1}, {"description": "Offboard", "index": 2}, {"description": "External Mode", "index": 3}, {"description": "Altitude Cruise", "index": 4}], "category": "Standard", "default": 0, "group": "Commander", "longDesc": "Specify modes in which ground control station connection loss is ignored and no failsafe action is triggered.\nSee also COM_RCL_EXCEPT.", "max": 31, "min": 0, "name": "COM_DLL_EXCEPT", "shortDesc": "Datalink loss exceptions", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10, "group": "Commander", "increment": 1, "longDesc": "After this amount of seconds without datalink, the GCS connection lost mode triggers", "max": 300, "min": 5, "name": "COM_DL_LOSS_T", "shortDesc": "GCS connection loss time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "longDesc": "Before entering failsafe (RTL, Land, Hold), wait COM_FAIL_ACT_T seconds in Hold mode\nfor the user to realize.\nDuring that time the user can switch modes, but cannot take over control via the stick override feature (see COM_RC_OVERRIDE).\nAfterwards the configured failsafe action is triggered and the user may use stick override.\nA zero value disables the delay.", "max": 25.0, "min": 0.0, "name": "COM_FAIL_ACT_T", "shortDesc": "Delay between failsafe condition triggered and failsafe reaction", "type": "Float", "units": "s"}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This number is incremented automatically after every flight on\ndisarming in order to remember the next flight UUID.\nThe first flight is 0.", "min": 0, "name": "COM_FLIGHT_UUID", "shortDesc": "Next flight UUID", "type": "Int32", "volatile": true}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE1", "shortDesc": "Mode slot 1", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "Altitude Cruise", "value": 16}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE2", "shortDesc": "Mode slot 2", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "Altitude Cruise", "value": 16}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE3", "shortDesc": "Mode slot 3", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "Altitude Cruise", "value": 16}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE4", "shortDesc": "Mode slot 4", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "Altitude Cruise", "value": 16}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE5", "shortDesc": "Mode slot 5", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "Altitude Cruise", "value": 16}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "If the main switch channel is in this range the\nselected flight mode will be applied.", "name": "COM_FLTMODE6", "shortDesc": "Mode slot 6", "type": "Int32", "values": [{"description": "Unassigned", "value": -1}, {"description": "Manual", "value": 0}, {"description": "Altitude", "value": 1}, {"description": "Position", "value": 2}, {"description": "Mission", "value": 3}, {"description": "Hold", "value": 4}, {"description": "Return", "value": 5}, {"description": "Acro", "value": 6}, {"description": "Offboard", "value": 7}, {"description": "Stabilized", "value": 8}, {"description": "Position Slow", "value": 9}, {"description": "Takeoff", "value": 10}, {"description": "Land", "value": 11}, {"description": "Follow Me", "value": 12}, {"description": "Precision Land", "value": 13}, {"description": "Altitude Cruise", "value": 16}, {"description": "External Mode 1", "value": 100}, {"description": "External Mode 2", "value": 101}, {"description": "External Mode 3", "value": 102}, {"description": "External Mode 4", "value": 103}, {"description": "External Mode 5", "value": 104}, {"description": "External Mode 6", "value": 105}, {"description": "External Mode 7", "value": 106}, {"description": "External Mode 8", "value": 107}]}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when the remaining flight time is below\nthe estimated time it takes to reach the RTL destination.", "name": "COM_FLTT_LOW_ACT", "shortDesc": "Remaining flight time low failsafe", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Return", "value": 3}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Describes the intended use of the vehicle.\nCan be used by ground control software or log post processing.\nThis param does not influence the behavior within the firmware. This means for example the control logic is independent of the setting of this param (but depends on other params).", "name": "COM_FLT_PROFILE", "shortDesc": "User Flight Profile", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Pro User", "value": 100}, {"description": "Flight Tester", "value": 200}, {"description": "Developer", "value": 300}]}, {"category": "Standard", "default": -1, "group": "Commander", "longDesc": "The vehicle aborts the current operation and returns to launch when\nthe time since takeoff is above this value. It is not possible to resume the\nmission or switch to any auto mode other than RTL or Land. Taking over in any manual\nmode is still possible.\nStarting from 90% of the maximum flight time, a warning message will be sent\nevery 1 minute with the remaining time until automatic RTL.\nSet to -1 to disable.", "min": -1, "name": "COM_FLT_TIME_MAX", "shortDesc": "Maximum allowed flight time", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Force safety when the vehicle disarms", "name": "COM_FORCE_SAFETY", "shortDesc": "Enable force safety", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 120, "group": "Commander", "longDesc": "After this amount of seconds without datalink the data link lost mode triggers", "max": 3600, "min": 60, "name": "COM_HLDL_LOSS_T", "shortDesc": "High Latency Datalink loss time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "After a data link loss: after this number of seconds with a healthy datalink the 'datalink loss'\nflag is set back to false", "max": 60, "min": 0, "name": "COM_HLDL_REG_T", "shortDesc": "High Latency Datalink regain time threshold", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "Set home position automatically if possible.\nDuring missions, the latitude/longitude of the home position is locked and will not reset during intermediate landings.\nIt will only update once the mission is complete or landed outside of a mission.\nHowever, the altitude is still being adjusted to correct for GNSS vertical drift in the first 2 minutes after takeoff.", "name": "COM_HOME_EN", "rebootRequired": true, "shortDesc": "Home position enabled", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "If set to true, the autopilot is allowed to set its home position after takeoff\nThe true home position is back-computed if a local position is estimate if available.\nIf no local position is available, home is set to the current position.", "name": "COM_HOME_IN_AIR", "shortDesc": "Allows setting the home position after takeoff", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when an imbalanced propeller is detected by the failure detector.\nSee also FD_IMB_PROP_THR to set the failure threshold.", "name": "COM_IMB_PROP_ACT", "shortDesc": "Imbalanced propeller failsafe mode", "type": "Int32", "values": [{"description": "Disabled", "value": -1}, {"description": "Warning", "value": 0}, {"description": "Return", "value": 1}, {"description": "Land", "value": 2}]}, {"category": "Standard", "default": 5.0, "group": "Commander", "increment": 0.1, "longDesc": "Use RC_MAP_KILL_SW to map a kill switch.", "max": 30.0, "min": 0.0, "name": "COM_KILL_DISARM", "shortDesc": "Timeout value for disarming when kill switch is engaged", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Commander", "longDesc": "A non-zero, positive value specifies the timeframe in seconds within failure detector is allowed to disarm the vehicle\nif attitude exceeds the limits defined in FD_FAIL_P and FD_FAIL_R.\nThe check is not executed for flight modes that do support acrobatic maneuvers, e.g: Acro (MC/FW) and Manual (FW).\nA zero or negative value means that the check is disabled.", "max": 5.0, "min": -1.0, "name": "COM_LKDOWN_TKO", "shortDesc": "Timeout for detecting a failure after takeoff", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Action the system takes at critical battery. See also BAT_CRIT_THR and BAT_EMERGEN_THR\nfor definition of battery states.", "name": "COM_LOW_BAT_ACT", "shortDesc": "Battery failsafe mode", "type": "Int32", "values": [{"description": "Warning", "value": 0}, {"description": "Land mode", "value": 2}, {"description": "Return at critical level, land at emergency level", "value": 3}]}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE0_HASH", "shortDesc": "External mode identifier 0", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE1_HASH", "shortDesc": "External mode identifier 1", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE2_HASH", "shortDesc": "External mode identifier 2", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE3_HASH", "shortDesc": "External mode identifier 3", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE4_HASH", "shortDesc": "External mode identifier 4", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE5_HASH", "shortDesc": "External mode identifier 5", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE6_HASH", "shortDesc": "External mode identifier 6", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Commander", "longDesc": "This parameter is automatically set to identify external modes. It ensures that modes\nget assigned to the same index independent from their startup order,\nwhich is required when mapping an external mode to an RC switch.", "name": "COM_MODE7_HASH", "shortDesc": "External mode identifier 7", "type": "Int32", "volatile": true}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "By default disabled for safety reasons", "name": "COM_MODE_ARM_CHK", "shortDesc": "Allow external mode registration while armed", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "If set, enables the actuator test interface via MAVLink (ACTUATOR_TEST), that\nallows spinning the motors and moving the servos for testing purposes.", "name": "COM_MOT_TEST_EN", "shortDesc": "Enable Actuator Testing", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 5.0, "group": "Commander", "increment": 0.01, "max": 60.0, "min": 0.0, "name": "COM_OBC_LOSS_T", "shortDesc": "Time-out to wait when onboard computer connection is lost before warning about loss connection", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The offboard loss failsafe will only be entered after a timeout,\nset by COM_OF_LOSS_T in seconds.", "name": "COM_OBL_RC_ACT", "shortDesc": "Set offboard loss failsafe mode", "type": "Int32", "values": [{"description": "Position mode", "value": 0}, {"description": "Altitude mode", "value": 1}, {"description": "Stabilized", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Land mode", "value": 4}, {"description": "Hold mode", "value": 5}, {"description": "Terminate", "value": 6}, {"description": "Disarm", "value": 7}]}, {"category": "Standard", "default": 1.0, "group": "Commander", "increment": 0.01, "longDesc": "See COM_OBL_RC_ACT to configure action.", "max": 60.0, "min": 0.0, "name": "COM_OF_LOSS_T", "shortDesc": "Time-out to wait when offboard connection is lost before triggering offboard lost action", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "name": "COM_PARACHUTE", "shortDesc": "Expect and require a healthy MAVLink parachute system", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "longDesc": "This is the horizontal position error (EPH) threshold that will trigger a failsafe.\nIf the previous position error was below this threshold, there is an additional\nfactor of 2.5 applied (threshold for invalidation 2.5 times the one for validation).\nOnly used for multicopters and VTOLs in hover mode.\nIndependent from estimator positioning data timeout threshold (see EKF2_NOAID_TOUT).\nSet to -1 to disable.", "max": 400.0, "min": -1.0, "name": "COM_POS_FS_EPH", "shortDesc": "Horizontal position error threshold for hovering systems", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when the estimated position has an accuracy below the specified threshold.\nSee COM_POS_LOW_EPH to set the failsafe threshold.\nThe failsafe action is only executed if the vehicle is in auto mission or auto loiter mode,\notherwise it is only a warning.", "name": "COM_POS_LOW_ACT", "shortDesc": "Low position accuracy action", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold", "value": 2}, {"description": "Return", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land", "value": 5}]}, {"category": "Standard", "default": -1.0, "group": "Commander", "longDesc": "This triggers the action specified in COM_POS_LOW_ACT if the estimated position accuracy is below this threshold.\nLocal position has to be still declared valid, which requires some kind of velocity aiding or large dead-reckoning time (EKF2_NOAID_TOUT),\nand a high failsafe threshold (COM_POS_FS_EPH).\nSet to -1 to disable.", "max": 1000.0, "min": -1.0, "name": "COM_POS_LOW_EPH", "shortDesc": "Low position accuracy failsafe threshold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Commander", "longDesc": "This configures a check to verify the expected number of 5V rail power supplies are present. By default only one is expected.\nNote: CBRK_SUPPLY_CHK disables all power checks including this one.", "max": 4, "min": 0, "name": "COM_POWER_COUNT", "shortDesc": "Required number of redundant power modules", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Condition to enter the prearmed state, an intermediate state between disarmed and armed\nin which non-throttling actuators are active.", "name": "COM_PREARM_MODE", "shortDesc": "Condition to enter prearmed mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Safety button", "value": 1}, {"description": "Always", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Commander", "name": "COM_QC_ACT", "shortDesc": "Set action after a quadchute", "type": "Int32", "values": [{"description": "Warning only", "value": -1}, {"description": "Return mode", "value": 0}, {"description": "Land mode", "value": 1}, {"description": "Hold mode", "value": 2}]}, {"category": "Standard", "default": 95.0, "group": "Commander", "increment": 1.0, "longDesc": "The check fails if the RAM usage is above this threshold.\nA negative value disables the check.", "max": 100.0, "min": -1.0, "name": "COM_RAM_MAX", "shortDesc": "Maximum allowed RAM usage to pass checks", "type": "Float", "units": "%"}, {"bitmask": [{"description": "Mission", "index": 0}, {"description": "Auto modes", "index": 1}, {"description": "Offboard", "index": 2}, {"description": "External Mode", "index": 3}, {"description": "Altitude Cruise", "index": 4}], "category": "Standard", "default": 0, "group": "Commander", "longDesc": "Specify modes in which stick input is ignored and no failsafe action is triggered.\nExternal modes requiring stick input will still failsafe.\nAuto modes are: Hold, Takeoff, Land, RTL, Descend, Follow Target, Precland, Orbit.", "max": 31, "min": 0, "name": "COM_RCL_EXCEPT", "shortDesc": "Manual control loss exceptions", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "Commander", "longDesc": "Selects stick input selection behavior:\neither a traditional remote control receiver (RC) or a MAVLink joystick (MANUAL_CONTROL message)\nPriority sources are immediately switched to whenever they get valid.\n0 RC only. Requires valid RC calibration.\n1 MAVLink only. RC and related checks are disabled.\n2 Switches only if current source becomes invalid.\n3 Locks to the first valid source until reboot.\n4 Ignores all sources.\n5 RC priority, then MAVLink (lower instance before higher)\n6 MAVLink priority (lower instance before higher), then RC\n7 RC priority, then MAVLink (higher instance before lower)\n8 MAVLink priority (higher instance before lower), then RC", "max": 8, "min": 0, "name": "COM_RC_IN_MODE", "shortDesc": "Manual control input source configuration", "type": "Int32", "values": [{"description": "RC only", "value": 0}, {"description": "MAVLink only", "value": 1}, {"description": "RC or MAVLink with fallback", "value": 2}, {"description": "RC or MAVLink keep first", "value": 3}, {"description": "Disable manual control", "value": 4}, {"description": "Prio: RC > MAVL 1 > MAVL 2", "value": 5}, {"description": "Prio: MAVL 1 > MAVL 2 > RC", "value": 6}, {"description": "Prio: RC > MAVL 2 > MAVL 1", "value": 7}, {"description": "Prio: MAVL 2 > MAVL 1 > RC", "value": 8}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Commander", "increment": 0.1, "longDesc": "The time in seconds without a new setpoint from RC or Joystick, after which the connection is considered lost.\nThis must be kept short as the vehicle will use the last supplied setpoint until the timeout triggers.\nEnsure the value is not set lower than the update interval of the RC or Joystick.", "max": 35.0, "min": 0.0, "name": "COM_RC_LOSS_T", "shortDesc": "Manual control loss timeout", "type": "Float", "units": "s"}, {"bitmask": [{"description": "Enable override during auto modes (except for in critical battery reaction)", "index": 0}, {"description": "Enable override during offboard mode", "index": 1}], "category": "Standard", "default": 1, "group": "Commander", "longDesc": "When enabled, moving the sticks more than COM_RC_STICK_OV\nimmediately gives control back to the pilot by switching to Position mode and\nif position is unavailable Altitude mode.\nNote: Only has an effect on multicopters, and VTOLs in multicopter mode.", "max": 3, "min": 0, "name": "COM_RC_OVERRIDE", "shortDesc": "Enable manual control stick override", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 0, "default": 30.0, "group": "Commander", "increment": 0.05, "longDesc": "If COM_RC_OVERRIDE is enabled and the joystick input is moved more than this threshold\nthe autopilot the pilot takes over control.", "max": 80.0, "min": 5.0, "name": "COM_RC_STICK_OV", "shortDesc": "Stick override threshold", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "increment": 0.1, "longDesc": "The minimal time from arming the motors until moving the vehicle is possible is COM_SPOOLUP_TIME seconds.\nGoal:\n- Motors and propellers spool up to idle speed before getting commanded to spin faster\n- Timeout for ESCs and smart batteries to successfulyy do failure checks\ne.g. for stuck rotors before the vehicle is off the ground", "max": 30.0, "min": 0.0, "name": "COM_SPOOLUP_TIME", "shortDesc": "Enforced delay between arming and further navigation", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The mode transition after TAKEOFF has completed successfully.", "name": "COM_TAKEOFF_ACT", "shortDesc": "Action after TAKEOFF has been accepted", "type": "Int32", "values": [{"description": "Hold", "value": 0}, {"description": "Mission (if valid)", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "Allows to start the vehicle by throwing it into the air.", "name": "COM_THROW_EN", "shortDesc": "Enable throw-start", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Commander", "increment": 0.1, "longDesc": "When the throw launch is enabled, the drone will only allow motors to spin after this speed\nis exceeded before detecting the freefall. This is a safety feature to ensure the drone does\nnot turn on after accidental drop or a rapid movement before the throw.\nSet to 0 to disable.", "min": 0.0, "name": "COM_THROW_SPEED", "shortDesc": "Minimum speed for the throw start", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Commander", "longDesc": "This is the horizontal velocity error (EVH) threshold that will trigger a failsafe.\nThe default is appropriate for a multicopter. Can be increased for a fixed-wing.\nIf the previous velocity error was below this threshold, there is an additional\nfactor of 2.5 applied (threshold for invalidation 2.5 times the one for validation).", "min": 0.0, "name": "COM_VEL_FS_EVH", "shortDesc": "Horizontal velocity error threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Commander", "increment": 0.1, "longDesc": "Wind speed threshold above which an automatic failsafe action is triggered.\nFailsafe action can be specified with COM_WIND_MAX_ACT.", "min": -1.0, "name": "COM_WIND_MAX", "shortDesc": "High wind speed failsafe threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Commander", "increment": 1, "longDesc": "Action the system takes when a wind speed above the specified threshold is detected.\nSee COM_WIND_MAX to set the failsafe threshold.\nIf enabled, it is not possible to resume the mission or switch to any auto mode other than\nRTL or Land if this threshold is exceeded. Taking over in any manual\nmode is still possible.", "name": "COM_WIND_MAX_ACT", "shortDesc": "High wind failsafe mode", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold", "value": 2}, {"description": "Return", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Commander", "increment": 0.1, "longDesc": "A warning is triggered if the currently estimated wind speed is above this value.\nWarning is sent periodically (every 1 minute).\nSet to -1 to disable.", "min": -1.0, "name": "COM_WIND_WARN", "shortDesc": "Wind speed warning threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "Commander", "longDesc": "The GCS connection loss failsafe will only be entered after a timeout,\nset by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected\naction will be executed.", "max": 6, "min": 0, "name": "NAV_DLL_ACT", "shortDesc": "Set GCS connection loss failsafe mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Hold mode", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Terminate", "value": 5}, {"description": "Disarm", "value": 6}]}, {"category": "Standard", "default": 2, "group": "Commander", "longDesc": "The manual control loss failsafe will only be entered after a timeout,\nset by COM_RC_LOSS_T in seconds.", "max": 6, "min": 1, "name": "NAV_RCL_ACT", "shortDesc": "Set manual control loss failsafe mode", "type": "Int32", "values": [{"description": "Hold mode", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Terminate", "value": 5}, {"description": "Disarm", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "max": 0.5, "min": 0.0, "name": "EKF2_ABIAS_INIT", "rebootRequired": true, "shortDesc": "1-sigma IMU accelerometer switch-on bias", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "EKF2", "longDesc": "If the magnitude of the IMU accelerometer vector exceeds this value, the EKF accel bias state estimation will be inhibited. This reduces the adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale factor errors on the accel bias estimates.", "max": 200.0, "min": 20.0, "name": "EKF2_ABL_ACCLIM", "shortDesc": "Maximum IMU accel magnitude that allows IMU bias learning", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "If the magnitude of the IMU angular rate vector exceeds this value, the EKF accel bias state estimation will be inhibited. This reduces the adverse effect of rapid rotation rates and associated errors on the accel bias estimates.", "max": 20.0, "min": 2.0, "name": "EKF2_ABL_GYRLIM", "shortDesc": "Maximum IMU gyro angular rate magnitude that allows IMU bias learning", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "EKF2", "longDesc": "The ekf accel bias states will be limited to within a range equivalent to +- of this value.", "max": 0.8, "min": 0.0, "name": "EKF2_ABL_LIM", "shortDesc": "Accelerometer bias learning limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay. This parameter controls the time constant of the decay.", "max": 1.0, "min": 0.1, "name": "EKF2_ABL_TAU", "shortDesc": "Accel bias learning inhibit time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.003, "group": "EKF2", "max": 0.01, "min": 0.0, "name": "EKF2_ACC_B_NOISE", "shortDesc": "Process noise for IMU accelerometer bias prediction", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.35, "group": "EKF2", "max": 1.0, "min": 0.01, "name": "EKF2_ACC_NOISE", "shortDesc": "Accelerometer noise for covariance prediction", "type": "Float", "units": "m/s^2"}, {"bitmask": [{"description": "Horizontal position", "index": 0}, {"description": "Vertical position", "index": 1}], "category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Horizontal position fusion 1 : Vertical position fusion", "max": 3, "min": 0, "name": "EKF2_AGP_CTRL", "shortDesc": "Aux global position (AGP) sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_AGP_DELAY", "rebootRequired": true, "shortDesc": "Aux global position estimator delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_AGP_GATE", "shortDesc": "Gate size for aux global position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Automatic: reset on fusion timeout if no other source of position is available Dead-reckoning: reset on fusion timeout if no source of velocity is available", "name": "EKF2_AGP_MODE", "shortDesc": "Fusion reset mode", "type": "Int32", "values": [{"description": "Automatic", "value": 0}, {"description": "Dead-reckoning", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.9, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_AGP_NOISE", "shortDesc": "Measurement noise for aux global position measurements", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "EKF2", "max": 0.5, "min": 0.0, "name": "EKF2_ANGERR_INIT", "rebootRequired": true, "shortDesc": "1-sigma tilt angle uncertainty after gravity vector alignment", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "longDesc": "Airspeed data is fused for wind estimation if above this threshold. Set to 0 to disable airspeed fusion. For reliable wind estimation both sideslip (see EKF2_FUSE_BETA) and airspeed fusion should be enabled. Only applies to fixed-wing vehicles (or VTOLs in fixed-wing mode).", "min": 0.0, "name": "EKF2_ARSP_THR", "shortDesc": "Airspeed fusion threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "max": 50.0, "min": 5.0, "name": "EKF2_ASPD_MAX", "shortDesc": "Maximum airspeed used for baro static pressure compensation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_ASP_DELAY", "rebootRequired": true, "shortDesc": "Airspeed measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_AVEL_DELAY", "rebootRequired": true, "shortDesc": "Auxiliary Velocity Estimate delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "If this parameter is enabled then the estimator will make use of the barometric height measurements to estimate its height in addition to other height sources (if activated).", "name": "EKF2_BARO_CTRL", "shortDesc": "Barometric sensor height aiding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_BARO_DELAY", "rebootRequired": true, "shortDesc": "Barometer measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_BARO_GATE", "shortDesc": "Gate size for barometric and GPS height fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.5, "group": "EKF2", "max": 15.0, "min": 0.01, "name": "EKF2_BARO_NOISE", "shortDesc": "Measurement noise for barometric altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by bluff body drag along the forward/reverse axis when flying a multi-copter which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis.", "max": 200.0, "min": 0.0, "name": "EKF2_BCOEF_X", "shortDesc": "X-axis ballistic coefficient used for multi-rotor wind estimation", "type": "Float", "units": "kg/m^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by bluff body drag along the right/left axis when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed squared. The predicted drag from the rotors is specified separately by the EKF2_MCOEF parameter. Set this parameter to zero to turn off the bluff body drag model for this axis.", "max": 200.0, "min": 0.0, "name": "EKF2_BCOEF_Y", "shortDesc": "Y-axis ballistic coefficient used for multi-rotor wind estimation", "type": "Float", "units": "kg/m^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_BETA_GATE", "shortDesc": "Gate size for synthetic sideslip fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 1.0, "min": 0.1, "name": "EKF2_BETA_NOISE", "shortDesc": "Noise for synthetic sideslip fusion", "type": "Float", "units": "m/s"}, {"bitmask": [{"description": "use geo_lookup declination", "index": 0}, {"description": "save EKF2_MAG_DECL on disarm", "index": 1}], "category": "Standard", "default": 3, "group": "EKF2", "longDesc": "Set bits in the following positions to enable functions. 0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value. 1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms.", "max": 3, "min": 0, "name": "EKF2_DECL_TYPE", "rebootRequired": true, "shortDesc": "Integer bitmask controlling handling of magnetic declination", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 200.0, "group": "EKF2", "longDesc": "Defines the delay between the current time and the delayed-time horizon. This value should be at least as large as the largest EKF2_XXX_DELAY parameter.", "max": 1000.0, "min": 0.0, "name": "EKF2_DELAY_MAX", "rebootRequired": true, "shortDesc": "Maximum delay of all the aiding sensors", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Activate wind speed estimation using specific-force measurements and a drag model defined by EKF2_BCOEF_[XY] and EKF2_MCOEF. Only use on vehicles that have their thrust aligned with the Z axis and no thrust in the XY plane.", "name": "EKF2_DRAG_CTRL", "shortDesc": "Multirotor wind estimation selection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 2.5, "group": "EKF2", "longDesc": "Used by the multi-rotor specific drag force model. Increasing this makes the multi-rotor wind estimates adjust more slowly.", "max": 10.0, "min": 0.5, "name": "EKF2_DRAG_NOISE", "shortDesc": "Specific drag force observation noise variance", "type": "Float", "units": "(m/s^2)^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.4, "group": "EKF2", "max": 5.0, "min": 0.5, "name": "EKF2_EAS_NOISE", "shortDesc": "Measurement noise for airspeed fusion", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "EKF2", "name": "EKF2_EN", "shortDesc": "EKF2 enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "When enabled, constant position fusion is enabled when the vehicle is landed and armed. This is intended for IC engine warmup (e.g., fuel engines on catapult) to allow mode transitions to auto/takeoff despite vibrations from running engines.", "name": "EKF2_ENGINE_WRM", "shortDesc": "Enable constant position fusion during engine warmup", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.05, "name": "EKF2_EVA_NOISE", "shortDesc": "Measurement noise for vision angle measurements", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_EVP_GATE", "shortDesc": "Gate size for vision position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_EVP_NOISE", "shortDesc": "Measurement noise for vision position measurements", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_EVV_GATE", "shortDesc": "Gate size for vision velocity estimate fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "longDesc": "Used to lower bound or replace the uncertainty included in the message", "min": 0.01, "name": "EKF2_EVV_NOISE", "shortDesc": "Measurement noise for vision velocity measurements", "type": "Float", "units": "m/s"}, {"bitmask": [{"description": "Horizontal position", "index": 0}, {"description": "Vertical position", "index": 1}, {"description": "3D velocity", "index": 2}, {"description": "Yaw", "index": 3}], "category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Horizontal position fusion 1 : Vertical position fusion 2 : 3D velocity fusion 3 : Yaw", "max": 15, "min": 0, "name": "EKF2_EV_CTRL", "shortDesc": "External vision (EV) sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_EV_DELAY", "rebootRequired": true, "shortDesc": "Vision Position Estimator delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "If set to 0 (default) the measurement noise is taken from the vision message and the EV noise parameters are used as a lower bound. If set to 1 the observation noise is set from the parameters directly,", "name": "EKF2_EV_NOISE_MD", "shortDesc": "External vision (EV) noise mode", "type": "Int32", "values": [{"description": "EV reported variance (parameter lower bound)", "value": 0}, {"description": "EV noise parameters", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_X", "shortDesc": "X position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_Y", "shortDesc": "Y position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_EV_POS_Z", "shortDesc": "Z position of VI sensor focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0, "group": "EKF2", "longDesc": "External vision will only be started and fused if the quality metric is above this threshold. The quality metric is a completely optional field provided by some VIO systems.", "max": 100, "min": 0, "name": "EKF2_EV_QMIN", "shortDesc": "External vision (EV) minimum quality (optional)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "For reliable wind estimation both sideslip and airspeed fusion (see EKF2_ARSP_THR) should be enabled. Only applies to vehicles in fixed-wing mode or with airspeed fusion active. Note: side slip fusion is currently not supported for tailsitters.", "name": "EKF2_FUSE_BETA", "shortDesc": "Enable synthetic sideslip fusion", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "max": 0.2, "min": 0.0, "name": "EKF2_GBIAS_INIT", "rebootRequired": true, "shortDesc": "1-sigma IMU gyro switch-on bias", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "EKF2", "longDesc": "Sets the value of deadzone applied to negative baro innovations. Deadzone is enabled when EKF2_GND_EFF_DZ > 0.", "max": 10.0, "min": 0.0, "name": "EKF2_GND_EFF_DZ", "shortDesc": "Baro deadzone range for height fusion", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "EKF2", "longDesc": "Sets the maximum distance to the ground level where negative baro innovations are expected.", "max": 5.0, "min": 0.0, "name": "EKF2_GND_MAX_HGT", "shortDesc": "Height above ground level for ground effect zone", "type": "Float", "units": "m"}, {"bitmask": [{"description": "Sat count (EKF2_REQ_NSATS)", "index": 0}, {"description": "PDOP (EKF2_REQ_PDOP)", "index": 1}, {"description": "EPH (EKF2_REQ_EPH)", "index": 2}, {"description": "EPV (EKF2_REQ_EPV)", "index": 3}, {"description": "Speed accuracy (EKF2_REQ_SACC)", "index": 4}, {"description": "Horizontal position drift (EKF2_REQ_HDRIFT)", "index": 5}, {"description": "Vertical position drift (EKF2_REQ_VDRIFT)", "index": 6}, {"description": "Horizontal speed offset (EKF2_REQ_HDRIFT)", "index": 7}, {"description": "Vertical speed offset (EKF2_REQ_VDRIFT)", "index": 8}, {"description": "Spoofing", "index": 9}, {"description": "GPS fix type (EKF2_REQ_FIX)", "index": 10}, {"description": "Jamming", "index": 11}], "category": "Standard", "default": 2047, "group": "EKF2", "longDesc": "Each threshold value is defined by the parameter indicated next to the check. Drift and offset checks only run when the vehicle is on ground and stationary.", "max": 4095, "min": 0, "name": "EKF2_GPS_CHECK", "shortDesc": "Integer bitmask controlling GPS checks", "type": "Int32"}, {"bitmask": [{"description": "Lon/lat", "index": 0}, {"description": "Altitude", "index": 1}, {"description": "3D velocity", "index": 2}, {"description": "Dual antenna heading", "index": 3}], "category": "Standard", "default": 7, "group": "EKF2", "longDesc": "Set bits in the following positions to enable: 0 : Longitude and latitude fusion 1 : Altitude fusion 2 : 3D velocity fusion 3 : Dual antenna heading fusion", "max": 15, "min": 0, "name": "EKF2_GPS_CTRL", "shortDesc": "GNSS sensor aiding", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 110.0, "group": "EKF2", "longDesc": "GPS measurement delay relative to IMU measurement if PPS time correction is not available/enabled (PPS_CAP_ENABLE).", "max": 300.0, "min": 0.0, "name": "EKF2_GPS_DELAY", "rebootRequired": true, "shortDesc": "GPS measurement delay relative to IMU measurement", "type": "Float", "units": "ms"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Automatic: reset on fusion timeout if no other source of position is available. Dead-reckoning: reset on fusion timeout if no source of velocity is available.", "name": "EKF2_GPS_MODE", "shortDesc": "Fusion reset mode", "type": "Int32", "values": [{"description": "Automatic", "value": 0}, {"description": "Dead-reckoning", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward (roll) axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_X", "shortDesc": "X position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Right (pitch) axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_Y", "shortDesc": "Y position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Down (yaw) axis with origin relative to vehicle centre of gravity", "name": "EKF2_GPS_POS_Z", "shortDesc": "Z position of GPS antenna in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_GPS_P_GATE", "shortDesc": "Gate size for GNSS position fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "max": 10.0, "min": 0.01, "name": "EKF2_GPS_P_NOISE", "shortDesc": "Measurement noise for GNSS position", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_GPS_V_GATE", "shortDesc": "Gate size for GNSS velocity fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 5.0, "min": 0.01, "name": "EKF2_GPS_V_NOISE", "shortDesc": "Measurement noise for GNSS velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 360.0, "min": 0.0, "name": "EKF2_GPS_YAW_OFF", "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "EKF2", "max": 10.0, "min": 0.1, "name": "EKF2_GRAV_NOISE", "shortDesc": "Accelerometer measurement noise for gravity based observations", "type": "Float", "units": "g0"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "EKF2", "longDesc": "If no airspeed measurements are available, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes.", "max": 100.0, "min": 0.0, "name": "EKF2_GSF_TAS", "shortDesc": "Default value of true airspeed used in EKF-GSF AHRS calculation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "EKF2", "longDesc": "The ekf gyro bias states will be limited to within a range equivalent to +- of this value.", "max": 0.4, "min": 0.0, "name": "EKF2_GYR_B_LIM", "shortDesc": "Gyro bias learning limit", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.001, "group": "EKF2", "max": 0.01, "min": 0.0, "name": "EKF2_GYR_B_NOISE", "shortDesc": "Process noise for IMU rate gyro bias prediction", "type": "Float", "units": "rad/s^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.015, "group": "EKF2", "max": 0.1, "min": 0.0001, "name": "EKF2_GYR_NOISE", "shortDesc": "Rate gyro noise for covariance prediction", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.6, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_HDG_GATE", "shortDesc": "Gate size for heading fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "EKF2", "max": 1.0, "min": 0.01, "name": "EKF2_HEAD_NOISE", "shortDesc": "Measurement noise for magnetic heading fusion", "type": "Float", "units": "rad"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "When multiple height sources are enabled at the same time, the height estimate will always converge towards the reference height source selected by this parameter. The range sensor and vision options should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level. If GPS is set as reference but altitude fusion is disabled in EKF2_GPS_CTRL, the GPS altitude is still used to initiaize the bias of the other height sensors.", "name": "EKF2_HGT_REF", "rebootRequired": true, "shortDesc": "Determines the reference source of height data used by the EKF", "type": "Int32", "values": [{"description": "Barometric pressure", "value": 0}, {"description": "GPS", "value": 1}, {"description": "Range sensor", "value": 2}, {"description": "Vision", "value": 3}]}, {"bitmask": [{"description": "Gyro Bias", "index": 0}, {"description": "Accel Bias", "index": 1}, {"description": "Gravity vector fusion", "index": 2}], "category": "Standard", "default": 7, "group": "EKF2", "max": 7, "min": 0, "name": "EKF2_IMU_CTRL", "shortDesc": "IMU control", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_X", "shortDesc": "X position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_Y", "shortDesc": "Y position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_IMU_POS_Z", "shortDesc": "Z position of IMU in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "EKF2", "name": "EKF2_LOG_VERBOSE", "shortDesc": "Verbose logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "The heading is assumed to be observable when the body acceleration is greater than this parameter when a global position/velocity aiding source is active.", "max": 5.0, "min": 0.0, "name": "EKF2_MAG_ACCLIM", "shortDesc": "Horizontal acceleration threshold used for heading observability check", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.0001, "group": "EKF2", "max": 0.1, "min": 0.0, "name": "EKF2_MAG_B_NOISE", "shortDesc": "Process noise for body magnetic field prediction", "type": "Float", "units": "gauss/s"}, {"bitmask": [{"description": "Strength (EKF2_MAG_CHK_STR)", "index": 0}, {"description": "Inclination (EKF2_MAG_CHK_INC)", "index": 1}, {"description": "Wait for WMM", "index": 2}], "category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Bitmask to set which check is used to decide whether the magnetometer data is valid. If GNSS data is received, the magnetic field is compared to a World Magnetic Model (WMM), otherwise an average value is used. This check is useful to reject occasional hard iron disturbance. Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Magnetic field strength. Set tolerance using EKF2_MAG_CHK_STR 1 : Magnetic field inclination. Set tolerance using EKF2_MAG_CHK_INC 2 : Wait for GNSS to find the theoretical strength and inclination using the WMM", "max": 7, "min": 0, "name": "EKF2_MAG_CHECK", "shortDesc": "Magnetic field strength test selection", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "longDesc": "Maximum allowed deviation from the expected magnetic field inclination to pass the check.", "max": 90.0, "min": 0.0, "name": "EKF2_MAG_CHK_INC", "shortDesc": "Magnetic field inclination check tolerance", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "longDesc": "Maximum allowed deviation from the expected magnetic field strength to pass the check.", "max": 1.0, "min": 0.0, "name": "EKF2_MAG_CHK_STR", "shortDesc": "Magnetic field strength check tolerance", "type": "Float", "units": "gauss"}, {"category": "System", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "name": "EKF2_MAG_DECL", "shortDesc": "Magnetic declination", "type": "Float", "units": "deg", "volatile": true}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_MAG_DELAY", "rebootRequired": true, "shortDesc": "Magnetometer measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 6, "default": 0.001, "group": "EKF2", "max": 0.1, "min": 0.0, "name": "EKF2_MAG_E_NOISE", "shortDesc": "Process noise for earth magnetic field prediction", "type": "Float", "units": "gauss/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_MAG_GATE", "shortDesc": "Gate size for magnetometer XYZ component fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "EKF2", "max": 1.0, "min": 0.001, "name": "EKF2_MAG_NOISE", "shortDesc": "Measurement noise for magnetometer 3-axis fusion", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. The fusion of magnetometer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight. If set to 'Magnetic heading' magnetic heading fusion is used at all times. If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GNSS velocity measurements to align the yaw angle. If set to 'Init' the magnetometer is only used to initalize the heading.", "name": "EKF2_MAG_TYPE", "rebootRequired": true, "shortDesc": "Type of magnetometer fusion", "type": "Int32", "values": [{"description": "Automatic", "value": 0}, {"description": "Magnetic heading", "value": 1}, {"description": "None", "value": 5}, {"description": "Init", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "EKF2", "longDesc": "This parameter controls the prediction of drag produced by the propellers when flying a multi-copter, which enables estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the propeller axis of rotation is lost when passing through the rotor disc. This changes the momentum of the flow which creates a drag reaction force. When comparing un-ducted propellers of the same diameter, the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with propeller selection. Momentum drag is significantly higher for ducted rotors. To account for the drag produced by the body which scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y parameters. Set this parameter to zero to turn off the momentum drag model for both axis.", "max": 1.0, "min": 0.0, "name": "EKF2_MCOEF", "shortDesc": "Propeller momentum drag coefficient for multi-rotor wind estimation", "type": "Float", "units": "1/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.01, "group": "EKF2", "longDesc": "If the vehicle is on ground, is not moving as determined by the motion test and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is available at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground.", "min": 0.01, "name": "EKF2_MIN_RNG", "shortDesc": "Expected range finder reading when on ground", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Maximum number of IMUs to use for Multi-EKF. Set 0 to disable. Requires SENS_IMU_MODE 0.", "max": 4, "min": 0, "name": "EKF2_MULTI_IMU", "rebootRequired": true, "shortDesc": "Multi-EKF IMUs", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Maximum number of magnetometers to use for Multi-EKF. Set 0 to disable. Requires SENS_MAG_MODE 0.", "max": 4, "min": 0, "name": "EKF2_MULTI_MAG", "rebootRequired": true, "shortDesc": "Multi-EKF Magnetometers", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "EKF2", "max": 50.0, "min": 0.5, "name": "EKF2_NOAID_NOISE", "shortDesc": "Measurement noise for non-aiding position hold", "type": "Float", "units": "m"}, {"category": "Standard", "default": 5000000, "group": "EKF2", "longDesc": "Maximum lapsed time from last fusion of measurements that constrain velocity drift before the EKF will report the horizontal nav solution as invalid", "max": 10000000, "min": 500000, "name": "EKF2_NOAID_TOUT", "shortDesc": "Maximum inertial dead-reckoning time", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Enable optical flow fusion.", "name": "EKF2_OF_CTRL", "shortDesc": "Optical flow aiding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "EKF2", "longDesc": "Assumes measurement is timestamped at trailing edge of integration period", "max": 300.0, "min": 0.0, "name": "EKF2_OF_DELAY", "rebootRequired": true, "shortDesc": "Optical flow measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_OF_GATE", "shortDesc": "Gate size for optical flow fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Auto: use gyro from optical flow message if available, internal gyro otherwise. Internal: always use internal gyro", "name": "EKF2_OF_GYR_SRC", "shortDesc": "Optical flow angular rate compensation source", "type": "Int32", "values": [{"description": "Auto", "value": 0}, {"description": "Internal", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "longDesc": "Measurement noise for the optical flow sensor when it's reported quality metric is at the minimum", "min": 0.05, "name": "EKF2_OF_N_MAX", "shortDesc": "Optical flow maximum noise", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.15, "group": "EKF2", "longDesc": "Measurement noise for the optical flow sensor when it's reported quality metric is at the maximum", "min": 0.05, "name": "EKF2_OF_N_MIN", "shortDesc": "Optical flow minimum noise", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_X", "shortDesc": "X position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_Y", "shortDesc": "Y position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_OF_POS_Z", "shortDesc": "Z position of optical flow focal point in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "Optical Flow data will only be used in air if the sensor reports a quality metric >= EKF2_OF_QMIN", "max": 255, "min": 0, "name": "EKF2_OF_QMIN", "shortDesc": "In air optical flow minimum quality", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Optical Flow data will only be used on the ground if the sensor reports a quality metric >= EKF2_OF_QMIN_GND", "max": 255, "min": 0, "name": "EKF2_OF_QMIN_GND", "shortDesc": "On ground optical flow minimum quality", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_XN", "shortDesc": "Static pressure position error coefficient for the negative X axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forward flight, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_XP", "shortDesc": "Static pressure position error coefficient for the positive X axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the negative Y (LH) body axis. If the baro height estimate rises during sideways flight to the left, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_YN", "shortDesc": "Pressure position error coefficient for the negative Y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the positive Y (RH) body axis. If the baro height estimate rises during sideways flight to the right, then this will be a negative number.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_YP", "shortDesc": "Pressure position error coefficient for the positive Y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "EKF2", "longDesc": "This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the Z body axis.", "max": 0.5, "min": -0.5, "name": "EKF2_PCOEF_Z", "shortDesc": "Static pressure position error coefficient for the Z axis", "type": "Float"}, {"category": "Standard", "default": 10000, "group": "EKF2", "longDesc": "EKF prediction period in microseconds. This should ideally be an integer multiple of the IMU time delta. Actual filter update will be an integer multiple of IMU update.", "max": 20000, "min": 1000, "name": "EKF2_PREDICT_US", "shortDesc": "EKF prediction period", "type": "Int32", "units": "us"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "max": 100.0, "min": 2.0, "name": "EKF2_REQ_EPH", "shortDesc": "Required EPH to use GPS", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 100.0, "min": 2.0, "name": "EKF2_REQ_EPV", "shortDesc": "Required EPV to use GPS", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "EKF2", "longDesc": "Minimum GPS fix type required for GPS usage.", "name": "EKF2_REQ_FIX", "shortDesc": "Required GPS fix", "type": "Int32", "values": [{"description": "No fix required", "value": 0}, {"description": "2D fix", "value": 2}, {"description": "3D fix", "value": 3}, {"description": "RTCM code differential", "value": 4}, {"description": "RTK float", "value": 5}, {"description": "RTK fixed", "value": 6}, {"description": "Extrapolated", "value": 8}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "EKF2", "longDesc": "Minimum continuous period without GPS failure required to mark a healthy GPS status. It can be reduced to speed up initialization, but it's recommended to keep this unchanged for a vehicle.", "min": 0.1, "name": "EKF2_REQ_GPS_H", "rebootRequired": true, "shortDesc": "Required GPS health time on startup", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "max": 1.0, "min": 0.1, "name": "EKF2_REQ_HDRIFT", "shortDesc": "Maximum horizontal drift speed to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 6, "group": "EKF2", "max": 12, "min": 4, "name": "EKF2_REQ_NSATS", "shortDesc": "Required satellite count to use GPS", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "EKF2", "max": 5.0, "min": 1.5, "name": "EKF2_REQ_PDOP", "shortDesc": "Maximum PDOP to use GPS", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "max": 5.0, "min": 0.5, "name": "EKF2_REQ_SACC", "shortDesc": "Required speed accuracy to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "EKF2", "max": 1.5, "min": 0.1, "name": "EKF2_REQ_VDRIFT", "shortDesc": "Maximum vertical drift speed to use GPS", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 5.0, "group": "EKF2", "longDesc": "If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1).", "max": 10.0, "min": 1.0, "name": "EKF2_RNG_A_HMAX", "shortDesc": "Maximum height above ground allowed for conditional range aid mode", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements to estimate its height. This only applies when conditional range aid mode is activated (EKF2_RNG_CTRL = 1).", "max": 2.0, "min": 0.1, "name": "EKF2_RNG_A_VMAX", "shortDesc": "Maximum horizontal velocity allowed for conditional range aid mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "EKF2", "longDesc": "WARNING: Range finder measurements are less reliable and can experience unexpected errors. For these reasons, if accurate control of height relative to ground is required, it is recommended to use the MPC_ALT_MODE parameter instead, unless baro errors are severe enough to cause problems with landing and takeoff. If this parameter is enabled then the estimator will make use of the range finder measurements to estimate its height in addition to other height sources (if activated). Range sensor aiding can be enabled (i.e.: always use) or set in \"conditional\" mode. Conditional mode: This enables the range finder to be used during low speed (< EKF2_RNG_A_VMAX) and low altitude (< EKF2_RNG_A_HMAX) operation, eg takeoff and landing, where baro interference from rotor wash is excessive and can corrupt EKF state estimates. It is intended to be used where a vertical takeoff and landing is performed, and horizontal flight does not occur until above EKF2_RNG_A_HMAX.", "name": "EKF2_RNG_CTRL", "shortDesc": "Range sensor height aiding", "type": "Int32", "values": [{"description": "Disable range fusion", "value": 0}, {"description": "Enabled (conditional mode)", "value": 1}, {"description": "Enabled", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "max": 300.0, "min": 0.0, "name": "EKF2_RNG_DELAY", "rebootRequired": true, "shortDesc": "Range finder measurement delay relative to IMU measurements", "type": "Float", "units": "ms"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "EKF2", "longDesc": "Limit for fog detection. If the range finder measures a distance greater than this value, the measurement is considered to not be blocked by fog or rain. If there's a jump from larger than RNG_FOG to smaller than EKF2_RNG_FOG, the measurement may gets rejected. 0 - disabled", "max": 20.0, "min": 0.0, "name": "EKF2_RNG_FOG", "shortDesc": "Maximum distance at which the range finder could detect fog (m)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_RNG_GATE", "shortDesc": "Gate size for range finder fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "To be used, the time derivative of the distance sensor measurements projected on the vertical axis needs to be statistically consistent with the estimated vertical velocity of the drone. Decrease this value to make the filter more robust against range finder faulty data (stuck, reflections, ...). Note: tune the range finder noise parameters (EKF2_RNG_NOISE and EKF2_RNG_SFE) before tuning this gate.", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_K_GATE", "shortDesc": "Gate size used for range finder kinematic consistency check", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "EKF2", "min": 0.01, "name": "EKF2_RNG_NOISE", "shortDesc": "Measurement noise for range finder fusion", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "max": 0.75, "min": -0.75, "name": "EKF2_RNG_PITCH", "shortDesc": "Range sensor pitch offset", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_X", "shortDesc": "X position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_Y", "shortDesc": "Y position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "EKF2", "longDesc": "Forward axis with origin relative to vehicle centre of gravity", "name": "EKF2_RNG_POS_Z", "shortDesc": "Z position of range finder origin in body frame", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "Minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (s)", "max": 5.0, "min": 0.1, "name": "EKF2_RNG_QLTY_T", "shortDesc": "Minumum range validity period", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0.05, "group": "EKF2", "longDesc": "Specifies the increase in range finder noise with range.", "max": 0.2, "min": 0.0, "name": "EKF2_RNG_SFE", "shortDesc": "Range finder range dependent noise scaler", "type": "Float", "units": "m/m"}, {"category": "Standard", "default": 0.2, "group": "EKF2", "longDesc": "EKF2 instances have to be better than the selected by at least this amount before their relative score can be reduced.", "name": "EKF2_SEL_ERR_RED", "shortDesc": "Selector error reduce threshold", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "EKF2", "longDesc": "EKF2 selector acceleration error threshold for comparing accelerometers. Acceleration vector differences larger than this will result in accumulated velocity error.", "name": "EKF2_SEL_IMU_ACC", "shortDesc": "Selector acceleration threshold", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 15.0, "group": "EKF2", "longDesc": "EKF2 selector maximum accumulated angular error threshold for comparing gyros. Accumulated angular error larger than this will result in the sensor being declared faulty.", "name": "EKF2_SEL_IMU_ANG", "shortDesc": "Selector angular threshold", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 7.0, "group": "EKF2", "longDesc": "EKF2 selector angular rate error threshold for comparing gyros. Angular rate vector differences larger than this will result in accumulated angular error.", "name": "EKF2_SEL_IMU_RAT", "shortDesc": "Selector angular rate threshold", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 2.0, "group": "EKF2", "longDesc": "EKF2 selector maximum accumulated velocity threshold for comparing accelerometers. Accumulated velocity error larger than this will result in the sensor being declared faulty.", "name": "EKF2_SEL_IMU_VEL", "shortDesc": "Selector angular threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 0, "group": "EKF2", "longDesc": "Use for vehicles where the measured body Z magnetic field is subject to strong magnetic interference. For magnetic heading fusion the magnetometer Z measurement will be replaced by a synthetic value calculated using the knowledge of the 3D magnetic field vector at the location of the drone. Therefore, this parameter will only have an effect if the global position of the drone is known. For 3D mag fusion the magnetometer Z measurement will simply be ignored instead of fusing the synthetic value.", "name": "EKF2_SYNT_MAG_Z", "shortDesc": "Enable synthetic magnetometer Z component measurement", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "longDesc": "Sets the number of standard deviations used by the innovation consistency test.", "min": 1.0, "name": "EKF2_TAS_GATE", "shortDesc": "Gate size for TAS fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "EKF2", "longDesc": "Controls how tightly the output track the EKF states", "max": 1.0, "min": 0.1, "name": "EKF2_TAU_POS", "shortDesc": "Output predictor position time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "EKF2", "max": 1.0, "name": "EKF2_TAU_VEL", "shortDesc": "Time constant of the velocity output prediction and smoothing filter", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "EKF2", "min": 0.0, "name": "EKF2_TERR_GRAD", "shortDesc": "Magnitude of terrain gradient", "type": "Float", "units": "m/m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "EKF2", "min": 0.5, "name": "EKF2_TERR_NOISE", "shortDesc": "Terrain altitude process noise", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "EKF2", "max": 299792458.0, "name": "EKF2_VEL_LIM", "shortDesc": "Velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "EKF2", "longDesc": "When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second.", "max": 1.0, "min": 0.0, "name": "EKF2_WIND_NSD", "shortDesc": "Process noise spectral density for wind velocity prediction", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "default": 0, "group": "Events", "longDesc": "Enable/disable event task for RC Loss. When enabled, an alarm tune will be\nplayed via buzzer or ESCs, if supported. The alarm will sound after a disarm,\nif the vehicle was previously armed and only if the vehicle had RC signal at\nsome point. Particularly useful for locating crashed drones without a GPS\nsensor.", "name": "EV_TSK_RC_LOSS", "rebootRequired": true, "shortDesc": "RC Loss Alarm", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Events", "longDesc": "Enable/disable event task for displaying the vehicle status using arm-mounted\nLEDs. When enabled and if the vehicle supports it, LEDs will flash\nindicating various vehicle status changes. Currently PX4 has not implemented\nany specific status events.\n-", "name": "EV_TSK_STAT_DIS", "rebootRequired": true, "shortDesc": "Status Display", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "Applies to both directions in all manual modes with attitude stabilization but without altitude control", "max": 90.0, "min": 0.0, "name": "FW_MAN_P_MAX", "shortDesc": "Maximum manual pitch angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 45.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "Applies to both directions in all manual modes with attitude stabilization", "max": 90.0, "min": 0.0, "name": "FW_MAN_R_MAX", "shortDesc": "Maximum manual roll angle", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "This is the maximally added yaw rate setpoint from the yaw stick in any attitude controlled flight mode.\nIt is added to the yaw rate setpoint generated by the controller for turn coordination.", "min": 0.0, "name": "FW_MAN_YR_MAX", "shortDesc": "Maximum manually added yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "An airframe specific offset of the pitch setpoint in degrees, the value is\nadded to the pitch setpoint and should correspond to the pitch at\ntypical cruise speed of the airframe.", "max": 90.0, "min": -90.0, "name": "FW_PSP_OFF", "shortDesc": "Pitch setpoint offset (pitch at level flight)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 60.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_P_RMAX_NEG", "shortDesc": "Maximum negative / down pitch rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 60.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_P_RMAX_POS", "shortDesc": "Maximum positive / up pitch rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "longDesc": "This defines the latency between a pitch step input and the achieved setpoint\n(inverse to a P gain). Smaller systems may require smaller values.", "max": 1.0, "min": 0.2, "name": "FW_P_TC", "shortDesc": "Attitude pitch time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 70.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_R_RMAX", "shortDesc": "Maximum roll rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "longDesc": "This defines the latency between a roll step input and the achieved setpoint\n(inverse to a P gain). Smaller systems may require smaller values.", "max": 1.0, "min": 0.2, "name": "FW_R_TC", "shortDesc": "Attitude Roll Time Constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Attitude Control", "increment": 0.05, "max": 10.0, "min": 0.0, "name": "FW_WR_FF", "shortDesc": "Wheel steering rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "FW Attitude Control", "increment": 0.005, "longDesc": "This gain defines how much control response will result out of a steady\nstate error. It trims any constant error.", "max": 10.0, "min": 0.0, "name": "FW_WR_I", "shortDesc": "Wheel steering rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Attitude Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_WR_IMAX", "shortDesc": "Wheel steering rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "FW Attitude Control", "increment": 0.005, "longDesc": "This defines how much the wheel steering input will be commanded depending on the\ncurrent body angular rate error.", "max": 10.0, "min": 0.0, "name": "FW_WR_P", "shortDesc": "Wheel steering rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "FW Attitude Control", "longDesc": "Only enabled during automatic runway takeoff and landing.\nIn all manual modes the wheel is directly controlled with yaw stick.", "name": "FW_W_EN", "shortDesc": "Enable wheel steering controller", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Attitude Control", "increment": 0.5, "longDesc": "This limits the maximum wheel steering rate the controller will output (in degrees per\nsecond).", "max": 90.0, "min": 0.0, "name": "FW_W_RMAX", "shortDesc": "Maximum wheel steering rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 50.0, "group": "FW Attitude Control", "increment": 0.5, "max": 180.0, "min": 0.0, "name": "FW_Y_RMAX", "shortDesc": "Maximum yaw rate setpoint", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Auto Landing", "increment": 0.01, "longDesc": "Sets a fraction of full flaps during landing.\nAlso applies to flaperons if enabled in the mixer/allocation.", "max": 1.0, "min": 0.0, "name": "FW_FLAPS_LND_SCL", "shortDesc": "Flaps setting during landing", "type": "Float", "units": "norm"}, {"bitmask": [{"description": "Abort if terrain is not found (only applies to mission landings)", "index": 0}, {"description": "Abort if terrain times out (after a first successful measurement)", "index": 1}], "category": "Standard", "default": 3, "group": "FW Auto Landing", "longDesc": "Terrain estimation:\nbit 0: Abort if terrain is not found\nbit 1: Abort if terrain times out (after a first successful measurement)\nThe last estimate is always used as ground, whether the last valid measurement or the land waypoint, depending on the\nselected abort criteria, until an abort condition is entered. If FW_LND_USETER == 0, these bits are ignored.\nTODO: Extend automatic abort conditions\ne.g. glide slope tracking error (horizontal and vertical)", "max": 3, "min": 0, "name": "FW_LND_ABORT", "shortDesc": "Bit mask to set the automatic landing abort conditions", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "The calibrated airspeed setpoint during landing.\nIf set <= 0, landing airspeed = FW_AIRSPD_MIN by default.", "min": -1.0, "name": "FW_LND_AIRSPD", "shortDesc": "Landing airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Typically the desired landing slope angle when landing configuration (flaps, airspeed) is enabled.\nSet this value within the vehicle's performance limits.", "max": 45.0, "min": 1.0, "name": "FW_LND_ANG", "shortDesc": "Maximum landing slope angle", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "FW Auto Landing", "longDesc": "Allows to deploy the landing configuration (flaps, landing airspeed, etc.) already in\nthe loiter-down waypoint before the final approach.\nOtherwise is enabled only in the final approach.", "name": "FW_LND_EARLYCFG", "shortDesc": "Early landing configuration deployment", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * |z-velocity|) is taken as the flare altitude", "min": 0.0, "name": "FW_LND_FLALT", "shortDesc": "Landing flare altitude (relative to landing altitude)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Maximum pitch during landing flare.", "max": 45.0, "min": 0.0, "name": "FW_LND_FL_PMAX", "shortDesc": "Flare, maximum pitch", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "FW Auto Landing", "increment": 0.5, "longDesc": "Minimum pitch during landing flare.", "max": 15.0, "min": -5.0, "name": "FW_LND_FL_PMIN", "shortDesc": "Flare, minimum pitch", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "TECS will attempt to control the aircraft to this sink rate via pitch angle (throttle killed during flare)", "max": 2.0, "min": 0.0, "name": "FW_LND_FL_SINK", "shortDesc": "Landing flare sink rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "Multiplied by the descent rate to calculate a dynamic altitude at which\nto trigger the flare.\nNOTE: max(FW_LND_FLALT, FW_LND_FL_TIME * descent rate) is taken as the flare altitude", "max": 5.0, "min": 0.1, "name": "FW_LND_FL_TIME", "shortDesc": "Landing flare time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 2, "group": "FW Auto Landing", "longDesc": "Approach angle nudging: shifts the touchdown point laterally while keeping the approach entrance point constant\nApproach path nudging: shifts the touchdown point laterally along with the entire approach path\nThis is useful for manually adjusting the landing point in real time when map or GNSS errors cause an offset from the\ndesired landing vector. Nudging is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is\nrelative to the vehicle heading (stick deflection to the right = land point moves to the right as seen by the vehicle).", "max": 2, "min": 0, "name": "FW_LND_NUDGE", "shortDesc": "Landing touchdown nudging option", "type": "Int32", "values": [{"description": "Disable nudging", "value": 0}, {"description": "Nudge approach angle", "value": 1}, {"description": "Nudge approach path", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "FW Auto Landing", "increment": 1.0, "max": 10.0, "min": 0.0, "name": "FW_LND_TD_OFF", "shortDesc": "Maximum lateral position offset for the touchdown point", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "This is the time after the start of flaring that we expect the vehicle to touch the runway.\nAt this time, a 0.5s clamp down ramp will engage, constraining the pitch setpoint to RWTO_PSP.\nIf enabled, ensure that RWTO_PSP is configured appropriately for full gear contact on ground roll.\nSet to -1.0 to disable touchdown clamping. E.g. it may not be desirable to clamp on belly landings.\nThe touchdown time will be constrained to be greater than or equal to the flare time (FW_LND_FL_TIME).", "max": 5.0, "min": -1.0, "name": "FW_LND_TD_TIME", "shortDesc": "Landing touchdown time (since flare start)", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW Auto Landing", "increment": 0.1, "longDesc": "The TECS altitude time constant (FW_T_ALT_TC) is multiplied by this value.", "max": 1.0, "min": 0.2, "name": "FW_LND_THRTC_SC", "shortDesc": "Altitude time constant factor for landing and low-height flight", "type": "Float", "units": ""}, {"category": "Standard", "default": 1, "group": "FW Auto Landing", "longDesc": "This is critical for detecting when to flare, and should be enabled if possible.\nIf enabled and no measurement is found within a given timeout, the landing waypoint altitude will be used OR the landing\nwill be aborted, depending on the criteria set in FW_LND_ABORT.\nIf disabled, FW_LND_ABORT terrain based criteria are ignored.", "max": 2, "min": 0, "name": "FW_LND_USETER", "shortDesc": "Use terrain estimation during landing", "type": "Int32", "values": [{"description": "Disable the terrain estimate", "value": 0}, {"description": "Use the terrain estimate to trigger the flare (only)", "value": 1}, {"description": "Calculate landing glide slope relative to the terrain estimate", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Auto Landing", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "FW_SPOILERS_LND", "shortDesc": "Spoiler landing setting", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Auto Takeoff", "increment": 0.01, "longDesc": "Sets a fraction of full flaps during take-off.\nAlso applies to flaperons if enabled in the mixer/allocation.", "max": 1.0, "min": 0.0, "name": "FW_FLAPS_TO_SCL", "shortDesc": "Flaps setting during take-off", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "FW Auto Takeoff", "increment": 0.05, "longDesc": "Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds.", "max": 5.0, "min": 0.0, "name": "FW_LAUN_AC_T", "shortDesc": "Trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW Auto Takeoff", "increment": 0.5, "longDesc": "Launch is detected when acceleration in body forward direction is above FW_LAUN_AC_THLD for FW_LAUN_AC_T seconds.", "min": 0.0, "name": "FW_LAUN_AC_THLD", "shortDesc": "Trigger acceleration threshold", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Auto Takeoff", "increment": 0.1, "longDesc": "Locks control surfaces during pre-launch (armed) and until this time since launch has passed.\nOnly affects control surfaces that have corresponding flag set, and not active for runway takeoff.\nSet to 0 to disable any surface locking after arming.", "min": 0.0, "name": "FW_LAUN_CS_LK_DY", "shortDesc": "Control surface launch delay", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "FW Auto Takeoff", "longDesc": "Enables automatic launch detection based on measured acceleration. Use for hand- or catapult-launched vehicles.\nNot compatible with runway takeoff.", "name": "FW_LAUN_DETCN_ON", "shortDesc": "Fixed-wing launch detection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Auto Takeoff", "increment": 0.5, "longDesc": "Start the motor(s) this amount of seconds after launch is detected.", "max": 10.0, "min": 0.0, "name": "FW_LAUN_MOT_DEL", "shortDesc": "Motor delay", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Auto Takeoff", "increment": 0.1, "longDesc": "The calibrated airspeed setpoint during the takeoff climbout.\nIf set <= 0, FW_AIRSPD_MIN will be set by default.", "min": -1.0, "name": "FW_TKO_AIRSPD", "shortDesc": "Takeoff Airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW Auto Takeoff", "increment": 0.5, "max": 80.0, "min": -5.0, "name": "FW_TKO_PITCH_MIN", "shortDesc": "Minimum pitch during takeoff", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 30, "group": "FW General", "longDesc": "The time the system should do open loop loiter and wait for GPS recovery\nbefore it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R.\nDoes only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0.", "min": 0, "name": "FW_GPSF_LT", "shortDesc": "GPS failure loiter time", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW General", "increment": 0.5, "longDesc": "Roll angle in GPS failure loiter mode.", "max": 60.0, "min": 0.0, "name": "FW_GPSF_R", "shortDesc": "GPS failure fixed roll angle", "type": "Float", "units": "deg"}, {"bitmask": [{"description": "Alternative stick configuration (height rate on throttle stick, airspeed on pitch stick)", "index": 0}, {"description": "Enable airspeed setpoint via sticks in altitude and position flight mode", "index": 1}], "category": "Standard", "default": 2, "group": "FW General", "longDesc": "Applies in manual Position and Altitude flight modes.", "max": 3, "min": 0, "name": "FW_POS_STK_CONF", "shortDesc": "Custom stick configuration", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 30.0, "group": "FW General", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 80.0, "min": 0.0, "name": "FW_P_LIM_MAX", "shortDesc": "Maximum pitch angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -30.0, "group": "FW General", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 0.0, "min": -60.0, "name": "FW_P_LIM_MIN", "shortDesc": "Minimum pitch angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 50.0, "group": "FW General", "increment": 0.5, "longDesc": "Applies in any altitude controlled flight mode.", "max": 75.0, "min": 35.0, "name": "FW_R_LIM", "shortDesc": "Maximum roll angle setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW General", "increment": 0.01, "longDesc": "This is the minimum throttle while on the ground (\"landed\") in auto modes.", "max": 1.0, "min": 0.0, "name": "FW_THR_IDLE", "shortDesc": "Idle throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW General", "increment": 0.01, "longDesc": "Applies in any altitude controlled flight mode.\nShould be set accordingly to achieve FW_T_CLMB_MAX.", "max": 1.0, "min": 0.0, "name": "FW_THR_MAX", "shortDesc": "Throttle limit max", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW General", "increment": 0.01, "longDesc": "Applies in any altitude controlled flight mode.\nUsually set to 0 but can be increased to prevent the motor from stopping when\ndescending, which can increase achievable descent rates.", "max": 1.0, "min": 0.0, "name": "FW_THR_MIN", "shortDesc": "Throttle limit min", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "FW General", "increment": 0.01, "longDesc": "In auto modes: default climb rate output by controller to achieve altitude setpoints.\nIn manual modes: maximum climb rate setpoint.", "min": 0.1, "name": "FW_T_CLMB_R_SP", "shortDesc": "Default target climbrate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "FW General", "increment": 0.01, "longDesc": "In auto modes: default sink rate output by controller to achieve altitude setpoints.\nIn manual modes: maximum sink rate setpoint.", "min": 0.1, "name": "FW_T_SINK_R_SP", "shortDesc": "Default target sinkrate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "FW General", "increment": 1.0, "longDesc": "Adjusts the amount of weighting that the pitch control\napplies to speed vs height errors.\n0 -> control height only\n2 -> control speed only (gliders)", "max": 2.0, "min": 0.0, "name": "FW_T_SPDWEIGHT", "shortDesc": "Speed <--> Altitude weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "FW General", "increment": 1.0, "longDesc": "This is used to constrain a minimum altitude below which we keep wings level to avoid wing tip strike. It's safer\nto give a slight margin here (> 0m)", "min": 0.0, "name": "FW_WING_HEIGHT", "shortDesc": "Height (AGL) of the wings when the aircraft is on the ground", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "FW General", "increment": 0.1, "longDesc": "This is used for limiting the roll setpoint near the ground. (if multiple wings, take the longest span)", "min": 0.1, "name": "FW_WING_SPAN", "shortDesc": "The aircraft's wing span (length from tip to tip)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "FW Lateral Control", "increment": 1.0, "longDesc": "Maximum change in roll angle setpoint per second.\nApplied in all Auto modes, plus manual Position & Altitude modes.", "min": 0.0, "name": "FW_PN_R_SLEW_MAX", "shortDesc": "Path navigation roll slew rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "longDesc": "The controller will increase the commanded airspeed to maintain\nthis minimum groundspeed to the next waypoint.", "max": 40.0, "min": 0.0, "name": "FW_GND_SPD_MIN", "shortDesc": "Minimum groundspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "Maximum slew rate for the commanded throttle", "max": 1.0, "min": 0.0, "name": "FW_THR_SLEW_MAX", "shortDesc": "Throttle max slew rate", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "min": 2.0, "name": "FW_T_ALT_TC", "shortDesc": "Altitude error time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW Longitudinal Control", "longDesc": "Minimum altitude error needed to descend with max airspeed and minimal throttle.\nA negative value disables fast descend.", "min": -1.0, "name": "FW_T_F_ALT_ERR", "shortDesc": "Fast descend: minimum altitude error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW Longitudinal Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_T_HRATE_FF", "shortDesc": "Height rate feed forward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW Longitudinal Control", "increment": 0.05, "longDesc": "Increase it to trim out speed and height offsets faster,\nwith the downside of possible overshoots and oscillations.", "max": 2.0, "min": 0.0, "name": "FW_T_I_GAIN_PIT", "shortDesc": "Integrator gain pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW Longitudinal Control", "increment": 0.1, "max": 2.0, "min": 0.0, "name": "FW_T_PTCH_DAMP", "shortDesc": "Pitch damping gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Longitudinal Control", "increment": 0.5, "longDesc": "Is used to compensate for the additional drag created by turning.\nIncrease this gain if the aircraft initially loses energy in turns\nand reduce if the aircraft initially gains energy in turns.", "max": 20.0, "min": 0.0, "name": "FW_T_RLL2THR", "shortDesc": "Roll -> Throttle feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Longitudinal Control", "increment": 0.01, "max": 3.0, "min": 0.5, "name": "FW_T_SEB_R_FF", "shortDesc": "Specific total energy balance rate feedforward gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "max": 15.0, "min": 1.0, "name": "FW_T_SINK_MAX", "shortDesc": "Maximum descent rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Longitudinal Control", "increment": 0.1, "longDesc": "For the airspeed filter in TECS.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_DEV_STD", "shortDesc": "Airspeed rate measurement standard deviation", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Longitudinal Control", "increment": 0.1, "longDesc": "This is defining the noise in the airspeed rate for the constant airspeed rate model\nof the TECS airspeed filter.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_PRC_STD", "shortDesc": "Process noise standard deviation for the airspeed rate", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.07, "group": "FW Longitudinal Control", "increment": 0.1, "longDesc": "For the airspeed filter in TECS.", "max": 10.0, "min": 0.01, "name": "FW_T_SPD_STD", "shortDesc": "Airspeed measurement standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "This filter is applied to the specific total energy rate used for throttle damping.", "max": 2.0, "min": 0.0, "name": "FW_T_STE_R_TC", "shortDesc": "Specific total energy rate first order filter time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "FW Longitudinal Control", "increment": 0.5, "min": 2.0, "name": "FW_T_TAS_TC", "shortDesc": "True airspeed error time constant", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "This is the damping gain for the throttle demand loop.", "max": 1.0, "min": 0.0, "name": "FW_T_THR_DAMPING", "shortDesc": "Throttle damping factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.02, "group": "FW Longitudinal Control", "increment": 0.005, "longDesc": "Increase it to trim out speed and height offsets faster,\nwith the downside of possible overshoots and oscillations.", "max": 1.0, "min": 0.0, "name": "FW_T_THR_INTEG", "shortDesc": "Integrator gain throttle", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW Longitudinal Control", "increment": 1.0, "longDesc": "Height above ground threshold below which tighter altitude\ntracking gets enabled (see FW_LND_THRTC_SC). Below this height, TECS smoothly\n(1 sec / sec) transitions the altitude tracking time constant from FW_T_ALT_TC\nto FW_LND_THRTC_SC*FW_T_ALT_TC.\n-1 to disable.", "min": -1.0, "name": "FW_T_THR_LOW_HGT", "shortDesc": "Low-height threshold for tighter altitude tracking", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 7.0, "group": "FW Longitudinal Control", "increment": 0.5, "longDesc": "This is the maximum vertical acceleration\neither up or down that the controller will use to correct speed\nor height errors.", "max": 10.0, "min": 1.0, "name": "FW_T_VERT_ACC", "shortDesc": "Maximum vertical acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Longitudinal Control", "increment": 0.01, "longDesc": "Multiplying this factor with the current absolute wind estimate gives the airspeed offset\nadded to the minimum airspeed setpoint limit. This helps to make the\nsystem more robust against disturbances (turbulence) in high wind.", "min": 0.0, "name": "FW_WIND_ARSP_SC", "shortDesc": "Wind-based airspeed scaling factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "FW NPFG Control", "increment": 0.01, "longDesc": "Damping ratio of NPFG control law.", "max": 1.0, "min": 0.1, "name": "NPFG_DAMPING", "shortDesc": "NPFG damping ratio", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Avoids limit cycling from a too aggressively tuned period/damping combination.\nIf false, also disables upper bound NPFG_PERIOD_UB.", "name": "NPFG_LB_PERIOD", "shortDesc": "Enable automatic lower bound on the NPFG period", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW NPFG Control", "increment": 0.1, "longDesc": "Period of NPFG control law.", "max": 100.0, "min": 1.0, "name": "NPFG_PERIOD", "shortDesc": "NPFG period", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "FW NPFG Control", "increment": 0.1, "longDesc": "Multiplied by period for conservative minimum period bounding (when period lower\nbounding is enabled). 1.0 bounds at marginal stability.", "max": 10.0, "min": 1.0, "name": "NPFG_PERIOD_SF", "shortDesc": "Period safety factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW NPFG Control", "increment": 0.05, "longDesc": "Time constant of roll controller command / response, modeled as first order delay.\nUsed to determine lower period bound. Setting zero disables automatic period bounding.", "max": 2.0, "min": 0.0, "name": "NPFG_ROLL_TC", "shortDesc": "Roll time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.32, "group": "FW NPFG Control", "increment": 0.01, "longDesc": "Multiplied by the track error boundary to determine when the aircraft switches\nto the next waypoint and/or path segment. Should be less than 1.", "max": 1.0, "min": 0.1, "name": "NPFG_SW_DST_MLT", "shortDesc": "NPFG switch distance multiplier", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW NPFG Control", "longDesc": "Adapts period to maintain track keeping in variable winds and path curvature.", "name": "NPFG_UB_PERIOD", "shortDesc": "Enable automatic upper bound on the NPFG period", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Factor applied to the minimum and stall airspeed when flaps are fully deployed.", "max": 1.0, "min": 0.5, "name": "FW_AIRSPD_FLP_SC", "shortDesc": "Airspeed scale with full flaps", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The maximal airspeed (calibrated airspeed) the user is able to command.", "min": 0.5, "name": "FW_AIRSPD_MAX", "shortDesc": "Maximum Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The minimal airspeed (calibrated airspeed) the user is able to command.\nFurther, if the airspeed falls below this value, the TECS controller will try to\nincrease airspeed more aggressively.\nHas to be set according to the vehicle's stall speed (which should be set in FW_AIRSPD_STALL),\nwith some margin between the stall speed and minimum airspeed.\nThis value corresponds to the desired minimum speed with the default load factor (level flight, default weight),\nand is automatically adpated to the current load factor (calculated from roll setpoint and WEIGHT_GROSS/WEIGHT_BASE).", "min": 0.5, "name": "FW_AIRSPD_MIN", "shortDesc": "Minimum Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 7.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The stall airspeed (calibrated airspeed) of the vehicle.\nIt is used for airspeed sensor failure detection and for the control\nsurface scaling airspeed limits.", "min": 0.5, "name": "FW_AIRSPD_STALL", "shortDesc": "Stall Airspeed (CAS)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "FW Performance", "increment": 0.5, "longDesc": "The trim CAS (calibrated airspeed) of the vehicle. If an airspeed controller is active,\nthis is the default airspeed setpoint that the controller will try to achieve.\nThis value corresponds to the trim airspeed with the default load factor (level flight, default weight).", "min": 0.5, "name": "FW_AIRSPD_TRIM", "shortDesc": "Trim (Cruise) Airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "FW Performance", "increment": 1.0, "longDesc": "Altitude in standard atmosphere at which the vehicle in normal configuration (WEIGHT_BASE) is still able to achieve a maximum climb rate of\n0.5m/s at maximum throttle (FW_THR_MAX). Used to compensate for air density in FW_T_CLMB_MAX.\nSet negative to disable.", "min": -1.0, "name": "FW_SERVICE_CEIL", "shortDesc": "Service ceiling", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at maximum airspeed FW_AIRSPD_MAX\nSet to 0 to disable mapping of airspeed to trim throttle.", "max": 1.0, "min": 0.0, "name": "FW_THR_ASPD_MAX", "shortDesc": "Throttle at max airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at minimum airspeed FW_AIRSPD_MIN\nSet to 0 to disable mapping of airspeed to trim throttle below FW_AIRSPD_TRIM.", "max": 1.0, "min": 0.0, "name": "FW_THR_ASPD_MIN", "shortDesc": "Throttle at min airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "FW Performance", "increment": 0.01, "longDesc": "Required throttle (at sea level, standard atmosphere) for level flight at FW_AIRSPD_TRIM", "max": 1.0, "min": 0.0, "name": "FW_THR_TRIM", "shortDesc": "Trim throttle", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the maximum calibrated climb rate that the aircraft can achieve with\nthe throttle set to FW_THR_MAX and the airspeed set to the\ntrim value. For electric aircraft make sure this number can be\nachieved towards the end of flight when the battery voltage has reduced.", "min": 1.0, "name": "FW_T_CLMB_MAX", "shortDesc": "Maximum climb rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the minimum calibrated sink rate of the aircraft with the throttle\nset to THR_MIN and flown at the same airspeed as used\nto measure FW_T_CLMB_MAX.", "min": 1.0, "name": "FW_T_SINK_MIN", "shortDesc": "Minimum descent rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Performance", "increment": 0.5, "longDesc": "This is the weight of the vehicle at which it's performance limits were derived. A zero or negative value\ndisables trim throttle and minimum airspeed compensation based on weight.", "name": "WEIGHT_BASE", "shortDesc": "Vehicle base weight", "type": "Float", "units": "kg"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "FW Performance", "increment": 0.1, "longDesc": "This is the actual weight of the vehicle at any time. This value will differ from WEIGHT_BASE in case weight was added\nor removed from the base weight. Examples are the addition of payloads or larger batteries. A zero or negative value\ndisables trim throttle and minimum airspeed compensation based on weight.", "name": "WEIGHT_GROSS", "shortDesc": "Vehicle gross weight", "type": "Float", "units": "kg"}, {"category": "Standard", "default": 90.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_X_MAX", "shortDesc": "Acro body roll max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "If this parameter is set to 1, the yaw rate controller is enabled in Fixed-wing Acro mode.\nOtherwise the pilot commands directly the yaw actuator.\nIt is disabled by default because an active yaw rate controller will fight against the\nnatural turn coordination of the plane.", "name": "FW_ACRO_YAW_EN", "shortDesc": "Enable yaw rate controller in Acro", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 90.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_Y_MAX", "shortDesc": "Acro body pitch max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 45.0, "group": "FW Rate Control", "max": 720.0, "min": 10.0, "name": "FW_ACRO_Z_MAX", "shortDesc": "Acro body yaw max rate setpoint", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "longDesc": "This enables a logic that automatically adjusts the output of the rate controller to take\ninto account the real torque produced by an aerodynamic control surface given\nthe current deviation from the trim airspeed (FW_AIRSPD_TRIM).\nEnable when using aerodynamic control surfaces (e.g.: plane)\nDisable when using rotor wings (e.g.: autogyro)", "name": "FW_ARSP_SCALE_EN", "shortDesc": "Enable airspeed scaling", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "This compensates for voltage drop of the battery over time by attempting to\nnormalize performance across the operating range of the battery.", "name": "FW_BAT_SCALE_EN", "shortDesc": "Enable throttle scale by battery level", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_P_VMAX", "shortDesc": "Pitch trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_P_VMIN", "shortDesc": "Pitch trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_R_VMAX", "shortDesc": "Roll trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_R_VMIN", "shortDesc": "Roll trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_Y_VMAX", "shortDesc": "Yaw trim increment at maximum airspeed", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN.", "max": 0.5, "min": -0.5, "name": "FW_DTRIM_Y_VMIN", "shortDesc": "Yaw trim increment at minimum airspeed", "type": "Float"}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "name": "FW_GC_EN", "shortDesc": "Enable rate gain compression", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW Rate Control", "increment": 0.01, "longDesc": "The range of the compression gain is between this parameter and 1.0", "max": 1.0, "min": 0.0, "name": "FW_GC_GAIN_MIN", "shortDesc": "Compression gain lower limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired pitch actuator command in full manual mode. This parameter allows\nto adjust the throws of the control surfaces.", "min": 0.0, "name": "FW_MAN_P_SC", "shortDesc": "Manual pitch scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired roll actuator command in full manual mode. This parameter allows\nto adjust the throws of the control surfaces.", "max": 1.0, "min": 0.0, "name": "FW_MAN_R_SC", "shortDesc": "Manual roll scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows\nto adjust the throws of the control surfaces.", "min": 0.0, "name": "FW_MAN_Y_SC", "shortDesc": "Manual yaw scale", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "longDesc": "Pitch rate differential gain.", "max": 10.0, "min": 0.0, "name": "FW_PR_D", "shortDesc": "Pitch rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output", "max": 10.0, "min": 0.0, "name": "FW_PR_FF", "shortDesc": "Pitch rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_PR_I", "shortDesc": "Pitch rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_PR_IMAX", "shortDesc": "Pitch rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.08, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_PR_P", "shortDesc": "Pitch rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "FW Rate Control", "increment": 0.01, "longDesc": "This gain can be used to counteract the \"adverse yaw\" effect for fixed wings.\nWhen the plane enters a roll it will tend to yaw the nose out of the turn.\nThis gain enables the use of a yaw actuator to counteract this effect.", "min": 0.0, "name": "FW_RLL_TO_YAW_FF", "shortDesc": "Roll control to yaw control feedforward gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_RR_D", "shortDesc": "Roll rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output.", "max": 10.0, "min": 0.0, "name": "FW_RR_FF", "shortDesc": "Roll rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "FW Rate Control", "increment": 0.01, "max": 10.0, "min": 0.0, "name": "FW_RR_I", "shortDesc": "Roll rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_RR_IMAX", "shortDesc": "Roll integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_RR_P", "shortDesc": "Roll rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "FW Rate Control", "longDesc": "Chose source for manual setting of spoilers in manual flight modes.", "name": "FW_SPOILERS_MAN", "shortDesc": "Spoiler input in manual flight", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Flaps channel", "value": 1}, {"description": "Aux1", "value": 2}]}, {"category": "Standard", "default": 1, "group": "FW Rate Control", "longDesc": "If set to 1, the airspeed measurement data, if valid, is used in the following controllers:\n- Rate controller: output scaling\n- Attitude controller: coordinated turn controller\n- Position controller: airspeed setpoint tracking, takeoff logic\n- VTOL: transition logic", "name": "FW_USE_AIRSPD", "shortDesc": "Use airspeed for control", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_YR_D", "shortDesc": "Yaw rate derivative gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "FW Rate Control", "increment": 0.05, "longDesc": "Direct feed forward from rate setpoint to control surface output", "max": 10.0, "min": 0.0, "name": "FW_YR_FF", "shortDesc": "Yaw rate feed forward", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.1, "group": "FW Rate Control", "increment": 0.5, "max": 10.0, "min": 0.0, "name": "FW_YR_I", "shortDesc": "Yaw rate integrator gain", "type": "Float", "units": "%/rad"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "FW Rate Control", "increment": 0.05, "max": 1.0, "min": 0.0, "name": "FW_YR_IMAX", "shortDesc": "Yaw rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "FW Rate Control", "increment": 0.005, "max": 10.0, "min": 0.0, "name": "FW_YR_P", "shortDesc": "Yaw rate proportional gain", "type": "Float", "units": "%/rad/s"}, {"category": "Standard", "default": 0, "group": "Failure Detector", "longDesc": "If enabled, failure detector will verify that for motors, a minimum amount of ESC current per throttle\nlevel is being consumed.\nOtherwise this indicates an motor failure.", "name": "FD_ACT_EN", "rebootRequired": true, "shortDesc": "Enable Actuator Failure check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Failure Detector", "increment": 1.0, "longDesc": "threshold = FD_ACT_MOT_C2T * thrust + FD_ACT_HIGH_OFF", "max": 30.0, "min": 0.0, "name": "FD_ACT_HIGH_OFF", "shortDesc": "Overcurrent motor failure limit offset", "type": "Float", "units": "A"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Failure Detector", "increment": 1.0, "longDesc": "threshold = FD_ACT_MOT_C2T * thrust - FD_ACT_LOW_OFF", "max": 30.0, "min": 0.0, "name": "FD_ACT_LOW_OFF", "shortDesc": "Undercurrent motor failure limit offset", "type": "Float", "units": "A"}, {"category": "Standard", "decimalPlaces": 2, "default": 35.0, "group": "Failure Detector", "increment": 1.0, "longDesc": "Determines the slope between expected steady state current and linearized, normalized thrust command.\nE.g. FD_ACT_MOT_C2T A represents the expected steady state current at 100%.\nFD_ACT_LOW_OFF and FD_ACT_HIGH_OFF offset the threshold from that slope.", "max": 50.0, "min": 0.0, "name": "FD_ACT_MOT_C2T", "shortDesc": "Motor Failure Current/Throttle Scale", "type": "Float", "units": "A/%"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Failure Detector", "increment": 0.01, "longDesc": "Failure detection per motor only triggers above this thrust value.\nSet to 1 to disable the detection.", "max": 1.0, "min": 0.0, "name": "FD_ACT_MOT_THR", "shortDesc": "Motor Failure Thrust Threshold", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 1000, "group": "Failure Detector", "increment": 100, "longDesc": "Motor failure only triggers after current thresholds are exceeded for this time.", "max": 10000, "min": 10, "name": "FD_ACT_MOT_TOUT", "shortDesc": "Motor Failure Hysteresis Time", "type": "Int32", "units": "ms"}, {"category": "Standard", "default": 1, "group": "Failure Detector", "longDesc": "If enabled, failure detector will verify that all the ESCs have successfully armed when the vehicle has transitioned to the armed state.\nTimeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback is received the failure detector will auto disarm the vehicle.", "name": "FD_ESCS_EN", "shortDesc": "Enable checks on ESCs that report their arming state", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Failure Detector", "longDesc": "Enabled on either AUX5 or MAIN5 depending on board.\nExternal ATS is required by ASTM F3322-18.", "name": "FD_EXT_ATS_EN", "rebootRequired": true, "shortDesc": "Enable PWM input on for engaging failsafe from an external automatic trigger system (ATS)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1900, "group": "Failure Detector", "longDesc": "External ATS is required by ASTM F3322-18.", "name": "FD_EXT_ATS_TRIG", "shortDesc": "The PWM threshold from external automatic trigger system for engaging failsafe", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 60, "group": "Failure Detector", "longDesc": "Maximum pitch angle before FailureDetector triggers the attitude_failure flag.\nThe flag triggers flight termination (if @CBRK_FLIGHTTERM = 0),\nwhich sets outputs to their failsafe values.\nOn takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM),\nwhich disarms motors but does not set outputs to failsafe values.\nSetting this parameter to 0 disables the check", "max": 180, "min": 0, "name": "FD_FAIL_P", "shortDesc": "FailureDetector Max Pitch", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Failure Detector", "longDesc": "Seconds (decimal) that pitch has to exceed FD_FAIL_P before being considered as a failure.", "max": 5.0, "min": 0.02, "name": "FD_FAIL_P_TTRI", "shortDesc": "Pitch failure trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 60, "group": "Failure Detector", "longDesc": "Maximum roll angle before FailureDetector triggers the attitude_failure flag.\nThe flag triggers flight termination (if @CBRK_FLIGHTTERM = 0),\nwhich sets outputs to their failsafe values.\nOn takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM),\nwhich disarms motors but does not set outputs to failsafe values.\nSetting this parameter to 0 disables the check", "max": 180, "min": 0, "name": "FD_FAIL_R", "shortDesc": "FailureDetector Max Roll", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Failure Detector", "longDesc": "Seconds (decimal) that roll has to exceed FD_FAIL_R before being considered as a failure.", "max": 5.0, "min": 0.02, "name": "FD_FAIL_R_TTRI", "shortDesc": "Roll failure trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 30, "group": "Failure Detector", "increment": 1, "longDesc": "Value at which the imbalanced propeller metric (based on horizontal and\nvertical acceleration variance) triggers a failure\nSetting this value to 0 disables the feature.", "max": 1000, "min": 0, "name": "FD_IMB_PROP_THR", "shortDesc": "Imbalanced propeller check threshold", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 1000.0, "group": "Flight Task Orbit", "increment": 0.5, "max": 10000.0, "min": 1.0, "name": "MC_ORBIT_RAD_MAX", "shortDesc": "Maximum radius of orbit", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Flight Task Orbit", "name": "MC_ORBIT_YAW_MOD", "shortDesc": "Yaw behaviour during orbit flight", "type": "Int32", "values": [{"description": "Front to Circle Center", "value": 0}, {"description": "Hold Initial Heading", "value": 1}, {"description": "Uncontrolled", "value": 2}, {"description": "Hold Front Tangent to Circle", "value": 3}, {"description": "Manually (yaw stick) Controlled", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Follow target", "longDesc": "Maintain altitude or track target's altitude. When maintaining the altitude,\nthe drone can crash into terrain when the target moves uphill. When tracking\nthe target's altitude, the follow altitude FLW_TGT_HT should be high enough\nto prevent terrain collisions due to GPS inaccuracies of the target.", "name": "FLW_TGT_ALT_M", "shortDesc": "Altitude control mode", "type": "Int32", "values": [{"description": "2D Tracking: Maintain constant altitude relative to home and track XY position only", "value": 0}, {"description": "2D + Terrain: Maintain constant altitude relative to terrain below and track XY position", "value": 1}, {"description": "3D Tracking: Track target's altitude (be aware that GPS altitude bias usually makes this useless)", "value": 2}]}, {"category": "Standard", "default": 8.0, "group": "Follow target", "longDesc": "The distance in meters to follow the target at", "min": 1.0, "name": "FLW_TGT_DST", "shortDesc": "Distance to follow target from", "type": "Float", "units": "m"}, {"category": "Standard", "default": 180.0, "group": "Follow target", "longDesc": "Angle to follow the target from. 0.0 Equals straight in front of the target's\ncourse (direction of motion) and the angle increases in clockwise direction,\nmeaning Right-side would be 90.0 degrees while Left-side is -90.0 degrees\nNote: When the user force sets the angle out of the min/max range, it will be\nwrapped (e.g. 480 -> 120) in the range to gracefully handle the out of range.", "max": 180.0, "min": -180.0, "name": "FLW_TGT_FA", "shortDesc": "Follow Angle setting in degrees", "type": "Float"}, {"category": "Standard", "default": 8.0, "group": "Follow target", "longDesc": "Following height above the target", "min": 8.0, "name": "FLW_TGT_HT", "shortDesc": "Follow target height", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Follow target", "longDesc": "This is the maximum tangential velocity the drone will circle around the target whenever\nan orbit angle setpoint changes. Higher value means more aggressive follow behavior.", "max": 20.0, "min": 0.0, "name": "FLW_TGT_MAX_VEL", "shortDesc": "Maximum tangential velocity setting for generating the follow orbit trajectory", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Follow target", "longDesc": "lower values increase the responsiveness to changing position, but also ignore less noise", "max": 1.0, "min": 0.0, "name": "FLW_TGT_RS", "shortDesc": "Responsiveness to target movement in Target Estimator", "type": "Float"}, {"bitmask": [{"description": "GPS (with QZSS)", "index": 0}, {"description": "SBAS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "BeiDou", "index": 3}, {"description": "GLONASS", "index": 4}, {"description": "NAVIC", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "longDesc": "This integer bitmask controls the set of GNSS systems used by the receiver. Check your\nreceiver's documentation on how many systems are supported to be used in parallel.\nCurrently this functionality is just implemented for u-blox receivers.\nWhen no bits are set, the receiver's default configuration should be used.\nSet bits true to enable:\n0 : Use GPS (with QZSS)\n1 : Use SBAS (multiple GPS augmentation systems)\n2 : Use Galileo\n3 : Use BeiDou\n4 : Use GLONASS\n5 : Use NAVIC", "max": 63, "min": 0, "name": "GPS_1_GNSS", "rebootRequired": true, "shortDesc": "GNSS Systems for Primary GPS (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Select the GPS protocol over serial.\nAuto-detection will probe all protocols, and thus is a bit slower.", "max": 7, "min": 0, "name": "GPS_1_PROTOCOL", "rebootRequired": true, "shortDesc": "Protocol for Main GPS", "type": "Int32", "values": [{"description": "Auto detect", "value": 0}, {"description": "u-blox", "value": 1}, {"description": "MTK", "value": 2}, {"description": "Ashtech / Trimble", "value": 3}, {"description": "Emlid Reach", "value": 4}, {"description": "Femtomes", "value": 5}, {"description": "NMEA (generic)", "value": 6}]}, {"bitmask": [{"description": "GPS (with QZSS)", "index": 0}, {"description": "SBAS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "BeiDou", "index": 3}, {"description": "GLONASS", "index": 4}, {"description": "NAVIC", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "longDesc": "This integer bitmask controls the set of GNSS systems used by the receiver. Check your\nreceiver's documentation on how many systems are supported to be used in parallel.\nCurrently this functionality is just implemented for u-blox receivers.\nWhen no bits are set, the receiver's default configuration should be used.\nSet bits true to enable:\n0 : Use GPS (with QZSS)\n1 : Use SBAS (multiple GPS augmentation systems)\n2 : Use Galileo\n3 : Use BeiDou\n4 : Use GLONASS\n5 : Use NAVIC", "max": 63, "min": 0, "name": "GPS_2_GNSS", "rebootRequired": true, "shortDesc": "GNSS Systems for Secondary GPS (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Select the GPS protocol over serial.\nAuto-detection will probe all protocols, and thus is a bit slower.", "max": 6, "min": 0, "name": "GPS_2_PROTOCOL", "rebootRequired": true, "shortDesc": "Protocol for Secondary GPS", "type": "Int32", "values": [{"description": "Auto detect", "value": 0}, {"description": "u-blox", "value": 1}, {"description": "MTK", "value": 2}, {"description": "Ashtech / Trimble", "value": 3}, {"description": "Emlid Reach", "value": 4}, {"description": "Femtomes", "value": 5}, {"description": "NMEA (generic)", "value": 6}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Some UBX modules have a FLASH that allows to store persistent configuration that will be loaded on start.\nPX4 does override all configuration parameters it needs in RAM, which takes precedence over the values in FLASH.\nHowever, configuration parameters that are not overriden by PX4 can still cause unexpected problems during flight.\nTo avoid these kind of problems a clean config can be reached by wiping the FLASH on boot.\nNote: Currently only supported on UBX.", "name": "GPS_CFG_WIPE", "rebootRequired": true, "shortDesc": "Wipes the flash config of UBX modules", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "If this is set to 1, all GPS communication data will be published via uORB,\nand written to the log file as gps_dump message.\nIf this is set to 2, the main GPS is configured to output RTCM data,\nwhich is then logged as gps_dump and can be used for PPK.", "max": 2, "min": 0, "name": "GPS_DUMP_COMM", "shortDesc": "Log GPS communication data", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Full communication", "value": 1}, {"description": "RTCM output (PPK)", "value": 2}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Enable publication of satellite info (ORB_ID(satellite_info)) if possible.\nNot available on MTK.", "name": "GPS_SAT_INFO", "rebootRequired": true, "shortDesc": "Enable sat info (if available)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 230400, "group": "GPS", "longDesc": "Select a baudrate for the F9P's UART2 port.\nIn GPS_UBX_MODE 1, 2, and 3, the F9P's UART2 port is configured to send/receive RTCM corrections.\nSet this to 57600 if you want to attach a telemetry radio on UART2.", "min": 0, "name": "GPS_UBX_BAUD2", "rebootRequired": true, "shortDesc": "u-blox F9P UART2 Baudrate", "type": "Int32", "units": "B/s"}, {"bitmask": [{"description": "Enable I2C input protocol UBX", "index": 0}, {"description": "Enable I2C input protocol NMEA", "index": 1}, {"description": "Enable I2C input protocol RTCM3X", "index": 2}, {"description": "Enable I2C output protocol UBX", "index": 3}, {"description": "Enable I2C output protocol NMEA", "index": 4}, {"description": "Enable I2C output protocol RTCM3X", "index": 5}], "category": "Standard", "default": 0, "group": "GPS", "max": 32, "min": 0, "name": "GPS_UBX_CFG_INTF", "rebootRequired": true, "shortDesc": "u-blox protocol configuration for interfaces", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "When set to 0 (default), default DGNSS timeout set by u-blox will be used.", "max": 255, "min": 0, "name": "GPS_UBX_DGNSS_TO", "rebootRequired": true, "shortDesc": "u-blox GPS DGNSS timeout", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 7, "group": "GPS", "longDesc": "u-blox receivers support different dynamic platform models to adjust the navigation engine to\nthe expected application environment.", "max": 9, "min": 0, "name": "GPS_UBX_DYNMODEL", "rebootRequired": true, "shortDesc": "u-blox GPS dynamic platform model", "type": "Int32", "values": [{"description": "stationary", "value": 2}, {"description": "automotive", "value": 4}, {"description": "airborne with <1g acceleration", "value": 6}, {"description": "airborne with <2g acceleration", "value": 7}, {"description": "airborne with <4g acceleration", "value": 8}]}, {"category": "Standard", "default": 1, "group": "GPS", "longDesc": "Enables or disables the high sensitivity mode for the u-blox jamming detection\n(CFG-SEC-JAMDET_SENSITIVITY_HI). When enabled, the receiver uses a\nmore sensitive algorithm to detect jamming. Disabling this may reduce false\npositives in electrically noisy environments.", "name": "GPS_UBX_JAM_DET", "rebootRequired": true, "shortDesc": "u-blox GPS jamming detection high sensitivity mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "When set to 0 (default), default minimum satellite signal level set by u-blox wll be used.", "max": 255, "min": 0, "name": "GPS_UBX_MIN_CNO", "rebootRequired": true, "shortDesc": "u-blox GPS minimum satellite signal level for navigation", "type": "Int32", "units": "dBHz"}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "When set to 0 (default), default minimum elevation set by u-blox will be used.", "max": 127, "min": 0, "name": "GPS_UBX_MIN_ELEV", "rebootRequired": true, "shortDesc": "u-blox GPS minimum elevation for a GNSS satellite to be used in navigation", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Select the u-blox configuration setup. Most setups will use the default, including RTK and\ndual GPS without heading.\nIf rover has RTCM corrections from a static base (or other static correction source) coming in on UART2, then select Mode 5.\nThe Heading mode requires 2 F9P devices to be attached. The main GPS will act as rover and output\nheading information, whereas the secondary will act as moving base.\nModes 1 and 2 require each F9P UART1 to be connected to the Autopilot. In addition, UART2 on the\nF9P units are connected to each other.\nModes 3 and 4 only require UART1 on each F9P connected to the Autopilot or Can Node. UART RX DMA is required.\nRTK is still possible with this setup.\nMode 6 is intended for use with a ground control station (not necessarily an RTK correction base).", "max": 1, "min": 0, "name": "GPS_UBX_MODE", "rebootRequired": true, "shortDesc": "u-blox GPS Mode", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Heading (Rover With Moving Base UART1 Connected To Autopilot, UART2 Connected To Moving Base)", "value": 1}, {"description": "Moving Base (UART1 Connected To Autopilot, UART2 Connected To Rover)", "value": 2}, {"description": "Heading (Rover With Moving Base UART1 Connected to Autopilot Or Can Node At 921600)", "value": 3}, {"description": "Moving Base (Moving Base UART1 Connected to Autopilot Or Can Node At 921600)", "value": 4}, {"description": "Rover with Static Base on UART2 (similar to Default, except coming in on UART2)", "value": 5}, {"description": "Ground Control Station (UART2 outputs NMEA)", "value": 6}]}, {"category": "Standard", "default": 0, "group": "GPS", "name": "GPS_UBX_PPK", "rebootRequired": true, "shortDesc": "Enable MSM7 message output for PPK workflow", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "GPS", "longDesc": "Configure the output rate of u-blox GPS receivers (protocol v27+).\nWhen set to 0, automatic rate selection is used based on the receiver model.\nDefault rates: M9N=8Hz, F9P L1L2=5Hz, F9P L1L5=5Hz, Others=10Hz.\nNote: Higher rates reduce satellite count (e.g., >8Hz limits to 16 SVs on M9N).\nMax rates vary by model and RTK mode: F9P L1L2=5-7Hz, F9P L1L5=7-8Hz, X20=25Hz.\nHigh rates at 115200 baud may cause dropouts.", "max": 25, "min": 0, "name": "GPS_UBX_RATE", "rebootRequired": true, "shortDesc": "u-blox GPS output rate", "type": "Int32", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "GPS", "longDesc": "Heading offset angle for dual antenna GPS setups that support heading estimation.\nSet this to 0 if the antennas are parallel to the forward-facing direction\nof the vehicle and the rover (or Unicore primary) antenna is in front.\nThe offset angle increases clockwise.\nSet this to 90 if the rover (or Unicore primary, or Septentrio Mosaic Aux)\nantenna is placed on the right side of the vehicle and the moving base\nantenna is on the left side.\n(Note: the Unicore primary antenna is the one connected on the right as seen\nfrom the top).", "max": 360.0, "min": 0.0, "name": "GPS_YAW_OFFSET", "rebootRequired": true, "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Geofence", "longDesc": "Note: Setting this value to 4 enables flight termination,\nwhich will kill the vehicle on violation of the fence.", "max": 5, "min": 0, "name": "GF_ACTION", "shortDesc": "Geofence violation action", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Warning", "value": 1}, {"description": "Hold mode", "value": 2}, {"description": "Return mode", "value": 3}, {"description": "Terminate", "value": 4}, {"description": "Land mode", "value": 5}]}, {"category": "Standard", "default": 0.0, "group": "Geofence", "increment": 1.0, "longDesc": "Maximum horizontal distance in meters the vehicle can be from Home before triggering a geofence action.\nDisabled if 0.", "max": 10000.0, "min": 0.0, "name": "GF_MAX_HOR_DIST", "shortDesc": "Max horizontal distance from Home", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0.0, "group": "Geofence", "increment": 1.0, "longDesc": "Maximum vertical distance in meters the vehicle can be from Home before triggering a geofence action.\nDisabled if 0.", "max": 10000.0, "min": 0.0, "name": "GF_MAX_VER_DIST", "shortDesc": "Max vertical distance from Home", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geofence", "longDesc": "WARNING: This experimental feature may cause flyaways. Use at your own risk.\nPredict the motion of the vehicle and trigger the breach if it is determined that the current trajectory\nwould result in a breach happening before the vehicle can make evasive maneuvers.\nThe vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing).", "name": "GF_PREDICT", "shortDesc": "[EXPERIMENTAL] Use Pre-emptive geofence triggering", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Geofence", "longDesc": "Select which position source should be used. Selecting GPS instead of global position makes sure that there is\nno dependence on the position estimator\n0 = global position, 1 = GPS", "max": 1, "min": 0, "name": "GF_SOURCE", "shortDesc": "Geofence source", "type": "Int32", "values": [{"description": "GPOS", "value": 0}, {"description": "GPS", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines which mixer implementation to use.\nSome are generic, while others are specifically fit to a certain vehicle with a fixed set of actuators.\n'Custom' should only be used if noting else can be used.", "name": "CA_AIRFRAME", "shortDesc": "Airframe selection", "type": "Int32", "values": [{"description": "Multirotor", "value": 0}, {"description": "Fixed-wing", "value": 1}, {"description": "Standard VTOL", "value": 2}, {"description": "Tiltrotor VTOL", "value": 3}, {"description": "Tailsitter VTOL", "value": 4}, {"description": "Rover (Ackermann)", "value": 5}, {"description": "Rover (Differential)", "value": 6}, {"description": "Motors (6DOF)", "value": 7}, {"description": "Multirotor with Tilt", "value": 8}, {"description": "Custom", "value": 9}, {"description": "Helicopter (tail ESC)", "value": 10}, {"description": "Helicopter (tail Servo)", "value": 11}, {"description": "Helicopter (Coaxial)", "value": 12}, {"description": "Rover (Mecanum)", "value": 13}, {"description": "Spacecraft 2D", "value": 14}, {"description": "Spacecraft 3D", "value": 15}]}, {"bitmask": [{"description": "Control Surface 1", "index": 0}, {"description": "Control Surface 2", "index": 1}, {"description": "Control Surface 3", "index": 2}, {"description": "Control Surface 4", "index": 3}, {"description": "Control Surface 5", "index": 4}, {"description": "Control Surface 6", "index": 5}, {"description": "Control Surface 7", "index": 6}, {"description": "Control Surface 8", "index": 7}], "category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If actuator launch lock is enabled, this surface is kept at the disarmed value.", "max": 255, "min": 0, "name": "CA_CS_LAUN_LK", "shortDesc": "Control surface launch lock enabled", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "This is used to specify how to handle motor failures\nreported by failure detector.", "name": "CA_FAILURE_MODE", "shortDesc": "Motor failure handling mode", "type": "Int32", "values": [{"description": "Ignore", "value": 0}, {"description": "Remove first failed motor from effectiveness", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": -0.05, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 0 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C0", "shortDesc": "Collective pitch curve at position 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0725, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 1 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C1", "shortDesc": "Collective pitch curve at position 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 2 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C2", "shortDesc": "Collective pitch curve at position 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.325, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 3 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C3", "shortDesc": "Collective pitch curve at position 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.45, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the collective pitch at the interval position 4 for a given thrust setpoint.\nUse negative values if the swash plate needs to move down to provide upwards thrust.", "max": 1.0, "min": -1.0, "name": "CA_HELI_PITCH_C4", "shortDesc": "Collective pitch curve at position 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Same definition as the proportional gain but for integral.", "max": 10.0, "min": 0.0, "name": "CA_HELI_RPM_I", "shortDesc": "Integral gain for rpm control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Ratio between rpm error devided by 1000 to how much normalized output gets added to correct for it.\nmotor_command = throttle_curve + CA_HELI_RPM_P * (rpm_setpoint - rpm_measurement) / 1000", "max": 10.0, "min": 0.0, "name": "CA_HELI_RPM_P", "shortDesc": "Proportional gain for rpm control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": 1500.0, "group": "Geometry", "increment": 1.0, "longDesc": "Requires rpm feedback for the controller.", "max": 10000.0, "min": 100.0, "name": "CA_HELI_RPM_SP", "shortDesc": "Setpoint for main rotor rpm", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 0.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C0", "shortDesc": "Throttle curve at position 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 1.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C1", "shortDesc": "Throttle curve at position 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 2.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C2", "shortDesc": "Throttle curve at position 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 3.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C3", "shortDesc": "Throttle curve at position 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Defines the output throttle at the interval position 4.", "max": 1.0, "min": 0.0, "name": "CA_HELI_THR_C4", "shortDesc": "Throttle curve at position 4", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Default configuration is for a clockwise turning main rotor and\npositive thrust of the tail rotor is expected to rotate the vehicle clockwise.\nSet this parameter to true if the tail rotor provides thrust in counter-clockwise direction\nwhich is mostly the case when the main rotor turns counter-clockwise.", "name": "CA_HELI_YAW_CCW", "shortDesc": "Main rotor turns counter-clockwise", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to specify which collective pitch command results in the least amount of rotor drag.\nThis is used to increase the accuracy of the yaw drag torque compensation based on collective pitch\nby aligning the lowest rotor drag with zero compensation.\nFor symmetric profile blades this is the command that results in exactly 0\u00b0 collective blade angle.\nFor lift profile blades this is typically a command resulting in slightly negative collective blade angle.\ntail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O)", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_CP_O", "shortDesc": "Offset for yaw compensation based on collective pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to add a proportional factor of the collective pitch command to the yaw command.\nA negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction.\ntail_output += CA_HELI_YAW_CP_S * abs(collective_pitch - CA_HELI_YAW_CP_O)", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_CP_S", "shortDesc": "Scale for yaw compensation based on collective pitch", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "This allows to add a proportional factor of the throttle command to the yaw command.\nA negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction.\ntail_output += CA_HELI_YAW_TH_S * throttle", "max": 2.0, "min": -2.0, "name": "CA_HELI_YAW_TH_S", "shortDesc": "Scale for yaw compensation based on throttle", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Ice shedding prevents ice buildup in VTOL aircraft motors by\nperiodically spinning inactive rotors. When enabled (period\n> 0), every cycle lasts for the defined period and includes\na 2\u2011second spin at 0.01 motor output. If period <= 0, the\nfeature is disabled.", "min": 0.0, "name": "CA_ICE_PERIOD", "shortDesc": "Ice shedding cycle period", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Used to linearize mechanical output of swashplate servos to avoid axis coupling and binding with 4 servo redundancy.\nThis requires a symmetric setup where the servo horn is exactly centered with a 0 command.\nSetting to zero disables feature.", "max": 75.0, "min": 0.0, "name": "CA_MAX_SVO_THROW", "shortDesc": "Throw angle of swashplate servo at maximum commands for linearization", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 2, "group": "Geometry", "longDesc": "Selects the algorithm and desaturation method.\nIf set to Automatic, the selection is based on the airframe (CA_AIRFRAME).", "name": "CA_METHOD", "shortDesc": "Control allocation method", "type": "Int32", "values": [{"description": "Pseudo-inverse with output clipping", "value": 0}, {"description": "Pseudo-inverse with sequential desaturation technique", "value": 1}, {"description": "Automatic", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R0_SLEW", "shortDesc": "Motor 0 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R10_SLEW", "shortDesc": "Motor 10 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R11_SLEW", "shortDesc": "Motor 11 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R1_SLEW", "shortDesc": "Motor 1 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R2_SLEW", "shortDesc": "Motor 2 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R3_SLEW", "shortDesc": "Motor 3 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R4_SLEW", "shortDesc": "Motor 4 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R5_SLEW", "shortDesc": "Motor 5 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R6_SLEW", "shortDesc": "Motor 6 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R7_SLEW", "shortDesc": "Motor 7 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R8_SLEW", "shortDesc": "Motor 8 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.01, "longDesc": "Forces the motor output signal to take at least the configured time (in seconds)\nto traverse its full range (normally [0, 1], or if reversible [-1, 1]).\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_R9_SLEW", "shortDesc": "Motor 9 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AX", "shortDesc": "Axis of rotor 0 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AY", "shortDesc": "Axis of rotor 0 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_AZ", "shortDesc": "Axis of rotor 0 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR0_CT", "shortDesc": "Thrust coefficient of rotor 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR0_KM", "shortDesc": "Moment coefficient of rotor 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PX", "shortDesc": "Position of rotor 0 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PY", "shortDesc": "Position of rotor 0 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR0_PZ", "shortDesc": "Position of rotor 0 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR0_TILT", "shortDesc": "Rotor 0 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AX", "shortDesc": "Axis of rotor 10 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AY", "shortDesc": "Axis of rotor 10 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_AZ", "shortDesc": "Axis of rotor 10 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR10_CT", "shortDesc": "Thrust coefficient of rotor 10", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR10_KM", "shortDesc": "Moment coefficient of rotor 10", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PX", "shortDesc": "Position of rotor 10 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PY", "shortDesc": "Position of rotor 10 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR10_PZ", "shortDesc": "Position of rotor 10 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR10_TILT", "shortDesc": "Rotor 10 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AX", "shortDesc": "Axis of rotor 11 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AY", "shortDesc": "Axis of rotor 11 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_AZ", "shortDesc": "Axis of rotor 11 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR11_CT", "shortDesc": "Thrust coefficient of rotor 11", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR11_KM", "shortDesc": "Moment coefficient of rotor 11", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PX", "shortDesc": "Position of rotor 11 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PY", "shortDesc": "Position of rotor 11 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR11_PZ", "shortDesc": "Position of rotor 11 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR11_TILT", "shortDesc": "Rotor 11 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AX", "shortDesc": "Axis of rotor 1 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AY", "shortDesc": "Axis of rotor 1 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_AZ", "shortDesc": "Axis of rotor 1 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR1_CT", "shortDesc": "Thrust coefficient of rotor 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR1_KM", "shortDesc": "Moment coefficient of rotor 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PX", "shortDesc": "Position of rotor 1 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PY", "shortDesc": "Position of rotor 1 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR1_PZ", "shortDesc": "Position of rotor 1 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR1_TILT", "shortDesc": "Rotor 1 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AX", "shortDesc": "Axis of rotor 2 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AY", "shortDesc": "Axis of rotor 2 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_AZ", "shortDesc": "Axis of rotor 2 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR2_CT", "shortDesc": "Thrust coefficient of rotor 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR2_KM", "shortDesc": "Moment coefficient of rotor 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PX", "shortDesc": "Position of rotor 2 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PY", "shortDesc": "Position of rotor 2 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR2_PZ", "shortDesc": "Position of rotor 2 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR2_TILT", "shortDesc": "Rotor 2 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AX", "shortDesc": "Axis of rotor 3 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AY", "shortDesc": "Axis of rotor 3 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_AZ", "shortDesc": "Axis of rotor 3 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR3_CT", "shortDesc": "Thrust coefficient of rotor 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR3_KM", "shortDesc": "Moment coefficient of rotor 3", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PX", "shortDesc": "Position of rotor 3 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PY", "shortDesc": "Position of rotor 3 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR3_PZ", "shortDesc": "Position of rotor 3 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR3_TILT", "shortDesc": "Rotor 3 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AX", "shortDesc": "Axis of rotor 4 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AY", "shortDesc": "Axis of rotor 4 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_AZ", "shortDesc": "Axis of rotor 4 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR4_CT", "shortDesc": "Thrust coefficient of rotor 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR4_KM", "shortDesc": "Moment coefficient of rotor 4", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PX", "shortDesc": "Position of rotor 4 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PY", "shortDesc": "Position of rotor 4 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR4_PZ", "shortDesc": "Position of rotor 4 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR4_TILT", "shortDesc": "Rotor 4 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AX", "shortDesc": "Axis of rotor 5 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AY", "shortDesc": "Axis of rotor 5 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_AZ", "shortDesc": "Axis of rotor 5 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR5_CT", "shortDesc": "Thrust coefficient of rotor 5", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR5_KM", "shortDesc": "Moment coefficient of rotor 5", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PX", "shortDesc": "Position of rotor 5 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PY", "shortDesc": "Position of rotor 5 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR5_PZ", "shortDesc": "Position of rotor 5 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR5_TILT", "shortDesc": "Rotor 5 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AX", "shortDesc": "Axis of rotor 6 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AY", "shortDesc": "Axis of rotor 6 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_AZ", "shortDesc": "Axis of rotor 6 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR6_CT", "shortDesc": "Thrust coefficient of rotor 6", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR6_KM", "shortDesc": "Moment coefficient of rotor 6", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PX", "shortDesc": "Position of rotor 6 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PY", "shortDesc": "Position of rotor 6 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR6_PZ", "shortDesc": "Position of rotor 6 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR6_TILT", "shortDesc": "Rotor 6 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AX", "shortDesc": "Axis of rotor 7 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AY", "shortDesc": "Axis of rotor 7 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_AZ", "shortDesc": "Axis of rotor 7 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR7_CT", "shortDesc": "Thrust coefficient of rotor 7", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR7_KM", "shortDesc": "Moment coefficient of rotor 7", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PX", "shortDesc": "Position of rotor 7 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PY", "shortDesc": "Position of rotor 7 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR7_PZ", "shortDesc": "Position of rotor 7 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR7_TILT", "shortDesc": "Rotor 7 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AX", "shortDesc": "Axis of rotor 8 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AY", "shortDesc": "Axis of rotor 8 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_AZ", "shortDesc": "Axis of rotor 8 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR8_CT", "shortDesc": "Thrust coefficient of rotor 8", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR8_KM", "shortDesc": "Moment coefficient of rotor 8", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PX", "shortDesc": "Position of rotor 8 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PY", "shortDesc": "Position of rotor 8 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR8_PZ", "shortDesc": "Position of rotor 8 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR8_TILT", "shortDesc": "Rotor 8 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AX", "shortDesc": "Axis of rotor 9 thrust vector, X body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AY", "shortDesc": "Axis of rotor 9 thrust vector, Y body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Geometry", "increment": 0.1, "longDesc": "Only the direction is considered (the vector is normalized).", "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_AZ", "shortDesc": "Axis of rotor 9 thrust vector, Z body axis component", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.5, "group": "Geometry", "increment": 1.0, "longDesc": "The thrust coefficient if defined as Thrust = CT * u^2,\nwhere u (with value between actuator minimum and maximum)\nis the output signal sent to the motor controller.", "max": 100.0, "min": 0.0, "name": "CA_ROTOR9_CT", "shortDesc": "Thrust coefficient of rotor 9", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Geometry", "increment": 0.01, "longDesc": "The moment coefficient if defined as Torque = KM * Thrust.\nUse a positive value for a rotor with CCW rotation.\nUse a negative value for a rotor with CW rotation.", "max": 1.0, "min": -1.0, "name": "CA_ROTOR9_KM", "shortDesc": "Moment coefficient of rotor 9", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PX", "shortDesc": "Position of rotor 9 along X body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PY", "shortDesc": "Position of rotor 9 along Y body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.1, "max": 100.0, "min": -100.0, "name": "CA_ROTOR9_PZ", "shortDesc": "Position of rotor 9 along Z body axis relative to center of gravity", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "If not set to None, this motor is tilted by the configured tilt servo.", "name": "CA_ROTOR9_TILT", "shortDesc": "Rotor 9 tilt assignment", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Tilt 1", "value": 1}, {"description": "Tilt 2", "value": 2}, {"description": "Tilt 3", "value": 3}, {"description": "Tilt 4", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_ROTOR_COUNT", "shortDesc": "Total number of rotors", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}, {"description": "5", "value": 5}, {"description": "6", "value": 6}, {"description": "7", "value": 7}, {"description": "8", "value": 8}, {"description": "9", "value": 9}, {"description": "10", "value": 10}, {"description": "11", "value": 11}, {"description": "12", "value": 12}]}, {"bitmask": [{"description": "Motor 1", "index": 0}, {"description": "Motor 2", "index": 1}, {"description": "Motor 3", "index": 2}, {"description": "Motor 4", "index": 3}, {"description": "Motor 5", "index": 4}, {"description": "Motor 6", "index": 5}, {"description": "Motor 7", "index": 6}, {"description": "Motor 8", "index": 7}, {"description": "Motor 9", "index": 8}, {"description": "Motor 10", "index": 9}, {"description": "Motor 11", "index": 10}, {"description": "Motor 12", "index": 11}], "category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Configure motors to be bidirectional/reversible. Note that the output driver needs to support this as well.", "max": 4095, "min": 0, "name": "CA_R_REV", "shortDesc": "Bidirectional/Reversible motors", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG0", "shortDesc": "Angle for swash plate servo 0", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 140.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG1", "shortDesc": "Angle for swash plate servo 1", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 220.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG2", "shortDesc": "Angle for swash plate servo 2", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "increment": 10.0, "longDesc": "The angle is measured clockwise (as seen from top), with 0 pointing forwards (X axis).", "max": 360.0, "min": 0.0, "name": "CA_SP0_ANG3", "shortDesc": "Angle for swash plate servo 3", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L0", "shortDesc": "Arm length for swash plate servo 0", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L1", "shortDesc": "Arm length for swash plate servo 1", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L2", "shortDesc": "Arm length for swash plate servo 2", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Geometry", "increment": 0.1, "longDesc": "This is relative to the other arm lengths.", "max": 10.0, "min": 0.0, "name": "CA_SP0_ARM_L3", "shortDesc": "Arm length for swash plate servo 3", "type": "Float"}, {"category": "Standard", "default": 3, "group": "Geometry", "name": "CA_SP0_COUNT", "shortDesc": "Number of swash plates servos", "type": "Int32", "values": [{"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV0_SLEW", "shortDesc": "Servo 0 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV1_SLEW", "shortDesc": "Servo 1 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV2_SLEW", "shortDesc": "Servo 2 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV3_SLEW", "shortDesc": "Servo 3 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV4_SLEW", "shortDesc": "Servo 4 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV5_SLEW", "shortDesc": "Servo 5 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV6_SLEW", "shortDesc": "Servo 6 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "increment": 0.05, "longDesc": "Forces the servo output signal to take at least the configured time (in seconds)\nto traverse its full range [-100%, 100%].\nZero means that slew rate limiting is disabled.", "max": 10.0, "min": 0.0, "name": "CA_SV7_SLEW", "shortDesc": "Servo 7 slew rate limit", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_FLAP", "shortDesc": "Control Surface 0 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_SPOIL", "shortDesc": "Control Surface 0 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS0_TRIM", "shortDesc": "Control Surface 0 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_P", "shortDesc": "Control Surface 0 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_R", "shortDesc": "Control Surface 0 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS0_TRQ_Y", "shortDesc": "Control Surface 0 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS0_TYPE", "shortDesc": "Control Surface 0 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_FLAP", "shortDesc": "Control Surface 1 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_SPOIL", "shortDesc": "Control Surface 1 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS1_TRIM", "shortDesc": "Control Surface 1 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_P", "shortDesc": "Control Surface 1 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_R", "shortDesc": "Control Surface 1 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS1_TRQ_Y", "shortDesc": "Control Surface 1 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS1_TYPE", "shortDesc": "Control Surface 1 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_FLAP", "shortDesc": "Control Surface 2 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_SPOIL", "shortDesc": "Control Surface 2 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS2_TRIM", "shortDesc": "Control Surface 2 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_P", "shortDesc": "Control Surface 2 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_R", "shortDesc": "Control Surface 2 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS2_TRQ_Y", "shortDesc": "Control Surface 2 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS2_TYPE", "shortDesc": "Control Surface 2 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_FLAP", "shortDesc": "Control Surface 3 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_SPOIL", "shortDesc": "Control Surface 3 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS3_TRIM", "shortDesc": "Control Surface 3 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_P", "shortDesc": "Control Surface 3 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_R", "shortDesc": "Control Surface 3 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS3_TRQ_Y", "shortDesc": "Control Surface 3 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS3_TYPE", "shortDesc": "Control Surface 3 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_FLAP", "shortDesc": "Control Surface 4 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_SPOIL", "shortDesc": "Control Surface 4 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS4_TRIM", "shortDesc": "Control Surface 4 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_P", "shortDesc": "Control Surface 4 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_R", "shortDesc": "Control Surface 4 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS4_TRQ_Y", "shortDesc": "Control Surface 4 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS4_TYPE", "shortDesc": "Control Surface 4 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_FLAP", "shortDesc": "Control Surface 5 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_SPOIL", "shortDesc": "Control Surface 5 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS5_TRIM", "shortDesc": "Control Surface 5 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_P", "shortDesc": "Control Surface 5 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_R", "shortDesc": "Control Surface 5 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS5_TRQ_Y", "shortDesc": "Control Surface 5 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS5_TYPE", "shortDesc": "Control Surface 5 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_FLAP", "shortDesc": "Control Surface 6 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_SPOIL", "shortDesc": "Control Surface 6 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS6_TRIM", "shortDesc": "Control Surface 6 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_P", "shortDesc": "Control Surface 6 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_R", "shortDesc": "Control Surface 6 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS6_TRQ_Y", "shortDesc": "Control Surface 6 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS6_TYPE", "shortDesc": "Control Surface 6 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_FLAP", "shortDesc": "Control Surface 7 configuration as flap", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_SPOIL", "shortDesc": "Control Surface 7 configuration as spoiler", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "longDesc": "Can be used to add an offset to the servo control.\nNOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead.\nThis parameter can only be set if all PWM Center parameters are set to default.", "max": 1.0, "min": -1.0, "name": "CA_SV_CS7_TRIM", "shortDesc": "Control Surface 7 trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_P", "shortDesc": "Control Surface 7 pitch torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_R", "shortDesc": "Control Surface 7 roll torque scaling", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Geometry", "name": "CA_SV_CS7_TRQ_Y", "shortDesc": "Control Surface 7 yaw torque scaling", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS7_TYPE", "shortDesc": "Control Surface 7 type", "type": "Int32", "values": [{"description": "(Not set)", "value": 0}, {"description": "Left Aileron", "value": 1}, {"description": "Right Aileron", "value": 2}, {"description": "Elevator", "value": 3}, {"description": "Rudder", "value": 4}, {"description": "Left Elevon", "value": 5}, {"description": "Right Elevon", "value": 6}, {"description": "Left V-Tail", "value": 7}, {"description": "Right V-Tail", "value": 8}, {"description": "Left Flap", "value": 9}, {"description": "Right Flap", "value": 10}, {"description": "Airbrake", "value": 11}, {"description": "Custom", "value": 12}, {"description": "Left A-tail", "value": 13}, {"description": "Right A-tail", "value": 14}, {"description": "Single Channel Aileron", "value": 15}, {"description": "Steering Wheel", "value": 16}, {"description": "Left Spoiler", "value": 17}, {"description": "Right Spoiler", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_CS_COUNT", "shortDesc": "Total number of Control Surfaces", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}, {"description": "5", "value": 5}, {"description": "6", "value": 6}, {"description": "7", "value": 7}, {"description": "8", "value": 8}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Geometry", "max": 5.0, "min": 0.0, "name": "CA_SV_FLAP_SLEW", "shortDesc": "Control Surface slew rate for normalized flaps setpoint", "type": "Float"}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL0_CT", "shortDesc": "Tilt 0 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL0_MAXA", "shortDesc": "Tilt Servo 0 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL0_MINA", "shortDesc": "Tilt Servo 0 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle.\nFor example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front',\nthe motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL0_TD", "shortDesc": "Tilt Servo 0 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL1_CT", "shortDesc": "Tilt 1 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL1_MAXA", "shortDesc": "Tilt Servo 1 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL1_MINA", "shortDesc": "Tilt Servo 1 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle.\nFor example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front',\nthe motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL1_TD", "shortDesc": "Tilt Servo 1 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL2_CT", "shortDesc": "Tilt 2 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL2_MAXA", "shortDesc": "Tilt Servo 2 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL2_MINA", "shortDesc": "Tilt Servo 2 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle.\nFor example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front',\nthe motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL2_TD", "shortDesc": "Tilt Servo 2 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 1, "group": "Geometry", "longDesc": "Define if this servo is used for additional control.", "name": "CA_SV_TL3_CT", "shortDesc": "Tilt 3 is used for control", "type": "Int32", "values": [{"description": "None", "value": 0}, {"description": "Yaw", "value": 1}, {"description": "Pitch", "value": 2}, {"description": "Yaw and Pitch", "value": 3}]}, {"category": "Standard", "decimalPlaces": 0, "default": 90.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the maximum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL3_MAXA", "shortDesc": "Tilt Servo 3 Tilt Angle at Maximum", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 0.0, "group": "Geometry", "longDesc": "Defines the tilt angle when the servo is at the minimum.\nAn angle of zero means upwards.", "max": 90.0, "min": -90.0, "name": "CA_SV_TL3_MINA", "shortDesc": "Tilt Servo 3 Tilt Angle at Minimum", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Geometry", "longDesc": "Defines the direction the servo tilts towards when moving towards the maximum tilt angle.\nFor example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front',\nthe motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt.", "max": 359, "min": 0, "name": "CA_SV_TL3_TD", "shortDesc": "Tilt Servo 3 Tilt Direction", "type": "Int32", "values": [{"description": "Towards Front", "value": 0}, {"description": "Towards Right", "value": 90}]}, {"category": "Standard", "default": 0, "group": "Geometry", "name": "CA_SV_TL_COUNT", "shortDesc": "Total number of Tilt Servos", "type": "Int32", "values": [{"description": "0", "value": 0}, {"description": "1", "value": 1}, {"description": "2", "value": 2}, {"description": "3", "value": 3}, {"description": "4", "value": 4}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Hover Thrust Estimator", "longDesc": "Sets the number of standard deviations used\nby the innovation consistency test.", "max": 10.0, "min": 1.0, "name": "HTE_ACC_GATE", "shortDesc": "Gate size for acceleration fusion", "type": "Float", "units": "SD"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Hover Thrust Estimator", "longDesc": "Sets the number of standard deviations used\nby the innovation consistency test.", "max": 1.0, "min": 0.0, "name": "HTE_HT_ERR_INIT", "shortDesc": "1-sigma initial hover thrust uncertainty", "type": "Float", "units": "normalized_thrust"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0036, "group": "Hover Thrust Estimator", "longDesc": "Reduce to make the hover thrust estimate\nmore stable, increase if the real hover thrust\nis expected to change quickly over time.", "max": 1.0, "min": 0.0001, "name": "HTE_HT_NOISE", "shortDesc": "Hover thrust process noise", "type": "Float", "units": "normalized_thrust/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Hover Thrust Estimator", "longDesc": "Defines the range of the hover thrust estimate around MPC_THR_HOVER.\nA value of 0.2 with MPC_THR_HOVER at 0.5 results in a range of [0.3, 0.7].\nSet to a large value if the vehicle operates in varying physical conditions that\naffect the required hover thrust strongly (e.g. differently sized payloads).", "max": 0.4, "min": 0.01, "name": "HTE_THR_RANGE", "shortDesc": "Max deviation from MPC_THR_HOVER", "type": "Float", "units": "normalized_thrust"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Hover Thrust Estimator", "longDesc": "Above this speed, the measurement noise is linearly increased\nto reduce the sensitivity of the estimator from biased measurement.\nSet to a low value on vehicles with large lifting surfaces.", "max": 20.0, "min": 1.0, "name": "HTE_VXY_THR", "shortDesc": "Horizontal velocity threshold for sensitivity reduction", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Hover Thrust Estimator", "longDesc": "Above this speed, the measurement noise is linearly increased\nto reduce the sensitivity of the estimator from biased measurement.\nSet to a low value on vehicles affected by air drag when climbing or descending.", "max": 10.0, "min": 1.0, "name": "HTE_VZ_THR", "shortDesc": "Vertical velocity threshold for sensitivity reduction", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.0, "group": "Land Detector", "longDesc": "Maximum airspeed allowed in the landed state", "max": 30.0, "min": 2.0, "name": "LNDFW_AIRSPD_MAX", "shortDesc": "Fixed-wing land detector: Max airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Land Detector", "longDesc": "Maximum allowed norm of the angular velocity in the landed state.\nOnly used if neither airspeed nor groundspeed can be used for landing detection.", "name": "LNDFW_ROT_MAX", "shortDesc": "Fixed-wing land detector: max rotational speed", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Land Detector", "longDesc": "Time the land conditions (speeds and acceleration) have to be satisfied to detect a landing.", "min": 0.1, "name": "LNDFW_TRIG_TIME", "rebootRequired": true, "shortDesc": "Fixed-wing land detection trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Land Detector", "longDesc": "Maximum horizontal velocity allowed in the landed state.\nA factor of 0.7 is applied in case of airspeed-less flying\n(either because no sensor is present or sensor data got invalid in flight).", "max": 20.0, "min": 0.5, "name": "LNDFW_VEL_XY_MAX", "shortDesc": "Fixed-wing land detector: Max horizontal velocity threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Land Detector", "longDesc": "Maximum vertical velocity allowed in the landed state.", "max": 20.0, "min": 0.1, "name": "LNDFW_VEL_Z_MAX", "shortDesc": "Fixed-wing land detector: Max vertiacal velocity threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 8.0, "group": "Land Detector", "longDesc": "Maximum horizontal (x,y body axes) acceleration allowed in the landed state", "max": 30.0, "min": 2.0, "name": "LNDFW_XYACC_MAX", "shortDesc": "Fixed-wing land detector: Max horizontal acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Land Detector", "longDesc": "The height above ground below which ground effect creates barometric altitude errors.\nA negative value indicates no ground effect.", "min": -1.0, "name": "LNDMC_ALT_GND", "shortDesc": "Ground effect altitude for multicopters", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Land Detector", "longDesc": "Maximum allowed norm of the angular velocity (roll, pitch) in the landed state.", "name": "LNDMC_ROT_MAX", "shortDesc": "Multicopter max rotational speed", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Land Detector", "longDesc": "Total time it takes to go through all three land detection stages:\nground contact, maybe landed, landed\nwhen all necessary conditions are constantly met.", "max": 10.0, "min": 0.1, "name": "LNDMC_TRIG_TIME", "shortDesc": "Multicopter land detection trigger time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Land Detector", "longDesc": "Maximum horizontal velocity allowed in the landed state", "name": "LNDMC_XY_VEL_MAX", "shortDesc": "Multicopter max horizontal velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.25, "group": "Land Detector", "longDesc": "Vertical velocity threshold to detect landing.\nHas to be set lower than the expected minimal speed for landing,\nwhich is either MPC_LAND_SPEED or MPC_LAND_CRWL.\nThis is enforced by an automatic check.", "min": 0.0, "name": "LNDMC_Z_VEL_MAX", "shortDesc": "Multicopter vertical velocity threshold", "type": "Float", "units": "m/s"}, {"category": "System", "default": 0, "group": "Land Detector", "longDesc": "Total flight time of this autopilot. Higher 32 bits of the value.\nFlight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO.", "min": 0, "name": "LND_FLIGHT_T_HI", "shortDesc": "Total flight time in microseconds", "type": "Int32", "volatile": true}, {"category": "System", "default": 0, "group": "Land Detector", "longDesc": "Total flight time of this autopilot. Lower 32 bits of the value.\nFlight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO.", "min": 0, "name": "LND_FLIGHT_T_LO", "shortDesc": "Total flight time in microseconds", "type": "Int32", "volatile": true}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Landing Target Estimator", "longDesc": "Variance of acceleration measurement used for landing target position prediction.\nHigher values results in tighter following of the measurements and more lenient outlier rejection", "min": 0.01, "name": "LTEST_ACC_UNC", "shortDesc": "Acceleration uncertainty", "type": "Float", "units": "(m/s^2)^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.005, "group": "Landing Target Estimator", "longDesc": "Variance of the landing target measurement from the driver.\nHigher values result in less aggressive following of the measurement and a smoother output as well as fewer rejected measurements.", "name": "LTEST_MEAS_UNC", "shortDesc": "Landing target measurement uncertainty", "type": "Float", "units": "tan(rad)^2"}, {"category": "Standard", "default": 0, "group": "Landing Target Estimator", "longDesc": "Configure the mode of the landing target. Depending on the mode, the landing target observations are used differently to aid position estimation.\nMode Moving: The landing target may be moving around while in the field of view of the vehicle. Landing target measurements are not used to aid positioning.\nMode Stationary: The landing target is stationary. Measured velocity w.r.t. the landing target is used to aid velocity estimation.", "max": 1, "min": 0, "name": "LTEST_MODE", "shortDesc": "Landing target mode", "type": "Int32", "values": [{"description": "Moving", "value": 0}, {"description": "Stationary", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Landing Target Estimator", "longDesc": "Initial variance of the relative landing target position in x and y direction", "min": 0.001, "name": "LTEST_POS_UNC_IN", "shortDesc": "Initial landing target position uncertainty", "type": "Float", "units": "m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Landing Target Estimator", "longDesc": "Landing target x measurements are scaled by this factor before being used", "min": 0.01, "name": "LTEST_SCALE_X", "shortDesc": "Scale factor for sensor measurements in sensor x axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Landing Target Estimator", "longDesc": "Landing target y measurements are scaled by this factor before being used", "min": 0.01, "name": "LTEST_SCALE_Y", "shortDesc": "Scale factor for sensor measurements in sensor y axis", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_X", "rebootRequired": true, "shortDesc": "X Position of IRLOCK in body frame (forward)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_Y", "rebootRequired": true, "shortDesc": "Y Position of IRLOCK in body frame (right)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Landing Target Estimator", "name": "LTEST_SENS_POS_Z", "rebootRequired": true, "shortDesc": "Z Position of IRLOCK in body frame (downward)", "type": "Float", "units": "m"}, {"category": "Standard", "default": 2, "group": "Landing Target Estimator", "longDesc": "Default orientation of Yaw 90\u00b0", "max": 40, "min": -1, "name": "LTEST_SENS_ROT", "rebootRequired": true, "shortDesc": "Rotation of IRLOCK sensor relative to airframe", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Landing Target Estimator", "longDesc": "Initial variance of the relative landing target velocity in x and y directions", "min": 0.001, "name": "LTEST_VEL_UNC_IN", "shortDesc": "Initial landing target velocity uncertainty", "type": "Float", "units": "(m/s)^2"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.012, "group": "Local Position Estimator", "longDesc": "Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)\nLarger than data sheet to account for tilt error.", "max": 2.0, "min": 1e-05, "name": "LPE_ACC_XY", "shortDesc": "Accelerometer xy noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.02, "group": "Local Position Estimator", "longDesc": "Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)", "max": 2.0, "min": 1e-05, "name": "LPE_ACC_Z", "shortDesc": "Accelerometer z noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Local Position Estimator", "max": 100.0, "min": 0.01, "name": "LPE_BAR_Z", "shortDesc": "Barometric presssure altitude z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Local Position Estimator", "name": "LPE_EN", "shortDesc": "Local position estimator enable (unsupported)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 3.0, "group": "Local Position Estimator", "max": 5.0, "min": 1.0, "name": "LPE_EPH_MAX", "shortDesc": "Max EPH allowed for GPS initialization", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 5.0, "group": "Local Position Estimator", "max": 5.0, "min": 1.0, "name": "LPE_EPV_MAX", "shortDesc": "Max EPV allowed for GPS initialization", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Local Position Estimator", "longDesc": "By initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable", "max": 1, "min": 0, "name": "LPE_FAKE_ORIGIN", "shortDesc": "Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow)", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Local Position Estimator", "max": 2.0, "min": 0.0, "name": "LPE_FGYRO_HP", "shortDesc": "Flow gyro high pass filter cut off frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_FLW_OFF_Z", "shortDesc": "Optical flow z offset from center", "type": "Float", "units": "m"}, {"category": "Standard", "default": 150, "group": "Local Position Estimator", "max": 255, "min": 0, "name": "LPE_FLW_QMIN", "shortDesc": "Optical flow minimum quality threshold", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 7.0, "group": "Local Position Estimator", "max": 10.0, "min": 0.1, "name": "LPE_FLW_R", "shortDesc": "Optical flow rotation (roll/pitch) noise gain", "type": "Float", "units": "m/s/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 7.0, "group": "Local Position Estimator", "max": 10.0, "min": 0.0, "name": "LPE_FLW_RR", "shortDesc": "Optical flow angular velocity noise gain", "type": "Float", "units": "m/rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.3, "group": "Local Position Estimator", "max": 10.0, "min": 0.1, "name": "LPE_FLW_SCALE", "shortDesc": "Optical flow scale", "type": "Float", "units": "m"}, {"bitmask": [{"description": "fuse GPS, requires GPS for alt. init", "index": 0}, {"description": "fuse optical flow", "index": 1}, {"description": "fuse vision position", "index": 2}, {"description": "fuse landing target", "index": 3}, {"description": "fuse land detector", "index": 4}, {"description": "pub agl as lpos down", "index": 5}, {"description": "flow gyro compensation", "index": 6}, {"description": "fuse baro", "index": 7}], "category": "Standard", "default": 145, "group": "Local Position Estimator", "longDesc": "Set bits in the following positions to enable:\n0 : Set to true to fuse GPS data if available, also requires GPS for altitude init\n1 : Set to true to fuse optical flow data if available\n2 : Set to true to fuse vision position\n3 : Set to true to enable landing target\n4 : Set to true to fuse land detector\n5 : Set to true to publish AGL as local position down component\n6 : Set to true to enable flow gyro compensation\n7 : Set to true to enable baro fusion\ndefault (145 - GPS, baro, land detector)", "max": 255, "min": 0, "name": "LPE_FUSION", "shortDesc": "Integer bitmask controlling data fusion", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.29, "group": "Local Position Estimator", "max": 0.4, "min": 0.0, "name": "LPE_GPS_DELAY", "shortDesc": "GPS delay compensaton", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Local Position Estimator", "longDesc": "EPV used if greater than this value.", "max": 2.0, "min": 0.01, "name": "LPE_GPS_VXY", "shortDesc": "GPS xy velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.25, "group": "Local Position Estimator", "max": 2.0, "min": 0.01, "name": "LPE_GPS_VZ", "shortDesc": "GPS z velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Local Position Estimator", "max": 5.0, "min": 0.01, "name": "LPE_GPS_XY", "shortDesc": "Minimum GPS xy standard deviation, uses reported EPH if greater", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Local Position Estimator", "max": 200.0, "min": 0.01, "name": "LPE_GPS_Z", "shortDesc": "Minimum GPS z standard deviation, uses reported EPV if greater", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Local Position Estimator", "max": 10.0, "min": 0.01, "name": "LPE_LAND_VXY", "shortDesc": "Land detector xy velocity standard deviation", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Local Position Estimator", "max": 10.0, "min": 0.001, "name": "LPE_LAND_Z", "shortDesc": "Land detector z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 8, "default": 47.397742, "group": "Local Position Estimator", "max": 90.0, "min": -90.0, "name": "LPE_LAT", "shortDesc": "Local origin latitude for nav w/o GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_LDR_OFF_Z", "shortDesc": "Lidar z offset from center of vehicle +down", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_LDR_Z", "shortDesc": "Lidar z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 8, "default": 8.545594, "group": "Local Position Estimator", "max": 180.0, "min": -180.0, "name": "LPE_LON", "shortDesc": "Local origin longitude for nav w/o GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0001, "group": "Local Position Estimator", "max": 10.0, "min": 0.0, "name": "LPE_LT_COV", "shortDesc": "Minimum landing target standard covariance, uses reported covariance if greater", "type": "Float", "units": "m^2"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0, "name": "LPE_PN_B", "shortDesc": "Accel bias propagation noise density", "type": "Float", "units": "m/s^3/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Increase to trust measurements more.\nDecrease to trust model more.", "max": 1.0, "min": 0.0, "name": "LPE_PN_P", "shortDesc": "Position propagation noise density", "type": "Float", "units": "m/s/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0, "name": "LPE_PN_T", "shortDesc": "Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001)", "type": "Float", "units": "m/s/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 8, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Increase to trust measurements more.\nDecrease to trust model more.", "max": 1.0, "min": 0.0, "name": "LPE_PN_V", "shortDesc": "Velocity propagation noise density", "type": "Float", "units": "m/s^2/sqrt(Hz)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Local Position Estimator", "max": 1.0, "min": -1.0, "name": "LPE_SNR_OFF_Z", "shortDesc": "Sonar z offset from center of vehicle +down", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.05, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_SNR_Z", "shortDesc": "Sonar z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Local Position Estimator", "longDesc": "Used to calculate increased terrain random walk nosie due to movement.", "max": 100.0, "min": 0.0, "name": "LPE_T_MAX_GRADE", "shortDesc": "Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg)", "type": "Float", "units": "%"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.001, "group": "Local Position Estimator", "max": 1.0, "min": 0.0001, "name": "LPE_VIC_P", "shortDesc": "Vicon position standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Local Position Estimator", "longDesc": "Set to zero to enable automatic compensation from measurement timestamps", "max": 0.1, "min": 0.0, "name": "LPE_VIS_DELAY", "shortDesc": "Vision delay compensation", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_VIS_XY", "shortDesc": "Vision xy standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "Local Position Estimator", "max": 100.0, "min": 0.01, "name": "LPE_VIS_Z", "shortDesc": "Vision z standard deviation", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.3, "group": "Local Position Estimator", "max": 1.0, "min": 0.01, "name": "LPE_VXY_PUB", "shortDesc": "Required velocity xy standard deviation to publish position", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 5.0, "group": "Local Position Estimator", "max": 1000.0, "min": 5.0, "name": "LPE_X_LP", "shortDesc": "Cut frequency for state publication", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Local Position Estimator", "max": 5.0, "min": 0.3, "name": "LPE_Z_PUB", "shortDesc": "Required z standard deviation to publish altitude/ terrain", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone\non the local network.", "name": "MAV_0_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 0", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink\ninstance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_0_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 0", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the\nmessage is either broadcast or the target is not the autopilot.\nThis allows for example a GCS to talk to a camera that is connected to the\nautopilot via MAVLink (on a different link than the GCS).", "name": "MAV_0_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 0", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the\nHIGH_LATENCY2 stream for instance 0, configured in iridium mode.\nThis parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_0_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 0", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the\nvehicle's attitude) and their sending rates.", "name": "MAV_0_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 0", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to\n`txbuf` field reported by radio_status.\nRequires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_0_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 0", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1200, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec.\nIf the configured streams exceed the maximum rate, the sending rate of\neach stream is automatically decreased.\nIf this is set to 0 a value of half of the theoretical maximum bandwidth is used.\nThis corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on\n8N1-configured links).", "min": 0, "name": "MAV_0_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 0", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 14550, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 0,\nselected remote port will be set and used in MAVLink instance 0.", "name": "MAV_0_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 0", "type": "Int32"}, {"category": "Standard", "default": 14556, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 0,\nselected udp port will be set and used in MAVLink instance 0.", "name": "MAV_0_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 0", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone\non the local network.", "name": "MAV_1_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 1", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink\ninstance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_1_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 1", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the\nmessage is either broadcast or the target is not the autopilot.\nThis allows for example a GCS to talk to a camera that is connected to the\nautopilot via MAVLink (on a different link than the GCS).", "name": "MAV_1_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 1", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the\nHIGH_LATENCY2 stream for instance 1, configured in iridium mode.\nThis parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_1_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 1", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the\nvehicle's attitude) and their sending rates.", "name": "MAV_1_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 1", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to\n`txbuf` field reported by radio_status.\nRequires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_1_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 1", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec.\nIf the configured streams exceed the maximum rate, the sending rate of\neach stream is automatically decreased.\nIf this is set to 0 a value of half of the theoretical maximum bandwidth is used.\nThis corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on\n8N1-configured links).", "min": 0, "name": "MAV_1_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 1", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 1,\nselected remote port will be set and used in MAVLink instance 1.", "name": "MAV_1_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 1", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 1,\nselected udp port will be set and used in MAVLink instance 1.", "name": "MAV_1_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 1", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "This allows a ground control station to automatically find the drone\non the local network.", "name": "MAV_2_BROADCAST", "shortDesc": "Broadcast heartbeats on local network for MAVLink instance 2", "type": "Int32", "values": [{"description": "Never broadcast", "value": 0}, {"description": "Always broadcast", "value": 1}, {"description": "Only multicast", "value": 2}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "longDesc": "This is used to force flow control on or off for the the mavlink\ninstance. By default it is auto detected. Use when auto detection fails.", "name": "MAV_2_FLOW_CTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for instance 2", "type": "Int32", "values": [{"description": "Force off", "value": 0}, {"description": "Force on", "value": 1}, {"description": "Auto-detected", "value": 2}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the\nmessage is either broadcast or the target is not the autopilot.\nThis allows for example a GCS to talk to a camera that is connected to the\nautopilot via MAVLink (on a different link than the GCS).", "name": "MAV_2_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink Message forwarding for instance 2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.015, "group": "MAVLink", "increment": 0.001, "longDesc": "Positive real value that configures the transmission frequency of the\nHIGH_LATENCY2 stream for instance 2, configured in iridium mode.\nThis parameter has no effect if the instance mode is different from iridium.", "max": 50.0, "min": 0.0, "name": "MAV_2_HL_FREQ", "rebootRequired": true, "shortDesc": "Configures the frequency of HIGH_LATENCY2 stream for instance 2", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the\nvehicle's attitude) and their sending rates.", "name": "MAV_2_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for instance 2", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Custom", "value": 1}, {"description": "Onboard", "value": 2}, {"description": "OSD", "value": 3}, {"description": "Magic", "value": 4}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "External Vision", "value": 8}, {"description": "Gimbal", "value": 10}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "uAvionix", "value": 12}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If enabled, MAVLink messages will be throttled according to\n`txbuf` field reported by radio_status.\nRequires a radio to send the mavlink message RADIO_STATUS.", "name": "MAV_2_RADIO_CTL", "rebootRequired": true, "shortDesc": "Enable software throttling of mavlink on instance 2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "Configure the maximum sending rate for the MAVLink streams in Bytes/sec.\nIf the configured streams exceed the maximum rate, the sending rate of\neach stream is automatically decreased.\nIf this is set to 0 a value of half of the theoretical maximum bandwidth is used.\nThis corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on\n8N1-configured links).", "min": 0, "name": "MAV_2_RATE", "rebootRequired": true, "shortDesc": "Maximum MAVLink sending rate for instance 2", "type": "Int32", "units": "B/s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 2,\nselected remote port will be set and used in MAVLink instance 2.", "name": "MAV_2_REMOTE_PRT", "rebootRequired": true, "shortDesc": "MAVLink Remote Port for instance 2", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If ethernet enabled and selected as configuration for MAVLink instance 2,\nselected udp port will be set and used in MAVLink instance 2.", "name": "MAV_2_UDP_PRT", "rebootRequired": true, "shortDesc": "MAVLink Network Port for instance 2", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "max": 250, "min": 1, "name": "MAV_COMP_ID", "rebootRequired": true, "shortDesc": "MAVLink component ID", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "If set to 1 incoming external setpoint messages will be directly forwarded\nto the controllers if in offboard control mode", "name": "MAV_FWDEXTSP", "shortDesc": "Forward external setpoint messages", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "Disabling the parameter hash check functionality will make the mavlink instance\nstream parameters continuously.", "name": "MAV_HASH_CHK_EN", "shortDesc": "Parameter hash check", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "MAVLink", "longDesc": "The mavlink heartbeat message will not be forwarded if this parameter is set to 'disabled'.\nThe main reason for disabling heartbeats to be forwarded is because they confuse dronekit.", "name": "MAV_HB_FORW_EN", "shortDesc": "Heartbeat message forwarding", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "MAVLink", "name": "MAV_PROTO_VER", "shortDesc": "MAVLink protocol version", "type": "Int32", "values": [{"description": "Version 1 with auto-upgrade to v2 if detected", "value": 1}, {"description": "Version 2", "value": 2}]}, {"category": "Standard", "default": 5, "group": "MAVLink", "longDesc": "If the connected radio stops reporting RADIO_STATUS for a certain time,\na warning is triggered and, if MAV_X_RADIO_CTL is enabled, the software-flow\ncontrol is reset.", "max": 250, "min": 1, "name": "MAV_RADIO_TOUT", "shortDesc": "Timeout in seconds for the RADIO_STATUS reports coming in", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "When non-zero the MAVLink app will attempt to configure the\nSiK radio to this ID and re-set the parameter to 0. If the value\nis negative it will reset the complete radio config to\nfactory defaults. Only applies if this mavlink instance is going through a SiK radio", "max": 240, "min": -1, "name": "MAV_SIK_RADIO_ID", "shortDesc": "MAVLink SiK Radio ID", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "MAVLink", "max": 250, "min": 1, "name": "MAV_SYS_ID", "rebootRequired": true, "shortDesc": "MAVLink system ID", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "TELEM2 on Skynode only.", "name": "MAV_S_FORWARD", "rebootRequired": true, "shortDesc": "Enable MAVLink forwarding on TELEM2", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 11, "group": "MAVLink", "longDesc": "The MAVLink Mode defines the set of streamed messages (for example the\nvehicle's attitude) and their sending rates.", "name": "MAV_S_MODE", "rebootRequired": true, "shortDesc": "MAVLink Mode for SOM to FMU communication channel", "type": "Int32", "values": [{"description": "Normal", "value": 0}, {"description": "Onboard", "value": 2}, {"description": "Config", "value": 5}, {"description": "Minimal", "value": 7}, {"description": "Onboard Low Bandwidth", "value": 11}, {"description": "Low Bandwidth", "value": 13}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "max": 22, "min": 0, "name": "MAV_TYPE", "shortDesc": "MAVLink airframe type", "type": "Int32", "values": [{"description": "Generic micro air vehicle", "value": 0}, {"description": "Fixed wing aircraft", "value": 1}, {"description": "Quadrotor", "value": 2}, {"description": "Coaxial helicopter", "value": 3}, {"description": "Normal helicopter with tail rotor", "value": 4}, {"description": "Airship, controlled", "value": 7}, {"description": "Free balloon, uncontrolled", "value": 8}, {"description": "Ground rover", "value": 10}, {"description": "Surface vessel, boat, ship", "value": 11}, {"description": "Submarine", "value": 12}, {"description": "Hexarotor", "value": 13}, {"description": "Octorotor", "value": 14}, {"description": "Tricopter", "value": 15}, {"description": "VTOL Two-rotor Tailsitter", "value": 19}, {"description": "VTOL Quad-rotor Tailsitter", "value": 20}, {"description": "VTOL Tiltrotor", "value": 21}, {"description": "VTOL Standard (separate fixed rotors for hover and cruise flight)", "value": 22}, {"description": "VTOL Tailsitter", "value": 23}]}, {"category": "Standard", "default": 0, "group": "MAVLink", "longDesc": "If set to 1 incoming HIL GPS messages are parsed.", "name": "MAV_USEHILGPS", "shortDesc": "Use/Accept HIL GPS message even if not in HIL mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Magnetometer Bias Estimator", "longDesc": "This enables continuous calibration of the magnetometers\nbefore takeoff using gyro data.", "name": "MBE_ENABLE", "rebootRequired": true, "shortDesc": "Enable online mag bias calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 18.0, "group": "Magnetometer Bias Estimator", "increment": 0.1, "longDesc": "Increase to make the estimator more responsive\nDecrease to make the estimator more robust to noise", "max": 100.0, "min": 0.1, "name": "MBE_LEARN_GAIN", "shortDesc": "Mag bias estimator learning gain", "type": "Float"}, {"category": "Standard", "default": 1, "group": "Manual Control", "longDesc": "This determines if moving the left stick to the lower right\narms and to the lower left disarms the vehicle.", "name": "MAN_ARM_GESTURE", "shortDesc": "Enable arm/disarm stick gesture", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Manual Control", "increment": 0.01, "longDesc": "Range around stick center ignored to prevent\nvehicle drift from stick hardware inaccuracy.\nDoes not apply to any precise constant input like\nthrottle and attitude or rate piloting.", "max": 1.0, "min": 0.0, "name": "MAN_DEADZONE", "shortDesc": "Deadzone for sticks (only specific use cases)", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Manual Control", "longDesc": "The timeout for holding the left stick to the lower left\nand the right stick to the lower right at the same time until the gesture\nkills the actuators one-way.\nA negative value disables the feature.", "max": 15.0, "min": -1.0, "name": "MAN_KILL_GEST_T", "shortDesc": "Trigger time for kill stick gesture", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Mission", "longDesc": "Ensure:\ngripper: NAV_CMD_DO_GRIPPER\nhas released before continuing mission.\nwinch: CMD_DO_WINCH\nhas delivered before continuing mission.\ngimbal: CMD_DO_GIMBAL_MANAGER_PITCHYAW\nhas reached the commanded orientation before beginning to take pictures.", "min": 0.0, "name": "MIS_COMMAND_TOUT", "shortDesc": "Timeout to allow the payload to execute the mission command", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 10000.0, "group": "Mission", "increment": 100.0, "longDesc": "There will be a warning message if the current waypoint is more distant than MIS_DIST_1WP from Home.\nHas no effect on mission validity.\nSet a value of zero or less to disable.", "max": 100000.0, "min": -1.0, "name": "MIS_DIST_1WP", "shortDesc": "Maximal horizontal distance from Home to first waypoint", "type": "Float", "units": "m"}, {"category": "Standard", "default": 30, "group": "Mission", "longDesc": "Minimum altitude above landing point that the vehicle will climb to after an aborted landing.\nThen vehicle will loiter in this altitude until further command is received.\nOnly applies to fixed-wing vehicles.", "min": 0, "name": "MIS_LND_ABRT_ALT", "shortDesc": "Landing abort min altitude", "type": "Int32", "units": "m"}, {"category": "Standard", "default": 0, "group": "Mission", "longDesc": "If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading towards the flight direction.\nIf disabled, the vehicle will yaw towards the ROI.", "max": 1, "min": 0, "name": "MIS_MNT_YAW_CTL", "shortDesc": "Enable yaw control of the mount. (Only affects multicopters and ROI mission items)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Enable", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 2.5, "group": "Mission", "increment": 0.5, "longDesc": "This is the relative altitude the system will take off to\nif not otherwise specified.", "min": 0.0, "name": "MIS_TAKEOFF_ALT", "shortDesc": "Default take-off altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Mission", "longDesc": "Specifies if a mission has to contain a takeoff and/or mission landing.\nValidity of configured takeoffs/landings is checked independently of the setting here.", "name": "MIS_TKO_LAND_REQ", "shortDesc": "Mission takeoff/landing required", "type": "Int32", "values": [{"description": "No requirements", "value": 0}, {"description": "Require a takeoff", "value": 1}, {"description": "Require a landing", "value": 2}, {"description": "Require a takeoff and a landing", "value": 3}, {"description": "Require both a takeoff and a landing, or neither", "value": 4}, {"description": "Same as previous when landed, in-air require landing only if no valid VTOL approach is present", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": 12.0, "group": "Mission", "increment": 1.0, "max": 90.0, "min": 0.0, "name": "MIS_YAW_ERR", "shortDesc": "Max yaw error in degrees needed for waypoint heading acceptance", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 1.0, "longDesc": "If set > 0 it will ignore the target heading for normal waypoint acceptance. If the\nwaypoint forces the heading the timeout will matter. For example on VTOL forwards transition.\nMainly useful for VTOLs that have less yaw authority and might not reach target\nyaw in wind. Disabled by default.", "max": 20.0, "min": -1.0, "name": "MIS_YAW_TMT", "shortDesc": "Time in seconds we wait on reaching target heading at a waypoint if it is forced", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Mission", "max": 4, "min": 0, "name": "MPC_YAW_MODE", "shortDesc": "Heading behavior in autonomous modes", "type": "Int32", "values": [{"description": "towards waypoint", "value": 0}, {"description": "towards home", "value": 1}, {"description": "away from home", "value": 2}, {"description": "along trajectory", "value": 3}, {"description": "towards waypoint (yaw first)", "value": 4}, {"description": "yaw fixed", "value": 5}]}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Mission", "increment": 0.5, "longDesc": "Default acceptance radius, overridden by acceptance radius of waypoint if set.\nFor fixed wing the npfg switch distance is used for horizontal acceptance.", "max": 200.0, "min": 0.05, "name": "NAV_ACC_RAD", "shortDesc": "Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Mission", "name": "NAV_FORCE_VT", "shortDesc": "Force VTOL mode takeoff and land", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Mission", "longDesc": "Altitude acceptance used for the last waypoint before a fixed-wing landing. This is usually smaller\nthan the standard vertical acceptance because close to the ground higher accuracy is required.", "max": 200.0, "min": 0.05, "name": "NAV_FW_ALTL_RAD", "shortDesc": "FW Altitude Acceptance Radius before a landing", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Mission", "increment": 0.5, "longDesc": "Acceptance radius for fixedwing altitude.", "max": 200.0, "min": 0.05, "name": "NAV_FW_ALT_RAD", "shortDesc": "FW Altitude Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 80.0, "group": "Mission", "increment": 0.5, "longDesc": "Default value of loiter radius in fixed-wing mode (e.g. for Loiter mode).\nThe direction of the loiter can be set via the sign: A positive value for\nclockwise, negative for counter-clockwise.", "max": 10000.0, "min": -10000.0, "name": "NAV_LOITER_RAD", "shortDesc": "Loiter radius (FW only)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.8, "group": "Mission", "increment": 0.5, "longDesc": "Acceptance radius for multicopter altitude.", "max": 200.0, "min": 0.05, "name": "NAV_MC_ALT_RAD", "shortDesc": "MC Altitude Acceptance Radius", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 1.0, "longDesc": "Minimum height above ground the vehicle is allowed to descend to during Mission and RTL,\nexcluding landing commands.\nRequires a distance sensor to be set up.\nNote: only prevents the vehicle from descending further, but does not force it to climb.\nSet to a negative value to disable.", "min": -1.0, "name": "NAV_MIN_GND_DIST", "shortDesc": "Minimum height above ground during Mission and RTL", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Mission", "increment": 0.5, "longDesc": "This is the minimum altitude above Home the system will always obey in Loiter (Hold) mode if switched into this\nmode without specifying an altitude (e.g. through Loiter switch on RC).\nDoesn't affect Loiters that are part of Missions or that are entered through a reposition setpoint (\"Go to\").\nSet to a negative value to disable.", "min": -1.0, "name": "NAV_MIN_LTR_ALT", "shortDesc": "Minimum Loiter altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 1, "group": "Mission", "longDesc": "Enabling this will allow the system to respond\nto transponder data from e.g. ADSB transponders", "name": "NAV_TRAFF_AVOID", "shortDesc": "Set traffic avoidance mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Warn only", "value": 1}, {"description": "Return mode", "value": 2}, {"description": "Land mode", "value": 3}, {"description": "Position Hold mode", "value": 4}]}, {"category": "Standard", "default": 500.0, "group": "Mission", "longDesc": "Defines a crosstrack horizontal distance", "min": 500.0, "name": "NAV_TRAFF_A_HOR", "shortDesc": "Set NAV TRAFFIC AVOID horizontal distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 500.0, "group": "Mission", "max": 500.0, "min": 10.0, "name": "NAV_TRAFF_A_VER", "shortDesc": "Set NAV TRAFFIC AVOID vertical distance", "type": "Float", "units": "m"}, {"category": "Standard", "default": 60, "group": "Mission", "longDesc": "Minimum acceptable time until collsion.\nAssumes constant speed over 3d distance.", "max": 900000000, "min": 1, "name": "NAV_TRAFF_COLL_T", "shortDesc": "Estimated time until collision", "type": "Int32", "units": "s"}, {"category": "Standard", "default": 0, "group": "Mixer Output", "longDesc": "The air-mode enables the mixer to increase the total thrust of the multirotor\nin order to keep attitude and rate control even at low and high throttle.\nThis function should be disabled during tuning as it will help the controller\nto diverge if the closed-loop is unstable (i.e. the vehicle is not tuned yet).\nEnabling air-mode for yaw requires the use of an arming switch.", "name": "MC_AIRMODE", "shortDesc": "Multicopter air-mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Roll/Pitch", "value": 1}, {"description": "Roll/Pitch/Yaw", "value": 2}]}, {"category": "Standard", "default": 0, "group": "Mount", "longDesc": "Set to true for servo gimbal, false for passthrough.\nThis is required for a gimbal which is not capable of stabilizing itself\nand relies on the IMU's attitude estimation.", "name": "MNT_DO_STAB", "shortDesc": "Stabilize the mount", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "Stabilize all axis", "value": 1}, {"description": "Stabilize yaw for absolute/lock mode.", "value": 2}, {"description": "Stabilize pitch for absolute/lock mode.", "value": 3}]}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "max": 90.0, "min": -90.0, "name": "MNT_LND_P_MAX", "shortDesc": "Pitch maximum when landed", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -90.0, "group": "Mount", "max": 90.0, "min": -90.0, "name": "MNT_LND_P_MIN", "shortDesc": "Pitch minimum when landed", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_PITCH", "shortDesc": "Auxiliary channel to control pitch (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_ROLL", "shortDesc": "Auxiliary channel to control roll (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Mount", "max": 6, "min": 0, "name": "MNT_MAN_YAW", "shortDesc": "Auxiliary channel to control yaw (in AUX input or manual mode)", "type": "Int32", "values": [{"description": "Disable", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 154, "group": "Mount", "longDesc": "If MNT_MODE_OUT is MAVLink protocol v2, mount configure/control commands will be sent with this component ID.", "name": "MNT_MAV_COMPID", "shortDesc": "Mavlink Component ID of the mount", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Mount", "longDesc": "If MNT_MODE_OUT is MAVLink gimbal protocol v1, mount configure/control commands will be sent with this target ID.", "name": "MNT_MAV_SYSID", "shortDesc": "Mavlink System ID of the mount", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 45.0, "group": "Mount", "longDesc": "Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX).", "name": "MNT_MAX_PITCH", "shortDesc": "Max positive angle of pitch setpoint (only in MNT_MODE_OUT=AUX)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": -45.0, "group": "Mount", "longDesc": "Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX).", "name": "MNT_MIN_PITCH", "shortDesc": "Min negative angle of pitch setpoint (only in MNT_MODE_OUT=AUX)", "type": "Float", "units": "deg"}, {"category": "Standard", "default": -1, "group": "Mount", "longDesc": "This is the protocol used between the ground station and the autopilot.\nRecommended is Auto, RC only or MAVLink gimbal protocol v2.\nThe rest will be deprecated.", "max": 4, "min": -1, "name": "MNT_MODE_IN", "rebootRequired": true, "shortDesc": "Mount input mode", "type": "Int32", "values": [{"description": "DISABLED", "value": -1}, {"description": "Auto (RC and MAVLink gimbal protocol v2)", "value": 0}, {"description": "RC", "value": 1}, {"description": "MAVLINK_ROI (protocol v1, to be deprecated)", "value": 2}, {"description": "MAVLINK_DO_MOUNT (protocol v1, to be deprecated)", "value": 3}, {"description": "MAVlink gimbal protocol v2", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Mount", "longDesc": "This is the protocol used between the autopilot and a connected gimbal.\nRecommended is the MAVLink gimbal protocol v2 if the gimbal supports it.", "max": 2, "min": 0, "name": "MNT_MODE_OUT", "rebootRequired": true, "shortDesc": "Mount output mode", "type": "Int32", "values": [{"description": "AUX", "value": 0}, {"description": "MAVLink gimbal protocol v1", "value": 1}, {"description": "MAVLink gimbal protocol v2", "value": 2}]}, {"category": "Standard", "decimalPlaces": 1, "default": 90.0, "group": "Mount", "longDesc": "Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX). Note that only symmetric angular ranges are supported.", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_ROLL", "shortDesc": "Range of roll channel output (only in MNT_MODE_OUT=AUX)", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 360.0, "group": "Mount", "longDesc": "Use output driver settings to calibrate (e.g. PWM_CENT/_MIN/_MAX). Note that only symmetric angular ranges are supported.", "max": 720.0, "min": 1.0, "name": "MNT_RANGE_YAW", "shortDesc": "Range of yaw channel output (only in MNT_MODE_OUT=AUX)", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 30.0, "group": "Mount", "longDesc": "Full stick input [-1..1] translats to [-pitch rate..pitch rate].", "max": 90.0, "min": 1.0, "name": "MNT_RATE_PITCH", "shortDesc": "Angular pitch rate for manual input in degrees/second", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 30.0, "group": "Mount", "longDesc": "Full stick input [-1..1] translats to [-yaw rate..yaw rate].", "max": 90.0, "min": 1.0, "name": "MNT_RATE_YAW", "shortDesc": "Angular yaw rate for manual input in degrees/second", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 1, "group": "Mount", "max": 1, "min": 0, "name": "MNT_RC_IN_MODE", "shortDesc": "Input mode for RC gimbal input", "type": "Int32", "values": [{"description": "Angle", "value": 0}, {"description": "Angular rate", "value": 1}]}, {"category": "Standard", "default": 0.3, "group": "Mount", "longDesc": "Use when no angular position feedback is available.\nWith MNT_MODE_OUT set to AUX, the mount operates in open-loop and directly commands the servo output.\nParameters must be tuned for the specific servo to approximate its speed and response.", "min": 0.0, "name": "MNT_TAU", "shortDesc": "Alpha filter time constant defining the convergence rate (in seconds) for open-loop AUX mount control", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "Exponential factor for tuning the input curve shape.\n0 Purely linear input curve\n1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MC_ACRO_EXPO", "shortDesc": "Acro mode roll, pitch expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "Exponential factor for tuning the input curve shape.\n0 Purely linear input curve\n1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "MC_ACRO_EXPO_Y", "shortDesc": "Acro mode yaw expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_P_MAX", "shortDesc": "Acro mode maximum pitch rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_R_MAX", "shortDesc": "Acro mode maximum roll rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using MC_ACRO_EXPO.\n0 Pure Expo function\n0.7 reasonable shape enhancement for intuitive stick feel\n0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "MC_ACRO_SUPEXPO", "shortDesc": "Acro mode roll, pitch super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Acro Mode", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y.\n0 Pure Expo function\n0.7 reasonable shape enhancement for intuitive stick feel\n0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "MC_ACRO_SUPEXPOY", "shortDesc": "Acro mode yaw super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 100.0, "group": "Multicopter Acro Mode", "increment": 5.0, "longDesc": "Full stick deflection leads to this rate.", "max": 1800.0, "min": 0.0, "name": "MC_ACRO_Y_MAX", "shortDesc": "Acro mode maximum yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 220.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limit for pitch rate in manual and auto modes (except acro).\nHas effect for large rotations in autonomous mode, to avoid large control\noutput and mixer saturation.\nThis is not only limited by the vehicle's properties, but also by the maximum\nmeasurement rate of the gyro.", "max": 1800.0, "min": 0.0, "name": "MC_PITCHRATE_MAX", "shortDesc": "Max pitch rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 12.0, "min": 0.0, "name": "MC_PITCH_P", "shortDesc": "Pitch P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 220.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limit for roll rate in manual and auto modes (except acro).\nHas effect for large rotations in autonomous mode, to avoid large control\noutput and mixer saturation.\nThis is not only limited by the vehicle's properties, but also by the maximum\nmeasurement rate of the gyro.", "max": 1800.0, "min": 0.0, "name": "MC_ROLLRATE_MAX", "shortDesc": "Max roll rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 12.0, "min": 0.0, "name": "MC_ROLL_P", "shortDesc": "Roll P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 200.0, "group": "Multicopter Attitude Control", "increment": 5.0, "max": 1800.0, "min": 0.0, "name": "MC_YAWRATE_MAX", "shortDesc": "Max yaw rate", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.8, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad.", "max": 5.0, "min": 0.0, "name": "MC_YAW_P", "shortDesc": "Yaw P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "Multicopter Attitude Control", "increment": 0.1, "longDesc": "A fraction [0,1] deprioritizing yaw compared to roll and pitch in non-linear attitude control.\nDeprioritizing yaw is necessary because multicopters have much less control authority\nin yaw compared to the other axes and it makes sense because yaw is not critical for\nstable hovering or 3D navigation.\nFor yaw control tuning use MC_YAW_P. This ratio has no impact on the yaw gain.", "max": 1.0, "min": 0.0, "name": "MC_YAW_WEIGHT", "shortDesc": "Yaw weight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 0, "default": 20.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limits the acceleration of the yaw setpoint to avoid large\ncontrol output and mixer saturation.", "max": 360.0, "min": 5.0, "name": "MPC_YAWRAUTO_ACC", "shortDesc": "Maximum yaw acceleration in autonomous modes", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 0, "default": 60.0, "group": "Multicopter Attitude Control", "increment": 5.0, "longDesc": "Limits the rate of change of the yaw setpoint to avoid large\ncontrol output and mixer saturation.", "max": 360.0, "min": 5.0, "name": "MPC_YAWRAUTO_MAX", "shortDesc": "Maximum yaw rate in autonomous modes", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0.4, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "max": 1.0, "min": 0.0, "name": "CP_DELAY", "shortDesc": "Average delay of the range sensor message plus the tracking delay of the position controller in seconds", "type": "Float", "units": "s"}, {"category": "Standard", "default": -1.0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode. Collision avoidance is disabled by setting this parameter to a negative value", "max": 15.0, "min": -1.0, "name": "CP_DIST", "shortDesc": "Minimum distance the vehicle should keep to all obstacles", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "name": "CP_GO_NO_DATA", "shortDesc": "Boolean to allow moving into directions where there is no sensor data (outside FOV)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 30.0, "group": "Multicopter Position Control", "longDesc": "Only used in Position mode.", "max": 90.0, "min": 0.0, "name": "CP_GUIDE_ANG", "shortDesc": "Angle left/right from the commanded setpoint by which the collision prevention algorithm can choose to change the setpoint direction", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Position Control", "longDesc": "Setting this parameter to 0 disables the filter", "max": 2.0, "min": 0.0, "name": "MC_MAN_TILT_TAU", "shortDesc": "Manual tilt input filter time constant", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "Multicopter Position Control", "longDesc": "Set to decouple tilt from vertical acceleration.\nThis provides smoother flight but slightly worse tracking in position and auto modes.\nUnset if accurate position tracking during dynamic maneuvers is more important than a smooth flight.", "name": "MPC_ACC_DECOUPLE", "shortDesc": "Acceleration to tilt coupling", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 15.0, "min": 2.0, "name": "MPC_ACC_DOWN_MAX", "shortDesc": "Maximum downwards acceleration in climb rate controlled modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "When piloting manually, this parameter is only used in MPC_POS_MODE Acceleration based.", "max": 15.0, "min": 2.0, "name": "MPC_ACC_HOR", "shortDesc": "Acceleration for autonomous and for manual modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "MPC_POS_MODE\n1 just deceleration\n4 not used, use MPC_ACC_HOR instead", "max": 15.0, "min": 2.0, "name": "MPC_ACC_HOR_MAX", "shortDesc": "Maximum horizontal acceleration", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 15.0, "min": 2.0, "name": "MPC_ACC_UP_MAX", "shortDesc": "Maximum upwards acceleration in climb rate controlled modes", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "default": 2, "group": "Multicopter Position Control", "longDesc": "Control height\n0: relative earth frame origin which may drift due to sensors\n1: relative to ground (requires distance sensor) which changes with terrain variation.\nIt will revert to relative earth frame if the distance to ground estimate becomes invalid.\n2: relative to ground (requires distance sensor) when stationary\nand relative to earth frame when moving horizontally.\nThe speed threshold is MPC_HOLD_MAX_XY", "max": 2, "min": 0, "name": "MPC_ALT_MODE", "shortDesc": "Altitude reference mode", "type": "Int32", "values": [{"description": "Altitude following", "value": 0}, {"description": "Terrain following", "value": 1}, {"description": "Terrain hold", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.8, "group": "Multicopter Position Control", "longDesc": "Only used with MPC_POS_MODE Direct velocity or MPC_ALT_MODE 2", "max": 3.0, "min": 0.0, "name": "MPC_HOLD_MAX_XY", "shortDesc": "Maximum horizontal velocity for which position hold is enabled (use 0 to disable check)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.6, "group": "Multicopter Position Control", "longDesc": "Only used with MPC_ALT_MODE 1", "max": 3.0, "min": 0.0, "name": "MPC_HOLD_MAX_Z", "shortDesc": "Maximum vertical velocity for which position hold is enabled (use 0 to disable check)", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 4.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Limit the maximum jerk of the vehicle (how fast the acceleration can change).\nA lower value leads to smoother vehicle motions but also limited agility.", "max": 80.0, "min": 1.0, "name": "MPC_JERK_AUTO", "shortDesc": "Jerk limit in autonomous modes", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 0, "default": 8.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Limit the maximum jerk (acceleration change) of the vehicle.\nA lower value leads to smoother motions but limits agility.\nSetting this to the maximum value essentially disables the limit.\nOnly used with MPC_POS_MODE Acceleration based.", "max": 500.0, "min": 0.5, "name": "MPC_JERK_MAX", "shortDesc": "Maximum horizontal and vertical jerk in Position/Altitude mode", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Multicopter Position Control", "longDesc": "Below this altitude descending velocity gets limited to a value\nbetween \"MPC_Z_VEL_MAX_DN\" (or \"MPC_Z_V_AUTO_DN\") and \"MPC_LAND_SPEED\"\nValue needs to be higher than \"MPC_LAND_ALT2\"", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT1", "shortDesc": "Altitude for 1. step of slow landing (descend)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "longDesc": "Below this altitude descending velocity gets\nlimited to \"MPC_LAND_SPEED\"\nValue needs to be lower than \"MPC_LAND_ALT1\"", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT2", "shortDesc": "Altitude for 2. step of slow landing (landing)", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Multicopter Position Control", "longDesc": "If a valid distance sensor measurement to the ground is available,\nlimit descending velocity to \"MPC_LAND_CRWL\" below this altitude.", "max": 122.0, "min": 0.0, "name": "MPC_LAND_ALT3", "shortDesc": "Altitude for 3. step of slow landing", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.3, "group": "Multicopter Position Control", "longDesc": "Used below MPC_LAND_ALT3 if distance sensor data is availabe.", "min": 0.1, "name": "MPC_LAND_CRWL", "shortDesc": "Land crawl descend rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "When nudging is enabled (see MPC_LAND_RC_HELP), this defines the maximum\nallowed horizontal displacement from the original landing point.\n- If inside of the radius, only allow nudging inputs that do not move the vehicle outside of it.\n- If outside of the radius, only allow nudging inputs that move the vehicle back towards it.\nSet it to -1 for infinite radius.", "min": -1.0, "name": "MPC_LAND_RADIUS", "shortDesc": "User assisted landing radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Using stick input the vehicle can be moved horizontally and yawed.\nThe descend speed is amended:\nstick full up - 0\nstick centered - MPC_LAND_SPEED\nstick full down - 2 * MPC_LAND_SPEED\nManual override during auto modes has to be disabled to use this feature (see COM_RC_OVERRIDE).", "max": 1, "min": 0, "name": "MPC_LAND_RC_HELP", "shortDesc": "Enable nudging based on user input during autonomous land routine", "type": "Int32", "values": [{"description": "Nudging disabled", "value": 0}, {"description": "Nudging enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.7, "group": "Multicopter Position Control", "min": 0.6, "name": "MPC_LAND_SPEED", "shortDesc": "Landing descend rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "The value is mapped to the lowest throttle stick position in Stabilized mode.\nToo low collective thrust leads to loss of roll/pitch/yaw torque control authority.\nAirmode is used to keep torque authority with zero thrust (see MC_AIRMODE).", "max": 1.0, "min": 0.0, "name": "MPC_MANTHR_MIN", "shortDesc": "Minimum collective thrust in Stabilized mode", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 0, "default": 35.0, "group": "Multicopter Position Control", "increment": 1.0, "max": 70.0, "min": 1.0, "name": "MPC_MAN_TILT_MAX", "shortDesc": "Maximal tilt angle in Stabilized, Altitude and Altitude Cruise mode", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 150.0, "group": "Multicopter Position Control", "increment": 10.0, "max": 400.0, "min": 0.0, "name": "MPC_MAN_Y_MAX", "shortDesc": "Max manual yaw rate for Stabilized, Altitude, Position mode", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Not used in Stabilized mode\nSetting this parameter to 0 disables the filter", "max": 5.0, "min": 0.0, "name": "MPC_MAN_Y_TAU", "shortDesc": "Manual yaw rate input filter time constant", "type": "Float", "units": "s"}, {"category": "Standard", "default": 4, "group": "Multicopter Position Control", "longDesc": "The supported sub-modes are:\nDirect velocity:\nSticks directly map to velocity setpoints without smoothing.\nAlso applies to vertical direction and Altitude mode.\nUseful for velocity control tuning.\nAcceleration based:\nSticks map to acceleration and there's a virtual brake drag", "name": "MPC_POS_MODE", "shortDesc": "Position/Altitude mode variant", "type": "Int32", "values": [{"description": "Direct velocity", "value": 0}, {"description": "Acceleration based", "value": 4}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "longDesc": "Defines how the throttle stick is mapped to collective thrust in Stabilized mode.\nRescale to hover thrust estimate:\nStick input is linearly rescaled, such that a centered throttle stick corresponds to the hover thrust estimator's output.\nNo rescale:\nDirectly map the stick 1:1 to the output.\nCan be useful with very low hover thrust which leads to much distortion and the upper half getting sensitive.\nRescale to hover thrust parameter:\nSimilar to rescaling to the hover thrust estimate, but it uses the hover thrust parameter value (see MPC_THR_HOVER) instead of estimated value.\nWith MPC_THR_HOVER 0.5 it's equivalent to No rescale.", "name": "MPC_THR_CURVE", "shortDesc": "Thrust curve mapping in Stabilized Mode", "type": "Int32", "values": [{"description": "Rescale to estimate", "value": 0}, {"description": "No rescale", "value": 1}, {"description": "Rescale to parameter", "value": 2}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Mapped to center throttle stick in Stabilized mode (see MPC_THR_CURVE).\nUsed for initialization of the hover thrust estimator (see MPC_USE_HTE).\nThe estimated hover thrust is used as base for zero vertical acceleration in altitude control.\nThe hover thrust is important for land detection to work correctly.", "max": 0.8, "min": 0.1, "name": "MPC_THR_HOVER", "shortDesc": "Vertical thrust required to hover", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Control", "increment": 0.05, "longDesc": "Limit allowed thrust e.g. for indoor test of overpowered vehicle.", "max": 1.0, "min": 0.0, "name": "MPC_THR_MAX", "shortDesc": "Maximum collective thrust in climb rate controlled modes", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.12, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Too low thrust leads to loss of roll/pitch/yaw torque control authority.\nWith airmode enabled this parameters can be set to 0\nwhile still keeping torque authority (see MC_AIRMODE).", "max": 0.5, "min": 0.05, "name": "MPC_THR_MIN", "shortDesc": "Minimum collective thrust in climb rate controlled modes", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Control", "increment": 0.01, "longDesc": "Margin that is kept for horizontal control when higher priority vertical thrust is saturated.\nTo avoid completely starving horizontal control with high vertical error.", "max": 0.5, "min": 0.0, "name": "MPC_THR_XY_MARG", "shortDesc": "Horizontal thrust margin", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Absolute maximum for all velocity or acceleration controlled modes.\nAny higher value is truncated.", "max": 89.0, "min": 20.0, "name": "MPC_TILTMAX_AIR", "shortDesc": "Maximum tilt angle in air", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 0, "default": 12.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Tighter tilt limit during takeoff to avoid tip over.", "max": 89.0, "min": 5.0, "name": "MPC_TILTMAX_LND", "shortDesc": "Maximum tilt during inital takeoff ramp", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 3.0, "group": "Multicopter Position Control", "longDesc": "Increasing this value will make climb rate controlled takeoff slower.\nIf it's too slow the drone might scratch the ground and tip over.\nA time constant of 0 disables the ramp", "max": 5.0, "min": 0.0, "name": "MPC_TKO_RAMP_T", "shortDesc": "Smooth takeoff ramp time constant", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.5, "group": "Multicopter Position Control", "max": 5.0, "min": 1.0, "name": "MPC_TKO_SPEED", "shortDesc": "Takeoff climb rate", "type": "Float", "units": "m/s"}, {"category": "Standard", "default": 1, "group": "Multicopter Position Control", "longDesc": "Disable to use the fixed parameter MPC_THR_HOVER instead of the hover thrust estimate in the position controller.\nThis parameter does not influence Stabilized mode throttle curve (see MPC_THR_CURVE).", "name": "MPC_USE_HTE", "shortDesc": "Use hover thrust estimate for altitude control", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VELD_LP", "shortDesc": "Velocity derivative low pass cutoff frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_LP", "shortDesc": "Velocity low pass cutoff frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Must be smaller than MPC_XY_VEL_MAX.\nThe maximum sideways and backward speed can be set differently\nusing MPC_VEL_MAN_SIDE and MPC_VEL_MAN_BACK, respectively.", "max": 20.0, "min": 3.0, "name": "MPC_VEL_MANUAL", "shortDesc": "Maximum horizontal velocity setpoint in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a negative value or larger than\nMPC_VEL_MANUAL then MPC_VEL_MANUAL is used.", "max": 20.0, "min": -1.0, "name": "MPC_VEL_MAN_BACK", "shortDesc": "Maximum backward velocity in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a negative value or larger than\nMPC_VEL_MANUAL then MPC_VEL_MANUAL is used.", "max": 20.0, "min": -1.0, "name": "MPC_VEL_MAN_SIDE", "shortDesc": "Maximum sideways velocity in Position mode", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "A value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_NF_BW", "shortDesc": "Velocity notch filter bandwidth", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "The center frequency for the 2nd order notch filter on the velocity.\nA value of 0 disables the filter.", "max": 50.0, "min": 0.0, "name": "MPC_VEL_NF_FRQ", "shortDesc": "Velocity notch filter frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 0, "default": 5.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "e.g. in Missions, RTL, Goto if the waypoint does not specify differently", "max": 20.0, "min": 3.0, "name": "MPC_XY_CRUISE", "shortDesc": "Default horizontal velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "The integration speed of the trajectory setpoint is linearly\nreduced with the horizontal position tracking error. When the\nerror is above this parameter, the integration of the\ntrajectory is stopped to wait for the drone.\nThis value can be adjusted depending on the tracking\ncapabilities of the vehicle.", "max": 10.0, "min": 0.1, "name": "MPC_XY_ERR_MAX", "shortDesc": "Maximum horizontal error allowed by the trajectory generator", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.95, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective velocity in m/s per m position error", "max": 2.0, "min": 0.0, "name": "MPC_XY_P", "shortDesc": "Proportional gain for horizontal position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.5, "group": "Multicopter Position Control", "increment": 0.1, "max": 1.0, "min": 0.1, "name": "MPC_XY_TRAJ_P", "shortDesc": "Proportional gain for horizontal trajectory position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -10.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "If set to a value greater than zero, other parameters are automatically set (such as\nMPC_XY_VEL_MAX or MPC_VEL_MANUAL).\nIf set to a negative value, the existing individual parameters are used.", "max": 20.0, "min": -20.0, "name": "MPC_XY_VEL_ALL", "shortDesc": "Overall Horizontal Velocity Limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative", "max": 2.0, "min": 0.1, "name": "MPC_XY_VEL_D_ACC", "shortDesc": "Differential gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.4, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as correction acceleration in m/s^2 per m velocity integral\nAllows to eliminate steady state errors in disturbances like wind.", "max": 60.0, "min": 0.0, "name": "MPC_XY_VEL_I_ACC", "shortDesc": "Integral gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 12.0, "group": "Multicopter Position Control", "increment": 1.0, "longDesc": "Absolute maximum for all velocity controlled modes.\nAny higher value is truncated.", "max": 20.0, "min": 0.0, "name": "MPC_XY_VEL_MAX", "shortDesc": "Maximum horizontal velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.8, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s velocity error", "max": 5.0, "min": 1.2, "name": "MPC_XY_VEL_P_ACC", "shortDesc": "Proportional gain for horizontal velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective velocity in m/s per m position error", "max": 1.5, "min": 0.1, "name": "MPC_Z_P", "shortDesc": "Proportional gain for vertical position error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": -3.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "If set to a value greater than zero, other parameters are automatically set (such as\nMPC_Z_VEL_MAX_UP or MPC_LAND_SPEED).\nIf set to a negative value, the existing individual parameters are used.", "max": 8.0, "min": -3.0, "name": "MPC_Z_VEL_ALL", "shortDesc": "Overall Vertical Velocity Limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Multicopter Position Control", "increment": 0.02, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative", "max": 2.0, "min": 0.0, "name": "MPC_Z_VEL_D_ACC", "shortDesc": "Differential gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m velocity integral", "max": 3.0, "min": 0.2, "name": "MPC_Z_VEL_I_ACC", "shortDesc": "Integral gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Absolute maximum for all climb rate controlled modes.\nIn manually piloted modes full stick deflection commands this velocity.\nFor default autonomous velocity see MPC_Z_V_AUTO_UP", "max": 4.0, "min": 0.5, "name": "MPC_Z_VEL_MAX_DN", "shortDesc": "Maximum descent velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Absolute maximum for all climb rate controlled modes.\nIn manually piloted modes full stick deflection commands this velocity.\nFor default autonomous velocity see MPC_Z_V_AUTO_UP", "max": 8.0, "min": 0.5, "name": "MPC_Z_VEL_MAX_UP", "shortDesc": "Maximum ascent velocity", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "Multicopter Position Control", "increment": 0.1, "longDesc": "Defined as corrective acceleration in m/s^2 per m/s velocity error", "max": 15.0, "min": 2.0, "name": "MPC_Z_VEL_P_ACC", "shortDesc": "Proportional gain for vertical velocity error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.5, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "For manual modes and offboard, see MPC_Z_VEL_MAX_DN", "max": 4.0, "min": 0.5, "name": "MPC_Z_V_AUTO_DN", "shortDesc": "Descent velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "Multicopter Position Control", "increment": 0.5, "longDesc": "For manually controlled modes and offboard see MPC_Z_VEL_MAX_UP", "max": 8.0, "min": 0.5, "name": "MPC_Z_V_AUTO_UP", "shortDesc": "Ascent velocity in autonomous modes", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": -0.4, "group": "Multicopter Position Control", "increment": 0.05, "longDesc": "Changes the overall responsiveness of the vehicle.\nThe higher the value, the faster the vehicle will react.\nIf set to a value greater than zero, other parameters are automatically set (such as\nthe acceleration or jerk limits).\nIf set to a negative value, the existing individual parameters are used.", "max": 1.0, "min": -1.0, "name": "SYS_VEHICLE_RESP", "shortDesc": "Responsiveness", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Control", "name": "WV_EN", "shortDesc": "Enable weathervane", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1.0, "group": "Multicopter Position Control", "max": 5.0, "min": 0.0, "name": "WV_ROLL_MIN", "shortDesc": "Minimum roll angle setpoint for weathervane controller to demand a yaw-rate", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 90.0, "group": "Multicopter Position Control", "max": 120.0, "min": 0.0, "name": "WV_YRATE_MAX", "shortDesc": "Maximum yawrate the weathervane controller is allowed to demand", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if\nno aux channel is mapped and\nno limit is commanded through MAVLink.", "min": 0.1, "name": "MC_SLOW_DEF_HVEL", "shortDesc": "Default horizontal velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if\nno aux channel is mapped and\nno limit is commanded through MAVLink.", "min": 0.1, "name": "MC_SLOW_DEF_VVEL", "shortDesc": "Default vertical velocity limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 45.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "This value is used in slow mode if\nno aux channel is mapped and\nno limit is commanded through MAVLink.", "min": 1.0, "name": "MC_SLOW_DEF_YAWR", "shortDesc": "Default yaw rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_HVEL", "shortDesc": "Manual input mapped to scale horizontal velocity in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_PTCH", "shortDesc": "RC_MAP_AUX{N} to allow for gimbal pitch rate control in position slow mode", "type": "Int32", "values": [{"description": "No pitch rate input", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_VVEL", "shortDesc": "Manual input mapped to scale vertical velocity in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "default": 0, "group": "Multicopter Position Slow Mode", "name": "MC_SLOW_MAP_YAWR", "shortDesc": "Manual input mapped to scale yaw rate in position slow mode", "type": "Int32", "values": [{"description": "No rescaling", "value": 0}, {"description": "AUX1", "value": 1}, {"description": "AUX2", "value": 2}, {"description": "AUX3", "value": 3}, {"description": "AUX4", "value": 4}, {"description": "AUX5", "value": 5}, {"description": "AUX6", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this velocity.", "min": 0.1, "name": "MC_SLOW_MIN_HVEL", "shortDesc": "Horizontal velocity lower limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this velocity.", "min": 0.1, "name": "MC_SLOW_MIN_VVEL", "shortDesc": "Vertical velocity lower limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 0, "default": 3.0, "group": "Multicopter Position Slow Mode", "increment": 0.1, "longDesc": "The lowest input maps and is clamped to this rate.", "min": 1.0, "name": "MC_SLOW_MIN_YAWR", "shortDesc": "Yaw rate lower limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "default": 0, "group": "Multicopter Rate Control", "longDesc": "This compensates for voltage drop of the battery over time by attempting to\nnormalize performance across the operating range of the battery. The copter\nshould constantly behave as if it was fully charged with reduced max acceleration\nat lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery,\nit will still be 0.5 at 60% battery.", "name": "MC_BAT_SCALE_EN", "shortDesc": "Battery power level scaler", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 4, "default": 0.003, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "min": 0.0, "name": "MC_PITCHRATE_D", "shortDesc": "Pitch rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_PITCHRATE_FF", "shortDesc": "Pitch rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_PITCHRATE_I", "shortDesc": "Pitch rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller.\nThis gain scales the P, I and D terms of the controller:\noutput = MC_PITCHRATE_K * (MC_PITCHRATE_P * error\n+ MC_PITCHRATE_I * error_integral\n+ MC_PITCHRATE_D * error_derivative)\nSet MC_PITCHRATE_P=1 to implement a PID in the ideal form.\nSet MC_PITCHRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_PITCHRATE_K", "shortDesc": "Pitch rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.6, "min": 0.01, "name": "MC_PITCHRATE_P", "shortDesc": "Pitch rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Pitch rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes.", "min": 0.0, "name": "MC_PR_INT_LIM", "shortDesc": "Pitch rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.003, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "max": 0.01, "min": 0.0, "name": "MC_ROLLRATE_D", "shortDesc": "Roll rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_ROLLRATE_FF", "shortDesc": "Roll rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_ROLLRATE_I", "shortDesc": "Roll rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller.\nThis gain scales the P, I and D terms of the controller:\noutput = MC_ROLLRATE_K * (MC_ROLLRATE_P * error\n+ MC_ROLLRATE_I * error_integral\n+ MC_ROLLRATE_D * error_derivative)\nSet MC_ROLLRATE_P=1 to implement a PID in the ideal form.\nSet MC_ROLLRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_ROLLRATE_K", "shortDesc": "Roll rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.15, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.5, "min": 0.01, "name": "MC_ROLLRATE_P", "shortDesc": "Roll rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Roll rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes.", "min": 0.0, "name": "MC_RR_INT_LIM", "shortDesc": "Roll rate integrator limit", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "min": 0.0, "name": "MC_YAWRATE_D", "shortDesc": "Yaw rate D gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Multicopter Rate Control", "longDesc": "Improves tracking performance.", "min": 0.0, "name": "MC_YAWRATE_FF", "shortDesc": "Yaw rate feedforward", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "min": 0.0, "name": "MC_YAWRATE_I", "shortDesc": "Yaw rate I gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 4, "default": 1.0, "group": "Multicopter Rate Control", "increment": 0.0005, "longDesc": "Global gain of the controller.\nThis gain scales the P, I and D terms of the controller:\noutput = MC_YAWRATE_K * (MC_YAWRATE_P * error\n+ MC_YAWRATE_I * error_integral\n+ MC_YAWRATE_D * error_derivative)\nSet MC_YAWRATE_P=1 to implement a PID in the ideal form.\nSet MC_YAWRATE_K=1 to implement a PID in the parallel form.", "max": 5.0, "min": 0.01, "name": "MC_YAWRATE_K", "shortDesc": "Yaw rate controller gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.2, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "max": 0.6, "min": 0.0, "name": "MC_YAWRATE_P", "shortDesc": "Yaw rate P gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 2.0, "group": "Multicopter Rate Control", "longDesc": "Reduces vibrations by lowering high frequency torque caused by rotor acceleration.\n0 disables the filter", "max": 10.0, "min": 0.0, "name": "MC_YAW_TQ_CUTOFF", "shortDesc": "Low pass filter cutoff frequency for yaw torque setpoint", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "Multicopter Rate Control", "increment": 0.01, "longDesc": "Yaw rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes.", "min": 0.0, "name": "MC_YR_INT_LIM", "shortDesc": "Yaw rate integrator limit", "type": "Float"}, {"category": "Standard", "default": 0, "group": "OSD", "longDesc": "Controls the vertical position of the crosshair display.\nResolution is limited by OSD to 15 discrete values. Negative\nvalues will display the crosshairs below the horizon", "max": 8, "min": -8, "name": "OSD_CH_HEIGHT", "shortDesc": "OSD Crosshairs Height", "type": "Int32"}, {"category": "Standard", "default": 500, "group": "OSD", "longDesc": "Amount of time in milliseconds to dwell at the beginning of the display, when scrolling.", "max": 10000, "min": 100, "name": "OSD_DWELL_TIME", "shortDesc": "OSD Dwell Time (ms)", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "OSD", "longDesc": "Minimum security of log level to display on the OSD.", "name": "OSD_LOG_LEVEL", "shortDesc": "OSD Warning Level", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "OSD", "longDesc": "Forward RC stick input to VTX when disarmed", "max": 1, "min": 0, "name": "OSD_RC_STICK", "shortDesc": "OSD RC Stick commands", "type": "Int32"}, {"category": "Standard", "default": 125, "group": "OSD", "longDesc": "Scroll rate in milliseconds for OSD messages longer than available character width.\nThis is lower-bounded by the nominal loop rate of this module.", "max": 1000, "min": 100, "name": "OSD_SCROLL_RATE", "shortDesc": "OSD Scroll Rate (ms)", "type": "Int32"}, {"bitmask": [{"description": "CRAFT_NAME", "index": 0}, {"description": "DISARMED", "index": 1}, {"description": "GPS_LAT", "index": 2}, {"description": "GPS_LON", "index": 3}, {"description": "GPS_SATS", "index": 4}, {"description": "GPS_SPEED", "index": 5}, {"description": "HOME_DIST", "index": 6}, {"description": "HOME_DIR", "index": 7}, {"description": "MAIN_BATT_VOLTAGE", "index": 8}, {"description": "CURRENT_DRAW", "index": 9}, {"description": "MAH_DRAWN", "index": 10}, {"description": "RSSI_VALUE", "index": 11}, {"description": "ALTITUDE", "index": 12}, {"description": "NUMERICAL_VARIO", "index": 13}, {"description": "(unused) FLYMODE", "index": 14}, {"description": "(unused) ESC_TMP", "index": 15}, {"description": "(unused) PITCH_ANGLE", "index": 16}, {"description": "(unused) ROLL_ANGLE", "index": 17}, {"description": "CROSSHAIRS", "index": 18}, {"description": "AVG_CELL_VOLTAGE", "index": 19}, {"description": "(unused) HORIZON_SIDEBARS", "index": 20}, {"description": "POWER", "index": 21}], "category": "Standard", "default": 16383, "group": "OSD", "longDesc": "Configure / toggle support display options.", "max": 4194303, "min": 0, "name": "OSD_SYMBOLS", "shortDesc": "OSD Symbol Selection", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "PWM Outputs", "increment": 0.1, "longDesc": "Parameter used to model the nonlinear relationship between\nmotor control signal (e.g. PWM) and static thrust.\nThe model is: rel_thrust = factor * rel_signal^2 + (1-factor) * rel_signal,\nwhere rel_thrust is the normalized thrust between 0 and 1, and\nrel_signal is the relative motor control signal between 0 and 1.", "max": 1.0, "min": 0.0, "name": "THR_MDL_FAC", "shortDesc": "Thrust to motor control signal model parameter", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Payload Deliverer", "longDesc": "Maximum time Gripper will wait while the successful griper actuation isn't recognised.\nIf the gripper has no feedback sensor, it will simply wait for\nthis time before considering gripper actuation successful and publish a\n'VehicleCommandAck' signaling successful gripper action", "min": 0.0, "name": "PD_GRIPPER_TO", "shortDesc": "Timeout for successful gripper actuation acknowledgement", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Payload Deliverer", "max": 0, "min": -1, "name": "PD_GRIPPER_TYPE", "shortDesc": "Type of Gripper (Servo, etc.)", "type": "Int32", "values": [{"description": "Undefined", "value": -1}, {"description": "Servo", "value": 0}]}, {"category": "Standard", "decimalPlaces": 1, "default": 5.0, "group": "Precision Land", "increment": 0.5, "longDesc": "Time after which the landing target is considered lost without any new measurements.", "max": 50.0, "min": 0.0, "name": "PLD_BTOUT", "shortDesc": "Landing Target Timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Precision Land", "increment": 0.1, "longDesc": "Allow final approach (without horizontal positioning) if losing landing target closer than this to the ground.", "max": 10.0, "min": 0.0, "name": "PLD_FAPPR_ALT", "shortDesc": "Final approach altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Precision Land", "increment": 0.1, "longDesc": "Start descending if closer above landing target than this.", "max": 10.0, "min": 0.0, "name": "PLD_HACC_RAD", "shortDesc": "Horizontal acceptance radius", "type": "Float", "units": "m"}, {"category": "Standard", "default": 3, "group": "Precision Land", "longDesc": "Maximum number of times to search for the landing target if it is lost during the precision landing.", "max": 100, "min": 0, "name": "PLD_MAX_SRCH", "shortDesc": "Maximum number of search attempts", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Precision Land", "increment": 0.1, "longDesc": "Altitude above home to which to climb when searching for the landing target.", "max": 100.0, "min": 0.0, "name": "PLD_SRCH_ALT", "shortDesc": "Search altitude", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Precision Land", "increment": 0.1, "longDesc": "Time allowed to search for the landing target before falling back to normal landing.", "max": 100.0, "min": 0.0, "name": "PLD_SRCH_TOUT", "shortDesc": "Search timeout", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Pure Pursuit", "increment": 0.01, "longDesc": "Lower value -> More aggressive controller (beware overshoot/oscillations)", "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_GAIN", "shortDesc": "Tuning parameter for the pure pursuit controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "Pure Pursuit", "increment": 0.01, "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_MAX", "shortDesc": "Maximum lookahead distance for the pure pursuit controller", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Pure Pursuit", "increment": 0.01, "max": 100.0, "min": 0.1, "name": "PP_LOOKAHD_MIN", "shortDesc": "Minimum lookahead distance for the pure pursuit controller", "type": "Float", "units": "m"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC10_MAX", "shortDesc": "RC channel 10 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC10_MIN", "shortDesc": "RC channel 10 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC10_REV", "shortDesc": "RC channel 10 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC10_TRIM", "shortDesc": "RC channel 10 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC11_MAX", "shortDesc": "RC channel 11 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC11_MIN", "shortDesc": "RC channel 11 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC11_REV", "shortDesc": "RC channel 11 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC11_TRIM", "shortDesc": "RC channel 11 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC12_MAX", "shortDesc": "RC channel 12 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC12_MIN", "shortDesc": "RC channel 12 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC12_REV", "shortDesc": "RC channel 12 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC12_TRIM", "shortDesc": "RC channel 12 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC13_MAX", "shortDesc": "RC channel 13 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC13_MIN", "shortDesc": "RC channel 13 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC13_REV", "shortDesc": "RC channel 13 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC13_TRIM", "shortDesc": "RC channel 13 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC14_MAX", "shortDesc": "RC channel 14 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC14_MIN", "shortDesc": "RC channel 14 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC14_REV", "shortDesc": "RC channel 14 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC14_TRIM", "shortDesc": "RC channel 14 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC15_MAX", "shortDesc": "RC channel 15 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC15_MIN", "shortDesc": "RC channel 15 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC15_REV", "shortDesc": "RC channel 15 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC15_TRIM", "shortDesc": "RC channel 15 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC16_MAX", "shortDesc": "RC channel 16 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC16_MIN", "shortDesc": "RC channel 16 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC16_REV", "shortDesc": "RC channel 16 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC16_TRIM", "shortDesc": "RC channel 16 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC17_MAX", "shortDesc": "RC channel 17 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC17_MIN", "shortDesc": "RC channel 17 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC17_REV", "shortDesc": "RC channel 17 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC17_TRIM", "shortDesc": "RC channel 17 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC18_MAX", "shortDesc": "RC channel 18 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC18_MIN", "shortDesc": "RC channel 18 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC18_REV", "shortDesc": "RC channel 18 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC18_TRIM", "shortDesc": "RC channel 18 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for RC channel 1", "max": 2200.0, "min": 1500.0, "name": "RC1_MAX", "shortDesc": "RC channel 1 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for RC channel 1", "max": 1500.0, "min": 800.0, "name": "RC1_MIN", "shortDesc": "RC channel 1 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC1_REV", "shortDesc": "RC channel 1 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC1_TRIM", "shortDesc": "RC channel 1 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC2_MAX", "shortDesc": "RC channel 2 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC2_MIN", "shortDesc": "RC channel 2 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC2_REV", "shortDesc": "RC channel 2 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC2_TRIM", "shortDesc": "RC channel 2 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC3_MAX", "shortDesc": "RC channel 3 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC3_MIN", "shortDesc": "RC channel 3 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC3_REV", "shortDesc": "RC channel 3 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC3_TRIM", "shortDesc": "RC channel 3 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC4_MAX", "shortDesc": "RC channel 4 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC4_MIN", "shortDesc": "RC channel 4 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC4_REV", "shortDesc": "RC channel 4 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC4_TRIM", "shortDesc": "RC channel 4 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC5_MAX", "shortDesc": "RC channel 5 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC5_MIN", "shortDesc": "RC channel 5 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC5_REV", "shortDesc": "RC channel 5 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC5_TRIM", "shortDesc": "RC channel 5 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC6_MAX", "shortDesc": "RC channel 6 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC6_MIN", "shortDesc": "RC channel 6 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC6_REV", "shortDesc": "RC channel 6 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC6_TRIM", "shortDesc": "RC channel 6 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC7_MAX", "shortDesc": "RC channel 7 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC7_MIN", "shortDesc": "RC channel 7 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC7_REV", "shortDesc": "RC channel 7 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC7_TRIM", "shortDesc": "RC channel 7 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC8_MAX", "shortDesc": "RC channel 8 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC8_MIN", "shortDesc": "RC channel 8 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC8_REV", "shortDesc": "RC channel 8 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC8_TRIM", "shortDesc": "RC channel 8 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 2000.0, "group": "Radio Calibration", "longDesc": "Maximum value for this channel.", "max": 2200.0, "min": 1500.0, "name": "RC9_MAX", "shortDesc": "RC channel 9 maximum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1000.0, "group": "Radio Calibration", "longDesc": "Minimum value for this channel.", "max": 1500.0, "min": 800.0, "name": "RC9_MIN", "shortDesc": "RC channel 9 minimum", "type": "Float", "units": "us"}, {"category": "Standard", "default": 1.0, "group": "Radio Calibration", "longDesc": "Set to -1 to reverse channel.", "max": 1.0, "min": -1.0, "name": "RC9_REV", "shortDesc": "RC channel 9 reverse", "type": "Float", "values": [{"description": "Reverse", "value": -1.0}, {"description": "Normal", "value": 1.0}]}, {"category": "Standard", "default": 1500.0, "group": "Radio Calibration", "longDesc": "Mid point value", "max": 2200.0, "min": 800.0, "name": "RC9_TRIM", "shortDesc": "RC channel 9 trim", "type": "Float", "units": "us"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "This parameter is used by Ground Station software to save the number\nof channels which were used during RC calibration. It is only meant\nfor ground station use.", "max": 18, "min": 0, "name": "RC_CHAN_CNT", "shortDesc": "RC channel count", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Use RC_MAP_FAILSAFE to specify which channel is used to indicate RC loss via this threshold.\nBy default this is the throttle channel.\nSet to a PWM value slightly above the PWM value for the channel (e.g. throttle) in a failsafe event,\nbut below the minimum PWM value for the channel during normal operation.\nNote: The default value of 0 disables the feature (it is below the expected range).", "max": 2200, "min": 0, "name": "RC_FAILS_THR", "shortDesc": "Failsafe channel PWM threshold", "type": "Int32", "units": "us"}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX1", "shortDesc": "AUX1 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX2", "shortDesc": "AUX2 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX3", "shortDesc": "AUX3 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX4", "shortDesc": "AUX4 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX5", "shortDesc": "AUX5 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_AUX6", "shortDesc": "AUX6 Passthrough RC channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "max": 18, "min": 0, "name": "RC_MAP_ENG_MOT", "shortDesc": "RC channel to engage the main motor (for helicopters)", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Configures which RC channel is used by the receiver to indicate the signal was lost\n(on receivers that use output a fixed signal value to report lost signal).\nIf set to 0, the channel mapped to throttle is used.\nUse RC_FAILS_THR to set the threshold indicating lost signal. By default it's below\nthe expected range and hence disabled.", "max": 18, "min": 0, "name": "RC_MAP_FAILSAFE", "shortDesc": "Failsafe channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel.\nSet to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM1", "shortDesc": "PARAM1 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel.\nSet to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM2", "shortDesc": "PARAM2 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel.\nSet to 0 to deactivate *", "max": 18, "min": 0, "name": "RC_MAP_PARAM3", "shortDesc": "PARAM3 tuning channel", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates\nwhich channel should be used for reading pitch inputs from.\nA value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_PITCH", "shortDesc": "Pitch control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates\nwhich channel should be used for reading roll inputs from.\nA value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_ROLL", "shortDesc": "Roll control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates\nwhich channel should be used for reading throttle inputs from.\nA value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_THROTTLE", "shortDesc": "Throttle control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "The channel index (starting from 1 for channel 1) indicates\nwhich channel should be used for reading yaw inputs from.\nA value of zero indicates the switch is not assigned.", "max": 18, "min": 0, "name": "RC_MAP_YAW", "shortDesc": "Yaw control channel mapping", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 0, "group": "Radio Calibration", "longDesc": "0: do not read RSSI from input channel\n1-18: read RSSI from specified input channel\nSpecify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters.", "max": 18, "min": 0, "name": "RC_RSSI_PWM_CHAN", "shortDesc": "PWM input channel that provides RSSI", "type": "Int32", "values": [{"description": "Unassigned", "value": 0}, {"description": "Channel 1", "value": 1}, {"description": "Channel 2", "value": 2}, {"description": "Channel 3", "value": 3}, {"description": "Channel 4", "value": 4}, {"description": "Channel 5", "value": 5}, {"description": "Channel 6", "value": 6}, {"description": "Channel 7", "value": 7}, {"description": "Channel 8", "value": 8}, {"description": "Channel 9", "value": 9}, {"description": "Channel 10", "value": 10}, {"description": "Channel 11", "value": 11}, {"description": "Channel 12", "value": 12}, {"description": "Channel 13", "value": 13}, {"description": "Channel 14", "value": 14}, {"description": "Channel 15", "value": 15}, {"description": "Channel 16", "value": 16}, {"description": "Channel 17", "value": 17}, {"description": "Channel 18", "value": 18}]}, {"category": "Standard", "default": 2000, "group": "Radio Calibration", "longDesc": "Only used if RC_RSSI_PWM_CHAN > 0", "max": 2000, "min": 0, "name": "RC_RSSI_PWM_MAX", "shortDesc": "Max input value for RSSI reading", "type": "Int32"}, {"category": "Standard", "default": 1000, "group": "Radio Calibration", "longDesc": "Only used if RC_RSSI_PWM_CHAN > 0", "max": 2000, "min": 0, "name": "RC_RSSI_PWM_MIN", "shortDesc": "Min input value for RSSI reading", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs\nfor straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_PITCH", "shortDesc": "Pitch trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs\nfor straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_ROLL", "shortDesc": "Roll trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Radio Calibration", "increment": 0.01, "longDesc": "The trim value is the actuator control value the system needs\nfor straight and level flight.", "max": 0.5, "min": -0.5, "name": "TRIM_YAW", "shortDesc": "Yaw trim", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.75, "group": "Radio Switches", "longDesc": "0-1 indicate where in the full channel range the threshold sits\n0 : min\n1 : max\nsign indicates polarity of comparison\npositive : true when channel>th\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channelth\nnegative : true when channel The rover starts to cut the corner earlier.", "max": 100.0, "min": 1.0, "name": "RA_ACC_RAD_GAIN", "shortDesc": "Tuning parameter for corner cutting", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Ackermann", "increment": 0.01, "longDesc": "The controller scales the acceptance radius based on the angle between\nthe previous, current and next waypoint.\nHigher value -> smoother trajectory at the cost of how close the rover gets\nto the waypoint (Set to -1 to disable corner cutting).", "max": 100.0, "min": -1.0, "name": "RA_ACC_RAD_MAX", "shortDesc": "Maximum acceptance radius for the waypoints", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Ackermann", "increment": 0.01, "max": 1.5708, "min": 0.0, "name": "RA_MAX_STR_ANG", "shortDesc": "Maximum steering angle", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Ackermann", "increment": 0.01, "longDesc": "Set to -1 to disable.", "max": 1000.0, "min": -1.0, "name": "RA_STR_RATE_LIM", "shortDesc": "Steering rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Ackermann", "increment": 0.001, "longDesc": "Distance from the front to the rear axle.", "max": 100.0, "min": 0.0, "name": "RA_WHEEL_BASE", "shortDesc": "Wheel base", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Attitude Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_P", "shortDesc": "Proportional gain for closed loop yaw controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.174533, "group": "Rover Differential", "increment": 0.01, "longDesc": "This threshold is used for the state machine to switch from driving to turning based on the\nerror between the desired and actual yaw. It is also used as the threshold whether the rover should come\nto a smooth stop at the next waypoint. This slow down effect is active if the angle between the\nline segments from prevWP-currWP and currWP-nextWP is smaller then 180 - RD_TRANS_DRV_TRN.", "max": 3.14159, "min": 0.001, "name": "RD_TRANS_DRV_TRN", "shortDesc": "Yaw error threshhold to switch from driving to spot turning", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0872665, "group": "Rover Differential", "increment": 0.01, "longDesc": "This threshold is used for the state machine to switch from turning to driving based on the\nerror between the desired and actual yaw.", "max": 3.14159, "min": 0.001, "name": "RD_TRANS_TRN_DRV", "shortDesc": "Yaw error threshhold to switch from spot turning to driving", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Differential", "increment": 0.001, "longDesc": "Distance from the center of the right wheel to the center of the left wheel.", "max": 100.0, "min": 0.0, "name": "RD_WHEEL_TRACK", "shortDesc": "Wheel track", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Rover Differential", "increment": 0.01, "longDesc": "Assign value <1.0 to decrease stick response for yaw control.", "max": 1.0, "min": 0.1, "name": "RD_YAW_STK_GAIN", "shortDesc": "Yaw stick gain for Manual mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.17, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "Threshold for the angle between the active cruise direction and the cruise direction given\nby the stick inputs.\nThis can be understood as a deadzone for the combined stick inputs for forward/backwards\nand lateral speed which defines a course direction.", "max": 3.14, "min": 0.0, "name": "RM_COURSE_CTL_TH", "shortDesc": "Threshold to update course control in manual position mode", "type": "Float", "units": "rad"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Mecanum", "increment": 0.001, "longDesc": "Distance from the center of the right wheel to the center of the left wheel.", "max": 100.0, "min": 0.0, "name": "RM_WHEEL_TRACK", "shortDesc": "Wheel track", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "Rover Mecanum", "increment": 0.01, "longDesc": "Assign value <1.0 to decrease stick response for yaw control.", "max": 1.0, "min": 0.1, "name": "RM_YAW_STK_GAIN", "shortDesc": "Yaw stick gain for Manual mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap how quickly the magnitude of yaw rate setpoints can increase.\nSet to -1 to disable.", "max": 10000.0, "min": -1.0, "name": "RO_YAW_ACCEL_LIM", "shortDesc": "Yaw acceleration limit", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap how quickly the magnitude of yaw rate setpoints can decrease.\nSet to -1 to disable.", "max": 10000.0, "min": -1.0, "name": "RO_YAW_DECEL_LIM", "shortDesc": "Yaw deceleration limit", "type": "Float", "units": "deg/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Rate Control", "longDesc": "Exponential factor for tuning the input curve shape.\n0 Purely linear input curve\n1 Purely cubic input curve", "max": 1.0, "min": 0.0, "name": "RO_YAW_EXPO", "shortDesc": "Yaw rate expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Multiplicative correction factor for the feedforward mapping of the yaw rate controller.\nIncrease this value (x > 1) if the measured yaw rate is lower than the setpoint, decrease (0 < x < 1) otherwise.\nNote: Tuning this is particularly useful for skid-steered rovers, or rovers with misaligned wheels/steering axes\nthat cause a lot of friction when turning.", "max": 10000.0, "min": 0.01, "name": "RO_YAW_RATE_CORR", "shortDesc": "Yaw rate correction factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_I", "shortDesc": "Integral gain for closed loop yaw rate controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Used to cap yaw rate setpoints and map controller inputs to yaw rate setpoints\nin Acro, Stabilized and Position mode.", "max": 10000.0, "min": 0.0, "name": "RO_YAW_RATE_LIM", "shortDesc": "Yaw rate limit", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Rate Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_P", "shortDesc": "Proportional gain for closed loop yaw rate controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 3.0, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "The minimum threshold for the yaw rate measurement not to be interpreted as zero.", "max": 100.0, "min": 0.0, "name": "RO_YAW_RATE_TH", "shortDesc": "Yaw rate measurement threshold", "type": "Float", "units": "deg/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Rate Control", "increment": 0.01, "longDesc": "Percentage of stick input range that will be interpreted as zero around the stick centered value.", "max": 1.0, "min": 0.0, "name": "RO_YAW_STICK_DZ", "shortDesc": "Yaw stick deadzone", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Rate Control", "longDesc": "\"Superexponential\" factor for refining the input curve shape tuned using RO_YAW_EXPO.\n0 Pure Expo function\n0.7 reasonable shape enhancement for intuitive stick feel\n0.95 very strong bent input curve only near maxima have effect", "max": 0.95, "min": 0.0, "name": "RO_YAW_SUPEXPO", "shortDesc": "Yaw rate super expo factor", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable.\nFor mecanum rovers this limit is used for longitudinal and lateral acceleration.", "max": 100.0, "min": -1.0, "name": "RO_ACCEL_LIM", "shortDesc": "Acceleration limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable.\nNote that if it is disabled the rover will not slow down when approaching waypoints in auto modes.\nFor mecanum rovers this limit is used for longitudinal and lateral deceleration.", "max": 100.0, "min": -1.0, "name": "RO_DECEL_LIM", "shortDesc": "Deceleration limit", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable.\nNote that if it is disabled the rover will not slow down when approaching waypoints in auto modes.\nFor mecanum rovers this limit is used for longitudinal and lateral jerk.", "max": 100.0, "min": -1.0, "name": "RO_JERK_LIM", "shortDesc": "Jerk limit", "type": "Float", "units": "m/s^3"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Used to linearly map speeds [m/s] to throttle values [-1. 1].", "max": 100.0, "min": 0.0, "name": "RO_MAX_THR_SPEED", "shortDesc": "Speed the rover drives at maximum throttle", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.001, "max": 100.0, "min": 0.0, "name": "RO_SPEED_I", "shortDesc": "Integral gain for ground speed controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Used to cap speed setpoints and map controller inputs to speed setpoints in Position mode.", "max": 100.0, "min": -1.0, "name": "RO_SPEED_LIM", "shortDesc": "Speed limit", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.0, "group": "Rover Velocity Control", "increment": 0.01, "max": 100.0, "min": 0.0, "name": "RO_SPEED_P", "shortDesc": "Proportional gain for ground speed controller", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": -1.0, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Reduced_speed = RO_MAX_THR_SPEED * (1 - normalized_course_error * RO_SPEED_RED)\nThe normalized course error is the angle between the current course and the bearing setpoint\ninterpolated from [0, 180] -> [0, 1].\nHigher value -> More speed reduction.\nNote: This is also used to calculate the speed at which the vehicle arrives at a waypoint in auto modes.\nSet to -1 to disable bearing error based speed reduction.", "max": 100.0, "min": -1.0, "name": "RO_SPEED_RED", "shortDesc": "Tuning parameter for the speed reduction based on the course error", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "Rover Velocity Control", "increment": 0.01, "longDesc": "Set to -1 to disable.\nThe minimum threshold for the speed measurement not to be interpreted as zero.", "max": 100.0, "min": 0.0, "name": "RO_SPEED_TH", "shortDesc": "Speed measurement threshold", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Runway Takeoff", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "RWTO_MAX_THR", "shortDesc": "Throttle during runway takeoff", "type": "Float", "units": "norm"}, {"category": "Standard", "default": 1, "group": "Runway Takeoff", "longDesc": "This is useful when map, GNSS, or yaw errors on ground are misaligned with what the operator intends for takeoff course.\nParticularly useful for skinny runways or if the wheel servo is a bit off trim.", "name": "RWTO_NUDGE", "shortDesc": "Enable use of yaw stick for nudging the wheel during runway ground roll", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Runway Takeoff", "increment": 0.5, "longDesc": "A taildragger with steerable wheel might need to pitch up\na little to keep its wheel on the ground before airspeed\nto takeoff is reached.", "max": 20.0, "min": -10.0, "name": "RWTO_PSP", "shortDesc": "Pitch setpoint during taxi / before takeoff rotation airspeed is reached", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "Runway Takeoff", "increment": 0.1, "max": 15.0, "min": 1.0, "name": "RWTO_RAMP_TIME", "shortDesc": "Throttle ramp up time for runway takeoff", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": -1.0, "group": "Runway Takeoff", "increment": 0.1, "longDesc": "The calibrated airspeed threshold during the takeoff ground roll when the plane should start rotating (pitching up).\nMust be less than the takeoff airspeed, will otherwise be capped at the takeoff airpeed (see FW_TKO_AIRSPD).\nIf set <= 0.0, defaults to 0.9 * takeoff airspeed (see FW_TKO_AIRSPD)", "min": -1.0, "name": "RWTO_ROT_AIRSPD", "shortDesc": "Takeoff rotation airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "Runway Takeoff", "increment": 0.1, "longDesc": "This is the time desired to linearly ramp in takeoff pitch constraints during the takeoff rotation", "min": 0.1, "name": "RWTO_ROT_TIME", "shortDesc": "Takeoff rotation time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Runway Takeoff", "name": "RWTO_TKOFF", "shortDesc": "Runway takeoff with landing gear", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"bitmask": [{"description": "SD card logging", "index": 0}, {"description": "Mavlink logging", "index": 1}], "category": "Standard", "default": 3, "group": "SD Logging", "longDesc": "If no logging is set the logger will not be started. Set bits true to enable: 0: SD card logging 1: Mavlink logging", "max": 3, "min": 0, "name": "SDLOG_BACKEND", "rebootRequired": true, "shortDesc": "Logging Backend (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "When enabled, logging will not start from boot if battery power is not detected (e.g. powered via USB on a test bench). This prevents extraneous flight logs from being created during bench testing. Note that this only applies to log-from-boot modes. This has no effect on arm-based modes.", "name": "SDLOG_BOOT_BAT", "shortDesc": "Battery-only Logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum. Note: this does not apply to mission log files.", "max": 1000, "min": 0, "name": "SDLOG_DIRS_MAX", "rebootRequired": true, "shortDesc": "Maximum number of log directories to keep", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "If enabled, a small additional \"mission\" log file will be written to the SD card. The log contains just those messages that are useful for tasks like generating flight statistics and geotagging. The different modes can be used to further reduce the logged data (and thus the log file size). For example, choose geotagging mode to only log data required for geotagging. Note that the normal/full log is still created, and contains all the data in the mission log (and more).", "name": "SDLOG_MISSION", "rebootRequired": true, "shortDesc": "Mission Log", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "All mission messages", "value": 1}, {"description": "Geotagging messages", "value": 2}]}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming. Note: The logging start/end points that can be configured here only apply to SD logging. The mavlink backend is started/stopped independently of these points.", "name": "SDLOG_MODE", "rebootRequired": true, "shortDesc": "Logging Mode", "type": "Int32", "values": [{"description": "when armed until disarm (default)", "value": 0}, {"description": "from boot until disarm", "value": 1}, {"description": "from boot until shutdown", "value": 2}, {"description": "while manual input AUX1 >30%", "value": 3}, {"description": "from 1st armed until shutdown", "value": 4}]}, {"bitmask": [{"description": "Default set (general log analysis)", "index": 0}, {"description": "Estimator replay (EKF2)", "index": 1}, {"description": "Thermal calibration", "index": 2}, {"description": "System identification", "index": 3}, {"description": "High rate", "index": 4}, {"description": "Debug", "index": 5}, {"description": "Sensor comparison", "index": 6}, {"description": "Computer Vision and Avoidance", "index": 7}, {"description": "Raw FIFO high-rate IMU (Gyro)", "index": 8}, {"description": "Raw FIFO high-rate IMU (Accel)", "index": 9}, {"description": "Mavlink tunnel message logging", "index": 10}, {"description": "High rate sensors", "index": 11}], "category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "This integer bitmask controls the set and rates of logged topics. The default allows for general log analysis while keeping the log file size reasonably small. Enabling multiple sets leads to higher bandwidth requirements and larger log files. Set bits true to enable: 0 : Default set (used for general log analysis) 1 : Full rate estimator (EKF2) replay topics 2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data) 3 : Topics for system identification (high rate actuator control and IMU data) 4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) 5 : Debugging topics (debug_*.msg topics, for custom code) 6 : Topics for sensor comparison (low rate raw IMU, Baro and magnetometer data) 7 : Topics for computer vision and collision prevention 8 : Raw FIFO high-rate IMU (Gyro) 9 : Raw FIFO high-rate IMU (Accel) 10: Logging of mavlink tunnel message (useful for payload communication debugging)", "max": 4095, "min": 0, "name": "SDLOG_PROFILE", "rebootRequired": true, "shortDesc": "Logging topic profile (integer bitmask)", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "SD Logging", "longDesc": "the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets", "max": 1000, "min": -1000, "name": "SDLOG_UTC_OFFSET", "shortDesc": "UTC offset (unit: min)", "type": "Int32", "units": "min"}, {"category": "Standard", "default": 1, "group": "SD Logging", "longDesc": "If set to 1, add an ID to the log, which uniquely identifies the vehicle", "name": "SDLOG_UUID", "shortDesc": "Log UUID", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 60.0, "group": "SITL", "increment": 1.0, "max": 86400.0, "min": 1.0, "name": "SIM_BAT_DRAIN", "shortDesc": "Simulator Battery drain interval", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "SITL", "longDesc": "Enable or disable the internal battery simulation. This is useful\nwhen the battery is simulated externally and interfaced with PX4\nthrough MAVLink for example.", "name": "SIM_BAT_ENABLE", "shortDesc": "Simulator Battery enabled", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 50.0, "group": "SITL", "increment": 0.1, "longDesc": "Can be used to alter the battery level during SITL- or HITL-simulation on the fly.\nParticularly useful for testing different low-battery behaviour.", "max": 100.0, "min": 0.0, "name": "SIM_BAT_MIN_PCT", "shortDesc": "Simulator Battery minimal percentage", "type": "Float", "units": "%"}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC0_ID", "shortDesc": "Accelerometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC0_PRIO", "shortDesc": "Accelerometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC0_ROT", "shortDesc": "Accelerometer 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_XOFF", "shortDesc": "Accelerometer 0 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_XSCALE", "shortDesc": "Accelerometer 0 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_YOFF", "shortDesc": "Accelerometer 0 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_YSCALE", "shortDesc": "Accelerometer 0 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC0_ZOFF", "shortDesc": "Accelerometer 0 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC0_ZSCALE", "shortDesc": "Accelerometer 0 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC1_ID", "shortDesc": "Accelerometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC1_PRIO", "shortDesc": "Accelerometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC1_ROT", "shortDesc": "Accelerometer 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_XOFF", "shortDesc": "Accelerometer 1 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_XSCALE", "shortDesc": "Accelerometer 1 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_YOFF", "shortDesc": "Accelerometer 1 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_YSCALE", "shortDesc": "Accelerometer 1 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC1_ZOFF", "shortDesc": "Accelerometer 1 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC1_ZSCALE", "shortDesc": "Accelerometer 1 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC2_ID", "shortDesc": "Accelerometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC2_PRIO", "shortDesc": "Accelerometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC2_ROT", "shortDesc": "Accelerometer 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_XOFF", "shortDesc": "Accelerometer 2 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_XSCALE", "shortDesc": "Accelerometer 2 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_YOFF", "shortDesc": "Accelerometer 2 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_YSCALE", "shortDesc": "Accelerometer 2 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC2_ZOFF", "shortDesc": "Accelerometer 2 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC2_ZSCALE", "shortDesc": "Accelerometer 2 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the accelerometer this calibration applies to.", "name": "CAL_ACC3_ID", "shortDesc": "Accelerometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": -1, "group": "Sensor Calibration", "name": "CAL_ACC3_PRIO", "shortDesc": "Accelerometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_ACC3_ROT", "shortDesc": "Accelerometer 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_XOFF", "shortDesc": "Accelerometer 3 X-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_XSCALE", "shortDesc": "Accelerometer 3 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_YOFF", "shortDesc": "Accelerometer 3 Y-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_YSCALE", "shortDesc": "Accelerometer 3 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_ACC3_ZOFF", "shortDesc": "Accelerometer 3 Z-axis offset", "type": "Float", "units": "m/s^2", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_ACC3_ZSCALE", "shortDesc": "Accelerometer 3 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO0_ID", "shortDesc": "Barometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO0_OFF", "shortDesc": "Barometer 0 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO0_PRIO", "shortDesc": "Barometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO1_ID", "shortDesc": "Barometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO1_OFF", "shortDesc": "Barometer 1 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO1_PRIO", "shortDesc": "Barometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO2_ID", "shortDesc": "Barometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO2_OFF", "shortDesc": "Barometer 2 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO2_PRIO", "shortDesc": "Barometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the barometer this calibration applies to.", "name": "CAL_BARO3_ID", "shortDesc": "Barometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_BARO3_OFF", "shortDesc": "Barometer 3 offset", "type": "Float", "volatile": true}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_BARO3_PRIO", "shortDesc": "Barometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO0_ID", "shortDesc": "Gyroscope 0 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO0_PRIO", "shortDesc": "Gyroscope 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO0_ROT", "shortDesc": "Gyroscope 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_XOFF", "shortDesc": "Gyroscope 0 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_YOFF", "shortDesc": "Gyroscope 0 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO0_ZOFF", "shortDesc": "Gyroscope 0 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO1_ID", "shortDesc": "Gyroscope 1 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO1_PRIO", "shortDesc": "Gyroscope 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO1_ROT", "shortDesc": "Gyroscope 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_XOFF", "shortDesc": "Gyroscope 1 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_YOFF", "shortDesc": "Gyroscope 1 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO1_ZOFF", "shortDesc": "Gyroscope 1 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO2_ID", "shortDesc": "Gyroscope 2 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO2_PRIO", "shortDesc": "Gyroscope 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO2_ROT", "shortDesc": "Gyroscope 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_XOFF", "shortDesc": "Gyroscope 2 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_YOFF", "shortDesc": "Gyroscope 2 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO2_ZOFF", "shortDesc": "Gyroscope 2 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the gyroscope this calibration applies to.", "name": "CAL_GYRO3_ID", "shortDesc": "Gyroscope 3 calibration device ID", "type": "Int32"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_GYRO3_PRIO", "shortDesc": "Gyroscope 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.", "max": 40, "min": -1, "name": "CAL_GYRO3_ROT", "shortDesc": "Gyroscope 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_XOFF", "shortDesc": "Gyroscope 3 X-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_YOFF", "shortDesc": "Gyroscope 3 Y-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_GYRO3_ZOFF", "shortDesc": "Gyroscope 3 Z-axis offset", "type": "Float", "units": "rad/s", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG0_ID", "shortDesc": "Magnetometer 0 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_PITCH", "shortDesc": "Magnetometer 0 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG0_PRIO", "shortDesc": "Magnetometer 0 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_ROLL", "shortDesc": "Magnetometer 0 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.\nSet to \"Custom Euler Angle\" to define the rotation using CAL_MAG0_ROLL, CAL_MAG0_PITCH and CAL_MAG0_YAW.", "max": 100, "min": -1, "name": "CAL_MAG0_ROT", "shortDesc": "Magnetometer 0 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nX component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG0_XCOMP", "shortDesc": "Magnetometer 0 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_XODIAG", "shortDesc": "Magnetometer 0 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_XOFF", "shortDesc": "Magnetometer 0 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_XSCALE", "shortDesc": "Magnetometer 0 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG0_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG0_YAW", "shortDesc": "Magnetometer 0 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nY component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG0_YCOMP", "shortDesc": "Magnetometer 0 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_YODIAG", "shortDesc": "Magnetometer 0 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_YOFF", "shortDesc": "Magnetometer 0 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_YSCALE", "shortDesc": "Magnetometer 0 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nZ component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG0_ZCOMP", "shortDesc": "Magnetometer 0 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_ZODIAG", "shortDesc": "Magnetometer 0 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG0_ZOFF", "shortDesc": "Magnetometer 0 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG0_ZSCALE", "shortDesc": "Magnetometer 0 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG1_ID", "shortDesc": "Magnetometer 1 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_PITCH", "shortDesc": "Magnetometer 1 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG1_PRIO", "shortDesc": "Magnetometer 1 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_ROLL", "shortDesc": "Magnetometer 1 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.\nSet to \"Custom Euler Angle\" to define the rotation using CAL_MAG1_ROLL, CAL_MAG1_PITCH and CAL_MAG1_YAW.", "max": 100, "min": -1, "name": "CAL_MAG1_ROT", "shortDesc": "Magnetometer 1 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nX component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG1_XCOMP", "shortDesc": "Magnetometer 1 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_XODIAG", "shortDesc": "Magnetometer 1 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_XOFF", "shortDesc": "Magnetometer 1 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_XSCALE", "shortDesc": "Magnetometer 1 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG1_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG1_YAW", "shortDesc": "Magnetometer 1 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nY component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG1_YCOMP", "shortDesc": "Magnetometer 1 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_YODIAG", "shortDesc": "Magnetometer 1 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_YOFF", "shortDesc": "Magnetometer 1 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_YSCALE", "shortDesc": "Magnetometer 1 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nZ component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG1_ZCOMP", "shortDesc": "Magnetometer 1 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_ZODIAG", "shortDesc": "Magnetometer 1 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG1_ZOFF", "shortDesc": "Magnetometer 1 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG1_ZSCALE", "shortDesc": "Magnetometer 1 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG2_ID", "shortDesc": "Magnetometer 2 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_PITCH", "shortDesc": "Magnetometer 2 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG2_PRIO", "shortDesc": "Magnetometer 2 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_ROLL", "shortDesc": "Magnetometer 2 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.\nSet to \"Custom Euler Angle\" to define the rotation using CAL_MAG2_ROLL, CAL_MAG2_PITCH and CAL_MAG2_YAW.", "max": 100, "min": -1, "name": "CAL_MAG2_ROT", "shortDesc": "Magnetometer 2 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nX component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG2_XCOMP", "shortDesc": "Magnetometer 2 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_XODIAG", "shortDesc": "Magnetometer 2 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_XOFF", "shortDesc": "Magnetometer 2 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_XSCALE", "shortDesc": "Magnetometer 2 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG2_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG2_YAW", "shortDesc": "Magnetometer 2 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nY component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG2_YCOMP", "shortDesc": "Magnetometer 2 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_YODIAG", "shortDesc": "Magnetometer 2 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_YOFF", "shortDesc": "Magnetometer 2 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_YSCALE", "shortDesc": "Magnetometer 2 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nZ component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG2_ZCOMP", "shortDesc": "Magnetometer 2 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_ZODIAG", "shortDesc": "Magnetometer 2 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG2_ZOFF", "shortDesc": "Magnetometer 2 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG2_ZSCALE", "shortDesc": "Magnetometer 2 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Device ID of the magnetometer this calibration applies to.", "name": "CAL_MAG3_ID", "shortDesc": "Magnetometer 3 calibration device ID", "type": "Int32"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_PITCH", "shortDesc": "Magnetometer 3 Custom Euler Pitch Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "name": "CAL_MAG3_PRIO", "shortDesc": "Magnetometer 3 priority", "type": "Int32", "values": [{"description": "Uninitialized", "value": -1}, {"description": "Disabled", "value": 0}, {"description": "Min", "value": 1}, {"description": "Low", "value": 25}, {"description": "Medium (Default)", "value": 50}, {"description": "High", "value": 75}, {"description": "Max", "value": 100}]}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_ROLL", "shortDesc": "Magnetometer 3 Custom Euler Roll Angle", "type": "Float", "units": "deg"}, {"category": "System", "default": -1, "group": "Sensor Calibration", "longDesc": "An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero.\nSet to \"Custom Euler Angle\" to define the rotation using CAL_MAG3_ROLL, CAL_MAG3_PITCH and CAL_MAG3_YAW.", "max": 100, "min": -1, "name": "CAL_MAG3_ROT", "shortDesc": "Magnetometer 3 rotation relative to airframe", "type": "Int32", "values": [{"description": "Internal", "value": -1}, {"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}, {"description": "Custom Euler Angle", "value": 100}]}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nX component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG3_XCOMP", "shortDesc": "Magnetometer 3 X Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_XODIAG", "shortDesc": "Magnetometer 3 X-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_XOFF", "shortDesc": "Magnetometer 3 X-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_XSCALE", "shortDesc": "Magnetometer 3 X-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Setting this parameter changes CAL_MAG3_ROT to \"Custom Euler Angle\"", "max": 180.0, "min": -180.0, "name": "CAL_MAG3_YAW", "shortDesc": "Magnetometer 3 Custom Euler Yaw Angle", "type": "Float", "units": "deg"}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nY component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG3_YCOMP", "shortDesc": "Magnetometer 3 Y Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_YODIAG", "shortDesc": "Magnetometer 3 Y-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_YOFF", "shortDesc": "Magnetometer 3 Y-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_YSCALE", "shortDesc": "Magnetometer 3 Y-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "longDesc": "Coefficient describing linear relationship between\nZ component of magnetometer in body frame axis\nand either current or throttle depending on value of CAL_MAG_COMP_TYP.\nUnit for throttle-based compensation is [G] and\nfor current-based compensation [G/kA]", "name": "CAL_MAG3_ZCOMP", "shortDesc": "Magnetometer 3 Z Axis throttle compensation", "type": "Float", "volatile": true}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_ZODIAG", "shortDesc": "Magnetometer 3 Z-axis off diagonal scale factor", "type": "Float", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 0.0, "group": "Sensor Calibration", "name": "CAL_MAG3_ZOFF", "shortDesc": "Magnetometer 3 Z-axis offset", "type": "Float", "units": "gauss", "volatile": true}, {"category": "System", "decimalPlaces": 3, "default": 1.0, "group": "Sensor Calibration", "max": 3.0, "min": 0.1, "name": "CAL_MAG3_ZSCALE", "shortDesc": "Magnetometer 3 Z-axis scaling factor", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "name": "CAL_MAG_COMP_TYP", "shortDesc": "Type of magnetometer compensation", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Throttle-based compensation", "value": 1}, {"description": "Current-based compensation (battery_status instance 0)", "value": 2}, {"description": "Current-based compensation (battery_status instance 1)", "value": 3}]}, {"category": "Standard", "default": 0.0, "group": "Sensor Calibration", "longDesc": "Pick the appropriate scaling from the datasheet.\nthis number defines the (linear) conversion from voltage\nto Pascal (pa). For the MPXV7002DP this is 1000.\nNOTE: If the sensor always registers zero, try switching\nthe static and dynamic tubes.", "name": "SENS_DPRES_ANSC", "shortDesc": "Differential pressure sensor analog scaling", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Sensor Calibration", "longDesc": "The offset (zero-reading) in Pascal", "name": "SENS_DPRES_OFF", "shortDesc": "Differential pressure sensor offset", "type": "Float", "volatile": true}, {"category": "System", "default": 0, "group": "Sensor Calibration", "longDesc": "Reverse the raw measurements of all differential pressure sensors.\nThis can be enabled if the sensors have static and dynamic ports swapped.", "name": "SENS_DPRES_REV", "shortDesc": "Reverse differential pressure sensor readings", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 100.0, "group": "Sensor Calibration", "increment": 0.1, "longDesc": "This parameter defines the maximum distance from ground at which the optical flow sensor operates reliably.\nThe height setpoint will be limited to be no greater than this value when the navigation system\nis completely reliant on optical flow data and the height above ground estimate is valid.\nThe sensor may be usable above this height, but accuracy will progressively degrade.", "max": 100.0, "min": 1.0, "name": "SENS_FLOW_MAXHGT", "shortDesc": "Maximum height above ground when reliant on optical flow", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 8.0, "group": "Sensor Calibration", "longDesc": "Optical flow data will not fused by the estimators if the magnitude of the flow rate exceeds this value and\ncontrol loops will be instructed to limit ground speed such that the flow rate produced by movement over ground\nis less than 50% of this value.", "min": 1.0, "name": "SENS_FLOW_MAXR", "shortDesc": "Magnitude of maximum angular flow rate reliably measurable by the optical flow sensor", "type": "Float", "units": "rad/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.08, "group": "Sensor Calibration", "increment": 0.1, "longDesc": "This parameter defines the minimum distance from ground at which the optical flow sensor operates reliably.\nThe sensor may be usable below this height, but accuracy will progressively reduce to loss of focus.", "max": 1.0, "min": 0.0, "name": "SENS_FLOW_MINHGT", "shortDesc": "Minimum height above ground when reliant on optical flow", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "Model with Pitot\nCAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed.\nCAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor.\nModel without Pitot (1.5 mm tubes)\nCAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed.\nCAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor.\nTube Pressure Drop\nCAL_AIR_TUBED_MM: Diameter in mm of the pitot and tubes, must have the same diameter.\nCAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor and the static + dynamic port length of the pitot.", "name": "CAL_AIR_CMODEL", "shortDesc": "Airspeed sensor compensation model for the SDP3x", "type": "Int32", "values": [{"description": "Model with Pitot", "value": 0}, {"description": "Model without Pitot (1.5 mm tubes)", "value": 1}, {"description": "Tube Pressure Drop", "value": 2}]}, {"category": "Standard", "default": 1.5, "group": "Sensors", "max": 100.0, "min": 1.5, "name": "CAL_AIR_TUBED_MM", "shortDesc": "Airspeed sensor tube diameter. Only used for the Tube Pressure Drop Compensation", "type": "Float", "units": "mm"}, {"category": "Standard", "default": 0.2, "group": "Sensors", "longDesc": "See the CAL_AIR_CMODEL explanation on how this parameter should be set.", "max": 2.0, "min": 0.01, "name": "CAL_AIR_TUBELEN", "shortDesc": "Airspeed sensor tube length", "type": "Float", "units": "m"}, {"category": "Developer", "default": 63, "group": "Sensors", "longDesc": "Use SENS_MAG_SIDES instead", "name": "CAL_MAG_SIDES", "shortDesc": "For legacy QGC support only", "type": "Int32"}, {"category": "Standard", "default": 30.0, "group": "Sensors", "longDesc": "The cutoff frequency for the 2nd order butterworth filter on the primary accelerometer.\nThis only affects the signal sent to the controllers, not the estimators. 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_ACCEL_CUTOFF", "rebootRequired": true, "shortDesc": "Low pass filter cutoff frequency for accel", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The cutoff frequency for the 2nd order butterworth filter used on\nthe time derivative of the measured angular velocity, also known as\nthe D-term filter in the rate controller. The D-term uses the derivative of\nthe rate and thus is the most susceptible to noise. Therefore, using\na D-term filter allows to increase IMU_GYRO_CUTOFF, which\nleads to reduced control latency and permits to increase the P gains.\nA value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_DGYRO_CUTOFF", "rebootRequired": true, "shortDesc": "Cutoff frequency for angular acceleration (D-Term filter)", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 1, "group": "Sensors", "name": "IMU_GYRO_CAL_EN", "rebootRequired": true, "shortDesc": "IMU gyro auto calibration enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 1, "default": 40.0, "group": "Sensors", "increment": 0.1, "longDesc": "The cutoff frequency for the 2nd order butterworth filter on the primary gyro.\nThis only affects the angular velocity sent to the controllers, not the estimators.\nIt applies also to the angular acceleration (D-Term filter), see IMU_DGYRO_CUTOFF.\nA value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_CUTOFF", "rebootRequired": true, "shortDesc": "Low pass filter cutoff frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 15.0, "group": "Sensors", "increment": 0.1, "longDesc": "Bandwidth per notch filter when using dynamic notch filtering with ESC RPM.", "max": 30.0, "min": 5.0, "name": "IMU_GYRO_DNF_BW", "shortDesc": "IMU gyro ESC notch filter bandwidth", "type": "Float", "units": "Hz"}, {"bitmask": [{"description": "ESC RPM", "index": 0}, {"description": "FFT", "index": 1}], "category": "Standard", "default": 0, "group": "Sensors", "longDesc": "Enable bank of dynamically updating notch filters.\nRequires ESC RPM feedback or onboard FFT (IMU_GYRO_FFT_EN).", "max": 3, "min": 0, "name": "IMU_GYRO_DNF_EN", "shortDesc": "IMU gyro dynamic notch filtering", "type": "Int32"}, {"category": "Standard", "default": 3, "group": "Sensors", "longDesc": "ESC RPM number of harmonics (multiples of RPM) for ESC RPM dynamic notch filtering.", "max": 7, "min": 1, "name": "IMU_GYRO_DNF_HMC", "shortDesc": "IMU gyro dynamic notch filter harmonics", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 25.0, "group": "Sensors", "increment": 0.1, "longDesc": "Minimum notch filter frequency in Hz.", "name": "IMU_GYRO_DNF_MIN", "shortDesc": "IMU gyro dynamic notch filter minimum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "name": "IMU_GYRO_FFT_EN", "rebootRequired": true, "shortDesc": "IMU gyro FFT enable", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 512, "group": "Sensors", "name": "IMU_GYRO_FFT_LEN", "rebootRequired": true, "shortDesc": "IMU gyro FFT length", "type": "Int32", "units": "Hz", "values": [{"description": "256", "value": 256}, {"description": "512", "value": 512}, {"description": "1024", "value": 1024}, {"description": "4096", "value": 4096}]}, {"category": "Standard", "default": 150.0, "group": "Sensors", "max": 1000.0, "min": 1.0, "name": "IMU_GYRO_FFT_MAX", "rebootRequired": true, "shortDesc": "IMU gyro FFT maximum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 30.0, "group": "Sensors", "max": 1000.0, "min": 1.0, "name": "IMU_GYRO_FFT_MIN", "rebootRequired": true, "shortDesc": "IMU gyro FFT minimum frequency", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 10.0, "group": "Sensors", "max": 30.0, "min": 1.0, "name": "IMU_GYRO_FFT_SNR", "shortDesc": "IMU gyro FFT SNR", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The frequency width of the stop band for the 2nd order notch filter on the primary gyro.\nSee \"IMU_GYRO_NF0_FRQ\" to activate the filter and to set the notch frequency.\nApplies to both angular velocity and angular acceleration sent to the controllers.", "max": 100.0, "min": 0.0, "name": "IMU_GYRO_NF0_BW", "rebootRequired": true, "shortDesc": "Notch filter bandwidth for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "increment": 0.1, "longDesc": "The center frequency for the 2nd order notch filter on the primary gyro.\nThis filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency.\nThis only affects the signal sent to the controllers, not the estimators.\nApplies to both angular velocity and angular acceleration sent to the controllers.\nSee \"IMU_GYRO_NF0_BW\" to set the bandwidth of the filter.\nA value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_NF0_FRQ", "rebootRequired": true, "shortDesc": "Notch filter frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "Sensors", "increment": 0.1, "longDesc": "The frequency width of the stop band for the 2nd order notch filter on the primary gyro.\nSee \"IMU_GYRO_NF1_FRQ\" to activate the filter and to set the notch frequency.\nApplies to both angular velocity and angular acceleration sent to the controllers.", "max": 100.0, "min": 0.0, "name": "IMU_GYRO_NF1_BW", "rebootRequired": true, "shortDesc": "Notch filter 1 bandwidth for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "increment": 0.1, "longDesc": "The center frequency for the 2nd order notch filter on the primary gyro.\nThis filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency.\nThis only affects the signal sent to the controllers, not the estimators.\nApplies to both angular velocity and angular acceleration sent to the controllers.\nSee \"IMU_GYRO_NF1_BW\" to set the bandwidth of the filter.\nA value of 0 disables the filter.", "max": 1000.0, "min": 0.0, "name": "IMU_GYRO_NF1_FRQ", "rebootRequired": true, "shortDesc": "Notch filter 2 frequency for gyro", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 400, "group": "Sensors", "longDesc": "The maximum rate the gyro control data (vehicle_angular_velocity) will be\nallowed to publish at. This is the loop rate for the rate controller and outputs.\nNote: sensor data is always read and filtered at the full raw rate (eg commonly 8 kHz) regardless of this setting.", "max": 2000, "min": 100, "name": "IMU_GYRO_RATEMAX", "rebootRequired": true, "shortDesc": "Gyro control data maximum publication rate (inner loop rate)", "type": "Int32", "units": "Hz", "values": [{"description": "100 Hz", "value": 100}, {"description": "250 Hz", "value": 250}, {"description": "400 Hz", "value": 400}, {"description": "800 Hz", "value": 800}, {"description": "1000 Hz", "value": 1000}, {"description": "2000 Hz", "value": 2000}]}, {"category": "Standard", "default": 200, "group": "Sensors", "longDesc": "The rate at which raw IMU data is integrated to produce delta angles and delta velocities.\nRecommended to set this to a multiple of the estimator update period (currently 10 ms for ekf2).", "max": 1000, "min": 100, "name": "IMU_INTEG_RATE", "rebootRequired": true, "shortDesc": "IMU integration rate", "type": "Int32", "units": "Hz", "values": [{"description": "100 Hz", "value": 100}, {"description": "200 Hz", "value": 200}, {"description": "250 Hz", "value": 250}, {"description": "400 Hz", "value": 400}]}, {"category": "Standard", "default": 1013.25, "group": "Sensors", "max": 1500.0, "min": 500.0, "name": "SENS_BARO_QNH", "shortDesc": "QNH for barometer", "type": "Float", "units": "hPa"}, {"category": "Standard", "default": 20.0, "group": "Sensors", "longDesc": "Barometric air data maximum publication rate. This is an upper bound,\nactual barometric data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_BARO_RATE", "shortDesc": "Baro max rate", "type": "Float", "units": "Hz"}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically calibrate barometer based on the GNSS height", "name": "SENS_BAR_AUTOCAL", "shortDesc": "Barometer auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "This parameter defines the rotation of the FMU board relative to the platform.", "max": 40, "min": -1, "name": "SENS_BOARD_ROT", "rebootRequired": true, "shortDesc": "Board rotation", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}, {"description": "Roll 180\u00b0", "value": 8}, {"description": "Roll 180\u00b0, Yaw 45\u00b0", "value": 9}, {"description": "Roll 180\u00b0, Yaw 90\u00b0", "value": 10}, {"description": "Roll 180\u00b0, Yaw 135\u00b0", "value": 11}, {"description": "Pitch 180\u00b0", "value": 12}, {"description": "Roll 180\u00b0, Yaw 225\u00b0", "value": 13}, {"description": "Roll 180\u00b0, Yaw 270\u00b0", "value": 14}, {"description": "Roll 180\u00b0, Yaw 315\u00b0", "value": 15}, {"description": "Roll 90\u00b0", "value": 16}, {"description": "Roll 90\u00b0, Yaw 45\u00b0", "value": 17}, {"description": "Roll 90\u00b0, Yaw 90\u00b0", "value": 18}, {"description": "Roll 90\u00b0, Yaw 135\u00b0", "value": 19}, {"description": "Roll 270\u00b0", "value": 20}, {"description": "Roll 270\u00b0, Yaw 45\u00b0", "value": 21}, {"description": "Roll 270\u00b0, Yaw 90\u00b0", "value": 22}, {"description": "Roll 270\u00b0, Yaw 135\u00b0", "value": 23}, {"description": "Pitch 90\u00b0", "value": 24}, {"description": "Pitch 270\u00b0", "value": 25}, {"description": "Pitch 180\u00b0, Yaw 90\u00b0", "value": 26}, {"description": "Pitch 180\u00b0, Yaw 270\u00b0", "value": 27}, {"description": "Roll 90\u00b0, Pitch 90\u00b0", "value": 28}, {"description": "Roll 180\u00b0, Pitch 90\u00b0", "value": 29}, {"description": "Roll 270\u00b0, Pitch 90\u00b0", "value": 30}, {"description": "Roll 90\u00b0, Pitch 180\u00b0", "value": 31}, {"description": "Roll 270\u00b0, Pitch 180\u00b0", "value": 32}, {"description": "Roll 90\u00b0, Pitch 270\u00b0", "value": 33}, {"description": "Roll 180\u00b0, Pitch 270\u00b0", "value": 34}, {"description": "Roll 270\u00b0, Pitch 270\u00b0", "value": 35}, {"description": "Roll 90\u00b0, Pitch 180\u00b0, Yaw 90\u00b0", "value": 36}, {"description": "Roll 90\u00b0, Yaw 270\u00b0", "value": 37}, {"description": "Roll 90\u00b0, Pitch 68\u00b0, Yaw 293\u00b0", "value": 38}, {"description": "Pitch 315\u00b0", "value": 39}, {"description": "Roll 90\u00b0, Pitch 315\u00b0", "value": 40}]}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "longDesc": "Rotation from flight controller board to vehicle body frame.\nThis parameter gets set during the \"level horizon\" calibration or can be\nset manually.", "max": 45.0, "min": -45.0, "name": "SENS_BOARD_X_OFF", "shortDesc": "Board rotation X (roll) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "longDesc": "Rotation from flight controller board to vehicle body frame.\nThis parameter gets set during the \"level horizon\" calibration or can be\nset manually.", "max": 45.0, "min": -45.0, "name": "SENS_BOARD_Y_OFF", "shortDesc": "Board rotation Y (pitch) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "Sensors", "longDesc": "Rotation from flight controller board to vehicle body frame.\nHas to be set manually (not set by any calibration).", "max": 45.0, "min": -45.0, "name": "SENS_BOARD_Z_OFF", "shortDesc": "Board rotation Z (yaw) offset", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_AGPSIM", "rebootRequired": true, "shortDesc": "Simulate Aux Global Position (AGP)", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_ARSPDSIM", "rebootRequired": true, "shortDesc": "Enable simulated airspeed sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_BAROSIM", "rebootRequired": true, "shortDesc": "Enable simulated barometer sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_GPSSIM", "rebootRequired": true, "shortDesc": "Enable simulated GPS sinstance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SENS_EN_MAGSIM", "rebootRequired": true, "shortDesc": "Enable simulated magnetometer sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": -1, "group": "Sensors", "name": "SENS_EN_THERMAL", "shortDesc": "Thermal control of sensor temperature", "type": "Int32", "values": [{"description": "Thermal control unavailable", "value": -1}, {"description": "Thermal control off", "value": 0}, {"description": "Thermal control enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Probe for optional external I2C devices.", "name": "SENS_EXT_I2C_PRB", "shortDesc": "External I2C probe", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 70.0, "group": "Sensors", "longDesc": "Optical flow data maximum publication rate. This is an upper bound,\nactual optical flow data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_FLOW_RATE", "rebootRequired": true, "shortDesc": "Optical flow max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "This parameter defines the yaw rotation of the optical flow relative to the vehicle body frame.\nZero rotation is defined as X on flow board pointing towards front of vehicle.", "name": "SENS_FLOW_ROT", "shortDesc": "Optical flow rotation", "type": "Int32", "values": [{"description": "No rotation", "value": 0}, {"description": "Yaw 45\u00b0", "value": 1}, {"description": "Yaw 90\u00b0", "value": 2}, {"description": "Yaw 135\u00b0", "value": 3}, {"description": "Yaw 180\u00b0", "value": 4}, {"description": "Yaw 225\u00b0", "value": 5}, {"description": "Yaw 270\u00b0", "value": 6}, {"description": "Yaw 315\u00b0", "value": 7}]}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Sensors", "max": 1.5, "min": 0.5, "name": "SENS_FLOW_SCALE", "shortDesc": "Optical flow scale factor", "type": "Float"}, {"bitmask": [{"description": "use speed accuracy", "index": 0}, {"description": "use hpos accuracy", "index": 1}, {"description": "use vpos accuracy", "index": 2}], "category": "Standard", "default": 7, "group": "Sensors", "longDesc": "Set bits in the following positions to set which GPS accuracy metrics will be used to calculate the blending weight. Set to zero to disable and always used first GPS instance.\n0 : Set to true to use speed accuracy\n1 : Set to true to use horizontal position accuracy\n2 : Set to true to use vertical position accuracy", "max": 7, "min": 0, "name": "SENS_GPS_MASK", "shortDesc": "Multi GPS Blending Control Mask", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Sensors", "longDesc": "When no blending is active, this defines the preferred GPS receiver instance.\nThe GPS selection logic waits until the primary receiver is available to\nsend data to the EKF even if a secondary instance is already available.\nThe secondary instance is then only used if the primary one times out.\nAccepted values:\n-1 : Auto (equal priority for all instances)\n0 : Main serial GPS instance\n1 : Secondary serial GPS instance\n2-127 : UAVCAN module node ID\nThis parameter has no effect if blending is active.", "max": 127, "min": -1, "name": "SENS_GPS_PRIME", "shortDesc": "Multi GPS primary instance", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 1, "default": 10.0, "group": "Sensors", "longDesc": "Sets the longest time constant that will be applied to the calculation of GPS position and height offsets used to correct data from multiple GPS data for steady state position differences.", "max": 100.0, "min": 1.0, "name": "SENS_GPS_TAU", "shortDesc": "Multi GPS Blending Time Constant", "type": "Float", "units": "s"}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically initialize IMU (accel/gyro) calibration from bias estimates if available.", "name": "SENS_IMU_AUTOCAL", "shortDesc": "IMU auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Notify the user if the IMU is clipping", "name": "SENS_IMU_CLPNOTI", "shortDesc": "IMU notify clipping", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "name": "SENS_IMU_MODE", "rebootRequired": true, "shortDesc": "Sensors hub IMU mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Publish primary IMU selection", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "For systems with an external barometer, this should be set to false to make sure that the external is used.", "name": "SENS_INT_BARO_EN", "rebootRequired": true, "shortDesc": "Enable internal barometers", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "longDesc": "Automatically initialize magnetometer calibration from bias estimate if available.", "name": "SENS_MAG_AUTOCAL", "shortDesc": "Magnetometer auto calibration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Sensors", "longDesc": "During calibration attempt to automatically determine the rotation of external magnetometers.", "name": "SENS_MAG_AUTOROT", "shortDesc": "Automatically set external rotations", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "Sensors", "name": "SENS_MAG_MODE", "rebootRequired": true, "shortDesc": "Sensors hub mag mode", "type": "Int32", "values": [{"description": "Publish all magnetometers", "value": 0}, {"description": "Publish primary magnetometer", "value": 1}]}, {"category": "Standard", "default": 15.0, "group": "Sensors", "longDesc": "Magnetometer data maximum publication rate. This is an upper bound,\nactual magnetometer data rate is still dependent on the sensor.", "max": 200.0, "min": 1.0, "name": "SENS_MAG_RATE", "rebootRequired": true, "shortDesc": "Magnetometer max rate", "type": "Float", "units": "Hz"}, {"category": "Standard", "default": 63, "group": "Sensors", "longDesc": "If set to two side calibration, only the offsets are estimated, the scale\ncalibration is left unchanged. Thus an initial six side calibration is\nrecommended.\nBits:\nORIENTATION_TAIL_DOWN = 1\nORIENTATION_NOSE_DOWN = 2\nORIENTATION_LEFT = 4\nORIENTATION_RIGHT = 8\nORIENTATION_UPSIDE_DOWN = 16\nORIENTATION_RIGHTSIDE_UP = 32", "max": 63, "min": 34, "name": "SENS_MAG_SIDES", "shortDesc": "Bitfield selecting mag sides for calibration", "type": "Int32", "values": [{"description": "Two side calibration", "value": 34}, {"description": "Three side calibration", "value": 38}, {"description": "Six side calibration", "value": 63}]}, {"category": "Standard", "default": 0, "group": "Sensors", "max": 1, "min": 0, "name": "SIM_ARSPD_FAIL", "rebootRequired": true, "shortDesc": "Dynamically simulate failure of airspeed sensor instance", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "Septentrio", "longDesc": "By default, the receiver is automatically configured. Sometimes it may be used for multiple purposes.\nIf the offered parameters aren't sufficient, this parameter can be disabled to have full control of the receiver configuration.\nA good way to use this is to enable automatic configuration, let the receiver be configured, and then disable it to make manual adjustments.", "name": "SEP_AUTO_CONFIG", "rebootRequired": true, "shortDesc": "Toggle automatic receiver configuration", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"bitmask": [{"description": "GPS", "index": 0}, {"description": "GLONASS", "index": 1}, {"description": "Galileo", "index": 2}, {"description": "SBAS", "index": 3}, {"description": "BeiDou", "index": 4}], "category": "Standard", "default": 0, "group": "Septentrio", "longDesc": "Choice of which constellations the receiver should use for PVT computation.\nWhen this is 0, the constellation usage isn't changed.", "max": 63, "min": 0, "name": "SEP_CONST_USAGE", "rebootRequired": true, "shortDesc": "Usage of different constellations", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "Septentrio", "longDesc": "Log raw communication between the driver and connected receivers.\nFor example, \"To receiver\" will log all commands and corrections sent by the driver to the receiver.", "max": 3, "min": 0, "name": "SEP_DUMP_COMM", "shortDesc": "Log GPS communication data", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "From receiver", "value": 1}, {"description": "To receiver", "value": 2}, {"description": "Both", "value": 3}]}, {"category": "Standard", "default": 0, "group": "Septentrio", "longDesc": "Setup and expected use of the hardware.\n- Default: Use two receivers as completely separate instances.\n- Moving base: Use two receivers in a rover & moving base setup for heading.", "max": 1, "min": 0, "name": "SEP_HARDW_SETUP", "rebootRequired": true, "shortDesc": "Setup and expected use of the hardware", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Moving base", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Septentrio", "longDesc": "When the receiver is already set up to log data, this decides whether extra logged data should be added or overwrite existing data.", "name": "SEP_LOG_FORCE", "rebootRequired": true, "shortDesc": "Whether to overwrite or add to existing logging", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "Septentrio", "longDesc": "Select the frequency at which the connected receiver should log data to its internal storage.", "max": 10, "min": 0, "name": "SEP_LOG_HZ", "rebootRequired": true, "shortDesc": "Logging frequency for the receiver", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "0.1 Hz", "value": 1}, {"description": "0.2 Hz", "value": 2}, {"description": "0.5 Hz", "value": 3}, {"description": "1 Hz", "value": 4}, {"description": "2 Hz", "value": 5}, {"description": "5 Hz", "value": 6}, {"description": "10 Hz", "value": 7}, {"description": "20 Hz", "value": 8}, {"description": "25 Hz", "value": 9}, {"description": "50 Hz", "value": 10}]}, {"category": "Standard", "default": 2, "group": "Septentrio", "longDesc": "Select the level of detail that needs to be logged by the receiver.", "max": 3, "min": 0, "name": "SEP_LOG_LEVEL", "rebootRequired": true, "shortDesc": "Logging level for the receiver", "type": "Int32", "values": [{"description": "Lite", "value": 0}, {"description": "Basic", "value": 1}, {"description": "Default", "value": 2}, {"description": "Full", "value": 3}]}, {"category": "Standard", "default": 1, "group": "Septentrio", "longDesc": "The output frequency of the main SBF blocks needed for PVT information.", "max": 3, "min": 0, "name": "SEP_OUTP_HZ", "rebootRequired": true, "shortDesc": "Output frequency of main SBF blocks", "type": "Int32", "values": [{"description": "5 Hz", "value": 0}, {"description": "10 Hz", "value": 1}, {"description": "20 Hz", "value": 2}, {"description": "25 Hz", "value": 3}]}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Septentrio", "longDesc": "Vertical offsets can be compensated for by adjusting the Pitch offset.\nNote that this can be interpreted as the \"roll\" angle in case the antennas are aligned along the perpendicular axis.\nThis occurs in situations where the two antenna ARPs may not be exactly at the same height in the vehicle reference frame.\nSince pitch is defined as the right-handed rotation about the vehicle Y axis,\na situation where the main antenna is mounted lower than the aux antenna (assuming the default antenna setup) will result in a positive pitch.", "max": 90.0, "min": -90.0, "name": "SEP_PITCH_OFFS", "rebootRequired": true, "shortDesc": "Pitch offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 0, "group": "Septentrio", "longDesc": "Enable publication of satellite info (ORB_ID(satellite_info)) if possible.", "name": "SEP_SAT_INFO", "rebootRequired": true, "shortDesc": "Enable sat info", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "Septentrio", "longDesc": "The stream the autopilot sets up on the receiver to output the logging data.\nSet this to another value if the default stream is already used for another purpose.", "max": 10, "min": 1, "name": "SEP_STREAM_LOG", "rebootRequired": true, "shortDesc": "Logging stream used during automatic configuration", "type": "Int32"}, {"category": "Standard", "default": 1, "group": "Septentrio", "longDesc": "The stream the autopilot sets up on the receiver to output the main data.\nSet this to another value if the default stream is already used for another purpose.", "max": 10, "min": 1, "name": "SEP_STREAM_MAIN", "rebootRequired": true, "shortDesc": "Main stream used during automatic configuration", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Septentrio", "longDesc": "Heading offset angle for dual antenna GPS setups that support heading estimation.\nSet this to 0 if the antennas are parallel to the forward-facing direction\nof the vehicle and the rover antenna is in front.\nThe offset angle increases clockwise.\nSet this to 90 if the rover antenna is placed on the\nright side of the vehicle and the moving base antenna is on the left side.", "max": 360.0, "min": -360.0, "name": "SEP_YAW_OFFS", "rebootRequired": true, "shortDesc": "Heading/Yaw offset for dual antenna GPS", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 4, "default": 100.0, "group": "Simulation In Hardware", "increment": 0.01, "max": 1000.0, "min": 0.0, "name": "SIH_DISTSNSR_MAX", "shortDesc": "distance sensor maximum range", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 4, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.01, "max": 10.0, "min": 0.0, "name": "SIH_DISTSNSR_MIN", "shortDesc": "distance sensor minimum range", "type": "Float", "units": "m"}, {"category": "Standard", "default": -1.0, "group": "Simulation In Hardware", "longDesc": "Absolute value superior to 10000 will disable distance sensor", "name": "SIH_DISTSNSR_OVR", "shortDesc": "if >= 0 the distance sensor measures will be overridden by this value", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nIt represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IXX", "shortDesc": "Vehicle inertia about X axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nThis value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IXY", "shortDesc": "Vehicle cross term inertia xy", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nThis value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IXZ", "shortDesc": "Vehicle cross term inertia xz", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nIt represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IYY", "shortDesc": "Vehicle inertia about Y axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nThis value can be set to 0 for a quad symmetric about its center of mass.", "name": "SIH_IYZ", "shortDesc": "Vehicle cross term inertia yz", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.03, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "The inertia is a 3 by 3 symmetric matrix.\nIt represents the difficulty of the vehicle to modify its angular rate.", "min": 0.0, "name": "SIH_IZZ", "shortDesc": "Vehicle inertia about Z axis", "type": "Float", "units": "kg m^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "Physical coefficient representing the friction with air particules.\nThe greater this value, the slower the quad will move.\nDrag force function of velocity: D=-KDV*V.\nThe maximum freefall velocity can be computed as V=10*MASS/KDV [m/s]", "min": 0.0, "name": "SIH_KDV", "shortDesc": "First order drag coefficient", "type": "Float", "units": "N/(m/s)"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.025, "group": "Simulation In Hardware", "increment": 0.005, "longDesc": "Physical coefficient representing the friction with air particules during rotations.\nThe greater this value, the slower the quad will rotate.\nAerodynamic moment function of body rate: Ma=-KDW*W_B.\nThis value can be set to 0 if unknown.", "min": 0.0, "name": "SIH_KDW", "shortDesc": "First order angular damper coefficient", "type": "Float", "units": "Nm/(rad/s)"}, {"category": "Standard", "decimalPlaces": 2, "default": 489.4, "group": "Simulation In Hardware", "increment": 0.01, "longDesc": "This value represents the Above Mean Sea Level (AMSL) altitude where the simulation begins.\nIf using FlightGear as a visual animation,\nthis value can be tweaked such that the vehicle lies on the ground at takeoff.\nLAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others\nto represent a physical ground location on Earth.", "max": 8848.0, "min": -420.0, "name": "SIH_LOC_H0", "shortDesc": "Initial AMSL ground altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 47.397742, "group": "Simulation In Hardware", "longDesc": "This value represents the North-South location on Earth where the simulation begins.\nLAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others\nto represent a physical ground location on Earth.", "max": 90.0, "min": -90.0, "name": "SIH_LOC_LAT0", "shortDesc": "Initial geodetic latitude", "type": "Float", "units": "deg"}, {"category": "Standard", "default": 8.545594, "group": "Simulation In Hardware", "longDesc": "This value represents the East-West location on Earth where the simulation begins.\nLAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others\nto represent a physical ground location on Earth.", "max": 180.0, "min": -180.0, "name": "SIH_LOC_LON0", "shortDesc": "Initial geodetic longitude", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the arm length generating the pitching moment\nThis value can be measured with a ruler.\nThis corresponds to half the distance between the front and rear motors.", "min": 0.0, "name": "SIH_L_PITCH", "shortDesc": "Pitch arm length", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.2, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the arm length generating the rolling moment\nThis value can be measured with a ruler.\nThis corresponds to half the distance between the left and right motors.", "min": 0.0, "name": "SIH_L_ROLL", "shortDesc": "Roll arm length", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "Simulation In Hardware", "increment": 0.1, "longDesc": "This value can be measured by weighting the quad on a scale.", "min": 0.0, "name": "SIH_MASS", "shortDesc": "Vehicle mass", "type": "Float", "units": "kg"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.1, "group": "Simulation In Hardware", "increment": 0.05, "longDesc": "This is the maximum torque delivered by one propeller\nwhen the motor is running at full speed.\nThis value is usually about few percent of the maximum thrust force.", "min": 0.0, "name": "SIH_Q_MAX", "shortDesc": "Max propeller torque", "type": "Float", "units": "Nm"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "Simulation In Hardware", "increment": 0.5, "longDesc": "This is the maximum force delivered by one propeller\nwhen the motor is running at full speed.\nThis value is usually about 5 times the mass of the quadrotor.", "min": 0.0, "name": "SIH_T_MAX", "shortDesc": "Max propeller thrust force", "type": "Float", "units": "N"}, {"category": "Standard", "default": 0.05, "group": "Simulation In Hardware", "longDesc": "the time taken for the thruster to step from 0 to 100% should be about 4 times tau", "name": "SIH_T_TAU", "shortDesc": "thruster time constant tau", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "Simulation In Hardware", "name": "SIH_VEHICLE_TYPE", "rebootRequired": true, "shortDesc": "Vehicle type", "type": "Int32", "values": [{"description": "Quadcopter", "value": 0}, {"description": "Fixed-Wing", "value": 1}, {"description": "Tailsitter", "value": 2}, {"description": "Standard VTOL", "value": 3}, {"description": "Hexacopter", "value": 4}, {"description": "Rover Ackermann", "value": 5}]}, {"bitmask": [{"description": "Stuck", "index": 0}, {"description": "Drift", "index": 1}], "category": "Standard", "default": 0, "group": "Simulator", "longDesc": "Stuck: freeze the measurement to the current location\nDrift: add a linearly growing bias to the sensor data", "max": 3, "min": 0, "name": "SIM_AGP_FAIL", "shortDesc": "AGP failure mode", "type": "Int32"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_BARO_OFF_P", "shortDesc": "simulated barometer pressure offset", "type": "Float"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_BARO_OFF_T", "shortDesc": "simulated barometer temperature offset", "type": "Float", "units": "celcius"}, {"category": "Standard", "default": 10, "group": "Simulator", "max": 50, "min": 0, "name": "SIM_GPS_USED", "shortDesc": "simulated GPS number of satellites used", "type": "Int32"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_X", "shortDesc": "simulated magnetometer X offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_Y", "shortDesc": "simulated magnetometer Y offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0.0, "group": "Simulator", "name": "SIM_MAG_OFFSET_Z", "shortDesc": "simulated magnetometer Z offset", "type": "Float", "units": "gauss"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "Set to 1 to reset parameters on next system startup (setting defaults).\nPlatform-specific values are used if available.\nRC* parameters are preserved.", "name": "SYS_AUTOCONFIG", "shortDesc": "Automatically configure default values", "type": "Int32", "values": [{"description": "Keep parameters", "value": 0}, {"description": "Reset parameters to airframe defaults", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "CHANGING THIS VALUE REQUIRES A RESTART. Defines the auto-start script used to bootstrap the system.", "max": 9999999, "min": 0, "name": "SYS_AUTOSTART", "rebootRequired": true, "shortDesc": "Auto-start script index", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled, update the bootloader on the next boot.\nWARNING: do not cut the power during an update process, otherwise you will\nhave to recover using some alternative method (e.g. JTAG).\nInstructions:\n- Insert an SD card\n- Enable this parameter\n- Reboot the board (plug the power or send a reboot command)\n- Wait until the board comes back up (or at least 2 minutes)\n- If it does not come back, check the file bootlog.txt on the SD card", "name": "SYS_BL_UPDATE", "rebootRequired": true, "shortDesc": "Bootloader update", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing\n1 : Set to 1 to start a calibration at next boot\nThis parameter is reset to zero when the temperature calibration starts.\ndefault (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_ACCEL", "shortDesc": "Enable auto start of accelerometer thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing\n1 : Set to 1 to start a calibration at next boot\nThis parameter is reset to zero when the temperature calibration starts.\ndefault (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_BARO", "shortDesc": "Enable auto start of barometer thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "0 : Set to 0 to do nothing\n1 : Set to 1 to start a calibration at next boot\nThis parameter is reset to zero when the temperature calibration starts.\ndefault (0, no calibration)", "max": 1, "min": 0, "name": "SYS_CAL_GYRO", "shortDesc": "Enable auto start of rate gyro thermal calibration at the next power up", "type": "Int32"}, {"category": "Standard", "default": 24, "group": "System", "longDesc": "A temperature increase greater than this value is required during calibration.\nCalibration will complete for each sensor when the temperature increase above the starting temperature exceeds the value set by SYS_CAL_TDEL.\nIf the temperature rise is insufficient, the calibration will continue indefinitely and the board will need to be repowered to exit.", "min": 10, "name": "SYS_CAL_TDEL", "shortDesc": "Required temperature rise during thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 10, "group": "System", "longDesc": "Temperature calibration will not start if the temperature of any sensor is higher than the value set by SYS_CAL_TMAX.", "name": "SYS_CAL_TMAX", "shortDesc": "Maximum starting temperature for thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 5, "group": "System", "longDesc": "Temperature calibration for each sensor will ignore data if the temperature is lower than the value set by SYS_CAL_TMIN.", "name": "SYS_CAL_TMIN", "shortDesc": "Minimum starting temperature for thermal calibration", "type": "Int32", "units": "celcius"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If the board supports persistent storage (i.e., the KConfig variable DATAMAN_PERSISTENT_STORAGE is set),\nthe 'Default storage' backend uses a file on persistent storage. If not supported, this backend uses\nnon-persistent storage in RAM.", "name": "SYS_DM_BACKEND", "rebootRequired": true, "shortDesc": "Dataman storage backend", "type": "Int32", "values": [{"description": "Dataman disabled", "value": -1}, {"description": "Default storage", "value": 0}, {"description": "RAM storage", "value": 1}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled, future sensor calibrations will be stored to /fs/mtd_caldata.\nNote: this is only supported on boards with a separate calibration storage\n/fs/mtd_caldata.", "name": "SYS_FAC_CAL_MODE", "shortDesc": "Enable factory calibration mode", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "All sensors", "value": 1}, {"description": "All sensors except mag", "value": 2}]}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "If enabled allows MAVLink INJECT_FAILURE commands.\nWARNING: the failures can easily cause crashes and are to be used with caution!", "name": "SYS_FAILURE_EN", "shortDesc": "Enable failure injection", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "Disable this if the board has no barometer, such as some of the Omnibus\nF4 SD variants.\nIf disabled, the preflight checks will not check for the presence of a\nbarometer.", "name": "SYS_HAS_BARO", "rebootRequired": true, "shortDesc": "Control if the vehicle has a barometer", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "Disable this if the system has no GPS.\nIf disabled, the sensors hub will not process sensor_gps,\nand GPS will not be available for the rest of the system.", "name": "SYS_HAS_GPS", "rebootRequired": true, "shortDesc": "Control if the vehicle has a GPS", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "0: System has no magnetometer, preflight checks should pass without one.\n1-N: Require the presence of N magnetometer sensors for check to pass.", "name": "SYS_HAS_MAG", "rebootRequired": true, "shortDesc": "Control if and how many magnetometers are expected", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "Set this to 0 if the board has no airspeed sensor.\nIf set to 0, the preflight checks will not check for the presence of an\nairspeed sensor.", "max": 1, "min": 0, "name": "SYS_HAS_NUM_ASPD", "shortDesc": "Control if the vehicle has an airspeed sensor", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "The preflight check will fail if fewer than this number of distance sensors with valid data is present.\nDisable the check with 0.", "max": 4, "min": 0, "name": "SYS_HAS_NUM_DIST", "shortDesc": "Number of distance sensors to check being available", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "The preflight check will fail if fewer than this number of optical flow sensors with valid data are present.", "max": 1, "min": 0, "name": "SYS_HAS_NUM_OF", "shortDesc": "Number of optical flow sensors required to be available", "type": "Int32"}, {"category": "Standard", "default": 0, "group": "System", "longDesc": "While enabled the system will boot in Hardware-In-The-Loop (HITL)\nor Simulation-In-Hardware (SIH) mode and not enable all sensors and checks.\nWhen disabled the same vehicle can be flown normally.\nSet to 'external HITL', if the system should perform as if it were a real\nvehicle (the only difference to a real system is then only the parameter\nvalue, which can be used for log analysis).", "name": "SYS_HITL", "rebootRequired": true, "shortDesc": "Enable HITL/SIH mode on next boot", "type": "Int32", "values": [{"description": "external HITL", "value": -1}, {"description": "HITL and SIH disabled", "value": 0}, {"description": "HITL enabled", "value": 1}, {"description": "SIH enabled", "value": 2}]}, {"category": "Standard", "default": 1, "group": "System", "longDesc": "This is used internally only: an airframe configuration might set an expected\nparameter version value via PARAM_DEFAULTS_VER. This is checked on bootup\nagainst SYS_PARAM_VER, and if they do not match, parameters are reset and\nreloaded from the airframe configuration.", "min": 0, "name": "SYS_PARAM_VER", "shortDesc": "Parameter version", "type": "Int32"}, {"category": "Standard", "default": 1.0, "group": "System", "longDesc": "Set to 0 to disable, 1 for maximum brightness", "name": "SYS_RGB_MAXBRT", "shortDesc": "RGB Led brightness limit", "type": "Float", "units": "%"}, {"category": "Standard", "default": 1, "group": "System", "name": "SYS_STCK_EN", "shortDesc": "Enable stack checking", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 2, "group": "Testing", "name": "TEST_1", "shortDesc": "TEST_1", "type": "Int32"}, {"category": "Standard", "default": 4, "group": "Testing", "name": "TEST_2", "shortDesc": "TEST_2", "type": "Int32"}, {"category": "Standard", "default": 5.0, "group": "Testing", "name": "TEST_3", "shortDesc": "TEST_3", "type": "Float"}, {"category": "Standard", "default": 0.01, "group": "Testing", "name": "TEST_D", "shortDesc": "TEST_D", "type": "Float"}, {"category": "Standard", "default": 2.0, "group": "Testing", "name": "TEST_DEV", "shortDesc": "TEST_DEV", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_D_LP", "shortDesc": "TEST_D_LP", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_HP", "shortDesc": "TEST_HP", "type": "Float"}, {"category": "Standard", "default": 0.1, "group": "Testing", "name": "TEST_I", "shortDesc": "TEST_I", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_I_MAX", "shortDesc": "TEST_I_MAX", "type": "Float"}, {"category": "Standard", "default": 10.0, "group": "Testing", "name": "TEST_LP", "shortDesc": "TEST_LP", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_MAX", "shortDesc": "TEST_MAX", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "Testing", "name": "TEST_MEAN", "shortDesc": "TEST_MEAN", "type": "Float"}, {"category": "Standard", "default": -1.0, "group": "Testing", "name": "TEST_MIN", "shortDesc": "TEST_MIN", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "Testing", "name": "TEST_P", "shortDesc": "TEST_P", "type": "Float"}, {"category": "Standard", "default": 12345678, "group": "Testing", "name": "TEST_PARAMS", "shortDesc": "TEST_PARAMS", "type": "Int32"}, {"category": "Standard", "default": 16, "group": "Testing", "name": "TEST_RC2_X", "shortDesc": "TEST_RC2_X", "type": "Int32"}, {"category": "Standard", "default": 8, "group": "Testing", "name": "TEST_RC_X", "shortDesc": "TEST_RC_X", "type": "Int32"}, {"category": "Standard", "default": 0.5, "group": "Testing", "name": "TEST_TRIM", "shortDesc": "TEST_TRIM", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A0_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A0_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A0_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A0_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A1_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A1_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A1_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A1_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A2_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A2_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A2_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A2_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_A3_ID", "shortDesc": "ID of Accelerometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_A3_TMAX", "shortDesc": "Accelerometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_TMIN", "shortDesc": "Accelerometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_A3_TREF", "shortDesc": "Accelerometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_0", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_1", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X0_2", "shortDesc": "Accelerometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_0", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_1", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X1_2", "shortDesc": "Accelerometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_0", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_1", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X2_2", "shortDesc": "Accelerometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_0", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_1", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_A3_X3_2", "shortDesc": "Accelerometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_A_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for accelerometer sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B0_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B0_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B0_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B0_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B0_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B1_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B1_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B1_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B1_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B1_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B2_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B2_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B2_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B2_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B2_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_B3_ID", "shortDesc": "ID of Barometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 75.0, "group": "Thermal Compensation", "name": "TC_B3_TMAX", "shortDesc": "Barometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 5.0, "group": "Thermal Compensation", "name": "TC_B3_TMIN", "shortDesc": "Barometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 40.0, "group": "Thermal Compensation", "name": "TC_B3_TREF", "shortDesc": "Barometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X0", "shortDesc": "Barometer offset temperature ^0 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X1", "shortDesc": "Barometer offset temperature ^1 polynomial coefficients", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X2", "shortDesc": "Barometer offset temperature ^2 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X3", "shortDesc": "Barometer offset temperature ^3 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X4", "shortDesc": "Barometer offset temperature ^4 polynomial coefficient", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_B3_X5", "shortDesc": "Barometer offset temperature ^5 polynomial coefficient", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_B_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for barometric pressure sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G0_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G0_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G0_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G0_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G1_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G1_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G1_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G1_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G2_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G2_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G2_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G2_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_G3_ID", "shortDesc": "ID of Gyro that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_G3_TMAX", "shortDesc": "Gyro calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_TMIN", "shortDesc": "Gyro calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_G3_TREF", "shortDesc": "Gyro calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_0", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_1", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X0_2", "shortDesc": "Gyro rate offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_0", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_1", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X1_2", "shortDesc": "Gyro rate offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_0", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_1", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X2_2", "shortDesc": "Gyro rate offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_0", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_1", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_G3_X3_2", "shortDesc": "Gyro rate offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_G_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for rate gyro sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M0_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M0_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M0_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M0_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M1_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M1_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M1_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M1_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M2_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M2_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M2_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M2_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0, "group": "Thermal Compensation", "name": "TC_M3_ID", "shortDesc": "ID of Magnetometer that the calibration is for", "type": "Int32"}, {"category": "System", "default": 100.0, "group": "Thermal Compensation", "name": "TC_M3_TMAX", "shortDesc": "Magnetometer calibration maximum temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_TMIN", "shortDesc": "Magnetometer calibration minimum temperature", "type": "Float"}, {"category": "System", "default": 25.0, "group": "Thermal Compensation", "name": "TC_M3_TREF", "shortDesc": "Magnetometer calibration reference temperature", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_0", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_1", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X0_2", "shortDesc": "Magnetometer offset temperature ^0 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_0", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_1", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X1_2", "shortDesc": "Magnetometer offset temperature ^1 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_0", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_1", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X2_2", "shortDesc": "Magnetometer offset temperature ^2 polynomial coefficient - Z axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_0", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - X axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_1", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Y axis", "type": "Float"}, {"category": "System", "default": 0.0, "group": "Thermal Compensation", "name": "TC_M3_X3_2", "shortDesc": "Magnetometer offset temperature ^3 polynomial coefficient - Z axis", "type": "Float"}, {"category": "Standard", "default": 0, "group": "Thermal Compensation", "name": "TC_M_ENABLE", "rebootRequired": true, "shortDesc": "Thermal compensation for magnetometer sensors", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_MGM_PITCH", "shortDesc": "Pitch gain for manual inputs in manual control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_MGM_ROLL", "shortDesc": "Roll gain for manual inputs in manual control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_MGM_THRTL", "shortDesc": "Throttle gain for manual inputs in manual control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.05, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_MGM_YAW", "shortDesc": "Yaw gain for manual inputs in manual control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_PITCH_D", "shortDesc": "Pitch differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_PITCH_P", "shortDesc": "Pitch proportional gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 100.0, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_RGM_PITCH", "shortDesc": "Pitch gain for manual inputs in rate control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 100.0, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_RGM_ROLL", "shortDesc": "Roll gain for manual inputs in rate control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_RGM_THRTL", "shortDesc": "Throttle gain for manual inputs in rate control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 100.0, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_RGM_YAW", "shortDesc": "Yaw gain for manual inputs in rate control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.5, "group": "UUV Attitude Control", "name": "UUV_ROLL_D", "shortDesc": "Roll differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_ROLL_P", "shortDesc": "Roll proportional gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_SGM_PITCH", "shortDesc": "Pitch gain for manual inputs in attitude control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_SGM_ROLL", "shortDesc": "Roll gain for manual inputs in attitude control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_SGM_THRTL", "shortDesc": "Throttle gain for manual inputs in attitude control mode", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.5, "group": "UUV Attitude Control", "min": 0.0, "name": "UUV_SGM_YAW", "shortDesc": "Yaw gain for manual inputs in attitude control mode", "type": "Float"}, {"category": "Standard", "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_SP_MAX_AGE", "shortDesc": "Maximum time (in seconds) before resetting setpoint", "type": "Float"}, {"category": "Standard", "default": 0, "group": "UUV Attitude Control", "max": 1, "min": 0, "name": "UUV_STICK_MODE", "shortDesc": "Stick mode selector (0=Heave/sway control, roll/pitch leveled; 1=Pitch/roll control)", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "UUV Attitude Control", "max": 1.0, "min": 0.0, "name": "UUV_THRUST_SAT", "shortDesc": "UUV Thrust setpoint Saturation", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.3, "group": "UUV Attitude Control", "max": 1.0, "min": 0.0, "name": "UUV_TORQUE_SAT", "shortDesc": "UUV Torque setpoint Saturation", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "UUV Attitude Control", "name": "UUV_YAW_D", "shortDesc": "Yaw differential gain", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 4.0, "group": "UUV Attitude Control", "name": "UUV_YAW_P", "shortDesc": "Yawh proportional gain", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_X_D", "shortDesc": "Gain of D controller X", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_X_P", "shortDesc": "Gain of P controller X", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_Y_D", "shortDesc": "Gain of D controller Y", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_Y_P", "shortDesc": "Gain of P controller Y", "type": "Float"}, {"category": "Standard", "default": 0.2, "group": "UUV Position Control", "name": "UUV_GAIN_Z_D", "shortDesc": "Gain of D controller Z", "type": "Float"}, {"category": "Standard", "default": 1.0, "group": "UUV Position Control", "name": "UUV_GAIN_Z_P", "shortDesc": "Gain of P controller Z", "type": "Float"}, {"category": "Standard", "default": 0.5, "group": "UUV Position Control", "name": "UUV_PGM_VEL", "shortDesc": "Gain for position control velocity setpoint update", "type": "Float"}, {"category": "Standard", "default": 1, "group": "UUV Position Control", "name": "UUV_POS_MODE", "shortDesc": "Stabilization mode(1) or Position Control(0)", "type": "Int32", "values": [{"description": "Moves position setpoint in world frame", "value": 0}, {"description": "Moves position setpoint in body frame", "value": 1}]}, {"category": "Standard", "default": 0.1, "group": "UUV Position Control", "name": "UUV_POS_STICK_DB", "shortDesc": "Deadband for changing position setpoint", "type": "Float"}, {"category": "Standard", "default": 1, "group": "UUV Position Control", "name": "UUV_STAB_MODE", "shortDesc": "Stabilization mode(1) or Position Control(0)", "type": "Int32", "values": [{"description": "Tracks previous attitude setpoint", "value": 0}, {"description": "Tracks horizontal attitude (allows yaw change)", "value": 1}]}, {"category": "Standard", "default": 2130706433, "group": "UXRCE-DDS Client", "longDesc": "If ethernet is enabled and is the selected configuration for uXRCE-DDS,\nthe selected Agent IP address will be set and used.\nDecimal dot notation is not supported. IP address must be provided\nin int32 format. For example, 192.168.1.2 is mapped to -1062731518;\n127.0.0.1 is mapped to 2130706433.", "name": "UXRCE_DDS_AG_IP", "rebootRequired": true, "shortDesc": "uXRCE-DDS Agent IP address", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "uXRCE-DDS domain ID", "name": "UXRCE_DDS_DOM_ID", "rebootRequired": true, "shortDesc": "uXRCE-DDS domain ID", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "This is used to enable flow control for the serial uXRCE instance.\nUsed for reliable high bandwidth communication.", "name": "UXRCE_DDS_FLCTRL", "rebootRequired": true, "shortDesc": "Enable serial flow control for UXRCE interface", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "UXRCE-DDS Client", "longDesc": "uXRCE-DDS key, must be different from zero.\nIn a single agent - multi client configuration, each client\nmust have a unique session key.", "name": "UXRCE_DDS_KEY", "rebootRequired": true, "shortDesc": "uXRCE-DDS session key", "type": "Int32"}, {"category": "System", "default": -1, "group": "UXRCE-DDS Client", "longDesc": "Defines an index-based namespace for DDS messages, e.g, uav_0, uav_1, up to uav_9999\nA value less than zero leaves the namespace empty", "max": 9999, "min": -1, "name": "UXRCE_DDS_NS_IDX", "rebootRequired": true, "shortDesc": "Define an index-based message namespace", "type": "Int32"}, {"category": "Standard", "default": 8888, "group": "UXRCE-DDS Client", "longDesc": "If ethernet is enabled and is the selected configuration for uXRCE-DDS,\nthe selected UDP port will be set and used.", "max": 65535, "min": 0, "name": "UXRCE_DDS_PRT", "rebootRequired": true, "shortDesc": "uXRCE-DDS UDP port", "type": "Int32"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "Set the participant configuration on the Agent's system.\n0: Use the default configuration.\n1: Restrict messages to localhost\n(use in combination with ROS_LOCALHOST_ONLY=1).\n2: Use a custom participant with the profile name \"px4_participant\".", "max": 2, "min": 0, "name": "UXRCE_DDS_PTCFG", "rebootRequired": true, "shortDesc": "uXRCE-DDS participant configuration", "type": "Int32", "values": [{"description": "Default", "value": 0}, {"description": "Localhost-only", "value": 1}, {"description": "Custom participant", "value": 2}]}, {"category": "System", "default": -1, "group": "UXRCE-DDS Client", "longDesc": "Specifies after how many seconds without receiving data the DDS connection is reestablished.\nA value less than one disables the RX rate timeout.", "name": "UXRCE_DDS_RX_TO", "rebootRequired": true, "shortDesc": "RX rate timeout configuration", "type": "Int32", "units": "s"}, {"category": "System", "default": 0, "group": "UXRCE-DDS Client", "longDesc": "When enabled along with UXRCE_DDS_SYNCT, uxrce_dds_client will set the system clock using the agents UTC timestamp.", "name": "UXRCE_DDS_SYNCC", "rebootRequired": true, "shortDesc": "Enable uXRCE-DDS system clock synchronization", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 1, "group": "UXRCE-DDS Client", "longDesc": "When enabled, uxrce_dds_client will synchronize the timestamps of the incoming and outgoing messages measuring the offset between the Agent OS time and the PX4 time.", "name": "UXRCE_DDS_SYNCT", "rebootRequired": true, "shortDesc": "Enable uXRCE-DDS timestamp synchronization", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "System", "default": 3, "group": "UXRCE-DDS Client", "longDesc": "Specifies after how many seconds without sending data the DDS connection is reestablished.\nA value less than one disables the TX rate timeout.", "name": "UXRCE_DDS_TX_TO", "rebootRequired": true, "shortDesc": "TX rate timeout configuration", "type": "Int32", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 8.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Airspeed at which we can start blending both fw and mc controls. Set to 0 to disable.", "max": 30.0, "min": 0.0, "name": "VT_ARSP_BLEND", "shortDesc": "Transition blending airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Airspeed at which we can switch to fw mode", "max": 30.0, "min": 0.0, "name": "VT_ARSP_TRANS", "shortDesc": "Transition airspeed", "type": "Float", "units": "m/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Time in seconds it takes to tilt form VT_TILT_FW to VT_TILT_MC.", "max": 10.0, "min": 0.1, "name": "VT_BT_TILT_DUR", "shortDesc": "Duration motor tilt up in backtransition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "VTOL Attitude Control", "increment": 0.05, "max": 0.3, "min": 0.0, "name": "VT_B_DEC_I", "shortDesc": "Backtransition deceleration setpoint to tilt I gain", "type": "Float", "units": "rad s/m"}, {"category": "Standard", "decimalPlaces": 2, "default": 2.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Used to calculate back transition distance in an auto mode.\nFor standard vtol and tiltrotors a controller is used to track this value during the transition.", "max": 10.0, "min": 0.5, "name": "VT_B_DEC_MSS", "shortDesc": "Approximate deceleration during back transition", "type": "Float", "units": "m/s^2"}, {"category": "Standard", "decimalPlaces": 2, "default": 10.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Transition is also declared over if the groundspeed drops below MPC_XY_CRUISE.", "max": 20.0, "min": 0.1, "name": "VT_B_TRANS_DUR", "shortDesc": "Maximum duration of a back transition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 3.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "This sets the duration during which the MC motors ramp up to the commanded thrust during the back transition stage.", "max": 20.0, "min": 0.0, "name": "VT_B_TRANS_RAMP", "shortDesc": "Back transition MC motor ramp up time", "type": "Float", "units": "s"}, {"category": "Standard", "default": 1, "group": "VTOL Attitude Control", "longDesc": "If set to 1 the control surfaces are locked at the disarmed value in multicopter mode.", "name": "VT_ELEV_MC_LOCK", "shortDesc": "Lock control surfaces in hover", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled", "value": 1}]}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Prevents downforce from pitching the body down when facing wind.\nUses puller/pusher (standard VTOL), or forward-tilt (tiltrotor VTOL) to accelerate forward instead.\nOnly active if demanded pitch is below VT_PITCH_MIN.\nUse VT_FWD_THRUST_SC to tune it.\nDescend mode is treated as Landing too.\nOnly active (if enabled) in height-rate controlled modes.", "name": "VT_FWD_THRUST_EN", "shortDesc": "Use fixed-wing actuation in hover to accelerate forward", "type": "Int32", "values": [{"description": "Disabled", "value": 0}, {"description": "Enabled (except LANDING)", "value": 1}, {"description": "Enabled if above MPC_LAND_ALT1", "value": 2}, {"description": "Enabled if above MPC_LAND_ALT2", "value": 3}, {"description": "Enabled constantly", "value": 4}, {"description": "Enabled if above MPC_LAND_ALT1 (except LANDING)", "value": 5}, {"description": "Enabled if above MPC_LAND_ALT2 (except LANDING)", "value": 6}]}, {"category": "Standard", "decimalPlaces": 2, "default": 0.7, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Scale applied to the demanded pitch (below VT_PITCH_MIN) to get the fixed-wing forward actuation in hover mode.\nEnabled via VT_FWD_THRUST_EN.", "max": 5.0, "min": 0.0, "name": "VT_FWD_THRUST_SC", "shortDesc": "Fixed-wing actuation thrust scale in hover", "type": "Float"}, {"bitmask": [{"description": "Yaw", "index": 0}, {"description": "Roll", "index": 1}, {"description": "Pitch", "index": 2}], "category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Enable differential thrust seperately for roll, pitch, yaw in forward (fixed-wing) mode.\nThe effectiveness of differential thrust around the corresponding axis can be\ntuned by setting VT_FW_DIFTHR_S_R / VT_FW_DIFTHR_S_P / VT_FW_DIFTHR_S_Y.", "max": 7, "min": 0, "name": "VT_FW_DIFTHR_EN", "shortDesc": "Differential thrust in forwards flight", "type": "Int32"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_P", "shortDesc": "Pitch differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_R", "shortDesc": "Roll differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.1, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN.", "max": 2.0, "min": 0.0, "name": "VT_FW_DIFTHR_S_Y", "shortDesc": "Yaw differential thrust factor in forward flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Minimum altitude for fixed-wing flight. When the vehicle is in fixed-wing mode\nand the altitude drops below this altitude (relative altitude above local origin),\nit will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT.", "max": 200.0, "min": 0.0, "name": "VT_FW_MIN_ALT", "shortDesc": "Quad-chute altitude", "type": "Float", "units": "m"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "increment": 1, "longDesc": "Maximum height above the ground (if available, otherwise above\nHome if available, otherwise above the local origin) where triggering a quad-chute is possible.\nAt high altitudes there is a big risk to deplete the battery and therefore crash if quad-chuting there.", "min": 0, "name": "VT_FW_QC_HMAX", "shortDesc": "Quad-chute maximum height", "type": "Int32", "units": "m"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Absolute pitch threshold for quad-chute triggering in FW mode.\nAbove this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT.\nSet to 0 do disable this threshold.", "max": 180, "min": 0, "name": "VT_FW_QC_P", "shortDesc": "Quad-chute max pitch threshold", "type": "Int32", "units": "deg"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "longDesc": "Absolute roll threshold for quad-chute triggering in FW mode.\nAbove this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT.\nSet to 0 do disable this threshold.", "max": 180, "min": 0, "name": "VT_FW_QC_R", "shortDesc": "Quad-chute max roll threshold", "type": "Int32", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 5.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Time in seconds used for a transition", "max": 20.0, "min": 0.1, "name": "VT_F_TRANS_DUR", "shortDesc": "Duration of a front transition", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_F_TRANS_THR", "shortDesc": "Target throttle value for the transition to fixed-wing flight", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 6.0, "group": "VTOL Attitude Control", "increment": 0.5, "longDesc": "The duration of the front transition when there is no airspeed feedback available.\nWhen airspeed is used, transition timeout is declared if airspeed does not\nreach VT_ARSP_BLEND after this time.", "max": 30.0, "min": 1.0, "name": "VT_F_TR_OL_TM", "shortDesc": "Airspeed-less front transition time (open loop)", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Overrides VT_PITCH_MIN when the vehicle is in LAND mode (hovering).\nDuring landing it can be beneficial to reduce the pitch angle to reduce the generated lift in head wind.", "max": 45.0, "min": -10.0, "name": "VT_LND_PITCH_MIN", "shortDesc": "Minimum pitch angle during hover landing", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Any pitch setpoint below this value is translated to a forward force by the fixed-wing forward actuation if\nVT_FWD_TRHUST_EN is set.", "max": 45.0, "min": -10.0, "name": "VT_PITCH_MIN", "shortDesc": "Minimum pitch angle during hover", "type": "Float", "units": "deg"}, {"category": "Standard", "decimalPlaces": 2, "default": 0.33, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Defines the slew rate of the puller/pusher throttle during transitions.\nZero will deactivate the slew rate limiting and thus produce an instant throttle\nrise to the transition throttle VT_F_TRANS_THR.", "min": 0.0, "name": "VT_PSHER_SLEW", "shortDesc": "Pusher throttle ramp up slew rate", "type": "Float", "units": "1/s"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Altitude error threshold for quad-chute triggering during fixed-wing flight.\nThe check is only active if altitude is controlled and the vehicle is below the current altitude reference.\nThe altitude error is relative to the highest altitude the vehicle has achieved since it has flown below the current\naltitude reference.\nSet to 0 do disable.", "max": 200.0, "min": 0.0, "name": "VT_QC_ALT_LOSS", "shortDesc": "Quad-chute uncommanded descent threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 20.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Altitude loss threshold for quad-chute triggering during VTOL transition to fixed-wing flight\nin altitude-controlled flight modes.\nActive until 5s after completing transition to fixed-wing.\nIf the current altitude is more than this value below the altitude at the beginning of the\ntransition, it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT.\nSet to 0 do disable this threshold.", "max": 50.0, "min": 0.0, "name": "VT_QC_T_ALT_LOSS", "shortDesc": "Quad-chute transition altitude loss threshold", "type": "Float", "units": "m"}, {"category": "Standard", "decimalPlaces": 1, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.1, "max": 1.0, "min": -1.0, "name": "VT_SPOILER_MC_LD", "shortDesc": "Spoiler setting while landing (hover)", "type": "Float", "units": "norm"}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_FW", "shortDesc": "Normalized tilt in FW", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.0, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_MC", "shortDesc": "Normalized tilt in Hover", "type": "Float"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.4, "group": "VTOL Attitude Control", "increment": 0.01, "max": 1.0, "min": 0.0, "name": "VT_TILT_TRANS", "shortDesc": "Normalized tilt in transition to FW", "type": "Float"}, {"category": "Standard", "decimalPlaces": 1, "default": 2.0, "group": "VTOL Attitude Control", "increment": 0.1, "longDesc": "Minimum time in seconds for front transition.", "max": 20.0, "min": 0.0, "name": "VT_TRANS_MIN_TM", "shortDesc": "Front transition minimum time", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 3, "default": 0.5, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "Time in seconds it takes to tilt form VT_TILT_TRANS to VT_TILT_FW.", "max": 5.0, "min": 0.1, "name": "VT_TRANS_P2_DUR", "shortDesc": "Duration of front transition phase 2", "type": "Float", "units": "s"}, {"category": "Standard", "decimalPlaces": 2, "default": 15.0, "group": "VTOL Attitude Control", "increment": 1.0, "longDesc": "Time in seconds after which transition will be cancelled.", "max": 30.0, "min": 0.1, "name": "VT_TRANS_TIMEOUT", "shortDesc": "Front transition timeout", "type": "Float", "units": "s"}, {"category": "Standard", "default": 0, "group": "VTOL Attitude Control", "max": 2, "min": 0, "name": "VT_TYPE", "rebootRequired": true, "shortDesc": "VTOL Type (Tailsitter=0, Tiltrotor=1, Standard=2)", "type": "Int32", "values": [{"description": "Tailsitter", "value": 0}, {"description": "Tiltrotor", "value": 1}, {"description": "Standard", "value": 2}]}, {"category": "Standard", "decimalPlaces": 3, "default": 1.0, "group": "VTOL Attitude Control", "increment": 0.01, "longDesc": "The desired gain to convert roll sp into yaw rate sp.", "max": 3.0, "min": 0.0, "name": "WV_GAIN", "shortDesc": "Weather-vane roll angle to yawrate", "type": "Float", "units": "Hz"}, {"category": "Standard", "decimalPlaces": 1, "default": 80.0, "group": "VTOL Takeoff", "increment": 1.0, "longDesc": "Altitude relative to home at which vehicle will loiter after front transition.", "max": 300.0, "min": 20.0, "name": "VTO_LOITER_ALT", "shortDesc": "VTOL Takeoff relative loiter altitude", "type": "Float", "units": "m"}], "translation": {"items": {"parameters": {"list": {"items": {"bitmask": {"list": {"key": "index", "translate": ["description"]}}, "values": {"list": {"key": "value", "translate": ["description"]}}}, "key": "name", "translate": ["shortDesc", "longDesc"], "translate-global": ["category", "group"]}}}}, "version": 1} \ No newline at end of file From d84903d520ef96cfe5db6a31466b1c1fe3e272ff Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Tue, 17 Feb 2026 00:06:29 -0900 Subject: [PATCH 806/812] init.d-posix/airframes/4004_gz_standard_vtol: param set-default VT_PITCH_MIN -5 (#26507) --- ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol | 1 + 1 file changed, 1 insertion(+) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol index 890a01f809..cc8bed693f 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol @@ -101,6 +101,7 @@ param set-default NAV_ACC_RAD 5 param set-default NAV_DLL_ACT 2 param set-default VT_FWD_THRUST_EN 4 +param set-default VT_PITCH_MIN -5 param set-default VT_F_TRANS_THR 1 param set-default VT_TYPE 2 param set-default FD_ESCS_EN 0 From 3a6f566e80187d4651b2f6baaa8d3be2e2137b2d Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Tue, 17 Feb 2026 09:15:19 +0000 Subject: [PATCH 807/812] docs: auto-sync metadata [skip ci] Co-Authored-By: PX4 BuildBot --- docs/en/middleware/dds_topics.md | 364 +++++++++++++++---------------- 1 file changed, 182 insertions(+), 182 deletions(-) diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index 612abca650..cfa995ddf0 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -94,199 +94,199 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages -- [PwmInput](../msg_docs/PwmInput.md) -- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) -- [GeneratorStatus](../msg_docs/GeneratorStatus.md) -- [VehicleAirData](../msg_docs/VehicleAirData.md) -- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) -- [SensorGyro](../msg_docs/SensorGyro.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) -- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) -- [EscStatus](../msg_docs/EscStatus.md) -- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) -- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) -- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) -- [CameraTrigger](../msg_docs/CameraTrigger.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) -- [EscReport](../msg_docs/EscReport.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) -- [HealthReport](../msg_docs/HealthReport.md) -- [SensorGyroFft](../msg_docs/SensorGyroFft.md) -- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [CellularStatus](../msg_docs/CellularStatus.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) -- [GimbalControls](../msg_docs/GimbalControls.md) -- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) -- [RaptorStatus](../msg_docs/RaptorStatus.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) -- [DebugArray](../msg_docs/DebugArray.md) -- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) -- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) -- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [Rpm](../msg_docs/Rpm.md) -- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) -- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [PositionSetpoint](../msg_docs/PositionSetpoint.md) -- [DebugValue](../msg_docs/DebugValue.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [Event](../msg_docs/Event.md) -- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) -- [DeviceInformation](../msg_docs/DeviceInformation.md) -- [UlogStream](../msg_docs/UlogStream.md) - [InputRc](../msg_docs/InputRc.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [GpsDump](../msg_docs/GpsDump.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [SensorUwb](../msg_docs/SensorUwb.md) -- [OrbTestLarge](../msg_docs/OrbTestLarge.md) -- [RoverRateStatus](../msg_docs/RoverRateStatus.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) -- [SystemPower](../msg_docs/SystemPower.md) -- [ActionRequest](../msg_docs/ActionRequest.md) -- [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) -- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) -- [TuneControl](../msg_docs/TuneControl.md) -- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [RaptorInput](../msg_docs/RaptorInput.md) -- [GeofenceStatus](../msg_docs/GeofenceStatus.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [GpioIn](../msg_docs/GpioIn.md) -- [CameraStatus](../msg_docs/CameraStatus.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) -- [VehicleRoi](../msg_docs/VehicleRoi.md) -- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) -- [BatteryInfo](../msg_docs/BatteryInfo.md) -- [GpsInjectData](../msg_docs/GpsInjectData.md) -- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) - [RadioStatus](../msg_docs/RadioStatus.md) -- [LogMessage](../msg_docs/LogMessage.md) -- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [RcParameterMap](../msg_docs/RcParameterMap.md) -- [VehicleImu](../msg_docs/VehicleImu.md) -- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) -- [QshellRetval](../msg_docs/QshellRetval.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) -- [SensorCorrection](../msg_docs/SensorCorrection.md) -- [SatelliteInfo](../msg_docs/SatelliteInfo.md) -- [Vtx](../msg_docs/Vtx.md) -- [GpioOut](../msg_docs/GpioOut.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) -- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) -- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) -- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) -- [SensorBaro](../msg_docs/SensorBaro.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [UlogStreamAck](../msg_docs/UlogStreamAck.md) -- [Mission](../msg_docs/Mission.md) -- [FollowTarget](../msg_docs/FollowTarget.md) -- [Gripper](../msg_docs/Gripper.md) -- [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [AirspeedWind](../msg_docs/AirspeedWind.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) -- [SensorAccel](../msg_docs/SensorAccel.md) -- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [IrlockReport](../msg_docs/IrlockReport.md) -- [GpioRequest](../msg_docs/GpioRequest.md) -- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [SensorTemp](../msg_docs/SensorTemp.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [GpioConfig](../msg_docs/GpioConfig.md) -- [EventV0](../msg_docs/EventV0.md) -- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) -- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) -- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [PowerButtonState](../msg_docs/PowerButtonState.md) -- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [PpsCapture](../msg_docs/PpsCapture.md) -- [EstimatorBias](../msg_docs/EstimatorBias.md) -- [SensorsStatus](../msg_docs/SensorsStatus.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) -- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) -- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) -- [TecsStatus](../msg_docs/TecsStatus.md) -- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) -- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) -- [ParameterUpdate](../msg_docs/ParameterUpdate.md) -- [Cpuload](../msg_docs/Cpuload.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) -- [SensorAirflow](../msg_docs/SensorAirflow.md) -- [AdcReport](../msg_docs/AdcReport.md) -- [LandingGearWheel](../msg_docs/LandingGearWheel.md) -- [RtlStatus](../msg_docs/RtlStatus.md) -- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) -- [Ping](../msg_docs/Ping.md) -- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) - [EstimatorStatus](../msg_docs/EstimatorStatus.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) +- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) - [OrbTestMedium](../msg_docs/OrbTestMedium.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) -- [RcChannels](../msg_docs/RcChannels.md) -- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) -- [Airspeed](../msg_docs/Airspeed.md) -- [EstimatorStates](../msg_docs/EstimatorStates.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) -- [NeuralControl](../msg_docs/NeuralControl.md) -- [SensorSelection](../msg_docs/SensorSelection.md) -- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) -- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) - [LedControl](../msg_docs/LedControl.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [LandingTargetPose](../msg_docs/LandingTargetPose.md) -- [GainCompression](../msg_docs/GainCompression.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) -- [ActuatorTest](../msg_docs/ActuatorTest.md) -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) -- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) +- [Event](../msg_docs/Event.md) +- [CameraCapture](../msg_docs/CameraCapture.md) +- [OrbTestLarge](../msg_docs/OrbTestLarge.md) - [QshellReq](../msg_docs/QshellReq.md) -- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) -- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [Cpuload](../msg_docs/Cpuload.md) +- [GainCompression](../msg_docs/GainCompression.md) +- [Airspeed](../msg_docs/Airspeed.md) +- [IrlockReport](../msg_docs/IrlockReport.md) +- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) - [ButtonEvent](../msg_docs/ButtonEvent.md) -- [ActuatorArmed](../msg_docs/ActuatorArmed.md) +- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) +- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) +- [RcParameterMap](../msg_docs/RcParameterMap.md) +- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [GpsInjectData](../msg_docs/GpsInjectData.md) +- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) +- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) +- [OrbTest](../msg_docs/OrbTest.md) +- [Vtx](../msg_docs/Vtx.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) +- [CellularStatus](../msg_docs/CellularStatus.md) +- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) +- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) +- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) +- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [SensorGyro](../msg_docs/SensorGyro.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) +- [BatteryInfo](../msg_docs/BatteryInfo.md) +- [SensorAccel](../msg_docs/SensorAccel.md) +- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) +- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) +- [GpsDump](../msg_docs/GpsDump.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [VehicleImu](../msg_docs/VehicleImu.md) +- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) +- [ActionRequest](../msg_docs/ActionRequest.md) +- [VehicleRoi](../msg_docs/VehicleRoi.md) +- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) +- [SatelliteInfo](../msg_docs/SatelliteInfo.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) +- [Rpm](../msg_docs/Rpm.md) +- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [SensorSelection](../msg_docs/SensorSelection.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [SystemPower](../msg_docs/SystemPower.md) - [MissionResult](../msg_docs/MissionResult.md) +- [QshellRetval](../msg_docs/QshellRetval.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [PpsCapture](../msg_docs/PpsCapture.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) +- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) +- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) +- [LogMessage](../msg_docs/LogMessage.md) - [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) - [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) -- [MountOrientation](../msg_docs/MountOrientation.md) - [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [GpioOut](../msg_docs/GpioOut.md) +- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) +- [GpioConfig](../msg_docs/GpioConfig.md) +- [LandingTargetPose](../msg_docs/LandingTargetPose.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [PwmInput](../msg_docs/PwmInput.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) +- [SensorCorrection](../msg_docs/SensorCorrection.md) +- [AdcReport](../msg_docs/AdcReport.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [EstimatorStates](../msg_docs/EstimatorStates.md) +- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [GpioRequest](../msg_docs/GpioRequest.md) +- [AirspeedWind](../msg_docs/AirspeedWind.md) +- [GimbalControls](../msg_docs/GimbalControls.md) +- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [SensorBaro](../msg_docs/SensorBaro.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [Mission](../msg_docs/Mission.md) +- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) +- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) +- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [Ping](../msg_docs/Ping.md) +- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [RoverRateStatus](../msg_docs/RoverRateStatus.md) +- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) +- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [ActuatorTest](../msg_docs/ActuatorTest.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) +- [CameraStatus](../msg_docs/CameraStatus.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) +- [HealthReport](../msg_docs/HealthReport.md) +- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) +- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [NeuralControl](../msg_docs/NeuralControl.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) +- [EventV0](../msg_docs/EventV0.md) +- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [PositionSetpoint](../msg_docs/PositionSetpoint.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [GeofenceStatus](../msg_docs/GeofenceStatus.md) +- [SensorUwb](../msg_docs/SensorUwb.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [FuelTankStatus](../msg_docs/FuelTankStatus.md) +- [ActuatorArmed](../msg_docs/ActuatorArmed.md) +- [DifferentialPressure](../msg_docs/DifferentialPressure.md) +- [RcChannels](../msg_docs/RcChannels.md) +- [GpioIn](../msg_docs/GpioIn.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [GeneratorStatus](../msg_docs/GeneratorStatus.md) +- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) +- [SensorHygrometer](../msg_docs/SensorHygrometer.md) +- [PowerButtonState](../msg_docs/PowerButtonState.md) +- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [LandingGearWheel](../msg_docs/LandingGearWheel.md) +- [SensorsStatus](../msg_docs/SensorsStatus.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) +- [RtlStatus](../msg_docs/RtlStatus.md) +- [DeviceInformation](../msg_docs/DeviceInformation.md) +- [CameraTrigger](../msg_docs/CameraTrigger.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [Gripper](../msg_docs/Gripper.md) +- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) +- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) +- [VehicleAirData](../msg_docs/VehicleAirData.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) +- [EscReport](../msg_docs/EscReport.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [UlogStream](../msg_docs/UlogStream.md) +- [FollowTarget](../msg_docs/FollowTarget.md) +- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) +- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) - [MagWorkerData](../msg_docs/MagWorkerData.md) - [SensorMag](../msg_docs/SensorMag.md) -- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) -- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [SensorAirflow](../msg_docs/SensorAirflow.md) +- [DebugValue](../msg_docs/DebugValue.md) ::: From d46a9266cefc6f9bc8afc0189dc1fa6bcc9d6cd5 Mon Sep 17 00:00:00 2001 From: Balduin Date: Tue, 17 Feb 2026 14:34:44 +0100 Subject: [PATCH 808/812] Failsafe docs: document COM_POS_LOW_EPH, COM_POS_LOW_ACT (#26508) * Failsafe docs: document COM_POS_LOW_EPH, COM_POS_LOW_ACT * Failsafe docs: address review --- docs/en/config/safety.md | 37 ++++++++++++++++++++++++++----------- 1 file changed, 26 insertions(+), 11 deletions(-) diff --git a/docs/en/config/safety.md b/docs/en/config/safety.md index f8a224f945..002d09641b 100644 --- a/docs/en/config/safety.md +++ b/docs/en/config/safety.md @@ -181,17 +181,22 @@ The following settings also apply, but are not displayed in the QGC UI. | Preemptive geofence triggering | [GF_PREDICT](../advanced_config/parameter_reference.md#GF_PREDICT) | (Experimental) Trigger geofence if current motion of the vehicle is predicted to trigger the breach (rather than late triggering after the breach). | | Circuit breaker for flight termination | [CBRK_FLIGHTTERM](../advanced_config/parameter_reference.md#CBRK_FLIGHTTERM) | Enables/Disables flight termination action (disabled by default). | -## Position (GNSS) Loss Failsafe +## Position Estimation Failsafes + +This section describes failsafes related to the quality of the vehicle's position estimate. + +### Position Loss Failsafe The _Position Loss Failsafe_ is triggered if the quality of the PX4 position estimate falls below acceptable levels (this might be caused by GPS loss) while in a mode that requires an acceptable position estimate. -The sections below cover first the trigger and then the failsafe action taken by the controller. ### Position Loss Failsafe Trigger -There are basically two mechanisms in PX4 to trigger position failsafes: +The position loss failsafe triggers if the position estimate becomes _invalid_. There are two mechanisms in PX4 to invalidate the position estimate: -- A timeout since the last sensor data was fused that provides direct speed or horizontal position measurements. Sensors that fall into that category are: GNSS, optical flow, airspeed, VIO, auxiliary global position. -- The estimated horizontal position accuracy exceeds a certain threshold. This check is only done on hovering systems (rotary wing vehicles or VTOLs in hover phase). +- A timeout since the last sensor data was fused that provides direct speed or horizontal position measurements. + - Sensors that fall into that category are: GNSS, optical flow, airspeed, VIO, auxiliary global position. +- The estimated horizontal position inaccuracy exceeds the threshold [COM_POS_LOW_EPH](../advanced_config/parameter_reference.md#COM_POS_LOW_EPH) + - This check is only done on hovering systems (rotary-wing vehicles or VTOLs in hover phase). For fixed-wing vehicles, refer to the [Position Accuracy Low](#position-accuracy-low-failsafe) section. The relevant parameters shown below. @@ -207,14 +212,24 @@ Multicopters will switch to [Altitude mode](../flight_modes_mc/altitude.md) if a Fixed-wing planes, and VTOLs not configured to land in hover ([NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT)), have a parameter ([FW_GPSF_LT](../advanced_config/parameter_reference.md#FW_GPSF_LT)) that defines how long they will loiter (circle with a constant roll angle ([FW_GPSF_R](../advanced_config/parameter_reference.md#FW_GPSF_R)) at the current altitude) after losing position before attempting to land. If VTOLs have are configured to switch to hover for landing ([NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT)) then they will first transition and then descend. -The relevant parameters for all vehicles shown below. +The relevant parameters are: -Parameters that only affect Fixed-wing vehicles: +| Parameter | Description | +| ----------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------- | +| [FW_GPSF_LT](../advanced_config/parameter_reference.md#FW_GPSF_LT) | Fixed-wing only: Loiter time (waiting at current altitude for position estimation recovery before starting to descend). Set to 0 to disable. | +| [FW_GPSF_R](../advanced_config/parameter_reference.md#FW_GPSF_R) | Fixed roll/bank angle while circling. | +| [NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT) | If true, force VTOL takeoff and landing, even in `Descend` failsafe. | -| Parameter | Description | -| ----------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------- | -| [FW_GPSF_LT](../advanced_config/parameter_reference.md#FW_GPSF_LT) | Loiter time (waiting for GPS recovery before it goes into land or flight termination). Set to 0 to disable. | -| [FW_GPSF_R](../advanced_config/parameter_reference.md#FW_GPSF_R) | Fixed roll/bank angle while circling. | +### Position Accuracy Low Failsafe + +In Fixed-wing, the position estimate is never strictly invalidated as long as we have a horizontal aiding source, such as an airspeed sensor. In that case, a separate failsafe can be configured that triggers if the position estimate inacuraccy exceeds the threshold [COM_POS_LOW_EPH](../advanced_config/parameter_reference.md#COM_POS_LOW_EPH). The failsafe action is taken if the vehicle is in mission or hold mode, otherwise it is only a warning. The relevant parameters are: + +| Parameter | Description | +| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------| +| [COM_POS_LOW_EPH](../advanced_config/parameter_reference.md#COM_POS_LOW_EPH) | Position inaccuracy threshold above which COM_POS_LOW_ACT is taken. | +| [COM_POS_LOW_ACT](../advanced_config/parameter_reference.md#COM_POS_LOW_ACT) | Failsafe action taken when position inaccuracy is above configured threshold. | + +Note that if there is no horizontal aiding source anymore, the position estimate is invalidated after `EKF2_NOAID_TOUT`, and the standard position loss failsafe applies. ## Offboard Loss Failsafe From d17a5b2c26e29006f45e1df8271d45ed2e667abd Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Tue, 17 Feb 2026 13:41:39 +0000 Subject: [PATCH 809/812] docs: auto-sync metadata [skip ci] Co-Authored-By: PX4 BuildBot --- docs/en/config/safety.md | 16 +- docs/en/middleware/dds_topics.md | 384 +++++++++++++++---------------- 2 files changed, 200 insertions(+), 200 deletions(-) diff --git a/docs/en/config/safety.md b/docs/en/config/safety.md index 002d09641b..f89914c9b0 100644 --- a/docs/en/config/safety.md +++ b/docs/en/config/safety.md @@ -194,9 +194,9 @@ The _Position Loss Failsafe_ is triggered if the quality of the PX4 position est The position loss failsafe triggers if the position estimate becomes _invalid_. There are two mechanisms in PX4 to invalidate the position estimate: - A timeout since the last sensor data was fused that provides direct speed or horizontal position measurements. - - Sensors that fall into that category are: GNSS, optical flow, airspeed, VIO, auxiliary global position. + - Sensors that fall into that category are: GNSS, optical flow, airspeed, VIO, auxiliary global position. - The estimated horizontal position inaccuracy exceeds the threshold [COM_POS_LOW_EPH](../advanced_config/parameter_reference.md#COM_POS_LOW_EPH) - - This check is only done on hovering systems (rotary-wing vehicles or VTOLs in hover phase). For fixed-wing vehicles, refer to the [Position Accuracy Low](#position-accuracy-low-failsafe) section. + - This check is only done on hovering systems (rotary-wing vehicles or VTOLs in hover phase). For fixed-wing vehicles, refer to the [Position Accuracy Low](#position-accuracy-low-failsafe) section. The relevant parameters shown below. @@ -214,18 +214,18 @@ If VTOLs have are configured to switch to hover for landing ([NAV_FORCE_VT](../a The relevant parameters are: -| Parameter | Description | -| ----------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------- | -| [FW_GPSF_LT](../advanced_config/parameter_reference.md#FW_GPSF_LT) | Fixed-wing only: Loiter time (waiting at current altitude for position estimation recovery before starting to descend). Set to 0 to disable. | -| [FW_GPSF_R](../advanced_config/parameter_reference.md#FW_GPSF_R) | Fixed roll/bank angle while circling. | -| [NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT) | If true, force VTOL takeoff and landing, even in `Descend` failsafe. | +| Parameter | Description | +| ----------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------- | +| [FW_GPSF_LT](../advanced_config/parameter_reference.md#FW_GPSF_LT) | Fixed-wing only: Loiter time (waiting at current altitude for position estimation recovery before starting to descend). Set to 0 to disable. | +| [FW_GPSF_R](../advanced_config/parameter_reference.md#FW_GPSF_R) | Fixed roll/bank angle while circling. | +| [NAV_FORCE_VT](../advanced_config/parameter_reference.md#NAV_FORCE_VT) | If true, force VTOL takeoff and landing, even in `Descend` failsafe. | ### Position Accuracy Low Failsafe In Fixed-wing, the position estimate is never strictly invalidated as long as we have a horizontal aiding source, such as an airspeed sensor. In that case, a separate failsafe can be configured that triggers if the position estimate inacuraccy exceeds the threshold [COM_POS_LOW_EPH](../advanced_config/parameter_reference.md#COM_POS_LOW_EPH). The failsafe action is taken if the vehicle is in mission or hold mode, otherwise it is only a warning. The relevant parameters are: | Parameter | Description | -| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------| +| -------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------- | | [COM_POS_LOW_EPH](../advanced_config/parameter_reference.md#COM_POS_LOW_EPH) | Position inaccuracy threshold above which COM_POS_LOW_ACT is taken. | | [COM_POS_LOW_ACT](../advanced_config/parameter_reference.md#COM_POS_LOW_ACT) | Failsafe action taken when position inaccuracy is above configured threshold. | diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index cfa995ddf0..fc2fb68b16 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -94,199 +94,199 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages -- [InputRc](../msg_docs/InputRc.md) -- [RadioStatus](../msg_docs/RadioStatus.md) -- [EstimatorStatus](../msg_docs/EstimatorStatus.md) -- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) -- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) -- [OrbTestMedium](../msg_docs/OrbTestMedium.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [LedControl](../msg_docs/LedControl.md) -- [Event](../msg_docs/Event.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [OrbTestLarge](../msg_docs/OrbTestLarge.md) -- [QshellReq](../msg_docs/QshellReq.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) -- [Cpuload](../msg_docs/Cpuload.md) -- [GainCompression](../msg_docs/GainCompression.md) -- [Airspeed](../msg_docs/Airspeed.md) -- [IrlockReport](../msg_docs/IrlockReport.md) -- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) -- [ButtonEvent](../msg_docs/ButtonEvent.md) -- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) -- [RcParameterMap](../msg_docs/RcParameterMap.md) -- [Px4ioStatus](../msg_docs/Px4ioStatus.md) -- [GpsInjectData](../msg_docs/GpsInjectData.md) -- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [Vtx](../msg_docs/Vtx.md) -- [DebugArray](../msg_docs/DebugArray.md) -- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [CellularStatus](../msg_docs/CellularStatus.md) -- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) -- [RaptorStatus](../msg_docs/RaptorStatus.md) -- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) -- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) -- [SensorGyroFft](../msg_docs/SensorGyroFft.md) -- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) -- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) -- [SensorGyro](../msg_docs/SensorGyro.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [BatteryInfo](../msg_docs/BatteryInfo.md) -- [SensorAccel](../msg_docs/SensorAccel.md) -- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) -- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) - [GpsDump](../msg_docs/GpsDump.md) -- [SensorTemp](../msg_docs/SensorTemp.md) -- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) -- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) -- [VehicleImu](../msg_docs/VehicleImu.md) -- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [ActionRequest](../msg_docs/ActionRequest.md) -- [VehicleRoi](../msg_docs/VehicleRoi.md) -- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) -- [SatelliteInfo](../msg_docs/SatelliteInfo.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) -- [Rpm](../msg_docs/Rpm.md) -- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) -- [TuneControl](../msg_docs/TuneControl.md) -- [SensorSelection](../msg_docs/SensorSelection.md) -- [EstimatorBias](../msg_docs/EstimatorBias.md) -- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) -- [SystemPower](../msg_docs/SystemPower.md) -- [MissionResult](../msg_docs/MissionResult.md) -- [QshellRetval](../msg_docs/QshellRetval.md) -- [EscStatus](../msg_docs/EscStatus.md) -- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) -- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) -- [PpsCapture](../msg_docs/PpsCapture.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) -- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) -- [LogMessage](../msg_docs/LogMessage.md) -- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) -- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) -- [GpioOut](../msg_docs/GpioOut.md) -- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) -- [GpioConfig](../msg_docs/GpioConfig.md) -- [LandingTargetPose](../msg_docs/LandingTargetPose.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [PwmInput](../msg_docs/PwmInput.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) -- [TecsStatus](../msg_docs/TecsStatus.md) -- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) -- [SensorCorrection](../msg_docs/SensorCorrection.md) -- [AdcReport](../msg_docs/AdcReport.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [EstimatorStates](../msg_docs/EstimatorStates.md) -- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) -- [GpioRequest](../msg_docs/GpioRequest.md) -- [AirspeedWind](../msg_docs/AirspeedWind.md) -- [GimbalControls](../msg_docs/GimbalControls.md) -- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) -- [SensorBaro](../msg_docs/SensorBaro.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [RaptorInput](../msg_docs/RaptorInput.md) -- [Mission](../msg_docs/Mission.md) -- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) -- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) -- [Ping](../msg_docs/Ping.md) -- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) -- [RoverRateStatus](../msg_docs/RoverRateStatus.md) -- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) -- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) -- [ParameterUpdate](../msg_docs/ParameterUpdate.md) -- [ActuatorTest](../msg_docs/ActuatorTest.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [CameraStatus](../msg_docs/CameraStatus.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) -- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) -- [HealthReport](../msg_docs/HealthReport.md) -- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) -- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [NeuralControl](../msg_docs/NeuralControl.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) -- [EventV0](../msg_docs/EventV0.md) -- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) -- [PositionSetpoint](../msg_docs/PositionSetpoint.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [GeofenceStatus](../msg_docs/GeofenceStatus.md) -- [SensorUwb](../msg_docs/SensorUwb.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) -- [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [ActuatorArmed](../msg_docs/ActuatorArmed.md) -- [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [RcChannels](../msg_docs/RcChannels.md) -- [GpioIn](../msg_docs/GpioIn.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) -- [GeneratorStatus](../msg_docs/GeneratorStatus.md) -- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) -- [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [PowerButtonState](../msg_docs/PowerButtonState.md) -- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) -- [LandingGearWheel](../msg_docs/LandingGearWheel.md) -- [SensorsStatus](../msg_docs/SensorsStatus.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) -- [RtlStatus](../msg_docs/RtlStatus.md) -- [DeviceInformation](../msg_docs/DeviceInformation.md) -- [CameraTrigger](../msg_docs/CameraTrigger.md) -- [MountOrientation](../msg_docs/MountOrientation.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) -- [Gripper](../msg_docs/Gripper.md) - [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) -- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) -- [VehicleAirData](../msg_docs/VehicleAirData.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [EscReport](../msg_docs/EscReport.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) -- [UlogStream](../msg_docs/UlogStream.md) -- [FollowTarget](../msg_docs/FollowTarget.md) -- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) -- [UlogStreamAck](../msg_docs/UlogStreamAck.md) -- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) -- [MagWorkerData](../msg_docs/MagWorkerData.md) -- [SensorMag](../msg_docs/SensorMag.md) -- [SensorAirflow](../msg_docs/SensorAirflow.md) +- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) +- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) - [DebugValue](../msg_docs/DebugValue.md) +- [Airspeed](../msg_docs/Airspeed.md) +- [LedControl](../msg_docs/LedControl.md) +- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) +- [CameraCapture](../msg_docs/CameraCapture.md) +- [PpsCapture](../msg_docs/PpsCapture.md) +- [GpioConfig](../msg_docs/GpioConfig.md) +- [DifferentialPressure](../msg_docs/DifferentialPressure.md) +- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) +- [GainCompression](../msg_docs/GainCompression.md) +- [ButtonEvent](../msg_docs/ButtonEvent.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) +- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) +- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) +- [GpioIn](../msg_docs/GpioIn.md) +- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [FuelTankStatus](../msg_docs/FuelTankStatus.md) +- [GeneratorStatus](../msg_docs/GeneratorStatus.md) +- [MagWorkerData](../msg_docs/MagWorkerData.md) +- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) +- [Mission](../msg_docs/Mission.md) +- [CameraStatus](../msg_docs/CameraStatus.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) +- [GpioOut](../msg_docs/GpioOut.md) +- [NeuralControl](../msg_docs/NeuralControl.md) +- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [QshellRetval](../msg_docs/QshellRetval.md) +- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [Rpm](../msg_docs/Rpm.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [FollowTarget](../msg_docs/FollowTarget.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [SensorAccel](../msg_docs/SensorAccel.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) +- [LogMessage](../msg_docs/LogMessage.md) +- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) +- [Gripper](../msg_docs/Gripper.md) +- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) +- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) +- [EventV0](../msg_docs/EventV0.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) +- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) +- [RadioStatus](../msg_docs/RadioStatus.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [QshellReq](../msg_docs/QshellReq.md) +- [ActuatorTest](../msg_docs/ActuatorTest.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [EscReport](../msg_docs/EscReport.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [VehicleRoi](../msg_docs/VehicleRoi.md) +- [EstimatorStates](../msg_docs/EstimatorStates.md) +- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) +- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) +- [EstimatorStatus](../msg_docs/EstimatorStatus.md) +- [RcParameterMap](../msg_docs/RcParameterMap.md) +- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [SensorSelection](../msg_docs/SensorSelection.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) +- [PositionSetpoint](../msg_docs/PositionSetpoint.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [MissionResult](../msg_docs/MissionResult.md) +- [CameraTrigger](../msg_docs/CameraTrigger.md) +- [GeofenceStatus](../msg_docs/GeofenceStatus.md) +- [RoverRateStatus](../msg_docs/RoverRateStatus.md) +- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) +- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) +- [LandingGearWheel](../msg_docs/LandingGearWheel.md) +- [BatteryInfo](../msg_docs/BatteryInfo.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) +- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) +- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) +- [RtlStatus](../msg_docs/RtlStatus.md) +- [VehicleAirData](../msg_docs/VehicleAirData.md) +- [ActionRequest](../msg_docs/ActionRequest.md) +- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [Vtx](../msg_docs/Vtx.md) +- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [AirspeedWind](../msg_docs/AirspeedWind.md) +- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) +- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [Cpuload](../msg_docs/Cpuload.md) +- [SensorsStatus](../msg_docs/SensorsStatus.md) +- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [Ping](../msg_docs/Ping.md) +- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) +- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [SensorUwb](../msg_docs/SensorUwb.md) +- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [CellularStatus](../msg_docs/CellularStatus.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) +- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) +- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) +- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) +- [PowerButtonState](../msg_docs/PowerButtonState.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [GpsInjectData](../msg_docs/GpsInjectData.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) +- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) +- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [LandingTargetPose](../msg_docs/LandingTargetPose.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) +- [SensorCorrection](../msg_docs/SensorCorrection.md) +- [HealthReport](../msg_docs/HealthReport.md) +- [Event](../msg_docs/Event.md) +- [UlogStream](../msg_docs/UlogStream.md) +- [ActuatorArmed](../msg_docs/ActuatorArmed.md) +- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) +- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) +- [AdcReport](../msg_docs/AdcReport.md) +- [VehicleImu](../msg_docs/VehicleImu.md) +- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [OrbTestLarge](../msg_docs/OrbTestLarge.md) +- [SystemPower](../msg_docs/SystemPower.md) +- [PwmInput](../msg_docs/PwmInput.md) +- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) +- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) +- [OrbTest](../msg_docs/OrbTest.md) +- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) +- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) +- [SensorAirflow](../msg_docs/SensorAirflow.md) +- [SensorHygrometer](../msg_docs/SensorHygrometer.md) +- [GimbalControls](../msg_docs/GimbalControls.md) +- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) +- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [GpioRequest](../msg_docs/GpioRequest.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [DeviceInformation](../msg_docs/DeviceInformation.md) +- [SensorGyro](../msg_docs/SensorGyro.md) +- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) +- [OrbTestMedium](../msg_docs/OrbTestMedium.md) +- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) +- [SensorMag](../msg_docs/SensorMag.md) +- [SensorBaro](../msg_docs/SensorBaro.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [RcChannels](../msg_docs/RcChannels.md) +- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [SatelliteInfo](../msg_docs/SatelliteInfo.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) +- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) +- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [IrlockReport](../msg_docs/IrlockReport.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [InputRc](../msg_docs/InputRc.md) ::: From 864df9fc7bf34395f5860d386fb361f7655a1b73 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Tue, 17 Feb 2026 08:56:10 -0800 Subject: [PATCH 810/812] CI: disable VTOL and tailsitter SITL tests Persistent flaky failures (timeouts, erratic transitions) make these tests unreliable in CI. Commented out from the workflow matrix so they can be re-enabled once the test infrastructure is stabilized. The test definitions in sitl.json are preserved for local use. Signed-off-by: Ramon Roche --- .github/workflows/sitl_tests.yml | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/.github/workflows/sitl_tests.yml b/.github/workflows/sitl_tests.yml index 813e78073b..c114b05cb3 100644 --- a/.github/workflows/sitl_tests.yml +++ b/.github/workflows/sitl_tests.yml @@ -33,8 +33,10 @@ jobs: matrix: config: - {model: "iris", latitude: "59.617693", longitude: "-151.145316", altitude: "48", build_type: "RelWithDebInfo" } # Alaska - - {model: "tailsitter" , latitude: "29.660316", longitude: "-82.316658", altitude: "30", build_type: "RelWithDebInfo" } # Florida - - {model: "standard_vtol", latitude: "47.397742", longitude: "8.545594", altitude: "488", build_type: "Coverage" } # Zurich + # VTOL/tailsitter disabled: persistent flaky CI failures (timeouts, erratic + # transitions). Re-enable once the test infrastructure is stabilized. + # - {model: "tailsitter" , latitude: "29.660316", longitude: "-82.316658", altitude: "30", build_type: "RelWithDebInfo" } # Florida + # - {model: "standard_vtol", latitude: "47.397742", longitude: "8.545594", altitude: "488", build_type: "Coverage" } # Zurich steps: - uses: actions/checkout@v4 From 0e6b904e801ba79e212e84bea67ed549dc7c5069 Mon Sep 17 00:00:00 2001 From: Alex Klimaj Date: Tue, 17 Feb 2026 12:54:38 -0700 Subject: [PATCH 811/812] LightwareLaser: add SF1XX rotation parameter (#26428) * Add SF1XX rotation parameter and update orientation in LightwareLaser driver * remove rotation opt arg, update docs about supported lightware --------- Co-authored-by: Jacob Dahl --- .../lightware_laser_i2c.cpp | 23 +++++++------------ .../lightware_laser_i2c/parameters.c | 23 +++++++++++++++++-- 2 files changed, 29 insertions(+), 17 deletions(-) diff --git a/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp b/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp index d5e9a8088b..93c4b94b82 100644 --- a/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp +++ b/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp @@ -162,7 +162,8 @@ private: DEFINE_PARAMETERS( (ParamInt) _param_sens_en_sf1xx, - (ParamInt) _param_sf1xx_mode + (ParamInt) _param_sf1xx_mode, + (ParamInt) _param_sf1xx_rot ) uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; @@ -178,7 +179,7 @@ LightwareLaser::LightwareLaser(const I2CSPIDriverConfig &config) : I2C(config), I2CSPIDriver(config), ModuleParams(nullptr), - _px4_rangefinder(get_device_id(), config.rotation) + _px4_rangefinder(get_device_id()) { _px4_rangefinder.set_device_type(DRV_DIST_DEVTYPE_LIGHTWARE_LASER); } @@ -194,6 +195,9 @@ int LightwareLaser::init() { int ret = PX4_ERROR; updateParams(); + + _px4_rangefinder.set_orientation(_param_sf1xx_rot.get()); + const int32_t hw_model = _param_sens_en_sf1xx.get(); switch (hw_model) { @@ -630,7 +634,7 @@ void LightwareLaser::print_usage() R"DESCR_STR( ### Description -I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20, SF30/d. +I2C bus driver for Lightware LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20, SF/LW30/d, GRF250, GRF500. Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html )DESCR_STR"); @@ -640,28 +644,17 @@ Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false); PRINT_MODULE_USAGE_PARAMS_I2C_ADDRESS(0x66); - PRINT_MODULE_USAGE_PARAM_INT('R', 25, 0, 25, "Sensor rotation - downward facing by default", true); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); } extern "C" __EXPORT int lightware_laser_i2c_main(int argc, char *argv[]) { - int ch; using ThisDriver = LightwareLaser; BusCLIArguments cli{true, false}; - cli.rotation = (Rotation)distance_sensor_s::ROTATION_DOWNWARD_FACING; cli.default_i2c_frequency = 400000; cli.i2c_address = LIGHTWARE_LASER_BASEADDR; - while ((ch = cli.getOpt(argc, argv, "R:")) != EOF) { - switch (ch) { - case 'R': - cli.rotation = (Rotation)atoi(cli.optArg()); - break; - } - } - - const char *verb = cli.optArg(); + const char *verb = cli.parseDefaultArguments(argc, argv); if (!verb) { ThisDriver::print_usage(); diff --git a/src/drivers/distance_sensor/lightware_laser_i2c/parameters.c b/src/drivers/distance_sensor/lightware_laser_i2c/parameters.c index 8fa96b629e..d549144f9d 100644 --- a/src/drivers/distance_sensor/lightware_laser_i2c/parameters.c +++ b/src/drivers/distance_sensor/lightware_laser_i2c/parameters.c @@ -32,7 +32,7 @@ ****************************************************************************/ /** - * Lightware SF1xx/SF20/LW20 laser rangefinder (i2c) + * Lightware laser rangefinder (i2c) * * @reboot_required true * @min 0 @@ -52,7 +52,7 @@ PARAM_DEFINE_INT32(SENS_EN_SF1XX, 0); /** - * Lightware SF1xx/SF20/LW20 Operation Mode + * Lightware laser rangefinder Operation Mode * * @value 0 Disabled * @value 1 Enabled @@ -62,3 +62,22 @@ PARAM_DEFINE_INT32(SENS_EN_SF1XX, 0); * @max 2 */ PARAM_DEFINE_INT32(SF1XX_MODE, 1); + +/** + * Lightware laser rangefinder Rotation + * + * Distance sensor orientation as MAV_SENSOR_ORIENTATION enum. + * Applies to all models supported by SENS_EN_SF1XX. + * + * @reboot_required true + * @min 0 + * @max 25 + * @group Sensors + * @value 0 Forward + * @value 2 Right + * @value 4 Backward + * @value 6 Left + * @value 24 Upward + * @value 25 Downward + */ +PARAM_DEFINE_INT32(SF1XX_ROT, 25); From 6b67ccb0ad6f2fd20b79d782a9d254e06e0a3756 Mon Sep 17 00:00:00 2001 From: PX4BuildBot Date: Tue, 17 Feb 2026 20:02:19 +0000 Subject: [PATCH 812/812] docs: auto-sync metadata [skip ci] Co-Authored-By: PX4 BuildBot --- .../en/advanced_config/parameter_reference.md | 24 +- docs/en/middleware/dds_topics.md | 374 +++++++++--------- .../modules/modules_driver_distance_sensor.md | 4 +- 3 files changed, 210 insertions(+), 192 deletions(-) diff --git a/docs/en/advanced_config/parameter_reference.md b/docs/en/advanced_config/parameter_reference.md index 63b3f3d195..2a179899a5 100644 --- a/docs/en/advanced_config/parameter_reference.md +++ b/docs/en/advanced_config/parameter_reference.md @@ -34607,7 +34607,7 @@ Lightware Laser Rangefinder hardware model (serial). ### SENS_EN_SF1XX (`INT32`) {#SENS_EN_SF1XX} -Lightware SF1xx/SF20/LW20 laser rangefinder (i2c). +Lightware laser rangefinder (i2c). **Values:** @@ -35782,6 +35782,26 @@ Configure on which serial port to run VectorNav (VN-100, VN-200, VN-300). | ------- | -------- | -------- | --------- | ------- | ---- | | ✓ | | | | 0 | +### SF1XX_ROT (`INT32`) {#SF1XX_ROT} + +Lightware laser rangefinder Rotation. + +Distance sensor orientation as MAV_SENSOR_ORIENTATION enum. +Applies to all models supported by SENS_EN_SF1XX. + +**Values:** + +- `0`: Forward +- `2`: Right +- `4`: Backward +- `6`: Left +- `24`: Upward +- `25`: Downward + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 25 | | 25 | + ### SF45_ORIENT_CFG (`INT32`) {#SF45_ORIENT_CFG} Orientation upright or facing downward. @@ -42610,7 +42630,7 @@ Gyro filter settings. ### SF1XX_MODE (`INT32`) {#SF1XX_MODE} -Lightware SF1xx/SF20/LW20 Operation Mode. +Lightware laser rangefinder Operation Mode. **Values:** diff --git a/docs/en/middleware/dds_topics.md b/docs/en/middleware/dds_topics.md index fc2fb68b16..226f0a801c 100644 --- a/docs/en/middleware/dds_topics.md +++ b/docs/en/middleware/dds_topics.md @@ -94,199 +94,199 @@ They are not build into the module, and hence are neither published or subscribe ::: details See messages -- [GpsDump](../msg_docs/GpsDump.md) -- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) -- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) -- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) -- [DebugValue](../msg_docs/DebugValue.md) -- [Airspeed](../msg_docs/Airspeed.md) -- [LedControl](../msg_docs/LedControl.md) -- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) -- [CameraCapture](../msg_docs/CameraCapture.md) -- [PpsCapture](../msg_docs/PpsCapture.md) -- [GpioConfig](../msg_docs/GpioConfig.md) -- [DifferentialPressure](../msg_docs/DifferentialPressure.md) -- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) -- [GainCompression](../msg_docs/GainCompression.md) -- [ButtonEvent](../msg_docs/ButtonEvent.md) -- [MountOrientation](../msg_docs/MountOrientation.md) -- [RaptorInput](../msg_docs/RaptorInput.md) -- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) -- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) -- [HomePositionV0](../msg_docs/HomePositionV0.md) -- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) -- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) -- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) -- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) -- [TecsStatus](../msg_docs/TecsStatus.md) -- [RaptorStatus](../msg_docs/RaptorStatus.md) -- [GpioIn](../msg_docs/GpioIn.md) -- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) -- [FuelTankStatus](../msg_docs/FuelTankStatus.md) -- [GeneratorStatus](../msg_docs/GeneratorStatus.md) -- [MagWorkerData](../msg_docs/MagWorkerData.md) -- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) -- [Mission](../msg_docs/Mission.md) -- [CameraStatus](../msg_docs/CameraStatus.md) -- [DebugArray](../msg_docs/DebugArray.md) -- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) -- [GpioOut](../msg_docs/GpioOut.md) -- [NeuralControl](../msg_docs/NeuralControl.md) -- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) -- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) -- [QshellRetval](../msg_docs/QshellRetval.md) -- [ParameterUpdate](../msg_docs/ParameterUpdate.md) -- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) -- [Rpm](../msg_docs/Rpm.md) -- [OrbitStatus](../msg_docs/OrbitStatus.md) -- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) -- [FollowTarget](../msg_docs/FollowTarget.md) -- [DebugKeyValue](../msg_docs/DebugKeyValue.md) -- [SensorAccel](../msg_docs/SensorAccel.md) -- [DatamanResponse](../msg_docs/DatamanResponse.md) -- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) -- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) -- [LogMessage](../msg_docs/LogMessage.md) -- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) -- [Gripper](../msg_docs/Gripper.md) -- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) -- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) -- [EventV0](../msg_docs/EventV0.md) -- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) -- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) -- [RadioStatus](../msg_docs/RadioStatus.md) -- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) -- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) -- [QshellReq](../msg_docs/QshellReq.md) -- [ActuatorTest](../msg_docs/ActuatorTest.md) -- [TuneControl](../msg_docs/TuneControl.md) -- [UlogStreamAck](../msg_docs/UlogStreamAck.md) -- [EscReport](../msg_docs/EscReport.md) -- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) -- [TaskStackInfo](../msg_docs/TaskStackInfo.md) -- [VehicleRoi](../msg_docs/VehicleRoi.md) -- [EstimatorStates](../msg_docs/EstimatorStates.md) -- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) -- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) -- [EstimatorStatus](../msg_docs/EstimatorStatus.md) -- [RcParameterMap](../msg_docs/RcParameterMap.md) -- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) -- [SensorSelection](../msg_docs/SensorSelection.md) -- [WheelEncoders](../msg_docs/WheelEncoders.md) -- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) -- [PositionSetpoint](../msg_docs/PositionSetpoint.md) -- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) -- [MissionResult](../msg_docs/MissionResult.md) -- [CameraTrigger](../msg_docs/CameraTrigger.md) -- [GeofenceStatus](../msg_docs/GeofenceStatus.md) -- [RoverRateStatus](../msg_docs/RoverRateStatus.md) -- [Px4ioStatus](../msg_docs/Px4ioStatus.md) -- [DatamanRequest](../msg_docs/DatamanRequest.md) -- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) -- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) -- [LandingGearWheel](../msg_docs/LandingGearWheel.md) - [BatteryInfo](../msg_docs/BatteryInfo.md) -- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) -- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) -- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) -- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) -- [RtlStatus](../msg_docs/RtlStatus.md) -- [VehicleAirData](../msg_docs/VehicleAirData.md) +- [DebugValue](../msg_docs/DebugValue.md) +- [LandingGearWheel](../msg_docs/LandingGearWheel.md) +- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md) - [ActionRequest](../msg_docs/ActionRequest.md) -- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) -- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) -- [Vtx](../msg_docs/Vtx.md) -- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) -- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) -- [HeaterStatus](../msg_docs/HeaterStatus.md) -- [LoggerStatus](../msg_docs/LoggerStatus.md) -- [AirspeedWind](../msg_docs/AirspeedWind.md) -- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) -- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) -- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) -- [Cpuload](../msg_docs/Cpuload.md) -- [SensorsStatus](../msg_docs/SensorsStatus.md) -- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) -- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) -- [Ping](../msg_docs/Ping.md) -- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) -- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) -- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) -- [SensorUwb](../msg_docs/SensorUwb.md) -- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) -- [CellularStatus](../msg_docs/CellularStatus.md) -- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) -- [SensorTemp](../msg_docs/SensorTemp.md) -- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) -- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) -- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) -- [GeofenceResult](../msg_docs/GeofenceResult.md) -- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) -- [VelocityLimits](../msg_docs/VelocityLimits.md) -- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) -- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) -- [PowerButtonState](../msg_docs/PowerButtonState.md) -- [EscStatus](../msg_docs/EscStatus.md) -- [FigureEightStatus](../msg_docs/FigureEightStatus.md) - [GpsInjectData](../msg_docs/GpsInjectData.md) -- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) -- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) -- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) -- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) -- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) -- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) -- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md) - [LandingTargetPose](../msg_docs/LandingTargetPose.md) -- [VehicleConstraints](../msg_docs/VehicleConstraints.md) -- [SensorCorrection](../msg_docs/SensorCorrection.md) -- [HealthReport](../msg_docs/HealthReport.md) -- [Event](../msg_docs/Event.md) -- [UlogStream](../msg_docs/UlogStream.md) -- [ActuatorArmed](../msg_docs/ActuatorArmed.md) -- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) -- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) -- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) -- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) -- [DebugVect](../msg_docs/DebugVect.md) -- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) -- [AdcReport](../msg_docs/AdcReport.md) -- [VehicleImu](../msg_docs/VehicleImu.md) -- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) -- [OrbTestLarge](../msg_docs/OrbTestLarge.md) -- [SystemPower](../msg_docs/SystemPower.md) -- [PwmInput](../msg_docs/PwmInput.md) +- [CameraTrigger](../msg_docs/CameraTrigger.md) - [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md) -- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) -- [OrbTest](../msg_docs/OrbTest.md) -- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) -- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) -- [SensorAirflow](../msg_docs/SensorAirflow.md) -- [SensorHygrometer](../msg_docs/SensorHygrometer.md) -- [GimbalControls](../msg_docs/GimbalControls.md) -- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) -- [SensorGyroFft](../msg_docs/SensorGyroFft.md) -- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [FigureEightStatus](../msg_docs/FigureEightStatus.md) +- [DatamanRequest](../msg_docs/DatamanRequest.md) +- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md) +- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md) +- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md) - [GpioRequest](../msg_docs/GpioRequest.md) -- [PowerMonitor](../msg_docs/PowerMonitor.md) -- [DeviceInformation](../msg_docs/DeviceInformation.md) -- [SensorGyro](../msg_docs/SensorGyro.md) -- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [EstimatorBias](../msg_docs/EstimatorBias.md) +- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md) - [SensorsStatusImu](../msg_docs/SensorsStatusImu.md) -- [OrbTestMedium](../msg_docs/OrbTestMedium.md) -- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) -- [SensorMag](../msg_docs/SensorMag.md) -- [SensorBaro](../msg_docs/SensorBaro.md) -- [MavlinkLog](../msg_docs/MavlinkLog.md) -- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) -- [RcChannels](../msg_docs/RcChannels.md) -- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) -- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) -- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) -- [SatelliteInfo](../msg_docs/SatelliteInfo.md) -- [TakeoffStatus](../msg_docs/TakeoffStatus.md) -- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) -- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) -- [IrlockReport](../msg_docs/IrlockReport.md) -- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [WheelEncoders](../msg_docs/WheelEncoders.md) +- [VehicleRoi](../msg_docs/VehicleRoi.md) +- [Airspeed](../msg_docs/Airspeed.md) +- [EstimatorStatus](../msg_docs/EstimatorStatus.md) +- [EventV0](../msg_docs/EventV0.md) +- [ActuatorTest](../msg_docs/ActuatorTest.md) +- [EscReport](../msg_docs/EscReport.md) +- [OrbTest](../msg_docs/OrbTest.md) +- [RoverRateStatus](../msg_docs/RoverRateStatus.md) +- [DebugKeyValue](../msg_docs/DebugKeyValue.md) +- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md) +- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md) +- [PowerMonitor](../msg_docs/PowerMonitor.md) +- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md) +- [VehicleImu](../msg_docs/VehicleImu.md) +- [QshellRetval](../msg_docs/QshellRetval.md) +- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md) +- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md) - [InputRc](../msg_docs/InputRc.md) +- [Ping](../msg_docs/Ping.md) +- [Px4ioStatus](../msg_docs/Px4ioStatus.md) +- [Event](../msg_docs/Event.md) +- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md) +- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md) +- [GpioIn](../msg_docs/GpioIn.md) +- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md) +- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md) +- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md) +- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md) +- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md) +- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md) +- [UlogStreamAck](../msg_docs/UlogStreamAck.md) +- [Rpm](../msg_docs/Rpm.md) +- [SensorsStatus](../msg_docs/SensorsStatus.md) +- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md) +- [HealthReport](../msg_docs/HealthReport.md) +- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md) +- [AirspeedWind](../msg_docs/AirspeedWind.md) +- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md) +- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md) +- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md) +- [PositionSetpoint](../msg_docs/PositionSetpoint.md) +- [FollowTarget](../msg_docs/FollowTarget.md) +- [PwmInput](../msg_docs/PwmInput.md) +- [SensorUwb](../msg_docs/SensorUwb.md) +- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md) +- [LedControl](../msg_docs/LedControl.md) +- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md) +- [EstimatorStates](../msg_docs/EstimatorStates.md) +- [GeofenceResult](../msg_docs/GeofenceResult.md) +- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md) +- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md) +- [TakeoffStatus](../msg_docs/TakeoffStatus.md) +- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md) +- [PowerButtonState](../msg_docs/PowerButtonState.md) +- [OrbTestLarge](../msg_docs/OrbTestLarge.md) +- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md) +- [PpsCapture](../msg_docs/PpsCapture.md) +- [SensorHygrometer](../msg_docs/SensorHygrometer.md) +- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md) +- [DeviceInformation](../msg_docs/DeviceInformation.md) +- [EscStatus](../msg_docs/EscStatus.md) +- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md) +- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md) +- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md) +- [SensorTemp](../msg_docs/SensorTemp.md) +- [OrbitStatus](../msg_docs/OrbitStatus.md) +- [MountOrientation](../msg_docs/MountOrientation.md) +- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md) +- [FuelTankStatus](../msg_docs/FuelTankStatus.md) +- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md) +- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md) +- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md) +- [SatelliteInfo](../msg_docs/SatelliteInfo.md) +- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md) +- [QshellReq](../msg_docs/QshellReq.md) +- [RcParameterMap](../msg_docs/RcParameterMap.md) +- [MavlinkLog](../msg_docs/MavlinkLog.md) +- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md) +- [LogMessage](../msg_docs/LogMessage.md) +- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md) +- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md) +- [ActuatorArmed](../msg_docs/ActuatorArmed.md) +- [TaskStackInfo](../msg_docs/TaskStackInfo.md) +- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md) +- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md) +- [UlogStream](../msg_docs/UlogStream.md) +- [SensorAirflow](../msg_docs/SensorAirflow.md) +- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md) +- [Mission](../msg_docs/Mission.md) +- [HomePositionV0](../msg_docs/HomePositionV0.md) +- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md) +- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md) +- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md) +- [GimbalControls](../msg_docs/GimbalControls.md) +- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md) +- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md) +- [SensorGyro](../msg_docs/SensorGyro.md) +- [MagWorkerData](../msg_docs/MagWorkerData.md) +- [RtlStatus](../msg_docs/RtlStatus.md) +- [VelocityLimits](../msg_docs/VelocityLimits.md) +- [SensorSelection](../msg_docs/SensorSelection.md) +- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md) +- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md) +- [ButtonEvent](../msg_docs/ButtonEvent.md) +- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md) +- [ParameterUpdate](../msg_docs/ParameterUpdate.md) +- [MissionResult](../msg_docs/MissionResult.md) +- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md) +- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md) +- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md) +- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md) +- [AdcReport](../msg_docs/AdcReport.md) +- [TuneControl](../msg_docs/TuneControl.md) +- [CameraStatus](../msg_docs/CameraStatus.md) +- [GpioOut](../msg_docs/GpioOut.md) +- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md) +- [HeaterStatus](../msg_docs/HeaterStatus.md) +- [OrbTestMedium](../msg_docs/OrbTestMedium.md) +- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md) +- [GainCompression](../msg_docs/GainCompression.md) +- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md) +- [SensorAccel](../msg_docs/SensorAccel.md) +- [NeuralControl](../msg_docs/NeuralControl.md) +- [Gripper](../msg_docs/Gripper.md) +- [SensorCorrection](../msg_docs/SensorCorrection.md) +- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md) +- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md) +- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md) +- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md) +- [DebugVect](../msg_docs/DebugVect.md) +- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md) +- [SensorGyroFft](../msg_docs/SensorGyroFft.md) +- [GeneratorStatus](../msg_docs/GeneratorStatus.md) +- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md) +- [DatamanResponse](../msg_docs/DatamanResponse.md) +- [DebugArray](../msg_docs/DebugArray.md) +- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md) +- [VehicleConstraints](../msg_docs/VehicleConstraints.md) +- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md) +- [NavigatorStatus](../msg_docs/NavigatorStatus.md) +- [RaptorInput](../msg_docs/RaptorInput.md) +- [RcChannels](../msg_docs/RcChannels.md) +- [Vtx](../msg_docs/Vtx.md) +- [LoggerStatus](../msg_docs/LoggerStatus.md) +- [GpsDump](../msg_docs/GpsDump.md) +- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md) +- [SensorBaro](../msg_docs/SensorBaro.md) +- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md) +- [TecsStatus](../msg_docs/TecsStatus.md) +- [IrlockReport](../msg_docs/IrlockReport.md) +- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md) +- [RadioStatus](../msg_docs/RadioStatus.md) +- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md) +- [CameraCapture](../msg_docs/CameraCapture.md) +- [GeofenceStatus](../msg_docs/GeofenceStatus.md) +- [GpioConfig](../msg_docs/GpioConfig.md) +- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md) +- [SensorMag](../msg_docs/SensorMag.md) +- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md) +- [RaptorStatus](../msg_docs/RaptorStatus.md) +- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md) +- [SystemPower](../msg_docs/SystemPower.md) +- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md) +- [Cpuload](../msg_docs/Cpuload.md) +- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md) +- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md) +- [VehicleAirData](../msg_docs/VehicleAirData.md) +- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md) +- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md) +- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md) +- [DifferentialPressure](../msg_docs/DifferentialPressure.md) +- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md) +- [CellularStatus](../msg_docs/CellularStatus.md) +- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md) +- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md) ::: diff --git a/docs/en/modules/modules_driver_distance_sensor.md b/docs/en/modules/modules_driver_distance_sensor.md index 9b82e6fc4a..101ba55dd3 100644 --- a/docs/en/modules/modules_driver_distance_sensor.md +++ b/docs/en/modules/modules_driver_distance_sensor.md @@ -147,7 +147,7 @@ Source: [drivers/distance_sensor/lightware_laser_i2c](https://github.com/PX4/PX4 ### Description -I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20, SF30/d. +I2C bus driver for Lightware LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20, SF/LW30/d, GRF250, GRF500. Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html @@ -165,8 +165,6 @@ lightware_laser_i2c [arguments...] [-q] quiet startup (no message if no device found) [-a ] I2C address default: 102 - [-R ] Sensor rotation - downward facing by default - default: 25 stop